From ae7b2674836546cc3f7dcd995836369ad2649308 Mon Sep 17 00:00:00 2001 From: dzalkind Date: Mon, 12 Sep 2022 09:14:05 -0600 Subject: [PATCH 001/224] Update example 05 units --- ROSCO_toolbox/sim.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ROSCO_toolbox/sim.py b/ROSCO_toolbox/sim.py index 54e3df62..18e0d41b 100644 --- a/ROSCO_toolbox/sim.py +++ b/ROSCO_toolbox/sim.py @@ -181,7 +181,7 @@ def sim_ws_series(self, t_array, ws_array, rotor_rpm_init=10, init_pitch=0.0, ax.grid() ax = axarr[3] ax.plot(self.t_array, self.gen_power/1000) - ax.set_ylabel('Gen Power (W)') + ax.set_ylabel('Gen Power (kW)') ax.grid() ax = axarr[4] ax.plot(self.t_array, self.bld_pitch*rad2deg) From 778822b5dd43f2aaffe622c1a38e90069d0bf923 Mon Sep 17 00:00:00 2001 From: dzalkind Date: Mon, 12 Sep 2022 09:36:09 -0600 Subject: [PATCH 002/224] Add generator efficiency to power output of simple simulation --- ROSCO_toolbox/sim.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ROSCO_toolbox/sim.py b/ROSCO_toolbox/sim.py index 18e0d41b..7ea930cd 100644 --- a/ROSCO_toolbox/sim.py +++ b/ROSCO_toolbox/sim.py @@ -140,7 +140,7 @@ def sim_ws_series(self, t_array, ws_array, rotor_rpm_init=10, init_pitch=0.0, gen_torque[i], bld_pitch[i], nac_yawrate[i] = self.controller_int.call_controller(turbine_state) # Calculate the power - gen_power[i] = gen_speed[i] * gen_torque[i] + gen_power[i] = gen_speed[i] * gen_torque[i] * self.turbine.GenEff / 100 # Calculate the nacelle position nac_yaw[i] = nac_yaw[i-1] + nac_yawrate[i] * dt From 86c8acfb2af838ee11559884f064bf12f62f49b8 Mon Sep 17 00:00:00 2001 From: dzalkind Date: Mon, 12 Sep 2022 10:20:45 -0600 Subject: [PATCH 003/224] Update Windows install instructions --- docs/source/install.rst | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/docs/source/install.rst b/docs/source/install.rst index 29a71620..12029399 100644 --- a/docs/source/install.rst +++ b/docs/source/install.rst @@ -104,6 +104,7 @@ On Mac/Linux, standard compilers are generally available without any additional .. code-block:: bash conda install m2w64-toolchain libpython + conda install cmake make # if Windows users would like to install these in anaconda environment Once the CMake and the required compilers are downloaded, the following code can be used to compile ROSCO. @@ -199,7 +200,8 @@ Please follow the following steps to install the ROSCO tool-chain. You should do cd ROSCO conda install compilers # (Mac/Linux only) conda install m2w64-toolchain libpython # (Windows only) - conda install -y wisdem + conda env config vars set FC=gfortran # Sometimes needed for Windows + conda install -y wisdem=3.5.0 python setup.py install --compile-rosco 3. Clone and Install the ROSCO toolbox without ROSCO From b933b3bab26fc837fccd99626c51a439e19b169d Mon Sep 17 00:00:00 2001 From: dzalkind Date: Tue, 13 Sep 2022 12:57:47 -0600 Subject: [PATCH 004/224] Add rotor speed tracking, test case --- ROSCO/rosco_registry/rosco_types.yaml | 22 + ROSCO/src/ControllerBlocks.f90 | 44 +- ROSCO/src/DISCON.F90 | 2 +- ROSCO/src/ROSCO_IO.f90 | 127 +- ROSCO/src/ROSCO_Types.f90 | 6 + ROSCO/src/ReadSetParameters.f90 | 12 + ROSCO_toolbox/inputs/toolbox_schema.yaml | 16 + ROSCO_toolbox/ofTools/case_gen/CaseLibrary.py | 7 +- ROSCO_toolbox/ofTools/case_gen/run_FAST.py | 28 +- ROSCO_toolbox/ofTools/fast_io/plot_FAST.ipynb | 173 +- ROSCO_toolbox/utilities.py | 16 +- .../IEA-15-240-RWT-UMaineSemi.fst | 4 +- .../IEA-15-240-RWT-UMaineSemi_ElastoDyn.dat | 12 +- Tune_Cases/IEA15MW_PRC.yaml | 67 + pCrunch_processing.ipynb | 1507 +++++++++++++++++ 15 files changed, 1917 insertions(+), 126 deletions(-) create mode 100644 Tune_Cases/IEA15MW_PRC.yaml create mode 100644 pCrunch_processing.ipynb diff --git a/ROSCO/rosco_registry/rosco_types.yaml b/ROSCO/rosco_registry/rosco_types.yaml index ea78a05c..2e9c104a 100644 --- a/ROSCO/rosco_registry/rosco_types.yaml +++ b/ROSCO/rosco_registry/rosco_types.yaml @@ -253,6 +253,22 @@ ControlParameters: SS_PCGain: <<: *real description: Collective pitch controller setpoint smoother gain, [-]. + + # Power reference tracking + PRC_Mode: + <<: *integer + description: Power reference tracking mode, 0- use standard rotor speed set points, 1- use PRC rotor speed setpoints + PRC_WindSpeeds: + <<: *real + description: Array of wind speeds used in rotor speed vs. wind speed lookup table + allocatable: True + PRC_RotorSpeeds: + <<: *real + description: Array of rotor speeds corresponding to PRC_WindSpeeds + allocatable: True + PRC_n: + <<: *integer + description: Number of elements in PRC_WindSpeeds and PRC_RotorSpeeds array # Wind Speed Estimator WE_Mode: @@ -726,6 +742,12 @@ LocalVariables: RotSpeedF: <<: *real description: Filtered LSS (generator) speed [rad/s]. + VS_RefSpd: + <<: *real + description: Generator speed set point of torque controller [rad/s] + PC_RefSpd: + <<: *real + description: Generator speed set point of pitch controller [rad/s] GenSpeedF: <<: *real description: Filtered HSS (generator) speed [rad/s]. diff --git a/ROSCO/src/ControllerBlocks.f90 b/ROSCO/src/ControllerBlocks.f90 index a62c5366..9fb7f0f6 100644 --- a/ROSCO/src/ControllerBlocks.f90 +++ b/ROSCO/src/ControllerBlocks.f90 @@ -24,58 +24,68 @@ MODULE ControllerBlocks CONTAINS ! ----------------------------------------------------------------------------------- ! Calculate setpoints for primary control actions - SUBROUTINE ComputeVariablesSetpoints(CntrPar, LocalVar, objInst) - USE ROSCO_Types, ONLY : ControlParameters, LocalVariables, ObjectInstances + SUBROUTINE ComputeVariablesSetpoints(CntrPar, LocalVar, objInst, ErrVar) + USE ROSCO_Types, ONLY : ControlParameters, LocalVariables, ObjectInstances, ErrorVariables USE Constants ! Allocate variables TYPE(ControlParameters), INTENT(INOUT) :: CntrPar TYPE(LocalVariables), INTENT(INOUT) :: LocalVar TYPE(ObjectInstances), INTENT(INOUT) :: objInst + TYPE(ErrorVariables), INTENT(INOUT) :: ErrVar - REAL(DbKi) :: VS_RefSpd ! Referece speed for variable speed torque controller, [rad/s] - REAL(DbKi) :: PC_RefSpd ! Referece speed for pitch controller, [rad/s] - REAL(DbKi) :: Omega_op ! Optimal TSR-tracking generator speed, [rad/s] ! ----- Pitch controller speed and power error ----- + + ! Power reference tracking rotor speed + IF (CntrPar%PRC_Mode == 1) THEN + LocalVar%PC_RefSpd = interp1d(CntrPar%PRC_WindSpeeds,CntrPar%PRC_RotorSpeeds,LocalVar%WE_Vw_F,ErrVar) * CntrPar%WE_GearboxRatio + ENDIF + ! Implement setpoint smoothing IF (LocalVar%SS_DelOmegaF < 0) THEN - PC_RefSpd = CntrPar%PC_RefSpd - LocalVar%SS_DelOmegaF + LocalVar%PC_RefSpd = LocalVar%PC_RefSpd - LocalVar%SS_DelOmegaF ELSE - PC_RefSpd = CntrPar%PC_RefSpd + LocalVar%PC_RefSpd = LocalVar%PC_RefSpd ENDIF - LocalVar%PC_SpdErr = PC_RefSpd - LocalVar%GenSpeedF ! Speed error + ! Compute error for pitch controller + LocalVar%PC_SpdErr = LocalVar%PC_RefSpd - LocalVar%GenSpeedF ! Speed error LocalVar%PC_PwrErr = CntrPar%VS_RtPwr - LocalVar%VS_GenPwr ! Power error ! ----- Torque controller reference errors ----- ! Define VS reference generator speed [rad/s] IF ((CntrPar%VS_ControlMode == 2) .OR. (CntrPar%VS_ControlMode == 3)) THEN - VS_RefSpd = (CntrPar%VS_TSRopt * LocalVar%We_Vw_F / CntrPar%WE_BladeRadius) * CntrPar%WE_GearboxRatio - VS_RefSpd = saturate(VS_RefSpd,CntrPar%VS_MinOMSpd, CntrPar%VS_RefSpd) + LocalVar%VS_RefSpd = (CntrPar%VS_TSRopt * LocalVar%We_Vw_F / CntrPar%WE_BladeRadius) * CntrPar%WE_GearboxRatio + LocalVar%VS_RefSpd = saturate(LocalVar%VS_RefSpd,CntrPar%VS_MinOMSpd, CntrPar%VS_RefSpd) ELSE - VS_RefSpd = CntrPar%VS_RefSpd + LocalVar%VS_RefSpd = CntrPar%VS_RefSpd ENDIF + + ! Implement power reference rotor speed (overwrites above), convert to generator speed + IF (CntrPar%PRC_Mode == 1) THEN + LocalVar%VS_RefSpd = interp1d(CntrPar%PRC_WindSpeeds,CntrPar%PRC_RotorSpeeds,LocalVar%WE_Vw_F,ErrVar) * CntrPar%WE_GearboxRatio + ENDIF ! Implement setpoint smoothing IF (LocalVar%SS_DelOmegaF > 0) THEN - VS_RefSpd = VS_RefSpd - LocalVar%SS_DelOmegaF + LocalVar%VS_RefSpd = LocalVar%VS_RefSpd - LocalVar%SS_DelOmegaF ENDIF ! Force zero torque in shutdown mode IF (LocalVar%SD) THEN - VS_RefSpd = CntrPar%VS_MinOMSpd + LocalVar%VS_RefSpd = CntrPar%VS_MinOMSpd ENDIF ! Force minimum rotor speed - VS_RefSpd = max(VS_RefSpd, CntrPar%VS_MinOmSpd) + LocalVar%VS_RefSpd = max(LocalVar%VS_RefSpd, CntrPar%VS_MinOmSpd) - ! TSR-tracking reference error + ! TSR-tracking reference error or PRC reference tracking error IF ((CntrPar%VS_ControlMode == 2) .OR. (CntrPar%VS_ControlMode == 3)) THEN - LocalVar%VS_SpdErr = VS_RefSpd - LocalVar%GenSpeedF + LocalVar%VS_SpdErr = LocalVar%VS_RefSpd - LocalVar%GenSpeedF ENDIF ! Define transition region setpoint errors - LocalVar%VS_SpdErrAr = VS_RefSpd - LocalVar%GenSpeedF ! Current speed error - Region 2.5 PI-control (Above Rated) + LocalVar%VS_SpdErrAr = LocalVar%VS_RefSpd - LocalVar%GenSpeedF ! Current speed error - Region 2.5 PI-control (Above Rated) LocalVar%VS_SpdErrBr = CntrPar%VS_MinOMSpd - LocalVar%GenSpeedF ! Current speed error - Region 1.5 PI-control (Below Rated) ! Region 3 minimum pitch angle for state machine diff --git a/ROSCO/src/DISCON.F90 b/ROSCO/src/DISCON.F90 index 2b2ec286..e88edc7c 100644 --- a/ROSCO/src/DISCON.F90 +++ b/ROSCO/src/DISCON.F90 @@ -103,7 +103,7 @@ SUBROUTINE DISCON(avrSWAP, aviFAIL, accINFILE, avcOUTNAME, avcMSG) BIND (C, NAME ENDIF CALL WindSpeedEstimator(LocalVar, CntrPar, objInst, PerfData, DebugVar, ErrVar) - CALL ComputeVariablesSetpoints(CntrPar, LocalVar, objInst) + CALL ComputeVariablesSetpoints(CntrPar, LocalVar, objInst, ErrVar) CALL StateMachine(CntrPar, LocalVar) CALL SetpointSmoother(LocalVar, CntrPar, objInst) CALL VariableSpeedControl(avrSWAP, CntrPar, LocalVar, objInst, ErrVar) diff --git a/ROSCO/src/ROSCO_IO.f90 b/ROSCO/src/ROSCO_IO.f90 index d495263b..c43af8b3 100644 --- a/ROSCO/src/ROSCO_IO.f90 +++ b/ROSCO/src/ROSCO_IO.f90 @@ -63,6 +63,8 @@ SUBROUTINE WriteRestartFile(LocalVar, CntrPar, ErrVar, objInst, RootName, size_a WRITE( Un, IOSTAT=ErrStat) LocalVar%FA_PitCom(2) WRITE( Un, IOSTAT=ErrStat) LocalVar%FA_PitCom(3) WRITE( Un, IOSTAT=ErrStat) LocalVar%RotSpeedF + WRITE( Un, IOSTAT=ErrStat) LocalVar%VS_RefSpd + WRITE( Un, IOSTAT=ErrStat) LocalVar%PC_RefSpd WRITE( Un, IOSTAT=ErrStat) LocalVar%GenSpeedF WRITE( Un, IOSTAT=ErrStat) LocalVar%GenTq WRITE( Un, IOSTAT=ErrStat) LocalVar%GenTqMeas @@ -242,6 +244,8 @@ SUBROUTINE ReadRestartFile(avrSWAP, LocalVar, CntrPar, objInst, PerfData, RootNa READ( Un, IOSTAT=ErrStat) LocalVar%FA_PitCom(2) READ( Un, IOSTAT=ErrStat) LocalVar%FA_PitCom(3) READ( Un, IOSTAT=ErrStat) LocalVar%RotSpeedF + READ( Un, IOSTAT=ErrStat) LocalVar%VS_RefSpd + READ( Un, IOSTAT=ErrStat) LocalVar%PC_RefSpd READ( Un, IOSTAT=ErrStat) LocalVar%GenSpeedF READ( Un, IOSTAT=ErrStat) LocalVar%GenTq READ( Un, IOSTAT=ErrStat) LocalVar%GenTqMeas @@ -434,7 +438,7 @@ SUBROUTINE Debug(LocalVar, CntrPar, DebugVar, ErrVar, avrSWAP, RootName, size_av '[rad/s]', '[rad/s]', '[m/s]', '[rad]', '[rad]', & '', '', '', '', '[rad/s]', & '[rad]', '[rad]', '[rad]', ''] - nLocalVars = 69 + nLocalVars = 71 Allocate(LocalVarOutData(nLocalVars)) Allocate(LocalVarOutStrings(nLocalVars)) LocalVarOutData(1) = LocalVar%iStatus @@ -457,69 +461,72 @@ SUBROUTINE Debug(LocalVar, CntrPar, DebugVar, ErrVar, avrSWAP, RootName, size_av LocalVarOutData(18) = LocalVar%FA_AccHPFI LocalVarOutData(19) = LocalVar%FA_PitCom(1) LocalVarOutData(20) = LocalVar%RotSpeedF - LocalVarOutData(21) = LocalVar%GenSpeedF - LocalVarOutData(22) = LocalVar%GenTq - LocalVarOutData(23) = LocalVar%GenTqMeas - LocalVarOutData(24) = LocalVar%GenArTq - LocalVarOutData(25) = LocalVar%GenBrTq - LocalVarOutData(26) = LocalVar%IPC_PitComF(1) - LocalVarOutData(27) = LocalVar%PC_KP - LocalVarOutData(28) = LocalVar%PC_KI - LocalVarOutData(29) = LocalVar%PC_KD - LocalVarOutData(30) = LocalVar%PC_TF - LocalVarOutData(31) = LocalVar%PC_MaxPit - LocalVarOutData(32) = LocalVar%PC_MinPit - LocalVarOutData(33) = LocalVar%PC_PitComT - LocalVarOutData(34) = LocalVar%PC_PitComT_Last - LocalVarOutData(35) = LocalVar%PC_PitComTF - LocalVarOutData(36) = LocalVar%PC_PitComT_IPC(1) - LocalVarOutData(37) = LocalVar%PC_PwrErr - LocalVarOutData(38) = LocalVar%PC_SpdErr - LocalVarOutData(39) = LocalVar%IPC_AxisTilt_1P - LocalVarOutData(40) = LocalVar%IPC_AxisYaw_1P - LocalVarOutData(41) = LocalVar%IPC_AxisTilt_2P - LocalVarOutData(42) = LocalVar%IPC_AxisYaw_2P - LocalVarOutData(43) = LocalVar%IPC_KI(1) - LocalVarOutData(44) = LocalVar%IPC_KP(1) - LocalVarOutData(45) = LocalVar%PC_State - LocalVarOutData(46) = LocalVar%PitCom(1) - LocalVarOutData(47) = LocalVar%PitComAct(1) - LocalVarOutData(48) = LocalVar%SS_DelOmegaF - LocalVarOutData(49) = LocalVar%TestType - LocalVarOutData(50) = LocalVar%VS_MaxTq - LocalVarOutData(51) = LocalVar%VS_LastGenTrq - LocalVarOutData(52) = LocalVar%VS_LastGenPwr - LocalVarOutData(53) = LocalVar%VS_MechGenPwr - LocalVarOutData(54) = LocalVar%VS_SpdErrAr - LocalVarOutData(55) = LocalVar%VS_SpdErrBr - LocalVarOutData(56) = LocalVar%VS_SpdErr - LocalVarOutData(57) = LocalVar%VS_State - LocalVarOutData(58) = LocalVar%VS_Rgn3Pitch - LocalVarOutData(59) = LocalVar%WE_Vw - LocalVarOutData(60) = LocalVar%WE_Vw_F - LocalVarOutData(61) = LocalVar%WE_VwI - LocalVarOutData(62) = LocalVar%WE_VwIdot - LocalVarOutData(63) = LocalVar%VS_LastGenTrqF - LocalVarOutData(64) = LocalVar%Fl_PitCom - LocalVarOutData(65) = LocalVar%NACIMU_FA_AccF - LocalVarOutData(66) = LocalVar%FA_AccF - LocalVarOutData(67) = LocalVar%Flp_Angle(1) - LocalVarOutData(68) = LocalVar%RootMyb_Last(1) - LocalVarOutData(69) = LocalVar%ACC_INFILE_SIZE + LocalVarOutData(21) = LocalVar%VS_RefSpd + LocalVarOutData(22) = LocalVar%PC_RefSpd + LocalVarOutData(23) = LocalVar%GenSpeedF + LocalVarOutData(24) = LocalVar%GenTq + LocalVarOutData(25) = LocalVar%GenTqMeas + LocalVarOutData(26) = LocalVar%GenArTq + LocalVarOutData(27) = LocalVar%GenBrTq + LocalVarOutData(28) = LocalVar%IPC_PitComF(1) + LocalVarOutData(29) = LocalVar%PC_KP + LocalVarOutData(30) = LocalVar%PC_KI + LocalVarOutData(31) = LocalVar%PC_KD + LocalVarOutData(32) = LocalVar%PC_TF + LocalVarOutData(33) = LocalVar%PC_MaxPit + LocalVarOutData(34) = LocalVar%PC_MinPit + LocalVarOutData(35) = LocalVar%PC_PitComT + LocalVarOutData(36) = LocalVar%PC_PitComT_Last + LocalVarOutData(37) = LocalVar%PC_PitComTF + LocalVarOutData(38) = LocalVar%PC_PitComT_IPC(1) + LocalVarOutData(39) = LocalVar%PC_PwrErr + LocalVarOutData(40) = LocalVar%PC_SpdErr + LocalVarOutData(41) = LocalVar%IPC_AxisTilt_1P + LocalVarOutData(42) = LocalVar%IPC_AxisYaw_1P + LocalVarOutData(43) = LocalVar%IPC_AxisTilt_2P + LocalVarOutData(44) = LocalVar%IPC_AxisYaw_2P + LocalVarOutData(45) = LocalVar%IPC_KI(1) + LocalVarOutData(46) = LocalVar%IPC_KP(1) + LocalVarOutData(47) = LocalVar%PC_State + LocalVarOutData(48) = LocalVar%PitCom(1) + LocalVarOutData(49) = LocalVar%PitComAct(1) + LocalVarOutData(50) = LocalVar%SS_DelOmegaF + LocalVarOutData(51) = LocalVar%TestType + LocalVarOutData(52) = LocalVar%VS_MaxTq + LocalVarOutData(53) = LocalVar%VS_LastGenTrq + LocalVarOutData(54) = LocalVar%VS_LastGenPwr + LocalVarOutData(55) = LocalVar%VS_MechGenPwr + LocalVarOutData(56) = LocalVar%VS_SpdErrAr + LocalVarOutData(57) = LocalVar%VS_SpdErrBr + LocalVarOutData(58) = LocalVar%VS_SpdErr + LocalVarOutData(59) = LocalVar%VS_State + LocalVarOutData(60) = LocalVar%VS_Rgn3Pitch + LocalVarOutData(61) = LocalVar%WE_Vw + LocalVarOutData(62) = LocalVar%WE_Vw_F + LocalVarOutData(63) = LocalVar%WE_VwI + LocalVarOutData(64) = LocalVar%WE_VwIdot + LocalVarOutData(65) = LocalVar%VS_LastGenTrqF + LocalVarOutData(66) = LocalVar%Fl_PitCom + LocalVarOutData(67) = LocalVar%NACIMU_FA_AccF + LocalVarOutData(68) = LocalVar%FA_AccF + LocalVarOutData(69) = LocalVar%Flp_Angle(1) + LocalVarOutData(70) = LocalVar%RootMyb_Last(1) + LocalVarOutData(71) = LocalVar%ACC_INFILE_SIZE LocalVarOutStrings = [CHARACTER(15) :: 'iStatus', 'Time', 'DT', 'VS_GenPwr', 'GenSpeed', & 'RotSpeed', 'NacHeading', 'NacVane', 'HorWindV', 'rootMOOP', & 'rootMOOPF', 'BlPitch', 'Azimuth', 'NumBl', 'FA_Acc', & 'NacIMU_FA_Acc', 'FA_AccHPF', 'FA_AccHPFI', 'FA_PitCom', 'RotSpeedF', & - 'GenSpeedF', 'GenTq', 'GenTqMeas', 'GenArTq', 'GenBrTq', & - 'IPC_PitComF', 'PC_KP', 'PC_KI', 'PC_KD', 'PC_TF', & - 'PC_MaxPit', 'PC_MinPit', 'PC_PitComT', 'PC_PitComT_Last', 'PC_PitComTF', & - 'PC_PitComT_IPC', 'PC_PwrErr', 'PC_SpdErr', 'IPC_AxisTilt_1P', 'IPC_AxisYaw_1P', & - 'IPC_AxisTilt_2P', 'IPC_AxisYaw_2P', 'IPC_KI', 'IPC_KP', 'PC_State', & - 'PitCom', 'PitComAct', 'SS_DelOmegaF', 'TestType', 'VS_MaxTq', & - 'VS_LastGenTrq', 'VS_LastGenPwr', 'VS_MechGenPwr', 'VS_SpdErrAr', 'VS_SpdErrBr', & - 'VS_SpdErr', 'VS_State', 'VS_Rgn3Pitch', 'WE_Vw', 'WE_Vw_F', & - 'WE_VwI', 'WE_VwIdot', 'VS_LastGenTrqF', 'Fl_PitCom', 'NACIMU_FA_AccF', & - 'FA_AccF', 'Flp_Angle', 'RootMyb_Last', 'ACC_INFILE_SIZE'] + 'VS_RefSpd', 'PC_RefSpd', 'GenSpeedF', 'GenTq', 'GenTqMeas', & + 'GenArTq', 'GenBrTq', 'IPC_PitComF', 'PC_KP', 'PC_KI', & + 'PC_KD', 'PC_TF', 'PC_MaxPit', 'PC_MinPit', 'PC_PitComT', & + 'PC_PitComT_Last', 'PC_PitComTF', 'PC_PitComT_IPC', 'PC_PwrErr', 'PC_SpdErr', & + 'IPC_AxisTilt_1P', 'IPC_AxisYaw_1P', 'IPC_AxisTilt_2P', 'IPC_AxisYaw_2P', 'IPC_KI', & + 'IPC_KP', 'PC_State', 'PitCom', 'PitComAct', 'SS_DelOmegaF', & + 'TestType', 'VS_MaxTq', 'VS_LastGenTrq', 'VS_LastGenPwr', 'VS_MechGenPwr', & + 'VS_SpdErrAr', 'VS_SpdErrBr', 'VS_SpdErr', 'VS_State', 'VS_Rgn3Pitch', & + 'WE_Vw', 'WE_Vw_F', 'WE_VwI', 'WE_VwIdot', 'VS_LastGenTrqF', & + 'Fl_PitCom', 'NACIMU_FA_AccF', 'FA_AccF', 'Flp_Angle', 'RootMyb_Last', & + 'ACC_INFILE_SIZE'] ! Initialize debug file IF ((LocalVar%iStatus == 0) .OR. (LocalVar%iStatus == -9)) THEN ! .TRUE. if we're on the first call to the DLL IF (CntrPar%LoggingLevel > 0) THEN diff --git a/ROSCO/src/ROSCO_Types.f90 b/ROSCO/src/ROSCO_Types.f90 index 46c26a09..1348389d 100644 --- a/ROSCO/src/ROSCO_Types.f90 +++ b/ROSCO/src/ROSCO_Types.f90 @@ -64,6 +64,10 @@ MODULE ROSCO_Types INTEGER(IntKi) :: SS_Mode ! Setpoint Smoother mode {0 - no setpoint smoothing, 1 - introduce setpoint smoothing} REAL(DbKi) :: SS_VSGain ! Variable speed torque controller setpoint smoother gain, [-]. REAL(DbKi) :: SS_PCGain ! Collective pitch controller setpoint smoother gain, [-]. + INTEGER(IntKi) :: PRC_Mode ! Power reference tracking mode, 0- use standard rotor speed set points, 1- use PRC rotor speed setpoints + REAL(DbKi), DIMENSION(:), ALLOCATABLE :: PRC_WindSpeeds ! Array of wind speeds used in rotor speed vs. wind speed lookup table + REAL(DbKi), DIMENSION(:), ALLOCATABLE :: PRC_RotorSpeeds ! Array of rotor speeds corresponding to PRC_WindSpeeds + INTEGER(IntKi) :: PRC_n ! Number of elements in PRC_WindSpeeds and PRC_RotorSpeeds array INTEGER(IntKi) :: WE_Mode ! Wind speed estimator mode {0 - One-second low pass filtered hub height wind speed, 1 - Imersion and Invariance Estimator (Ortega et al.) REAL(DbKi) :: WE_BladeRadius ! Blade length [m] INTEGER(IntKi) :: WE_CP_n ! Amount of parameters in the Cp array @@ -202,6 +206,8 @@ MODULE ROSCO_Types REAL(DbKi) :: FA_AccHPFI ! Tower velocity, high-pass filtered and integrated fore-aft acceleration [m/s] REAL(DbKi) :: FA_PitCom(3) ! Tower fore-aft vibration damping pitch contribution [rad] REAL(DbKi) :: RotSpeedF ! Filtered LSS (generator) speed [rad/s]. + REAL(DbKi) :: VS_RefSpd ! Generator speed set point of torque controller [rad/s] + REAL(DbKi) :: PC_RefSpd ! Generator speed set point of pitch controller [rad/s] REAL(DbKi) :: GenSpeedF ! Filtered HSS (generator) speed [rad/s]. REAL(DbKi) :: GenTq ! Electrical generator torque, [Nm]. REAL(DbKi) :: GenTqMeas ! Measured generator torque [Nm] diff --git a/ROSCO/src/ReadSetParameters.f90 b/ROSCO/src/ReadSetParameters.f90 index a0ac9e38..84e199d6 100644 --- a/ROSCO/src/ReadSetParameters.f90 +++ b/ROSCO/src/ReadSetParameters.f90 @@ -237,6 +237,7 @@ SUBROUTINE ReadControlParameterFileSub(CntrPar, zmqVar, accINFILE, accINFILE_siz CALL ParseInput(UnControllerParameters,CurLine,'PC_ControlMode',accINFILE(1),CntrPar%PC_ControlMode,ErrVar) CALL ParseInput(UnControllerParameters,CurLine,'Y_ControlMode',accINFILE(1),CntrPar%Y_ControlMode,ErrVar) CALL ParseInput(UnControllerParameters,CurLine,'SS_Mode',accINFILE(1),CntrPar%SS_Mode,ErrVar) + CALL ParseInput(UnControllerParameters,CurLine,'PRC_Mode',accINFILE(1),CntrPar%PRC_Mode,ErrVar) CALL ParseInput(UnControllerParameters,CurLine,'WE_Mode',accINFILE(1),CntrPar%WE_Mode,ErrVar) CALL ParseInput(UnControllerParameters,CurLine,'PS_Mode',accINFILE(1),CntrPar%PS_Mode,ErrVar) CALL ParseInput(UnControllerParameters,CurLine,'SD_Mode',accINFILE(1),CntrPar%SD_Mode,ErrVar) @@ -315,6 +316,13 @@ SUBROUTINE ReadControlParameterFileSub(CntrPar, zmqVar, accINFILE, accINFILE_siz CALL ParseInput(UnControllerParameters,CurLine,'SS_PCGain',accINFILE(1),CntrPar%SS_PCGain,ErrVar) CALL ReadEmptyLine(UnControllerParameters,CurLine) + !------------ POWER REFERENCE TRACKING SETPOINTS -------------- + CALL ReadEmptyLine(UnControllerParameters,CurLine) + CALL ParseInput(UnControllerParameters,CurLine,'PRC_n',accINFILE(1),CntrPar%PRC_n,ErrVar) + CALL ParseAry(UnControllerParameters, CurLine, 'PRC_WindSpeeds', CntrPar%PRC_WindSpeeds, CntrPar%PRC_n, accINFILE(1), ErrVar ) + CALL ParseAry(UnControllerParameters, CurLine, 'PRC_RotorSpeeds', CntrPar%PRC_RotorSpeeds, CntrPar%PRC_n, accINFILE(1), ErrVar ) + CALL ReadEmptyLine(UnControllerParameters,CurLine) + !------------ WIND SPEED ESTIMATOR CONTANTS -------------- CALL ReadEmptyLine(UnControllerParameters,CurLine) CALL ParseInput(UnControllerParameters,CurLine,'WE_BladeRadius',accINFILE(1),CntrPar%WE_BladeRadius,ErrVar) @@ -867,6 +875,10 @@ SUBROUTINE CheckInputs(LocalVar, CntrPar, avrSWAP, ErrVar, size_avcMSG) ErrVar%aviFAIL = -1 ErrVar%ErrMsg = 'SS_PCGain must be greater than zero.' ENDIF + + IF (CntrPar%PRC_Mode > 0) THEN + PRINT *, "Note: PRC Mode = ", CntrPar%PRC_Mode, ", which will ignore VS_RefSpeed, VS_TSRopt, and PC_RefSpeed" + ENDIF !------- WIND SPEED ESTIMATOR --------------------------------------------- diff --git a/ROSCO_toolbox/inputs/toolbox_schema.yaml b/ROSCO_toolbox/inputs/toolbox_schema.yaml index c3e0c80b..39776544 100644 --- a/ROSCO_toolbox/inputs/toolbox_schema.yaml +++ b/ROSCO_toolbox/inputs/toolbox_schema.yaml @@ -680,6 +680,22 @@ properties: SS_PCGain: type: number description: Collective pitch controller setpoint smoother gain + PRC_Mode: + type: number + description: Power reference tracking mode, 0- use standard rotor speed set points, 1- use PRC rotor speed setpoints + PRC_WindSpeeds: + type: array + items: + type: number + description: Array of wind speeds used in rotor speed vs. wind speed lookup table + PRC_RotorSpeeds: + type: array + items: + type: number + description: Array of rotor speeds corresponding to PRC_WindSpeeds + PRC_n: + type: number + description: Number of elements in PRC_WindSpeeds and PRC_RotorSpeeds array WE_BladeRadius: type: number description: Blade length (distance from hub center to blade tip) diff --git a/ROSCO_toolbox/ofTools/case_gen/CaseLibrary.py b/ROSCO_toolbox/ofTools/case_gen/CaseLibrary.py index 72fe0763..a6262d61 100644 --- a/ROSCO_toolbox/ofTools/case_gen/CaseLibrary.py +++ b/ROSCO_toolbox/ofTools/case_gen/CaseLibrary.py @@ -134,7 +134,10 @@ def power_curve(**wind_case_opts): else: # default # Run conditions U = np.arange(4,14.5,.5).tolist() - U = np.linspace(9.5,12,num=16) + U = np.linspace(3,25,num=16) + + if 'T_max' in wind_case_opts: + T_max = wind_case_opts['T_max'] case_inputs = base_op_case() @@ -472,7 +475,7 @@ def sweep_ps_percent(start_group, **control_sweep_opts): # make default controller, turbine objects for ROSCO_toolbox turbine = ROSCO_turbine.Turbine(turbine_params) - turbine.load_from_fast( path_params['FAST_InputFile'],path_params['FAST_directory'], dev_branch=True) + turbine.load_from_fast( path_params['FAST_InputFile'],path_params['FAST_directory'], dev_branch=True) #TODO: this is not working with relative paths in yaml controller = ROSCO_controller.Controller(controller_params) diff --git a/ROSCO_toolbox/ofTools/case_gen/run_FAST.py b/ROSCO_toolbox/ofTools/case_gen/run_FAST.py index a0c31925..9bd5e4f9 100644 --- a/ROSCO_toolbox/ofTools/case_gen/run_FAST.py +++ b/ROSCO_toolbox/ofTools/case_gen/run_FAST.py @@ -179,7 +179,7 @@ def run_FAST(self): if __name__ == "__main__": # Simulation config - sim_config = 11 + sim_config = 14 r = run_FAST_ROSCO() @@ -270,6 +270,32 @@ def run_FAST(self): r.control_sweep_fcn = cl.sweep_ps_percent r.n_cores = 4 + elif sim_config == 12: + + # RAAW FAD set up + r.tuning_yaml = '/Users/dzalkind/Projects/BAR/BAR_Designs/BAR_USC/WEIS/ROSCO_BAR_USC.yaml' + r.wind_case_fcn = cl.turb_bts + r.wind_case_opts = { + 'TMax': 720, + 'wind_filenames': ['/Users/dzalkind/Tools/WEIS-1/outputs/02_loads/wind/IEA15_NTM_U7.000000_Seed1501552846.0.bts'] + } + r.save_dir = '/Users/dzalkind/Projects/BAR/BAR_Designs/BAR_USC' + # r.control_sweep_fcn = cl.sweep_ps_percent + r.n_cores = 1 + + elif sim_config == 14: + + # RAAW FAD set up + r.tuning_yaml = '/Users/dzalkind/Tools/ROSCO/Tune_Cases/IEA15MW_PRC.yaml' + r.wind_case_fcn = cl.power_curve + r.wind_case_opts = { + # 'U': [16], + 'T_max': 200 + } + r.save_dir = '/Users/dzalkind/Tools/ROSCO/outputs/PRC_2' + # r.control_sweep_fcn = cl.sweep_ps_percent + r.n_cores = 8 + else: raise Exception('This simulation configuration is not supported.') diff --git a/ROSCO_toolbox/ofTools/fast_io/plot_FAST.ipynb b/ROSCO_toolbox/ofTools/fast_io/plot_FAST.ipynb index 4e64a191..9846ce9b 100644 --- a/ROSCO_toolbox/ofTools/fast_io/plot_FAST.ipynb +++ b/ROSCO_toolbox/ofTools/fast_io/plot_FAST.ipynb @@ -9,7 +9,7 @@ }, { "cell_type": "code", - "execution_count": 2, + "execution_count": 9, "metadata": {}, "outputs": [], "source": [ @@ -38,7 +38,10 @@ "import matplotlib.pyplot as plt\n", "# %matplotlib\n", "\n", - "i_fig = 0" + "i_fig = 0\n", + "\n", + "rpm2RadSec = 2.0*(np.pi)/60.0\n", + "\n" ] }, { @@ -50,7 +53,7 @@ }, { "cell_type": "code", - "execution_count": 3, + "execution_count": 74, "metadata": {}, "outputs": [], "source": [ @@ -60,7 +63,10 @@ "# '/Users/dzalkind/Tools/WEIS-1/outputs/iea15mw/iea15mw_02.outb',\n", "# '/Users/dzalkind/Tools/WEIS-1/outputs/iea15mw/iea15mw_08.outb',\n", "# '/Users/dzalkind/Tools/ROSCO_toolbox/Examples/examples_out/13_Simulink_Test/OL_Test_1.SFunc.outb',\n", - " '/Users/dzalkind/Projects/FOCAL/IEA15MW_FOCAL/power_curve/base/IEA15MW_FOCAL_07.outb',\n", + " # '/Users/dzalkind/Projects/BAR/BAR_Designs/BAR_USC/ROSCO_BAR_USC/turb_bts/base/ROSCO_BAR_USC_0.out',\n", + " # '/Users/dzalkind/Tools/ROSCO/outputs/PRC_0/IEA15MW_PRC/power_curve/base/IEA15MW_PRC_0.outb',\n", + " # '/Users/dzalkind/Tools/ROSCO/outputs/PRC_1/IEA15MW_PRC/power_curve/base/IEA15MW_PRC_0.out',\n", + " '/Users/dzalkind/Tools/ROSCO/outputs/PRC_2/IEA15MW_PRC/power_curve/base/IEA15MW_PRC_01.out',\n", "# '/Users/dzalkind/Tools/WEIS-3/results/UMaine-Semi/DISCON/IB_NTM_Raft/iea15mw_1.outb',\n", "# '/Users/dzalkind/Tools/WEIS-3/results/UMaine-Semi/DISCON/IB_NTM_Raft/iea15mw_2.outb',\n", "# '/Users/dzalkind/Tools/WEIS-3/results/CT-semi/ntm_long/DISCON-CT-semi/iea15mw_13.outb',\n", @@ -78,38 +84,26 @@ }, { "cell_type": "code", - "execution_count": 6, + "execution_count": 75, "metadata": {}, "outputs": [ { "name": "stdout", "output_type": "stream", "text": [ - "Wind1VelX is not available as an output channel.\n", - "BldPitch1 is not available as an output channel.\n", - "GenTq is not available as an output channel.\n", - "TwrBsMyt is not available as an output channel.\n", - "GenPwr is not available as an output channel.\n", - "RotThrust is not available as an output channel.\n", - "Fl_Pitcom is not available as an output channel.\n", + "WE_Vw_F is not available as an output channel.\n", + "VS_RefSpd is not available as an output channel.\n", + "PC_RefSpd is not available as an output channel.\n", + "PC_SpdErr is not available as an output channel.\n", + "VS_SpdErr is not available as an output channel.\n", + "Fl_PitCom is not available as an output channel.\n", "PC_MinPit is not available as an output channel.\n", - "WE_Vw is not available as an output channel.\n", - "RtVAvgxh is not available as an output channel.\n", - "BldPitch1 is not available as an output channel.\n", - "PtfmSurge is not available as an output channel.\n", - "PtfmSway is not available as an output channel.\n", - "PtfmHeave is not available as an output channel.\n", - "PtfmPitch is not available as an output channel.\n", - "PtfmRoll is not available as an output channel.\n", - "PtfmYaw is not available as an output channel.\n", - "RtVAvgxh is not available as an output channel.\n", - "BldPitch1 is not available as an output channel.\n", - "RotThrust is not available as an output channel.\n" + "WE_Vw is not available as an output channel.\n" ] }, { "data": { - "image/png": "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\n", + "image/png": "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\n", "text/plain": [ "
" ] @@ -121,7 +115,7 @@ }, { "data": { - "image/png": "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\n", + "image/png": "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\n", "text/plain": [ "
" ] @@ -133,9 +127,9 @@ }, { "data": { - "image/png": "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\n", + "image/png": "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\n", "text/plain": [ - "
" + "
" ] }, "metadata": { @@ -145,7 +139,7 @@ }, { "data": { - "image/png": "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\n", + "image/png": "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\n", "text/plain": [ "
" ] @@ -161,24 +155,33 @@ "plt.rcParams[\"figure.figsize\"] = [9,7]\n", "\n", "ROSCO = True\n", + "ROSCO2 = True\n", "\n", "# Define Plot cases \n", "cases = {}\n", "cases['Gen. Speed Sigs.'] = ['Wind1VelX', 'BldPitch1', 'GenTq', 'GenSpeed','TwrBsMyt','GenPwr','RotThrust']#,'PtfmPitch','PtfmYaw','NacYaw']\n", "# cases['Debug'] = ['IPDefl1','OoPDefl1','Azimuth','RotTorq']#,'PtfmPitch','PtfmYaw','NacYaw']\n", - "cases['Plt. Control Sigs.'] = ['RtVAvgxh', 'BldPitch1', 'Fl_Pitcom', 'PC_MinPit','WE_Vw']\n", - "cases['Platform Motion'] = ['PtfmSurge', 'PtfmSway', 'PtfmHeave', 'PtfmPitch','PtfmRoll','PtfmYaw']\n", + "cases['PRC Control Sigs.'] = ['WE_Vw_F','VS_RefSpd', 'PC_RefSpd','PC_SpdErr','VS_SpdErr']\n", + "cases['Plt. Control Sigs.'] = ['RtVAvgxh', 'BldPitch1', 'Fl_PitCom', 'PC_MinPit','WE_Vw']\n", + "# cases['Platform Motion'] = ['PtfmSurge', 'PtfmSway', 'PtfmHeave', 'PtfmPitch','PtfmRoll','PtfmYaw']\n", "cases['Rot Thrust'] = ['RtVAvgxh','BldPitch1','RotThrust']\n", "\n", "op = output_processing.output_processing()\n", + "op_RO = output_processing.output_processing()\n", + "op_RO2 = output_processing.output_processing()\n", + "\n", "\n", - "# Rosco outfiles\n", - "r_outfiles = [out.split('.out')[0] + '.RO.dbg' for out in outfiles]\n", "\n", "fast_out = []\n", "fast_out = op.load_fast_out(outfiles, tmin=0)\n", "if ROSCO:\n", - " rosco_out = op.load_fast_out(r_outfiles, tmin=0)\n", + " # Rosco outfiles\n", + " r_outfiles = [out.split('.out')[0] + '.RO.dbg' for out in outfiles]\n", + " rosco_out = op_RO.load_fast_out(r_outfiles, tmin=0)\n", + " \n", + " if ROSCO2:\n", + " r_outfiles = [out.split('.out')[0] + '.RO.dbg2' for out in outfiles]\n", + " rosco_out2 = op_RO2.load_fast_out(r_outfiles, tmin=0)\n", " \n", "# Combine outputs\n", "if ROSCO:\n", @@ -186,6 +189,10 @@ " for i, (r_out, f_out) in enumerate(zip(rosco_out,fast_out)):\n", " r_out.update(f_out)\n", " comb_out[i] = r_out\n", + " if ROSCO2:\n", + " for i, (r_out2, f_out) in enumerate(zip(rosco_out2,comb_out)):\n", + " r_out2.update(f_out)\n", + " comb_out[i] = r_out2\n", "else:\n", " comb_out = fast_out\n", "\n", @@ -205,6 +212,102 @@ " i_fig += 1" ] }, + { + "cell_type": "code", + "execution_count": 72, + "metadata": {}, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "[ 0.052, 0.032, 0.012, -0.012, -0.017, -0.017, -0.017, -0.017, -0.017, -0.017, -0.001, 0.01 , 0.02 , 0.029, 0.048, 0.068, 0.085, 0.1 , 0.113, 0.129, 0.145, 0.159, 0.172, 0.185, 0.197, 0.208, 0.219, 0.229, 0.238, 0.244, 0.251, 0.26 , 0.269, 0.277, 0.286, 0.296, 0.304, 0.313, 0.322, 0.332, 0.341, 0.35 , 0.359, 0.369, 0.378, 0.387, 0.396, 0.407, 0.416, 0.424, 0.434, 0.444, 0.454, 0.463, 0.473, 0.481]\n", + "[ 3. , 3.4, 3.8, 4.2, 4.6, 5. , 5.4, 5.8, 6.2, 6.6, 7. , 7.4, 7.8, 8.2, 8.6, 9. , 9.4, 9.8, 10.2, 10.6, 11. , 11.4, 11.8, 12.2, 12.6, 13. , 13.4, 13.8, 14.2, 14.6, 15. , 15.4, 15.8, 16.2, 16.6, 17. , 17.4, 17.8, 18.2, 18.6, 19. , 19.4, 19.8, 20.2, 20.6, 21. , 21.4, 21.8, 22.2, 22.6, 23. , 23.4, 23.8, 24.2, 24.6, 25. ]\n", + "[0.292, 0.292, 0.292, 0.292, 0.311, 0.338, 0.365, 0.392, 0.419, 0.446, 0.459, 0.459, 0.459, 0.459, 0.475, 0.497, 0.519, 0.542, 0.564, 0.564, 0.564, 0.564, 0.564, 0.564, 0.564, 0.564, 0.564, 0.564, 0.564, 0.564, 0.564, 0.558, 0.553, 0.547, 0.542, 0.536, 0.531, 0.526, 0.52 , 0.515, 0.509, 0.504, 0.498, 0.493, 0.487, 0.482, 0.477, 0.471, 0.466, 0.46 , 0.455, 0.449, 0.444, 0.439, 0.433, 0.428]\n" + ] + }, + { + "data": { + "image/png": "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\n", + "text/plain": [ + "
" + ] + }, + "metadata": { + "needs_background": "light" + }, + "output_type": "display_data" + } + ], + "source": [ + "M = np.loadtxt('/Users/dzalkind/Downloads/Megablade_35_sr180_GenEff_control_schedule.txt',delimiter=',')\n", + "\n", + "UU = M[:,0]\n", + "\n", + "rot_speed = M[:,1] * rpm2RadSec\n", + "\n", + "rot_speed\n", + "\n", + "min_pitch = np.deg2rad(M[:,2])\n", + "\n", + "min_pitch\n", + "\n", + "ds = 4\n", + "\n", + "fig, axs = plt.subplots(2,1)\n", + "\n", + "# axs[0].plot(UU,rot_speed)\n", + "axs[0].plot(UU[::ds],rot_speed[::ds]/ rpm2RadSec)\n", + "# axs[1].plot(UU,min_pitch)\n", + "axs[1].plot(UU[::ds],np.rad2deg(min_pitch[::ds]))\n", + "\n", + "\n", + "\n", + "\n", + "[a.grid(True) for a in axs]\n", + "\n", + "np.set_printoptions(linewidth=np.inf)\n", + "\n", + "# print(min_pitch)\n", + "\n", + "print(np.array2string(min_pitch[::ds], separator=', ', precision=3))\n", + "print(np.array2string(UU[::ds], separator=', ', precision=3))\n", + "print(np.array2string(rot_speed[::ds], separator=', ', precision=3))\n", + "\n", + "# # len(min_pitch)\n", + "\n", + "# # a = '3.000000 3.100000 3.200000 3.300000 3.400000 3.500000 3.600000 3.700000 3.800000 3.900000 4.000000 4.100000 4.200000 4.300000 4.400000 4.500000 4.600000 4.700000 4.800000 4.900000 5.000000 5.100000 5.200000 5.300000 5.400000 5.500000 5.600000 5.700000 5.800000 5.900000 6.000000 6.100000 6.200000 6.300000 6.400000 6.500000 6.600000 6.700000 6.800000 6.900000 7.000000 7.100000 7.200000 7.300000 7.400000 7.500000 7.600000 7.700000 7.800000 7.900000 8.000000 8.100000 8.200000 8.300000 8.400000 8.500000 8.600000 8.700000 8.800000 8.900000 9.000000 9.100000 9.200000 9.300000 9.400000 9.500000 9.600000 9.700000 9.800000 9.900000 10.000000 10.100000 10.200000 10.300000 10.400000 10.500000 10.600000 10.700000 10.800000 10.900000 11.000000 11.100000 11.200000 11.300000 11.400000 11.500000 11.600000 11.700000 11.800000 11.900000 12.000000 12.100000 12.200000 12.300000 12.400000 12.500000 12.600000 12.700000 12.800000 12.900000 13.000000 13.100000 13.200000 13.300000 13.400000 13.500000 13.600000 13.700000 13.800000 13.900000 14.000000 14.100000 14.200000 14.300000 14.400000 14.500000 14.600000 14.700000 14.800000 14.900000 15.000000 15.100000 15.200000 15.300000 15.400000 15.500000 15.600000 15.700000 15.800000 15.900000 16.000000 16.100000 16.200000 16.300000 16.400000 16.500000 16.600000 16.700000 16.800000 16.900000 17.000000 17.100000 17.200000 17.300000 17.400000 17.500000 17.600000 17.700000 17.800000 17.900000 18.000000 18.100000 18.200000 18.300000 18.400000 18.500000 18.600000 18.700000 18.800000 18.900000 19.000000 19.100000 19.200000 19.300000 19.400000 19.500000 19.600000 19.700000 19.800000 19.900000 20.000000 20.100000 20.200000 20.300000 20.400000 20.500000 20.600000 20.700000 20.800000 20.900000 21.000000 21.100000 21.200000 21.300000 21.400000 21.500000 21.600000 21.700000 21.800000 21.900000 22.000000 22.100000 22.200000 22.300000 22.400000 22.500000 22.600000 22.700000 22.800000 22.900000 23.000000 23.100000 23.200000 23.300000 23.400000 23.500000 23.600000 23.700000 23.800000 23.900000 24.000000 24.100000 24.200000 24.300000 24.400000 24.500000 24.600000 24.700000 24.800000 24.900000 25.000000 ! PRC_WindSpeeds\t- Array of wind speeds used in rotor speed vs. wind speed lookup table [m/s].'\n", + "\n", + "# len(rot_speed[::ds])" + ] + }, + { + "cell_type": "code", + "execution_count": 71, + "metadata": {}, + "outputs": [ + { + "data": { + "text/plain": [ + "4.087098938599873" + ] + }, + "execution_count": 71, + "metadata": {}, + "output_type": "execute_result" + } + ], + "source": [ + "co = comb_out[0]\n", + "\n", + "ind = co['Time'] > 100\n", + "\n", + "co['Wind1VelX'][ind].mean()\n", + "co['GenSpeed'][ind].mean()\n", + "co['PC_RefSpd'][ind].mean() / rpm2RadSec\n", + "\n" + ] + }, { "cell_type": "code", "execution_count": 28, @@ -721,7 +824,7 @@ "name": "python", "nbconvert_exporter": "python", "pygments_lexer": "ipython3", - "version": "3.8.6" + "version": "3.8.13" } }, "nbformat": 4, diff --git a/ROSCO_toolbox/utilities.py b/ROSCO_toolbox/utilities.py index b68dd3a9..dda56a66 100644 --- a/ROSCO_toolbox/utilities.py +++ b/ROSCO_toolbox/utilities.py @@ -73,6 +73,7 @@ def write_DISCON(turbine, controller, param_file='DISCON.IN', txt_filename='Cp_C file.write('{0:<12d} ! PC_ControlMode - Blade pitch control mode {{0: No pitch, fix to fine pitch, 1: active PI blade pitch control}}\n'.format(int(rosco_vt['PC_ControlMode']))) file.write('{0:<12d} ! Y_ControlMode - Yaw control mode {{0: no yaw control, 1: yaw rate control, 2: yaw-by-IPC}}\n'.format(int(rosco_vt['Y_ControlMode']))) file.write('{0:<12d} ! SS_Mode - Setpoint Smoother mode {{0: no setpoint smoothing, 1: introduce setpoint smoothing}}\n'.format(int(rosco_vt['SS_Mode']))) + file.write('{0:<12d} ! PRC_Mode - Power reference tracking mode{{0: use standard rotor speed set points, 1: use PRC rotor speed setpoints}}\n'.format(int(rosco_vt['PRC_Mode']))) file.write('{0:<12d} ! WE_Mode - Wind speed estimator mode {{0: One-second low pass filtered hub height wind speed, 1: Immersion and Invariance Estimator, 2: Extended Kalman Filter}}\n'.format(int(rosco_vt['WE_Mode']))) file.write('{0:<12d} ! PS_Mode - Pitch saturation mode {{0: no pitch saturation, 1: implement pitch saturation}}\n'.format(int(rosco_vt['PS_Mode']))) file.write('{0:<12d} ! SD_Mode - Shutdown mode {{0: no shutdown procedure, 1: pitch to max pitch at shutdown}}\n'.format(int(rosco_vt['SD_Mode']))) @@ -141,6 +142,11 @@ def write_DISCON(turbine, controller, param_file='DISCON.IN', txt_filename='Cp_C file.write('{:<13.5f} ! SS_VSGain - Variable speed torque controller setpoint smoother gain, [-].\n'.format(rosco_vt['SS_VSGain'])) file.write('{:<13.5f} ! SS_PCGain - Collective pitch controller setpoint smoother gain, [-].\n'.format(rosco_vt['SS_PCGain'])) file.write('\n') + file.write('!------- POWER REFERENCE TRACKING --------------------------------------\n') + file.write('{:<11d} ! PRC_n - Number of elements in PRC_WindSpeeds and PRC_RotorSpeeds array\n'.format(int(rosco_vt['PRC_n']))) + file.write('{} ! PRC_WindSpeeds - Array of wind speeds used in rotor speed vs. wind speed lookup table [m/s].\n'.format(''.join('{:<4.3f} '.format(rosco_vt['PRC_WindSpeeds'][i]) for i in range(rosco_vt['PRC_n'])))) + file.write('{} ! PRC_RotorSpeeds - Array of rotor speeds corresponding to PRC_WindSpeeds [rad/s].\n'.format(''.join('{:<4.3f} '.format(rosco_vt['PRC_RotorSpeeds'][i]) for i in range(rosco_vt['PRC_n'])))) + file.write('\n') file.write('!------- WIND SPEED ESTIMATOR ---------------------------------------------\n') file.write('{:<13.3f} ! WE_BladeRadius - Blade length (distance from hub center to blade tip), [m]\n'.format(rosco_vt['WE_BladeRadius'])) file.write('{:<11d} ! WE_CP_n - Amount of parameters in the Cp array\n'.format(int(rosco_vt['WE_CP_n']))) @@ -171,8 +177,8 @@ def write_DISCON(turbine, controller, param_file='DISCON.IN', txt_filename='Cp_C file.write('\n') file.write('!------- MINIMUM PITCH SATURATION -------------------------------------------\n') file.write('{:<11d} ! 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(int(rosco_vt['PS_BldPitchMin_N']))) - file.write('{} ! PS_WindSpeeds - Wind speeds corresponding to minimum blade pitch angles [m/s]\n'.format(''.join('{:<4.4f} '.format(rosco_vt['PS_WindSpeeds'][i]) for i in range(len(rosco_vt['PS_WindSpeeds']))))) - file.write('{} ! PS_BldPitchMin - Minimum blade pitch angles [rad]\n'.format(''.join('{:<10.8f} '.format(rosco_vt['PS_BldPitchMin'][i]) for i in range(len(rosco_vt['PS_BldPitchMin']))))) + file.write('{} ! PS_WindSpeeds - Wind speeds corresponding to minimum blade pitch angles [m/s]\n'.format(''.join('{:<4.3f} '.format(rosco_vt['PS_WindSpeeds'][i]) for i in range(len(rosco_vt['PS_WindSpeeds']))))) + file.write('{} ! PS_BldPitchMin - Minimum blade pitch angles [rad]\n'.format(''.join('{:<10.3f} '.format(rosco_vt['PS_BldPitchMin'][i]) for i in range(len(rosco_vt['PS_BldPitchMin']))))) file.write('\n') file.write('!------- SHUTDOWN -----------------------------------------------------------\n') file.write('{:<014.5f} ! SD_MaxPit - Maximum blade pitch angle to initiate shutdown, [rad]\n'.format(rosco_vt['SD_MaxPit'])) @@ -386,6 +392,7 @@ def DISCON_dict(turbine, controller, txt_filename=None): DISCON_dict['PC_ControlMode'] = int(controller.PC_ControlMode) DISCON_dict['Y_ControlMode'] = int(controller.Y_ControlMode) DISCON_dict['SS_Mode'] = int(controller.SS_Mode) + DISCON_dict['PRC_Mode'] = 0 DISCON_dict['WE_Mode'] = int(controller.WE_Mode) DISCON_dict['PS_Mode'] = int(controller.PS_Mode > 0) DISCON_dict['SD_Mode'] = int(controller.SD_Mode) @@ -454,6 +461,11 @@ def DISCON_dict(turbine, controller, txt_filename=None): # ------- SETPOINT SMOOTHER ------- DISCON_dict['SS_VSGain'] = controller.ss_vsgain DISCON_dict['SS_PCGain'] = controller.ss_pcgain + # -------- POWER REFERENCE TRACKING ------ + DISCON_dict['PRC_n'] = 2 + DISCON_dict['PRC_WindSpeeds'] = [3,25] + DISCON_dict['PRC_RotorSpeeds'] = [rpm2RadSec * 7.56] * 2 + # ------- WIND SPEED ESTIMATOR ------- DISCON_dict['WE_BladeRadius'] = turbine.rotor_radius DISCON_dict['WE_CP_n'] = 1 diff --git a/Test_Cases/IEA-15-240-RWT-UMaineSemi/IEA-15-240-RWT-UMaineSemi.fst b/Test_Cases/IEA-15-240-RWT-UMaineSemi/IEA-15-240-RWT-UMaineSemi.fst index a2684323..aff9b66e 100644 --- a/Test_Cases/IEA-15-240-RWT-UMaineSemi/IEA-15-240-RWT-UMaineSemi.fst +++ b/Test_Cases/IEA-15-240-RWT-UMaineSemi/IEA-15-240-RWT-UMaineSemi.fst @@ -14,9 +14,9 @@ False Echo - Echo input data to .ech (flag) 1 CompInflow - Compute inflow wind velocities (switch) {0=still air; 1=InflowWind; 2=external from OpenFOAM} 2 CompAero - Compute aerodynamic loads (switch) {0=None; 1=AeroDyn v14; 2=AeroDyn v15} 1 CompServo - Compute control and electrical-drive dynamics (switch) {0=None; 1=ServoDyn} - 1 CompHydro - Compute hydrodynamic loads (switch) {0=None; 1=HydroDyn} + 0 CompHydro - Compute hydrodynamic loads (switch) {0=None; 1=HydroDyn} 0 CompSub - Compute sub-structural dynamics (switch) {0=None; 1=SubDyn} - 3 CompMooring - Compute mooring system (switch) {0=None; 1=MAP++; 2=FEAMooring; 3=MoorDyn; 4=OrcaFlex} + 0 CompMooring - Compute mooring system (switch) {0=None; 1=MAP++; 2=FEAMooring; 3=MoorDyn; 4=OrcaFlex} 0 CompIce - Compute ice loads (switch) {0=None; 1=IceFloe; 2=IceDyn} 0 MHK - MHK turbine type (switch) {0=Not an MHK turbine; 1=Fixed MHK turbine; 2=Floating MHK turbine} ---------------------- ENVIRONMENTAL CONDITIONS -------------------------------- diff --git a/Test_Cases/IEA-15-240-RWT-UMaineSemi/IEA-15-240-RWT-UMaineSemi_ElastoDyn.dat b/Test_Cases/IEA-15-240-RWT-UMaineSemi/IEA-15-240-RWT-UMaineSemi_ElastoDyn.dat index 07ca94c0..11740369 100644 --- a/Test_Cases/IEA-15-240-RWT-UMaineSemi/IEA-15-240-RWT-UMaineSemi_ElastoDyn.dat +++ b/Test_Cases/IEA-15-240-RWT-UMaineSemi/IEA-15-240-RWT-UMaineSemi_ElastoDyn.dat @@ -16,12 +16,12 @@ True TwFADOF1 - First fore-aft tower bending-mode DOF (flag) True TwFADOF2 - Second fore-aft tower bending-mode DOF (flag) True TwSSDOF1 - First side-to-side tower bending-mode DOF (flag) True TwSSDOF2 - Second side-to-side tower bending-mode DOF (flag) -True PtfmSgDOF - Platform horizontal surge translation DOF (flag) -True PtfmSwDOF - Platform horizontal sway translation DOF (flag) -True PtfmHvDOF - Platform vertical heave translation DOF (flag) -True PtfmRDOF - Platform roll tilt rotation DOF (flag) -True PtfmPDOF - Platform pitch tilt rotation DOF (flag) -True PtfmYDOF - Platform yaw rotation DOF (flag) +False PtfmSgDOF - Platform horizontal surge translation DOF (flag) +False PtfmSwDOF - Platform horizontal sway translation DOF (flag) +False PtfmHvDOF - Platform vertical heave translation DOF (flag) +False PtfmRDOF - Platform roll tilt rotation DOF (flag) +False PtfmPDOF - Platform pitch tilt rotation DOF (flag) +False PtfmYDOF - Platform yaw rotation DOF (flag) ---------------------- INITIAL CONDITIONS -------------------------------------- 0 OoPDefl - Initial out-of-plane blade-tip displacement (meters) 0 IPDefl - Initial in-plane blade-tip deflection (meters) diff --git a/Tune_Cases/IEA15MW_PRC.yaml b/Tune_Cases/IEA15MW_PRC.yaml new file mode 100644 index 00000000..5e70d1e0 --- /dev/null +++ b/Tune_Cases/IEA15MW_PRC.yaml @@ -0,0 +1,67 @@ +# --------------------- ROSCO controller tuning input file ------------------- + # Written for use with ROSCO_Toolbox tuning procedures + # Turbine: IEA 15MW Reference Wind Turbine +# ------------------------------ OpenFAST PATH DEFINITIONS ------------------------------ +path_params: + FAST_InputFile: 'IEA-15-240-RWT-UMaineSemi.fst' # Name of *.fst file + FAST_directory: '../Test_Cases/IEA-15-240-RWT-UMaineSemi' # Main OpenFAST model directory, where the *.fst lives + # Optional (but suggested...) + rotor_performance_filename: 'Cp_Ct_Cq.IEA15MW.txt' # Filename for rotor performance text file (if it has been generated by ccblade already) + +# -------------------------------- TURBINE PARAMETERS ----------------------------------- +turbine_params: + rotor_inertia: 310619488. # Rotor inertia [kg m^2], {Available in Elastodyn .sum file} + rated_rotor_speed: 0.7916813478 # Rated rotor speed [rad/s] + v_min: 3. # Cut-in wind speed [m/s] + v_rated: 10.74 # Rated wind speed [m/s] + v_max: 25.0 # Cut-out wind speed [m/s], -- Does not need to be exact (JUST ASSUME FOR NOW) + max_pitch_rate: 0.0349 # Maximum blade pitch rate [rad/s] + max_torque_rate: 4500000. # Maximum torque rate [Nm/s], {~1/4 VS_RtTq/s} + rated_power: 15000000. # Rated Power [W] + bld_edgewise_freq: 4.0324 # Blade edgewise first natural frequency [rad/s] + bld_flapwise_freq: 3.4872 # Blade flapwise first natural frequency [rad/s] + TSR_operational: 9.0 + +#------------------------------- CONTROLLER PARAMETERS ---------------------------------- +controller_params: + # Controller flags + LoggingLevel: 2 # {0: write no debug files, 1: write standard output .dbg-file, 2: write standard output .dbg-file and complete avrSWAP-array .dbg2-file + F_LPFType: 2 # {1: first-order low-pass filter, 2: second-order low-pass filter}, [rad/s] (currently filters generator speed and pitch control signals) + F_NotchType: 0 # Notch on the measured generator speed {0: disable, 1: enable} + IPC_ControlMode: 0 # Turn Individual Pitch Control (IPC) for fatigue load reductions (pitch contribution) {0: off, 1: 1P reductions, 2: 1P+2P reductions} + VS_ControlMode: 2 # Generator torque control mode in above rated conditions {0: constant torque, 1: constant power, 2: TSR tracking PI control} + PC_ControlMode: 1 # Blade pitch control mode {0: No pitch, fix to fine pitch, 1: active PI blade pitch control} + Y_ControlMode: 0 # Yaw control mode {0: no yaw control, 1: yaw rate control, 2: yaw-by-IPC} + SS_Mode: 1 # Setpoint Smoother mode {0: no setpoint smoothing, 1: introduce setpoint smoothing} + WE_Mode: 2 # Wind speed estimator mode {0: One-second low pass filtered hub height wind speed, 1: Immersion and Invariance Estimator (Ortega et al.)} + PS_Mode: 3 # Pitch saturation mode {0: no pitch saturation, 1: peak shaving, 2: Cp-maximizing pitch saturation, 3: peak shaving and Cp-maximizing pitch saturation} + SD_Mode: 0 # Shutdown mode {0: no shutdown procedure, 1: pitch to max pitch at shutdown} + Fl_Mode: 2 # Floating specific feedback mode {0: no nacelle velocity feedback, 1: nacelle velocity feedback} + Flp_Mode: 0 # Flap control mode {0: no flap control, 1: steady state flap angle, 2: Proportional flap control} + PA_Mode: 2 # Pitch actuator mode {0 - not used, 1 - first order filter, 2 - second order filter} + # Controller parameters + # U_pc: [14] + zeta_pc: 1.0 # Pitch controller desired damping ratio [-] + omega_pc: 0.2 # Pitch controller desired natural frequency [rad/s] + zeta_vs: 0.85 # Torque controller desired damping ratio [-] + omega_vs: 0.12 # Torque controller desired natural frequency [rad/s] + twr_freq: 3.355 # for semi only! + ptfm_freq: 0.213 # for semi only! + # Optional - these can be defined, but do not need to be + min_pitch: 0.0 # Minimum pitch angle [rad], {default = 0 degrees} + vs_minspd: 0.523598775 # Minimum rotor speed [rad/s], {default = 0 rad/s} + ps_percent: 0.8 # Percent peak shaving [%, <= 1 ], {default = 80%} + PA_CornerFreq: 1.5708 # Pitch actuator natural frequency [rad/s] + PA_Damping: 0.707 # Pitch actuator natural frequency [rad/s] + + DISCON: + PS_BldPitchMin_N: 56 + PS_WindSpeeds: [ 3. , 3.4, 3.8, 4.2, 4.6, 5. , 5.4, 5.8, 6.2, 6.6, 7. , 7.4, 7.8, 8.2, 8.6, 9. , 9.4, 9.8, 10.2, 10.6, 11. , 11.4, 11.8, 12.2, 12.6, 13. , 13.4, 13.8, 14.2, 14.6, 15. , 15.4, 15.8, 16.2, 16.6, 17. , 17.4, 17.8, 18.2, 18.6, 19. , 19.4, 19.8, 20.2, 20.6, 21. , 21.4, 21.8, 22.2, 22.6, 23. , 23.4, 23.8, 24.2, 24.6, 25. ] + PS_BldPitchMin: [ 0.052, 0.032, 0.012, -0.012, -0.017, -0.017, -0.017, -0.017, -0.017, -0.017, -0.001, 0.01 , 0.02 , 0.029, 0.048, 0.068, 0.085, 0.1 , 0.113, 0.129, 0.145, 0.159, 0.172, 0.185, 0.197, 0.208, 0.219, 0.229, 0.238, 0.244, 0.251, 0.26 , 0.269, 0.277, 0.286, 0.296, 0.304, 0.313, 0.322, 0.332, 0.341, 0.35 , 0.359, 0.369, 0.378, 0.387, 0.396, 0.407, 0.416, 0.424, 0.434, 0.444, 0.454, 0.463, 0.473, 0.481] + PRC_RotorSpeeds: [0.292, 0.292, 0.292, 0.292, 0.311, 0.338, 0.365, 0.392, 0.419, 0.446, 0.459, 0.459, 0.459, 0.459, 0.475, 0.497, 0.519, 0.542, 0.564, 0.564, 0.564, 0.564, 0.564, 0.564, 0.564, 0.564, 0.564, 0.564, 0.564, 0.564, 0.564, 0.558, 0.553, 0.547, 0.542, 0.536, 0.531, 0.526, 0.52 , 0.515, 0.509, 0.504, 0.498, 0.493, 0.487, 0.482, 0.477, 0.471, 0.466, 0.46 , 0.455, 0.449, 0.444, 0.439, 0.433, 0.428] + PRC_WindSpeeds: [ 3. , 3.4, 3.8, 4.2, 4.6, 5. , 5.4, 5.8, 6.2, 6.6, 7. , 7.4, 7.8, 8.2, 8.6, 9. , 9.4, 9.8, 10.2, 10.6, 11. , 11.4, 11.8, 12.2, 12.6, 13. , 13.4, 13.8, 14.2, 14.6, 15. , 15.4, 15.8, 16.2, 16.6, 17. , 17.4, 17.8, 18.2, 18.6, 19. , 19.4, 19.8, 20.2, 20.6, 21. , 21.4, 21.8, 22.2, 22.6, 23. , 23.4, 23.8, 24.2, 24.6, 25. ] + PRC_n: 56 + PRC_Mode: 1 + VS_MinOMSpd: 0 + Fl_Mode: 0 + diff --git a/pCrunch_processing.ipynb b/pCrunch_processing.ipynb new file mode 100644 index 00000000..056eff06 --- /dev/null +++ b/pCrunch_processing.ipynb @@ -0,0 +1,1507 @@ +{ + "cells": [ + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "### pCrunch Update\n", + "\n", + "Jake Nunemaker\n", + "\n", + "Last Updated: 02/08/2021" + ] + }, + { + "cell_type": "code", + "execution_count": 30, + "metadata": {}, + "outputs": [], + "source": [ + "import os\n", + "from fnmatch import fnmatch\n", + "\n", + "import numpy as np\n", + "import pandas as pd\n", + "import ruamel_yaml as ry\n", + "\n", + "import matplotlib.pyplot as plt\n", + "\n", + "from weis.aeroelasticse import FileTools\n", + "\n", + "rpm2RadSec = 2.0*(np.pi)/60.0\n", + "\n", + "\n", + "from pCrunch import LoadsAnalysis, PowerProduction, FatigueParams\n", + "from pCrunch.io import load_FAST_out\n", + "from pCrunch.utility import save_yaml, get_windspeeds, convert_summary_stats\n", + "\n", + "def valid_extension(fp):\n", + " return any([fnmatch(fp, ext) for ext in [\"*.outb\", \"*.out\"]])" + ] + }, + { + "cell_type": "code", + "execution_count": 3, + "metadata": {}, + "outputs": [ + { + "data": { + "text/html": [ + "
\n", + "\n", + "\n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + "
(AeroDyn15, AFAeroMod)(AeroDyn15, AIDrag)(AeroDyn15, HubLoss)(AeroDyn15, IndToler)(AeroDyn15, MaxIter)(AeroDyn15, SkewMod)(AeroDyn15, TIDrag)(AeroDyn15, TanInd)(AeroDyn15, TipLoss)(AeroDyn15, TwrAero)...(ServoDyn, GenTiStp)(ServoDyn, GenTiStr)(ServoDyn, HSSBrMode)(ServoDyn, PCMode)(ServoDyn, SpdGenOn)(ServoDyn, TimGenOn)(ServoDyn, VSContrl)(ServoDyn, YCMode)Case_IDCase_Name
02TrueTrue0.0000150001TrueTrueTrueFalse...TrueTrue550.00.0550IEA15MW_PRC_00
12TrueTrue0.0000150001TrueTrueTrueFalse...TrueTrue550.00.0551IEA15MW_PRC_01
22TrueTrue0.0000150001TrueTrueTrueFalse...TrueTrue550.00.0552IEA15MW_PRC_02
32TrueTrue0.0000150001TrueTrueTrueFalse...TrueTrue550.00.0553IEA15MW_PRC_03
42TrueTrue0.0000150001TrueTrueTrueFalse...TrueTrue550.00.0554IEA15MW_PRC_04
52TrueTrue0.0000150001TrueTrueTrueFalse...TrueTrue550.00.0555IEA15MW_PRC_05
62TrueTrue0.0000150001TrueTrueTrueFalse...TrueTrue550.00.0556IEA15MW_PRC_06
72TrueTrue0.0000150001TrueTrueTrueFalse...TrueTrue550.00.0557IEA15MW_PRC_07
82TrueTrue0.0000150001TrueTrueTrueFalse...TrueTrue550.00.0558IEA15MW_PRC_08
92TrueTrue0.0000150001TrueTrueTrueFalse...TrueTrue550.00.0559IEA15MW_PRC_09
102TrueTrue0.0000150001TrueTrueTrueFalse...TrueTrue550.00.05510IEA15MW_PRC_10
112TrueTrue0.0000150001TrueTrueTrueFalse...TrueTrue550.00.05511IEA15MW_PRC_11
122TrueTrue0.0000150001TrueTrueTrueFalse...TrueTrue550.00.05512IEA15MW_PRC_12
132TrueTrue0.0000150001TrueTrueTrueFalse...TrueTrue550.00.05513IEA15MW_PRC_13
142TrueTrue0.0000150001TrueTrueTrueFalse...TrueTrue550.00.05514IEA15MW_PRC_14
152TrueTrue0.0000150001TrueTrueTrueFalse...TrueTrue550.00.05515IEA15MW_PRC_15
\n", + "

16 rows × 142 columns

\n", + "
" + ], + "text/plain": [ + " (AeroDyn15, AFAeroMod) (AeroDyn15, AIDrag) (AeroDyn15, HubLoss) \\\n", + "0 2 True True \n", + "1 2 True True \n", + "2 2 True True \n", + "3 2 True True \n", + "4 2 True True \n", + "5 2 True True \n", + "6 2 True True \n", + "7 2 True True \n", + "8 2 True True \n", + "9 2 True True \n", + "10 2 True True \n", + "11 2 True True \n", + "12 2 True True \n", + "13 2 True True \n", + "14 2 True True \n", + "15 2 True True \n", + "\n", + " (AeroDyn15, IndToler) (AeroDyn15, MaxIter) (AeroDyn15, SkewMod) \\\n", + "0 0.00001 5000 1 \n", + "1 0.00001 5000 1 \n", + "2 0.00001 5000 1 \n", + "3 0.00001 5000 1 \n", + "4 0.00001 5000 1 \n", + "5 0.00001 5000 1 \n", + "6 0.00001 5000 1 \n", + "7 0.00001 5000 1 \n", + "8 0.00001 5000 1 \n", + "9 0.00001 5000 1 \n", + "10 0.00001 5000 1 \n", + "11 0.00001 5000 1 \n", + "12 0.00001 5000 1 \n", + "13 0.00001 5000 1 \n", + "14 0.00001 5000 1 \n", + "15 0.00001 5000 1 \n", + "\n", + " (AeroDyn15, TIDrag) (AeroDyn15, TanInd) (AeroDyn15, TipLoss) \\\n", + "0 True True True \n", + "1 True True True \n", + "2 True True True \n", + "3 True True True \n", + "4 True True True \n", + "5 True True True \n", + "6 True True True \n", + "7 True True True \n", + "8 True True True \n", + "9 True True True \n", + "10 True True True \n", + "11 True True True \n", + "12 True True True \n", + "13 True True True \n", + "14 True True True \n", + "15 True True True \n", + "\n", + " (AeroDyn15, TwrAero) ... (ServoDyn, GenTiStp) (ServoDyn, GenTiStr) \\\n", + "0 False ... True True \n", + "1 False ... True True \n", + "2 False ... True True \n", + "3 False ... True True \n", + "4 False ... True True \n", + "5 False ... True True \n", + "6 False ... True True \n", + "7 False ... True True \n", + "8 False ... True True \n", + "9 False ... True True \n", + "10 False ... True True \n", + "11 False ... True True \n", + "12 False ... True True \n", + "13 False ... True True \n", + "14 False ... True True \n", + "15 False ... True True \n", + "\n", + " (ServoDyn, HSSBrMode) (ServoDyn, PCMode) (ServoDyn, SpdGenOn) \\\n", + "0 5 5 0.0 \n", + "1 5 5 0.0 \n", + "2 5 5 0.0 \n", + "3 5 5 0.0 \n", + "4 5 5 0.0 \n", + "5 5 5 0.0 \n", + "6 5 5 0.0 \n", + "7 5 5 0.0 \n", + "8 5 5 0.0 \n", + "9 5 5 0.0 \n", + "10 5 5 0.0 \n", + "11 5 5 0.0 \n", + "12 5 5 0.0 \n", + "13 5 5 0.0 \n", + "14 5 5 0.0 \n", + "15 5 5 0.0 \n", + "\n", + " (ServoDyn, TimGenOn) (ServoDyn, VSContrl) (ServoDyn, YCMode) Case_ID \\\n", + "0 0.0 5 5 0 \n", + "1 0.0 5 5 1 \n", + "2 0.0 5 5 2 \n", + "3 0.0 5 5 3 \n", + "4 0.0 5 5 4 \n", + "5 0.0 5 5 5 \n", + "6 0.0 5 5 6 \n", + "7 0.0 5 5 7 \n", + "8 0.0 5 5 8 \n", + "9 0.0 5 5 9 \n", + "10 0.0 5 5 10 \n", + "11 0.0 5 5 11 \n", + "12 0.0 5 5 12 \n", + "13 0.0 5 5 13 \n", + "14 0.0 5 5 14 \n", + "15 0.0 5 5 15 \n", + "\n", + " Case_Name \n", + "0 IEA15MW_PRC_00 \n", + "1 IEA15MW_PRC_01 \n", + "2 IEA15MW_PRC_02 \n", + "3 IEA15MW_PRC_03 \n", + "4 IEA15MW_PRC_04 \n", + "5 IEA15MW_PRC_05 \n", + "6 IEA15MW_PRC_06 \n", + "7 IEA15MW_PRC_07 \n", + "8 IEA15MW_PRC_08 \n", + "9 IEA15MW_PRC_09 \n", + "10 IEA15MW_PRC_10 \n", + "11 IEA15MW_PRC_11 \n", + "12 IEA15MW_PRC_12 \n", + "13 IEA15MW_PRC_13 \n", + "14 IEA15MW_PRC_14 \n", + "15 IEA15MW_PRC_15 \n", + "\n", + "[16 rows x 142 columns]" + ] + }, + "execution_count": 3, + "metadata": {}, + "output_type": "execute_result" + } + ], + "source": [ + "\n", + "fname_case_matrix = '/Users/dzalkind/Tools/ROSCO/outputs/PRC_2/IEA15MW_PRC/power_curve/base/case_matrix.yaml'\n", + "cm_dict = FileTools.load_yaml(fname_case_matrix, package=1)\n", + "cnames = []\n", + "for c in list(cm_dict.keys()):\n", + " if isinstance(c,ry.comments.CommentedKeySeq):\n", + " cnames.append(tuple(c))\n", + " else:\n", + " cnames.append(c)\n", + " \n", + "cm = pd.DataFrame(cm_dict, columns=cnames)\n", + "\n", + "if ('DLC','Label') in cm:\n", + " cm[('DLC','Label')].unique()\n", + "\n", + " dlc_inds = {}\n", + "\n", + " for dlc in cm[('DLC','Label')].unique():\n", + " dlc_inds[dlc] = cm[('DLC','Label')] == dlc\n", + " \n", + "cm" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "#### Project Directory" + ] + }, + { + "cell_type": "code", + "execution_count": 5, + "metadata": {}, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "Found 16 files.\n" + ] + } + ], + "source": [ + "output_dir = \"/Users/dzalkind/Tools/ROSCO/outputs/PRC_2/IEA15MW_PRC/power_curve/base\"\n", + "# results_dir = os.path.join(output_dir, \"results\")\n", + "# save_results = True\n", + "\n", + "# outfiles = [\n", + "# os.path.join(output_dir, f) for f in os.listdir(output_dir)\n", + "# if valid_extension(f)\n", + "# ]\n", + "\n", + "outfiles = [os.path.join(output_dir,f'IEA15MW_PRC_{i:02d}.out') for i in range(len(cm))]\n", + "\n", + "# iea15mw_04.HD\n", + "\n", + "# /projects/esteyco/dzalkind/02_DLC_02_1661_Wide/rank_0/IEA15_00.out\n", + "\n", + "print(f\"Found {len(outfiles)} files.\")" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "#### Interacting with output files" + ] + }, + { + "cell_type": "code", + "execution_count": 37, + "metadata": {}, + "outputs": [], + "source": [ + "# The new framework provides an object oriented framework to interact with\n", + "# output files. The easiest way to use this is to use the 'load_FAST_out' function.\n", + "\n", + "# load_FAST_out(filenames, tmin=0, tmax=np.inf, cores=1, **kwargs)\n", + "# outputs = load_FAST_out(outfiles,tmin=120,cores=12)\n", + "# outputs" + ] + }, + { + "cell_type": "code", + "execution_count": 20, + "metadata": {}, + "outputs": [ + { + "data": { + "text/plain": [ + "array([10.85912037, 10.77266312, 10.68620682, ..., 13.05524254,\n", + " 13.10151958, 13.14779663])" + ] + }, + "execution_count": 20, + "metadata": {}, + "output_type": "execute_result" + } + ], + "source": [ + "# An instance of 'OpenFASTBinary' (or 'OpenFASTAscii' if applicable) is created.\n", + "# The instance stores the raw data but also provides many useful methods for\n", + "# interacting with the data:\n", + "\n", + "# print(outputs[0].data)\n", + "# print(outputs[0].time)\n", + "# print(outputs[0].channels)\n", + "# print(outputs[0].maxima)\n", + "# print(outputs[0].stddevs)\n", + "\n", + "# Individual channel time series can also be accessed with dict style indexing:\n", + "outputs[0][\"Wind1VelX\"]" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "#### pCrunch Configuration" + ] + }, + { + "cell_type": "code", + "execution_count": 6, + "metadata": {}, + "outputs": [], + "source": [ + "# Channel magnitudes are defined in a dict:\n", + "magnitude_channels = {\n", + " \"RootMc1\": [\"RootMxc1\", \"RootMyc1\", \"RootMzc1\"],\n", + " \"RootMc2\": [\"RootMxc2\", \"RootMyc2\", \"RootMzc2\"],\n", + " \"RootMc3\": [\"RootMxc3\", \"RootMyc3\", \"RootMzc3\"],\n", + "}\n", + "\n", + "# Define channels (and their fatigue slopes) in a dict:\n", + "fatigue_channels = {\n", + " \"RootMc1\": FatigueParams(lifetime=25.0, slope=10.0, ult_stress=6e8),\n", + " \"RootMc2\": FatigueParams(lifetime=25.0, slope=10.0, ult_stress=6e8),\n", + " \"RootMc3\": FatigueParams(lifetime=25.0, slope=10.0, ult_stress=6e8),\n", + "}\n", + "\n", + "# Define channels to save extreme data in a list:\n", + "channel_extremes = [\n", + " \"RotSpeed\",\n", + " \"RotThrust\",\n", + " \"RotTorq\",\n", + " \"RootMc1\",\n", + " \"RootMc2\",\n", + " \"RootMc3\",\n", + "]" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "#### Run pCrunch" + ] + }, + { + "cell_type": "code", + "execution_count": 18, + "metadata": {}, + "outputs": [], + "source": [ + "# The API has changed and is in more of an object oriented framework.\n", + "la = LoadsAnalysis(\n", + " outfiles, # The primary input is a list of output files\n", + " magnitude_channels=magnitude_channels, # All of the following inputs are optional\n", + " fatigue_channels=fatigue_channels, # \n", + " extreme_channels=channel_extremes, #\n", + " trim_data=(120,), # If 'trim_data' is passed, all input files will\n", + ") # be trimmed to (tmin, tmax(optional))\n", + "\n", + "la.process_outputs(cores=8) # Once LoadsAnalysis is configured, process outputs with\n", + " # `process_outputs`. `cores` is optional but will trigger parallel processing if configured" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "#### Outputs" + ] + }, + { + "cell_type": "code", + "execution_count": 32, + "metadata": {}, + "outputs": [ + { + "data": { + "text/plain": [ + "[]" + ] + }, + "execution_count": 32, + "metadata": {}, + "output_type": "execute_result" + }, + { + "data": { + "image/png": "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\n", + "text/plain": [ + "
" + ] + }, + "metadata": { + "needs_background": "light" + }, + "output_type": "display_data" + } + ], + "source": [ + "# The summary stats per each file are here:\n", + "ss = la.summary_stats\n", + "\n", + "ss['GenSpeed']['mean']\n", + "\n", + "chans = ['GenSpeed','TSR','BldPitch1']\n", + "\n", + "ss['TSR']\n", + "ss['TSR'] = ss['RotSpeed']['mean'] * 120 / ss['Wind1VelX']['mean'] * rpm2RadSec\n", + "\n", + "fig, axs = plt.subplots(len(chans),1)\n", + "\n", + "fig.set_size_inches(6,2.5*len(chans))\n", + "\n", + "for i_chan, chan in enumerate(chans):\n", + " \n", + " try:\n", + " axs[i_chan].plot(ss['Wind1VelX']['mean'],ss[chan]['mean'])\n", + " except:\n", + " axs[i_chan].plot(ss['Wind1VelX']['mean'],ss[chan])\n", + " \n", + "\n", + "[a.grid(True) for a in axs]\n", + "\n", + "\n", + "M = np.loadtxt('/Users/dzalkind/Downloads/Megablade_35_sr180_GenEff_control_schedule.txt',delimiter=',')\n", + "\n", + "UU = M[:,0]\n", + "\n", + "rot_speed = M[:,1] * rpm2RadSec\n", + "\n", + "rot_speed\n", + "\n", + "min_pitch = np.deg2rad(M[:,2])\n", + "\n", + "min_pitch\n", + "\n", + "ds = 1\n", + "\n", + "# fig, axs = plt.subplots(2,1)\n", + "\n", + "# axs[0].plot(UU,rot_speed)\n", + "axs[0].plot(UU[::ds],rot_speed[::ds]/ rpm2RadSec)\n", + "# axs[1].plot(UU,min_pitch)\n", + "axs[2].plot(UU[::ds],np.rad2deg(min_pitch[::ds]))\n" + ] + }, + { + "cell_type": "code", + "execution_count": 20, + "metadata": {}, + "outputs": [ + { + "ename": "NameError", + "evalue": "name 'dlc_inds' is not defined", + "output_type": "error", + "traceback": [ + "\u001b[0;31m---------------------------------------------------------------------------\u001b[0m", + "\u001b[0;31mNameError\u001b[0m Traceback (most recent call last)", + "\u001b[0;32m\u001b[0m in \u001b[0;36m\u001b[0;34m\u001b[0m\n\u001b[1;32m 6\u001b[0m \u001b[0;32mfor\u001b[0m \u001b[0mdlc\u001b[0m \u001b[0;32min\u001b[0m \u001b[0mdlcs\u001b[0m\u001b[0;34m:\u001b[0m\u001b[0;34m\u001b[0m\u001b[0;34m\u001b[0m\u001b[0m\n\u001b[1;32m 7\u001b[0m \u001b[0;32mfor\u001b[0m \u001b[0mchan\u001b[0m \u001b[0;32min\u001b[0m \u001b[0mchannels\u001b[0m\u001b[0;34m:\u001b[0m\u001b[0;34m\u001b[0m\u001b[0;34m\u001b[0m\u001b[0m\n\u001b[0;32m----> 8\u001b[0;31m \u001b[0mss_max\u001b[0m \u001b[0;34m=\u001b[0m \u001b[0mss\u001b[0m\u001b[0;34m.\u001b[0m\u001b[0mreset_index\u001b[0m\u001b[0;34m(\u001b[0m\u001b[0;34m)\u001b[0m\u001b[0;34m[\u001b[0m\u001b[0mdlc_inds\u001b[0m\u001b[0;34m[\u001b[0m\u001b[0mdlc\u001b[0m\u001b[0;34m]\u001b[0m\u001b[0;34m]\u001b[0m\u001b[0;34m[\u001b[0m\u001b[0mchan\u001b[0m\u001b[0;34m]\u001b[0m\u001b[0;34m[\u001b[0m\u001b[0;34m'max'\u001b[0m\u001b[0;34m]\u001b[0m\u001b[0;34m\u001b[0m\u001b[0;34m\u001b[0m\u001b[0m\n\u001b[0m\u001b[1;32m 9\u001b[0m \u001b[0mss_min\u001b[0m \u001b[0;34m=\u001b[0m \u001b[0mss\u001b[0m\u001b[0;34m.\u001b[0m\u001b[0mreset_index\u001b[0m\u001b[0;34m(\u001b[0m\u001b[0;34m)\u001b[0m\u001b[0;34m[\u001b[0m\u001b[0mdlc_inds\u001b[0m\u001b[0;34m[\u001b[0m\u001b[0mdlc\u001b[0m\u001b[0;34m]\u001b[0m\u001b[0;34m]\u001b[0m\u001b[0;34m[\u001b[0m\u001b[0mchan\u001b[0m\u001b[0;34m]\u001b[0m\u001b[0;34m[\u001b[0m\u001b[0;34m'min'\u001b[0m\u001b[0;34m]\u001b[0m\u001b[0;34m\u001b[0m\u001b[0;34m\u001b[0m\u001b[0m\n\u001b[1;32m 10\u001b[0m \u001b[0mi_max\u001b[0m \u001b[0;34m=\u001b[0m \u001b[0mss_max\u001b[0m\u001b[0;34m.\u001b[0m\u001b[0margmax\u001b[0m\u001b[0;34m(\u001b[0m\u001b[0;34m)\u001b[0m\u001b[0;34m\u001b[0m\u001b[0;34m\u001b[0m\u001b[0m\n", + "\u001b[0;31mNameError\u001b[0m: name 'dlc_inds' is not defined" + ] + } + ], + "source": [ + "dlcs = ['1.6','6.1']\n", + "# dlcs = ['1.1','1.3','1.4','1.5']\n", + "channels = ['GenSpeed','PtfmSurge', 'PtfmSway', 'PtfmHeave', 'PtfmRoll','PtfmPitch','PtfmYaw']\n", + "\n", + "\n", + "for dlc in dlcs:\n", + " for chan in channels:\n", + " ss_max = ss.reset_index()[dlc_inds[dlc]][chan]['max']\n", + " ss_min = ss.reset_index()[dlc_inds[dlc]][chan]['min']\n", + " i_max = ss_max.argmax()\n", + " i_min = ss_min.argmin()\n", + " print(f\"DLC {dlc}: Max {chan} of {ss_max.max():.3f} in {ss.index[ss_max.index[i_max]]}\")\n", + " print(f\"DLC {dlc}: Min {chan} of {ss_min.min():.3f} in {ss.index[ss_min.index[i_min]]}\")" + ] + }, + { + "cell_type": "code", + "execution_count": 27, + "metadata": {}, + "outputs": [ + { + "data": { + "text/plain": [ + "IEA15MW_PRC_00.out 1\n", + "IEA15MW_PRC_01.out 1\n", + "IEA15MW_PRC_02.out 1\n", + "IEA15MW_PRC_03.out 1\n", + "IEA15MW_PRC_04.out 1\n", + "IEA15MW_PRC_05.out 1\n", + "IEA15MW_PRC_06.out 1\n", + "IEA15MW_PRC_07.out 1\n", + "IEA15MW_PRC_08.out 1\n", + "IEA15MW_PRC_09.out 1\n", + "IEA15MW_PRC_10.out 1\n", + "IEA15MW_PRC_11.out 1\n", + "IEA15MW_PRC_12.out 1\n", + "IEA15MW_PRC_13.out 1\n", + "IEA15MW_PRC_14.out 1\n", + "IEA15MW_PRC_15.out 1\n", + "Name: TSR, dtype: int64" + ] + }, + "execution_count": 27, + "metadata": {}, + "output_type": "execute_result" + } + ], + "source": [ + "ss['TSR'] = 1\n", + "\n", + "ss['TSR']" + ] + }, + { + "cell_type": "code", + "execution_count": 74, + "metadata": {}, + "outputs": [], + "source": [ + "la.summary_stats[(\"Wind1VelX\", 'min')]\n", + "\n", + "10.12/7.56\n", + "\n", + "ss.to_pickle(\"/projects/esteyco/dzalkind/02_DLC_02_1661_NoCW/rank_0/ss_12345.p\")" + ] + }, + { + "cell_type": "code", + "execution_count": 27, + "metadata": {}, + "outputs": [ + { + "data": { + "text/plain": [ + "Wind1VelX min 7.331778e+00\n", + "Wind1VelY min -6.869149e+00\n", + "Wind1VelZ min -4.288182e+00\n", + "Azimuth min 7.724802e-04\n", + "BldPitch1 min 6.118227e+00\n", + " ... \n", + "GenPwr integrated -1.709636e+05\n", + "GenTq integrated 0.000000e+00\n", + "RootMc1 integrated 2.066127e+06\n", + "RootMc2 integrated 6.123670e+06\n", + "RootMc3 integrated 5.847567e+06\n", + "Name: BAR10_0_IEC_13.outb, Length: 1104, dtype: float64" + ] + }, + "execution_count": 27, + "metadata": {}, + "output_type": "execute_result" + } + ], + "source": [ + "# Or by file\n", + "la.summary_stats.loc[\"BAR10_0_IEC_13.outb\"]" + ] + }, + { + "cell_type": "code", + "execution_count": 28, + "metadata": {}, + "outputs": [ + { + "data": { + "text/html": [ + "
\n", + "\n", + "\n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + "
RootMc1RootMc2RootMc3
BAR10_0_IEC_13.outb17155.97267218123.88292618975.048930
BAR10_0_IEC_44.outb20769.76053320173.28814820931.456407
BAR10_0_IEC_05.outb12965.95909612840.96246313141.212547
BAR10_0_IEC_29.outb17868.45067617151.79657316319.655247
BAR10_0_IEC_09.outb15761.53147916148.63270616634.678742
\n", + "
" + ], + "text/plain": [ + " RootMc1 RootMc2 RootMc3\n", + "BAR10_0_IEC_13.outb 17155.972672 18123.882926 18975.048930\n", + "BAR10_0_IEC_44.outb 20769.760533 20173.288148 20931.456407\n", + "BAR10_0_IEC_05.outb 12965.959096 12840.962463 13141.212547\n", + "BAR10_0_IEC_29.outb 17868.450676 17151.796573 16319.655247\n", + "BAR10_0_IEC_09.outb 15761.531479 16148.632706 16634.678742" + ] + }, + "execution_count": 28, + "metadata": {}, + "output_type": "execute_result" + } + ], + "source": [ + "# Damage equivalent loads are found here:\n", + "la.DELs" + ] + }, + { + "cell_type": "code", + "execution_count": 31, + "metadata": {}, + "outputs": [ + { + "data": { + "text/plain": [ + "[{'Time': 500.02000000000004,\n", + " 'RotSpeed': 9.196721076965332,\n", + " 'RotThrust': 1832.1434326171875,\n", + " 'RotTorq': 19779.529296875,\n", + " 'RootMc1': 37811.284398457174,\n", + " 'RootMc2': 55838.312057143645,\n", + " 'RootMc3': 50827.68616140148},\n", + " {'Time': 368.26,\n", + " 'RotSpeed': 9.146635055541992,\n", + " 'RotThrust': 1628.4447021484375,\n", + " 'RotTorq': 19790.078125,\n", + " 'RootMc1': 47771.370180076294,\n", + " 'RootMc2': 49087.65189598435,\n", + " 'RootMc3': 48430.43687242791},\n", + " {'Time': 368.72,\n", + " 'RotSpeed': 9.249673843383789,\n", + " 'RotThrust': 2189.477294921875,\n", + " 'RotTorq': 19810.16015625,\n", + " 'RootMc1': 59575.98150937143,\n", + " 'RootMc2': 68240.34957165274,\n", + " 'RootMc3': 52813.63114797467},\n", + " {'Time': 356.36,\n", + " 'RotSpeed': 9.03768539428711,\n", + " 'RotThrust': 1109.2626953125,\n", + " 'RotTorq': 19767.958984375,\n", + " 'RootMc1': 28428.160164204783,\n", + " 'RootMc2': 47520.51453251602,\n", + " 'RootMc3': 26678.213325803477},\n", + " {'Time': 218.85,\n", + " 'RotSpeed': 8.697166442871094,\n", + " 'RotThrust': 1519.8240966796875,\n", + " 'RotTorq': 19807.201171875,\n", + " 'RootMc1': 42921.23490015305,\n", + " 'RootMc2': 26077.389696628106,\n", + " 'RootMc3': 42566.349186912346},\n", + " {'Time': 368.73,\n", + " 'RotSpeed': 8.878805160522461,\n", + " 'RotThrust': 1549.9483642578125,\n", + " 'RotTorq': 19805.7890625,\n", + " 'RootMc1': 31664.332491803867,\n", + " 'RootMc2': 46879.82219401657,\n", + " 'RootMc3': 49487.4606661061},\n", + " {'Time': 519.4,\n", + " 'RotSpeed': 8.663159370422363,\n", + " 'RotThrust': 2036.2601318359375,\n", + " 'RotTorq': 19761.43359375,\n", + " 'RootMc1': 50181.80794211208,\n", + " 'RootMc2': 46826.314080330514,\n", + " 'RootMc3': 49344.15798839514},\n", + " {'Time': 162.29,\n", + " 'RotSpeed': 9.140069961547852,\n", + " 'RotThrust': 1878.1090087890625,\n", + " 'RotTorq': 19773.65234375,\n", + " 'RootMc1': 48787.83397343496,\n", + " 'RootMc2': 52380.788688063425,\n", + " 'RootMc3': 35632.23116383259},\n", + " {'Time': 355.8,\n", + " 'RotSpeed': 9.123079299926758,\n", + " 'RotThrust': 1792.07861328125,\n", + " 'RotTorq': 19774.005859375,\n", + " 'RootMc1': 50532.15050757147,\n", + " 'RootMc2': 43871.60336434941,\n", + " 'RootMc3': 58478.44111155466},\n", + " {'Time': 369.2,\n", + " 'RotSpeed': 9.184767723083496,\n", + " 'RotThrust': 2361.0,\n", + " 'RotTorq': 19795.474609375,\n", + " 'RootMc1': 67171.44060773586,\n", + " 'RootMc2': 64144.0015416387,\n", + " 'RootMc3': 66307.21959893759},\n", + " {'Time': 338.11,\n", + " 'RotSpeed': 9.081233024597168,\n", + " 'RotThrust': 1432.0780029296875,\n", + " 'RotTorq': 19794.19921875,\n", + " 'RootMc1': 44348.38533282857,\n", + " 'RootMc2': 35461.39568142322,\n", + " 'RootMc3': 35720.97401760876},\n", + " {'Time': 309.57,\n", + " 'RotSpeed': 8.808978080749512,\n", + " 'RotThrust': 1784.7720947265625,\n", + " 'RotTorq': 19794.677734375,\n", + " 'RootMc1': 51039.595345969086,\n", + " 'RootMc2': 33415.46799670461,\n", + " 'RootMc3': 49962.997862840064},\n", + " {'Time': 432.16,\n", + " 'RotSpeed': 8.889041900634766,\n", + " 'RotThrust': 1938.8626708984375,\n", + " 'RotTorq': 19759.9765625,\n", + " 'RootMc1': 50439.551159886076,\n", + " 'RootMc2': 59261.815251303284,\n", + " 'RootMc3': 39933.391602874246},\n", + " {'Time': 592.33,\n", + " 'RotSpeed': 9.256232261657715,\n", + " 'RotThrust': 2138.162841796875,\n", + " 'RotTorq': 19770.294921875,\n", + " 'RootMc1': 47760.279101389024,\n", + " 'RootMc2': 56772.73864663361,\n", + " 'RootMc3': 49697.389655866646},\n", + " {'Time': 140.01,\n", + " 'RotSpeed': 8.930659294128418,\n", + " 'RotThrust': 2355.755615234375,\n", + " 'RotTorq': 19798.275390625,\n", + " 'RootMc1': 55682.92431117121,\n", + " 'RootMc2': 54641.07015748553,\n", + " 'RootMc3': 77077.90317607606},\n", + " {'Time': 369.74,\n", + " 'RotSpeed': 10.078149795532227,\n", + " 'RotThrust': 2048.104736328125,\n", + " 'RotTorq': 19784.431640625,\n", + " 'RootMc1': 63686.819849083135,\n", + " 'RootMc2': 62722.78466291298,\n", + " 'RootMc3': 42559.807718172815},\n", + " {'Time': 145.98,\n", + " 'RotSpeed': 9.945197105407715,\n", + " 'RotThrust': 1736.0693359375,\n", + " 'RotTorq': 19766.533203125,\n", + " 'RootMc1': 57107.34525097212,\n", + " 'RootMc2': 20899.90533129373,\n", + " 'RootMc3': 44866.49202475942},\n", + " {'Time': 370.05,\n", + " 'RotSpeed': 9.10218334197998,\n", + " 'RotThrust': 2219.190185546875,\n", + " 'RotTorq': 19780.0625,\n", + " 'RootMc1': 57215.6716968554,\n", + " 'RootMc2': 62357.436171842215,\n", + " 'RootMc3': 61932.423372583435},\n", + " {'Time': 362.19,\n", + " 'RotSpeed': 1.0845158100128174,\n", + " 'RotThrust': -269.979248046875,\n", + " 'RotTorq': 24.871183395385742,\n", + " 'RootMc1': 58010.374504584404,\n", + " 'RootMc2': 73026.87023199385,\n", + " 'RootMc3': 11501.542745264986},\n", + " {'Time': 319.56,\n", + " 'RotSpeed': 2.1253559589385986,\n", + " 'RotThrust': 886.7853393554688,\n", + " 'RotTorq': -47.52824020385742,\n", + " 'RootMc1': 88873.58411735375,\n", + " 'RootMc2': 137240.6447854445,\n", + " 'RootMc3': 92696.27588271046},\n", + " {'Time': 532.14,\n", + " 'RotSpeed': 1.512349009513855,\n", + " 'RotThrust': -536.5031127929688,\n", + " 'RotTorq': -9.38508415222168,\n", + " 'RootMc1': 141657.0715266282,\n", + " 'RootMc2': 202748.90347223374,\n", + " 'RootMc3': 44464.73157894751},\n", + " {'Time': 548.21,\n", + " 'RotSpeed': 2.2312963008880615,\n", + " 'RotThrust': 443.90032958984375,\n", + " 'RotTorq': -3.8658337593078613,\n", + " 'RootMc1': 117455.15330477503,\n", + " 'RootMc2': 138826.02250426452,\n", + " 'RootMc3': 59169.92360525166},\n", + " {'Time': 363.38,\n", + " 'RotSpeed': 0.9708657264709473,\n", + " 'RotThrust': -1625.6156005859375,\n", + " 'RotTorq': -82.18456268310547,\n", + " 'RootMc1': 66760.709080843,\n", + " 'RootMc2': 106385.45271373939,\n", + " 'RootMc3': 92546.23548581263},\n", + " {'Time': 485.56,\n", + " 'RotSpeed': 2.1143946647644043,\n", + " 'RotThrust': 380.2807312011719,\n", + " 'RotTorq': 29.63134002685547,\n", + " 'RootMc1': 140224.03452825797,\n", + " 'RootMc2': 81751.8429490026,\n", + " 'RootMc3': 69690.85356305895},\n", + " {'Time': 580.13,\n", + " 'RotSpeed': 0.7789886593818665,\n", + " 'RotThrust': -1370.467529296875,\n", + " 'RotTorq': -104.5961685180664,\n", + " 'RootMc1': 37763.97319287498,\n", + " 'RootMc2': 70996.03458713405,\n", + " 'RootMc3': 87349.31356127908},\n", + " {'Time': 337.62,\n", + " 'RotSpeed': 2.252070665359497,\n", + " 'RotThrust': 80.88116455078125,\n", + " 'RotTorq': 49.50742721557617,\n", + " 'RootMc1': 102552.94313450111,\n", + " 'RootMc2': 18707.17113997944,\n", + " 'RootMc3': 83043.64130492897},\n", + " {'Time': 285.72,\n", + " 'RotSpeed': 1.4705394506454468,\n", + " 'RotThrust': -406.57525634765625,\n", + " 'RotTorq': 38.92527389526367,\n", + " 'RootMc1': 138110.54053477198,\n", + " 'RootMc2': 169304.80340388033,\n", + " 'RootMc3': 20140.25049010069},\n", + " {'Time': 717.8100000000001,\n", + " 'RotSpeed': 2.0292696952819824,\n", + " 'RotThrust': 411.42730712890625,\n", + " 'RotTorq': 14.589661598205566,\n", + " 'RootMc1': 62275.418866609376,\n", + " 'RootMc2': 147978.99754989002,\n", + " 'RootMc3': 114591.73863847277},\n", + " {'Time': 362.15000000000003,\n", + " 'RotSpeed': 1.5603829622268677,\n", + " 'RotThrust': 383.2719421386719,\n", + " 'RotTorq': -26.811803817749023,\n", + " 'RootMc1': 140662.91704337584,\n", + " 'RootMc2': 145032.08913958006,\n", + " 'RootMc3': 13956.956830886636},\n", + " {'Time': 683.59,\n", + " 'RotSpeed': 2.178495168685913,\n", + " 'RotThrust': 912.2911987304688,\n", + " 'RotTorq': -19.01127815246582,\n", + " 'RootMc1': 147077.7607709096,\n", + " 'RootMc2': 150881.86301316196,\n", + " 'RootMc3': 9552.38511948408},\n", + " {'Time': 371.35,\n", + " 'RotSpeed': 0.8236762285232544,\n", + " 'RotThrust': -972.6253051757812,\n", + " 'RotTorq': 10.888876914978027,\n", + " 'RootMc1': 61334.7989925495,\n", + " 'RootMc2': 73960.80131035403,\n", + " 'RootMc3': 61444.44756566308},\n", + " {'Time': 618.47,\n", + " 'RotSpeed': 2.1806609630584717,\n", + " 'RotThrust': 774.4859008789062,\n", + " 'RotTorq': -72.732666015625,\n", + " 'RootMc1': 56086.918586787964,\n", + " 'RootMc2': 116335.34531937476,\n", + " 'RootMc3': 156844.60812533938},\n", + " {'Time': 120.49000000000001,\n", + " 'RotSpeed': 1.4905682802200317,\n", + " 'RotThrust': -616.0191040039062,\n", + " 'RotTorq': -27.170148849487305,\n", + " 'RootMc1': 101656.89432714453,\n", + " 'RootMc2': 197091.84231484696,\n", + " 'RootMc3': 64010.11036702907},\n", + " {'Time': 502.17,\n", + " 'RotSpeed': 2.140622615814209,\n", + " 'RotThrust': 1057.51123046875,\n", + " 'RotTorq': -17.38741111755371,\n", + " 'RootMc1': 124323.0448939255,\n", + " 'RootMc2': 107238.89330603335,\n", + " 'RootMc3': 65575.35210504149},\n", + " {'Time': 542.19,\n", + " 'RotSpeed': 1.6982858180999756,\n", + " 'RotThrust': -339.0162658691406,\n", + " 'RotTorq': -26.61520767211914,\n", + " 'RootMc1': 139250.58071381506,\n", + " 'RootMc2': 191552.23033279885,\n", + " 'RootMc3': 37391.675248771586},\n", + " {'Time': 445.43,\n", + " 'RotSpeed': 2.012869119644165,\n", + " 'RotThrust': 960.855712890625,\n", + " 'RotTorq': -10.877129554748535,\n", + " 'RootMc1': 76787.92778794201,\n", + " 'RootMc2': 151362.73517860894,\n", + " 'RootMc3': 81804.42068809773},\n", + " {'Time': 363.47,\n", + " 'RotSpeed': 1.694690227508545,\n", + " 'RotThrust': -263.94842529296875,\n", + " 'RotTorq': -25.910903930664062,\n", + " 'RootMc1': 156963.48160764077,\n", + " 'RootMc2': 201551.08178892208,\n", + " 'RootMc3': 30926.970226574063},\n", + " {'Time': 641.34,\n", + " 'RotSpeed': 2.2814862728118896,\n", + " 'RotThrust': 653.01904296875,\n", + " 'RotTorq': 8.365302085876465,\n", + " 'RootMc1': 73873.17661947786,\n", + " 'RootMc2': 115032.19736012808,\n", + " 'RootMc3': 47605.537551260524},\n", + " {'Time': 220.67000000000002,\n", + " 'RotSpeed': 1.4255976676940918,\n", + " 'RotThrust': -37.78099822998047,\n", + " 'RotTorq': -70.7003402709961,\n", + " 'RootMc1': 86367.87757851247,\n", + " 'RootMc2': 159911.237938548,\n", + " 'RootMc3': 44026.22219167016},\n", + " {'Time': 322.40000000000003,\n", + " 'RotSpeed': 2.4135708808898926,\n", + " 'RotThrust': 1031.006103515625,\n", + " 'RotTorq': 3.167031764984131,\n", + " 'RootMc1': 117889.61765603493,\n", + " 'RootMc2': 93103.18101157891,\n", + " 'RootMc3': 176108.7206103024},\n", + " {'Time': 361.51,\n", + " 'RotSpeed': 1.502587080001831,\n", + " 'RotThrust': 201.8974151611328,\n", + " 'RotTorq': -3.726184368133545,\n", + " 'RootMc1': 144257.25669438674,\n", + " 'RootMc2': 158737.3617287686,\n", + " 'RootMc3': 29712.876836581345},\n", + " {'Time': 230.48000000000002,\n", + " 'RotSpeed': 2.0762851238250732,\n", + " 'RotThrust': 616.7235717773438,\n", + " 'RotTorq': 13.007423400878906,\n", + " 'RootMc1': 85186.64284667293,\n", + " 'RootMc2': 60036.467439487365,\n", + " 'RootMc3': 120489.81542490129},\n", + " {'Time': 360.99,\n", + " 'RotSpeed': 0.9616844058036804,\n", + " 'RotThrust': -1982.93603515625,\n", + " 'RotTorq': -81.02360534667969,\n", + " 'RootMc1': 59232.840667935176,\n", + " 'RootMc2': 78363.49722922806,\n", + " 'RootMc3': 107098.33420801},\n", + " {'Time': 611.25,\n", + " 'RotSpeed': 2.174319267272949,\n", + " 'RotThrust': 260.4977111816406,\n", + " 'RotTorq': -55.35261535644531,\n", + " 'RootMc1': 79280.41142281189,\n", + " 'RootMc2': 134543.36444773452,\n", + " 'RootMc3': 52657.85305474285},\n", + " {'Time': 361.63,\n", + " 'RotSpeed': 1.5833404064178467,\n", + " 'RotThrust': 74.41678619384766,\n", + " 'RotTorq': -1.6260857582092285,\n", + " 'RootMc1': 149049.1875939595,\n", + " 'RootMc2': 162782.64032074402,\n", + " 'RootMc3': 6944.901395886403},\n", + " {'Time': 179.27,\n", + " 'RotSpeed': 2.2349133491516113,\n", + " 'RotThrust': -637.0066528320312,\n", + " 'RotTorq': 26.083894729614258,\n", + " 'RootMc1': 68581.21306145628,\n", + " 'RootMc2': 67944.18234472333,\n", + " 'RootMc3': 79204.42921220326},\n", + " {'Time': 404.95,\n", + " 'RotSpeed': 1.5384154319763184,\n", + " 'RotThrust': -563.662353515625,\n", + " 'RotTorq': 40.3087043762207,\n", + " 'RootMc1': 85467.41996643576,\n", + " 'RootMc2': 180404.66875909013,\n", + " 'RootMc3': 70676.94690953195},\n", + " {'Time': 328.27,\n", + " 'RotSpeed': 1.944204568862915,\n", + " 'RotThrust': 399.10626220703125,\n", + " 'RotTorq': 20.774803161621094,\n", + " 'RootMc1': 49517.814015380696,\n", + " 'RootMc2': 115720.86150516325,\n", + " 'RootMc3': 99227.4960413297},\n", + " {'Time': 149.69,\n", + " 'RotSpeed': 1.5412728786468506,\n", + " 'RotThrust': -666.01953125,\n", + " 'RotTorq': 9.556767463684082,\n", + " 'RootMc1': 93277.69348175765,\n", + " 'RootMc2': 216225.14492550617,\n", + " 'RootMc3': 80878.64989207157},\n", + " {'Time': 599.0500000000001,\n", + " 'RotSpeed': 2.1643471717834473,\n", + " 'RotThrust': 1036.2357177734375,\n", + " 'RotTorq': -21.235111236572266,\n", + " 'RootMc1': 122089.35121634079,\n", + " 'RootMc2': 64029.00067137171,\n", + " 'RootMc3': 128470.74237645337},\n", + " {'Time': 539.88,\n", + " 'RotSpeed': 1.6076937913894653,\n", + " 'RotThrust': -771.647705078125,\n", + " 'RotTorq': -2.1965253353118896,\n", + " 'RootMc1': 137707.8663385115,\n", + " 'RootMc2': 207889.32578990934,\n", + " 'RootMc3': 46489.91055183886},\n", + " {'Time': 352.39,\n", + " 'RotSpeed': 2.3288607597351074,\n", + " 'RotThrust': 395.71697998046875,\n", + " 'RotTorq': 30.873764038085938,\n", + " 'RootMc1': 136270.11608488843,\n", + " 'RootMc2': 67387.69824493826,\n", + " 'RootMc3': 187807.69514581264},\n", + " {'Time': 375.34000000000003,\n", + " 'RotSpeed': 0.8010825514793396,\n", + " 'RotThrust': -243.02584838867188,\n", + " 'RotTorq': -0.4656263589859009,\n", + " 'RootMc1': 36891.37271612412,\n", + " 'RootMc2': 55038.42409595816,\n", + " 'RootMc3': 31419.79685091404},\n", + " {'Time': 510.97,\n", + " 'RotSpeed': 2.042186737060547,\n", + " 'RotThrust': 608.8619995117188,\n", + " 'RotTorq': -51.640777587890625,\n", + " 'RootMc1': 110874.1808363096,\n", + " 'RootMc2': 48979.6837848612,\n", + " 'RootMc3': 110748.08654790567}]" + ] + }, + "execution_count": 31, + "metadata": {}, + "output_type": "execute_result" + } + ], + "source": [ + "# Extreme events:\n", + "la.extreme_events['RotSpeed']" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [] + } + ], + "metadata": { + "kernelspec": { + "display_name": "weis-env4", + "language": "python", + "name": "weis-env4" + }, + "language_info": { + "codemirror_mode": { + "name": "ipython", + "version": 3 + }, + "file_extension": ".py", + "mimetype": "text/x-python", + "name": "python", + "nbconvert_exporter": "python", + "pygments_lexer": "ipython3", + "version": "3.8.10" + } + }, + "nbformat": 4, + "nbformat_minor": 4 +} From 34ca985eff7f418e03675038c92e2668f6ae6057 Mon Sep 17 00:00:00 2001 From: dzalkind Date: Wed, 14 Sep 2022 09:34:20 -0600 Subject: [PATCH 005/224] Update discons --- Test_Cases/BAR_10/BAR_10_DISCON.IN | 14 ++++++++++---- .../IEA-15-240-RWT-UMaineSemi/DISCON-UMaineSemi.IN | 14 ++++++++++---- Test_Cases/NREL-5MW/DISCON.IN | 14 ++++++++++---- 3 files changed, 30 insertions(+), 12 deletions(-) diff --git a/Test_Cases/BAR_10/BAR_10_DISCON.IN b/Test_Cases/BAR_10/BAR_10_DISCON.IN index a2d09fa1..a34da036 100644 --- a/Test_Cases/BAR_10/BAR_10_DISCON.IN +++ b/Test_Cases/BAR_10/BAR_10_DISCON.IN @@ -1,5 +1,5 @@ ! Controller parameter input file for the BAR_10 wind turbine -! - File written using ROSCO version 2.5.0 controller tuning logic on 07/22/22 +! - File written using ROSCO version 2.6.0 controller tuning logic on 09/14/22 !------- DEBUG ------------------------------------------------------------ 1 ! LoggingLevel - {0: write no debug files, 1: write standard output .dbg-file, 2: LoggingLevel 1 + ROSCO LocalVars (.dbg2) 3: LoggingLevel 2 + complete avrSWAP-array (.dbg3)} @@ -12,6 +12,7 @@ 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} +0 ! PRC_Mode - Power reference tracking mode{0: use standard rotor speed set points, 1: use PRC rotor speed setpoints} 2 ! WE_Mode - Wind speed estimator mode {0: One-second low pass filtered hub height wind speed, 1: Immersion and Invariance Estimator, 2: Extended Kalman Filter} 1 ! PS_Mode - Pitch saturation mode {0: no pitch saturation, 1: implement pitch saturation} 0 ! SD_Mode - Shutdown mode {0: no shutdown procedure, 1: pitch to max pitch at shutdown} @@ -78,6 +79,11 @@ 1.00000 ! SS_VSGain - Variable speed torque controller setpoint smoother gain, [-]. 0.00100 ! SS_PCGain - Collective pitch controller setpoint smoother gain, [-]. +!------- POWER REFERENCE TRACKING -------------------------------------- +2 ! PRC_n - Number of elements in PRC_WindSpeeds and PRC_RotorSpeeds array +3.000 25.000 ! PRC_WindSpeeds - Array of wind speeds used in rotor speed vs. wind speed lookup table [m/s]. +0.792 0.792 ! PRC_RotorSpeeds - Array of rotor speeds corresponding to PRC_WindSpeeds [rad/s]. + !------- WIND SPEED ESTIMATOR --------------------------------------------- 102.996 ! WE_BladeRadius - Blade length (distance from hub center to blade tip), [m] 1 ! WE_CP_n - Amount of parameters in the Cp array @@ -94,7 +100,7 @@ !------- YAW CONTROL ------------------------------------------------------ 0.00000 ! Y_uSwitch - Wind speed to switch between Y_ErrThresh. If zero, only the first value of Y_ErrThresh is used [m/s] -4.000000 8.000000 ! Y_ErrThresh - Yaw error threshold. Turbine begins to yaw when it passes this. If Y_uSwitch is zero, only the first value is used. [deg]. +4.000000 8.000000 ! Y_ErrThresh - Yaw error threshold/deadband. Turbine begins to yaw when it passes this. If Y_uSwitch is zero, only the first value is used. [deg]. 0.00870 ! Y_Rate - Yaw rate [rad/s] 0.00000 ! Y_MErrSet - Integrator saturation (maximum signal amplitude contribution to pitch from yaw-by-IPC), [rad] 0.00000 ! Y_IPC_IntSat - Integrator saturation (maximum signal amplitude contribution to pitch from yaw-by-IPC), [rad] @@ -108,8 +114,8 @@ !------- MINIMUM PITCH SATURATION ------------------------------------------- 60 ! PS_BldPitchMin_N - Number of values in minimum blade pitch lookup table (should equal number of values in PS_WindSpeeds and PS_BldPitchMin) -3.0000 3.1818 3.3637 3.5455 3.7274 3.9092 4.0911 4.2729 4.4548 4.6366 4.8185 5.0003 5.1822 5.3640 5.5459 5.7277 5.9096 6.0914 6.2732 6.4551 6.6369 6.8188 7.0006 7.1825 7.3643 7.5462 7.7280 7.9099 8.0917 8.2736 8.8311 9.3887 9.9462 10.5038 11.0613 11.6188 12.1764 12.7339 13.2915 13.8490 14.4066 14.9641 15.5217 16.0792 16.6368 17.1943 17.7519 18.3094 18.8670 19.4245 19.9821 20.5396 21.0972 21.6547 22.2123 22.7698 23.3274 23.8849 24.4425 25.0000 ! PS_WindSpeeds - Wind speeds corresponding to minimum blade pitch angles [m/s] --0.01505486 -0.01505486 -0.01505486 -0.01505486 -0.01505486 -0.01505486 -0.01505486 -0.01505486 -0.01505486 -0.01505486 -0.01505486 -0.01505486 -0.01505486 -0.01505486 -0.01505486 -0.01505486 -0.01505486 -0.01505486 -0.01505486 -0.01505486 -0.01505486 -0.01505486 -0.01505486 -0.01505486 -0.01247538 0.00009416 0.01064594 0.02025612 0.02875892 0.04130468 0.05575026 0.06941162 0.08245994 0.09516301 0.10759186 0.11974680 0.13166674 0.14343508 0.15503135 0.16644975 0.17776272 0.18893241 0.19997037 0.21092550 0.22173526 0.23245676 0.24309225 0.25359679 0.26404201 0.27436979 0.28461736 0.29478565 0.30484212 0.31485020 0.32473305 0.33456481 0.34429551 0.35395031 0.36352600 0.37300643 ! PS_BldPitchMin - Minimum blade pitch angles [rad] +3.000 3.182 3.364 3.546 3.727 3.909 4.091 4.273 4.455 4.637 4.818 5.000 5.182 5.364 5.546 5.728 5.910 6.091 6.273 6.455 6.637 6.819 7.001 7.182 7.364 7.546 7.728 7.910 8.092 8.274 8.831 9.389 9.946 10.504 11.061 11.619 12.176 12.734 13.291 13.849 14.407 14.964 15.522 16.079 16.637 17.194 17.752 18.309 18.867 19.425 19.982 20.540 21.097 21.655 22.212 22.770 23.327 23.885 24.442 25.000 ! PS_WindSpeeds - Wind speeds corresponding to minimum blade pitch angles [m/s] +-0.015 -0.015 -0.015 -0.015 -0.015 -0.015 -0.015 -0.015 -0.015 -0.015 -0.015 -0.015 -0.015 -0.015 -0.015 -0.015 -0.015 -0.015 -0.015 -0.015 -0.015 -0.015 -0.015 -0.015 -0.012 0.000 0.011 0.020 0.029 0.041 0.056 0.069 0.082 0.095 0.108 0.120 0.132 0.143 0.155 0.166 0.178 0.189 0.200 0.211 0.222 0.232 0.243 0.254 0.264 0.274 0.285 0.295 0.305 0.315 0.325 0.335 0.344 0.354 0.364 0.373 ! PS_BldPitchMin - Minimum blade pitch angles [rad] !------- SHUTDOWN ----------------------------------------------------------- 0.698100000000 ! SD_MaxPit - Maximum blade pitch angle to initiate shutdown, [rad] diff --git a/Test_Cases/IEA-15-240-RWT-UMaineSemi/DISCON-UMaineSemi.IN b/Test_Cases/IEA-15-240-RWT-UMaineSemi/DISCON-UMaineSemi.IN index 3745fee9..e87d61b5 100644 --- a/Test_Cases/IEA-15-240-RWT-UMaineSemi/DISCON-UMaineSemi.IN +++ b/Test_Cases/IEA-15-240-RWT-UMaineSemi/DISCON-UMaineSemi.IN @@ -1,5 +1,5 @@ ! Controller parameter input file for the IEA-15-240-RWT-UMaineSemi wind turbine -! - File written using ROSCO version 2.5.0 controller tuning logic on 07/22/22 +! - File written using ROSCO version 2.6.0 controller tuning logic on 09/14/22 !------- DEBUG ------------------------------------------------------------ 2 ! LoggingLevel - {0: write no debug files, 1: write standard output .dbg-file, 2: LoggingLevel 1 + ROSCO LocalVars (.dbg2) 3: LoggingLevel 2 + complete avrSWAP-array (.dbg3)} @@ -12,6 +12,7 @@ 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} +0 ! PRC_Mode - Power reference tracking mode{0: use standard rotor speed set points, 1: use PRC rotor speed setpoints} 2 ! WE_Mode - Wind speed estimator mode {0: One-second low pass filtered hub height wind speed, 1: Immersion and Invariance Estimator, 2: Extended Kalman Filter} 1 ! PS_Mode - Pitch saturation mode {0: no pitch saturation, 1: implement pitch saturation} 0 ! SD_Mode - Shutdown mode {0: no shutdown procedure, 1: pitch to max pitch at shutdown} @@ -78,6 +79,11 @@ 1.00000 ! SS_VSGain - Variable speed torque controller setpoint smoother gain, [-]. 0.00100 ! SS_PCGain - Collective pitch controller setpoint smoother gain, [-]. +!------- POWER REFERENCE TRACKING -------------------------------------- +2 ! PRC_n - Number of elements in PRC_WindSpeeds and PRC_RotorSpeeds array +3.000 25.000 ! PRC_WindSpeeds - Array of wind speeds used in rotor speed vs. wind speed lookup table [m/s]. +0.792 0.792 ! PRC_RotorSpeeds - Array of rotor speeds corresponding to PRC_WindSpeeds [rad/s]. + !------- WIND SPEED ESTIMATOR --------------------------------------------- 120.000 ! WE_BladeRadius - Blade length (distance from hub center to blade tip), [m] 1 ! WE_CP_n - Amount of parameters in the Cp array @@ -94,7 +100,7 @@ !------- YAW CONTROL ------------------------------------------------------ 0.00000 ! Y_uSwitch - Wind speed to switch between Y_ErrThresh. If zero, only the first value of Y_ErrThresh is used [m/s] -4.000000 8.000000 ! Y_ErrThresh - Yaw error threshold. Turbine begins to yaw when it passes this. If Y_uSwitch is zero, only the first value is used. [deg]. +4.000000 8.000000 ! Y_ErrThresh - Yaw error threshold/deadband. Turbine begins to yaw when it passes this. If Y_uSwitch is zero, only the first value is used. [deg]. 0.00870 ! Y_Rate - Yaw rate [rad/s] 0.00000 ! Y_MErrSet - Integrator saturation (maximum signal amplitude contribution to pitch from yaw-by-IPC), [rad] 0.00000 ! Y_IPC_IntSat - Integrator saturation (maximum signal amplitude contribution to pitch from yaw-by-IPC), [rad] @@ -108,8 +114,8 @@ !------- MINIMUM PITCH SATURATION ------------------------------------------- 60 ! PS_BldPitchMin_N - Number of values in minimum blade pitch lookup table (should equal number of values in PS_WindSpeeds and PS_BldPitchMin) -3.0000 3.2669 3.5338 3.8007 4.0676 4.3345 4.6014 4.8683 5.1352 5.4021 5.6690 5.9359 6.2028 6.4697 6.7366 7.0034 7.2703 7.5372 7.8041 8.0710 8.3379 8.6048 8.8717 9.1386 9.4055 9.6724 9.9393 10.2062 10.4731 10.7400 11.2153 11.6907 12.1660 12.6413 13.1167 13.5920 14.0673 14.5427 15.0180 15.4933 15.9687 16.4440 16.9193 17.3947 17.8700 18.3453 18.8207 19.2960 19.7713 20.2467 20.7220 21.1973 21.6727 22.1480 22.6233 23.0987 23.5740 24.0493 24.5247 25.0000 ! PS_WindSpeeds - Wind speeds corresponding to minimum blade pitch angles [m/s] -0.05997374 0.05997374 0.05997374 0.05997374 0.05997374 0.05995230 0.05568017 0.05139305 0.04630957 0.04053154 0.03444871 0.02774193 0.02083682 0.01377992 0.00660717 0.00000000 0.00000000 0.00000000 0.00000000 0.00000000 0.00000000 0.00000000 0.00000000 0.00000000 0.00000000 0.00798358 0.02222567 0.03475505 0.04563791 0.05328450 0.06405592 0.07436594 0.08427713 0.09385932 0.10323575 0.11234777 0.12134295 0.13011531 0.13881511 0.14732690 0.15578898 0.16409463 0.17235500 0.18049466 0.18858365 0.19658691 0.20452181 0.21241204 0.22021131 0.22800500 0.23567545 0.24336643 0.25094186 0.25851588 0.26602564 0.27348266 0.28093357 0.28828297 0.29566389 0.30293290 ! PS_BldPitchMin - Minimum blade pitch angles [rad] +3.000 3.267 3.534 3.801 4.068 4.334 4.601 4.868 5.135 5.402 5.669 5.936 6.203 6.470 6.737 7.003 7.270 7.537 7.804 8.071 8.338 8.605 8.872 9.139 9.406 9.672 9.939 10.206 10.473 10.740 11.215 11.691 12.166 12.641 13.117 13.592 14.067 14.543 15.018 15.493 15.969 16.444 16.919 17.395 17.870 18.345 18.821 19.296 19.771 20.247 20.722 21.197 21.673 22.148 22.623 23.099 23.574 24.049 24.525 25.000 ! PS_WindSpeeds - Wind speeds corresponding to minimum blade pitch angles [m/s] +0.060 0.060 0.060 0.060 0.060 0.060 0.056 0.051 0.046 0.041 0.034 0.028 0.021 0.014 0.007 0.000 0.000 0.000 0.000 0.000 0.000 0.000 0.000 0.000 0.000 0.008 0.022 0.035 0.046 0.053 0.064 0.074 0.084 0.094 0.103 0.112 0.121 0.130 0.139 0.147 0.156 0.164 0.172 0.180 0.189 0.197 0.205 0.212 0.220 0.228 0.236 0.243 0.251 0.259 0.266 0.273 0.281 0.288 0.296 0.303 ! PS_BldPitchMin - Minimum blade pitch angles [rad] !------- SHUTDOWN ----------------------------------------------------------- 0.698100000000 ! SD_MaxPit - Maximum blade pitch angle to initiate shutdown, [rad] diff --git a/Test_Cases/NREL-5MW/DISCON.IN b/Test_Cases/NREL-5MW/DISCON.IN index b5a353ae..b9c03e84 100644 --- a/Test_Cases/NREL-5MW/DISCON.IN +++ b/Test_Cases/NREL-5MW/DISCON.IN @@ -1,5 +1,5 @@ ! Controller parameter input file for the NREL-5MW wind turbine -! - File written using ROSCO version 2.5.0 controller tuning logic on 07/22/22 +! - File written using ROSCO version 2.6.0 controller tuning logic on 09/14/22 !------- DEBUG ------------------------------------------------------------ 1 ! LoggingLevel - {0: write no debug files, 1: write standard output .dbg-file, 2: LoggingLevel 1 + ROSCO LocalVars (.dbg2) 3: LoggingLevel 2 + complete avrSWAP-array (.dbg3)} @@ -12,6 +12,7 @@ 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} +0 ! PRC_Mode - Power reference tracking mode{0: use standard rotor speed set points, 1: use PRC rotor speed setpoints} 2 ! WE_Mode - Wind speed estimator mode {0: One-second low pass filtered hub height wind speed, 1: Immersion and Invariance Estimator, 2: Extended Kalman Filter} 1 ! PS_Mode - Pitch saturation mode {0: no pitch saturation, 1: implement pitch saturation} 0 ! SD_Mode - Shutdown mode {0: no shutdown procedure, 1: pitch to max pitch at shutdown} @@ -78,6 +79,11 @@ 1.00000 ! SS_VSGain - Variable speed torque controller setpoint smoother gain, [-]. 0.00100 ! SS_PCGain - Collective pitch controller setpoint smoother gain, [-]. +!------- POWER REFERENCE TRACKING -------------------------------------- +2 ! PRC_n - Number of elements in PRC_WindSpeeds and PRC_RotorSpeeds array +3.000 25.000 ! PRC_WindSpeeds - Array of wind speeds used in rotor speed vs. wind speed lookup table [m/s]. +0.792 0.792 ! PRC_RotorSpeeds - Array of rotor speeds corresponding to PRC_WindSpeeds [rad/s]. + !------- WIND SPEED ESTIMATOR --------------------------------------------- 63.000 ! WE_BladeRadius - Blade length (distance from hub center to blade tip), [m] 1 ! WE_CP_n - Amount of parameters in the Cp array @@ -94,7 +100,7 @@ !------- YAW CONTROL ------------------------------------------------------ 0.00000 ! Y_uSwitch - Wind speed to switch between Y_ErrThresh. If zero, only the first value of Y_ErrThresh is used [m/s] -4.000000 8.000000 ! Y_ErrThresh - Yaw error threshold. Turbine begins to yaw when it passes this. If Y_uSwitch is zero, only the first value is used. [deg]. +4.000000 8.000000 ! Y_ErrThresh - Yaw error threshold/deadband. Turbine begins to yaw when it passes this. If Y_uSwitch is zero, only the first value is used. [deg]. 0.00870 ! Y_Rate - Yaw rate [rad/s] 0.00000 ! Y_MErrSet - Integrator saturation (maximum signal amplitude contribution to pitch from yaw-by-IPC), [rad] 0.00000 ! Y_IPC_IntSat - Integrator saturation (maximum signal amplitude contribution to pitch from yaw-by-IPC), [rad] @@ -108,8 +114,8 @@ !------- MINIMUM PITCH SATURATION ------------------------------------------- 60 ! PS_BldPitchMin_N - Number of values in minimum blade pitch lookup table (should equal number of values in PS_WindSpeeds and PS_BldPitchMin) -3.0000 3.2897 3.5793 3.8690 4.1586 4.4483 4.7379 5.0276 5.3172 5.6069 5.8966 6.1862 6.4759 6.7655 7.0552 7.3448 7.6345 7.9241 8.2138 8.5034 8.7931 9.0828 9.3724 9.6621 9.9517 10.2414 10.5310 10.8207 11.1103 11.4000 11.8533 12.3067 12.7600 13.2133 13.6667 14.1200 14.5733 15.0267 15.4800 15.9333 16.3867 16.8400 17.2933 17.7467 18.2000 18.6533 19.1067 19.5600 20.0133 20.4667 20.9200 21.3733 21.8267 22.2800 22.7333 23.1867 23.6400 24.0933 24.5467 25.0000 ! PS_WindSpeeds - Wind speeds corresponding to minimum blade pitch angles [m/s] -0.00088027 0.00088027 0.00088027 0.00088027 0.00088027 0.00088027 0.00088027 0.00088027 0.00088027 0.00088027 0.00088027 0.00088027 0.00088027 0.00088027 0.00088027 0.00088027 0.00088027 0.00088027 0.00088027 0.00088027 0.00088027 0.00088027 0.00088027 0.00088027 0.00088027 0.01116187 0.02310060 0.03164156 0.03968639 0.04741131 0.05899071 0.07019329 0.08090119 0.09141661 0.10169361 0.11174124 0.12170066 0.13137494 0.14103377 0.15048120 0.15989580 0.16913227 0.17831010 0.18739638 0.19643591 0.20537011 0.21419674 0.22293719 0.23161365 0.24025975 0.24885012 0.25735704 0.26578040 0.27407178 0.28233051 0.29047594 0.29867838 0.30674517 0.31490089 0.32284411 ! PS_BldPitchMin - Minimum blade pitch angles [rad] +3.000 3.290 3.579 3.869 4.159 4.448 4.738 5.028 5.317 5.607 5.897 6.186 6.476 6.766 7.055 7.345 7.634 7.924 8.214 8.503 8.793 9.083 9.372 9.662 9.952 10.241 10.531 10.821 11.110 11.400 11.853 12.307 12.760 13.213 13.667 14.120 14.573 15.027 15.480 15.933 16.387 16.840 17.293 17.747 18.200 18.653 19.107 19.560 20.013 20.467 20.920 21.373 21.827 22.280 22.733 23.187 23.640 24.093 24.547 25.000 ! PS_WindSpeeds - Wind speeds corresponding to minimum blade pitch angles [m/s] +0.001 0.001 0.001 0.001 0.001 0.001 0.001 0.001 0.001 0.001 0.001 0.001 0.001 0.001 0.001 0.001 0.001 0.001 0.001 0.001 0.001 0.001 0.001 0.001 0.001 0.011 0.023 0.032 0.040 0.047 0.059 0.070 0.081 0.091 0.102 0.112 0.122 0.131 0.141 0.150 0.160 0.169 0.178 0.187 0.196 0.205 0.214 0.223 0.232 0.240 0.249 0.257 0.266 0.274 0.282 0.290 0.299 0.307 0.315 0.323 ! PS_BldPitchMin - Minimum blade pitch angles [rad] !------- SHUTDOWN ----------------------------------------------------------- 0.436300000000 ! SD_MaxPit - Maximum blade pitch angle to initiate shutdown, [rad] From 2efac8480c186fb3d91083f52cc1c8201030fad6 Mon Sep 17 00:00:00 2001 From: Mayank Chetan <4620557+mayankchetan@users.noreply.github.com> Date: Mon, 26 Sep 2022 16:31:19 -0500 Subject: [PATCH 006/224] Adding pitch actuator fault (#163) * FOCAL Updates (#64) * Update headers * fix bullets * make uppercase * Update turbine.py (#56) * Update turbine.py This add several lines for fixing the problem of repeated maximum values in the performance tables. This will cause the error (' the length of x and y is different.') of 'interpolate.interp1d.' * Add comments and catch when there are multiple optimal pitch angles Co-authored-by: dzalkind * increment version * Update for OpenFAST v3.0.0 * Update for OpenFAST v3.0.0 * Install OF3.0.0 for tests * update for OF v3.0.0 * add publish to pypi on release * Update to ROSCO v2.3.0 * Update Testing (#58) * Update scripts to run on eagle * Update IEA-15MW semi example: use peak shaving w/ ps_percen=0.8 * Add comparison plots to testing scripts * Update submit script for testing * Update for latest eagle runs * Add future to install dependencies * add TMax to self, define tmin in print_results * run tests in CI * generic ROSCO path * default to overwrite * fix path * import platform * separate run_testing * cleanup, specify lite test * don't run testing in after examples, oops. Co-authored-by: nikhar-abbas <40865984+nikhar-abbas@users.noreply.github.com> Co-authored-by: Nikhar Abbas * increment version * Update for OpenFAST v3.0.0 * Install OF3.0.0 for tests * update for OF v3.0.0 * add publish to pypi on release * Update to ROSCO v2.3.0 * Increment Version, OF3.0 (#57) * increment version * Update for OpenFAST v3.0.0 * Install OF3.0.0 for tests * update for OF v3.0.0 * add publish to pypi on release * Update to ROSCO v2.3.0 * increment version * Update for OpenFAST v3.0.0 * Install OF3.0.0 for tests * update for OF v3.0.0 * add publish to pypi on release * Update to ROSCO v2.3.0 * add ROSCO without submodule * move ROSCO source to ROSCO folder * Move cmake-related files to ROSCO * Add back pesky ErrVar * Remove parameters_files * Merge ROSCO and _toolbox gitignore * Fix .gitignore * Remove Examples/DISCON.IN from git * Fix and point example_01 to Tune_Cases/ * Update verbiage around using ofTools vs. weis * Fix and point example_04 to Tune_Cases/ * Clean up example_06 * Clean up example_07 * Only check FlpCornerFreq if using Flp control, fixes example 05 * Make example_04 consistent with others * Let example_05 run independently from 04 * Clean up example_05, wind files * Add schema and update empty tuning yaml inputs, not connected yet * Integrate schema into turbine, controller, and examples * Only check Fl filter parameters if Fl_Mode > 0, fix example_05 * bump version to 2.3 * Compile ROSCO from ROSCO dir * Rename to CI_rosco * Add omega vs. windspeed functionality * Fix tests: 5MW U_pc and 06 example dir * Make _Toolbox vs_minspeed in rotor frame to match ROSCO * Revert ServoDyn change * change rotor speed constraint to be epsilon * rename for clarity * docs major refresh * fix FA_AccF units in debug file * docs that build locally * Deallocate arrays in ROSCO, check in example_05 * Clean up comments * remove gitmodules * furo theme * furo in requirements * move readthedocs config file, remove furo import in conf.py * add docs requirements file * typo * move index out of source folder * trying to get furo to work * import date * fix versions and titles, cleanup readthedocs requirements * typo fix, remove extras * more cleanup * bump version * no furo extension, "hack" to load RT version * proper toctree paths * specify method * add mock modules * fix typos * update python install requirements * running locally * move index to main docs dir again * update to build locally * error during warnings * automated version * cleanup * remove old docs * re-add docs * simplify * fix figure path * try alabaster * remove archived docs * Add omega vs. windspeed functionality * Fix tests: 5MW U_pc and 06 example dir * more detailed sp.optimize settings * run MBC3 in parallel * restructure driver, run initialization doe for tuning * Try new dlclose function * Update example_05 to run simple simulation twice and check result * Revert deallocation stuff * Close discon library after every sim run * Test examples on macOS and windows * Run examples instead of testing on other platforms * Skip examples in windows for now * update paths and yaml load funciton * Skip mac testing of examples * provide default U_pc for single omega/zeta case * allow for float or list-like pc tuning inputs * Change name in setup.py * WE_Vw unit fix * Pass through kp_float, if desired * Minor fixes: schema error and InputReader defaults * cleeanup for improved stability * check for doe_logs as string in load_DOE * major restructure for rsched_driver class * cleanup verbosity * run serial by default * load_parallel as linturb_option * specific IEA15MW yaml for multi omega * remove unused module imports * fix error message types * lin_file as input * add comments on inputs to LinearTurbineModel init method * remove relative file paths * provide OpenFAST linearizations for IEA15MW UMaineSemi * put plotting in specific function * fix WE_lambda units * add self in on a few necessary variables * creaete example 12 for robust scheduling * try a few mbc3 locations for import * allow list-like or numpy arrays for omega_pc and zeta_pc schedules * create and use recorder setup function * Pass Through Kp_float (#57) * Pass through kp_float, if desired * Minor fixes: schema error and InputReader defaults * fix setup_recorder to work for optimization driver too * Allow pass through of Kp_float = 0 * cleanup om problems, update om0 calc * doe levels as input * negative k_float to account for OF conventions * cleanup print statements * variable name cleanup, use calculated k_float * Add defaults to omega_,zeta_ pc and vs, allow to be numbers * use standard tuning k_float as IC * formatting update * update problem setup methods * cleanup add_dv, enable adding design variables after problem is setup * change optimization step size * more setup restructure * update verbosity * use sphinx-rtd-theme * master doc and sphinx rtd theme * index back to root folder * only ignore install folders * remove hidden toctree * furo theme * update paths * convert rt version to string * update sphinx settings * move conf * furo theme * Mostly a docs update (#61) * rename for clarity * docs major refresh * fix FA_AccF units in debug file * docs that build locally * remove gitmodules * furo theme * furo in requirements * move readthedocs config file, remove furo import in conf.py * add docs requirements file * typo * move index out of source folder * trying to get furo to work * import date * fix versions and titles, cleanup readthedocs requirements * typo fix, remove extras * more cleanup * bump version * no furo extension, "hack" to load RT version * proper toctree paths * specify method * add mock modules * fix typos * update python install requirements * running locally * move index to main docs dir again * update to build locally * error during warnings * automated version * cleanup * remove old docs * re-add docs * simplify * fix figure path * try alabaster * remove archived docs * use sphinx-rtd-theme * master doc and sphinx rtd theme * index back to root folder * only ignore install folders * remove hidden toctree * furo theme * update paths * convert rt version to string * update sphinx settings * move conf * furo theme * Pass through Kp_float = 0 (#59) * Pass through kp_float, if desired * Minor fixes: schema error and InputReader defaults * Allow pass through of Kp_float = 0 * Add flp parameters to schema * Change Fl_Mode default to 0 * Add defaults to omega_,zeta_ pc and vs, allow to be numbers * Allow single pitch tuning values in code, default U_pc to 0 * use nac acceleration for floating feedback * Fix TSR saturation for region 2.5operation * Modify system for constant power operation * Only modify pole for constant power above-rated * Remove GenEff from K calc * Update tuning, use constant power * use load_rosco_yaml * constant power * Fix broken tests * Include Fl_Mode=2 for nacelle pitching feedback * Add FOCAL inputs - hpf on floating feedback - lpf on wind speed estimator - associated schema updates * Set notch and check frequencies when Fl_Mode = 1 (fixes bug) * Skip filter step if there's an error * Update IEA-15MW test case DISCON with focal inputs * Allow Fl_Mode = 2 in ROSCO * Pass through lpf frequency * Add FOCAL tuning yaml * Set Cp contour number of levels * Add FOCAL params to various writers * Update/tune focal yaml * Add scripts for running FAST, tuning various parameters and cases * Add notebook for FAST plotting * Set up step case for testing * Change doubles to C_doubles * Define real and integer kinds, assign to all of ROSCO * Add ADJUSTL to DISCON error message * Fix Fl_Mode == 2 * Fix Fl_Mode == 2 again * Call yaw, flap, and debug only if enabled in DISOCN.IN * Make avrSWAP a ReKi and set constant kinds * Add DISCONs for testing - revert this later * Fix DISCON comparison, before DISCON's were overwritten by model * Rename DEBUG2.dbg to RootName.dbg2 * Update TestCase DISCONs to new input file * Add API change page in docs * Add link to API change on main page * Fix table headers * Fix title underlines * Fix tables again * Fix tables again * Fix version numbering in docs * Simplify FAST_directory in run_FAST * Versioning (#65) * use sphinx-rtd-theme * master doc and sphinx rtd theme * index back to root folder * only ignore install folders * remove hidden toctree * furo theme * update paths * convert rt version to string * update sphinx settings * move conf * furo theme * remove git versioning from cmake * use hard coded rosco_version * update intro write method * set nowrap for intel compilers * Add transfer of error message and clear message after each call * update install instructions * Catch nans in ROSCO at end of WSE * fix conda install typo * cleanup docs * Rename DEBUG2.dbg to RootName.dbg2 * Fix Fl_Mode == 2 * Fix Fl_Mode == 2 again * Allow Fl_Mode = 2 in ROSCO * Set notch and check frequencies when Fl_Mode = 1 (fixes bug) * Update FOCAL tuning yaml * Update TSR * Clean up and doc fix * Remove publish to pypi * Define all constant inputs to functions with kind typing * Generate Test_Case/ inputs automatically * Fix IEA15 DISCON path * Fix example 11 paths * Auto-generate tuning input yaml using schema * Add toolbox_input to doc index * Add toctree * Re-name title of toolbox_input Co-authored-by: Nikhar Abbas Co-authored-by: Xianping Du <38188001+Seager1989@users.noreply.github.com> Co-authored-by: nikhar-abbas <40865984+nikhar-abbas@users.noreply.github.com> * update listcheck method for numpy arrays * Open Loop Control (#98) * create rosco types yaml * Add more descriptions, add integer_c default, cleanup * updates for allocatability and shapes * python scripts to write ROSCO_types.f90 * reemove superfulous modules * use types from ROSCO registry * create rosco types yaml * Add more descriptions, add integer_c default, cleanup * updates for allocatability and shapes * python scripts to write ROSCO_types.f90 * reemove superfulous modules * use types from ROSCO registry * Saturate inputs to WSE. Needs some TLC, but seems to work * Reduce saturation limits on speed, torque * Re-organize, set saturation limits. Working at 3 m/s * Initial add of OL control to ROSCO: builds * Update DISCONs with open loop inputs * Fix file reading for OL_Filename * Add open loop control generation and file writing * Use DISCON_dict for more manageable DISCON file writing * Add open loop example, fix constant timeseries * Make open loop example generate power * Handle relative paths and calling from outside the run directory: - Some helper functions borrowed from OpenFAST, f/ext_control - Updated file writing * Clean up: versions, print statements * Fix SysFiles paths in CMakeLists * Tidy up Ext_DLL names * More Ext_DLL name tidying * Test write_registry.py * Update for OL Control * Move preprocessor lines * add zenodo DOI * Regenerated Types * fix shape * revert filepath change * give all types a size, ProcAddr size = 3 * update types * test registry in compile step * specify default shell * update write_registry path * remove default shell * Document API changes, provide OL input example * Fix example 14 (yaw input) * Add error catching to yaw control * Tidy up OL_Input Reading: error catching, generalize * More yaw control fixes, to model * Checkout develop CMakeLists for ROSCO * Update DISCON.INs for TestCases/ * Revert "Checkout develop CMakeLists for ROSCO" This reverts commit 87a491359d73806e3aaa59b4cfdc00f2838875df. * Revert windows cmake stuff to develop * Fix CMake again * Revert "Revert windows cmake stuff to develop" This reverts commit 39df122449b0e2055f2e12e3ce38a0c010c7bd91. * Make last cmake fix - hopefully Co-authored-by: Nikhar Abbas * Convert WE saved variables to WE type * Put restart flag in localvars * Use saved filter params from LocalVar * save pitcomt last * Move IPC saved variables to localvars * Saved pi controller variables to localvar * Save RootMyb_Last to localvar * ROSCO_IO - initial commit. Include restart and debug functions * Use ROSCO IO and call restart functions * Remove debug from function.f90 * Save ACC Infile info * update for restart capabilities * add rosco_io with restart and debug functions * cleanup debug call * use registry generate types and IO * delete DFController * fix timestep mismatch * remove unnecessaray istatus check * close files * add reg test for restart * add restart option to run_openfast * add testing to CI, ignore generate files * fix fastcall * remove extra commas * specify gfortran-10 * testing flag cleanup * Use lv_strings to generate debug output * Revert "testing flag cleanup" This reverts commit 6f295563832413e96347acd82716f9aadac6d46c. * Revert "specify gfortran-10" This reverts commit 4c3154491523bcd542133ca2bce5803cdc94523f. * minor cleanup * Use kind from constants * Add some comments for clarity * put debug in if statements * separate reg tests from oother tests * Fl_Mode>0 * Remove hard coded values * Add filtered signals and WE_Vw to debug varrs * cd for regtest * Check logging level before calling debug * add fl_pitcom and pc_minpit to debugvars * Turn runFAST into a class * Refactor/simplify CaseLibrary * Restart & registry (#99) * Convert WE saved variables to WE type * Put restart flag in localvars * Use saved filter params from LocalVar * save pitcomt last * Move IPC saved variables to localvars * Saved pi controller variables to localvar * Save RootMyb_Last to localvar * ROSCO_IO - initial commit. Include restart and debug functions * Use ROSCO IO and call restart functions * Remove debug from function.f90 * Save ACC Infile info * update for restart capabilities * add rosco_io with restart and debug functions * cleanup debug call * use registry generate types and IO * delete DFController * fix timestep mismatch * remove unnecessaray istatus check * close files * add reg test for restart * add restart option to run_openfast * add testing to CI, ignore generate files * fix fastcall * remove extra commas * specify gfortran-10 * testing flag cleanup * Use lv_strings to generate debug output * Revert "testing flag cleanup" This reverts commit 6f295563832413e96347acd82716f9aadac6d46c. * Revert "specify gfortran-10" This reverts commit 4c3154491523bcd542133ca2bce5803cdc94523f. * minor cleanup * Use kind from constants * Add some comments for clarity * put debug in if statements * separate reg tests from oother tests * Fl_Mode>0 * Remove hard coded values * Add filtered signals and WE_Vw to debug varrs * cd for regtest * Check logging level before calling debug * add fl_pitcom and pc_minpit to debugvars Co-authored-by: dzalkind * Implement initial pitch actuator * Set up steps case * Break up if statement in open loop pitch (#100) * Break up if statement in open loop pitch * Make torque and yaw consistent with pitch: can start after some time * add bld edgewise freq to robust dict_inputs * Add actuator variable * Print first time step in debug outs * Fix FOCAL yaml * Set actuator to 0.25 Hz bandwidth * Fix ccrotor inputs (#104) * remove interpolation of blade chord and twist * rename aerodynblade inputs * Update surface and DISCON.INs * Fix performance table paths * Allow default inputs (#110) * Allow defaults for AeroDyn inputs * Allow AeroDyn inputs to be floats, too * ipc (#105) * remove interpolation of blade chord and twist * rename aerodynblade inputs * Update surface and DISCON.INs * Fix performance table paths * Add proportional control and cleanup IPC * Add IPC and filtered RootMyc to registry * Better logic for filtering RootMOOP and fix notch filter slopes bug * Add cyclic flap conrol * Fix comments in ColemanTransformInverse * Addd IPC_KP to DISCON.IN * Error checking foro flp or ipc * add mutichannel plotting with tuples * add CMakeFiles to gitignore * Add IPC_KP to api changes * numerical qualifiers for error handling * add IPC gains to schema for pass-through ability * fix variable names * fix ipc gain printing bug * make sure IPC_KP is positive * Update Polars to point to coord files * ignore dbg2 files * Add IEA15MW_OL.yaml * update coord reader/writer * expand pitch_initial to 30 degrees * Add example 13 for IPC * Update cp surfaces and DISCONS * add examples to readme * cleanup and streaamline run_examples * Add IPC tuning vars * Allow IPC to command pitch value below peak shaving saturation limit * shorten simulation time * Fix Material parameter path * Update DISCONs again * Fix OL_Input reading * Set wind speed, rotor speed IC in example 14 * Debug OL reading * Add more debugging lines * Add more debugging lines 2 * Clean up, hone in on debug call * Disable logging level * Update discons - resolve conflict * Print when finished with ROSCO * add control packageg * Use PriPath and RootName to name dbg files * Print AvrSWAP * Revert "Use PriPath and RootName to name dbg files" This reverts commit 062fcaa55b3bf42d44f8a3f163aa883ab9552412. * Disable other examples * Print OL inputs * Allow logging level 3 * Print OL inputs * Make example shorter * Print more stuf * Print shape * Revert "Print OL inputs" This reverts commit 8e2a642bb35e46850f579ca4e69ca6d6fc93f4cc. * Update ROSCO Simulink model with IPC example * refactor flap tuning for normalization methods * improved flap controller filtering * delete extra F_FlpCornerFrerq * Update inputs, reader, and writer for OF 3.1.0 * Make sigma default interp type for multi_sigma * Use openfast 3.1.0 in CI * Fix leak...maybe * Use OF 3.1.0 in testing * Use gfotran for compile * Clean up print statements * Re-enable all examples * Update NREL-5MW AD file * Only check airfoil controls if more than one table * Update BAR models * Revert "Use gfotran for compile" This reverts commit 5a6e2b7e30287a09a09781e2ba12f9b578132e1f. * Install pyFAST for CI * Fix some paths in ex12 * Disable example 12 * Fix example 12 linear path, re-enable * Skip compilers install for mac * Try gfortran-9, no compilers * Try gfortran-10, no compilers * Skip windows compile in pytools * Re-enable windows, use gfortran as FC * Unset FC in windows * Set environment for windows when dependencies installed * Try setting environment in installation * Put conditional env setting in correct place * Try in setup again * Break up tasks: Windows vs. not * Update DISCONs * Update docs with new variables * Add example documentation * Update ROSCO Simulink model for 3.1.0 * Make IEA model float again * Reduce IEA timestep * Match DT to checkpoint time Co-authored-by: dzalkind * Increment version number * Bladed docs (#116) * Added image of Bladed control screen setup * Delete Bladed control screen.png * Adding image of Bladed control screen * Add files via upload * Minor edit 1 * Minor change 2 * Minor change 3 * Minor change 4 * Change 6 * Change 7 * Change 8 * Minor change 9 Co-authored-by: nikhar-abbas <40865984+nikhar-abbas@users.noreply.github.com> Co-authored-by: WillC-DNV <100850534+WillC-DNV@users.noreply.github.com> * Update version in API change docs * Bladed readthedocs (#117) * Added image of Bladed control screen setup * Delete Bladed control screen.png * Adding image of Bladed control screen * Add files via upload * Minor edit 1 * Minor change 2 * Minor change 3 * Minor change 4 * Change 6 * Change 7 * Change 8 * Minor change 9 * Tinker with characters in bladed instructions * Add bladed instructions to index * Change bladed toctree label * Do underline stuff * Make toctree label same as file * Remove colons from headers Co-authored-by: nikhar-abbas <40865984+nikhar-abbas@users.noreply.github.com> Co-authored-by: WillC-DNV <100850534+WillC-DNV@users.noreply.github.com> * Update docs to reflect CI process * Regenerate types, IO with registry * Update registry so first timestep is printed * Update inverted notch to move frequency properly * Saturate inv notch corner frequency at 0 * Add tower damper mode flag * Add Azimuth tracking controller in Simulink * Always enable GenDOF, add options for simp_step * Add sweep for IPC gains and FA damper * Fix NumCoords in FAST_writer * sigma + ipc (#125) * cleanup api change table * Update inverted notch to move frequency properly * Saturate inv notch corner frequency at 0 * add sigma function * Use IPC_Vramp for IPC cut-in * Add IPC_Vramp DISCON inputs * update registry * Update DISCONs * Update docs for API change * Fix IPC_Vramp data type * update comments Co-authored-by: dzalkind * Add turbulent case to runFAST/CaseLibrary * Add peak shaving sweep function * Increase default IPC_IntSat, make input parameter in future * Flip Ct and Cq table allocation * Flip Ct and Cq table allocation (#130) * Regen types * Remove print statements used for debugging * Update input files: IEA model has pitch actuator * Add back flap control (no idea when it was deleted) * Update discons, docs with API change * Add user-defined hh case * Fix AddF0 and RayleighDamp in FAST_reader * Pitch Actuator and IPC updates (#123) * Convert WE saved variables to WE type * Put restart flag in localvars * Use saved filter params from LocalVar * save pitcomt last * Move IPC saved variables to localvars * Saved pi controller variables to localvar * Save RootMyb_Last to localvar * ROSCO_IO - initial commit. Include restart and debug functions * Use ROSCO IO and call restart functions * Remove debug from function.f90 * Save ACC Infile info * update for restart capabilities * add rosco_io with restart and debug functions * cleanup debug call * use registry generate types and IO * delete DFController * fix timestep mismatch * remove unnecessaray istatus check * close files * add reg test for restart * add restart option to run_openfast * add testing to CI, ignore generate files * fix fastcall * remove extra commas * specify gfortran-10 * testing flag cleanup * Use lv_strings to generate debug output * Revert "testing flag cleanup" This reverts commit 6f295563832413e96347acd82716f9aadac6d46c. * Revert "specify gfortran-10" This reverts commit 4c3154491523bcd542133ca2bce5803cdc94523f. * minor cleanup * Use kind from constants * Add some comments for clarity * put debug in if statements * separate reg tests from oother tests * Fl_Mode>0 * Remove hard coded values * Add filtered signals and WE_Vw to debug varrs * cd for regtest * Check logging level before calling debug * add fl_pitcom and pc_minpit to debugvars * Turn runFAST into a class * Refactor/simplify CaseLibrary * Implement initial pitch actuator * Set up steps case * Add actuator variable * Print first time step in debug outs * Fix FOCAL yaml * Set actuator to 0.25 Hz bandwidth * ROSCO 2.5.0 (#115) * FOCAL Updates (#64) * Update headers * fix bullets * make uppercase * Update turbine.py (#56) * Update turbine.py This add several lines for fixing the problem of repeated maximum values in the performance tables. This will cause the error (' the length of x and y is different.') of 'interpolate.interp1d.' * Add comments and catch when there are multiple optimal pitch angles Co-authored-by: dzalkind * increment version * Update for OpenFAST v3.0.0 * Update for OpenFAST v3.0.0 * Install OF3.0.0 for tests * update for OF v3.0.0 * add publish to pypi on release * Update to ROSCO v2.3.0 * Update Testing (#58) * Update scripts to run on eagle * Update IEA-15MW semi example: use peak shaving w/ ps_percen=0.8 * Add comparison plots to testing scripts * Update submit script for testing * Update for latest eagle runs * Add future to install dependencies * add TMax to self, define tmin in print_results * run tests in CI * generic ROSCO path * default to overwrite * fix path * import platform * separate run_testing * cleanup, specify lite test * don't run testing in after examples, oops. Co-authored-by: nikhar-abbas <40865984+nikhar-abbas@users.noreply.github.com> Co-authored-by: Nikhar Abbas * increment version * Update for OpenFAST v3.0.0 * Install OF3.0.0 for tests * update for OF v3.0.0 * add publish to pypi on release * Update to ROSCO v2.3.0 * Increment Version, OF3.0 (#57) * increment version * Update for OpenFAST v3.0.0 * Install OF3.0.0 for tests * update for OF v3.0.0 * add publish to pypi on release * Update to ROSCO v2.3.0 * increment version * Update for OpenFAST v3.0.0 * Install OF3.0.0 for tests * update for OF v3.0.0 * add publish to pypi on release * Update to ROSCO v2.3.0 * add ROSCO without submodule * move ROSCO source to ROSCO folder * Move cmake-related files to ROSCO * Add back pesky ErrVar * Remove parameters_files * Merge ROSCO and _toolbox gitignore * Fix .gitignore * Remove Examples/DISCON.IN from git * Fix and point example_01 to Tune_Cases/ * Update verbiage around using ofTools vs. weis * Fix and point example_04 to Tune_Cases/ * Clean up example_06 * Clean up example_07 * Only check FlpCornerFreq if using Flp control, fixes example 05 * Make example_04 consistent with others * Let example_05 run independently from 04 * Clean up example_05, wind files * Add schema and update empty tuning yaml inputs, not connected yet * Integrate schema into turbine, controller, and examples * Only check Fl filter parameters if Fl_Mode > 0, fix example_05 * bump version to 2.3 * Compile ROSCO from ROSCO dir * Rename to CI_rosco * Add omega vs. windspeed functionality * Fix tests: 5MW U_pc and 06 example dir * Make _Toolbox vs_minspeed in rotor frame to match ROSCO * Revert ServoDyn change * change rotor speed constraint to be epsilon * rename for clarity * docs major refresh * fix FA_AccF units in debug file * docs that build locally * Deallocate arrays in ROSCO, check in example_05 * Clean up comments * remove gitmodules * furo theme * furo in requirements * move readthedocs config file, remove furo import in conf.py * add docs requirements file * typo * move index out of source folder * trying to get furo to work * import date * fix versions and titles, cleanup readthedocs requirements * typo fix, remove extras * more cleanup * bump version * no furo extension, "hack" to load RT version * proper toctree paths * specify method * add mock modules * fix typos * update python install requirements * running locally * move index to main docs dir again * update to build locally * error during warnings * automated version * cleanup * remove old docs * re-add docs * simplify * fix figure path * try alabaster * remove archived docs * Add omega vs. windspeed functionality * Fix tests: 5MW U_pc and 06 example dir * more detailed sp.optimize settings * run MBC3 in parallel * restructure driver, run initialization doe for tuning * Try new dlclose function * Update example_05 to run simple simulation twice and check result * Revert deallocation stuff * Close discon library after every sim run * Test examples on macOS and windows * Run examples instead of testing on other platforms * Skip examples in windows for now * update paths and yaml load funciton * Skip mac testing of examples * provide default U_pc for single omega/zeta case * allow for float or list-like pc tuning inputs * Change name in setup.py * WE_Vw unit fix * Pass through kp_float, if desired * Minor fixes: schema error and InputReader defaults * cleeanup for improved stability * check for doe_logs as string in load_DOE * major restructure for rsched_driver class * cleanup verbosity * run serial by default * load_parallel as linturb_option * specific IEA15MW yaml for multi omega * remove unused module imports * fix error message types * lin_file as input * add comments on inputs to LinearTurbineModel init method * remove relative file paths * provide OpenFAST linearizations for IEA15MW UMaineSemi * put plotting in specific function * fix WE_lambda units * add self in on a few necessary variables * creaete example 12 for robust scheduling * try a few mbc3 locations for import * allow list-like or numpy arrays for omega_pc and zeta_pc schedules * create and use recorder setup function * Pass Through Kp_float (#57) * Pass through kp_float, if desired * Minor fixes: schema error and InputReader defaults * fix setup_recorder to work for optimization driver too * Allow pass through of Kp_float = 0 * cleanup om problems, update om0 calc * doe levels as input * negative k_float to account for OF conventions * cleanup print statements * variable name cleanup, use calculated k_float * Add defaults to omega_,zeta_ pc and vs, allow to be numbers * use standard tuning k_float as IC * formatting update * update problem setup methods * cleanup add_dv, enable adding design variables after problem is setup * change optimization step size * more setup restructure * update verbosity * use sphinx-rtd-theme * master doc and sphinx rtd theme * index back to root folder * only ignore install folders * remove hidden toctree * furo theme * update paths * convert rt version to string * update sphinx settings * move conf * furo theme * Mostly a docs update (#61) * rename for clarity * docs major refresh * fix FA_AccF units in debug file * docs that build locally * remove gitmodules * furo theme * furo in requirements * move readthedocs config file, remove furo import in conf.py * add docs requirements file * typo * move index out of source folder * trying to get furo to work * import date * fix versions and titles, cleanup readthedocs requirements * typo fix, remove extras * more cleanup * bump version * no furo extension, "hack" to load RT version * proper toctree paths * specify method * add mock modules * fix typos * update python install requirements * running locally * move index to main docs dir again * update to build locally * error during warnings * automated version * cleanup * remove old docs * re-add docs * simplify * fix figure path * try alabaster * remove archived docs * use sphinx-rtd-theme * master doc and sphinx rtd theme * index back to root folder * only ignore install folders * remove hidden toctree * furo theme * update paths * convert rt version to string * update sphinx settings * move conf * furo theme * Pass through Kp_float = 0 (#59) * Pass through kp_float, if desired * Minor fixes: schema error and InputReader defaults * Allow pass through of Kp_float = 0 * Add flp parameters to schema * Change Fl_Mode default to 0 * Add defaults to omega_,zeta_ pc and vs, allow to be numbers * Allow single pitch tuning values in code, default U_pc to 0 * use nac acceleration for floating feedback * Fix TSR saturation for region 2.5operation * Modify system for constant power operation * Only modify pole for constant power above-rated * Remove GenEff from K calc * Update tuning, use constant power * use load_rosco_yaml * constant power * Fix broken tests * Include Fl_Mode=2 for nacelle pitching feedback * Add FOCAL inputs - hpf on floating feedback - lpf on wind speed estimator - associated schema updates * Set notch and check frequencies when Fl_Mode = 1 (fixes bug) * Skip filter step if there's an error * Update IEA-15MW test case DISCON with focal inputs * Allow Fl_Mode = 2 in ROSCO * Pass through lpf frequency * Add FOCAL tuning yaml * Set Cp contour number of levels * Add FOCAL params to various writers * Update/tune focal yaml * Add scripts for running FAST, tuning various parameters and cases * Add notebook for FAST plotting * Set up step case for testing * Change doubles to C_doubles * Define real and integer kinds, assign to all of ROSCO * Add ADJUSTL to DISCON error message * Fix Fl_Mode == 2 * Fix Fl_Mode == 2 again * Call yaw, flap, and debug only if enabled in DISOCN.IN * Make avrSWAP a ReKi and set constant kinds * Add DISCONs for testing - revert this later * Fix DISCON comparison, before DISCON's were overwritten by model * Rename DEBUG2.dbg to RootName.dbg2 * Update TestCase DISCONs to new input file * Add API change page in docs * Add link to API change on main page * Fix table headers * Fix title underlines * Fix tables again * Fix tables again * Fix version numbering in docs * Simplify FAST_directory in run_FAST * Versioning (#65) * use sphinx-rtd-theme * master doc and sphinx rtd theme * index back to root folder * only ignore install folders * remove hidden toctree * furo theme * update paths * convert rt version to string * update sphinx settings * move conf * furo theme * remove git versioning from cmake * use hard coded rosco_version * update intro write method * set nowrap for intel compilers * Add transfer of error message and clear message after each call * update install instructions * Catch nans in ROSCO at end of WSE * fix conda install typo * cleanup docs * Rename DEBUG2.dbg to RootName.dbg2 * Fix Fl_Mode == 2 * Fix Fl_Mode == 2 again * Allow Fl_Mode = 2 in ROSCO * Set notch and check frequencies when Fl_Mode = 1 (fixes bug) * Update FOCAL tuning yaml * Update TSR * Clean up and doc fix * Remove publish to pypi * Define all constant inputs to functions with kind typing * Generate Test_Case/ inputs automatically * Fix IEA15 DISCON path * Fix example 11 paths * Auto-generate tuning input yaml using schema * Add toolbox_input to doc index * Add toctree * Re-name title of toolbox_input Co-authored-by: Nikhar Abbas Co-authored-by: Xianping Du <38188001+Seager1989@users.noreply.github.com> Co-authored-by: nikhar-abbas <40865984+nikhar-abbas@users.noreply.github.com> * update listcheck method for numpy arrays * Open Loop Control (#98) * create rosco types yaml * Add more descriptions, add integer_c default, cleanup * updates for allocatability and shapes * python scripts to write ROSCO_types.f90 * reemove superfulous modules * use types from ROSCO registry * create rosco types yaml * Add more descriptions, add integer_c default, cleanup * updates for allocatability and shapes * python scripts to write ROSCO_types.f90 * reemove superfulous modules * use types from ROSCO registry * Saturate inputs to WSE. Needs some TLC, but seems to work * Reduce saturation limits on speed, torque * Re-organize, set saturation limits. Working at 3 m/s * Initial add of OL control to ROSCO: builds * Update DISCONs with open loop inputs * Fix file reading for OL_Filename * Add open loop control generation and file writing * Use DISCON_dict for more manageable DISCON file writing * Add open loop example, fix constant timeseries * Make open loop example generate power * Handle relative paths and calling from outside the run directory: - Some helper functions borrowed from OpenFAST, f/ext_control - Updated file writing * Clean up: versions, print statements * Fix SysFiles paths in CMakeLists * Tidy up Ext_DLL names * More Ext_DLL name tidying * Test write_registry.py * Update for OL Control * Move preprocessor lines * add zenodo DOI * Regenerated Types * fix shape * revert filepath change * give all types a size, ProcAddr size = 3 * update types * test registry in compile step * specify default shell * update write_registry path * remove default shell * Document API changes, provide OL input example * Fix example 14 (yaw input) * Add error catching to yaw control * Tidy up OL_Input Reading: error catching, generalize * More yaw control fixes, to model * Checkout develop CMakeLists for ROSCO * Update DISCON.INs for TestCases/ * Revert "Checkout develop CMakeLists for ROSCO" This reverts commit 87a491359d73806e3aaa59b4cfdc00f2838875df. * Revert windows cmake stuff to develop * Fix CMake again * Revert "Revert windows cmake stuff to develop" This reverts commit 39df122449b0e2055f2e12e3ce38a0c010c7bd91. * Make last cmake fix - hopefully Co-authored-by: Nikhar Abbas * Restart & registry (#99) * Convert WE saved variables to WE type * Put restart flag in localvars * Use saved filter params from LocalVar * save pitcomt last * Move IPC saved variables to localvars * Saved pi controller variables to localvar * Save RootMyb_Last to localvar * ROSCO_IO - initial commit. Include restart and debug functions * Use ROSCO IO and call restart functions * Remove debug from function.f90 * Save ACC Infile info * update for restart capabilities * add rosco_io with restart and debug functions * cleanup debug call * use registry generate types and IO * delete DFController * fix timestep mismatch * remove unnecessaray istatus check * close files * add reg test for restart * add restart option to run_openfast * add testing to CI, ignore generate files * fix fastcall * remove extra commas * specify gfortran-10 * testing flag cleanup * Use lv_strings to generate debug output * Revert "testing flag cleanup" This reverts commit 6f295563832413e96347acd82716f9aadac6d46c. * Revert "specify gfortran-10" This reverts commit 4c3154491523bcd542133ca2bce5803cdc94523f. * minor cleanup * Use kind from constants * Add some comments for clarity * put debug in if statements * separate reg tests from oother tests * Fl_Mode>0 * Remove hard coded values * Add filtered signals and WE_Vw to debug varrs * cd for regtest * Check logging level before calling debug * add fl_pitcom and pc_minpit to debugvars Co-authored-by: dzalkind * Break up if statement in open loop pitch (#100) * Break up if statement in open loop pitch * Make torque and yaw consistent with pitch: can start after some time * add bld edgewise freq to robust dict_inputs * Fix ccrotor inputs (#104) * remove interpolation of blade chord and twist * rename aerodynblade inputs * Update surface and DISCON.INs * Fix performance table paths * Allow default inputs (#110) * Allow defaults for AeroDyn inputs * Allow AeroDyn inputs to be floats, too * ipc (#105) * remove interpolation of blade chord and twist * rename aerodynblade inputs * Update surface and DISCON.INs * Fix performance table paths * Add proportional control and cleanup IPC * Add IPC and filtered RootMyc to registry * Better logic for filtering RootMOOP and fix notch filter slopes bug * Add cyclic flap conrol * Fix comments in ColemanTransformInverse * Addd IPC_KP to DISCON.IN * Error checking foro flp or ipc * add mutichannel plotting with tuples * add CMakeFiles to gitignore * Add IPC_KP to api changes * numerical qualifiers for error handling * add IPC gains to schema for pass-through ability * fix variable names * fix ipc gain printing bug * make sure IPC_KP is positive * Update Polars to point to coord files * ignore dbg2 files * Add IEA15MW_OL.yaml * update coord reader/writer * expand pitch_initial to 30 degrees * Add example 13 for IPC * Update cp surfaces and DISCONS * add examples to readme * cleanup and streaamline run_examples * Add IPC tuning vars * Allow IPC to command pitch value below peak shaving saturation limit * shorten simulation time * Fix Material parameter path * Update DISCONs again * Fix OL_Input reading * Set wind speed, rotor speed IC in example 14 * Debug OL reading * Add more debugging lines * Add more debugging lines 2 * Clean up, hone in on debug call * Disable logging level * Update discons - resolve conflict * Print when finished with ROSCO * add control packageg * Use PriPath and RootName to name dbg files * Print AvrSWAP * Revert "Use PriPath and RootName to name dbg files" This reverts commit 062fcaa55b3bf42d44f8a3f163aa883ab9552412. * Disable other examples * Print OL inputs * Allow logging level 3 * Print OL inputs * Make example shorter * Print more stuf * Print shape * Revert "Print OL inputs" This reverts commit 8e2a642bb35e46850f579ca4e69ca6d6fc93f4cc. * Update ROSCO Simulink model with IPC example * refactor flap tuning for normalization methods * improved flap controller filtering * delete extra F_FlpCornerFrerq * Update inputs, reader, and writer for OF 3.1.0 * Make sigma default interp type for multi_sigma * Use openfast 3.1.0 in CI * Fix leak...maybe * Use OF 3.1.0 in testing * Use gfotran for compile * Clean up print statements * Re-enable all examples * Update NREL-5MW AD file * Only check airfoil controls if more than one table * Update BAR models * Revert "Use gfotran for compile" This reverts commit 5a6e2b7e30287a09a09781e2ba12f9b578132e1f. * Install pyFAST for CI * Fix some paths in ex12 * Disable example 12 * Fix example 12 linear path, re-enable * Skip compilers install for mac * Try gfortran-9, no compilers * Try gfortran-10, no compilers * Skip windows compile in pytools * Re-enable windows, use gfortran as FC * Unset FC in windows * Set environment for windows when dependencies installed * Try setting environment in installation * Put conditional env setting in correct place * Try in setup again * Break up tasks: Windows vs. not * Update DISCONs * Update docs with new variables * Add example documentation * Update ROSCO Simulink model for 3.1.0 * Make IEA model float again * Reduce IEA timestep * Match DT to checkpoint time Co-authored-by: dzalkind * Increment version number * Bladed docs (#116) * Added image of Bladed control screen setup * Delete Bladed control screen.png * Adding image of Bladed control screen * Add files via upload * Minor edit 1 * Minor change 2 * Minor change 3 * Minor change 4 * Change 6 * Change 7 * Change 8 * Minor change 9 Co-authored-by: nikhar-abbas <40865984+nikhar-abbas@users.noreply.github.com> Co-authored-by: WillC-DNV <100850534+WillC-DNV@users.noreply.github.com> * Update version in API change docs * Bladed readthedocs (#117) * Added image of Bladed control screen setup * Delete Bladed control screen.png * Adding image of Bladed control screen * Add files via upload * Minor edit 1 * Minor change 2 * Minor change 3 * Minor change 4 * Change 6 * Change 7 * Change 8 * Minor change 9 * Tinker with characters in bladed instructions * Add bladed instructions to index * Change bladed toctree label * Do underline stuff * Make toctree label same as file * Remove colons from headers Co-authored-by: nikhar-abbas <40865984+nikhar-abbas@users.noreply.github.com> Co-authored-by: WillC-DNV <100850534+WillC-DNV@users.noreply.github.com> * Update docs to reflect CI process Co-authored-by: Nikhar Abbas Co-authored-by: Xianping Du <38188001+Seager1989@users.noreply.github.com> Co-authored-by: nikhar-abbas <40865984+nikhar-abbas@users.noreply.github.com> Co-authored-by: WillC-DNV <100850534+WillC-DNV@users.noreply.github.com> * Fixed wrong formatting of list items (#122) extra newline required between list elements * Regenerate types, IO with registry * Update registry so first timestep is printed * Update inverted notch to move frequency properly * Saturate inv notch corner frequency at 0 * Add tower damper mode flag * Flip Ct and Cq table allocation * Regen types * Remove print statements used for debugging * Update input files: IEA model has pitch actuator * Add back flap control (no idea when it was deleted) * Update discons, docs with API change Co-authored-by: nikhar-abbas <40865984+nikhar-abbas@users.noreply.github.com> Co-authored-by: Nikhar Abbas Co-authored-by: Xianping Du <38188001+Seager1989@users.noreply.github.com> Co-authored-by: WillC-DNV <100850534+WillC-DNV@users.noreply.github.com> Co-authored-by: Gustavo Hylander <74593034+ghylander@users.noreply.github.com> * Add max_torque_factor for constant power control, flexible upper limit * Make update discons relative to tuning yaml * Update AddF0 and NumCoords in FAST_reader/writer * Add OpenFAST channels that Simulink reads (#135) * RAAW Updates (#133) * Convert WE saved variables to WE type * Put restart flag in localvars * Use saved filter params from LocalVar * save pitcomt last * Move IPC saved variables to localvars * Saved pi controller variables to localvar * Save RootMyb_Last to localvar * ROSCO_IO - initial commit. Include restart and debug functions * Use ROSCO IO and call restart functions * Remove debug from function.f90 * Save ACC Infile info * update for restart capabilities * add rosco_io with restart and debug functions * cleanup debug call * use registry generate types and IO * delete DFController * fix timestep mismatch * remove unnecessaray istatus check * close files * add reg test for restart * add restart option to run_openfast * add testing to CI, ignore generate files * fix fastcall * remove extra commas * specify gfortran-10 * testing flag cleanup * Use lv_strings to generate debug output * Revert "testing flag cleanup" This reverts commit 6f295563832413e96347acd82716f9aadac6d46c. * Revert "specify gfortran-10" This reverts commit 4c3154491523bcd542133ca2bce5803cdc94523f. * minor cleanup * Use kind from constants * Add some comments for clarity * put debug in if statements * separate reg tests from oother tests * Fl_Mode>0 * Remove hard coded values * Add filtered signals and WE_Vw to debug varrs * cd for regtest * Check logging level before calling debug * add fl_pitcom and pc_minpit to debugvars * Turn runFAST into a class * Refactor/simplify CaseLibrary * Implement initial pitch actuator * Set up steps case * Add actuator variable * Print first time step in debug outs * Fix FOCAL yaml * Set actuator to 0.25 Hz bandwidth * ROSCO 2.5.0 (#115) * FOCAL Updates (#64) * Update headers * fix bullets * make uppercase * Update turbine.py (#56) * Update turbine.py This add several lines for fixing the problem of repeated maximum values in the performance tables. This will cause the error (' the length of x and y is different.') of 'interpolate.interp1d.' * Add comments and catch when there are multiple optimal pitch angles Co-authored-by: dzalkind * increment version * Update for OpenFAST v3.0.0 * Update for OpenFAST v3.0.0 * Install OF3.0.0 for tests * update for OF v3.0.0 * add publish to pypi on release * Update to ROSCO v2.3.0 * Update Testing (#58) * Update scripts to run on eagle * Update IEA-15MW semi example: use peak shaving w/ ps_percen=0.8 * Add comparison plots to testing scripts * Update submit script for testing * Update for latest eagle runs * Add future to install dependencies * add TMax to self, define tmin in print_results * run tests in CI * generic ROSCO path * default to overwrite * fix path * import platform * separate run_testing * cleanup, specify lite test * don't run testing in after examples, oops. Co-authored-by: nikhar-abbas <40865984+nikhar-abbas@users.noreply.github.com> Co-authored-by: Nikhar Abbas * increment version * Update for OpenFAST v3.0.0 * Install OF3.0.0 for tests * update for OF v3.0.0 * add publish to pypi on release * Update to ROSCO v2.3.0 * Increment Version, OF3.0 (#57) * increment version * Update for OpenFAST v3.0.0 * Install OF3.0.0 for tests * update for OF v3.0.0 * add publish to pypi on release * Update to ROSCO v2.3.0 * increment version * Update for OpenFAST v3.0.0 * Install OF3.0.0 for tests * update for OF v3.0.0 * add publish to pypi on release * Update to ROSCO v2.3.0 * add ROSCO without submodule * move ROSCO source to ROSCO folder * Move cmake-related files to ROSCO * Add back pesky ErrVar * Remove parameters_files * Merge ROSCO and _toolbox gitignore * Fix .gitignore * Remove Examples/DISCON.IN from git * Fix and point example_01 to Tune_Cases/ * Update verbiage around using ofTools vs. weis * Fix and point example_04 to Tune_Cases/ * Clean up example_06 * Clean up example_07 * Only check FlpCornerFreq if using Flp control, fixes example 05 * Make example_04 consistent with others * Let example_05 run independently from 04 * Clean up example_05, wind files * Add schema and update empty tuning yaml inputs, not connected yet * Integrate schema into turbine, controller, and examples * Only check Fl filter parameters if Fl_Mode > 0, fix example_05 * bump version to 2.3 * Compile ROSCO from ROSCO dir * Rename to CI_rosco * Add omega vs. windspeed functionality * Fix tests: 5MW U_pc and 06 example dir * Make _Toolbox vs_minspeed in rotor frame to match ROSCO * Revert ServoDyn change * change rotor speed constraint to be epsilon * rename for clarity * docs major refresh * fix FA_AccF units in debug file * docs that build locally * Deallocate arrays in ROSCO, check in example_05 * Clean up comments * remove gitmodules * furo theme * furo in requirements * move readthedocs config file, remove furo import in conf.py * add docs requirements file * typo * move index out of source folder * trying to get furo to work * import date * fix versions and titles, cleanup readthedocs requirements * typo fix, remove extras * more cleanup * bump version * no furo extension, "hack" to load RT version * proper toctree paths * specify method * add mock modules * fix typos * update python install requirements * running locally * move index to main docs dir again * update to build locally * error during warnings * automated version * cleanup * remove old docs * re-add docs * simplify * fix figure path * try alabaster * remove archived docs * Add omega vs. windspeed functionality * Fix tests: 5MW U_pc and 06 example dir * more detailed sp.optimize settings * run MBC3 in parallel * restructure driver, run initialization doe for tuning * Try new dlclose function * Update example_05 to run simple simulation twice and check result * Revert deallocation stuff * Close discon library after every sim run * Test examples on macOS and windows * Run examples instead of testing on other platforms * Skip examples in windows for now * update paths and yaml load funciton * Skip mac testing of examples * provide default U_pc for single omega/zeta case * allow for float or list-like pc tuning inputs * Change name in setup.py * WE_Vw unit fix * Pass through kp_float, if desired * Minor fixes: schema error and InputReader defaults * cleeanup for improved stability * check for doe_logs as string in load_DOE * major restructure for rsched_driver class * cleanup verbosity * run serial by default * load_parallel as linturb_option * specific IEA15MW yaml for multi omega * remove unused module imports * fix error message types * lin_file as input * add comments on inputs to LinearTurbineModel init method * remove relative file paths * provide OpenFAST linearizations for IEA15MW UMaineSemi * put plotting in specific function * fix WE_lambda units * add self in on a few necessary variables * creaete example 12 for robust scheduling * try a few mbc3 locations for import * allow list-like or numpy arrays for omega_pc and zeta_pc schedules * create and use recorder setup function * Pass Through Kp_float (#57) * Pass through kp_float, if desired * Minor fixes: schema error and InputReader defaults * fix setup_recorder to work for optimization driver too * Allow pass through of Kp_float = 0 * cleanup om problems, update om0 calc * doe levels as input * negative k_float to account for OF conventions * cleanup print statements * variable name cleanup, use calculated k_float * Add defaults to omega_,zeta_ pc and vs, allow to be numbers * use standard tuning k_float as IC * formatting update * update problem setup methods * cleanup add_dv, enable adding design variables after problem is setup * change optimization step size * more setup restructure * update verbosity * use sphinx-rtd-theme * master doc and sphinx rtd theme * index back to root folder * only ignore install folders * remove hidden toctree * furo theme * update paths * convert rt version to string * update sphinx settings * move conf * furo theme * Mostly a docs update (#61) * rename for clarity * docs major refresh * fix FA_AccF units in debug file * docs that build locally * remove gitmodules * furo theme * furo in requirements * move readthedocs config file, remove furo import in conf.py * add docs requirements file * typo * move index out of source folder * trying to get furo to work * import date * fix versions and titles, cleanup readthedocs requirements * typo fix, remove extras * more cleanup * bump version * no furo extension, "hack" to load RT version * proper toctree paths * specify method * add mock modules * fix typos * update python install requirements * running locally * move index to main docs dir again * update to build locally * error during warnings * automated version * cleanup * remove old docs * re-add docs * simplify * fix figure path * try alabaster * remove archived docs * use sphinx-rtd-theme * master doc and sphinx rtd theme * index back to root folder * only ignore install folders * remove hidden toctree * furo theme * update paths * convert rt version to string * update sphinx settings * move conf * furo theme * Pass through Kp_float = 0 (#59) * Pass through kp_float, if desired * Minor fixes: schema error and InputReader defaults * Allow pass through of Kp_float = 0 * Add flp parameters to schema * Change Fl_Mode default to 0 * Add defaults to omega_,zeta_ pc and vs, allow to be numbers * Allow single pitch tuning values in code, default U_pc to 0 * use nac acceleration for floating feedback * Fix TSR saturation for region 2.5operation * Modify system for constant power operation * Only modify pole for constant power above-rated * Remove GenEff from K calc * Update tuning, use constant power * use load_rosco_yaml * constant power * Fix broken tests * Include Fl_Mode=2 for nacelle pitching feedback * Add FOCAL inputs - hpf on floating feedback - lpf on wind speed estimator - associated schema updates * Set notch and check frequencies when Fl_Mode = 1 (fixes bug) * Skip filter step if there's an error * Update IEA-15MW test case DISCON with focal inputs * Allow Fl_Mode = 2 in ROSCO * Pass through lpf frequency * Add FOCAL tuning yaml * Set Cp contour number of levels * Add FOCAL params to various writers * Update/tune focal yaml * Add scripts for running FAST, tuning various parameters and cases * Add notebook for FAST plotting * Set up step case for testing * Change doubles to C_doubles * Define real and integer kinds, assign to all of ROSCO * Add ADJUSTL to DISCON error message * Fix Fl_Mode == 2 * Fix Fl_Mode == 2 again * Call yaw, flap, and debug only if enabled in DISOCN.IN * Make avrSWAP a ReKi and set constant kinds * Add DISCONs for testing - revert this later * Fix DISCON comparison, before DISCON's were overwritten by model * Rename DEBUG2.dbg to RootName.dbg2 * Update TestCase DISCONs to new input file * Add API change page in docs * Add link to API change on main page * Fix table headers * Fix title underlines * Fix tables again * Fix tables again * Fix version numbering in docs * Simplify FAST_directory in run_FAST * Versioning (#65) * use sphinx-rtd-theme * master doc and sphinx rtd theme * index back to root folder * only ignore install folders * remove hidden toctree * furo theme * update paths * convert rt version to string * update sphinx settings * move conf * furo theme * remove git versioning from cmake * use hard coded rosco_version * update intro write method * set nowrap for intel compilers * Add transfer of error message and clear message after each call * update install instructions * Catch nans in ROSCO at end of WSE * fix conda install typo * cleanup docs * Rename DEBUG2.dbg to RootName.dbg2 * Fix Fl_Mode == 2 * Fix Fl_Mode == 2 again * Allow Fl_Mode = 2 in ROSCO * Set notch and check frequencies when Fl_Mode = 1 (fixes bug) * Update FOCAL tuning yaml * Update TSR * Clean up and doc fix * Remove publish to pypi * Define all constant inputs to functions with kind typing * Generate Test_Case/ inputs automatically * Fix IEA15 DISCON path * Fix example 11 paths * Auto-generate tuning input yaml using schema * Add toolbox_input to doc index * Add toctree * Re-name title of toolbox_input Co-authored-by: Nikhar Abbas Co-authored-by: Xianping Du <38188001+Seager1989@users.noreply.github.com> Co-authored-by: nikhar-abbas <40865984+nikhar-abbas@users.noreply.github.com> * update listcheck method for numpy arrays * Open Loop Control (#98) * create rosco types yaml * Add more descriptions, add integer_c default, cleanup * updates for allocatability and shapes * python scripts to write ROSCO_types.f90 * reemove superfulous modules * use types from ROSCO registry * create rosco types yaml * Add more descriptions, add integer_c default, cleanup * updates for allocatability and shapes * python scripts to write ROSCO_types.f90 * reemove superfulous modules * use types from ROSCO registry * Saturate inputs to WSE. Needs some TLC, but seems to work * Reduce saturation limits on speed, torque * Re-organize, set saturation limits. Working at 3 m/s * Initial add of OL control to ROSCO: builds * Update DISCONs with open loop inputs * Fix file reading for OL_Filename * Add open loop control generation and file writing * Use DISCON_dict for more manageable DISCON file writing * Add open loop example, fix constant timeseries * Make open loop example generate power * Handle relative paths and calling from outside the run directory: - Some helper functions borrowed from OpenFAST, f/ext_control - Updated file writing * Clean up: versions, print statements * Fix SysFiles paths in CMakeLists * Tidy up Ext_DLL names * More Ext_DLL name tidying * Test write_registry.py * Update for OL Control * Move preprocessor lines * add zenodo DOI * Regenerated Types * fix shape * revert filepath change * give all types a size, ProcAddr size = 3 * update types * test registry in compile step * specify default shell * update write_registry path * remove default shell * Document API changes, provide OL input example * Fix example 14 (yaw input) * Add error catching to yaw control * Tidy up OL_Input Reading: error catching, generalize * More yaw control fixes, to model * Checkout develop CMakeLists for ROSCO * Update DISCON.INs for TestCases/ * Revert "Checkout develop CMakeLists for ROSCO" This reverts commit 87a491359d73806e3aaa59b4cfdc00f2838875df. * Revert windows cmake stuff to develop * Fix CMake again * Revert "Revert windows cmake stuff to develop" This reverts commit 39df122449b0e2055f2e12e3ce38a0c010c7bd91. * Make last cmake fix - hopefully Co-authored-by: Nikhar Abbas * Restart & registry (#99) * Convert WE saved variables to WE type * Put restart flag in localvars * Use saved filter params from LocalVar * save pitcomt last * Move IPC saved variables to localvars * Saved pi controller variables to localvar * Save RootMyb_Last to localvar * ROSCO_IO - initial commit. Include restart and debug functions * Use ROSCO IO and call restart functions * Remove debug from function.f90 * Save ACC Infile info * update for restart capabilities * add rosco_io with restart and debug functions * cleanup debug call * use registry generate types and IO * delete DFController * fix timestep mismatch * remove unnecessaray istatus check * close files * add reg test for restart * add restart option to run_openfast * add testing to CI, ignore generate files * fix fastcall * remove extra commas * specify gfortran-10 * testing flag cleanup * Use lv_strings to generate debug output * Revert "testing flag cleanup" This reverts commit 6f295563832413e96347acd82716f9aadac6d46c. * Revert "specify gfortran-10" This reverts commit 4c3154491523bcd542133ca2bce5803cdc94523f. * minor cleanup * Use kind from constants * Add some comments for clarity * put debug in if statements * separate reg tests from oother tests * Fl_Mode>0 * Remove hard coded values * Add filtered signals and WE_Vw to debug varrs * cd for regtest * Check logging level before calling debug * add fl_pitcom and pc_minpit to debugvars Co-authored-by: dzalkind * Break up if statement in open loop pitch (#100) * Break up if statement in open loop pitch * Make torque and yaw consistent with pitch: can start after some time * add bld edgewise freq to robust dict_inputs * Fix ccrotor inputs (#104) * remove interpolation of blade chord and twist * rename aerodynblade inputs * Update surface and DISCON.INs * Fix performance table paths * Allow default inputs (#110) * Allow defaults for AeroDyn inputs * Allow AeroDyn inputs to be floats, too * ipc (#105) * remove interpolation of blade chord and twist * rename aerodynblade inputs * Update surface and DISCON.INs * Fix performance table paths * Add proportional control and cleanup IPC * Add IPC and filtered RootMyc to registry * Better logic for filtering RootMOOP and fix notch filter slopes bug * Add cyclic flap conrol * Fix comments in ColemanTransformInverse * Addd IPC_KP to DISCON.IN * Error checking foro flp or ipc * add mutichannel plotting with tuples * add CMakeFiles to gitignore * Add IPC_KP to api changes * numerical qualifiers for error handling * add IPC gains to schema for pass-through ability * fix variable names * fix ipc gain printing bug * make sure IPC_KP is positive * Update Polars to point to coord files * ignore dbg2 files * Add IEA15MW_OL.yaml * update coord reader/writer * expand pitch_initial to 30 degrees * Add example 13 for IPC * Update cp surfaces and DISCONS * add examples to readme * cleanup and streaamline run_examples * Add IPC tuning vars * Allow IPC to command pitch value below peak shaving saturation limit * shorten simulation time * Fix Material parameter path * Update DISCONs again * Fix OL_Input reading * Set wind speed, rotor speed IC in example 14 * Debug OL reading * Add more debugging lines * Add more debugging lines 2 * Clean up, hone in on debug call * Disable logging level * Update discons - resolve conflict * Print when finished with ROSCO * add control packageg * Use PriPath and RootName to name dbg files * Print AvrSWAP * Revert "Use PriPath and RootName to name dbg files" This reverts commit 062fcaa55b3bf42d44f8a3f163aa883ab9552412. * Disable other examples * Print OL inputs * Allow logging level 3 * Print OL inputs * Make example shorter * Print more stuf * Print shape * Revert "Print OL inputs" This reverts commit 8e2a642bb35e46850f579ca4e69ca6d6fc93f4cc. * Update ROSCO Simulink model with IPC example * refactor flap tuning for normalization methods * improved flap controller filtering * delete extra F_FlpCornerFrerq * Update inputs, reader, and writer for OF 3.1.0 * Make sigma default interp type for multi_sigma * Use openfast 3.1.0 in CI * Fix leak...maybe * Use OF 3.1.0 in testing * Use gfotran for compile * Clean up print statements * Re-enable all examples * Update NREL-5MW AD file * Only check airfoil controls if more than one table * Update BAR models * Revert "Use gfotran for compile" This reverts commit 5a6e2b7e30287a09a09781e2ba12f9b578132e1f. * Install pyFAST for CI * Fix some paths in ex12 * Disable example 12 * Fix example 12 linear path, re-enable * Skip compilers install for mac * Try gfortran-9, no compilers * Try gfortran-10, no compilers * Skip windows compile in pytools * Re-enable windows, use gfortran as FC * Unset FC in windows * Set environment for windows when dependencies installed * Try setting environment in installation * Put conditional env setting in correct place * Try in setup again * Break up tasks: Windows vs. not * Update DISCONs * Update docs with new variables * Add example documentation * Update ROSCO Simulink model for 3.1.0 * Make IEA model float again * Reduce IEA timestep * Match DT to checkpoint time Co-authored-by: dzalkind * Increment version number * Bladed docs (#116) * Added image of Bladed control screen setup * Delete Bladed control screen.png * Adding image of Bladed control screen * Add files via upload * Minor edit 1 * Minor change 2 * Minor change 3 * Minor change 4 * Change 6 * Change 7 * Change 8 * Minor change 9 Co-authored-by: nikhar-abbas <40865984+nikhar-abbas@users.noreply.github.com> Co-authored-by: WillC-DNV <100850534+WillC-DNV@users.noreply.github.com> * Update version in API change docs * Bladed readthedocs (#117) * Added image of Bladed control screen setup * Delete Bladed control screen.png * Adding image of Bladed control screen * Add files via upload * Minor edit 1 * Minor change 2 * Minor change 3 * Minor change 4 * Change 6 * Change 7 * Change 8 * Minor change 9 * Tinker with characters in bladed instructions * Add bladed instructions to index * Change bladed toctree label * Do underline stuff * Make toctree label same as file * Remove colons from headers Co-authored-by: nikhar-abbas <40865984+nikhar-abbas@users.noreply.github.com> Co-authored-by: WillC-DNV <100850534+WillC-DNV@users.noreply.github.com> * Update docs to reflect CI process Co-authored-by: Nikhar Abbas Co-authored-by: Xianping Du <38188001+Seager1989@users.noreply.github.com> Co-authored-by: nikhar-abbas <40865984+nikhar-abbas@users.noreply.github.com> Co-authored-by: WillC-DNV <100850534+WillC-DNV@users.noreply.github.com> * Fixed wrong formatting of list items (#122) extra newline required between list elements * Regenerate types, IO with registry * Update registry so first timestep is printed * Update inverted notch to move frequency properly * Saturate inv notch corner frequency at 0 * Add tower damper mode flag * Add Azimuth tracking controller in Simulink * Always enable GenDOF, add options for simp_step * Add sweep for IPC gains and FA damper * Fix NumCoords in FAST_writer * Add turbulent case to runFAST/CaseLibrary * Add peak shaving sweep function * Increase default IPC_IntSat, make input parameter in future * Flip Ct and Cq table allocation (#129) * Flip Ct and Cq table allocation * Regen types * Remove print statements used for debugging * Update input files: IEA model has pitch actuator * Add back flap control (no idea when it was deleted) * Update discons, docs with API change * Add user-defined hh case * Fix AddF0 and RayleighDamp in FAST_reader * Add max_torque_factor for constant power control, flexible upper limit * Make update discons relative to tuning yaml * Update AddF0 and NumCoords in FAST_reader/writer * Remove matlab/rotor position control stuff Co-authored-by: nikhar-abbas <40865984+nikhar-abbas@users.noreply.github.com> Co-authored-by: Nikhar Abbas Co-authored-by: Xianping Du <38188001+Seager1989@users.noreply.github.com> Co-authored-by: WillC-DNV <100850534+WillC-DNV@users.noreply.github.com> Co-authored-by: Gustavo Hylander <74593034+ghylander@users.noreply.github.com> * Pass through (#136) * Convert WE saved variables to WE type * Put restart flag in localvars * Use saved filter params from LocalVar * save pitcomt last * Move IPC saved variables to localvars * Saved pi controller variables to localvar * Save RootMyb_Last to localvar * ROSCO_IO - initial commit. Include restart and debug functions * Use ROSCO IO and call restart functions * Remove debug from function.f90 * Save ACC Infile info * update for restart capabilities * add rosco_io with restart and debug functions * cleanup debug call * use registry generate types and IO * delete DFController * fix timestep mismatch * remove unnecessaray istatus check * close files * add reg test for restart * add restart option to run_openfast * add testing to CI, ignore generate files * fix fastcall * remove extra commas * specify gfortran-10 * testing flag cleanup * Use lv_strings to generate debug output * Revert "testing flag cleanup" This reverts commit 6f295563832413e96347acd82716f9aadac6d46c. * Revert "specify gfortran-10" This reverts commit 4c3154491523bcd542133ca2bce5803cdc94523f. * minor cleanup * Use kind from constants * Add some comments for clarity * put debug in if statements * separate reg tests from oother tests * Fl_Mode>0 * Remove hard coded values * Add filtered signals and WE_Vw to debug varrs * cd for regtest * Check logging level before calling debug * add fl_pitcom and pc_minpit to debugvars * Turn runFAST into a class * Refactor/simplify CaseLibrary * Implement initial pitch actuator * Set up steps case * Add actuator variable * Print first time step in debug outs * Fix FOCAL yaml * Set actuator to 0.25 Hz bandwidth * ROSCO 2.5.0 (#115) * FOCAL Updates (#64) * Update headers * fix bullets * make uppercase * Update turbine.py (#56) * Update turbine.py This add several lines for fixing the problem of repeated maximum values in the performance tables. This will cause the error (' the length of x and y is different.') of 'interpolate.interp1d.' * Add comments and catch when there are multiple optimal pitch angles Co-authored-by: dzalkind * increment version * Update for OpenFAST v3.0.0 * Update for OpenFAST v3.0.0 * Install OF3.0.0 for tests * update for OF v3.0.0 * add publish to pypi on release * Update to ROSCO v2.3.0 * Update Testing (#58) * Update scripts to run on eagle * Update IEA-15MW semi example: use peak shaving w/ ps_percen=0.8 * Add comparison plots to testing scripts * Update submit script for testing * Update for latest eagle runs * Add future to install dependencies * add TMax to self, define tmin in print_results * run tests in CI * generic ROSCO path * default to overwrite * fix path * import platform * separate run_testing * cleanup, specify lite test * don't run testing in after examples, oops. Co-authored-by: nikhar-abbas <40865984+nikhar-abbas@users.noreply.github.com> Co-authored-by: Nikhar Abbas * increment version * Update for OpenFAST v3.0.0 * Install OF3.0.0 for tests * update for OF v3.0.0 * add publish to pypi on release * Update to ROSCO v2.3.0 * Increment Version, OF3.0 (#57) * increment version * Update for OpenFAST v3.0.0 * Install OF3.0.0 for tests * update for OF v3.0.0 * add publish to pypi on release * Update to ROSCO v2.3.0 * increment version * Update for OpenFAST v3.0.0 * Install OF3.0.0 for tests * update for OF v3.0.0 * add publish to pypi on release * Update to ROSCO v2.3.0 * add ROSCO without submodule * move ROSCO source to ROSCO folder * Move cmake-related files to ROSCO * Add back pesky ErrVar * Remove parameters_files * Merge ROSCO and _toolbox gitignore * Fix .gitignore * Remove Examples/DISCON.IN from git * Fix and point example_01 to Tune_Cases/ * Update verbiage around using ofTools vs. weis * Fix and point example_04 to Tune_Cases/ * Clean up example_06 * Clean up example_07 * Only check FlpCornerFreq if using Flp control, fixes example 05 * Make example_04 consistent with others * Let example_05 run independently from 04 * Clean up example_05, wind files * Add schema and update empty tuning yaml inputs, not connected yet * Integrate schema into turbine, controller, and examples * Only check Fl filter parameters if Fl_Mode > 0, fix example_05 * bump version to 2.3 * Compile ROSCO from ROSCO dir * Rename to CI_rosco * Add omega vs. windspeed functionality * Fix tests: 5MW U_pc and 06 example dir * Make _Toolbox vs_minspeed in rotor frame to match ROSCO * Revert ServoDyn change * change rotor speed constraint to be epsilon * rename for clarity * docs major refresh * fix FA_AccF units in debug file * docs that build locally * Deallocate arrays in ROSCO, check in example_05 * Clean up comments * remove gitmodules * furo theme * furo in requirements * move readthedocs config file, remove furo import in conf.py * add docs requirements file * typo * move index out of source folder * trying to get furo to work * import date * fix versions and titles, cleanup readthedocs requirements * typo fix, remove extras * more cleanup * bump version * no furo extension, "hack" to load RT version * proper toctree paths * specify method * add mock modules * fix typos * update python install requirements * running locally * move index to main docs dir again * update to build locally * error during warnings * automated version * cleanup * remove old docs * re-add docs * simplify * fix figure path * try alabaster * remove archived docs * Add omega vs. windspeed functionality * Fix tests: 5MW U_pc and 06 example dir * more detailed sp.optimize settings * run MBC3 in parallel * restructure driver, run initialization doe for tuning * Try new dlclose function * Update example_05 to run simple simulation twice and check result * Revert deallocation stuff * Close discon library after every sim run * Test examples on macOS and windows * Run examples instead of testing on other platforms * Skip examples in windows for now * update paths and yaml load funciton * Skip mac testing of examples * provide default U_pc for single omega/zeta case * allow for float or list-like pc tuning inputs * Change name in setup.py * WE_Vw unit fix * Pass through kp_float, if desired * Minor fixes: schema error and InputReader defaults * cleeanup for improved stability * check for doe_logs as string in load_DOE * major restructure for rsched_driver class * cleanup verbosity * run serial by default * load_parallel as linturb_option * specific IEA15MW yaml for multi omega * remove unused module imports * fix error message types * lin_file as input * add comments on inputs to LinearTurbineModel init method * remove relative file paths * provide OpenFAST linearizations for IEA15MW UMaineSemi * put plotting in specific function * fix WE_lambda units * add self in on a few necessary variables * creaete example 12 for robust scheduling * try a few mbc3 locations for import * allow list-like or numpy arrays for omega_pc and zeta_pc schedules * create and use recorder setup function * Pass Through Kp_float (#57) * Pass through kp_float, if desired * Minor fixes: schema error and InputReader defaults * fix setup_recorder to work for optimization driver too * Allow pass through of Kp_float = 0 * cleanup om problems, update om0 calc * doe levels as input * negative k_float to account for OF conventions * cleanup print statements * variable name cleanup, use calculated k_float * Add defaults to omega_,zeta_ pc and vs, allow to be numbers * use standard tuning k_float as IC * formatting update * update problem setup methods * cleanup add_dv, enable adding design variables after problem is setup * change optimization step size * more setup restructure * update verbosity * use sphinx-rtd-theme * master doc and sphinx rtd theme * index back to root folder * only ignore install folders * remove hidden toctree * furo theme * update paths * convert rt version to string * update sphinx settings * move conf * furo theme * Mostly a docs update (#61) * rename for clarity * docs major refresh * fix FA_AccF units in debug file * docs that build locally * remove gitmodules * furo theme * furo in requirements * move readthedocs config file, remove furo import in conf.py * add docs requirements file * typo * move index out of source folder * trying to get furo to work * import date * fix versions and titles, cleanup readthedocs requirements * typo fix, remove extras * more cleanup * bump version * no furo extension, "hack" to load RT version * proper toctree paths * specify method * add mock modules * fix typos * update python install requirements * running locally * move index to main docs dir again * update to build locally * error during warnings * automated version * cleanup * remove old docs * re-add docs * simplify * fix figure path * try alabaster * remove archived docs * use sphinx-rtd-theme * master doc and sphinx rtd theme * index back to root folder * only ignore install folders * remove hidden toctree * furo theme * update paths * convert rt version to string * update sphinx settings * move conf * furo theme * Pass through Kp_float = 0 (#59) * Pass through kp_float, if desired * Minor fixes: schema error and InputReader defaults * Allow pass through of Kp_float = 0 * Add flp parameters to schema * Change Fl_Mode default to 0 * Add defaults to omega_,zeta_ pc and vs, allow to be numbers * Allow single pitch tuning values in code, default U_pc to 0 * use nac acceleration for floating feedback * Fix TSR saturation for region 2.5operation * Modify system for constant power operation * Only modify pole for constant power above-rated * Remove GenEff from K calc * Update tuning, use constant power * use load_rosco_yaml * constant power * Fix broken tests * Include Fl_Mode=2 for nacelle pitching feedback * Add FOCAL inputs - hpf on floating feedback - lpf on wind speed estimator - associated schema updates * Set notch and check frequencies when Fl_Mode = 1 (fixes bug) * Skip filter step if there's an error * Update IEA-15MW test case DISCON with focal inputs * Allow Fl_Mode = 2 in ROSCO * Pass through lpf frequency * Add FOCAL tuning yaml * Set Cp contour number of levels * Add FOCAL params to various writers * Update/tune focal yaml * Add scripts for running FAST, tuning various parameters and cases * Add notebook for FAST plotting * Set up step case for testing * Change doubles to C_doubles * Define real and integer kinds, assign to all of ROSCO * Add ADJUSTL to DISCON error message * Fix Fl_Mode == 2 * Fix Fl_Mode == 2 again * Call yaw, flap, and debug only if enabled in DISOCN.IN * Make avrSWAP a ReKi and set constant kinds * Add DISCONs for testing - revert this later * Fix DISCON comparison, before DISCON's were overwritten by model * Rename DEBUG2.dbg to RootName.dbg2 * Update TestCase DISCONs to new input file * Add API change page in docs * Add link to API change on main page * Fix table headers * Fix title underlines * Fix tables again * Fix tables again * Fix version numbering in docs * Simplify FAST_directory in run_FAST * Versioning (#65) * use sphinx-rtd-theme * master doc and sphinx rtd theme * index back to root folder * only ignore install folders * remove hidden toctree * furo theme * update paths * convert rt version to string * update sphinx settings * move conf * furo theme * remove git versioning from cmake * use hard coded rosco_version * update intro write method * set nowrap for intel compilers * Add transfer of error message and clear message after each call * update install instructions * Catch nans in ROSCO at end of WSE * fix conda install typo * cleanup docs * Rename DEBUG2.dbg to RootName.dbg2 * Fix Fl_Mode == 2 * Fix Fl_Mode == 2 again * Allow Fl_Mode = 2 in ROSCO * Set notch and check frequencies when Fl_Mode = 1 (fixes bug) * Update FOCAL tuning yaml * Update TSR * Clean up and doc fix * Remove publish to pypi * Define all constant inputs to functions with kind typing * Generate Test_Case/ inputs automatically * Fix IEA15 DISCON path * Fix example 11 paths * Auto-generate tuning input yaml using schema * Add toolbox_input to doc index * Add toctree * Re-name title of toolbox_input Co-authored-by: Nikhar Abbas Co-authored-by: Xianping Du <38188001+Seager1989@users.noreply.github.com> Co-authored-by: nikhar-abbas <40865984+nikhar-abbas@users.noreply.github.com> * update listcheck method for numpy arrays * Open Loop Control (#98) * create rosco types yaml * Add more descriptions, add integer_c default, cleanup * updates for allocatability and shapes * python scripts to write ROSCO_types.f90 * reemove superfulous modules * use types from ROSCO registry * create rosco types yaml * Add more descriptions, add integer_c default, cleanup * updates for allocatability and shapes * python scripts to write ROSCO_types.f90 * reemove superfulous modules * use types from ROSCO registry * Saturate inputs to WSE. Needs some TLC, but seems to work * Reduce saturation limits on speed, torque * Re-organize, set saturation limits. Working at 3 m/s * Initial add of OL control to ROSCO: builds * Update DISCONs with open loop inputs * Fix file reading for OL_Filename * Add open loop control generation and file writing * Use DISCON_dict for more manageable DISCON file writing * Add open loop example, fix constant timeseries * Make open loop example generate power * Handle relative paths and calling from outside the run directory: - Some helper functions borrowed from OpenFAST, f/ext_control - Updated file writing * Clean up: versions, print statements * Fix SysFiles paths in CMakeLists * Tidy up Ext_DLL names * More Ext_DLL name tidying * Test write_registry.py * Update for OL Control * Move preprocessor lines * add zenodo DOI * Regenerated Types * fix shape * revert filepath change * give all types a size, ProcAddr size = 3 * update types * test registry in compile step * specify default shell * update write_registry path * remove default shell * Document API changes, provide OL input example * Fix example 14 (yaw input) * Add error catching to yaw control * Tidy up OL_Input Reading: error catching, generalize * More yaw control fixes, to model * Checkout develop CMakeLists for ROSCO * Update DISCON.INs for TestCases/ * Revert "Checkout develop CMakeLists for ROSCO" This reverts commit 87a491359d73806e3aaa59b4cfdc00f2838875df. * Revert windows cmake stuff to develop * Fix CMake again * Revert "Revert windows cmake stuff to develop" This reverts commit 39df122449b0e2055f2e12e3ce38a0c010c7bd91. * Make last cmake fix - hopefully Co-authored-by: Nikhar Abbas * Restart & registry (#99) * Convert WE saved variables to WE type * Put restart flag in localvars * Use saved filter params from LocalVar * save pitcomt last * Move IPC saved variables to localvars * Saved pi controller variables to localvar * Save RootMyb_Last to localvar * ROSCO_IO - initial commit. Include restart and debug functions * Use ROSCO IO and call restart functions * Remove debug from function.f90 * Save ACC Infile info * update for restart capabilities * add rosco_io with restart and debug functions * cleanup debug call * use registry generate types and IO * delete DFController * fix timestep mismatch * remove unnecessaray istatus check * close files * add reg test for restart * add restart option to run_openfast * add testing to CI, ignore generate files * fix fastcall * remove extra commas * specify gfortran-10 * testing flag cleanup * Use lv_strings to generate debug output * Revert "testing flag cleanup" This reverts commit 6f295563832413e96347acd82716f9aadac6d46c. * Revert "specify gfortran-10" This reverts commit 4c3154491523bcd542133ca2bce5803cdc94523f. * minor cleanup * Use kind from constants * Add some comments for clarity * put debug in if statements * separate reg tests from oother tests * Fl_Mode>0 * Remove hard coded values * Add filtered signals and WE_Vw to debug varrs * cd for regtest * Check logging level before calling debug * add fl_pitcom and pc_minpit to debugvars Co-authored-by: dzalkind * Break up if statement in open loop pitch (#100) * Break up if statement in open loop pitch * Make torque and yaw consistent with pitch: can start after some time * add bld edgewise freq to robust dict_inputs * Fix ccrotor inputs (#104) * remove interpolation of blade chord and twist * rename aerodynblade inputs * Update surface and DISCON.INs * Fix performance table paths * Allow default inputs (#110) * Allow defaults for AeroDyn inputs * Allow AeroDyn inputs to be floats, too * ipc (#105) * remove interpolation of blade chord and twist * rename aerodynblade inputs * Update surface and DISCON.INs * Fix performance table paths * Add proportional control and cleanup IPC * Add IPC and filtered RootMyc to registry * Better logic for filtering RootMOOP and fix notch filter slopes bug * Add cyclic flap conrol * Fix comments in ColemanTransformInverse * Addd IPC_KP to DISCON.IN * Error checking foro flp or ipc * add mutichannel plotting with tuples * add CMakeFiles to gitignore * Add IPC_KP to api changes * numerical qualifiers for error handling * add IPC gains to schema for pass-through ability * fix variable names * fix ipc gain printing bug * make sure IPC_KP is positive * Update Polars to point to coord files * ignore dbg2 files * Add IEA15MW_OL.yaml * update coord reader/writer * expand pitch_initial to 30 degrees * Add example 13 for IPC * Update cp surfaces and DISCONS * add examples to readme * cleanup and streaamline run_examples * Add IPC tuning vars * Allow IPC to command pitch value below peak shaving saturation limit * shorten simulation time * Fix Material parameter path * Update DISCONs again * Fix OL_Input reading * Set wind speed, rotor speed IC in example 14 * Debug OL reading * Add more debugging lines * Add more debugging lines 2 * Clean up, hone in on debug call * Disable logging level * Update discons - resolve conflict * Print when finished with ROSCO * add control packageg * Use PriPath and RootName to name dbg files * Print AvrSWAP * Revert "Use PriPath and RootName to name dbg files" This reverts commit 062fcaa55b3bf42d44f8a3f163aa883ab9552412. * Disable other examples * Print OL inputs * Allow logging level 3 * Print OL inputs * Make example shorter * Print more stuf * Print shape * Revert "Print OL inputs" This reverts commit 8e2a642bb35e46850f579ca4e69ca6d6fc93f4cc. * Update ROSCO Simulink model with IPC example * refactor flap tuning for normalization methods * improved flap controller filtering * delete extra F_FlpCornerFrerq * Update inputs, reader, and writer for OF 3.1.0 * Make sigma default interp type for multi_sigma * Use openfast 3.1.0 in CI * Fix leak...maybe * Use OF 3.1.0 in testing * Use gfotran for compile * Clean up print statements * Re-enable all examples * Update NREL-5MW AD file * Only check airfoil controls if more than one table * Update BAR models * Revert "Use gfotran for compile" This reverts commit 5a6e2b7e30287a09a09781e2ba12f9b578132e1f. * Install pyFAST for CI * Fix some paths in ex12 * Disable example 12 * Fix example 12 linear path, re-enable * Skip compilers install for mac * Try gfortran-9, no compilers * Try gfortran-10, no compilers * Skip windows compile in pytools * Re-enable windows, use gfortran as FC * Unset FC in windows * Set environment for windows when dependencies installed * Try setting environment in installation * Put conditional env setting in correct place * Try in setup again * Break up tasks: Windows vs. not * Update DISCONs * Update docs with new variables * Add example documentation * Update ROSCO Simulink model for 3.1.0 * Make IEA model float again * Reduce IEA timestep * Match DT to checkpoint time Co-authored-by: dzalkind * Increment version number * Bladed docs (#116) * Added image of Bladed control screen setup * Delete Bladed control screen.png * Adding image of Bladed control screen * Add files via upload * Minor edit 1 * Minor change 2 * Minor change 3 * Minor change 4 * Change 6 * Change 7 * Change 8 * Minor change 9 Co-authored-by: nikhar-abbas <40865984+nikhar-abbas@users.noreply.github.com> Co-authored-by: WillC-DNV <100850534+WillC-DNV@users.noreply.github.com> * Update version in API change docs * Bladed readthedocs (#117) * Added image of Bladed control screen setup * Delete Bladed control screen.png * Adding image of Bladed control screen * Add files via upload * Minor edit 1 * Minor change 2 * Minor change 3 * Minor change 4 * Change 6 * Change 7 * Change 8 * Minor change 9 * Tinker with characters in bladed instructions * Add bladed instructions to index * Change bladed toctree label * Do underline stuff * Make toctree label same as file * Remove colons from headers Co-authored-by: nikhar-abbas <40865984+nikhar-abbas@users.noreply.github.com> Co-authored-by: WillC-DNV <100850534+WillC-DNV@users.noreply.github.com> * Update docs to reflect CI process Co-authored-by: Nikhar Abbas Co-authored-by: Xianping Du <38188001+Seager1989@users.noreply.github.com> Co-authored-by: nikhar-abbas <40865984+nikhar-abbas@users.noreply.github.com> Co-authored-by: WillC-DNV <100850534+WillC-DNV@users.noreply.github.com> * Fixed wrong formatting of list items (#122) extra newline required between list elements * Regenerate types, IO with registry * Update registry so first timestep is printed * Update inverted notch to move frequency properly * Saturate inv notch corner frequency at 0 * Add tower damper mode flag * Add Azimuth tracking controller in Simulink * Always enable GenDOF, add options for simp_step * Add sweep for IPC gains and FA damper * Fix NumCoords in FAST_writer * Add turbulent case to runFAST/CaseLibrary * Add peak shaving sweep function * Increase default IPC_IntSat, make input parameter in future * Flip Ct and Cq table allocation (#129) * Flip Ct and Cq table allocation * Regen types * Remove print statements used for debugging * Update input files: IEA model has pitch actuator * Add back flap control (no idea when it was deleted) * Update discons, docs with API change * Add user-defined hh case * Fix AddF0 and RayleighDamp in FAST_reader * Add max_torque_factor for constant power control, flexible upper limit * Make update discons relative to tuning yaml * Update AddF0 and NumCoords in FAST_reader/writer * Remove matlab/rotor position control stuff * Add initial DISCON pass through schema * Add TODO items for pull requests * Add initial pass through capability, example * Add PassThrough example yaml * Make cp filename relative to FAST_directory throughout * Remove brackets, regen input docs * Add to PassThrough example yaml * Add example 15 to testing, fix yaml * Tidy comments in CaseLibrary Co-authored-by: nikhar-abbas <40865984+nikhar-abbas@users.noreply.github.com> Co-authored-by: Nikhar Abbas Co-authored-by: Xianping Du <38188001+Seager1989@users.noreply.github.com> Co-authored-by: WillC-DNV <100850534+WillC-DNV@users.noreply.github.com> Co-authored-by: Gustavo Hylander <74593034+ghylander@users.noreply.github.com> * Robust control updates (#139) * change default interp type * improve nested MPI handling * fix cl bug, sm calc more robust, allow single plant for interp * add load from pickle capabilites * add re-try logic * save v_above_rated to controller object * fix BAR cp_ct_cq surface path * update discons * remove rogue DISCON * External Control Interface (#141) * Add ExtControl manually from f/ext_control, compiling * Fix Cp plots * Update multiple discons * Make FAST_Directory relative to yaml * Set control to ROSCO, sweep max torque * Fix c_float type in registry, building * Update DISCON writer, fix reader * Add example for running Ext control, running * Max example actually call extdll, update inputs, running * Add ExtControl module! * Add ROSCO_Helpers, GetNewUnit, shorten ReadSetParameters, Functions * Update write_registry with GetNewUnit * Tidy up RootName: remove hard-coded index * Close Cp file, fixes checkpoint test * Clean up examples, add 16 to CI testing * Change regtest name in CI * Update DISCONs * Add API change documentation * Add summary of API changes, finish external interface * Tidy code, point to location for using ExtDLL * F/zmq (#145) * cleanup api change table * zeromq client and f90 files - initia lcommit * add zmq install reqs * remove yaw-by-ipc * typo fix * add zeroMQ interface to registry and source - enable zeroMQ for yaw control * cleanup to compile, move ZMQ_Mode to flags, write DISCONS * only set ZMQ_Client if flag is enabled * fix bug in discons * minor updates and add sim with wind direction * change to dict inputs for control interface * add zmq example * Revert "remove yaw-by-ipc" This reverts commit 2ca2859884313aa6d8fdd217a7fede73802a5fcf. * Enable Yaw-by-ipc again * update and execute zeromq example * add zmq to dependencies * sudo for apt-get * libzmq3-dev typo * setup cmake * rename example 16 to 17 * read empty line * update types, regen discons * fix build path * remove non-ubuntu examples, type in cmake command * Set ROSCO=True * typo fix and update DISCONs * document API changes * newlines and in-text code * updated removed inputs, fix intext code syntax * run example 17 * Add description to example 17 * zeromq -> pyzmq, cleanup * better table for new/modified/removed * fix real(8) * cleanup zmqVar conventions and uses. Call zmq using a time period * Update DISCONS * run all examples * Fix Y_uSwitch description * update comm address example * execute with runpy instead of importlib * move zmq interface classes to control_interface * Properly shutdown ZMQ interface * add IEA15MW_ExtInterface.yaml * Incorporate runFAST stuff from WEIS, clean up * Remove specific rosco_dll * Publish artifacts from examples * Clean up examples following runFAST business * move archive artifacts * Fix build dir in example 17 * Switch install/develop in pytools CI * archive even if exampless fail * add zmq build instructions * cleanup and rename sim * Remove BITS_IN_ADDR stuff * Pass case_inputs and rosco_dll to runFAST object * Pass correct DLL_FileName for external control * Tidy example 15 commenting Co-authored-by: dzalkind * Generalize update discons * Update PR template * Update update discons * Nyquist plotting (#157) * change default interp type * improve nested MPI handling * fix cl bug, sm calc more robust, allow single plant for interp * add load from pickle capabilites * add re-try logic * save v_above_rated to controller object * fix BAR cp_ct_cq surface path * update discons * remove rogue DISCON * Add linear model visualization tools * plot nyquist * remove plt.show() * fix indexing, windspeed * Comments (#150) * cleanup api change table * Update comments to describe zmq modules and functions better * comment and cleanup controller-related moduels * cleanup and comments for turbine modules * psuedo functions for weird interpolation steps * minor sim cleanup * More comments for robust tuning procedures * add descriptions and comments for robust scheduling * Add some comments * Add Ct_max comment Co-authored-by: dzalkind * Update ROSCO_walkthrough to use new yaml reader (#159) * Update ROSCO_walkthrough to use new yaml reader * Add CI for notebooks * Make parameter_filename a relative path * Generalize dylib extension in RW * Update to openfast==3.2.0, no API changes! (#160) * Updates in preparation for ROSCO 2.6.0 (#161) * ROSCO 2.5.0 (#115) * FOCAL Updates (#64) * Update headers * fix bullets * make uppercase * Update turbine.py (#56) * Update turbine.py This add several lines for fixing the problem of repeated maximum values in the performance tables. This will cause the error (' the length of x and y is different.') of 'interpolate.interp1d.' * Add comments and catch when there are multiple optimal pitch angles Co-authored-by: dzalkind * increment version * Update for OpenFAST v3.0.0 * Update for OpenFAST v3.0.0 * Install OF3.0.0 for tests * update for OF v3.0.0 * add publish to pypi on release * Update to ROSCO v2.3.0 * Update Testing (#58) * Update scripts to run on eagle * Update IEA-15MW semi example: use peak shaving w/ ps_percen=0.8 * Add comparison plots to testing scripts * Update submit script for testing * Update for latest eagle runs * Add future to install dependencies * add TMax to self, define tmin in print_results * run tests in CI * generic ROSCO path * default to overwrite * fix path * import platform * separate run_testing * cleanup, specify lite test * don't run testing in after examples, oops. Co-authored-by: nikhar-abbas <40865984+nikhar-abbas@users.noreply.github.com> Co-authored-by: Nikhar Abbas * increment version * Update for OpenFAST v3.0.0 * Install OF3.0.0 for tests * update for OF v3.0.0 * add publish to pypi on release * Update to ROSCO v2.3.0 * Increment Version, OF3.0 (#57) * increment version * Update for OpenFAST v3.0.0 * Install OF3.0.0 for tests * update for OF v3.0.0 * add publish to pypi on release * Update to ROSCO v2.3.0 * increment version * Update for OpenFAST v3.0.0 * Install OF3.0.0 for tests * update for OF v3.0.0 * add publish to pypi on release * Update to ROSCO v2.3.0 * add ROSCO without submodule * move ROSCO source to ROSCO folder * Move cmake-related files to ROSCO * Add back pesky ErrVar * Remove parameters_files * Merge ROSCO and _toolbox gitignore * Fix .gitignore * Remove Examples/DISCON.IN from git * Fix and point example_01 to Tune_Cases/ * Update verbiage around using ofTools vs. weis * Fix and point example_04 to Tune_Cases/ * Clean up example_06 * Clean up example_07 * Only check FlpCornerFreq if using Flp control, fixes example 05 * Make example_04 consistent with others * Let example_05 run independently from 04 * Clean up example_05, wind files * Add schema and update empty tuning yaml inputs, not connected yet * Integrate schema into turbine, controller, and examples * Only check Fl filter parameters if Fl_Mode > 0, fix example_05 * bump version to 2.3 * Compile ROSCO from ROSCO dir * Rename to CI_rosco * Add omega vs. windspeed functionality * Fix tests: 5MW U_pc and 06 example dir * Make _Toolbox vs_minspeed in rotor frame to match ROSCO * Revert ServoDyn change * change rotor speed constraint to be epsilon * rename for clarity * docs major refresh * fix FA_AccF units in debug file * docs that build locally * Deallocate arrays in ROSCO, check in example_05 * Clean up comments * remove gitmodules * furo theme * furo in requirements * move readthedocs config file, remove furo import in conf.py * add docs requirements file * typo * move index out of source folder * trying to get furo to work * import date * fix versions and titles, cleanup readthedocs requirements * typo fix, remove extras * more cleanup * bump version * no furo extension, "hack" to load RT version * proper toctree paths * specify method * add mock modules * fix typos * update python install requirements * running locally * move index to main docs dir again * update to build locally * error during warnings * automated version * cleanup * remove old docs * re-add docs * simplify * fix figure path * try alabaster * remove archived docs * Add omega vs. windspeed functionality * Fix tests: 5MW U_pc and 06 example dir * more detailed sp.optimize settings * run MBC3 in parallel * restructure driver, run initialization doe for tuning * Try new dlclose function * Update example_05 to run simple simulation twice and check result * Revert deallocation stuff * Close discon library after every sim run * Test examples on macOS and windows * Run examples instead of testing on other platforms * Skip examples in windows for now * update paths and yaml load funciton * Skip mac testing of examples * provide default U_pc for single omega/zeta case * allow for float or list-like pc tuning inputs * Change name in setup.py * WE_Vw unit fix * Pass through kp_float, if desired * Minor fixes: schema error and InputReader defaults * cleeanup for improved stability * check for doe_logs as string in load_DOE * major restructure for rsched_driver class * cleanup verbosity * run serial by default * load_parallel as linturb_option * specific IEA15MW yaml for multi omega * remove unused module imports * fix error message types * lin_file as input * add comments on inputs to LinearTurbineModel init method * remove relative file paths * provide OpenFAST linearizations for IEA15MW UMaineSemi * put plotting in specific function * fix WE_lambda units * add self in on a few necessary variables * creaete example 12 for robust scheduling * try a few mbc3 locations for import * allow list-like or numpy arrays for omega_pc and zeta_pc schedules * create and use recorder setup function * Pass Through Kp_float (#57) * Pass through kp_float, if desired * Minor fixes: schema error and InputReader defaults * fix setup_recorder to work for optimization driver too * Allow pass through of Kp_float = 0 * cleanup om problems, update om0 calc * doe levels as input * negative k_float to account for OF conventions * cleanup print statements * variable name cleanup, use calculated k_float * Add defaults to omega_,zeta_ pc and vs, allow to be numbers * use standard tuning k_float as IC * formatting update * update problem setup methods * cleanup add_dv, enable adding design variables after problem is setup * change optimization step size * more setup restructure * update verbosity * use sphinx-rtd-theme * master doc and sphinx rtd theme * index back to root folder * only ignore install folders * remove hidden toctree * furo theme * update paths * convert rt version to string * update sphinx settings * move conf * furo theme * Mostly a docs update (#61) * rename for clarity * docs major refresh * fix FA_AccF units in debug file * docs that build locally * remove gitmodules * furo theme * furo in requirements * move readthedocs config file, remove furo import in conf.py * add docs requirements file * typo * move index out of source folder * trying to get furo to work * import date * fix versions and titles, cleanup readthedocs requirements * typo fix, remove extras * more cleanup * bump version * no furo extension, "hack" to load RT version * proper toctree paths * specify method * add mock modules * fix typos * update python install requirements * running locally * move index to main docs dir again * update to build locally * error during warnings * automated version * cleanup * remove old docs * re-add docs * simplify * fix figure path * try alabaster * remove archived docs * use sphinx-rtd-theme * master doc and sphinx rtd theme * index back to root folder * only ignore install folders * remove hidden toctree * furo theme * update paths * convert rt version to string * update sphinx settings * move conf * furo theme * Pass through Kp_float = 0 (#59) * Pass through kp_float, if desired * Minor fixes: schema error and InputReader defaults * Allow pass through of Kp_float = 0 * Add flp parameters to schema * Change Fl_Mode default to 0 * Add defaults to omega_,zeta_ pc and vs, allow to be numbers * Allow single pitch tuning values in code, default U_pc to 0 * use nac acceleration for floating feedback * Fix TSR saturation for region 2.5operation * Modify system for constant power operation * Only modify pole for constant power above-rated * Remove GenEff from K calc * Update tuning, use constant power * use load_rosco_yaml * constant power * Fix broken tests * Include Fl_Mode=2 for nacelle pitching feedback * Add FOCAL inputs - hpf on floating feedback - lpf on wind speed estimator - associated schema updates * Set notch and check frequencies when Fl_Mode = 1 (fixes bug) * Skip filter step if there's an error * Update IEA-15MW test case DISCON with focal inputs * Allow Fl_Mode = 2 in ROSCO * Pass through lpf frequency * Add FOCAL tuning yaml * Set Cp contour number of levels * Add FOCAL params to various writers * Update/tune focal yaml * Add scripts for running FAST, tuning various parameters and cases * Add notebook for FAST plotting * Set up step case for testing * Change doubles to C_doubles * Define real and integer kinds, assign to all of ROSCO * Add ADJUSTL to DISCON error message * Fix Fl_Mode == 2 * Fix Fl_Mode == 2 again * Call yaw, flap, and debug only if enabled in DISOCN.IN * Make avrSWAP a ReKi and set constant kinds * Add DISCONs for testing - revert this later * Fix DISCON comparison, before DISCON's were overwritten by model * Rename DEBUG2.dbg to RootName.dbg2 * Update TestCase DISCONs to new input file * Add API change page in docs * Add link to API change on main page * Fix table headers * Fix title underlines * Fix tables again * Fix tables again * Fix version numbering in docs * Simplify FAST_directory in run_FAST * Versioning (#65) * use sphinx-rtd-theme * master doc and sphinx rtd theme * index back to root folder * only ignore install folders * remove hidden toctree * furo theme * update paths * convert rt version to string * update sphinx settings * move conf * furo theme * remove git versioning from cmake * use hard coded rosco_version * update intro write method * set nowrap for intel compilers * Add transfer of error message and clear message after each call * update install instructions * Catch nans in ROSCO at end of WSE * fix conda install typo * cleanup docs * Rename DEBUG2.dbg to RootName.dbg2 * Fix Fl_Mode == 2 * Fix Fl_Mode == 2 again * Allow Fl_Mode = 2 in ROSCO * Set notch and check frequencies when Fl_Mode = 1 (fixes bug) * Update FOCAL tuning yaml * Update TSR * Clean up and doc fix * Remove publish to pypi * Define all constant inputs to functions with kind typing * Generate Test_Case/ inputs automatically * Fix IEA15 DISCON path * Fix example 11 paths * Auto-generate tuning input yaml using schema * Add toolbox_input to doc index * Add toctree * Re-name title of toolbox_input Co-authored-by: Nikhar Abbas Co-authored-by: Xianping Du <38188001+Seager1989@users.noreply.github.com> Co-authored-by: nikhar-abbas <40865984+nikhar-abbas@users.noreply.github.com> * update listcheck method for numpy arrays * Open Loop Control (#98) * create rosco types yaml * Add more descriptions, add integer_c default, cleanup * updates for allocatability and shapes * python scripts to write ROSCO_types.f90 * reemove superfulous modules * use types from ROSCO registry * create rosco types yaml * Add more descriptions, add integer_c default, cleanup * updates for allocatability and shapes * python scripts to write ROSCO_types.f90 * reemove superfulous modules * use types from ROSCO registry * Saturate inputs to WSE. Needs some TLC, but seems to work * Reduce saturation limits on speed, torque * Re-organize, set saturation limits. Working at 3 m/s * Initial add of OL control to ROSCO: builds * Update DISCONs with open loop inputs * Fix file reading for OL_Filename * Add open loop control generation and file writing * Use DISCON_dict for more manageable DISCON file writing * Add open loop example, fix constant timeseries * Make open loop example generate power * Handle relative paths and calling from outside the run directory: - Some helper functions borrowed from OpenFAST, f/ext_control - Updated file writing * Clean up: versions, print statements * Fix SysFiles paths in CMakeLists * Tidy up Ext_DLL names * More Ext_DLL name tidying * Test write_registry.py * Update for OL Control * Move preprocessor lines * add zenodo DOI * Regenerated Types * fix shape * revert filepath change * give all types a size, ProcAddr size = 3 * update types * test registry in compile step * specify default shell * update write_registry path * remove default shell * Document API changes, provide OL input example * Fix example 14 (yaw input) * Add error catching to yaw control * Tidy up OL_Input Reading: error catching, generalize * More yaw control fixes, to model * Checkout develop CMakeLists for ROSCO * Update DISCON.INs for TestCases/ * Revert "Checkout develop CMakeLists for ROSCO" This reverts commit 87a491359d73806e3aaa59b4cfdc00f2838875df. * Revert windows cmake stuff to develop * Fix CMake again * Revert "Revert windows cmake stuff to develop" This reverts commit 39df122449b0e2055f2e12e3ce38a0c010c7bd91. * Make last cmake fix - hopefully Co-authored-by: Nikhar Abbas * Restart & registry (#99) * Convert WE saved variables to WE type * Put restart flag in localvars * Use saved filter params from LocalVar * save pitcomt last * Move IPC saved variables to localvars * Saved pi controller variables to localvar * Save RootMyb_Last to localvar * ROSCO_IO - initial commit. Include restart and debug functions * Use ROSCO IO and call restart functions * Remove debug from function.f90 * Save ACC Infile info * update for restart capabilities * add rosco_io with restart and debug functions * cleanup debug call * use registry generate types and IO * delete DFController * fix timestep mismatch * remove unnecessaray istatus check * close files * add reg test for restart * add restart option to run_openfast * add testing to CI, ignore generate files * fix fastcall * remove extra commas * specify gfortran-10 * testing flag cleanup * Use lv_strings to generate debug output * Revert "testing flag cleanup" This reverts commit 6f295563832413e96347acd82716f9aadac6d46c. * Revert "specify gfortran-10" This reverts commit 4c3154491523bcd542133ca2bce5803cdc94523f. * minor cleanup * Use kind from constants * Add some comments for clarity * put debug in if statements * separate reg tests from oother tests * Fl_Mode>0 * Remove hard coded values * Add filtered signals and WE_Vw to debug varrs * cd for regtest * Check logging level before calling debug * add fl_pitcom and pc_minpit to debugvars Co-authored-by: dzalkind * Break up if statement in open loop pitch (#100) * Break up if statement in open loop pitch * Make torque and yaw consistent with pitch: can start after some time * add bld edgewise freq to robust dict_inputs * Fix ccrotor inputs (#104) * remove interpolation of blade chord and twist * rename aerodynblade inputs * Update surface and DISCON.INs * Fix performance table paths * Allow default inputs (#110) * Allow defaults for AeroDyn inputs * Allow AeroDyn inputs to be floats, too * ipc (#105) * remove interpolation of blade chord and twist * rename aerodynblade inputs * Update surface and DISCON.INs * Fix performance table paths * Add proportional control and cleanup IPC * Add IPC and filtered RootMyc to registry * Better logic for filtering RootMOOP and fix notch filter slopes bug * Add cyclic flap conrol * Fix comments in ColemanTransformInverse * Addd IPC_KP to DISCON.IN * Error checking foro flp or ipc * add mutichannel plotting with tuples * add CMakeFiles to gitignore * Add IPC_KP to api changes * numerical qualifiers for error handling * add IPC gains to schema for pass-through ability * fix variable names * fix ipc gain printing bug * make sure IPC_KP is positive * Update Polars to point to coord files * ignore dbg2 files * Add IEA15MW_OL.yaml * update coord reader/writer * expand pitch_initial to 30 degrees * Add example 13 for IPC * Update cp surfaces and DISCONS * add examples to readme * cleanup and streaamline run_examples * Add IPC tuning vars * Allow IPC to command pitch value below peak shaving saturation limit * shorten simulation time * Fix Material parameter path * Update DISCONs again * Fix OL_Input reading * Set wind speed, rotor speed IC in example 14 * Debug OL reading * Add more debugging lines * Add more debugging lines 2 * Clean up, hone in on debug call * Disable logging level * Update discons - resolve conflict * Print when finished with ROSCO * add control packageg * Use PriPath and RootName to name dbg files * Print AvrSWAP * Revert "Use PriPath and RootName to name dbg files" This reverts commit 062fcaa55b3bf42d44f8a3f163aa883ab9552412. * Disable other examples * Print OL inputs * Allow logging level 3 * Print OL inputs * Make example shorter * Print more stuf * Print shape * Revert "Print OL inputs" This reverts commit 8e2a642bb35e46850f579ca4e69ca6d6fc93f4cc. * Update ROSCO Simulink model with IPC example * refactor flap tuning for normalization methods * improved flap controller filtering * delete extra F_FlpCornerFrerq * Update inputs, reader, and writer for OF 3.1.0 * Make sigma default interp type for multi_sigma * Use openfast 3.1.0 in CI * Fix leak...maybe * Use OF 3.1.0 in testing * Use gfotran for compile * Clean up print statements * Re-enable all examples * Update NREL-5MW AD file * Only check airfoil controls if more than one table * Update BAR models * Revert "Use gfotran for compile" This reverts commit 5a6e2b7e30287a09a09781e2ba12f9b578132e1f. * Install pyFAST for CI * Fix some paths in ex12 * Disable example 12 * Fix example 12 linear path, re-enable * Skip compilers install for mac * Try gfortran-9, no compilers * Try gfortran-10, no compilers * Skip windows compile in pytools * Re-enable windows, use gfortran as FC * Unset FC in windows * Set environment for windows when dependencies installed * Try setting environment in installation * Put conditional env setting in correct place * Try in setup again * Break up tasks: Windows vs. not * Update DISCONs * Update docs with new variables * Add example documentation * Update ROSCO Simulink model for 3.1.0 * Make IEA model float again * Reduce IEA timestep * Match DT to checkpoint time Co-authored-by: dzalkind * Increment version number * Bladed docs (#116) * Added image of Bladed control screen setup * Delete Bladed control screen.png * Adding image of Bladed control screen * Add files via upload * Minor edit 1 * Minor change 2 * Minor change 3 * Minor change 4 * Change 6 * Change 7 * Change 8 * Minor change 9 Co-authored-by: nikhar-abbas <40865984+nikhar-abbas@users.noreply.github.com> Co-authored-by: WillC-DNV <100850534+WillC-DNV@users.noreply.github.com> * Update version in API change docs * Bladed readthedocs (#117) * Added image of Bladed control screen setup * Delete Bladed control screen.png * Adding image of Bladed control screen * Add files via upload * Minor edit 1 * Minor change 2 * Minor change 3 * Minor change 4 * Change 6 * Change 7 * Change 8 * Minor change 9 * Tinker with characters in bladed instructions * Add bladed instructions to index * Change bladed toctree label * Do underline stuff * Make toctree label same as file * Remove colons from headers Co-authored-by: nikhar-abbas <40865984+nikhar-abbas@users.noreply.github.com> Co-authored-by: WillC-DNV <100850534+WillC-DNV@users.noreply.github.com> * Update docs to reflect CI process Co-authored-by: Nikhar Abbas Co-authored-by: Xianping Du <38188001+Seager1989@users.noreply.github.com> Co-authored-by: nikhar-abbas <40865984+nikhar-abbas@users.noreply.github.com> Co-authored-by: WillC-DNV <100850534+WillC-DNV@users.noreply.github.com> * Fixed wrong formatting of list items (#122) extra newline required between list elements * Flip Ct and Cq table allocation (#129) * Clean up merge and regen discons Co-authored-by: nikhar-abbas <40865984+nikhar-abbas@users.noreply.github.com> Co-authored-by: Nikhar Abbas Co-authored-by: Xianping Du <38188001+Seager1989@users.noreply.github.com> Co-authored-by: WillC-DNV <100850534+WillC-DNV@users.noreply.github.com> Co-authored-by: Gustavo Hylander <74593034+ghylander@users.noreply.github.com> * Clean up merge and regen discons * adding a pitch actuator error * code clean up and added params to writer * renaming as 'pitch fault' and using arrays for offsets * Re-run registry, update modes in controller.py, re-gen inputs * Fix file writing: space after PF section * Add offset test in run_FAST * Enable PF_Mode in test * Regen discons after adding newline * typo * increased significant figures for pitch fault offset * Update docs, input file writing with minor edits before 2.6.0 * Making ROSCO 'blind' to the pitch fault * PitCom changed to PitComAct * Regenerate inputs, types, docs with new API * Error -> Faults * Add pitch offset example, test * Throw error if PF_Mode = 1 and IPC not enabled in ServoDyn * Tidy example 18 * Regen discons * Document API change * Set last blade pitch to PitCom, not PitComAct * Give ratelimit it's own memory of last signal * Make current pitch angle PitComAct again * Get rid of PitComAct_Last * Revert Matlab changes to develop Co-authored-by: dzalkind <65573423+dzalkind@users.noreply.github.com> Co-authored-by: Nikhar Abbas Co-authored-by: Xianping Du <38188001+Seager1989@users.noreply.github.com> Co-authored-by: nikhar-abbas <40865984+nikhar-abbas@users.noreply.github.com> Co-authored-by: dzalkind Co-authored-by: WillC-DNV <100850534+WillC-DNV@users.noreply.github.com> Co-authored-by: Gustavo Hylander <74593034+ghylander@users.noreply.github.com> Co-authored-by: Mayank Chetan --- Examples/example_16.py | 2 +- Examples/example_18.py | 84 +++++++++++++++++++ Examples/run_examples.py | 1 + ROSCO/rosco_registry/rosco_types.yaml | 26 +++++- ROSCO/src/Controllers.f90 | 16 +++- ROSCO/src/DISCON.F90 | 2 +- ROSCO/src/Functions.f90 | 37 ++++++-- ROSCO/src/ROSCO_IO.f90 | 4 + ROSCO/src/ROSCO_Types.f90 | 10 ++- ROSCO/src/ReadSetParameters.f90 | 37 ++++++-- ROSCO_toolbox/controller.py | 1 + ROSCO_toolbox/inputs/toolbox_schema.yaml | 12 +++ ROSCO_toolbox/ofTools/case_gen/CaseLibrary.py | 9 ++ ROSCO_toolbox/ofTools/case_gen/run_FAST.py | 4 +- ROSCO_toolbox/utilities.py | 10 ++- Test_Cases/BAR_10/BAR_10_DISCON.IN | 10 ++- .../DISCON-UMaineSemi.IN | 10 ++- .../IEA-15-240-RWT-UMaineSemi_ElastoDyn.dat | 2 + Test_Cases/NREL-5MW/DISCON.IN | 10 ++- docs/source/api_change.rst | 23 ++++- docs/source/toolbox_input.rst | 14 +++- 21 files changed, 285 insertions(+), 39 deletions(-) create mode 100644 Examples/example_18.py diff --git a/Examples/example_16.py b/Examples/example_16.py index 96268013..fbd45d82 100644 --- a/Examples/example_16.py +++ b/Examples/example_16.py @@ -48,7 +48,7 @@ def main(): controller_params['DISCON']['DLL_InFile'] = os.path.join(rosco_dir,'Test_Cases/NREL-5MW/DISCON.IN') controller_params['DISCON']['DLL_ProcName'] = 'DISCON' - # RAAW FAD set up + # simulation set up r = run_FAST_ROSCO() r.tuning_yaml = parameter_filename r.wind_case_fcn = cl.simp_step diff --git a/Examples/example_18.py b/Examples/example_18.py new file mode 100644 index 00000000..89c6ca54 --- /dev/null +++ b/Examples/example_18.py @@ -0,0 +1,84 @@ +''' +----------- Example_18 ------------------------ +Run openfast with ROSCO and pitch offset faults +----------------------------------------------- + +Set up and run simulation with pitch offsets, check outputs + +''' + +import os, platform +from ROSCO_toolbox.ofTools.case_gen.run_FAST import run_FAST_ROSCO +from ROSCO_toolbox.ofTools.case_gen import CaseLibrary as cl +from ROSCO_toolbox.ofTools.fast_io import output_processing +import numpy as np + + +#directories +this_dir = os.path.dirname(os.path.abspath(__file__)) +rosco_dir = os.path.dirname(this_dir) +example_out_dir = os.path.join(this_dir,'examples_out') +os.makedirs(example_out_dir,exist_ok=True) + +if platform.system() == 'Windows': + lib_name = os.path.realpath(os.path.join(this_dir, '../ROSCO/build/libdiscon.dll')) +elif platform.system() == 'Darwin': + lib_name = os.path.realpath(os.path.join(this_dir, '../ROSCO/build/libdiscon.dylib')) +else: + lib_name = os.path.realpath(os.path.join(this_dir, '../ROSCO/build/libdiscon.so')) + + +def main(): + + # Input yaml and output directory + parameter_filename = os.path.join(rosco_dir,'Tune_Cases/IEA15MW.yaml') + run_dir = os.path.join(example_out_dir,'18_PitchFaults') + os.makedirs(run_dir,exist_ok=True) + + # Set DISCON input dynamically through yaml/dict + controller_params = {} + controller_params['PF_Mode'] = 1 # Set pitch fault mode to pitch offsets + controller_params['DISCON'] = {} + + pitch2_offset = 1 # deg + pitch3_offset = -2 # deg + controller_params['DISCON']['PF_Offsets'] = [0.,float(np.radians(pitch2_offset)),float(np.radians(pitch3_offset))] + + # simulation set up + r = run_FAST_ROSCO() + r.tuning_yaml = parameter_filename + r.wind_case_fcn = cl.simp_step # single step wind input + r.wind_case_opts = { + 'U_start': [10], # from 10 to 15 m/s + 'U_end': [15], + 'wind_dir': run_dir, + 'T_step': 50, # step at 50 sec + 'T_Max': 100 # simulation is 100 sec + } + r.case_inputs = {} + r.case_inputs[("ServoDyn","Ptch_Cntrl")] = {'vals':[1], 'group':0} # Individual pitch control must be enabled in ServoDyn + r.controller_params = controller_params + r.save_dir = run_dir + + r.run_FAST() + + + # Check pitch offsets + filenames = [os.path.join(run_dir,'IEA15MW/simp_step/base/IEA15MW_0.outb')] + fast_out = output_processing.output_processing() + + # Load and plot + fastout = fast_out.load_fast_out(filenames) + offset_2 = fastout[0]['BldPitch2'] - fastout[0]['BldPitch1'] + offset_3 = fastout[0]['BldPitch3'] - fastout[0]['BldPitch1'] + + # check that offset (min,max) is very close to prescribed values + np.testing.assert_almost_equal(offset_2.max(),pitch2_offset,decimal=3) + np.testing.assert_almost_equal(offset_2.min(),pitch2_offset,decimal=3) + np.testing.assert_almost_equal(offset_3.max(),pitch3_offset,decimal=3) + np.testing.assert_almost_equal(offset_3.max(),pitch3_offset,decimal=3) + + + +if __name__=="__main__": + main() \ No newline at end of file diff --git a/Examples/run_examples.py b/Examples/run_examples.py index 56b47208..fc570081 100644 --- a/Examples/run_examples.py +++ b/Examples/run_examples.py @@ -21,6 +21,7 @@ 'example_15', 'example_16', 'example_17', # NJA: only runs on unix in CI + 'example_18', ] def execute_script(fscript): diff --git a/ROSCO/rosco_registry/rosco_types.yaml b/ROSCO/rosco_registry/rosco_types.yaml index ea78a05c..f3ac8ddd 100644 --- a/ROSCO/rosco_registry/rosco_types.yaml +++ b/ROSCO/rosco_registry/rosco_types.yaml @@ -430,7 +430,16 @@ ControlParameters: PA_Damping: <<: *real description: Pitch actuator damping ratio [-, unused if PA_Mode = 1] - + + # Pitch actuator error + PF_Mode: + <<: *integer + description: Pitch actuator fault mode {0 - not used, 1 - offsets on one or more blades} + PF_Offsets: + <<: *real + description: Pitch actuator fault offsets for blade 1-3 [rad/s] + allocatable: True + # External Control Ext_Mode: <<: *integer @@ -643,6 +652,12 @@ FilterParameters: dimension: (99) description: Notch filter denominator coefficient 0 +rlParams: + LastSignal: + <<: *real + dimension: (99) + description: Last input signal + piParams: ITerm: <<: *real @@ -811,7 +826,7 @@ LocalVariables: size: 3 PitComAct: <<: *real - description: Actuated pitch of each blade the last time the controller was called [rad]. + description: Actuated pitch command of each blade [rad]. size: 3 SS_DelOmegaF: <<: *real @@ -902,6 +917,10 @@ LocalVariables: <<: *derived_type id: piParams description: PI parameters derived type + rlP: + <<: *derived_type + id: rlParams + description: Rate limiter parameters derived type ObjectInstances: instLPF: @@ -922,6 +941,9 @@ ObjectInstances: instPI: <<: *integer description: PI controller instance + instRL: + <<: *integer + description: Rate limiter instance PerformanceData: TSR_vec: diff --git a/ROSCO/src/Controllers.f90 b/ROSCO/src/Controllers.f90 index 7568d4df..8e54b586 100644 --- a/ROSCO/src/Controllers.f90 +++ b/ROSCO/src/Controllers.f90 @@ -96,7 +96,7 @@ SUBROUTINE PitchControl(avrSWAP, CntrPar, LocalVar, objInst, DebugVar, ErrVar) ! Saturate collective pitch commands: LocalVar%PC_PitComT = saturate(LocalVar%PC_PitComT, LocalVar%PC_MinPit, CntrPar%PC_MaxPit) ! Saturate the overall command using the pitch angle limits - LocalVar%PC_PitComT = ratelimit(LocalVar%PC_PitComT, LocalVar%PC_PitComT_Last, CntrPar%PC_MinRat, CntrPar%PC_MaxRat, LocalVar%DT) ! Saturate the overall command of blade K using the pitch rate limit + LocalVar%PC_PitComT = ratelimit(LocalVar%PC_PitComT, CntrPar%PC_MinRat, CntrPar%PC_MaxRat, LocalVar%DT, LocalVar%restart, LocalVar%rlP,objInst%instRL) ! Saturate the overall command of blade K using the pitch rate limit LocalVar%PC_PitComT_Last = LocalVar%PC_PitComT ! Combine and saturate all individual pitch commands in software @@ -105,7 +105,7 @@ SUBROUTINE PitchControl(avrSWAP, CntrPar, LocalVar, objInst, DebugVar, ErrVar) LocalVar%PitCom(K) = saturate(LocalVar%PitCom(K), LocalVar%PC_MinPit, CntrPar%PC_MaxPit) ! Saturate the command using the pitch satauration limits LocalVar%PitCom(K) = LocalVar%PitCom(K) + LocalVar%IPC_PitComF(K) ! Add IPC LocalVar%PitCom(K) = saturate(LocalVar%PitCom(K), LocalVar%PC_MinPit, CntrPar%PC_MaxPit) ! Saturate the command using the absolute pitch angle limits - LocalVar%PitCom(K) = ratelimit(LocalVar%PitCom(K), LocalVar%BlPitch(K), CntrPar%PC_MinRat, CntrPar%PC_MaxRat, LocalVar%DT) ! Saturate the overall command of blade K using the pitch rate limit + LocalVar%PitCom(K) = ratelimit(LocalVar%PitCom(K), CntrPar%PC_MinRat, CntrPar%PC_MaxRat, LocalVar%DT, LocalVar%restart, LocalVar%rlP,objInst%instRL) ! Saturate the overall command of blade K using the pitch rate limit END DO ! Open Loop control, use if @@ -136,9 +136,17 @@ SUBROUTINE PitchControl(avrSWAP, CntrPar, LocalVar, objInst, DebugVar, ErrVar) ! Saturate the pitch command using the overall (hardware) limit LocalVar%PitComAct(K) = saturate(LocalVar%PitComAct(K), LocalVar%PC_MinPit, CntrPar%PC_MaxPit) ! Saturate the overall command of blade K using the pitch rate limit - LocalVar%PitComAct(K) = ratelimit(LocalVar%PitComAct(K), LocalVar%BlPitch(K), CntrPar%PC_MinRat, CntrPar%PC_MaxRat, LocalVar%DT) ! Saturate the overall command of blade K using the pitch rate limit + LocalVar%PitComAct(K) = ratelimit(LocalVar%PitComAct(K), CntrPar%PC_MinRat, CntrPar%PC_MaxRat, LocalVar%DT, LocalVar%restart, LocalVar%rlP,objInst%instRL) ! Saturate the overall command of blade K using the pitch rate limit END DO + ! Add pitch actuator fault for blade K + IF (CntrPar%PF_Mode == 1) THEN + DO K = 1, LocalVar%NumBl + ! This assumes that the pitch actuator fault overides the Hardware saturation + LocalVar%PitComAct(K) = LocalVar%PitComAct(K) + CntrPar%PF_Offsets(K) + END DO + END IF + ! Command the pitch demanded from the last ! call to the controller (See Appendix A of Bladed User's Guide): avrSWAP(42) = LocalVar%PitComAct(1) ! Use the command angles of all blades if using individual pitch @@ -222,7 +230,7 @@ SUBROUTINE VariableSpeedControl(avrSWAP, CntrPar, LocalVar, objInst, ErrVar) LocalVar%GenTq = MIN(LocalVar%GenTq, CntrPar%VS_MaxTq) ! Saturate the command using the maximum torque limit ! Saturate the commanded torque using the torque rate limit: - LocalVar%GenTq = ratelimit(LocalVar%GenTq, LocalVar%VS_LastGenTrq, -CntrPar%VS_MaxRat, CntrPar%VS_MaxRat, LocalVar%DT) ! Saturate the command using the torque rate limit + LocalVar%GenTq = ratelimit(LocalVar%GenTq, -CntrPar%VS_MaxRat, CntrPar%VS_MaxRat, LocalVar%DT, LocalVar%restart, LocalVar%rlP,objInst%instRL) ! Saturate the command using the torque rate limit ! Open loop torque control IF ((CntrPar%OL_Mode == 1) .AND. (CntrPar%Ind_GenTq > 0)) THEN diff --git a/ROSCO/src/DISCON.F90 b/ROSCO/src/DISCON.F90 index 2b2ec286..1e5e5421 100644 --- a/ROSCO/src/DISCON.F90 +++ b/ROSCO/src/DISCON.F90 @@ -79,7 +79,7 @@ SUBROUTINE DISCON(avrSWAP, aviFAIL, accINFILE, avcOUTNAME, avcMSG) BIND (C, NAME END IF ! Read avrSWAP array into derived types/variables -CALL ReadAvrSWAP(avrSWAP, LocalVar) +CALL ReadAvrSWAP(avrSWAP, LocalVar, CntrPar) ! Set Control Parameters CALL SetParameters(avrSWAP, accINFILE, SIZE(avcMSG), CntrPar, LocalVar, objInst, PerfData, zmqVar, ErrVar) diff --git a/ROSCO/src/Functions.f90 b/ROSCO/src/Functions.f90 index af9a0c2c..eca51839 100644 --- a/ROSCO/src/Functions.f90 +++ b/ROSCO/src/Functions.f90 @@ -48,21 +48,40 @@ REAL(DbKi) FUNCTION saturate(inputValue, minValue, maxValue) END FUNCTION saturate !------------------------------------------------------------------------------------------------------------------------------- - REAL(DbKi) FUNCTION ratelimit(inputSignal, inputSignalPrev, minRate, maxRate, DT) + REAL(DbKi) FUNCTION ratelimit(inputSignal, minRate, maxRate, DT, reset, rlP, inst) ! Saturates inputValue. Makes sure it is not smaller than minValue and not larger than maxValue + USE ROSCO_Types, ONLY : rlParams + + IMPLICIT NONE - REAL(DbKi), INTENT(IN) :: inputSignal - REAL(DbKi), INTENT(IN) :: inputSignalPrev - REAL(DbKi), INTENT(IN) :: minRate - REAL(DbKi), INTENT(IN) :: maxRate - REAL(DbKi), INTENT(IN) :: DT + REAL(DbKi), INTENT(IN) :: inputSignal + REAL(DbKi), INTENT(IN) :: minRate + REAL(DbKi), INTENT(IN) :: maxRate + REAL(DbKi), INTENT(IN) :: DT + LOGICAL, INTENT(IN) :: reset + TYPE(rlParams), INTENT(INOUT) :: rlP + INTEGER(IntKi), INTENT(INOUT) :: inst + ! Local variables REAL(DbKi) :: rate - rate = (inputSignal - inputSignalPrev)/DT ! Signal rate (unsaturated) - rate = saturate(rate, minRate, maxRate) ! Saturate the signal rate - ratelimit = inputSignalPrev + rate*DT ! Saturate the overall command using the rate limit + IF (reset) THEN + rlP%LastSignal(inst) = inputSignal + ratelimit = inputSignal + + ELSE + rate = (inputSignal - rlP%LastSignal(inst))/DT ! Signal rate (unsaturated) + rate = saturate(rate, minRate, maxRate) ! Saturate the signal rate + + ratelimit = rlP%LastSignal(inst) + rate*DT + + rlP%LastSignal(inst) = ratelimit + + ENDIF + + ! Increment instance + inst = inst + 1 ! Saturate the overall command using the rate limit END FUNCTION ratelimit diff --git a/ROSCO/src/ROSCO_IO.f90 b/ROSCO/src/ROSCO_IO.f90 index d495263b..8ad72098 100644 --- a/ROSCO/src/ROSCO_IO.f90 +++ b/ROSCO/src/ROSCO_IO.f90 @@ -176,12 +176,14 @@ SUBROUTINE WriteRestartFile(LocalVar, CntrPar, ErrVar, objInst, RootName, size_a WRITE( Un, IOSTAT=ErrStat) LocalVar%piP%ITermLast WRITE( Un, IOSTAT=ErrStat) LocalVar%piP%ITerm2 WRITE( Un, IOSTAT=ErrStat) LocalVar%piP%ITermLast2 + WRITE( Un, IOSTAT=ErrStat) LocalVar%rlP%LastSignal WRITE( Un, IOSTAT=ErrStat) objInst%instLPF WRITE( Un, IOSTAT=ErrStat) objInst%instSecLPF WRITE( Un, IOSTAT=ErrStat) objInst%instHPF WRITE( Un, IOSTAT=ErrStat) objInst%instNotchSlopes WRITE( Un, IOSTAT=ErrStat) objInst%instNotch WRITE( Un, IOSTAT=ErrStat) objInst%instPI + WRITE( Un, IOSTAT=ErrStat) objInst%instRL Close ( Un ) ENDIF END SUBROUTINE WriteRestartFile @@ -356,12 +358,14 @@ SUBROUTINE ReadRestartFile(avrSWAP, LocalVar, CntrPar, objInst, PerfData, RootNa READ( Un, IOSTAT=ErrStat) LocalVar%piP%ITermLast READ( Un, IOSTAT=ErrStat) LocalVar%piP%ITerm2 READ( Un, IOSTAT=ErrStat) LocalVar%piP%ITermLast2 + READ( Un, IOSTAT=ErrStat) LocalVar%rlP%LastSignal READ( Un, IOSTAT=ErrStat) objInst%instLPF READ( Un, IOSTAT=ErrStat) objInst%instSecLPF READ( Un, IOSTAT=ErrStat) objInst%instHPF READ( Un, IOSTAT=ErrStat) objInst%instNotchSlopes READ( Un, IOSTAT=ErrStat) objInst%instNotch READ( Un, IOSTAT=ErrStat) objInst%instPI + READ( Un, IOSTAT=ErrStat) objInst%instRL Close ( Un ) ENDIF ! Read Parameter files diff --git a/ROSCO/src/ROSCO_Types.f90 b/ROSCO/src/ROSCO_Types.f90 index 46c26a09..115458ec 100644 --- a/ROSCO/src/ROSCO_Types.f90 +++ b/ROSCO/src/ROSCO_Types.f90 @@ -113,6 +113,8 @@ MODULE ROSCO_Types INTEGER(IntKi) :: PA_Mode ! Pitch actuator mode {0 - not used, 1 - first order filter, 2 - second order filter} REAL(DbKi) :: PA_CornerFreq ! Pitch actuator bandwidth/cut-off frequency [rad/s] REAL(DbKi) :: PA_Damping ! Pitch actuator damping ratio [-, unused if PA_Mode = 1] + INTEGER(IntKi) :: PF_Mode ! Pitch actuator fault mode {0 - not used, 1 - offsets on one or more blades} + REAL(DbKi), DIMENSION(:), ALLOCATABLE :: PF_Offsets ! Pitch actuator fault offsets for blade 1-3 [rad/s] INTEGER(IntKi) :: Ext_Mode ! External control mode (0 - not used, 1 - call external control library) CHARACTER(1024) :: DLL_FileName ! File name of external dynamic library CHARACTER(1024) :: DLL_InFile ! Name of input file called by dynamic library (DISCON.IN, e.g.) @@ -174,6 +176,10 @@ MODULE ROSCO_Types REAL(DbKi), DIMENSION(99) :: nf_a0 ! Notch filter denominator coefficient 0 END TYPE FilterParameters +TYPE, PUBLIC :: rlParams + REAL(DbKi), DIMENSION(99) :: LastSignal ! Last input signal +END TYPE rlParams + TYPE, PUBLIC :: piParams REAL(DbKi), DIMENSION(99) :: ITerm ! Integrator term REAL(DbKi), DIMENSION(99) :: ITermLast ! Previous integrator term @@ -228,7 +234,7 @@ MODULE ROSCO_Types REAL(DbKi) :: IPC_KP(2) ! Proportional gain for IPC, after ramp [-] INTEGER(IntKi) :: PC_State ! State of the pitch control system REAL(DbKi) :: PitCom(3) ! Commanded pitch of each blade the last time the controller was called [rad]. - REAL(DbKi) :: PitComAct(3) ! Actuated pitch of each blade the last time the controller was called [rad]. + REAL(DbKi) :: PitComAct(3) ! Actuated pitch command of each blade [rad]. REAL(DbKi) :: SS_DelOmegaF ! Filtered setpoint shifting term defined in setpoint smoother [rad/s]. REAL(DbKi) :: TestType ! Test variable, no use REAL(DbKi) :: VS_MaxTq ! Maximum allowable generator torque [Nm]. @@ -257,6 +263,7 @@ MODULE ROSCO_Types TYPE(WE) :: WE ! Wind speed estimator parameters derived type TYPE(FilterParameters) :: FP ! Filter parameters derived type TYPE(piParams) :: piP ! PI parameters derived type + TYPE(rlParams) :: rlP ! Rate limiter parameters derived type END TYPE LocalVariables TYPE, PUBLIC :: ObjectInstances @@ -266,6 +273,7 @@ MODULE ROSCO_Types INTEGER(IntKi) :: instNotchSlopes ! Notch filter slopes instance INTEGER(IntKi) :: instNotch ! Notch filter instance INTEGER(IntKi) :: instPI ! PI controller instance + INTEGER(IntKi) :: instRL ! Rate limiter instance END TYPE ObjectInstances TYPE, PUBLIC :: PerformanceData diff --git a/ROSCO/src/ReadSetParameters.f90 b/ROSCO/src/ReadSetParameters.f90 index a0ac9e38..7da9ebd7 100644 --- a/ROSCO/src/ReadSetParameters.f90 +++ b/ROSCO/src/ReadSetParameters.f90 @@ -26,11 +26,15 @@ MODULE ReadSetParameters CONTAINS ! ----------------------------------------------------------------------------------- ! Read avrSWAP array passed from ServoDyn - SUBROUTINE ReadAvrSWAP(avrSWAP, LocalVar) + SUBROUTINE ReadAvrSWAP(avrSWAP, LocalVar, CntrPar) USE ROSCO_Types, ONLY : LocalVariables, ZMQ_Variables REAL(ReKi), INTENT(INOUT) :: avrSWAP(*) ! The swap array, used to pass data to, and receive data from, the DLL controller. TYPE(LocalVariables), INTENT(INOUT) :: LocalVar + TYPE(ControlParameters), INTENT(IN) :: CntrPar + + ! Allocate Variables: + INTEGER(IntKi) :: K ! Index used for looping through blades. ! Load variables from calling program (See Appendix A of Bladed User's Guide): LocalVar%iStatus = NINT(avrSWAP(1)) @@ -57,9 +61,19 @@ SUBROUTINE ReadAvrSWAP(avrSWAP, LocalVar) LocalVar%BlPitch(2) = avrSWAP(33) LocalVar%BlPitch(3) = avrSWAP(34) ELSE - LocalVar%BlPitch(1) = LocalVar%PitCom(1) - LocalVar%BlPitch(2) = LocalVar%PitCom(2) - LocalVar%BlPitch(3) = LocalVar%PitCom(3) + + ! Subtract pitch actuator fault for blade K - This in a sense would make the controller blind to the pitch fault + IF (CntrPar%PF_Mode == 1) THEN + DO K = 1, LocalVar%NumBl + ! This assumes that the pitch actuator fault is hardware fault + LocalVar%BlPitch(K) = LocalVar%PitComAct(K) - CntrPar%PF_Offsets(K) ! why is PitCom used and not PitComAct?? + END DO + ELSE + LocalVar%BlPitch(1) = LocalVar%PitComAct(1) + LocalVar%BlPitch(2) = LocalVar%PitComAct(2) + LocalVar%BlPitch(3) = LocalVar%PitComAct(3) + END IF + ENDIF IF (LocalVar%iStatus == 0) THEN @@ -106,6 +120,7 @@ SUBROUTINE SetParameters(avrSWAP, accINFILE, size_avcMSG, CntrPar, LocalVar, obj objInst%instNotchSlopes = 1 objInst%instNotch = 1 objInst%instPI = 1 + objInst%instRL = 1 ! Set unused outputs to zero (See Appendix A of Bladed User's Guide): avrSWAP(35) = 1.0 ! Generator contactor status: 1=main (high speed) variable-speed generator @@ -245,6 +260,7 @@ SUBROUTINE ReadControlParameterFileSub(CntrPar, zmqVar, accINFILE, accINFILE_siz CALL ParseInput(UnControllerParameters,CurLine,'Flp_Mode',accINFILE(1),CntrPar%Flp_Mode,ErrVar) CALL ParseInput(UnControllerParameters,CurLine,'OL_Mode',accINFILE(1),CntrPar%OL_Mode,ErrVar) CALL ParseInput(UnControllerParameters,CurLine,'PA_Mode',accINFILE(1),CntrPar%PA_Mode,ErrVar) + CALL ParseInput(UnControllerParameters,CurLine,'PF_Mode',accINFILE(1),CntrPar%PF_Mode,ErrVar) CALL ParseInput(UnControllerParameters,CurLine,'Ext_Mode',accINFILE(1),CntrPar%Ext_Mode,ErrVar) CALL ParseInput(UnControllerParameters,CurLine,'ZMQ_Mode',accINFILE(1), CntrPar%ZMQ_Mode,ErrVar) @@ -389,6 +405,11 @@ SUBROUTINE ReadControlParameterFileSub(CntrPar, zmqVar, accINFILE, accINFILE_siz CALL ReadEmptyLine(UnControllerParameters,CurLine) CALL ParseInput(UnControllerParameters,CurLine,'PA_CornerFreq',accINFILE(1),CntrPar%PA_CornerFreq,ErrVar) CALL ParseInput(UnControllerParameters,CurLine,'PA_Damping',accINFILE(1),CntrPar%PA_Damping,ErrVar) + CALL ReadEmptyLine(UnControllerParameters,CurLine) + + !------------ Pitch Actuator Faults ------------ + CALL ReadEmptyLine(UnControllerParameters,CurLine) + CALL ParseAry(UnControllerParameters, CurLine,'PF_Offsets', CntrPar%PF_Offsets, 3, accINFILE(1), ErrVar) CALL ReadEmptyLine(UnControllerParameters,CurLine) !------------ External control interface ------------ @@ -996,7 +1017,13 @@ SUBROUTINE CheckInputs(LocalVar, CntrPar, avrSWAP, ErrVar, size_avcMSG) IF (NINT(avrSWAP(28)) == 0 .AND. ((CntrPar%IPC_ControlMode > 0) .OR. (CntrPar%Y_ControlMode > 1))) THEN ErrVar%aviFAIL = -1 - ErrVar%ErrMsg = 'IPC enabled, but Ptch_Cntrl in ServoDyn has a value of 0. Set it to 1.' + ErrVar%ErrMsg = 'IPC enabled, but Ptch_Cntrl in ServoDyn has a value of 0. Set it to 1 for individual pitch control.' + ENDIF + + ! PF_Mode = 1 + IF (NINT(avrSWAP(28)) == 0 .AND. (CntrPar%PF_Mode == 1)) THEN + ErrVar%aviFAIL = -1 + ErrVar%ErrMsg = 'Pitch offset fault enabled (PF_Mode = 1), but Ptch_Cntrl in ServoDyn has a value of 0. Set it to 1 for individual pitch control.' ENDIF ! DT diff --git a/ROSCO_toolbox/controller.py b/ROSCO_toolbox/controller.py index b4e3c353..f7cae56a 100644 --- a/ROSCO_toolbox/controller.py +++ b/ROSCO_toolbox/controller.py @@ -64,6 +64,7 @@ def __init__(self, controller_params): self.TD_Mode = controller_params['TD_Mode'] self.Flp_Mode = controller_params['Flp_Mode'] self.PA_Mode = controller_params['PA_Mode'] + self.PF_Mode = controller_params['PF_Mode'] self.Ext_Mode = controller_params['Ext_Mode'] self.ZMQ_Mode = controller_params['ZMQ_Mode'] diff --git a/ROSCO_toolbox/inputs/toolbox_schema.yaml b/ROSCO_toolbox/inputs/toolbox_schema.yaml index c3e0c80b..d88c346e 100644 --- a/ROSCO_toolbox/inputs/toolbox_schema.yaml +++ b/ROSCO_toolbox/inputs/toolbox_schema.yaml @@ -197,6 +197,12 @@ properties: maximum: 2 default: 0 description: Pitch actuator mode {0 - not used, 1 - first order filter, 2 - second order filter} + PF_Mode: + type: number + minimum: 0 + maximum: 1 + default: 0 + description: Pitch fault mode {0 - not used, 1 - constant offset on one or more blades} Ext_Mode: type: number minimum: 0 @@ -849,6 +855,12 @@ properties: type: string description: Name of procedure in DLL to be called default: DISCON + PF_Offsets: + type: array + items: + type: number + description: Pitch angle offsets for each blade (array with length of 3) + units: rad linmodel_tuning: type: object diff --git a/ROSCO_toolbox/ofTools/case_gen/CaseLibrary.py b/ROSCO_toolbox/ofTools/case_gen/CaseLibrary.py index 72fe0763..cc86785c 100644 --- a/ROSCO_toolbox/ofTools/case_gen/CaseLibrary.py +++ b/ROSCO_toolbox/ofTools/case_gen/CaseLibrary.py @@ -497,6 +497,15 @@ def sweep_ps_percent(start_group, **control_sweep_opts): return case_inputs_control +def test_pitch_offset(start_group, **control_sweep_opts): + case_inputs_control = {} + case_inputs_control[('DISCON_in','PF_Mode')] = {'vals': [1], 'group': start_group} + case_inputs_control[('DISCON_in','PF_Offsets')] = {'vals': [[0,float(np.radians(2)),0]], 'group': start_group} + return case_inputs_control + + + + # def sweep_pc_mode(cont_yaml,omega=np.linspace(.05,.35,8,endpoint=True).tolist(),zeta=[1.5],group=2): diff --git a/ROSCO_toolbox/ofTools/case_gen/run_FAST.py b/ROSCO_toolbox/ofTools/case_gen/run_FAST.py index a0c31925..4a65c0e5 100644 --- a/ROSCO_toolbox/ofTools/case_gen/run_FAST.py +++ b/ROSCO_toolbox/ofTools/case_gen/run_FAST.py @@ -227,8 +227,8 @@ def run_FAST(self): r.wind_case_opts = { 'U': [16], } - r.save_dir = '/Users/dzalkind/Projects/RAAW/RAAW_OpenFAST/outputs/IPC_play' - r.control_sweep_fcn = cl.sweep_ipc_gains + r.save_dir = '/Users/dzalkind/Tools/ROSCO/outputs/offset_test' + r.control_sweep_fcn = cl.test_pitch_offset elif sim_config == 9: diff --git a/ROSCO_toolbox/utilities.py b/ROSCO_toolbox/utilities.py index b68dd3a9..e4f55670 100644 --- a/ROSCO_toolbox/utilities.py +++ b/ROSCO_toolbox/utilities.py @@ -81,8 +81,9 @@ def write_DISCON(turbine, controller, param_file='DISCON.IN', txt_filename='Cp_C file.write('{0:<12d} ! Flp_Mode - Flap control mode {{0: no flap control, 1: steady state flap angle, 2: Proportional flap control, 2: Cyclic (1P) flap control}}\n'.format(int(rosco_vt['Flp_Mode']))) file.write('{0:<12d} ! OL_Mode - Open loop control mode {{0: no open loop control, 1: open loop control vs. time}}\n'.format(int(rosco_vt['OL_Mode']))) file.write('{0:<12d} ! PA_Mode - Pitch actuator mode {{0 - not used, 1 - first order filter, 2 - second order filter}}\n'.format(int(rosco_vt['PA_Mode']))) + file.write('{0:<12d} ! PF_Mode - Pitch fault mode {{0 - not used, 1 - constant offset on one or more blades}}\n'.format(int(rosco_vt['PF_Mode']))) file.write('{0:<12d} ! Ext_Mode - External control mode {{0 - not used, 1 - call external dynamic library}}\n'.format(int(rosco_vt['Ext_Mode']))) - file.write('{0:<12d} ! ZMQ_Mode - Fuse ZeroMQ interaface {{0: unused, 1: Yaw Control}}\n'.format(int(rosco_vt['ZMQ_Mode']))) + file.write('{0:<12d} ! ZMQ_Mode - Fuse ZeroMQ interface {{0: unused, 1: Yaw Control}}\n'.format(int(rosco_vt['ZMQ_Mode']))) file.write('\n') file.write('!------- FILTERS ----------------------------------------------------------\n') @@ -202,6 +203,9 @@ def write_DISCON(turbine, controller, param_file='DISCON.IN', txt_filename='Cp_C file.write('{:<014.5f} ! PA_CornerFreq - Pitch actuator bandwidth/cut-off frequency [rad/s]\n'.format(rosco_vt['PA_CornerFreq'])) file.write('{:<014.5f} ! PA_Damping - Pitch actuator damping ratio [-, unused if PA_Mode = 1]\n'.format(rosco_vt['PA_Damping'])) file.write('\n') + file.write('!------- Pitch Actuator Faults -----------------------------------------------------\n') + file.write('{} ! PF_Offsets - Constant blade pitch offsets for blades 1-3 [rad]\n'.format(''.join('{:<10.8f} '.format(rosco_vt['PF_Offsets'][i]) for i in range(3)))) + file.write('\n') file.write('!------- External Controller Interface -----------------------------------------------------\n') file.write('"{}" ! DLL_FileName - Name/location of the dynamic library in the Bladed-DLL format\n'.format(rosco_vt['DLL_FileName'])) file.write('"{}" ! DLL_InFile - Name of input file sent to the DLL (-)\n'.format(rosco_vt['DLL_InFile'])) @@ -393,6 +397,7 @@ def DISCON_dict(turbine, controller, txt_filename=None): DISCON_dict['TD_Mode'] = int(controller.TD_Mode) DISCON_dict['Flp_Mode'] = int(controller.Flp_Mode) DISCON_dict['OL_Mode'] = int(controller.OL_Mode) + DISCON_dict['PF_Mode'] = int(controller.PF_Mode) DISCON_dict['PA_Mode'] = int(controller.PA_Mode) DISCON_dict['Ext_Mode'] = int(controller.Ext_Mode) DISCON_dict['ZMQ_Mode'] = int(controller.ZMQ_Mode) @@ -503,9 +508,12 @@ def DISCON_dict(turbine, controller, txt_filename=None): DISCON_dict['PA_Mode'] = controller.PA_Mode DISCON_dict['PA_CornerFreq'] = controller.PA_CornerFreq DISCON_dict['PA_Damping'] = controller.PA_Damping + # ------- Pitch Actuator Fault ------- + DISCON_dict['PF_Offsets'] = [0.,0.,0.] # ------- Zero-MQ ------- DISCON_dict['ZMQ_CommAddress'] = "tcp://localhost:5555" DISCON_dict['ZMQ_UpdatePeriod'] = 2 + # Add pass through here for param, value in controller.controller_params['DISCON'].items(): DISCON_dict[param] = value diff --git a/Test_Cases/BAR_10/BAR_10_DISCON.IN b/Test_Cases/BAR_10/BAR_10_DISCON.IN index a2d09fa1..a3f8cb24 100644 --- a/Test_Cases/BAR_10/BAR_10_DISCON.IN +++ b/Test_Cases/BAR_10/BAR_10_DISCON.IN @@ -1,5 +1,5 @@ ! Controller parameter input file for the BAR_10 wind turbine -! - File written using ROSCO version 2.5.0 controller tuning logic on 07/22/22 +! - File written using ROSCO version 2.6.0 controller tuning logic on 09/20/22 !------- DEBUG ------------------------------------------------------------ 1 ! LoggingLevel - {0: write no debug files, 1: write standard output .dbg-file, 2: LoggingLevel 1 + ROSCO LocalVars (.dbg2) 3: LoggingLevel 2 + complete avrSWAP-array (.dbg3)} @@ -20,8 +20,9 @@ 2 ! Flp_Mode - Flap control mode {0: no flap control, 1: steady state flap angle, 2: Proportional flap control, 2: Cyclic (1P) flap control} 0 ! OL_Mode - Open loop control mode {0: no open loop control, 1: open loop control vs. time} 0 ! PA_Mode - Pitch actuator mode {0 - not used, 1 - first order filter, 2 - second order filter} +0 ! PF_Mode - Pitch fault mode {0 - not used, 1 - constant offset on one or more blades} 0 ! Ext_Mode - External control mode {0 - not used, 1 - call external dynamic library} -0 ! ZMQ_Mode - Fuse ZeroMQ interaface {0: unused, 1: Yaw Control} +0 ! ZMQ_Mode - Fuse ZeroMQ interface {0: unused, 1: Yaw Control} !------- FILTERS ---------------------------------------------------------- 0.81771 ! F_LPFCornerFreq - Corner frequency (-3dB point) in the low-pass filters, [rad/s] @@ -94,7 +95,7 @@ !------- YAW CONTROL ------------------------------------------------------ 0.00000 ! Y_uSwitch - Wind speed to switch between Y_ErrThresh. If zero, only the first value of Y_ErrThresh is used [m/s] -4.000000 8.000000 ! Y_ErrThresh - Yaw error threshold. Turbine begins to yaw when it passes this. If Y_uSwitch is zero, only the first value is used. [deg]. +4.000000 8.000000 ! Y_ErrThresh - Yaw error threshold/deadband. Turbine begins to yaw when it passes this. If Y_uSwitch is zero, only the first value is used. [deg]. 0.00870 ! Y_Rate - Yaw rate [rad/s] 0.00000 ! Y_MErrSet - Integrator saturation (maximum signal amplitude contribution to pitch from yaw-by-IPC), [rad] 0.00000 ! Y_IPC_IntSat - Integrator saturation (maximum signal amplitude contribution to pitch from yaw-by-IPC), [rad] @@ -135,6 +136,9 @@ 3.140000000000 ! PA_CornerFreq - Pitch actuator bandwidth/cut-off frequency [rad/s] 0.707000000000 ! PA_Damping - Pitch actuator damping ratio [-, unused if PA_Mode = 1] +!------- Pitch Actuator Faults ----------------------------------------------------- +0.00000000 0.00000000 0.00000000 ! PF_Offsets - Constant blade pitch offsets for blades 1-3 [rad] + !------- External Controller Interface ----------------------------------------------------- "unused" ! DLL_FileName - Name/location of the dynamic library in the Bladed-DLL format "unused" ! DLL_InFile - Name of input file sent to the DLL (-) diff --git a/Test_Cases/IEA-15-240-RWT-UMaineSemi/DISCON-UMaineSemi.IN b/Test_Cases/IEA-15-240-RWT-UMaineSemi/DISCON-UMaineSemi.IN index 3745fee9..c59453cc 100644 --- a/Test_Cases/IEA-15-240-RWT-UMaineSemi/DISCON-UMaineSemi.IN +++ b/Test_Cases/IEA-15-240-RWT-UMaineSemi/DISCON-UMaineSemi.IN @@ -1,5 +1,5 @@ ! Controller parameter input file for the IEA-15-240-RWT-UMaineSemi wind turbine -! - File written using ROSCO version 2.5.0 controller tuning logic on 07/22/22 +! - File written using ROSCO version 2.6.0 controller tuning logic on 09/20/22 !------- DEBUG ------------------------------------------------------------ 2 ! LoggingLevel - {0: write no debug files, 1: write standard output .dbg-file, 2: LoggingLevel 1 + ROSCO LocalVars (.dbg2) 3: LoggingLevel 2 + complete avrSWAP-array (.dbg3)} @@ -20,8 +20,9 @@ 0 ! Flp_Mode - Flap control mode {0: no flap control, 1: steady state flap angle, 2: Proportional flap control, 2: Cyclic (1P) flap control} 0 ! OL_Mode - Open loop control mode {0: no open loop control, 1: open loop control vs. time} 2 ! PA_Mode - Pitch actuator mode {0 - not used, 1 - first order filter, 2 - second order filter} +0 ! PF_Mode - Pitch fault mode {0 - not used, 1 - constant offset on one or more blades} 0 ! Ext_Mode - External control mode {0 - not used, 1 - call external dynamic library} -0 ! ZMQ_Mode - Fuse ZeroMQ interaface {0: unused, 1: Yaw Control} +0 ! ZMQ_Mode - Fuse ZeroMQ interface {0: unused, 1: Yaw Control} !------- FILTERS ---------------------------------------------------------- 1.00810 ! F_LPFCornerFreq - Corner frequency (-3dB point) in the low-pass filters, [rad/s] @@ -94,7 +95,7 @@ !------- YAW CONTROL ------------------------------------------------------ 0.00000 ! Y_uSwitch - Wind speed to switch between Y_ErrThresh. If zero, only the first value of Y_ErrThresh is used [m/s] -4.000000 8.000000 ! Y_ErrThresh - Yaw error threshold. Turbine begins to yaw when it passes this. If Y_uSwitch is zero, only the first value is used. [deg]. +4.000000 8.000000 ! Y_ErrThresh - Yaw error threshold/deadband. Turbine begins to yaw when it passes this. If Y_uSwitch is zero, only the first value is used. [deg]. 0.00870 ! Y_Rate - Yaw rate [rad/s] 0.00000 ! Y_MErrSet - Integrator saturation (maximum signal amplitude contribution to pitch from yaw-by-IPC), [rad] 0.00000 ! Y_IPC_IntSat - Integrator saturation (maximum signal amplitude contribution to pitch from yaw-by-IPC), [rad] @@ -135,6 +136,9 @@ 1.570800000000 ! PA_CornerFreq - Pitch actuator bandwidth/cut-off frequency [rad/s] 0.707000000000 ! PA_Damping - Pitch actuator damping ratio [-, unused if PA_Mode = 1] +!------- Pitch Actuator Faults ----------------------------------------------------- +0.00000000 0.00000000 0.00000000 ! PF_Offsets - Constant blade pitch offsets for blades 1-3 [rad] + !------- External Controller Interface ----------------------------------------------------- "unused" ! DLL_FileName - Name/location of the dynamic library in the Bladed-DLL format "unused" ! DLL_InFile - Name of input file sent to the DLL (-) diff --git a/Test_Cases/IEA-15-240-RWT-UMaineSemi/IEA-15-240-RWT-UMaineSemi_ElastoDyn.dat b/Test_Cases/IEA-15-240-RWT-UMaineSemi/IEA-15-240-RWT-UMaineSemi_ElastoDyn.dat index 07ca94c0..c0f6fbe7 100644 --- a/Test_Cases/IEA-15-240-RWT-UMaineSemi/IEA-15-240-RWT-UMaineSemi_ElastoDyn.dat +++ b/Test_Cases/IEA-15-240-RWT-UMaineSemi/IEA-15-240-RWT-UMaineSemi_ElastoDyn.dat @@ -120,6 +120,8 @@ True TabDelim - Use tab delimiters in text tabular output file? (fla OutList - The next line(s) contains a list of output parameters. See OutListParameters.xlsx for a listing of available output channels, (-) "Azimuth" "BldPitch1" +"BldPitch2" +"BldPitch3" "GenSpeed" "IPDefl1" "LSSGagMya" diff --git a/Test_Cases/NREL-5MW/DISCON.IN b/Test_Cases/NREL-5MW/DISCON.IN index b5a353ae..9abc9297 100644 --- a/Test_Cases/NREL-5MW/DISCON.IN +++ b/Test_Cases/NREL-5MW/DISCON.IN @@ -1,5 +1,5 @@ ! Controller parameter input file for the NREL-5MW wind turbine -! - File written using ROSCO version 2.5.0 controller tuning logic on 07/22/22 +! - File written using ROSCO version 2.6.0 controller tuning logic on 09/20/22 !------- DEBUG ------------------------------------------------------------ 1 ! LoggingLevel - {0: write no debug files, 1: write standard output .dbg-file, 2: LoggingLevel 1 + ROSCO LocalVars (.dbg2) 3: LoggingLevel 2 + complete avrSWAP-array (.dbg3)} @@ -20,8 +20,9 @@ 0 ! Flp_Mode - Flap control mode {0: no flap control, 1: steady state flap angle, 2: Proportional flap control, 2: Cyclic (1P) flap control} 0 ! OL_Mode - Open loop control mode {0: no open loop control, 1: open loop control vs. time} 0 ! PA_Mode - Pitch actuator mode {0 - not used, 1 - first order filter, 2 - second order filter} +0 ! PF_Mode - Pitch fault mode {0 - not used, 1 - constant offset on one or more blades} 0 ! Ext_Mode - External control mode {0 - not used, 1 - call external dynamic library} -0 ! ZMQ_Mode - Fuse ZeroMQ interaface {0: unused, 1: Yaw Control} +0 ! ZMQ_Mode - Fuse ZeroMQ interface {0: unused, 1: Yaw Control} !------- FILTERS ---------------------------------------------------------- 1.57080 ! F_LPFCornerFreq - Corner frequency (-3dB point) in the low-pass filters, [rad/s] @@ -94,7 +95,7 @@ !------- YAW CONTROL ------------------------------------------------------ 0.00000 ! Y_uSwitch - Wind speed to switch between Y_ErrThresh. If zero, only the first value of Y_ErrThresh is used [m/s] -4.000000 8.000000 ! Y_ErrThresh - Yaw error threshold. Turbine begins to yaw when it passes this. If Y_uSwitch is zero, only the first value is used. [deg]. +4.000000 8.000000 ! Y_ErrThresh - Yaw error threshold/deadband. Turbine begins to yaw when it passes this. If Y_uSwitch is zero, only the first value is used. [deg]. 0.00870 ! Y_Rate - Yaw rate [rad/s] 0.00000 ! Y_MErrSet - Integrator saturation (maximum signal amplitude contribution to pitch from yaw-by-IPC), [rad] 0.00000 ! Y_IPC_IntSat - Integrator saturation (maximum signal amplitude contribution to pitch from yaw-by-IPC), [rad] @@ -135,6 +136,9 @@ 3.140000000000 ! PA_CornerFreq - Pitch actuator bandwidth/cut-off frequency [rad/s] 0.707000000000 ! PA_Damping - Pitch actuator damping ratio [-, unused if PA_Mode = 1] +!------- Pitch Actuator Faults ----------------------------------------------------- +0.00000000 0.00000000 0.00000000 ! PF_Offsets - Constant blade pitch offsets for blades 1-3 [rad] + !------- External Controller Interface ----------------------------------------------------- "unused" ! DLL_FileName - Name/location of the dynamic library in the Bladed-DLL format "unused" ! DLL_InFile - Name of input file sent to the DLL (-) diff --git a/docs/source/api_change.rst b/docs/source/api_change.rst index 9efdd8db..c126598f 100644 --- a/docs/source/api_change.rst +++ b/docs/source/api_change.rst @@ -9,6 +9,23 @@ The changes are tabulated according to the line number, and flag name. The line number corresponds to the resulting line number after all changes are implemented. Thus, be sure to implement each in order so that subsequent line numbers are correct. +2.6.0 to develop +------------------------------- +Pitch Faults +- Constant pitch actuator offsets (PF_Mode = 1) + +====== ================= ====================================================================================================================================================================================================== +New in ROSCO develop +---------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- +Line Input Name Example Value +====== ================= ====================================================================================================================================================================================================== +23 PF_Mode 0 ! PF_Mode - Pitch fault mode {0 - not used, 1 - constant offset on one or more blades} +139 PF_Section !------- Pitch Actuator Faults --------------------------------------------------------- +140 PF_Offsets 0.00000000 0.00000000 0.00000000 ! PF_Offsets - Constant blade pitch offsets for blades 1-3 [rad] +141 Empty Line +====== ================= ====================================================================================================================================================================================================== + + 2.5.0 to 2.6.0 ------------------------------- IPC @@ -27,7 +44,7 @@ Updated yaw control - Filter wind direction with deadband, and yaw until direction error changes signs (https://iopscience.iop.org/article/10.1088/1742-6596/1037/3/032011) ====== ================= ====================================================================================================================================================================================================== -New in ROSCO develop +New in ROSCO 2.6.0 ---------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- Line Input Name Example Value ====== ================= ====================================================================================================================================================================================================== @@ -54,7 +71,7 @@ Line Input Name Example Value ====== ================= ====================================================================================================================================================================================================== ====== ================= ====================================================================================================================================================================================================== -Modified in ROSCO develop +Modified in ROSCO 2.6.0 ---------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- Line Input Name Example Value ====== ================= ====================================================================================================================================================================================================== @@ -64,7 +81,7 @@ Line Input Name Example Value ====== ================= ====================================================================================================================================================================================================== ====== ================= ====================================================================================================================================================================================================== -Removed in ROSCO develop +Removed in ROSCO 2.6.0 ---------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- Line Input Name Example Value ====== ================= ====================================================================================================================================================================================================== diff --git a/docs/source/toolbox_input.rst b/docs/source/toolbox_input.rst index a3b47729..9ac78581 100644 --- a/docs/source/toolbox_input.rst +++ b/docs/source/toolbox_input.rst @@ -9,7 +9,7 @@ ROSCO_Toolbox tuning .yaml Definition of inputs for ROSCO tuning procedure -toolbox_schema. +/Users/dzalkind/Tools/ROSCO/ROSCO_toolbox/inputs/toolbox_schema. @@ -256,6 +256,15 @@ controller_params *Minimum* = 0 *Maximum* = 2 +:code:`PF_Mode` : Float + Pitch fault mode {0 - not used, 1 - constant offset on one or more + blades} + + *Default* = 0 + + *Minimum* = 0 *Maximum* = 1 + + :code:`Ext_Mode` : Float External control mode {{0 - not used, 1 - call external dynamic library}} @@ -909,6 +918,9 @@ These are pass-through parameters for the DISCON.IN file. Use with caution. *Default* = DISCON +:code:`PF_Offsets` : Array of Floats + Pitch angle offsets for each blade (array with length of 3) + linmodel_tuning From decd694706e8546c42fc222d40e4cd3ab5da277f Mon Sep 17 00:00:00 2001 From: dzalkind <65573423+dzalkind@users.noreply.github.com> Date: Wed, 28 Sep 2022 11:40:19 -0600 Subject: [PATCH 007/224] Various Bug Fixes (#167) * FOCAL Updates (#64) * Update headers * fix bullets * make uppercase * Update turbine.py (#56) * Update turbine.py This add several lines for fixing the problem of repeated maximum values in the performance tables. This will cause the error (' the length of x and y is different.') of 'interpolate.interp1d.' * Add comments and catch when there are multiple optimal pitch angles Co-authored-by: dzalkind * increment version * Update for OpenFAST v3.0.0 * Update for OpenFAST v3.0.0 * Install OF3.0.0 for tests * update for OF v3.0.0 * add publish to pypi on release * Update to ROSCO v2.3.0 * Update Testing (#58) * Update scripts to run on eagle * Update IEA-15MW semi example: use peak shaving w/ ps_percen=0.8 * Add comparison plots to testing scripts * Update submit script for testing * Update for latest eagle runs * Add future to install dependencies * add TMax to self, define tmin in print_results * run tests in CI * generic ROSCO path * default to overwrite * fix path * import platform * separate run_testing * cleanup, specify lite test * don't run testing in after examples, oops. Co-authored-by: nikhar-abbas <40865984+nikhar-abbas@users.noreply.github.com> Co-authored-by: Nikhar Abbas * increment version * Update for OpenFAST v3.0.0 * Install OF3.0.0 for tests * update for OF v3.0.0 * add publish to pypi on release * Update to ROSCO v2.3.0 * Increment Version, OF3.0 (#57) * increment version * Update for OpenFAST v3.0.0 * Install OF3.0.0 for tests * update for OF v3.0.0 * add publish to pypi on release * Update to ROSCO v2.3.0 * increment version * Update for OpenFAST v3.0.0 * Install OF3.0.0 for tests * update for OF v3.0.0 * add publish to pypi on release * Update to ROSCO v2.3.0 * add ROSCO without submodule * move ROSCO source to ROSCO folder * Move cmake-related files to ROSCO * Add back pesky ErrVar * Remove parameters_files * Merge ROSCO and _toolbox gitignore * Fix .gitignore * Remove Examples/DISCON.IN from git * Fix and point example_01 to Tune_Cases/ * Update verbiage around using ofTools vs. weis * Fix and point example_04 to Tune_Cases/ * Clean up example_06 * Clean up example_07 * Only check FlpCornerFreq if using Flp control, fixes example 05 * Make example_04 consistent with others * Let example_05 run independently from 04 * Clean up example_05, wind files * Add schema and update empty tuning yaml inputs, not connected yet * Integrate schema into turbine, controller, and examples * Only check Fl filter parameters if Fl_Mode > 0, fix example_05 * bump version to 2.3 * Compile ROSCO from ROSCO dir * Rename to CI_rosco * Add omega vs. windspeed functionality * Fix tests: 5MW U_pc and 06 example dir * Make _Toolbox vs_minspeed in rotor frame to match ROSCO * Revert ServoDyn change * change rotor speed constraint to be epsilon * rename for clarity * docs major refresh * fix FA_AccF units in debug file * docs that build locally * Deallocate arrays in ROSCO, check in example_05 * Clean up comments * remove gitmodules * furo theme * furo in requirements * move readthedocs config file, remove furo import in conf.py * add docs requirements file * typo * move index out of source folder * trying to get furo to work * import date * fix versions and titles, cleanup readthedocs requirements * typo fix, remove extras * more cleanup * bump version * no furo extension, "hack" to load RT version * proper toctree paths * specify method * add mock modules * fix typos * update python install requirements * running locally * move index to main docs dir again * update to build locally * error during warnings * automated version * cleanup * remove old docs * re-add docs * simplify * fix figure path * try alabaster * remove archived docs * Add omega vs. windspeed functionality * Fix tests: 5MW U_pc and 06 example dir * more detailed sp.optimize settings * run MBC3 in parallel * restructure driver, run initialization doe for tuning * Try new dlclose function * Update example_05 to run simple simulation twice and check result * Revert deallocation stuff * Close discon library after every sim run * Test examples on macOS and windows * Run examples instead of testing on other platforms * Skip examples in windows for now * update paths and yaml load funciton * Skip mac testing of examples * provide default U_pc for single omega/zeta case * allow for float or list-like pc tuning inputs * Change name in setup.py * WE_Vw unit fix * Pass through kp_float, if desired * Minor fixes: schema error and InputReader defaults * cleeanup for improved stability * check for doe_logs as string in load_DOE * major restructure for rsched_driver class * cleanup verbosity * run serial by default * load_parallel as linturb_option * specific IEA15MW yaml for multi omega * remove unused module imports * fix error message types * lin_file as input * add comments on inputs to LinearTurbineModel init method * remove relative file paths * provide OpenFAST linearizations for IEA15MW UMaineSemi * put plotting in specific function * fix WE_lambda units * add self in on a few necessary variables * creaete example 12 for robust scheduling * try a few mbc3 locations for import * allow list-like or numpy arrays for omega_pc and zeta_pc schedules * create and use recorder setup function * Pass Through Kp_float (#57) * Pass through kp_float, if desired * Minor fixes: schema error and InputReader defaults * fix setup_recorder to work for optimization driver too * Allow pass through of Kp_float = 0 * cleanup om problems, update om0 calc * doe levels as input * negative k_float to account for OF conventions * cleanup print statements * variable name cleanup, use calculated k_float * Add defaults to omega_,zeta_ pc and vs, allow to be numbers * use standard tuning k_float as IC * formatting update * update problem setup methods * cleanup add_dv, enable adding design variables after problem is setup * change optimization step size * more setup restructure * update verbosity * use sphinx-rtd-theme * master doc and sphinx rtd theme * index back to root folder * only ignore install folders * remove hidden toctree * furo theme * update paths * convert rt version to string * update sphinx settings * move conf * furo theme * Mostly a docs update (#61) * rename for clarity * docs major refresh * fix FA_AccF units in debug file * docs that build locally * remove gitmodules * furo theme * furo in requirements * move readthedocs config file, remove furo import in conf.py * add docs requirements file * typo * move index out of source folder * trying to get furo to work * import date * fix versions and titles, cleanup readthedocs requirements * typo fix, remove extras * more cleanup * bump version * no furo extension, "hack" to load RT version * proper toctree paths * specify method * add mock modules * fix typos * update python install requirements * running locally * move index to main docs dir again * update to build locally * error during warnings * automated version * cleanup * remove old docs * re-add docs * simplify * fix figure path * try alabaster * remove archived docs * use sphinx-rtd-theme * master doc and sphinx rtd theme * index back to root folder * only ignore install folders * remove hidden toctree * furo theme * update paths * convert rt version to string * update sphinx settings * move conf * furo theme * Pass through Kp_float = 0 (#59) * Pass through kp_float, if desired * Minor fixes: schema error and InputReader defaults * Allow pass through of Kp_float = 0 * Add flp parameters to schema * Change Fl_Mode default to 0 * Add defaults to omega_,zeta_ pc and vs, allow to be numbers * Allow single pitch tuning values in code, default U_pc to 0 * use nac acceleration for floating feedback * Fix TSR saturation for region 2.5operation * Modify system for constant power operation * Only modify pole for constant power above-rated * Remove GenEff from K calc * Update tuning, use constant power * use load_rosco_yaml * constant power * Fix broken tests * Include Fl_Mode=2 for nacelle pitching feedback * Add FOCAL inputs - hpf on floating feedback - lpf on wind speed estimator - associated schema updates * Set notch and check frequencies when Fl_Mode = 1 (fixes bug) * Skip filter step if there's an error * Update IEA-15MW test case DISCON with focal inputs * Allow Fl_Mode = 2 in ROSCO * Pass through lpf frequency * Add FOCAL tuning yaml * Set Cp contour number of levels * Add FOCAL params to various writers * Update/tune focal yaml * Add scripts for running FAST, tuning various parameters and cases * Add notebook for FAST plotting * Set up step case for testing * Change doubles to C_doubles * Define real and integer kinds, assign to all of ROSCO * Add ADJUSTL to DISCON error message * Fix Fl_Mode == 2 * Fix Fl_Mode == 2 again * Call yaw, flap, and debug only if enabled in DISOCN.IN * Make avrSWAP a ReKi and set constant kinds * Add DISCONs for testing - revert this later * Fix DISCON comparison, before DISCON's were overwritten by model * Rename DEBUG2.dbg to RootName.dbg2 * Update TestCase DISCONs to new input file * Add API change page in docs * Add link to API change on main page * Fix table headers * Fix title underlines * Fix tables again * Fix tables again * Fix version numbering in docs * Simplify FAST_directory in run_FAST * Versioning (#65) * use sphinx-rtd-theme * master doc and sphinx rtd theme * index back to root folder * only ignore install folders * remove hidden toctree * furo theme * update paths * convert rt version to string * update sphinx settings * move conf * furo theme * remove git versioning from cmake * use hard coded rosco_version * update intro write method * set nowrap for intel compilers * Add transfer of error message and clear message after each call * update install instructions * Catch nans in ROSCO at end of WSE * fix conda install typo * cleanup docs * Rename DEBUG2.dbg to RootName.dbg2 * Fix Fl_Mode == 2 * Fix Fl_Mode == 2 again * Allow Fl_Mode = 2 in ROSCO * Set notch and check frequencies when Fl_Mode = 1 (fixes bug) * Update FOCAL tuning yaml * Update TSR * Clean up and doc fix * Remove publish to pypi * Define all constant inputs to functions with kind typing * Generate Test_Case/ inputs automatically * Fix IEA15 DISCON path * Fix example 11 paths * Auto-generate tuning input yaml using schema * Add toolbox_input to doc index * Add toctree * Re-name title of toolbox_input Co-authored-by: Nikhar Abbas Co-authored-by: Xianping Du <38188001+Seager1989@users.noreply.github.com> Co-authored-by: nikhar-abbas <40865984+nikhar-abbas@users.noreply.github.com> * update listcheck method for numpy arrays * Open Loop Control (#98) * create rosco types yaml * Add more descriptions, add integer_c default, cleanup * updates for allocatability and shapes * python scripts to write ROSCO_types.f90 * reemove superfulous modules * use types from ROSCO registry * create rosco types yaml * Add more descriptions, add integer_c default, cleanup * updates for allocatability and shapes * python scripts to write ROSCO_types.f90 * reemove superfulous modules * use types from ROSCO registry * Saturate inputs to WSE. Needs some TLC, but seems to work * Reduce saturation limits on speed, torque * Re-organize, set saturation limits. Working at 3 m/s * Initial add of OL control to ROSCO: builds * Update DISCONs with open loop inputs * Fix file reading for OL_Filename * Add open loop control generation and file writing * Use DISCON_dict for more manageable DISCON file writing * Add open loop example, fix constant timeseries * Make open loop example generate power * Handle relative paths and calling from outside the run directory: - Some helper functions borrowed from OpenFAST, f/ext_control - Updated file writing * Clean up: versions, print statements * Fix SysFiles paths in CMakeLists * Tidy up Ext_DLL names * More Ext_DLL name tidying * Test write_registry.py * Update for OL Control * Move preprocessor lines * add zenodo DOI * Regenerated Types * fix shape * revert filepath change * give all types a size, ProcAddr size = 3 * update types * test registry in compile step * specify default shell * update write_registry path * remove default shell * Document API changes, provide OL input example * Fix example 14 (yaw input) * Add error catching to yaw control * Tidy up OL_Input Reading: error catching, generalize * More yaw control fixes, to model * Checkout develop CMakeLists for ROSCO * Update DISCON.INs for TestCases/ * Revert "Checkout develop CMakeLists for ROSCO" This reverts commit 87a491359d73806e3aaa59b4cfdc00f2838875df. * Revert windows cmake stuff to develop * Fix CMake again * Revert "Revert windows cmake stuff to develop" This reverts commit 39df122449b0e2055f2e12e3ce38a0c010c7bd91. * Make last cmake fix - hopefully Co-authored-by: Nikhar Abbas * Convert WE saved variables to WE type * Put restart flag in localvars * Use saved filter params from LocalVar * save pitcomt last * Move IPC saved variables to localvars * Saved pi controller variables to localvar * Save RootMyb_Last to localvar * ROSCO_IO - initial commit. Include restart and debug functions * Use ROSCO IO and call restart functions * Remove debug from function.f90 * Save ACC Infile info * update for restart capabilities * add rosco_io with restart and debug functions * cleanup debug call * use registry generate types and IO * delete DFController * fix timestep mismatch * remove unnecessaray istatus check * close files * add reg test for restart * add restart option to run_openfast * add testing to CI, ignore generate files * fix fastcall * remove extra commas * specify gfortran-10 * testing flag cleanup * Use lv_strings to generate debug output * Revert "testing flag cleanup" This reverts commit 6f295563832413e96347acd82716f9aadac6d46c. * Revert "specify gfortran-10" This reverts commit 4c3154491523bcd542133ca2bce5803cdc94523f. * minor cleanup * Use kind from constants * Add some comments for clarity * put debug in if statements * separate reg tests from oother tests * Fl_Mode>0 * Remove hard coded values * Add filtered signals and WE_Vw to debug varrs * cd for regtest * Check logging level before calling debug * add fl_pitcom and pc_minpit to debugvars * Turn runFAST into a class * Refactor/simplify CaseLibrary * Restart & registry (#99) * Convert WE saved variables to WE type * Put restart flag in localvars * Use saved filter params from LocalVar * save pitcomt last * Move IPC saved variables to localvars * Saved pi controller variables to localvar * Save RootMyb_Last to localvar * ROSCO_IO - initial commit. Include restart and debug functions * Use ROSCO IO and call restart functions * Remove debug from function.f90 * Save ACC Infile info * update for restart capabilities * add rosco_io with restart and debug functions * cleanup debug call * use registry generate types and IO * delete DFController * fix timestep mismatch * remove unnecessaray istatus check * close files * add reg test for restart * add restart option to run_openfast * add testing to CI, ignore generate files * fix fastcall * remove extra commas * specify gfortran-10 * testing flag cleanup * Use lv_strings to generate debug output * Revert "testing flag cleanup" This reverts commit 6f295563832413e96347acd82716f9aadac6d46c. * Revert "specify gfortran-10" This reverts commit 4c3154491523bcd542133ca2bce5803cdc94523f. * minor cleanup * Use kind from constants * Add some comments for clarity * put debug in if statements * separate reg tests from oother tests * Fl_Mode>0 * Remove hard coded values * Add filtered signals and WE_Vw to debug varrs * cd for regtest * Check logging level before calling debug * add fl_pitcom and pc_minpit to debugvars Co-authored-by: dzalkind * Implement initial pitch actuator * Set up steps case * Break up if statement in open loop pitch (#100) * Break up if statement in open loop pitch * Make torque and yaw consistent with pitch: can start after some time * add bld edgewise freq to robust dict_inputs * Add actuator variable * Print first time step in debug outs * Fix FOCAL yaml * Set actuator to 0.25 Hz bandwidth * Fix ccrotor inputs (#104) * remove interpolation of blade chord and twist * rename aerodynblade inputs * Update surface and DISCON.INs * Fix performance table paths * Allow default inputs (#110) * Allow defaults for AeroDyn inputs * Allow AeroDyn inputs to be floats, too * ipc (#105) * remove interpolation of blade chord and twist * rename aerodynblade inputs * Update surface and DISCON.INs * Fix performance table paths * Add proportional control and cleanup IPC * Add IPC and filtered RootMyc to registry * Better logic for filtering RootMOOP and fix notch filter slopes bug * Add cyclic flap conrol * Fix comments in ColemanTransformInverse * Addd IPC_KP to DISCON.IN * Error checking foro flp or ipc * add mutichannel plotting with tuples * add CMakeFiles to gitignore * Add IPC_KP to api changes * numerical qualifiers for error handling * add IPC gains to schema for pass-through ability * fix variable names * fix ipc gain printing bug * make sure IPC_KP is positive * Update Polars to point to coord files * ignore dbg2 files * Add IEA15MW_OL.yaml * update coord reader/writer * expand pitch_initial to 30 degrees * Add example 13 for IPC * Update cp surfaces and DISCONS * add examples to readme * cleanup and streaamline run_examples * Add IPC tuning vars * Allow IPC to command pitch value below peak shaving saturation limit * shorten simulation time * Fix Material parameter path * Update DISCONs again * Fix OL_Input reading * Set wind speed, rotor speed IC in example 14 * Debug OL reading * Add more debugging lines * Add more debugging lines 2 * Clean up, hone in on debug call * Disable logging level * Update discons - resolve conflict * Print when finished with ROSCO * add control packageg * Use PriPath and RootName to name dbg files * Print AvrSWAP * Revert "Use PriPath and RootName to name dbg files" This reverts commit 062fcaa55b3bf42d44f8a3f163aa883ab9552412. * Disable other examples * Print OL inputs * Allow logging level 3 * Print OL inputs * Make example shorter * Print more stuf * Print shape * Revert "Print OL inputs" This reverts commit 8e2a642bb35e46850f579ca4e69ca6d6fc93f4cc. * Update ROSCO Simulink model with IPC example * refactor flap tuning for normalization methods * improved flap controller filtering * delete extra F_FlpCornerFrerq * Update inputs, reader, and writer for OF 3.1.0 * Make sigma default interp type for multi_sigma * Use openfast 3.1.0 in CI * Fix leak...maybe * Use OF 3.1.0 in testing * Use gfotran for compile * Clean up print statements * Re-enable all examples * Update NREL-5MW AD file * Only check airfoil controls if more than one table * Update BAR models * Revert "Use gfotran for compile" This reverts commit 5a6e2b7e30287a09a09781e2ba12f9b578132e1f. * Install pyFAST for CI * Fix some paths in ex12 * Disable example 12 * Fix example 12 linear path, re-enable * Skip compilers install for mac * Try gfortran-9, no compilers * Try gfortran-10, no compilers * Skip windows compile in pytools * Re-enable windows, use gfortran as FC * Unset FC in windows * Set environment for windows when dependencies installed * Try setting environment in installation * Put conditional env setting in correct place * Try in setup again * Break up tasks: Windows vs. not * Update DISCONs * Update docs with new variables * Add example documentation * Update ROSCO Simulink model for 3.1.0 * Make IEA model float again * Reduce IEA timestep * Match DT to checkpoint time Co-authored-by: dzalkind * Increment version number * Bladed docs (#116) * Added image of Bladed control screen setup * Delete Bladed control screen.png * Adding image of Bladed control screen * Add files via upload * Minor edit 1 * Minor change 2 * Minor change 3 * Minor change 4 * Change 6 * Change 7 * Change 8 * Minor change 9 Co-authored-by: nikhar-abbas <40865984+nikhar-abbas@users.noreply.github.com> Co-authored-by: WillC-DNV <100850534+WillC-DNV@users.noreply.github.com> * Update version in API change docs * Bladed readthedocs (#117) * Added image of Bladed control screen setup * Delete Bladed control screen.png * Adding image of Bladed control screen * Add files via upload * Minor edit 1 * Minor change 2 * Minor change 3 * Minor change 4 * Change 6 * Change 7 * Change 8 * Minor change 9 * Tinker with characters in bladed instructions * Add bladed instructions to index * Change bladed toctree label * Do underline stuff * Make toctree label same as file * Remove colons from headers Co-authored-by: nikhar-abbas <40865984+nikhar-abbas@users.noreply.github.com> Co-authored-by: WillC-DNV <100850534+WillC-DNV@users.noreply.github.com> * Update docs to reflect CI process * Regenerate types, IO with registry * Update registry so first timestep is printed * Update inverted notch to move frequency properly * Saturate inv notch corner frequency at 0 * Add tower damper mode flag * Add Azimuth tracking controller in Simulink * Always enable GenDOF, add options for simp_step * Add sweep for IPC gains and FA damper * Fix NumCoords in FAST_writer * sigma + ipc (#125) * cleanup api change table * Update inverted notch to move frequency properly * Saturate inv notch corner frequency at 0 * add sigma function * Use IPC_Vramp for IPC cut-in * Add IPC_Vramp DISCON inputs * update registry * Update DISCONs * Update docs for API change * Fix IPC_Vramp data type * update comments Co-authored-by: dzalkind * Add turbulent case to runFAST/CaseLibrary * Add peak shaving sweep function * Increase default IPC_IntSat, make input parameter in future * Flip Ct and Cq table allocation * Flip Ct and Cq table allocation (#130) * Regen types * Remove print statements used for debugging * Update input files: IEA model has pitch actuator * Add back flap control (no idea when it was deleted) * Update discons, docs with API change * Add user-defined hh case * Fix AddF0 and RayleighDamp in FAST_reader * Pitch Actuator and IPC updates (#123) * Convert WE saved variables to WE type * Put restart flag in localvars * Use saved filter params from LocalVar * save pitcomt last * Move IPC saved variables to localvars * Saved pi controller variables to localvar * Save RootMyb_Last to localvar * ROSCO_IO - initial commit. Include restart and debug functions * Use ROSCO IO and call restart functions * Remove debug from function.f90 * Save ACC Infile info * update for restart capabilities * add rosco_io with restart and debug functions * cleanup debug call * use registry generate types and IO * delete DFController * fix timestep mismatch * remove unnecessaray istatus check * close files * add reg test for restart * add restart option to run_openfast * add testing to CI, ignore generate files * fix fastcall * remove extra commas * specify gfortran-10 * testing flag cleanup * Use lv_strings to generate debug output * Revert "testing flag cleanup" This reverts commit 6f295563832413e96347acd82716f9aadac6d46c. * Revert "specify gfortran-10" This reverts commit 4c3154491523bcd542133ca2bce5803cdc94523f. * minor cleanup * Use kind from constants * Add some comments for clarity * put debug in if statements * separate reg tests from oother tests * Fl_Mode>0 * Remove hard coded values * Add filtered signals and WE_Vw to debug varrs * cd for regtest * Check logging level before calling debug * add fl_pitcom and pc_minpit to debugvars * Turn runFAST into a class * Refactor/simplify CaseLibrary * Implement initial pitch actuator * Set up steps case * Add actuator variable * Print first time step in debug outs * Fix FOCAL yaml * Set actuator to 0.25 Hz bandwidth * ROSCO 2.5.0 (#115) * FOCAL Updates (#64) * Update headers * fix bullets * make uppercase * Update turbine.py (#56) * Update turbine.py This add several lines for fixing the problem of repeated maximum values in the performance tables. This will cause the error (' the length of x and y is different.') of 'interpolate.interp1d.' * Add comments and catch when there are multiple optimal pitch angles Co-authored-by: dzalkind * increment version * Update for OpenFAST v3.0.0 * Update for OpenFAST v3.0.0 * Install OF3.0.0 for tests * update for OF v3.0.0 * add publish to pypi on release * Update to ROSCO v2.3.0 * Update Testing (#58) * Update scripts to run on eagle * Update IEA-15MW semi example: use peak shaving w/ ps_percen=0.8 * Add comparison plots to testing scripts * Update submit script for testing * Update for latest eagle runs * Add future to install dependencies * add TMax to self, define tmin in print_results * run tests in CI * generic ROSCO path * default to overwrite * fix path * import platform * separate run_testing * cleanup, specify lite test * don't run testing in after examples, oops. Co-authored-by: nikhar-abbas <40865984+nikhar-abbas@users.noreply.github.com> Co-authored-by: Nikhar Abbas * increment version * Update for OpenFAST v3.0.0 * Install OF3.0.0 for tests * update for OF v3.0.0 * add publish to pypi on release * Update to ROSCO v2.3.0 * Increment Version, OF3.0 (#57) * increment version * Update for OpenFAST v3.0.0 * Install OF3.0.0 for tests * update for OF v3.0.0 * add publish to pypi on release * Update to ROSCO v2.3.0 * increment version * Update for OpenFAST v3.0.0 * Install OF3.0.0 for tests * update for OF v3.0.0 * add publish to pypi on release * Update to ROSCO v2.3.0 * add ROSCO without submodule * move ROSCO source to ROSCO folder * Move cmake-related files to ROSCO * Add back pesky ErrVar * Remove parameters_files * Merge ROSCO and _toolbox gitignore * Fix .gitignore * Remove Examples/DISCON.IN from git * Fix and point example_01 to Tune_Cases/ * Update verbiage around using ofTools vs. weis * Fix and point example_04 to Tune_Cases/ * Clean up example_06 * Clean up example_07 * Only check FlpCornerFreq if using Flp control, fixes example 05 * Make example_04 consistent with others * Let example_05 run independently from 04 * Clean up example_05, wind files * Add schema and update empty tuning yaml inputs, not connected yet * Integrate schema into turbine, controller, and examples * Only check Fl filter parameters if Fl_Mode > 0, fix example_05 * bump version to 2.3 * Compile ROSCO from ROSCO dir * Rename to CI_rosco * Add omega vs. windspeed functionality * Fix tests: 5MW U_pc and 06 example dir * Make _Toolbox vs_minspeed in rotor frame to match ROSCO * Revert ServoDyn change * change rotor speed constraint to be epsilon * rename for clarity * docs major refresh * fix FA_AccF units in debug file * docs that build locally * Deallocate arrays in ROSCO, check in example_05 * Clean up comments * remove gitmodules * furo theme * furo in requirements * move readthedocs config file, remove furo import in conf.py * add docs requirements file * typo * move index out of source folder * trying to get furo to work * import date * fix versions and titles, cleanup readthedocs requirements * typo fix, remove extras * more cleanup * bump version * no furo extension, "hack" to load RT version * proper toctree paths * specify method * add mock modules * fix typos * update python install requirements * running locally * move index to main docs dir again * update to build locally * error during warnings * automated version * cleanup * remove old docs * re-add docs * simplify * fix figure path * try alabaster * remove archived docs * Add omega vs. windspeed functionality * Fix tests: 5MW U_pc and 06 example dir * more detailed sp.optimize settings * run MBC3 in parallel * restructure driver, run initialization doe for tuning * Try new dlclose function * Update example_05 to run simple simulation twice and check result * Revert deallocation stuff * Close discon library after every sim run * Test examples on macOS and windows * Run examples instead of testing on other platforms * Skip examples in windows for now * update paths and yaml load funciton * Skip mac testing of examples * provide default U_pc for single omega/zeta case * allow for float or list-like pc tuning inputs * Change name in setup.py * WE_Vw unit fix * Pass through kp_float, if desired * Minor fixes: schema error and InputReader defaults * cleeanup for improved stability * check for doe_logs as string in load_DOE * major restructure for rsched_driver class * cleanup verbosity * run serial by default * load_parallel as linturb_option * specific IEA15MW yaml for multi omega * remove unused module imports * fix error message types * lin_file as input * add comments on inputs to LinearTurbineModel init method * remove relative file paths * provide OpenFAST linearizations for IEA15MW UMaineSemi * put plotting in specific function * fix WE_lambda units * add self in on a few necessary variables * creaete example 12 for robust scheduling * try a few mbc3 locations for import * allow list-like or numpy arrays for omega_pc and zeta_pc schedules * create and use recorder setup function * Pass Through Kp_float (#57) * Pass through kp_float, if desired * Minor fixes: schema error and InputReader defaults * fix setup_recorder to work for optimization driver too * Allow pass through of Kp_float = 0 * cleanup om problems, update om0 calc * doe levels as input * negative k_float to account for OF conventions * cleanup print statements * variable name cleanup, use calculated k_float * Add defaults to omega_,zeta_ pc and vs, allow to be numbers * use standard tuning k_float as IC * formatting update * update problem setup methods * cleanup add_dv, enable adding design variables after problem is setup * change optimization step size * more setup restructure * update verbosity * use sphinx-rtd-theme * master doc and sphinx rtd theme * index back to root folder * only ignore install folders * remove hidden toctree * furo theme * update paths * convert rt version to string * update sphinx settings * move conf * furo theme * Mostly a docs update (#61) * rename for clarity * docs major refresh * fix FA_AccF units in debug file * docs that build locally * remove gitmodules * furo theme * furo in requirements * move readthedocs config file, remove furo import in conf.py * add docs requirements file * typo * move index out of source folder * trying to get furo to work * import date * fix versions and titles, cleanup readthedocs requirements * typo fix, remove extras * more cleanup * bump version * no furo extension, "hack" to load RT version * proper toctree paths * specify method * add mock modules * fix typos * update python install requirements * running locally * move index to main docs dir again * update to build locally * error during warnings * automated version * cleanup * remove old docs * re-add docs * simplify * fix figure path * try alabaster * remove archived docs * use sphinx-rtd-theme * master doc and sphinx rtd theme * index back to root folder * only ignore install folders * remove hidden toctree * furo theme * update paths * convert rt version to string * update sphinx settings * move conf * furo theme * Pass through Kp_float = 0 (#59) * Pass through kp_float, if desired * Minor fixes: schema error and InputReader defaults * Allow pass through of Kp_float = 0 * Add flp parameters to schema * Change Fl_Mode default to 0 * Add defaults to omega_,zeta_ pc and vs, allow to be numbers * Allow single pitch tuning values in code, default U_pc to 0 * use nac acceleration for floating feedback * Fix TSR saturation for region 2.5operation * Modify system for constant power operation * Only modify pole for constant power above-rated * Remove GenEff from K calc * Update tuning, use constant power * use load_rosco_yaml * constant power * Fix broken tests * Include Fl_Mode=2 for nacelle pitching feedback * Add FOCAL inputs - hpf on floating feedback - lpf on wind speed estimator - associated schema updates * Set notch and check frequencies when Fl_Mode = 1 (fixes bug) * Skip filter step if there's an error * Update IEA-15MW test case DISCON with focal inputs * Allow Fl_Mode = 2 in ROSCO * Pass through lpf frequency * Add FOCAL tuning yaml * Set Cp contour number of levels * Add FOCAL params to various writers * Update/tune focal yaml * Add scripts for running FAST, tuning various parameters and cases * Add notebook for FAST plotting * Set up step case for testing * Change doubles to C_doubles * Define real and integer kinds, assign to all of ROSCO * Add ADJUSTL to DISCON error message * Fix Fl_Mode == 2 * Fix Fl_Mode == 2 again * Call yaw, flap, and debug only if enabled in DISOCN.IN * Make avrSWAP a ReKi and set constant kinds * Add DISCONs for testing - revert this later * Fix DISCON comparison, before DISCON's were overwritten by model * Rename DEBUG2.dbg to RootName.dbg2 * Update TestCase DISCONs to new input file * Add API change page in docs * Add link to API change on main page * Fix table headers * Fix title underlines * Fix tables again * Fix tables again * Fix version numbering in docs * Simplify FAST_directory in run_FAST * Versioning (#65) * use sphinx-rtd-theme * master doc and sphinx rtd theme * index back to root folder * only ignore install folders * remove hidden toctree * furo theme * update paths * convert rt version to string * update sphinx settings * move conf * furo theme * remove git versioning from cmake * use hard coded rosco_version * update intro write method * set nowrap for intel compilers * Add transfer of error message and clear message after each call * update install instructions * Catch nans in ROSCO at end of WSE * fix conda install typo * cleanup docs * Rename DEBUG2.dbg to RootName.dbg2 * Fix Fl_Mode == 2 * Fix Fl_Mode == 2 again * Allow Fl_Mode = 2 in ROSCO * Set notch and check frequencies when Fl_Mode = 1 (fixes bug) * Update FOCAL tuning yaml * Update TSR * Clean up and doc fix * Remove publish to pypi * Define all constant inputs to functions with kind typing * Generate Test_Case/ inputs automatically * Fix IEA15 DISCON path * Fix example 11 paths * Auto-generate tuning input yaml using schema * Add toolbox_input to doc index * Add toctree * Re-name title of toolbox_input Co-authored-by: Nikhar Abbas Co-authored-by: Xianping Du <38188001+Seager1989@users.noreply.github.com> Co-authored-by: nikhar-abbas <40865984+nikhar-abbas@users.noreply.github.com> * update listcheck method for numpy arrays * Open Loop Control (#98) * create rosco types yaml * Add more descriptions, add integer_c default, cleanup * updates for allocatability and shapes * python scripts to write ROSCO_types.f90 * reemove superfulous modules * use types from ROSCO registry * create rosco types yaml * Add more descriptions, add integer_c default, cleanup * updates for allocatability and shapes * python scripts to write ROSCO_types.f90 * reemove superfulous modules * use types from ROSCO registry * Saturate inputs to WSE. Needs some TLC, but seems to work * Reduce saturation limits on speed, torque * Re-organize, set saturation limits. Working at 3 m/s * Initial add of OL control to ROSCO: builds * Update DISCONs with open loop inputs * Fix file reading for OL_Filename * Add open loop control generation and file writing * Use DISCON_dict for more manageable DISCON file writing * Add open loop example, fix constant timeseries * Make open loop example generate power * Handle relative paths and calling from outside the run directory: - Some helper functions borrowed from OpenFAST, f/ext_control - Updated file writing * Clean up: versions, print statements * Fix SysFiles paths in CMakeLists * Tidy up Ext_DLL names * More Ext_DLL name tidying * Test write_registry.py * Update for OL Control * Move preprocessor lines * add zenodo DOI * Regenerated Types * fix shape * revert filepath change * give all types a size, ProcAddr size = 3 * update types * test registry in compile step * specify default shell * update write_registry path * remove default shell * Document API changes, provide OL input example * Fix example 14 (yaw input) * Add error catching to yaw control * Tidy up OL_Input Reading: error catching, generalize * More yaw control fixes, to model * Checkout develop CMakeLists for ROSCO * Update DISCON.INs for TestCases/ * Revert "Checkout develop CMakeLists for ROSCO" This reverts commit 87a491359d73806e3aaa59b4cfdc00f2838875df. * Revert windows cmake stuff to develop * Fix CMake again * Revert "Revert windows cmake stuff to develop" This reverts commit 39df122449b0e2055f2e12e3ce38a0c010c7bd91. * Make last cmake fix - hopefully Co-authored-by: Nikhar Abbas * Restart & registry (#99) * Convert WE saved variables to WE type * Put restart flag in localvars * Use saved filter params from LocalVar * save pitcomt last * Move IPC saved variables to localvars * Saved pi controller variables to localvar * Save RootMyb_Last to localvar * ROSCO_IO - initial commit. Include restart and debug functions * Use ROSCO IO and call restart functions * Remove debug from function.f90 * Save ACC Infile info * update for restart capabilities * add rosco_io with restart and debug functions * cleanup debug call * use registry generate types and IO * delete DFController * fix timestep mismatch * remove unnecessaray istatus check * close files * add reg test for restart * add restart option to run_openfast * add testing to CI, ignore generate files * fix fastcall * remove extra commas * specify gfortran-10 * testing flag cleanup * Use lv_strings to generate debug output * Revert "testing flag cleanup" This reverts commit 6f295563832413e96347acd82716f9aadac6d46c. * Revert "specify gfortran-10" This reverts commit 4c3154491523bcd542133ca2bce5803cdc94523f. * minor cleanup * Use kind from constants * Add some comments for clarity * put debug in if statements * separate reg tests from oother tests * Fl_Mode>0 * Remove hard coded values * Add filtered signals and WE_Vw to debug varrs * cd for regtest * Check logging level before calling debug * add fl_pitcom and pc_minpit to debugvars Co-authored-by: dzalkind * Break up if statement in open loop pitch (#100) * Break up if statement in open loop pitch * Make torque and yaw consistent with pitch: can start after some time * add bld edgewise freq to robust dict_inputs * Fix ccrotor inputs (#104) * remove interpolation of blade chord and twist * rename aerodynblade inputs * Update surface and DISCON.INs * Fix performance table paths * Allow default inputs (#110) * Allow defaults for AeroDyn inputs * Allow AeroDyn inputs to be floats, too * ipc (#105) * remove interpolation of blade chord and twist * rename aerodynblade inputs * Update surface and DISCON.INs * Fix performance table paths * Add proportional control and cleanup IPC * Add IPC and filtered RootMyc to registry * Better logic for filtering RootMOOP and fix notch filter slopes bug * Add cyclic flap conrol * Fix comments in ColemanTransformInverse * Addd IPC_KP to DISCON.IN * Error checking foro flp or ipc * add mutichannel plotting with tuples * add CMakeFiles to gitignore * Add IPC_KP to api changes * numerical qualifiers for error handling * add IPC gains to schema for pass-through ability * fix variable names * fix ipc gain printing bug * make sure IPC_KP is positive * Update Polars to point to coord files * ignore dbg2 files * Add IEA15MW_OL.yaml * update coord reader/writer * expand pitch_initial to 30 degrees * Add example 13 for IPC * Update cp surfaces and DISCONS * add examples to readme * cleanup and streaamline run_examples * Add IPC tuning vars * Allow IPC to command pitch value below peak shaving saturation limit * shorten simulation time * Fix Material parameter path * Update DISCONs again * Fix OL_Input reading * Set wind speed, rotor speed IC in example 14 * Debug OL reading * Add more debugging lines * Add more debugging lines 2 * Clean up, hone in on debug call * Disable logging level * Update discons - resolve conflict * Print when finished with ROSCO * add control packageg * Use PriPath and RootName to name dbg files * Print AvrSWAP * Revert "Use PriPath and RootName to name dbg files" This reverts commit 062fcaa55b3bf42d44f8a3f163aa883ab9552412. * Disable other examples * Print OL inputs * Allow logging level 3 * Print OL inputs * Make example shorter * Print more stuf * Print shape * Revert "Print OL inputs" This reverts commit 8e2a642bb35e46850f579ca4e69ca6d6fc93f4cc. * Update ROSCO Simulink model with IPC example * refactor flap tuning for normalization methods * improved flap controller filtering * delete extra F_FlpCornerFrerq * Update inputs, reader, and writer for OF 3.1.0 * Make sigma default interp type for multi_sigma * Use openfast 3.1.0 in CI * Fix leak...maybe * Use OF 3.1.0 in testing * Use gfotran for compile * Clean up print statements * Re-enable all examples * Update NREL-5MW AD file * Only check airfoil controls if more than one table * Update BAR models * Revert "Use gfotran for compile" This reverts commit 5a6e2b7e30287a09a09781e2ba12f9b578132e1f. * Install pyFAST for CI * Fix some paths in ex12 * Disable example 12 * Fix example 12 linear path, re-enable * Skip compilers install for mac * Try gfortran-9, no compilers * Try gfortran-10, no compilers * Skip windows compile in pytools * Re-enable windows, use gfortran as FC * Unset FC in windows * Set environment for windows when dependencies installed * Try setting environment in installation * Put conditional env setting in correct place * Try in setup again * Break up tasks: Windows vs. not * Update DISCONs * Update docs with new variables * Add example documentation * Update ROSCO Simulink model for 3.1.0 * Make IEA model float again * Reduce IEA timestep * Match DT to checkpoint time Co-authored-by: dzalkind * Increment version number * Bladed docs (#116) * Added image of Bladed control screen setup * Delete Bladed control screen.png * Adding image of Bladed control screen * Add files via upload * Minor edit 1 * Minor change 2 * Minor change 3 * Minor change 4 * Change 6 * Change 7 * Change 8 * Minor change 9 Co-authored-by: nikhar-abbas <40865984+nikhar-abbas@users.noreply.github.com> Co-authored-by: WillC-DNV <100850534+WillC-DNV@users.noreply.github.com> * Update version in API change docs * Bladed readthedocs (#117) * Added image of Bladed control screen setup * Delete Bladed control screen.png * Adding image of Bladed control screen * Add files via upload * Minor edit 1 * Minor change 2 * Minor change 3 * Minor change 4 * Change 6 * Change 7 * Change 8 * Minor change 9 * Tinker with characters in bladed instructions * Add bladed instructions to index * Change bladed toctree label * Do underline stuff * Make toctree label same as file * Remove colons from headers Co-authored-by: nikhar-abbas <40865984+nikhar-abbas@users.noreply.github.com> Co-authored-by: WillC-DNV <100850534+WillC-DNV@users.noreply.github.com> * Update docs to reflect CI process Co-authored-by: Nikhar Abbas Co-authored-by: Xianping Du <38188001+Seager1989@users.noreply.github.com> Co-authored-by: nikhar-abbas <40865984+nikhar-abbas@users.noreply.github.com> Co-authored-by: WillC-DNV <100850534+WillC-DNV@users.noreply.github.com> * Fixed wrong formatting of list items (#122) extra newline required between list elements * Regenerate types, IO with registry * Update registry so first timestep is printed * Update inverted notch to move frequency properly * Saturate inv notch corner frequency at 0 * Add tower damper mode flag * Flip Ct and Cq table allocation * Regen types * Remove print statements used for debugging * Update input files: IEA model has pitch actuator * Add back flap control (no idea when it was deleted) * Update discons, docs with API change Co-authored-by: nikhar-abbas <40865984+nikhar-abbas@users.noreply.github.com> Co-authored-by: Nikhar Abbas Co-authored-by: Xianping Du <38188001+Seager1989@users.noreply.github.com> Co-authored-by: WillC-DNV <100850534+WillC-DNV@users.noreply.github.com> Co-authored-by: Gustavo Hylander <74593034+ghylander@users.noreply.github.com> * Add max_torque_factor for constant power control, flexible upper limit * Make update discons relative to tuning yaml * Update AddF0 and NumCoords in FAST_reader/writer * Add OpenFAST channels that Simulink reads (#135) * RAAW Updates (#133) * Convert WE saved variables to WE type * Put restart flag in localvars * Use saved filter params from LocalVar * save pitcomt last * Move IPC saved variables to localvars * Saved pi controller variables to localvar * Save RootMyb_Last to localvar * ROSCO_IO - initial commit. Include restart and debug functions * Use ROSCO IO and call restart functions * Remove debug from function.f90 * Save ACC Infile info * update for restart capabilities * add rosco_io with restart and debug functions * cleanup debug call * use registry generate types and IO * delete DFController * fix timestep mismatch * remove unnecessaray istatus check * close files * add reg test for restart * add restart option to run_openfast * add testing to CI, ignore generate files * fix fastcall * remove extra commas * specify gfortran-10 * testing flag cleanup * Use lv_strings to generate debug output * Revert "testing flag cleanup" This reverts commit 6f295563832413e96347acd82716f9aadac6d46c. * Revert "specify gfortran-10" This reverts commit 4c3154491523bcd542133ca2bce5803cdc94523f. * minor cleanup * Use kind from constants * Add some comments for clarity * put debug in if statements * separate reg tests from oother tests * Fl_Mode>0 * Remove hard coded values * Add filtered signals and WE_Vw to debug varrs * cd for regtest * Check logging level before calling debug * add fl_pitcom and pc_minpit to debugvars * Turn runFAST into a class * Refactor/simplify CaseLibrary * Implement initial pitch actuator * Set up steps case * Add actuator variable * Print first time step in debug outs * Fix FOCAL yaml * Set actuator to 0.25 Hz bandwidth * ROSCO 2.5.0 (#115) * FOCAL Updates (#64) * Update headers * fix bullets * make uppercase * Update turbine.py (#56) * Update turbine.py This add several lines for fixing the problem of repeated maximum values in the performance tables. This will cause the error (' the length of x and y is different.') of 'interpolate.interp1d.' * Add comments and catch when there are multiple optimal pitch angles Co-authored-by: dzalkind * increment version * Update for OpenFAST v3.0.0 * Update for OpenFAST v3.0.0 * Install OF3.0.0 for tests * update for OF v3.0.0 * add publish to pypi on release * Update to ROSCO v2.3.0 * Update Testing (#58) * Update scripts to run on eagle * Update IEA-15MW semi example: use peak shaving w/ ps_percen=0.8 * Add comparison plots to testing scripts * Update submit script for testing * Update for latest eagle runs * Add future to install dependencies * add TMax to self, define tmin in print_results * run tests in CI * generic ROSCO path * default to overwrite * fix path * import platform * separate run_testing * cleanup, specify lite test * don't run testing in after examples, oops. Co-authored-by: nikhar-abbas <40865984+nikhar-abbas@users.noreply.github.com> Co-authored-by: Nikhar Abbas * increment version * Update for OpenFAST v3.0.0 * Install OF3.0.0 for tests * update for OF v3.0.0 * add publish to pypi on release * Update to ROSCO v2.3.0 * Increment Version, OF3.0 (#57) * increment version * Update for OpenFAST v3.0.0 * Install OF3.0.0 for tests * update for OF v3.0.0 * add publish to pypi on release * Update to ROSCO v2.3.0 * increment version * Update for OpenFAST v3.0.0 * Install OF3.0.0 for tests * update for OF v3.0.0 * add publish to pypi on release * Update to ROSCO v2.3.0 * add ROSCO without submodule * move ROSCO source to ROSCO folder * Move cmake-related files to ROSCO * Add back pesky ErrVar * Remove parameters_files * Merge ROSCO and _toolbox gitignore * Fix .gitignore * Remove Examples/DISCON.IN from git * Fix and point example_01 to Tune_Cases/ * Update verbiage around using ofTools vs. weis * Fix and point example_04 to Tune_Cases/ * Clean up example_06 * Clean up example_07 * Only check FlpCornerFreq if using Flp control, fixes example 05 * Make example_04 consistent with others * Let example_05 run independently from 04 * Clean up example_05, wind files * Add schema and update empty tuning yaml inputs, not connected yet * Integrate schema into turbine, controller, and examples * Only check Fl filter parameters if Fl_Mode > 0, fix example_05 * bump version to 2.3 * Compile ROSCO from ROSCO dir * Rename to CI_rosco * Add omega vs. windspeed functionality * Fix tests: 5MW U_pc and 06 example dir * Make _Toolbox vs_minspeed in rotor frame to match ROSCO * Revert ServoDyn change * change rotor speed constraint to be epsilon * rename for clarity * docs major refresh * fix FA_AccF units in debug file * docs that build locally * Deallocate arrays in ROSCO, check in example_05 * Clean up comments * remove gitmodules * furo theme * furo in requirements * move readthedocs config file, remove furo import in conf.py * add docs requirements file * typo * move index out of source folder * trying to get furo to work * import date * fix versions and titles, cleanup readthedocs requirements * typo fix, remove extras * more cleanup * bump version * no furo extension, "hack" to load RT version * proper toctree paths * specify method * add mock modules * fix typos * update python install requirements * running locally * move index to main docs dir again * update to build locally * error during warnings * automated version * cleanup * remove old docs * re-add docs * simplify * fix figure path * try alabaster * remove archived docs * Add omega vs. windspeed functionality * Fix tests: 5MW U_pc and 06 example dir * more detailed sp.optimize settings * run MBC3 in parallel * restructure driver, run initialization doe for tuning * Try new dlclose function * Update example_05 to run simple simulation twice and check result * Revert deallocation stuff * Close discon library after every sim run * Test examples on macOS and windows * Run examples instead of testing on other platforms * Skip examples in windows for now * update paths and yaml load funciton * Skip mac testing of examples * provide default U_pc for single omega/zeta case * allow for float or list-like pc tuning inputs * Change name in setup.py * WE_Vw unit fix * Pass through kp_float, if desired * Minor fixes: schema error and InputReader defaults * cleeanup for improved stability * check for doe_logs as string in load_DOE * major restructure for rsched_driver class * cleanup verbosity * run serial by default * load_parallel as linturb_option * specific IEA15MW yaml for multi omega * remove unused module imports * fix error message types * lin_file as input * add comments on inputs to LinearTurbineModel init method * remove relative file paths * provide OpenFAST linearizations for IEA15MW UMaineSemi * put plotting in specific function * fix WE_lambda units * add self in on a few necessary variables * creaete example 12 for robust scheduling * try a few mbc3 locations for import * allow list-like or numpy arrays for omega_pc and zeta_pc schedules * create and use recorder setup function * Pass Through Kp_float (#57) * Pass through kp_float, if desired * Minor fixes: schema error and InputReader defaults * fix setup_recorder to work for optimization driver too * Allow pass through of Kp_float = 0 * cleanup om problems, update om0 calc * doe levels as input * negative k_float to account for OF conventions * cleanup print statements * variable name cleanup, use calculated k_float * Add defaults to omega_,zeta_ pc and vs, allow to be numbers * use standard tuning k_float as IC * formatting update * update problem setup methods * cleanup add_dv, enable adding design variables after problem is setup * change optimization step size * more setup restructure * update verbosity * use sphinx-rtd-theme * master doc and sphinx rtd theme * index back to root folder * only ignore install folders * remove hidden toctree * furo theme * update paths * convert rt version to string * update sphinx settings * move conf * furo theme * Mostly a docs update (#61) * rename for clarity * docs major refresh * fix FA_AccF units in debug file * docs that build locally * remove gitmodules * furo theme * furo in requirements * move readthedocs config file, remove furo import in conf.py * add docs requirements file * typo * move index out of source folder * trying to get furo to work * import date * fix versions and titles, cleanup readthedocs requirements * typo fix, remove extras * more cleanup * bump version * no furo extension, "hack" to load RT version * proper toctree paths * specify method * add mock modules * fix typos * update python install requirements * running locally * move index to main docs dir again * update to build locally * error during warnings * automated version * cleanup * remove old docs * re-add docs * simplify * fix figure path * try alabaster * remove archived docs * use sphinx-rtd-theme * master doc and sphinx rtd theme * index back to root folder * only ignore install folders * remove hidden toctree * furo theme * update paths * convert rt version to string * update sphinx settings * move conf * furo theme * Pass through Kp_float = 0 (#59) * Pass through kp_float, if desired * Minor fixes: schema error and InputReader defaults * Allow pass through of Kp_float = 0 * Add flp parameters to schema * Change Fl_Mode default to 0 * Add defaults to omega_,zeta_ pc and vs, allow to be numbers * Allow single pitch tuning values in code, default U_pc to 0 * use nac acceleration for floating feedback * Fix TSR saturation for region 2.5operation * Modify system for constant power operation * Only modify pole for constant power above-rated * Remove GenEff from K calc * Update tuning, use constant power * use load_rosco_yaml * constant power * Fix broken tests * Include Fl_Mode=2 for nacelle pitching feedback * Add FOCAL inputs - hpf on floating feedback - lpf on wind speed estimator - associated schema updates * Set notch and check frequencies when Fl_Mode = 1 (fixes bug) * Skip filter step if there's an error * Update IEA-15MW test case DISCON with focal inputs * Allow Fl_Mode = 2 in ROSCO * Pass through lpf frequency * Add FOCAL tuning yaml * Set Cp contour number of levels * Add FOCAL params to various writers * Update/tune focal yaml * Add scripts for running FAST, tuning various parameters and cases * Add notebook for FAST plotting * Set up step case for testing * Change doubles to C_doubles * Define real and integer kinds, assign to all of ROSCO * Add ADJUSTL to DISCON error message * Fix Fl_Mode == 2 * Fix Fl_Mode == 2 again * Call yaw, flap, and debug only if enabled in DISOCN.IN * Make avrSWAP a ReKi and set constant kinds * Add DISCONs for testing - revert this later * Fix DISCON comparison, before DISCON's were overwritten by model * Rename DEBUG2.dbg to RootName.dbg2 * Update TestCase DISCONs to new input file * Add API change page in docs * Add link to API change on main page * Fix table headers * Fix title underlines * Fix tables again * Fix tables again * Fix version numbering in docs * Simplify FAST_directory in run_FAST * Versioning (#65) * use sphinx-rtd-theme * master doc and sphinx rtd theme * index back to root folder * only ignore install folders * remove hidden toctree * furo theme * update paths * convert rt version to string * update sphinx settings * move conf * furo theme * remove git versioning from cmake * use hard coded rosco_version * update intro write method * set nowrap for intel compilers * Add transfer of error message and clear message after each call * update install instructions * Catch nans in ROSCO at end of WSE * fix conda install typo * cleanup docs * Rename DEBUG2.dbg to RootName.dbg2 * Fix Fl_Mode == 2 * Fix Fl_Mode == 2 again * Allow Fl_Mode = 2 in ROSCO * Set notch and check frequencies when Fl_Mode = 1 (fixes bug) * Update FOCAL tuning yaml * Update TSR * Clean up and doc fix * Remove publish to pypi * Define all constant inputs to functions with kind typing * Generate Test_Case/ inputs automatically * Fix IEA15 DISCON path * Fix example 11 paths * Auto-generate tuning input yaml using schema * Add toolbox_input to doc index * Add toctree * Re-name title of toolbox_input Co-authored-by: Nikhar Abbas Co-authored-by: Xianping Du <38188001+Seager1989@users.noreply.github.com> Co-authored-by: nikhar-abbas <40865984+nikhar-abbas@users.noreply.github.com> * update listcheck method for numpy arrays * Open Loop Control (#98) * create rosco types yaml * Add more descriptions, add integer_c default, cleanup * updates for allocatability and shapes * python scripts to write ROSCO_types.f90 * reemove superfulous modules * use types from ROSCO registry * create rosco types yaml * Add more descriptions, add integer_c default, cleanup * updates for allocatability and shapes * python scripts to write ROSCO_types.f90 * reemove superfulous modules * use types from ROSCO registry * Saturate inputs to WSE. Needs some TLC, but seems to work * Reduce saturation limits on speed, torque * Re-organize, set saturation limits. Working at 3 m/s * Initial add of OL control to ROSCO: builds * Update DISCONs with open loop inputs * Fix file reading for OL_Filename * Add open loop control generation and file writing * Use DISCON_dict for more manageable DISCON file writing * Add open loop example, fix constant timeseries * Make open loop example generate power * Handle relative paths and calling from outside the run directory: - Some helper functions borrowed from OpenFAST, f/ext_control - Updated file writing * Clean up: versions, print statements * Fix SysFiles paths in CMakeLists * Tidy up Ext_DLL names * More Ext_DLL name tidying * Test write_registry.py * Update for OL Control * Move preprocessor lines * add zenodo DOI * Regenerated Types * fix shape * revert filepath change * give all types a size, ProcAddr size = 3 * update types * test registry in compile step * specify default shell * update write_registry path * remove default shell * Document API changes, provide OL input example * Fix example 14 (yaw input) * Add error catching to yaw control * Tidy up OL_Input Reading: error catching, generalize * More yaw control fixes, to model * Checkout develop CMakeLists for ROSCO * Update DISCON.INs for TestCases/ * Revert "Checkout develop CMakeLists for ROSCO" This reverts commit 87a491359d73806e3aaa59b4cfdc00f2838875df. * Revert windows cmake stuff to develop * Fix CMake again * Revert "Revert windows cmake stuff to develop" This reverts commit 39df122449b0e2055f2e12e3ce38a0c010c7bd91. * Make last cmake fix - hopefully Co-authored-by: Nikhar Abbas * Restart & registry (#99) * Convert WE saved variables to WE type * Put restart flag in localvars * Use saved filter params from LocalVar * save pitcomt last * Move IPC saved variables to localvars * Saved pi controller variables to localvar * Save RootMyb_Last to localvar * ROSCO_IO - initial commit. Include restart and debug functions * Use ROSCO IO and call restart functions * Remove debug from function.f90 * Save ACC Infile info * update for restart capabilities * add rosco_io with restart and debug functions * cleanup debug call * use registry generate types and IO * delete DFController * fix timestep mismatch * remove unnecessaray istatus check * close files * add reg test for restart * add restart option to run_openfast * add testing to CI, ignore generate files * fix fastcall * remove extra commas * specify gfortran-10 * testing flag cleanup * Use lv_strings to generate debug output * Revert "testing flag cleanup" This reverts commit 6f295563832413e96347acd82716f9aadac6d46c. * Revert "specify gfortran-10" This reverts commit 4c3154491523bcd542133ca2bce5803cdc94523f. * minor cleanup * Use kind from constants * Add some comments for clarity * put debug in if statements * separate reg tests from oother tests * Fl_Mode>0 * Remove hard coded values * Add filtered signals and WE_Vw to debug varrs * cd for regtest * Check logging level before calling debug * add fl_pitcom and pc_minpit to debugvars Co-authored-by: dzalkind * Break up if statement in open loop pitch (#100) * Break up if statement in open loop pitch * Make torque and yaw consistent with pitch: can start after some time * add bld edgewise freq to robust dict_inputs * Fix ccrotor inputs (#104) * remove interpolation of blade chord and twist * rename aerodynblade inputs * Update surface and DISCON.INs * Fix performance table paths * Allow default inputs (#110) * Allow defaults for AeroDyn inputs * Allow AeroDyn inputs to be floats, too * ipc (#105) * remove interpolation of blade chord and twist * rename aerodynblade inputs * Update surface and DISCON.INs * Fix performance table paths * Add proportional control and cleanup IPC * Add IPC and filtered RootMyc to registry * Better logic for filtering RootMOOP and fix notch filter slopes bug * Add cyclic flap conrol * Fix comments in ColemanTransformInverse * Addd IPC_KP to DISCON.IN * Error checking foro flp or ipc * add mutichannel plotting with tuples * add CMakeFiles to gitignore * Add IPC_KP to api changes * numerical qualifiers for error handling * add IPC gains to schema for pass-through ability * fix variable names * fix ipc gain printing bug * make sure IPC_KP is positive * Update Polars to point to coord files * ignore dbg2 files * Add IEA15MW_OL.yaml * update coord reader/writer * expand pitch_initial to 30 degrees * Add example 13 for IPC * Update cp surfaces and DISCONS * add examples to readme * cleanup and streaamline run_examples * Add IPC tuning vars * Allow IPC to command pitch value below peak shaving saturation limit * shorten simulation time * Fix Material parameter path * Update DISCONs again * Fix OL_Input reading * Set wind speed, rotor speed IC in example 14 * Debug OL reading * Add more debugging lines * Add more debugging lines 2 * Clean up, hone in on debug call * Disable logging level * Update discons - resolve conflict * Print when finished with ROSCO * add control packageg * Use PriPath and RootName to name dbg files * Print AvrSWAP * Revert "Use PriPath and RootName to name dbg files" This reverts commit 062fcaa55b3bf42d44f8a3f163aa883ab9552412. * Disable other examples * Print OL inputs * Allow logging level 3 * Print OL inputs * Make example shorter * Print more stuf * Print shape * Revert "Print OL inputs" This reverts commit 8e2a642bb35e46850f579ca4e69ca6d6fc93f4cc. * Update ROSCO Simulink model with IPC example * refactor flap tuning for normalization methods * improved flap controller filtering * delete extra F_FlpCornerFrerq * Update inputs, reader, and writer for OF 3.1.0 * Make sigma default interp type for multi_sigma * Use openfast 3.1.0 in CI * Fix leak...maybe * Use OF 3.1.0 in testing * Use gfotran for compile * Clean up print statements * Re-enable all examples * Update NREL-5MW AD file * Only check airfoil controls if more than one table * Update BAR models * Revert "Use gfotran for compile" This reverts commit 5a6e2b7e30287a09a09781e2ba12f9b578132e1f. * Install pyFAST for CI * Fix some paths in ex12 * Disable example 12 * Fix example 12 linear path, re-enable * Skip compilers install for mac * Try gfortran-9, no compilers * Try gfortran-10, no compilers * Skip windows compile in pytools * Re-enable windows, use gfortran as FC * Unset FC in windows * Set environment for windows when dependencies installed * Try setting environment in installation * Put conditional env setting in correct place * Try in setup again * Break up tasks: Windows vs. not * Update DISCONs * Update docs with new variables * Add example documentation * Update ROSCO Simulink model for 3.1.0 * Make IEA model float again * Reduce IEA timestep * Match DT to checkpoint time Co-authored-by: dzalkind * Increment version number * Bladed docs (#116) * Added image of Bladed control screen setup * Delete Bladed control screen.png * Adding image of Bladed control screen * Add files via upload * Minor edit 1 * Minor change 2 * Minor change 3 * Minor change 4 * Change 6 * Change 7 * Change 8 * Minor change 9 Co-authored-by: nikhar-abbas <40865984+nikhar-abbas@users.noreply.github.com> Co-authored-by: WillC-DNV <100850534+WillC-DNV@users.noreply.github.com> * Update version in API change docs * Bladed readthedocs (#117) * Added image of Bladed control screen setup * Delete Bladed control screen.png * Adding image of Bladed control screen * Add files via upload * Minor edit 1 * Minor change 2 * Minor change 3 * Minor change 4 * Change 6 * Change 7 * Change 8 * Minor change 9 * Tinker with characters in bladed instructions * Add bladed instructions to index * Change bladed toctree label * Do underline stuff * Make toctree label same as file * Remove colons from headers Co-authored-by: nikhar-abbas <40865984+nikhar-abbas@users.noreply.github.com> Co-authored-by: WillC-DNV <100850534+WillC-DNV@users.noreply.github.com> * Update docs to reflect CI process Co-authored-by: Nikhar Abbas Co-authored-by: Xianping Du <38188001+Seager1989@users.noreply.github.com> Co-authored-by: nikhar-abbas <40865984+nikhar-abbas@users.noreply.github.com> Co-authored-by: WillC-DNV <100850534+WillC-DNV@users.noreply.github.com> * Fixed wrong formatting of list items (#122) extra newline required between list elements * Regenerate types, IO with registry * Update registry so first timestep is printed * Update inverted notch to move frequency properly * Saturate inv notch corner frequency at 0 * Add tower damper mode flag * Add Azimuth tracking controller in Simulink * Always enable GenDOF, add options for simp_step * Add sweep for IPC gains and FA damper * Fix NumCoords in FAST_writer * Add turbulent case to runFAST/CaseLibrary * Add peak shaving sweep function * Increase default IPC_IntSat, make input parameter in future * Flip Ct and Cq table allocation (#129) * Flip Ct and Cq table allocation * Regen types * Remove print statements used for debugging * Update input files: IEA model has pitch actuator * Add back flap control (no idea when it was deleted) * Update discons, docs with API change * Add user-defined hh case * Fix AddF0 and RayleighDamp in FAST_reader * Add max_torque_factor for constant power control, flexible upper limit * Make update discons relative to tuning yaml * Update AddF0 and NumCoords in FAST_reader/writer * Remove matlab/rotor position control stuff Co-authored-by: nikhar-abbas <40865984+nikhar-abbas@users.noreply.github.com> Co-authored-by: Nikhar Abbas Co-authored-by: Xianping Du <38188001+Seager1989@users.noreply.github.com> Co-authored-by: WillC-DNV <100850534+WillC-DNV@users.noreply.github.com> Co-authored-by: Gustavo Hylander <74593034+ghylander@users.noreply.github.com> * Pass through (#136) * Convert WE saved variables to WE type * Put restart flag in localvars * Use saved filter params from LocalVar * save pitcomt last * Move IPC saved variables to localvars * Saved pi controller variables to localvar * Save RootMyb_Last to localvar * ROSCO_IO - initial commit. Include restart and debug functions * Use ROSCO IO and call restart functions * Remove debug from function.f90 * Save ACC Infile info * update for restart capabilities * add rosco_io with restart and debug functions * cleanup debug call * use registry generate types and IO * delete DFController * fix timestep mismatch * remove unnecessaray istatus check * close files * add reg test for restart * add restart option to run_openfast * add testing to CI, ignore generate files * fix fastcall * remove extra commas * specify gfortran-10 * testing flag cleanup * Use lv_strings to generate debug output * Revert "testing flag cleanup" This reverts commit 6f295563832413e96347acd82716f9aadac6d46c. * Revert "specify gfortran-10" This reverts commit 4c3154491523bcd542133ca2bce5803cdc94523f. * minor cleanup * Use kind from constants * Add some comments for clarity * put debug in if statements * separate reg tests from oother tests * Fl_Mode>0 * Remove hard coded values * Add filtered signals and WE_Vw to debug varrs * cd for regtest * Check logging level before calling debug * add fl_pitcom and pc_minpit to debugvars * Turn runFAST into a class * Refactor/simplify CaseLibrary * Implement initial pitch actuator * Set up steps case * Add actuator variable * Print first time step in debug outs * Fix FOCAL yaml * Set actuator to 0.25 Hz bandwidth * ROSCO 2.5.0 (#115) * FOCAL Updates (#64) * Update headers * fix bullets * make uppercase * Update turbine.py (#56) * Update turbine.py This add several lines for fixing the problem of repeated maximum values in the performance tables. This will cause the error (' the length of x and y is different.') of 'interpolate.interp1d.' * Add comments and catch when there are multiple optimal pitch angles Co-authored-by: dzalkind * increment version * Update for OpenFAST v3.0.0 * Update for OpenFAST v3.0.0 * Install OF3.0.0 for tests * update for OF v3.0.0 * add publish to pypi on release * Update to ROSCO v2.3.0 * Update Testing (#58) * Update scripts to run on eagle * Update IEA-15MW semi example: use peak shaving w/ ps_percen=0.8 * Add comparison plots to testing scripts * Update submit script for testing * Update for latest eagle runs * Add future to install dependencies * add TMax to self, define tmin in print_results * run tests in CI * generic ROSCO path * default to overwrite * fix path * import platform * separate run_testing * cleanup, specify lite test * don't run testing in after examples, oops. Co-authored-by: nikhar-abbas <40865984+nikhar-abbas@users.noreply.github.com> Co-authored-by: Nikhar Abbas * increment version * Update for OpenFAST v3.0.0 * Install OF3.0.0 for tests * update for OF v3.0.0 * add publish to pypi on release * Update to ROSCO v2.3.0 * Increment Version, OF3.0 (#57) * increment version * Update for OpenFAST v3.0.0 * Install OF3.0.0 for tests * update for OF v3.0.0 * add publish to pypi on release * Update to ROSCO v2.3.0 * increment version * Update for OpenFAST v3.0.0 * Install OF3.0.0 for tests * update for OF v3.0.0 * add publish to pypi on release * Update to ROSCO v2.3.0 * add ROSCO without submodule * move ROSCO source to ROSCO folder * Move cmake-related files to ROSCO * Add back pesky ErrVar * Remove parameters_files * Merge ROSCO and _toolbox gitignore * Fix .gitignore * Remove Examples/DISCON.IN from git * Fix and point example_01 to Tune_Cases/ * Update verbiage around using ofTools vs. weis * Fix and point example_04 to Tune_Cases/ * Clean up example_06 * Clean up example_07 * Only check FlpCornerFreq if using Flp control, fixes example 05 * Make example_04 consistent with others * Let example_05 run independently from 04 * Clean up example_05, wind files * Add schema and update empty tuning yaml inputs, not connected yet * Integrate schema into turbine, controller, and examples * Only check Fl filter parameters if Fl_Mode > 0, fix example_05 * bump version to 2.3 * Compile ROSCO from ROSCO dir * Rename to CI_rosco * Add omega vs. windspeed functionality * Fix tests: 5MW U_pc and 06 example dir * Make _Toolbox vs_minspeed in rotor frame to match ROSCO * Revert ServoDyn change * change rotor speed constraint to be epsilon * rename for clarity * docs major refresh * fix FA_AccF units in debug file * docs that build locally * Deallocate arrays in ROSCO, check in example_05 * Clean up comments * remove gitmodules * furo theme * furo in requirements * move readthedocs config file, remove furo import in conf.py * add docs requirements file * typo * move index out of source folder * trying to get furo to work * import date * fix versions and titles, cleanup readthedocs requirements * typo fix, remove extras * more cleanup * bump version * no furo extension, "hack" to load RT version * proper toctree paths * specify method * add mock modules * fix typos * update python install requirements * running locally * move index to main docs dir again * update to build locally * error during warnings * automated version * cleanup * remove old docs * re-add docs * simplify * fix figure path * try alabaster * remove archived docs * Add omega vs. windspeed functionality * Fix tests: 5MW U_pc and 06 example dir * more detailed sp.optimize settings * run MBC3 in parallel * restructure driver, run initialization doe for tuning * Try new dlclose function * Update example_05 to run simple simulation twice and check result * Revert deallocation stuff * Close discon library after every sim run * Test examples on macOS and windows * Run examples instead of testing on other platforms * Skip examples in windows for now * update paths and yaml load funciton * Skip mac testing of examples * provide default U_pc for single omega/zeta case * allow for float or list-like pc tuning inputs * Change name in setup.py * WE_Vw unit fix * Pass through kp_float, if desired * Minor fixes: schema error and InputReader defaults * cleeanup for improved stability * check for doe_logs as string in load_DOE * major restructure for rsched_driver class * cleanup verbosity * run serial by default * load_parallel as linturb_option * specific IEA15MW yaml for multi omega * remove unused module imports * fix error message types * lin_file as input * add comments on inputs to LinearTurbineModel init method * remove relative file paths * provide OpenFAST linearizations for IEA15MW UMaineSemi * put plotting in specific function * fix WE_lambda units * add self in on a few necessary variables * creaete example 12 for robust scheduling * try a few mbc3 locations for import * allow list-like or numpy arrays for omega_pc and zeta_pc schedules * create and use recorder setup function * Pass Through Kp_float (#57) * Pass through kp_float, if desired * Minor fixes: schema error and InputReader defaults * fix setup_recorder to work for optimization driver too * Allow pass through of Kp_float = 0 * cleanup om problems, update om0 calc * doe levels as input * negative k_float to account for OF conventions * cleanup print statements * variable name cleanup, use calculated k_float * Add defaults to omega_,zeta_ pc and vs, allow to be numbers * use standard tuning k_float as IC * formatting update * update problem setup methods * cleanup add_dv, enable adding design variables after problem is setup * change optimization step size * more setup restructure * update verbosity * use sphinx-rtd-theme * master doc and sphinx rtd theme * index back to root folder * only ignore install folders * remove hidden toctree * furo theme * update paths * convert rt version to string * update sphinx settings * move conf * furo theme * Mostly a docs update (#61) * rename for clarity * docs major refresh * fix FA_AccF units in debug file * docs that build locally * remove gitmodules * furo theme * furo in requirements * move readthedocs config file, remove furo import in conf.py * add docs requirements file * typo * move index out of source folder * trying to get furo to work * import date * fix versions and titles, cleanup readthedocs requirements * typo fix, remove extras * more cleanup * bump version * no furo extension, "hack" to load RT version * proper toctree paths * specify method * add mock modules * fix typos * update python install requirements * running locally * move index to main docs dir again * update to build locally * error during warnings * automated version * cleanup * remove old docs * re-add docs * simplify * fix figure path * try alabaster * remove archived docs * use sphinx-rtd-theme * master doc and sphinx rtd theme * index back to root folder * only ignore install folders * remove hidden toctree * furo theme * update paths * convert rt version to string * update sphinx settings * move conf * furo theme * Pass through Kp_float = 0 (#59) * Pass through kp_float, if desired * Minor fixes: schema error and InputReader defaults * Allow pass through of Kp_float = 0 * Add flp parameters to schema * Change Fl_Mode default to 0 * Add defaults to omega_,zeta_ pc and vs, allow to be numbers * Allow single pitch tuning values in code, default U_pc to 0 * use nac acceleration for floating feedback * Fix TSR saturation for region 2.5operation * Modify system for constant power operation * Only modify pole for constant power above-rated * Remove GenEff from K calc * Update tuning, use constant power * use load_rosco_yaml * constant power * Fix broken tests * Include Fl_Mode=2 for nacelle pitching feedback * Add FOCAL inputs - hpf on floating feedback - lpf on wind speed estimator - associated schema updates * Set notch and check frequencies when Fl_Mode = 1 (fixes bug) * Skip filter step if there's an error * Update IEA-15MW test case DISCON with focal inputs * Allow Fl_Mode = 2 in ROSCO * Pass through lpf frequency * Add FOCAL tuning yaml * Set Cp contour number of levels * Add FOCAL params to various writers * Update/tune focal yaml * Add scripts for running FAST, tuning various parameters and cases * Add notebook for FAST plotting * Set up step case for testing * Change doubles to C_doubles * Define real and integer kinds, assign to all of ROSCO * Add ADJUSTL to DISCON error message * Fix Fl_Mode == 2 * Fix Fl_Mode == 2 again * Call yaw, flap, and debug only if enabled in DISOCN.IN * Make avrSWAP a ReKi and set constant kinds * Add DISCONs for testing - revert this later * Fix DISCON comparison, before DISCON's were overwritten by model * Rename DEBUG2.dbg to RootName.dbg2 * Update TestCase DISCONs to new input file * Add API change page in docs * Add link to API change on main page * Fix table headers * Fix title underlines * Fix tables again * Fix tables again * Fix version numbering in docs * Simplify FAST_directory in run_FAST * Versioning (#65) * use sphinx-rtd-theme * master doc and sphinx rtd theme * index back to root folder * only ignore install folders * remove hidden toctree * furo theme * update paths * convert rt version to string * update sphinx settings * move conf * furo theme * remove git versioning from cmake * use hard coded rosco_version * update intro write method * set nowrap for intel compilers * Add transfer of error message and clear message after each call * update install instructions * Catch nans in ROSCO at end of WSE * fix conda install typo * cleanup docs * Rename DEBUG2.dbg to RootName.dbg2 * Fix Fl_Mode == 2 * Fix Fl_Mode == 2 again * Allow Fl_Mode = 2 in ROSCO * Set notch and check frequencies when Fl_Mode = 1 (fixes bug) * Update FOCAL tuning yaml * Update TSR * Clean up and doc fix * Remove publish to pypi * Define all constant inputs to functions with kind typing * Generate Test_Case/ inputs automatically * Fix IEA15 DISCON path * Fix example 11 paths * Auto-generate tuning input yaml using schema * Add toolbox_input to doc index * Add toctree * Re-name title of toolbox_input Co-authored-by: Nikhar Abbas Co-authored-by: Xianping Du <38188001+Seager1989@users.noreply.github.com> Co-authored-by: nikhar-abbas <40865984+nikhar-abbas@users.noreply.github.com> * update listcheck method for numpy arrays * Open Loop Control (#98) * create rosco types yaml * Add more descriptions, add integer_c default, cleanup * updates for allocatability and shapes * python scripts to write ROSCO_types.f90 * reemove superfulous modules * use types from ROSCO registry * create rosco types yaml * Add more descriptions, add integer_c default, cleanup * updates for allocatability and shapes * python scripts to write ROSCO_types.f90 * reemove superfulous modules * use types from ROSCO registry * Saturate inputs to WSE. Needs some TLC, but seems to work * Reduce saturation limits on speed, torque * Re-organize, set saturation limits. Working at 3 m/s * Initial add of OL control to ROSCO: builds * Update DISCONs with open loop inputs * Fix file reading for OL_Filename * Add open loop control generation and file writing * Use DISCON_dict for more manageable DISCON file writing * Add open loop example, fix constant timeseries * Make open loop example generate power * Handle relative paths and calling from outside the run directory: - Some helper functions borrowed from OpenFAST, f/ext_control - Updated file writing * Clean up: versions, print statements * Fix SysFiles paths in CMakeLists * Tidy up Ext_DLL names * More Ext_DLL name tidying * Test write_registry.py * Update for OL Control * Move preprocessor lines * add zenodo DOI * Regenerated Types * fix shape * revert filepath change * give all types a size, ProcAddr size = 3 * update types * test registry in compile step * specify default shell * update write_registry path * remove default shell * Document API changes, provide OL input example * Fix example 14 (yaw input) * Add error catching to yaw control * Tidy up OL_Input Reading: error catching, generalize * More yaw control fixes, to model * Checkout develop CMakeLists for ROSCO * Update DISCON.INs for TestCases/ * Revert "Checkout develop CMakeLists for ROSCO" This reverts commit 87a491359d73806e3aaa59b4cfdc00f2838875df. * Revert windows cmake stuff to develop * Fix CMake again * Revert "Revert windows cmake stuff to develop" This reverts commit 39df122449b0e2055f2e12e3ce38a0c010c7bd91. * Make last cmake fix - hopefully Co-authored-by: Nikhar Abbas * Restart & registry (#99) * Convert WE saved variables to WE type * Put restart flag in localvars * Use saved filter params from LocalVar * save pitcomt last * Move IPC saved variables to localvars * Saved pi controller variables to localvar * Save RootMyb_Last to localvar * ROSCO_IO - initial commit. Include restart and debug functions * Use ROSCO IO and call restart functions * Remove debug from function.f90 * Save ACC Infile info * update for restart capabilities * add rosco_io with restart and debug functions * cleanup debug call * use registry generate types and IO * delete DFController * fix timestep mismatch * remove unnecessaray istatus check * close files * add reg test for restart * add restart option to run_openfast * add testing to CI, ignore generate files * fix fastcall * remove extra commas * specify gfortran-10 * testing flag cleanup * Use lv_strings to generate debug output * Revert "testing flag cleanup" This reverts commit 6f295563832413e96347acd82716f9aadac6d46c. * Revert "specify gfortran-10" This reverts commit 4c3154491523bcd542133ca2bce5803cdc94523f. * minor cleanup * Use kind from constants * Add some comments for clarity * put debug in if statements * separate reg tests from oother tests * Fl_Mode>0 * Remove hard coded values * Add filtered signals and WE_Vw to debug varrs * cd for regtest * Check logging level before calling debug * add fl_pitcom and pc_minpit to debugvars Co-authored-by: dzalkind * Break up if statement in open loop pitch (#100) * Break up if statement in open loop pitch * Make torque and yaw consistent with pitch: can start after some time * add bld edgewise freq to robust dict_inputs * Fix ccrotor inputs (#104) * remove interpolation of blade chord and twist * rename aerodynblade inputs * Update surface and DISCON.INs * Fix performance table paths * Allow default inputs (#110) * Allow defaults for AeroDyn inputs * Allow AeroDyn inputs to be floats, too * ipc (#105) * remove interpolation of blade chord and twist * rename aerodynblade inputs * Update surface and DISCON.INs * Fix performance table paths * Add proportional control and cleanup IPC * Add IPC and filtered RootMyc to registry * Better logic for filtering RootMOOP and fix notch filter slopes bug * Add cyclic flap conrol * Fix comments in ColemanTransformInverse * Addd IPC_KP to DISCON.IN * Error checking foro flp or ipc * add mutichannel plotting with tuples * add CMakeFiles to gitignore * Add IPC_KP to api changes * numerical qualifiers for error handling * add IPC gains to schema for pass-through ability * fix variable names * fix ipc gain printing bug * make sure IPC_KP is positive * Update Polars to point to coord files * ignore dbg2 files * Add IEA15MW_OL.yaml * update coord reader/writer * expand pitch_initial to 30 degrees * Add example 13 for IPC * Update cp surfaces and DISCONS * add examples to readme * cleanup and streaamline run_examples * Add IPC tuning vars * Allow IPC to command pitch value below peak shaving saturation limit * shorten simulation time * Fix Material parameter path * Update DISCONs again * Fix OL_Input reading * Set wind speed, rotor speed IC in example 14 * Debug OL reading * Add more debugging lines * Add more debugging lines 2 * Clean up, hone in on debug call * Disable logging level * Update discons - resolve conflict * Print when finished with ROSCO * add control packageg * Use PriPath and RootName to name dbg files * Print AvrSWAP * Revert "Use PriPath and RootName to name dbg files" This reverts commit 062fcaa55b3bf42d44f8a3f163aa883ab9552412. * Disable other examples * Print OL inputs * Allow logging level 3 * Print OL inputs * Make example shorter * Print more stuf * Print shape * Revert "Print OL inputs" This reverts commit 8e2a642bb35e46850f579ca4e69ca6d6fc93f4cc. * Update ROSCO Simulink model with IPC example * refactor flap tuning for normalization methods * improved flap controller filtering * delete extra F_FlpCornerFrerq * Update inputs, reader, and writer for OF 3.1.0 * Make sigma default interp type for multi_sigma * Use openfast 3.1.0 in CI * Fix leak...maybe * Use OF 3.1.0 in testing * Use gfotran for compile * Clean up print statements * Re-enable all examples * Update NREL-5MW AD file * Only check airfoil controls if more than one table * Update BAR models * Revert "Use gfotran for compile" This reverts commit 5a6e2b7e30287a09a09781e2ba12f9b578132e1f. * Install pyFAST for CI * Fix some paths in ex12 * Disable example 12 * Fix example 12 linear path, re-enable * Skip compilers install for mac * Try gfortran-9, no compilers * Try gfortran-10, no compilers * Skip windows compile in pytools * Re-enable windows, use gfortran as FC * Unset FC in windows * Set environment for windows when dependencies installed * Try setting environment in installation * Put conditional env setting in correct place * Try in setup again * Break up tasks: Windows vs. not * Update DISCONs * Update docs with new variables * Add example documentation * Update ROSCO Simulink model for 3.1.0 * Make IEA model float again * Reduce IEA timestep * Match DT to checkpoint time Co-authored-by: dzalkind * Increment version number * Bladed docs (#116) * Added image of Bladed control screen setup * Delete Bladed control screen.png * Adding image of Bladed control screen * Add files via upload * Minor edit 1 * Minor change 2 * Minor change 3 * Minor change 4 * Change 6 * Change 7 * Change 8 * Minor change 9 Co-authored-by: nikhar-abbas <40865984+nikhar-abbas@users.noreply.github.com> Co-authored-by: WillC-DNV <100850534+WillC-DNV@users.noreply.github.com> * Update version in API change docs * Bladed readthedocs (#117) * Added image of Bladed control screen setup * Delete Bladed control screen.png * Adding image of Bladed control screen * Add files via upload * Minor edit 1 * Minor change 2 * Minor change 3 * Minor change 4 * Change 6 * Change 7 * Change 8 * Minor change 9 * Tinker with characters in bladed instructions * Add bladed instructions to index * Change bladed toctree label * Do underline stuff * Make toctree label same as file * Remove colons from headers Co-authored-by: nikhar-abbas <40865984+nikhar-abbas@users.noreply.github.com> Co-authored-by: WillC-DNV <100850534+WillC-DNV@users.noreply.github.com> * Update docs to reflect CI process Co-authored-by: Nikhar Abbas Co-authored-by: Xianping Du <38188001+Seager1989@users.noreply.github.com> Co-authored-by: nikhar-abbas <40865984+nikhar-abbas@users.noreply.github.com> Co-authored-by: WillC-DNV <100850534+WillC-DNV@users.noreply.github.com> * Fixed wrong formatting of list items (#122) extra newline required between list elements * Regenerate types, IO with registry * Update registry so first timestep is printed * Update inverted notch to move frequency properly * Saturate inv notch corner frequency at 0 * Add tower damper mode flag * Add Azimuth tracking controller in Simulink * Always enable GenDOF, add options for simp_step * Add sweep for IPC gains and FA damper * Fix NumCoords in FAST_writer * Add turbulent case to runFAST/CaseLibrary * Add peak shaving sweep function * Increase default IPC_IntSat, make input parameter in future * Flip Ct and Cq table allocation (#129) * Flip Ct and Cq table allocation * Regen types * Remove print statements used for debugging * Update input files: IEA model has pitch actuator * Add back flap control (no idea when it was deleted) * Update discons, docs with API change * Add user-defined hh case * Fix AddF0 and RayleighDamp in FAST_reader * Add max_torque_factor for constant power control, flexible upper limit * Make update discons relative to tuning yaml * Update AddF0 and NumCoords in FAST_reader/writer * Remove matlab/rotor position control stuff * Add initial DISCON pass through schema * Add TODO items for pull requests * Add initial pass through capability, example * Add PassThrough example yaml * Make cp filename relative to FAST_directory throughout * Remove brackets, regen input docs * Add to PassThrough example yaml * Add example 15 to testing, fix yaml * Tidy comments in CaseLibrary Co-authored-by: nikhar-abbas <40865984+nikhar-abbas@users.noreply.github.com> Co-authored-by: Nikhar Abbas Co-authored-by: Xianping Du <38188001+Seager1989@users.noreply.github.com> Co-authored-by: WillC-DNV <100850534+WillC-DNV@users.noreply.github.com> Co-authored-by: Gustavo Hylander <74593034+ghylander@users.noreply.github.com> * Robust control updates (#139) * change default interp type * improve nested MPI handling * fix cl bug, sm calc more robust, allow single plant for interp * add load from pickle capabilites * add re-try logic * save v_above_rated to controller object * fix BAR cp_ct_cq surface path * update discons * remove rogue DISCON * External Control Interface (#141) * Add ExtControl manually from f/ext_control, compiling * Fix Cp plots * Update multiple discons * Make FAST_Directory relative to yaml * Set control to ROSCO, sweep max torque * Fix c_float type in registry, building * Update DISCON writer, fix reader * Add example for running Ext control, running * Max example actually call extdll, update inputs, running * Add ExtControl module! * Add ROSCO_Helpers, GetNewUnit, shorten ReadSetParameters, Functions * Update write_registry with GetNewUnit * Tidy up RootName: remove hard-coded index * Close Cp file, fixes checkpoint test * Clean up examples, add 16 to CI testing * Change regtest name in CI * Update DISCONs * Add API change documentation * Add summary of API changes, finish external interface * Tidy code, point to location for using ExtDLL * F/zmq (#145) * cleanup api change table * zeromq client and f90 files - initia lcommit * add zmq install reqs * remove yaw-by-ipc * typo fix * add zeroMQ interface to registry and source - enable zeroMQ for yaw control * cleanup to compile, move ZMQ_Mode to flags, write DISCONS * only set ZMQ_Client if flag is enabled * fix bug in discons * minor updates and add sim with wind direction * change to dict inputs for control interface * add zmq example * Revert "remove yaw-by-ipc" This reverts commit 2ca2859884313aa6d8fdd217a7fede73802a5fcf. * Enable Yaw-by-ipc again * update and execute zeromq example * add zmq to dependencies * sudo for apt-get * libzmq3-dev typo * setup cmake * rename example 16 to 17 * read empty line * update types, regen discons * fix build path * remove non-ubuntu examples, type in cmake command * Set ROSCO=True * typo fix and update DISCONs * document API changes * newlines and in-text code * updated removed inputs, fix intext code syntax * run example 17 * Add description to example 17 * zeromq -> pyzmq, cleanup * better table for new/modified/removed * fix real(8) * cleanup zmqVar conventions and uses. Call zmq using a time period * Update DISCONS * run all examples * Fix Y_uSwitch description * update comm address example * execute with runpy instead of importlib * move zmq interface classes to control_interface * Properly shutdown ZMQ interface * add IEA15MW_ExtInterface.yaml * Incorporate runFAST stuff from WEIS, clean up * Remove specific rosco_dll * Publish artifacts from examples * Clean up examples following runFAST business * move archive artifacts * Fix build dir in example 17 * Switch install/develop in pytools CI * archive even if exampless fail * add zmq build instructions * cleanup and rename sim * Remove BITS_IN_ADDR stuff * Pass case_inputs and rosco_dll to runFAST object * Pass correct DLL_FileName for external control * Tidy example 15 commenting Co-authored-by: dzalkind * Generalize update discons * Update PR template * Update update discons * Nyquist plotting (#157) * change default interp type * improve nested MPI handling * fix cl bug, sm calc more robust, allow single plant for interp * add load from pickle capabilites * add re-try logic * save v_above_rated to controller object * fix BAR cp_ct_cq surface path * update discons * remove rogue DISCON * Add linear model visualization tools * plot nyquist * remove plt.show() * fix indexing, windspeed * Comments (#150) * cleanup api change table * Update comments to describe zmq modules and functions better * comment and cleanup controller-related moduels * cleanup and comments for turbine modules * psuedo functions for weird interpolation steps * minor sim cleanup * More comments for robust tuning procedures * add descriptions and comments for robust scheduling * Add some comments * Add Ct_max comment Co-authored-by: dzalkind * Update ROSCO_walkthrough to use new yaml reader (#159) * Update ROSCO_walkthrough to use new yaml reader * Add CI for notebooks * Make parameter_filename a relative path * Generalize dylib extension in RW * Update to openfast==3.2.0, no API changes! (#160) * Updates in preparation for ROSCO 2.6.0 (#161) * ROSCO 2.5.0 (#115) * FOCAL Updates (#64) * Update headers * fix bullets * make uppercase * Update turbine.py (#56) * Update turbine.py This add several lines for fixing the problem of repeated maximum values in the performance tables. This will cause the error (' the length of x and y is different.') of 'interpolate.interp1d.' * Add comments and catch when there are multiple optimal pitch angles Co-authored-by: dzalkind * increment version * Update for OpenFAST v3.0.0 * Update for OpenFAST v3.0.0 * Install OF3.0.0 for tests * update for OF v3.0.0 * add publish to pypi on release * Update to ROSCO v2.3.0 * Update Testing (#58) * Update scripts to run on eagle * Update IEA-15MW semi example: use peak shaving w/ ps_percen=0.8 * Add comparison plots to testing scripts * Update submit script for testing * Update for latest eagle runs * Add future to install dependencies * add TMax to self, define tmin in print_results * run tests in CI * generic ROSCO path * default to overwrite * fix path * import platform * separate run_testing * cleanup, specify lite test * don't run testing in after examples, oops. Co-authored-by: nikhar-abbas <40865984+nikhar-abbas@users.noreply.github.com> Co-authored-by: Nikhar Abbas * increment version * Update for OpenFAST v3.0.0 * Install OF3.0.0 for tests * update for OF v3.0.0 * add publish to pypi on release * Update to ROSCO v2.3.0 * Increment Version, OF3.0 (#57) * increment version * Update for OpenFAST v3.0.0 * Install OF3.0.0 for tests * update for OF v3.0.0 * add publish to pypi on release * Update to ROSCO v2.3.0 * increment version * Update for OpenFAST v3.0.0 * Install OF3.0.0 for tests * update for OF v3.0.0 * add publish to pypi on release * Update to ROSCO v2.3.0 * add ROSCO without submodule * move ROSCO source to ROSCO folder * Move cmake-related files to ROSCO * Add back pesky ErrVar * Remove parameters_files * Merge ROSCO and _toolbox gitignore * Fix .gitignore * Remove Examples/DISCON.IN from git * Fix and point example_01 to Tune_Cases/ * Update verbiage around using ofTools vs. weis * Fix and point example_04 to Tune_Cases/ * Clean up example_06 * Clean up example_07 * Only check FlpCornerFreq if using Flp control, fixes example 05 * Make example_04 consistent with others * Let example_05 run independently from 04 * Clean up example_05, wind files * Add schema and update empty tuning yaml inputs, not connected yet * Integrate schema into turbine, controller, and examples * Only check Fl filter parameters if Fl_Mode > 0, fix example_05 * bump version to 2.3 * Compile ROSCO from ROSCO dir * Rename to CI_rosco * Add omega vs. windspeed functionality * Fix tests: 5MW U_pc and 06 example dir * Make _Toolbox vs_minspeed in rotor frame to match ROSCO * Revert ServoDyn change * change rotor speed constraint to be epsilon * rename for clarity * docs major refresh * fix FA_AccF units in debug file * docs that build locally * Deallocate arrays in ROSCO, check in example_05 * Clean up comments * remove gitmodules * furo theme * furo in requirements * move readthedocs config file, remove furo import in conf.py * add docs requirements file * typo * move index out of source folder * trying to get furo to work * import date * fix versions and titles, cleanup readthedocs requirements * typo fix, remove extras * more cleanup * bump version * no furo extension, "hack" to load RT version * proper toctree paths * specify method * add mock modules * fix typos * update python install requirements * running locally * move index to main docs dir again * update to build locally * error during warnings * automated version * cleanup * remove old docs * re-add docs * simplify * fix figure path * try alabaster * remove archived docs * Add omega vs. windspeed functionality * Fix tests: 5MW U_pc and 06 example dir * more detailed sp.optimize settings * run MBC3 in parallel * restructure driver, run initialization doe for tuning * Try new dlclose function * Update example_05 to run simple simulation twice and check result * Revert deallocation stuff * Close discon library after every sim run * Test examples on macOS and windows * Run examples instead of testing on other platforms * Skip examples in windows for now * update paths and yaml load funciton * Skip mac testing of examples * provide default U_pc for single omega/zeta case * allow for float or list-like pc tuning inputs * Change name in setup.py * WE_Vw unit fix * Pass through kp_float, if desired * Minor fixes: schema error and InputReader defaults * cleeanup for improved stability * check for doe_logs as string in load_DOE * major restructure for rsched_driver class * cleanup verbosity * run serial by default * load_parallel as linturb_option * specific IEA15MW yaml for multi omega * remove unused module imports * fix error message types * lin_file as input * add comments on inputs to LinearTurbineModel init method * remove relative file paths * provide OpenFAST linearizations for IEA15MW UMaineSemi * put plotting in specific function * fix WE_lambda units * add self in on a few necessary variables * creaete example 12 for robust scheduling * try a few mbc3 locations for import * allow list-like or numpy arrays for omega_pc and zeta_pc schedules * create and use recorder setup function * Pass Through Kp_float (#57) * Pass through kp_float, if desired * Minor fixes: schema error and InputReader defaults * fix setup_recorder to work for optimization driver too * Allow pass through of Kp_float = 0 * cleanup om problems, update om0 calc * doe levels as input * negative k_float to account for OF conventions * cleanup print statements * variable name cleanup, use calculated k_float * Add defaults to omega_,zeta_ pc and vs, allow to be numbers * use standard tuning k_float as IC * formatting update * update problem setup methods * cleanup add_dv, enable adding design variables after problem is setup * change optimization step size * more setup restructure * update verbosity * use sphinx-rtd-theme * master doc and sphinx rtd theme * index back to root folder * only ignore install folders * remove hidden toctree * furo theme * update paths * convert rt version to string * update sphinx settings * move conf * furo theme * Mostly a docs update (#61) * rename for clarity * docs major refresh * fix FA_AccF units in debug file * docs that build locally * remove gitmodules * furo theme * furo in requirements * move readthedocs config file, remove furo import in conf.py * add docs requirements file * typo * move index out of source folder * trying to get furo to work * import date * fix versions and titles, cleanup readthedocs requirements * typo fix, remove extras * more cleanup * bump version * no furo extension, "hack" to load RT version * proper toctree paths * specify method * add mock modules * fix typos * update python install requirements * running locally * move index to main docs dir again * update to build locally * error during warnings * automated version * cleanup * remove old docs * re-add docs * simplify * fix figure path * try alabaster * remove archived docs * use sphinx-rtd-theme * master doc and sphinx rtd theme * index back to root folder * only ignore install folders * remove hidden toctree * furo theme * update paths * convert rt version to string * update sphinx settings * move conf * furo theme * Pass through Kp_float = 0 (#59) * Pass through kp_float, if desired * Minor fixes: schema error and InputReader defaults * Allow pass through of Kp_float = 0 * Add flp parameters to schema * Change Fl_Mode default to 0 * Add defaults to omega_,zeta_ pc and vs, allow to be numbers * Allow single pitch tuning values in code, default U_pc to 0 * use nac acceleration for floating feedback * Fix TSR saturation for region 2.5operation * Modify system for constant power operation * Only modify pole for constant power above-rated * Remove GenEff from K calc * Update tuning, use constant power * use load_rosco_yaml * constant power * Fix broken tests * Include Fl_Mode=2 for nacelle pitching feedback * Add FOCAL inputs - hpf on floating feedback - lpf on wind speed estimator - associated schema updates * Set notch and check frequencies when Fl_Mode = 1 (fixes bug) * Skip filter step if there's an error * Update IEA-15MW test case DISCON with focal inputs * Allow Fl_Mode = 2 in ROSCO * Pass through lpf frequency * Add FOCAL tuning yaml * Set Cp contour number of levels * Add FOCAL params to various writers * Update/tune focal yaml * Add scripts for running FAST, tuning various parameters and cases * Add notebook for FAST plotting * Set up step case for testing * Change doubles to C_doubles * Define real and integer kinds, assign to all of ROSCO * Add ADJUSTL to DISCON error message * Fix Fl_Mode == 2 * Fix Fl_Mode == 2 again * Call yaw, flap, and debug only if enabled in DISOCN.IN * Make avrSWAP a ReKi and set constant kinds * Add DISCONs for testing - revert this later * Fix DISCON comparison, before DISCON's were overwritten by model * Rename DEBUG2.dbg to RootName.dbg2 * Update TestCase DISCONs to new input file * Add API change page in docs * Add link to API change on main page * Fix table headers * Fix title underlines * Fix tables again * Fix tables again * Fix version numbering in docs * Simplify FAST_directory in run_FAST * Versioning (#65) * use sphinx-rtd-theme * master doc and sphinx rtd theme * index back to root folder * only ignore install folders * remove hidden toctree * furo theme * update paths * convert rt version to string * update sphinx settings * move conf * furo theme * remove git versioning from cmake * use hard coded rosco_version * update intro write method * set nowrap for intel compilers * Add transfer of error message and clear message after each call * update install instructions * Catch nans in ROSCO at end of WSE * fix conda install typo * cleanup docs * Rename DEBUG2.dbg to RootName.dbg2 * Fix Fl_Mode == 2 * Fix Fl_Mode == 2 again * Allow Fl_Mode = 2 in ROSCO * Set notch and check frequencies when Fl_Mode = 1 (fixes bug) * Update FOCAL tuning yaml * Update TSR * Clean up and doc fix * Remove publish to pypi * Define all constant inputs to functions with kind typing * Generate Test_Case/ inputs automatically * Fix IEA15 DISCON path * Fix example 11 paths * Auto-generate tuning input yaml using schema * Add toolbox_input to doc index * Add toctree * Re-name title of toolbox_input Co-authored-by: Nikhar Abbas Co-authored-by: Xianping Du <38188001+Seager1989@users.noreply.github.com> Co-authored-by: nikhar-abbas <40865984+nikhar-abbas@users.noreply.github.com> * update listcheck method for numpy arrays * Open Loop Control (#98) * create rosco types yaml * Add more descriptions, add integer_c default, cleanup * updates for allocatability and shapes * python scripts to write ROSCO_types.f90 * reemove superfulous modules * use types from ROSCO registry * create rosco types yaml * Add more descriptions, add integer_c default, cleanup * updates for allocatability and shapes * python scripts to write ROSCO_types.f90 * reemove superfulous modules * use types from ROSCO registry * Saturate inputs to WSE. Needs some TLC, but seems to work * Reduce saturation limits on speed, torque * Re-organize, set saturation limits. Working at 3 m/s * Initial add of OL control to ROSCO: builds * Update DISCONs with open loop inputs * Fix file reading for OL_Filename * Add open loop control generation and file writing * Use DISCON_dict for more manageable DISCON file writing * Add open loop example, fix constant timeseries * Make open loop example generate power * Handle relative paths and calling from outside the run directory: - Some helper functions borrowed from OpenFAST, f/ext_control - Updated file writing * Clean up: versions, print statements * Fix SysFiles paths in CMakeLists * Tidy up Ext_DLL names * More Ext_DLL name tidying * Test write_registry.py * Update for OL Control * Move preprocessor lines * add zenodo DOI * Regenerated Types * fix shape * revert filepath change * give all types a size, ProcAddr size = 3 * update types * test registry in compile step * specify default shell * update write_registry path * remove default shell * Document API changes, provide OL input example * Fix example 14 (yaw input) * Add error catching to yaw control * Tidy up OL_Input Reading: error catching, generalize * More yaw control fixes, to model * Checkout develop CMakeLists for ROSCO * Update DISCON.INs for TestCases/ * Revert "Checkout develop CMakeLists for ROSCO" This reverts commit 87a491359d73806e3aaa59b4cfdc00f2838875df. * Revert windows cmake stuff to develop * Fix CMake again * Revert "Revert windows cmake stuff to develop" This reverts commit 39df122449b0e2055f2e12e3ce38a0c010c7bd91. * Make last cmake fix - hopefully Co-authored-by: Nikhar Abbas * Restart & registry (#99) * Convert WE saved variables to WE type * Put restart flag in localvars * Use saved filter params from LocalVar * save pitcomt last * Move IPC saved variables to localvars * Saved pi controller variables to localvar * Save RootMyb_Last to localvar * ROSCO_IO - initial commit. Include restart and debug functions * Use ROSCO IO and call restart functions * Remove debug from function.f90 * Save ACC Infile info * update for restart capabilities * add rosco_io with restart and debug functions * cleanup debug call * use registry generate types and IO * delete DFController * fix timestep mismatch * remove unnecessaray istatus check * close files * add reg test for restart * add restart option to run_openfast * add testing to CI, ignore generate files * fix fastcall * remove extra commas * specify gfortran-10 * testing flag cleanup * Use lv_strings to generate debug output * Revert "testing flag cleanup" This reverts commit 6f295563832413e96347acd82716f9aadac6d46c. * Revert "specify gfortran-10" This reverts commit 4c3154491523bcd542133ca2bce5803cdc94523f. * minor cleanup * Use kind from constants * Add some comments for clarity * put debug in if statements * separate reg tests from oother tests * Fl_Mode>0 * Remove hard coded values * Add filtered signals and WE_Vw to debug varrs * cd for regtest * Check logging level before calling debug * add fl_pitcom and pc_minpit to debugvars Co-authored-by: dzalkind * Break up if statement in open loop pitch (#100) * Break up if statement in open loop pitch * Make torque and yaw consistent with pitch: can start after some time * add bld edgewise freq to robust dict_inputs * Fix ccrotor inputs (#104) * remove interpolation of blade chord and twist * rename aerodynblade inputs * Update surface and DISCON.INs * Fix performance table paths * Allow default inputs (#110) * Allow defaults for AeroDyn inputs * Allow AeroDyn inputs to be floats, too * ipc (#105) * remove interpolation of blade chord and twist * rename aerodynblade inputs * Update surface and DISCON.INs * Fix performance table paths * Add proportional control and cleanup IPC * Add IPC and filtered RootMyc to registry * Better logic for filtering RootMOOP and fix notch filter slopes bug * Add cyclic flap conrol * Fix comments in ColemanTransformInverse * Addd IPC_KP to DISCON.IN * Error checking foro flp or ipc * add mutichannel plotting with tuples * add CMakeFiles to gitignore * Add IPC_KP to api changes * numerical qualifiers for error handling * add IPC gains to schema for pass-through ability * fix variable names * fix ipc gain printing bug * make sure IPC_KP is positive * Update Polars to point to coord files * ignore dbg2 files * Add IEA15MW_OL.yaml * update coord reader/writer * expand pitch_initial to 30 degrees * Add example 13 for IPC * Update cp surfaces and DISCONS * add examples to readme * cleanup and streaamline run_examples * Add IPC tuning vars * Allow IPC to command pitch value below peak shaving saturation limit * shorten simulation time * Fix Material parameter path * Update DISCONs again * Fix OL_Input reading * Set wind speed, rotor speed IC in example 14 * Debug OL reading * Add more debugging lines * Add more debugging lines 2 * Clean up, hone in on debug call * Disable logging level * Update discons - resolve conflict * Print when finished with ROSCO * add control packageg * Use PriPath and RootName to name dbg files * Print AvrSWAP * Revert "Use PriPath and RootName to name dbg files" This reverts commit 062fcaa55b3bf42d44f8a3f163aa883ab9552412. * Disable other examples * Print OL inputs * Allow logging level 3 * Print OL inputs * Make example shorter * Print more stuf * Print shape * Revert "Print OL inputs" This reverts commit 8e2a642bb35e46850f579ca4e69ca6d6fc93f4cc. * Update ROSCO Simulink model with IPC example * refactor flap tuning for normalization methods * improved flap controller filtering * delete extra F_FlpCornerFrerq * Update inputs, reader, and writer for OF 3.1.0 * Make sigma default interp type for multi_sigma * Use openfast 3.1.0 in CI * Fix leak...maybe * Use OF 3.1.0 in testing * Use gfotran for compile * Clean up print statements * Re-enable all examples * Update NREL-5MW AD file * Only check airfoil controls if more than one table * Update BAR models * Revert "Use gfotran for compile" This reverts commit 5a6e2b7e30287a09a09781e2ba12f9b578132e1f. * Install pyFAST for CI * Fix some paths in ex12 * Disable example 12 * Fix example 12 linear path, re-enable * Skip compilers install for mac * Try gfortran-9, no compilers * Try gfortran-10, no compilers * Skip windows compile in pytools * Re-enable windows, use gfortran as FC * Unset FC in windows * Set environment for windows when dependencies installed * Try setting environment in installation * Put conditional env setting in correct place * Try in setup again * Break up tasks: Windows vs. not * Update DISCONs * Update docs with new variables * Add example documentation * Update ROSCO Simulink model for 3.1.0 * Make IEA model float again * Reduce IEA timestep * Match DT to checkpoint time Co-authored-by: dzalkind * Increment version number * Bladed docs (#116) * Added image of Bladed control screen setup * Delete Bladed control screen.png * Adding image of Bladed control screen * Add files via upload * Minor edit 1 * Minor change 2 * Minor change 3 * Minor change 4 * Change 6 * Change 7 * Change 8 * Minor change 9 Co-authored-by: nikhar-abbas <40865984+nikhar-abbas@users.noreply.github.com> Co-authored-by: WillC-DNV <100850534+WillC-DNV@users.noreply.github.com> * Update version in API change docs * Bladed readthedocs (#117) * Added image of Bladed control screen setup * Delete Bladed control screen.png * Adding image of Bladed control screen * Add files via upload * Minor edit 1 * Minor change 2 * Minor change 3 * Minor change 4 * Change 6 * Change 7 * Change 8 * Minor change 9 * Tinker with characters in bladed instructions * Add bladed instructions to index * Change bladed toctree label * Do underline stuff * Make toctree label same as file * Remove colons from headers Co-authored-by: nikhar-abbas <40865984+nikhar-abbas@users.noreply.github.com> Co-authored-by: WillC-DNV <100850534+WillC-DNV@users.noreply.github.com> * Update docs to reflect CI process Co-authored-by: Nikhar Abbas Co-authored-by: Xianping Du <38188001+Seager1989@users.noreply.github.com> Co-authored-by: nikhar-abbas <40865984+nikhar-abbas@users.noreply.github.com> Co-authored-by: WillC-DNV <100850534+WillC-DNV@users.noreply.github.com> * Fixed wrong formatting of list items (#122) extra newline required between list elements * Flip Ct and Cq table allocation (#129) * Clean up merge and regen discons Co-authored-by: nikhar-abbas <40865984+nikhar-abbas@users.noreply.github.com> Co-authored-by: Nikhar Abbas Co-authored-by: Xianping Du <38188001+Seager1989@users.noreply.github.com> Co-authored-by: WillC-DNV <100850534+WillC-DNV@users.noreply.github.com> Co-authored-by: Gustavo Hylander <74593034+ghylander@users.noreply.github.com> * Clean up merge and regen discons * adding a pitch actuator error * code clean up and added params to writer * renaming as 'pitch fault' and using arrays for offsets * Re-run registry, update modes in controller.py, re-gen inputs * Fix file writing: space after PF section * Add offset test in run_FAST * Enable PF_Mode in test * Regen discons after adding newline * typo * increased significant figures for pitch fault offset * Update docs, input file writing with minor edits before 2.6.0 * Making ROSCO 'blind' to the pitch fault * Update example 05 units * Add generator efficiency to power output of simple simulation * Update Windows install instructions * Standardize avrSWAP to ReKi type * Fix StC input writer * PitCom changed to PitComAct * Regenerate inputs, types, docs with new API * Error -> Faults * Add pitch offset example, test * Throw error if PF_Mode = 1 and IPC not enabled in ServoDyn * Tidy example 18 * Regen discons * Document API change * Load only needed OpenFAST inputs in turbine.py * Set last blade pitch to PitCom, not PitComAct * Give ratelimit it's own memory of last signal * Make current pitch angle PitComAct again * Get rid of PitComAct_Last * Fix typo in ZMQ_Mode description * Revert Matlab changes to develop Co-authored-by: Nikhar Abbas Co-authored-by: Xianping Du <38188001+Seager1989@users.noreply.github.com> Co-authored-by: nikhar-abbas <40865984+nikhar-abbas@users.noreply.github.com> Co-authored-by: WillC-DNV <100850534+WillC-DNV@users.noreply.github.com> Co-authored-by: Gustavo Hylander <74593034+ghylander@users.noreply.github.com> Co-authored-by: Mayank Chetan Co-authored-by: Mayank Chetan <4620557+mayankchetan@users.noreply.github.com> --- ROSCO/rosco_registry/rosco_types.yaml | 9 ++++++++- ROSCO/rosco_registry/write_registry.py | 11 ++++++++++- ROSCO/src/Controllers.f90 | 2 +- ROSCO/src/DISCON.F90 | 2 +- ROSCO/src/ExtControl.f90 | 7 +++++-- ROSCO/src/ROSCO_IO.f90 | 2 +- ROSCO/src/ROSCO_Types.f90 | 2 +- ROSCO_toolbox/ofTools/fast_io/FAST_writer.py | 8 ++++---- ROSCO_toolbox/sim.py | 4 ++-- ROSCO_toolbox/turbine.py | 17 ++++++++++++++++- docs/source/install.rst | 4 +++- 11 files changed, 52 insertions(+), 16 deletions(-) diff --git a/ROSCO/rosco_registry/rosco_types.yaml b/ROSCO/rosco_registry/rosco_types.yaml index f3ac8ddd..577008f3 100644 --- a/ROSCO/rosco_registry/rosco_types.yaml +++ b/ROSCO/rosco_registry/rosco_types.yaml @@ -12,6 +12,13 @@ default_types: size: 0 # Use this if the type IS an array (size:3 --> REAL(8), BldPitch(3)) allocatable: False equals: + float: &float + type: float + description: + dimension: # Use this if a higher-dimensional allocatable array (dimension:(:,:) --> REAL(8), DIMESION(:,:), ALLOCATABLE) + size: 0 # Use this if the type IS an array (size:3 --> REAL(8), BldPitch(3)) + allocatable: False + equals: character: &character type: character description: @@ -1093,7 +1100,7 @@ ZMQ_Variables: ExtControlType: avrSWAP: - <<: *c_float + <<: *float description: The swap array- used to pass data to and from the DLL controller [see Bladed DLL documentation] allocatable: True dimension: (:) diff --git a/ROSCO/rosco_registry/write_registry.py b/ROSCO/rosco_registry/write_registry.py index 05baaa8d..22ae079f 100644 --- a/ROSCO/rosco_registry/write_registry.py +++ b/ROSCO/rosco_registry/write_registry.py @@ -125,7 +125,7 @@ def write_roscoio(yfile): file.write(" TYPE(PerformanceData), INTENT(INOUT) :: PerfData\n") file.write(" TYPE(ErrorVariables), INTENT(INOUT) :: ErrVar\n") file.write(" TYPE(ZMQ_Variables), INTENT(INOUT) :: zmqVar\n") - file.write(" REAL(C_FLOAT), INTENT(IN) :: avrSWAP(*)\n") + file.write(" REAL(ReKi), INTENT(IN) :: avrSWAP(*)\n") file.write(" INTEGER(IntKi), INTENT(IN) :: size_avcOUTNAME\n") file.write(" CHARACTER(size_avcOUTNAME-1), INTENT(IN) :: RootName \n") file.write(" \n") @@ -336,6 +336,15 @@ def read_type(param): f90type += ', DIMENSION(:), ALLOCATABLE' elif param['dimension']: f90type += ', DIMENSION{}'.format(param['dimension']) + elif param['type'] == 'float': + f90type = 'REAL(ReKi)' + if param['allocatable']: + if param['dimension']: + f90type += ', DIMENSION{}, ALLOCATABLE'.format(param['dimension']) + else: + f90type += ', DIMENSION(:), ALLOCATABLE' + elif param['dimension']: + f90type += ', DIMENSION{}'.format(param['dimension']) elif param['type'] == 'character': f90type = 'CHARACTER' if param['length']: diff --git a/ROSCO/src/Controllers.f90 b/ROSCO/src/Controllers.f90 index 8e54b586..121d188a 100644 --- a/ROSCO/src/Controllers.f90 +++ b/ROSCO/src/Controllers.f90 @@ -262,7 +262,7 @@ SUBROUTINE YawRateControl(avrSWAP, CntrPar, LocalVar, objInst, zmqVar, DebugVar, ! TODO: The constant offset implementation is sort of circular here as a setpoint is already being defined in SetVariablesSetpoints. This could also use cleanup USE ROSCO_Types, ONLY : ControlParameters, LocalVariables, ObjectInstances, DebugVariables, ErrorVariables, ZMQ_Variables - REAL(C_FLOAT), INTENT(INOUT) :: avrSWAP(*) ! The swap array, used to pass data to, and receive data from, the DLL controller. + REAL(ReKi), INTENT(INOUT) :: avrSWAP(*) ! The swap array, used to pass data to, and receive data from, the DLL controller. TYPE(ControlParameters), INTENT(INOUT) :: CntrPar TYPE(LocalVariables), INTENT(INOUT) :: LocalVar diff --git a/ROSCO/src/DISCON.F90 b/ROSCO/src/DISCON.F90 index 1e5e5421..e27b06b8 100644 --- a/ROSCO/src/DISCON.F90 +++ b/ROSCO/src/DISCON.F90 @@ -44,7 +44,7 @@ SUBROUTINE DISCON(avrSWAP, aviFAIL, accINFILE, avcOUTNAME, avcMSG) BIND (C, NAME !REAL(ReKi), INTENT(IN) :: from_SC(*) ! DATA from the super controller !REAL(ReKi), INTENT(INOUT) :: to_SC(*) ! DATA to the super controller -REAL(C_FLOAT), INTENT(INOUT) :: avrSWAP(*) ! The swap array, used to pass data to, and receive data from, the DLL controller. +REAL(ReKi), INTENT(INOUT) :: avrSWAP(*) ! The swap array, used to pass data to, and receive data from, the DLL controller. INTEGER(C_INT), INTENT(INOUT) :: aviFAIL ! A flag used to indicate the success of this DLL call set as follows: 0 if the DLL call was successful, >0 if the DLL call was successful but cMessage should be issued as a warning messsage, <0 if the DLL call was unsuccessful or for any other reason the simulation is to be stopped at this point with cMessage as the error message. CHARACTER(KIND=C_CHAR), INTENT(IN ) :: accINFILE(NINT(avrSWAP(50))) ! The name of the parameter input file CHARACTER(KIND=C_CHAR), INTENT(IN ) :: avcOUTNAME(NINT(avrSWAP(51))) ! OUTNAME (Simulation RootName) diff --git a/ROSCO/src/ExtControl.f90 b/ROSCO/src/ExtControl.f90 index 2a398cda..17d821e4 100644 --- a/ROSCO/src/ExtControl.f90 +++ b/ROSCO/src/ExtControl.f90 @@ -26,6 +26,7 @@ MODULE ExtControl USE Functions USE ROSCO_Types USE SysSubs + USE Constants IMPLICIT NONE @@ -35,7 +36,9 @@ MODULE ExtControl SUBROUTINE BladedDLL_Legacy_Procedure ( avrSWAP, aviFAIL, accINFILE, avcOUTNAME, avcMSG ) BIND(C) USE, INTRINSIC :: ISO_C_Binding - REAL(C_FLOAT), INTENT(INOUT) :: avrSWAP (*) !< DATA + USE Constants + + REAL(ReKi), INTENT(INOUT) :: avrSWAP (*) !< DATA INTEGER(C_INT), INTENT(INOUT) :: aviFAIL !< FLAG (Status set in DLL and returned to simulation code) CHARACTER(KIND=C_CHAR), INTENT(IN) :: accINFILE (*) !< INFILE CHARACTER(KIND=C_CHAR), INTENT(INOUT) :: avcOUTNAME(*) !< OUTNAME (in:Simulation RootName; out:Name:Units; of logging channels) @@ -54,7 +57,7 @@ SUBROUTINE ExtController(avrSWAP, CntrPar, LocalVar, ExtDLL, ErrVar) TYPE(ExtControlType), INTENT(INOUT) :: ExtDLL - REAL(C_FLOAT), INTENT(INOUT) :: avrSWAP(*) ! The swap array, used to pass data to, and receive data from the DLL controller. + REAL(ReKi), INTENT(INOUT) :: avrSWAP(*) ! The swap array, used to pass data to, and receive data from the DLL controller. ! Temporary variables ! CHARACTER(1024), PARAMETER :: ExtDLL_InFile = '/Users/dzalkind/Tools/ROSCO/Test_Cases/IEA-15-240-RWT-UMaineSemi/ServoData/DISCON-UMaineSemi.IN' diff --git a/ROSCO/src/ROSCO_IO.f90 b/ROSCO/src/ROSCO_IO.f90 index 8ad72098..a46db3fd 100644 --- a/ROSCO/src/ROSCO_IO.f90 +++ b/ROSCO/src/ROSCO_IO.f90 @@ -196,7 +196,7 @@ SUBROUTINE ReadRestartFile(avrSWAP, LocalVar, CntrPar, objInst, PerfData, RootNa TYPE(PerformanceData), INTENT(INOUT) :: PerfData TYPE(ErrorVariables), INTENT(INOUT) :: ErrVar TYPE(ZMQ_Variables), INTENT(INOUT) :: zmqVar - REAL(C_FLOAT), INTENT(IN) :: avrSWAP(*) + REAL(ReKi), INTENT(IN) :: avrSWAP(*) INTEGER(IntKi), INTENT(IN) :: size_avcOUTNAME CHARACTER(size_avcOUTNAME-1), INTENT(IN) :: RootName diff --git a/ROSCO/src/ROSCO_Types.f90 b/ROSCO/src/ROSCO_Types.f90 index 115458ec..96067b6c 100644 --- a/ROSCO/src/ROSCO_Types.f90 +++ b/ROSCO/src/ROSCO_Types.f90 @@ -332,7 +332,7 @@ MODULE ROSCO_Types END TYPE ZMQ_Variables TYPE, PUBLIC :: ExtControlType - REAL(C_FLOAT), DIMENSION(:), ALLOCATABLE :: avrSWAP ! The swap array- used to pass data to and from the DLL controller [see Bladed DLL documentation] + REAL(ReKi), DIMENSION(:), ALLOCATABLE :: avrSWAP ! The swap array- used to pass data to and from the DLL controller [see Bladed DLL documentation] END TYPE ExtControlType END MODULE ROSCO_Types \ No newline at end of file diff --git a/ROSCO_toolbox/ofTools/fast_io/FAST_writer.py b/ROSCO_toolbox/ofTools/fast_io/FAST_writer.py index c3f45edf..6df98654 100644 --- a/ROSCO_toolbox/ofTools/fast_io/FAST_writer.py +++ b/ROSCO_toolbox/ofTools/fast_io/FAST_writer.py @@ -1293,13 +1293,13 @@ def write_ServoDyn(self): f.write('{:<22} {:<11} {:}'.format(self.fst_vt['ServoDyn']['AfC_Phase'], 'AfC_phase', '- Phase relative to the blade azimuth (0 is vertical) for for cosine cycling of flap signal (deg) [used only with AfCmode==1]\n')) f.write('---------------------- STRUCTURAL CONTROL ---------------------------------------\n') f.write('{:<22} {:<11} {:}'.format(self.fst_vt['ServoDyn']['NumBStC'], 'NumBStC', '- Number of blade structural controllers (integer)\n')) - f.write('{!s:<22} {:<11} {:}'.format('"' + '" "'.join(self.fst_vt['ServoDyn']['BStCfiles']) + '"', 'BStCfiles', '- Name of the file for blade tuned mass damper (quoted string) [unused when CompNTMD is false]\n')) + f.write('{!s:<22} {:<11} {:}'.format('"' + ''.join(self.fst_vt['ServoDyn']['BStCfiles']) + '"', 'BStCfiles', '- Name of the file for blade tuned mass damper (quoted string) [unused when CompNTMD is false]\n')) f.write('{:<22} {:<11} {:}'.format(self.fst_vt['ServoDyn']['NumNStC'], 'NumNStC', '- Number of nacelle structural controllers (integer)\n')) - f.write('{!s:<22} {:<11} {:}'.format('"' + '" "'.join(self.fst_vt['ServoDyn']['NStCfiles']) + '"', 'NStCfiles', '- Name of the file for nacelle tuned mass damper (quoted string) [unused when CompNTMD is false]\n')) + f.write('{!s:<22} {:<11} {:}'.format('"' + ''.join(self.fst_vt['ServoDyn']['NStCfiles']) + '"', 'NStCfiles', '- Name of the file for nacelle tuned mass damper (quoted string) [unused when CompNTMD is false]\n')) f.write('{:<22} {:<11} {:}'.format(self.fst_vt['ServoDyn']['NumTStC'], 'NumTStC', '- Number of tower structural controllers (integer)\n')) - f.write('{!s:<22} {:<11} {:}'.format('"' + '" "'.join(self.fst_vt['ServoDyn']['TStCfiles']) + '"', 'TStCfiles', '- Name of the file for tower tuned mass damper (quoted string) [unused when CompNTMD is false]\n')) + f.write('{!s:<22} {:<11} {:}'.format('"' + ''.join(self.fst_vt['ServoDyn']['TStCfiles']) + '"', 'TStCfiles', '- Name of the file for tower tuned mass damper (quoted string) [unused when CompNTMD is false]\n')) f.write('{:<22} {:<11} {:}'.format(self.fst_vt['ServoDyn']['NumSStC'], 'NumSStC', '- Number of sbustructure structural controllers (integer)\n')) - f.write('{!s:<22} {:<11} {:}'.format('"' + '" "'.join(self.fst_vt['ServoDyn']['SStCfiles']) + '"', 'SStCfiles', '- Name of the file for sbustructure tuned mass damper (quoted string) [unused when CompNTMD is false]\n')) + f.write('{!s:<22} {:<11} {:}'.format('"' + ''.join(self.fst_vt['ServoDyn']['SStCfiles']) + '"', 'SStCfiles', '- Name of the file for sbustructure tuned mass damper (quoted string) [unused when CompNTMD is false]\n')) f.write('---------------------- CABLE CONTROL ---------------------------------------- \n') f.write('{:<22} {:<11} {:}'.format(self.fst_vt['ServoDyn']['CCmode'], 'CCmode', '- Cable control mode {0- none, 4- user-defined from Simulink/Labview, 5- user-defineAfC_phased from Bladed-style DLL}\n')) f.write('---------------------- BLADED INTERFACE ---------------------------------------- [used only with Bladed Interface]\n') diff --git a/ROSCO_toolbox/sim.py b/ROSCO_toolbox/sim.py index 54e3df62..7ea930cd 100644 --- a/ROSCO_toolbox/sim.py +++ b/ROSCO_toolbox/sim.py @@ -140,7 +140,7 @@ def sim_ws_series(self, t_array, ws_array, rotor_rpm_init=10, init_pitch=0.0, gen_torque[i], bld_pitch[i], nac_yawrate[i] = self.controller_int.call_controller(turbine_state) # Calculate the power - gen_power[i] = gen_speed[i] * gen_torque[i] + gen_power[i] = gen_speed[i] * gen_torque[i] * self.turbine.GenEff / 100 # Calculate the nacelle position nac_yaw[i] = nac_yaw[i-1] + nac_yawrate[i] * dt @@ -181,7 +181,7 @@ def sim_ws_series(self, t_array, ws_array, rotor_rpm_init=10, init_pitch=0.0, ax.grid() ax = axarr[3] ax.plot(self.t_array, self.gen_power/1000) - ax.set_ylabel('Gen Power (W)') + ax.set_ylabel('Gen Power (kW)') ax.grid() ax = axarr[4] ax.plot(self.t_array, self.bld_pitch*rad2deg) diff --git a/ROSCO_toolbox/turbine.py b/ROSCO_toolbox/turbine.py index e97d7203..0d965abc 100644 --- a/ROSCO_toolbox/turbine.py +++ b/ROSCO_toolbox/turbine.py @@ -163,7 +163,22 @@ def load_from_fast(self, FAST_InputFile,FAST_directory, FAST_ver='OpenFAST',dev_ fast = self.fast = InputReader_OpenFAST() fast.FAST_InputFile = FAST_InputFile fast.FAST_directory = FAST_directory - fast.execute() + + fast.read_MainInput() + fast.read_ElastoDyn() + + + fast.read_AeroDyn15() + + fast.read_ServoDyn() + fast.read_DISCON_in() + + + if fast.fst_vt['Fst']['CompHydro'] == 1: # SubDyn not yet implimented + fast.read_HydroDyn() + + # fast.read_AeroDyn15() + # fast.execute() # Use Performance tables if defined, otherwise use defaults if txt_filename: diff --git a/docs/source/install.rst b/docs/source/install.rst index 29a71620..12029399 100644 --- a/docs/source/install.rst +++ b/docs/source/install.rst @@ -104,6 +104,7 @@ On Mac/Linux, standard compilers are generally available without any additional .. code-block:: bash conda install m2w64-toolchain libpython + conda install cmake make # if Windows users would like to install these in anaconda environment Once the CMake and the required compilers are downloaded, the following code can be used to compile ROSCO. @@ -199,7 +200,8 @@ Please follow the following steps to install the ROSCO tool-chain. You should do cd ROSCO conda install compilers # (Mac/Linux only) conda install m2w64-toolchain libpython # (Windows only) - conda install -y wisdem + conda env config vars set FC=gfortran # Sometimes needed for Windows + conda install -y wisdem=3.5.0 python setup.py install --compile-rosco 3. Clone and Install the ROSCO toolbox without ROSCO From 9384f0307b40306025497d8ffca0cadf0e09194c Mon Sep 17 00:00:00 2001 From: verlivkra <92805931+verlivkra@users.noreply.github.com> Date: Fri, 14 Oct 2022 14:21:10 -0600 Subject: [PATCH 008/224] Added feature to read AeroDyn 14 files also for the case without tower influence. (#177) closes #176 --- ROSCO_toolbox/ofTools/fast_io/FAST_reader.py | 21 +++++++++++++------- 1 file changed, 14 insertions(+), 7 deletions(-) diff --git a/ROSCO_toolbox/ofTools/fast_io/FAST_reader.py b/ROSCO_toolbox/ofTools/fast_io/FAST_reader.py index f4fb2f59..94d12ede 100644 --- a/ROSCO_toolbox/ofTools/fast_io/FAST_reader.py +++ b/ROSCO_toolbox/ofTools/fast_io/FAST_reader.py @@ -936,10 +936,16 @@ def read_AeroDyn14(self): self.fst_vt['AeroDyn14']['TLModel'] = f.readline().split()[0] self.fst_vt['AeroDyn14']['HLModel'] = f.readline().split()[0] self.fst_vt['AeroDyn14']['TwrShad'] = f.readline().split()[0] - self.fst_vt['AeroDyn14']['TwrPotent'] = bool_read(f.readline().split()[0]) - self.fst_vt['AeroDyn14']['TwrShadow'] = bool_read(f.readline().split()[0]) - self.fst_vt['AeroDyn14']['TwrFile'] = f.readline().split()[0].replace('"','').replace("'",'') - self.fst_vt['AeroDyn14']['CalcTwrAero'] = bool_read(f.readline().split()[0]) + + if self.fst_vt['AeroDyn14']['TwrShad'] == "NEWTOWER": #w tower influence + self.fst_vt['AeroDyn14']['TwrPotent'] = bool_read(f.readline().split()[0]) + self.fst_vt['AeroDyn14']['TwrShadow'] = bool_read(f.readline().split()[0]) + self.fst_vt['AeroDyn14']['TwrFile'] = f.readline().split()[0].replace('"','').replace("'",'') + self.fst_vt['AeroDyn14']['CalcTwrAero'] = bool_read(f.readline().split()[0]) + else: #w/o tower influence + self.fst_vt['AeroDyn14']['ShadHWid'] = float_read(f.readline().split()[0]) + self.fst_vt['AeroDyn14']['T_Shad_Refpt'] = float_read(f.readline().split()[0]) + self.fst_vt['AeroDyn14']['AirDens'] = float_read(f.readline().split()[0]) self.fst_vt['AeroDyn14']['KinVisc'] = float_read(f.readline().split()[0]) self.fst_vt['AeroDyn14']['DTAero'] = float_read(f.readline().split()[0]) @@ -973,11 +979,12 @@ def read_AeroDyn14(self): # create airfoil objects self.fst_vt['AeroDynBlade']['af_data'] = [] - for i in range(self.fst_vt['AeroDynBlade']['NumFoil']): - self.fst_vt['AeroDynBlade']['af_data'].append(self.read_AeroDyn14Polar(os.path.join(self.FAST_directory,self.fst_vt['AeroDyn14']['FoilNm'][i]))) + for i in range(self.fst_vt['AeroDyn14']['NumFoil']): + self.fst_vt['AeroDynBlade']['af_data'].append(self.read_AeroDyn14Polar(os.path.join(self.FAST_directory,self.fst_vt['Fst']['AeroFile_path'],self.fst_vt['AeroDyn14']['FoilNm'][i]))) # tower - self.read_AeroDyn14Tower() + if self.fst_vt['AeroDyn14']['TwrShad'] == "NEWTOWER": + self.read_AeroDyn14Tower() def read_AeroDyn14Tower(self): # AeroDyn v14.04 Tower From 602332eac9a9d67c8577e2956c85fb17aa7093f9 Mon Sep 17 00:00:00 2001 From: dzalkind <65573423+dzalkind@users.noreply.github.com> Date: Mon, 12 Dec 2022 12:00:14 -0700 Subject: [PATCH 009/224] Various Bug Fixes (#188) * Fix yaw threshold documentation in DISCON * Fix debug unit labels * Add nacelle heading error to DebugVar * Update ROSCO_IO and Types * Read NacHeading from OpenFAST * Update DISCONs * Fix ******s in dbg files * Allow single U in power_curve * Initialize floating feedback filters at 0, make optional input for filts * give dummy units if dbg units missing * Update FAST_wrapper.py Fix UnboundLocalError: local variable 'e' referenced before assignment * Update example_08.py Remove tmin so that entire simulation is plotted. Removing tmin=10 because with that setting only the final timestep of the simulation is loaded * Update linear_model handling for new pyFAST, will break with weis import * Try with conda installed compiler * Re-do filter initialization, reset value unused for now * Regen registry and discons * Enable run_FAST in setup install * Set default wind_dir in simp_step case * Add dll shutdown method to control_interface Co-authored-by: Alex Clerc --- .github/workflows/CI_rosco-pytools.yml | 8 +- Examples/example_08.py | 2 +- Examples/example_15.py | 1 + Examples/example_16.py | 1 + Examples/example_18.py | 1 + ROSCO/rosco_registry/rosco_types.yaml | 8 +- ROSCO/rosco_registry/write_registry.py | 21 ++++- ROSCO/src/Controllers.f90 | 1 + ROSCO/src/Filters.f90 | 83 ++++++++++++++----- ROSCO/src/ROSCO_IO.f90 | 22 ++++- ROSCO/src/ROSCO_Types.f90 | 6 +- ROSCO/src/ReadSetParameters.f90 | 3 +- ROSCO_testing/test_checkpoint.py | 3 +- ROSCO_toolbox/control_interface.py | 9 +- ROSCO_toolbox/linear/linear_models.py | 13 ++- ROSCO_toolbox/ofTools/case_gen/CaseLibrary.py | 11 ++- ROSCO_toolbox/ofTools/case_gen/run_FAST.py | 49 +++++++---- ROSCO_toolbox/ofTools/fast_io/FAST_wrapper.py | 2 +- ROSCO_toolbox/utilities.py | 4 +- Test_Cases/BAR_10/BAR_10_DISCON.IN | 2 +- .../DISCON-UMaineSemi.IN | 2 +- Test_Cases/NREL-5MW/DISCON.IN | 2 +- 22 files changed, 176 insertions(+), 78 deletions(-) diff --git a/.github/workflows/CI_rosco-pytools.yml b/.github/workflows/CI_rosco-pytools.yml index 141c16ee..143fc286 100644 --- a/.github/workflows/CI_rosco-pytools.yml +++ b/.github/workflows/CI_rosco-pytools.yml @@ -46,10 +46,10 @@ jobs: FC: gfortran - # - name: Add dependencies macOS specific - # if: true == contains( matrix.os, 'macOS') - # run: | - # conda install compilers + - name: Add dependencies macOS specific + if: true == contains( matrix.os, 'macOS') + run: | + conda install compilers # Install ROSCO toolbox - name: Install ROSCO toolbox on Windows diff --git a/Examples/example_08.py b/Examples/example_08.py index f4732a27..0307f738 100644 --- a/Examples/example_08.py +++ b/Examples/example_08.py @@ -46,7 +46,7 @@ # fast_out.plot_fast_out() # Load and plot -fastout = fast_out.load_fast_out(filenames, tmin=10) +fastout = fast_out.load_fast_out(filenames) fast_out.plot_fast_out(cases=cases,showplot=False) plt.savefig(os.path.join(example_out_dir,'08_IEA-15MW_Semi_Out.png')) diff --git a/Examples/example_15.py b/Examples/example_15.py index baa29c8a..2b4716e9 100644 --- a/Examples/example_15.py +++ b/Examples/example_15.py @@ -37,6 +37,7 @@ def main(): 'wind_dir': run_dir } r.save_dir = run_dir + r.rosco_dir = rosco_dir r.run_FAST() diff --git a/Examples/example_16.py b/Examples/example_16.py index fbd45d82..b040c2af 100644 --- a/Examples/example_16.py +++ b/Examples/example_16.py @@ -58,6 +58,7 @@ def main(): 'wind_dir': run_dir } r.controller_params = controller_params + r.rosco_dir = rosco_dir r.save_dir = run_dir r.run_FAST() diff --git a/Examples/example_18.py b/Examples/example_18.py index 89c6ca54..00a4d4d4 100644 --- a/Examples/example_18.py +++ b/Examples/example_18.py @@ -59,6 +59,7 @@ def main(): r.case_inputs[("ServoDyn","Ptch_Cntrl")] = {'vals':[1], 'group':0} # Individual pitch control must be enabled in ServoDyn r.controller_params = controller_params r.save_dir = run_dir + r.rosco_dir = rosco_dir r.run_FAST() diff --git a/ROSCO/rosco_registry/rosco_types.yaml b/ROSCO/rosco_registry/rosco_types.yaml index 577008f3..ea486fd1 100644 --- a/ROSCO/rosco_registry/rosco_types.yaml +++ b/ROSCO/rosco_registry/rosco_types.yaml @@ -1041,13 +1041,13 @@ DebugVariables: description: Commanded yaw rate [rad/s]. NacHeadingTarget: <<: *real - description: Target nacelle heading [rad]. + description: Target nacelle heading [deg]. NacVaneOffset: <<: *real - description: Nacelle vane angle with offset [rad]. - Yaw_err: + description: Nacelle vane angle with offset [deg]. + Yaw_Err: <<: *real - description: Yaw error [rad]. + description: Yaw error [deg]. YawState: <<: *real description: State of yaw controller diff --git a/ROSCO/rosco_registry/write_registry.py b/ROSCO/rosco_registry/write_registry.py index 22ae079f..09c855b3 100644 --- a/ROSCO/rosco_registry/write_registry.py +++ b/ROSCO/rosco_registry/write_registry.py @@ -221,12 +221,15 @@ def write_roscoio(yfile): file.write(' DebugOutUnits = [CHARACTER(15) :: ') counter = 0 for unit in dbg_units: + # Give dummy unit if not defined + if not unit: + unit = '[N/A]' counter += 1 if counter == len(dbg_units): - file.write(" '{}'".format(unit)) + file.write(" '{}'".format(unit)) # last line else: file.write(" '{}',".format(unit)) - if (counter % 5 == 0): + if (counter % 5 == 0): # group in groups of 5 file.write(' & \n ') file.write(']\n') @@ -293,6 +296,20 @@ def write_roscoio(yfile): file.write(" 100 FORMAT('Generator speed: ', f6.1, ' RPM, Pitch angle: ', f5.1, ' deg, Power: ', f7.1, ' kW, Est. wind Speed: ', f5.1, ' m/s')\n") file.write(" END IF\n") file.write("\n") + file.write(" ! Process DebugOutData, LocalVarOutData\n") + file.write(" ! Remove very small numbers that cause ******** outputs\n") + file.write(" DO I = 1,SIZE(DebugOutData)\n") + file.write(" IF (ABS(DebugOutData(I)) < 1E-10) THEN\n") + file.write(" DebugOutData(I) = 0\n") + file.write(" END IF\n") + file.write(" END DO\n") + file.write(" \n") + file.write(" DO I = 1,SIZE(LocalVarOutData)\n") + file.write(" IF (ABS(LocalVarOutData(I)) < 1E-10) THEN\n") + file.write(" LocalVarOutData(I) = 0\n") + file.write(" END IF\n") + file.write(" END DO\n") + file.write(" \n") file.write(" ! Write debug files\n") file.write(" IF(CntrPar%LoggingLevel > 0) THEN\n") file.write(" WRITE (UnDb, FmtDat) LocalVar%Time, DebugOutData\n") diff --git a/ROSCO/src/Controllers.f90 b/ROSCO/src/Controllers.f90 index 121d188a..29eda914 100644 --- a/ROSCO/src/Controllers.f90 +++ b/ROSCO/src/Controllers.f90 @@ -365,6 +365,7 @@ SUBROUTINE YawRateControl(avrSWAP, CntrPar, LocalVar, objInst, zmqVar, DebugVar, DebugVar%NacHeadingTarget = NacHeadingTarget DebugVar%NacVaneOffset = NacVaneOffset DebugVar%YawState = YawState + DebugVar%Yaw_Err = NacHeadingError END IF END SUBROUTINE YawRateControl !------------------------------------------------------------------------------------------------------------------------------- diff --git a/ROSCO/src/Filters.f90 b/ROSCO/src/Filters.f90 index 5123b74c..a108dfda 100644 --- a/ROSCO/src/Filters.f90 +++ b/ROSCO/src/Filters.f90 @@ -26,7 +26,7 @@ MODULE Filters CONTAINS !------------------------------------------------------------------------------------------------------------------------------- - REAL(DbKi) FUNCTION LPFilter(InputSignal, DT, CornerFreq, FP, iStatus, reset, inst) + REAL(DbKi) FUNCTION LPFilter(InputSignal, DT, CornerFreq, FP, iStatus, reset, inst, InitialValue) ! Discrete time Low-Pass Filter of the form: ! Continuous Time Form: H(s) = CornerFreq/(1 + CornerFreq) ! Discrete Time Form: H(z) = (b1z + b0) / (a1*z + a0) @@ -40,11 +40,18 @@ REAL(DbKi) FUNCTION LPFilter(InputSignal, DT, CornerFreq, FP, iStatus, reset, in INTEGER(IntKi), INTENT(IN) :: iStatus ! A status flag set by the simulation as follows: 0 if this is the first call, 1 for all subsequent time steps, -1 if this is the final call at the end of the simulation. INTEGER(IntKi), INTENT(INOUT) :: inst ! Instance number. Every instance of this function needs to have an unique instance number to ensure instances don't influence each other. LOGICAL(4), INTENT(IN) :: reset ! Reset the filter to the input signal + REAL(DbKi), OPTIONAL, INTENT(IN) :: InitialValue ! Value to set when reset + + REAL(DbKi) :: InitialValue_ ! Value to set when reset + + ! Defaults + InitialValue_ = InputSignal + IF (PRESENT(InitialValue)) InitialValue_ = InitialValue - ! Initialization + ! Initialization IF ((iStatus == 0) .OR. reset) THEN - FP%lpf1_OutputSignalLast(inst) = InputSignal - FP%lpf1_InputSignalLast(inst) = InputSignal + FP%lpf1_OutputSignalLast(inst) = InitialValue_ + FP%lpf1_InputSignalLast(inst) = InitialValue_ FP%lpf1_a1(inst) = 2 + CornerFreq*DT FP%lpf1_a0(inst) = CornerFreq*DT - 2 FP%lpf1_b1(inst) = CornerFreq*DT @@ -63,7 +70,7 @@ REAL(DbKi) FUNCTION LPFilter(InputSignal, DT, CornerFreq, FP, iStatus, reset, in END FUNCTION LPFilter !------------------------------------------------------------------------------------------------------------------------------- - REAL(DbKi) FUNCTION SecLPFilter(InputSignal, DT, CornerFreq, Damp, FP, iStatus, reset, inst) + REAL(DbKi) FUNCTION SecLPFilter(InputSignal, DT, CornerFreq, Damp, FP, iStatus, reset, inst, InitialValue) ! Discrete time Low-Pass Filter of the form: ! Continuous Time Form: H(s) = CornerFreq^2/(s^2 + 2*CornerFreq*Damp*s + CornerFreq^2) ! Discrete Time From: H(z) = (b2*z^2 + b1*z + b0) / (a2*z^2 + a1*z + a0) @@ -75,14 +82,21 @@ REAL(DbKi) FUNCTION SecLPFilter(InputSignal, DT, CornerFreq, Damp, FP, iStatus, REAL(DbKi), INTENT(IN) :: Damp ! Dampening constant INTEGER(IntKi), INTENT(IN) :: iStatus ! A status flag set by the simulation as follows: 0 if this is the first call, 1 for all subsequent time steps, -1 if this is the final call at the end of the simulation. INTEGER(IntKi), INTENT(INOUT) :: inst ! Instance number. Every instance of this function needs to have an unique instance number to ensure instances don't influence each other. - LOGICAL(4), INTENT(IN) :: reset ! Reset the filter to the input signal + LOGICAL(4), INTENT(IN) :: reset ! Reset the filter to the input signal + REAL(DbKi), OPTIONAL, INTENT(IN) :: InitialValue ! Value to set when reset + + REAL(DbKi) :: InitialValue_ ! Value to set when reset + + ! Defaults + InitialValue_ = InputSignal + IF (PRESENT(InitialValue)) InitialValue_ = InitialValue ! Initialization IF ((iStatus == 0) .OR. reset ) THEN - FP%lpf2_OutputSignalLast1(inst) = InputSignal - FP%lpf2_OutputSignalLast2(inst) = InputSignal - FP%lpf2_InputSignalLast1(inst) = InputSignal - FP%lpf2_InputSignalLast2(inst) = InputSignal + FP%lpf2_OutputSignalLast1(inst) = InitialValue_ + FP%lpf2_OutputSignalLast2(inst) = InitialValue_ + FP%lpf2_InputSignalLast1(inst) = InitialValue_ + FP%lpf2_InputSignalLast2(inst) = InitialValue_ ! Coefficients FP%lpf2_a2(inst) = DT**2.0*CornerFreq**2.0 + 4.0 + 4.0*Damp*CornerFreq*DT @@ -106,7 +120,7 @@ REAL(DbKi) FUNCTION SecLPFilter(InputSignal, DT, CornerFreq, Damp, FP, iStatus, END FUNCTION SecLPFilter !------------------------------------------------------------------------------------------------------------------------------- - REAL(DbKi) FUNCTION HPFilter( InputSignal, DT, CornerFreq, FP, iStatus, reset, inst) + REAL(DbKi) FUNCTION HPFilter( InputSignal, DT, CornerFreq, FP, iStatus, reset, inst, InitialValue) ! Discrete time High-Pass Filter USE ROSCO_Types, ONLY : FilterParameters TYPE(FilterParameters), INTENT(INOUT) :: FP @@ -119,11 +133,18 @@ REAL(DbKi) FUNCTION HPFilter( InputSignal, DT, CornerFreq, FP, iStatus, reset, i LOGICAL(4), INTENT(IN) :: reset ! Reset the filter to the input signal ! Local REAL(DbKi) :: K ! Constant gain + REAL(DbKi), OPTIONAL, INTENT(IN) :: InitialValue ! Value to set when reset + + REAL(DbKi) :: InitialValue_ ! Value to set when reset + + ! Defaults + InitialValue_ = InputSignal + IF (PRESENT(InitialValue)) InitialValue_ = InitialValue ! Initialization IF ((iStatus == 0) .OR. reset) THEN - FP%hpf_OutputSignalLast(inst) = InputSignal - FP%hpf_InputSignalLast(inst) = InputSignal + FP%hpf_OutputSignalLast(inst) = InitialValue_ + FP%hpf_InputSignalLast(inst) = InitialValue_ ENDIF K = 2.0 / DT @@ -137,7 +158,7 @@ REAL(DbKi) FUNCTION HPFilter( InputSignal, DT, CornerFreq, FP, iStatus, reset, i END FUNCTION HPFilter !------------------------------------------------------------------------------------------------------------------------------- - REAL(DbKi) FUNCTION NotchFilterSlopes(InputSignal, DT, CornerFreq, Damp, FP, iStatus, reset, inst, Moving) + REAL(DbKi) FUNCTION NotchFilterSlopes(InputSignal, DT, CornerFreq, Damp, FP, iStatus, reset, inst, Moving, InitialValue) ! Discrete time inverted Notch Filter with descending slopes, G = CornerFreq*s/(Damp*s^2+CornerFreq*s+Damp*CornerFreq^2) USE ROSCO_Types, ONLY : FilterParameters TYPE(FilterParameters), INTENT(INOUT) :: FP @@ -150,9 +171,15 @@ REAL(DbKi) FUNCTION NotchFilterSlopes(InputSignal, DT, CornerFreq, Damp, FP, iSt INTEGER(IntKi), INTENT(INOUT) :: inst ! Instance number. Every instance of this function needs to have an unique instance number to ensure instances don't influence each other. LOGICAL(4), INTENT(IN) :: reset ! Reset the filter to the input signal LOGICAL, OPTIONAL, INTENT(IN) :: Moving ! Moving CornerFreq flag + REAL(DbKi), OPTIONAL, INTENT(IN) :: InitialValue ! Value to set when reset LOGICAL :: Moving_ ! Local version REAL(DbKi) :: CornerFreq_ ! Local version + REAL(DbKi) :: InitialValue_ ! Value to set when reset + + ! Defaults + InitialValue_ = InputSignal + IF (PRESENT(InitialValue)) InitialValue_ = InitialValue Moving_ = .FALSE. IF (PRESENT(Moving)) Moving_ = Moving @@ -166,10 +193,10 @@ REAL(DbKi) FUNCTION NotchFilterSlopes(InputSignal, DT, CornerFreq, Damp, FP, iSt ! Initialization IF ((iStatus == 0) .OR. reset) THEN - FP%nfs_OutputSignalLast1(inst) = InputSignal - FP%nfs_OutputSignalLast2(inst) = InputSignal - FP%nfs_InputSignalLast1(inst) = InputSignal - FP%nfs_InputSignalLast2(inst) = InputSignal + FP%nfs_OutputSignalLast1(inst) = InitialValue_ + FP%nfs_OutputSignalLast2(inst) = InitialValue_ + FP%nfs_InputSignalLast1(inst) = InitialValue_ + FP%nfs_InputSignalLast2(inst) = InitialValue_ ENDIF IF ((iStatus == 0) .OR. reset .OR. Moving_) THEN @@ -192,7 +219,7 @@ REAL(DbKi) FUNCTION NotchFilterSlopes(InputSignal, DT, CornerFreq, Damp, FP, iSt END FUNCTION NotchFilterSlopes !------------------------------------------------------------------------------------------------------------------------------- - REAL(DbKi) FUNCTION NotchFilter(InputSignal, DT, omega, betaNum, betaDen, FP, iStatus, reset, inst) + REAL(DbKi) FUNCTION NotchFilter(InputSignal, DT, omega, betaNum, betaDen, FP, iStatus, reset, inst, InitialValue) ! Discrete time Notch Filter ! Continuous Time Form: G(s) = (s^2 + 2*omega*betaNum*s + omega^2)/(s^2 + 2*omega*betaDen*s + omega^2) ! Discrete Time Form: H(z) = (b2*z^2 +b1*z^2 + b0*z)/((z^2 +a1*z^2 + a0*z)) @@ -207,16 +234,22 @@ REAL(DbKi) FUNCTION NotchFilter(InputSignal, DT, omega, betaNum, betaDen, FP, iS INTEGER(IntKi), INTENT(IN) :: iStatus ! A status flag set by the simulation as follows: 0 if this is the first call, 1 for all subsequent time steps, -1 if this is the final call at the end of the simulation. INTEGER(IntKi), INTENT(INOUT) :: inst ! Instance number. Every instance of this function needs to have an unique instance number to ensure instances don't influence each other. LOGICAL(4), INTENT(IN) :: reset ! Reset the filter to the input signal + REAL(DbKi), OPTIONAL, INTENT(IN) :: InitialValue ! Value to set when reset ! Local REAL(DbKi) :: K ! Constant gain + REAL(DbKi) :: InitialValue_ ! Value to set when reset + + ! Defaults + InitialValue_ = InputSignal + IF (PRESENT(InitialValue)) InitialValue_ = InitialValue ! Initialization K = 2.0/DT IF ((iStatus == 0) .OR. reset) THEN - FP%nf_OutputSignalLast1(inst) = InputSignal - FP%nf_OutputSignalLast2(inst) = InputSignal - FP%nf_InputSignalLast1(inst) = InputSignal - FP%nf_InputSignalLast2(inst) = InputSignal + FP%nf_OutputSignalLast1(inst) = InitialValue_ + FP%nf_OutputSignalLast2(inst) = InitialValue_ + FP%nf_InputSignalLast1(inst) = InitialValue_ + FP%nf_InputSignalLast2(inst) = InitialValue_ FP%nf_b2(inst) = (K**2.0 + 2.0*omega*BetaNum*K + omega**2.0)/(K**2.0 + 2.0*omega*BetaDen*K + omega**2.0) FP%nf_b1(inst) = (2.0*omega**2.0 - 2.0*K**2.0) / (K**2.0 + 2.0*omega*BetaDen*K + omega**2.0); FP%nf_b0(inst) = (K**2.0 - 2.0*omega*BetaNum*K + omega**2.0) / (K**2.0 + 2.0*omega*BetaDen*K + omega**2.0) @@ -269,6 +302,10 @@ SUBROUTINE PreFilterMeasuredSignals(CntrPar, LocalVar, DebugVar, objInst, ErrVar ! Filtering the tower fore-aft acceleration signal IF (CntrPar%Fl_Mode > 0) THEN ! Force to start at 0 + IF (LocalVar%iStatus == 0 .AND. LocalVar%Time == 0) THEN + LocalVar%NacIMU_FA_Acc = 0 + LocalVar%FA_Acc = 0 + ENDIF LocalVar%NacIMU_FA_AccF = SecLPFilter(LocalVar%NacIMU_FA_Acc, LocalVar%DT, CntrPar%F_FlCornerFreq(1), CntrPar%F_FlCornerFreq(2), LocalVar%FP, LocalVar%iStatus, LocalVar%restart, objInst%instSecLPF) ! Fixed Damping LocalVar%FA_AccF = SecLPFilter(LocalVar%FA_Acc, LocalVar%DT, CntrPar%F_FlCornerFreq(1), CntrPar%F_FlCornerFreq(2), LocalVar%FP, LocalVar%iStatus, LocalVar%restart, objInst%instSecLPF) ! Fixed Damping LocalVar%NacIMU_FA_AccF = HPFilter(LocalVar%NacIMU_FA_AccF, LocalVar%DT, CntrPar%F_FlHighPassFreq, LocalVar%FP, LocalVar%iStatus, LocalVar%restart, objInst%instHPF) diff --git a/ROSCO/src/ROSCO_IO.f90 b/ROSCO/src/ROSCO_IO.f90 index a46db3fd..6e97878d 100644 --- a/ROSCO/src/ROSCO_IO.f90 +++ b/ROSCO/src/ROSCO_IO.f90 @@ -426,18 +426,18 @@ SUBROUTINE Debug(LocalVar, CntrPar, DebugVar, ErrVar, avrSWAP, RootName, size_av DebugOutData(20) = DebugVar%YawRateCom DebugOutData(21) = DebugVar%NacHeadingTarget DebugOutData(22) = DebugVar%NacVaneOffset - DebugOutData(23) = DebugVar%Yaw_err + DebugOutData(23) = DebugVar%Yaw_Err DebugOutData(24) = DebugVar%YawState DebugOutStrings = [CHARACTER(15) :: 'WE_Cp', 'WE_b', 'WE_w', 'WE_t', 'WE_Vm', & 'WE_Vt', 'WE_Vw', 'WE_lambda', 'PC_PICommand', 'GenSpeedF', & 'RotSpeedF', 'NacIMU_FA_AccF', 'FA_AccF', 'Fl_PitCom', 'PC_MinPit', & 'axisTilt_1P', 'axisYaw_1P', 'axisTilt_2P', 'axisYaw_2P', 'YawRateCom', & - 'NacHeadingTarget', 'NacVaneOffset', 'Yaw_err', 'YawState'] + 'NacHeadingTarget', 'NacVaneOffset', 'Yaw_Err', 'YawState'] DebugOutUnits = [CHARACTER(15) :: '[-]', '[-]', '[-]', '[-]', '[m/s]', & '[m/s]', '[m/s]', '[rad]', '[rad]', '[rad/s]', & '[rad/s]', '[rad/s]', '[m/s]', '[rad]', '[rad]', & - '', '', '', '', '[rad/s]', & - '[rad]', '[rad]', '[rad]', ''] + '[N/A]', '[N/A]', '[N/A]', '[N/A]', '[rad/s]', & + '[deg]', '[deg]', '[deg]', '[N/A]'] nLocalVars = 69 Allocate(LocalVarOutData(nLocalVars)) Allocate(LocalVarOutStrings(nLocalVars)) @@ -556,6 +556,20 @@ SUBROUTINE Debug(LocalVar, CntrPar, DebugVar, ErrVar, avrSWAP, RootName, size_av 100 FORMAT('Generator speed: ', f6.1, ' RPM, Pitch angle: ', f5.1, ' deg, Power: ', f7.1, ' kW, Est. wind Speed: ', f5.1, ' m/s') END IF + ! Process DebugOutData, LocalVarOutData + ! Remove very small numbers that cause ******** outputs + DO I = 1,SIZE(DebugOutData) + IF (ABS(DebugOutData(I)) < 1E-10) THEN + DebugOutData(I) = 0 + END IF + END DO + + DO I = 1,SIZE(LocalVarOutData) + IF (ABS(LocalVarOutData(I)) < 1E-10) THEN + LocalVarOutData(I) = 0 + END IF + END DO + ! Write debug files IF(CntrPar%LoggingLevel > 0) THEN WRITE (UnDb, FmtDat) LocalVar%Time, DebugOutData diff --git a/ROSCO/src/ROSCO_Types.f90 b/ROSCO/src/ROSCO_Types.f90 index 96067b6c..3426ae9f 100644 --- a/ROSCO/src/ROSCO_Types.f90 +++ b/ROSCO/src/ROSCO_Types.f90 @@ -305,9 +305,9 @@ MODULE ROSCO_Types REAL(DbKi) :: axisTilt_2P ! Tilt component of coleman transformation, 2P REAL(DbKi) :: axisYaw_2P ! Yaw component of coleman transformation, 2P REAL(DbKi) :: YawRateCom ! Commanded yaw rate [rad/s]. - REAL(DbKi) :: NacHeadingTarget ! Target nacelle heading [rad]. - REAL(DbKi) :: NacVaneOffset ! Nacelle vane angle with offset [rad]. - REAL(DbKi) :: Yaw_err ! Yaw error [rad]. + REAL(DbKi) :: NacHeadingTarget ! Target nacelle heading [deg]. + REAL(DbKi) :: NacVaneOffset ! Nacelle vane angle with offset [deg]. + REAL(DbKi) :: Yaw_Err ! Yaw error [deg]. REAL(DbKi) :: YawState ! State of yaw controller END TYPE DebugVariables diff --git a/ROSCO/src/ReadSetParameters.f90 b/ROSCO/src/ReadSetParameters.f90 index 7da9ebd7..0bfd59d2 100644 --- a/ROSCO/src/ReadSetParameters.f90 +++ b/ROSCO/src/ReadSetParameters.f90 @@ -50,6 +50,7 @@ SUBROUTINE ReadAvrSWAP(avrSWAP, LocalVar, CntrPar) LocalVar%rootMOOP(1) = avrSWAP(30) LocalVar%rootMOOP(2) = avrSWAP(31) LocalVar%rootMOOP(3) = avrSWAP(32) + LocalVar%NacHeading = avrSWAP(37) * R2D LocalVar%FA_Acc = avrSWAP(53) LocalVar%NacIMU_FA_Acc = avrSWAP(83) LocalVar%Azimuth = avrSWAP(60) @@ -76,7 +77,7 @@ SUBROUTINE ReadAvrSWAP(avrSWAP, LocalVar, CntrPar) ENDIF - IF (LocalVar%iStatus == 0) THEN + IF (LocalVar%iStatus == 0) THEN ! TODO: Technically, LocalVar%Time > 0, too, but this restart is in many places as a reset LocalVar%restart = .True. ELSE LocalVar%restart = .False. diff --git a/ROSCO_testing/test_checkpoint.py b/ROSCO_testing/test_checkpoint.py index d42c7e74..e1d15f03 100644 --- a/ROSCO_testing/test_checkpoint.py +++ b/ROSCO_testing/test_checkpoint.py @@ -53,6 +53,7 @@ def test_restart(self): case_inputs[('Fst', 'OutFileFmt')] = {'vals': [2], 'group': 1} case_inputs[('Fst', 'DT')] = {'vals': [0.025], 'group': 0} case_inputs[('DISCON_in', 'LoggingLevel')] = {'vals': [2], 'group': 1} + case_inputs[('ElastoDyn', 'RotSpeed')] = {'vals': [7], 'group': 0} # Generate cases run_dir = os.path.join(test_out_dir, 'restart') @@ -110,7 +111,7 @@ def test_restart(self): if False: # Plotting for debug import matplotlib.pyplot as plt cases = {} - cases['Baseline'] = ['Wind1VelX', 'BldPitch1', 'GenTq', 'RotSpeed', 'NacYaw'] + cases['Baseline'] = ['Wind1VelX', 'BldPitch1', 'GenTq', 'RotSpeed', 'NacYaw','GenPwr'] fig, ax = op.plot_fast_out(cases=cases, showplot=False) plt.show() diff --git a/ROSCO_toolbox/control_interface.py b/ROSCO_toolbox/control_interface.py index 5514bf6a..b3ad2777 100644 --- a/ROSCO_toolbox/control_interface.py +++ b/ROSCO_toolbox/control_interface.py @@ -209,8 +209,13 @@ def null_free_dll(*spam): # pragma: no cover extra_libs = [] if OS == "Windows": # pragma: Windows - _dlclose = ctypes.windll.kernel32.FreeLibrary - dlclose = lambda handle: 0 if _dlclose(handle) else 1 + try: + _dlclose = ctypes.windll.kernel32.FreeLibrary + dlclose = lambda handle: 0 if _dlclose(handle) else 1 + except: + kernel32 = ctypes.WinDLL('kernel32',use_last_error=True) + kernel32.FreeLibrary.argtypes = [ctypes.wintypes.HMODULE] + dlclose = lambda handle: 0 if kernel32.FreeLibrary(handle) else 1 # There's some controversy as to whether this DLL is guaranteed to exist. # It always has so far but isn't documented. However, MinGW assumes that it # is so, should this DLL be removed, then we have much bigger problems than diff --git a/ROSCO_toolbox/linear/linear_models.py b/ROSCO_toolbox/linear/linear_models.py index 5a4d6969..f096ce56 100644 --- a/ROSCO_toolbox/linear/linear_models.py +++ b/ROSCO_toolbox/linear/linear_models.py @@ -15,7 +15,7 @@ from scipy.io import loadmat try: - import pyFAST.linearization.mbc.mbc3 as mbc + import pyFAST.linearization.mbc as mbc except ImportError: import weis.control.mbc.mbc3 as mbc except ImportError: @@ -43,7 +43,6 @@ def __init__(self, lin_file_dir, lin_file_names, nlin=12, reduceStates=False, fr u_ops = np.array([], []) all_MBC = [] all_matData = [] - all_FAST_linData = [] if load_parallel: import time @@ -52,7 +51,7 @@ def __init__(self, lin_file_dir, lin_file_names, nlin=12, reduceStates=False, fr lin_file_dir, lin_file_names[iCase] + '.{}.lin'.format(i_lin+1))) for i_lin in range(0, nlin)] for iCase in range(0,n_lin_cases)] cores = mp.cpu_count() pool = mp.Pool(cores) - all_MBC, all_matData, all_FAST_linData = zip(*pool.map(run_mbc3, all_linfiles)) + all_MBC, all_matData = zip(*pool.map(run_mbc3, all_linfiles)) pool.close() pool.join() print('loaded in parallel in {} seconds'.format(time.time()-t1)) @@ -62,10 +61,9 @@ def __init__(self, lin_file_dir, lin_file_names, nlin=12, reduceStates=False, fr for iCase in range(0, n_lin_cases): lin_files_i = [os.path.realpath(os.path.join( lin_file_dir, lin_file_names[iCase] + '.{}.lin'.format(i_lin+1))) for i_lin in range(0, nlin)] - MBC, matData, FAST_linData = run_mbc3(lin_files_i) + MBC, matData = run_mbc3(lin_files_i) all_MBC.append(MBC) all_matData.append(matData) - all_FAST_linData.append(FAST_linData) print('loaded in serial in {} seconds'.format(time.time()-t1)) @@ -74,7 +72,6 @@ def __init__(self, lin_file_dir, lin_file_names, nlin=12, reduceStates=False, fr MBC = all_MBC[iCase] matData = all_matData[iCase] - FAST_linData = all_FAST_linData[iCase] if not iCase: # first time through # Initialize operating points, matrices @@ -713,9 +710,9 @@ def run_mbc3(fnames): Helper function to run mbc3 ''' print('Loading linearizations from:', ''.join(fnames[0].split('.')[:-2])) - MBC, matData, FAST_linData = mbc.fx_mbc3(fnames, verbose=False) + MBC, matData = mbc.fx_mbc3(fnames, verbose=False) - return MBC, matData, FAST_linData + return MBC, matData def connect_ml(mods, inputs, outputs): ''' diff --git a/ROSCO_toolbox/ofTools/case_gen/CaseLibrary.py b/ROSCO_toolbox/ofTools/case_gen/CaseLibrary.py index cc86785c..a637885e 100644 --- a/ROSCO_toolbox/ofTools/case_gen/CaseLibrary.py +++ b/ROSCO_toolbox/ofTools/case_gen/CaseLibrary.py @@ -131,6 +131,10 @@ def power_curve(**wind_case_opts): if 'U' in wind_case_opts: U = wind_case_opts['U'] + if type(U) != list: + U = [U] + elif type(U) == np.ndarray: + U = U.tolist() else: # default # Run conditions U = np.arange(4,14.5,.5).tolist() @@ -171,6 +175,9 @@ def simp_step(**wind_case_opts): else: #default T_step = 150 + # Wind directory, default is run_dir + wind_case_opts['wind_dir'] = wind_case_opts.get('wind_dir',wind_case_opts['run_dir']) + # Step Wind Setup # Make Default step wind object @@ -425,9 +432,9 @@ def sweep_pitch_act(start_group, **control_sweep_opts): def sweep_ipc_gains(start_group, **control_sweep_opts): case_inputs_control = {} - kis = np.linspace(0,3,6).tolist() + kis = np.linspace(0,1,6).tolist() # kis = [0.,0.6,1.2,1.8,2.4,3.] - KIs = [[ki * 1e-8,0.] for ki in kis] + KIs = [[ki * 6e-9,0.] for ki in kis] case_inputs_control[('DISCON_in','IPC_ControlMode')] = {'vals': [1], 'group': 0} # case_inputs_control[('DISCON_in','IPC_KI')] = {'vals': [[0.,0.],[1e-8,0.]], 'group': start_group} case_inputs_control[('DISCON_in','IPC_KI')] = {'vals': KIs, 'group': start_group} diff --git a/ROSCO_toolbox/ofTools/case_gen/run_FAST.py b/ROSCO_toolbox/ofTools/case_gen/run_FAST.py index 4a65c0e5..17944e46 100644 --- a/ROSCO_toolbox/ofTools/case_gen/run_FAST.py +++ b/ROSCO_toolbox/ofTools/case_gen/run_FAST.py @@ -2,6 +2,9 @@ Example script to run the DLCs in OpenFAST +This script is designed to work as-is if ROSCO is installed in 'develop' mode, i.e., python setup.py develop +Otherwise, the directories can be defined as attributes of the run_FAST_ROSCO + """ from ROSCO_toolbox.ofTools.case_gen.runFAST_pywrapper import runFAST_pywrapper, runFAST_pywrapper_batch @@ -17,29 +20,42 @@ from ROSCO_toolbox import controller as ROSCO_controller from ROSCO_toolbox import turbine as ROSCO_turbine -# Globals -this_dir = os.path.dirname(os.path.abspath(__file__)) -tune_case_dir = os.path.realpath(os.path.join(this_dir,'../../../Tune_Cases')) -rosco_dir = os.path.realpath(os.path.join(this_dir,'../../..')) - +this_dir = os.path.dirname(os.path.abspath(__file__)) class run_FAST_ROSCO(): def __init__(self): # Set default parameters - self.tuning_yaml = os.path.join(tune_case_dir,'IEA15MW.yaml') + self.tuning_yaml = 'IEA15MW.yaml' self.wind_case_fcn = cl.power_curve self.wind_case_opts = {} self.control_sweep_opts = {} self.control_sweep_fcn = None self.case_inputs = {} self.rosco_dll = '' - self.save_dir = os.path.join(rosco_dir,'outputs') self.n_cores = 1 self.base_name = '' self.controller_params = {} + # Directories + self.tune_case_dir = '' + self.rosco_dir = '' + self.save_dir = '' + + def run_FAST(self): + + # handle directories, set defaults + if not self.rosco_dir: + self.rosco_dir = os.path.realpath(os.path.join(this_dir,'../../..')) + + if not self.tune_case_dir: + self.tune_case_dir = os.path.realpath(os.path.join(self.rosco_dir,'Tune_Cases')) + + if not self.save_dir: + self.save_dir = os.path.join(self.rosco_dir,'outputs') + + # set up run directory if self.control_sweep_fcn: sweep_name = self.control_sweep_fcn.__name__ @@ -55,7 +71,7 @@ def run_FAST(self): # Start with tuning yaml definition of controller if not os.path.isabs(self.tuning_yaml): - self.tuning_yaml = os.path.join(tune_case_dir,self.tuning_yaml) + self.tuning_yaml = os.path.join(self.tune_case_dir,self.tuning_yaml) # Load yaml file inps = load_rosco_yaml(self.tuning_yaml) @@ -98,13 +114,12 @@ def run_FAST(self): # Set up rosco_dll if not self.rosco_dll: - rosco_dir = os.path.realpath(os.path.join(os.path.dirname(__file__),'../../..')) if platform.system() == 'Windows': - rosco_dll = os.path.join(rosco_dir, 'ROSCO/build/libdiscon.dll') + rosco_dll = os.path.join(self.rosco_dir, 'ROSCO/build/libdiscon.dll') elif platform.system() == 'Darwin': - rosco_dll = os.path.join(rosco_dir, 'ROSCO/build/libdiscon.dylib') + rosco_dll = os.path.join(self.rosco_dir, 'ROSCO/build/libdiscon.dylib') else: - rosco_dll = os.path.join(rosco_dir, 'ROSCO/build/libdiscon.so') + rosco_dll = os.path.join(self.rosco_dir, 'ROSCO/build/libdiscon.so') case_inputs[('ServoDyn','DLL_FileName')] = {'vals': [rosco_dll], 'group': 0} @@ -179,7 +194,7 @@ def run_FAST(self): if __name__ == "__main__": # Simulation config - sim_config = 11 + sim_config = 1 r = run_FAST_ROSCO() @@ -187,7 +202,7 @@ def run_FAST(self): if sim_config == 1: # FOCAL single wind speed testing - r.tuning_yaml = os.path.join(tune_case_dir,'IEA15MW.yaml') + r.tuning_yaml = 'IEA15MW.yaml' r.wind_case_fcn = cl.simp_step r.sweep_mode = None r.save_dir = '/Users/dzalkind/Tools/ROSCO/outputs' @@ -195,15 +210,15 @@ def run_FAST(self): elif sim_config == 6: # FOCAL rated wind speed tuning - r.tuning_yaml = os.path.join(tune_case_dir,'IEA15MW_FOCAL.yaml') - r.wind_case_fcn = power_curve + r.tuning_yaml = 'IEA15MW_FOCAL.yaml' + r.wind_case_fcn = cl.power_curve r.sweep_mode = cl.sweep_rated_torque r.save_dir = '/Users/dzalkind/Projects/FOCAL/drop_torque' elif sim_config == 7: # FOCAL rated wind speed tuning - r.tuning_yaml = os.path.join(tune_case_dir,'IEA15MW.yaml') + r.tuning_yaml = 'IEA15MW.yaml' r.wind_case_fcn = cl.steps r.wind_case_opts = { 'tt': [100,200], diff --git a/ROSCO_toolbox/ofTools/fast_io/FAST_wrapper.py b/ROSCO_toolbox/ofTools/fast_io/FAST_wrapper.py index 66e73ff6..cc8780f5 100644 --- a/ROSCO_toolbox/ofTools/fast_io/FAST_wrapper.py +++ b/ROSCO_toolbox/ofTools/fast_io/FAST_wrapper.py @@ -54,7 +54,7 @@ def execute(self): print('OpenFAST Failed: {}'.format(e)) failed = True run_idx = 2 - except: + except Exception as e: print('OpenFAST Failed: {}'.format(e)) failed = True run_idx = 2 diff --git a/ROSCO_toolbox/utilities.py b/ROSCO_toolbox/utilities.py index e4f55670..10ddc7d3 100644 --- a/ROSCO_toolbox/utilities.py +++ b/ROSCO_toolbox/utilities.py @@ -157,8 +157,8 @@ def write_DISCON(turbine, controller, param_file='DISCON.IN', txt_filename='Cp_C file.write('{} ! WE_FOPoles - First order system poles [1/s]\n'.format(''.join('{:<10.8f} '.format(rosco_vt['WE_FOPoles'][i]) for i in range(len(rosco_vt['WE_FOPoles']))))) file.write('\n') file.write('!------- YAW CONTROL ------------------------------------------------------\n') - file.write('{:<13.5f} ! Y_uSwitch - Wind speed to switch between Y_ErrThresh. If zero, only the first value of Y_ErrThresh is used [m/s]\n'.format(rosco_vt['Y_uSwitch'])) - file.write('{}! Y_ErrThresh - Yaw error threshold/deadband. Turbine begins to yaw when it passes this. If Y_uSwitch is zero, only the first value is used. [deg].\n'.format(''.join('{:<4.6f} '.format(rosco_vt['Y_ErrThresh'][i]) for i in range(len(rosco_vt['F_FlCornerFreq']))))) + file.write('{:<13.5f} ! Y_uSwitch - Wind speed to switch between Y_ErrThresh. If zero, only the second value of Y_ErrThresh is used [m/s]\n'.format(rosco_vt['Y_uSwitch'])) + file.write('{}! Y_ErrThresh - Yaw error threshold/deadbands. Turbine begins to yaw when it passes this. If Y_uSwitch is zero, only the second value is used. [deg].\n'.format(''.join('{:<4.6f} '.format(rosco_vt['Y_ErrThresh'][i]) for i in range(len(rosco_vt['F_FlCornerFreq']))))) file.write('{:<13.5f} ! Y_Rate - Yaw rate [rad/s]\n'.format(rosco_vt['Y_Rate'])) file.write('{:<13.5f} ! Y_MErrSet - Integrator saturation (maximum signal amplitude contribution to pitch from yaw-by-IPC), [rad]\n'.format(rosco_vt['Y_MErrSet'])) file.write('{:<13.5f} ! Y_IPC_IntSat - Integrator saturation (maximum signal amplitude contribution to pitch from yaw-by-IPC), [rad]\n'.format(rosco_vt['Y_IPC_IntSat'])) diff --git a/Test_Cases/BAR_10/BAR_10_DISCON.IN b/Test_Cases/BAR_10/BAR_10_DISCON.IN index a3f8cb24..f05cc03d 100644 --- a/Test_Cases/BAR_10/BAR_10_DISCON.IN +++ b/Test_Cases/BAR_10/BAR_10_DISCON.IN @@ -1,5 +1,5 @@ ! Controller parameter input file for the BAR_10 wind turbine -! - File written using ROSCO version 2.6.0 controller tuning logic on 09/20/22 +! - File written using ROSCO version 2.6.0 controller tuning logic on 11/29/22 !------- DEBUG ------------------------------------------------------------ 1 ! LoggingLevel - {0: write no debug files, 1: write standard output .dbg-file, 2: LoggingLevel 1 + ROSCO LocalVars (.dbg2) 3: LoggingLevel 2 + complete avrSWAP-array (.dbg3)} diff --git a/Test_Cases/IEA-15-240-RWT-UMaineSemi/DISCON-UMaineSemi.IN b/Test_Cases/IEA-15-240-RWT-UMaineSemi/DISCON-UMaineSemi.IN index c59453cc..82eec8be 100644 --- a/Test_Cases/IEA-15-240-RWT-UMaineSemi/DISCON-UMaineSemi.IN +++ b/Test_Cases/IEA-15-240-RWT-UMaineSemi/DISCON-UMaineSemi.IN @@ -1,5 +1,5 @@ ! Controller parameter input file for the IEA-15-240-RWT-UMaineSemi wind turbine -! - File written using ROSCO version 2.6.0 controller tuning logic on 09/20/22 +! - File written using ROSCO version 2.6.0 controller tuning logic on 11/29/22 !------- DEBUG ------------------------------------------------------------ 2 ! LoggingLevel - {0: write no debug files, 1: write standard output .dbg-file, 2: LoggingLevel 1 + ROSCO LocalVars (.dbg2) 3: LoggingLevel 2 + complete avrSWAP-array (.dbg3)} diff --git a/Test_Cases/NREL-5MW/DISCON.IN b/Test_Cases/NREL-5MW/DISCON.IN index 9abc9297..7369eac9 100644 --- a/Test_Cases/NREL-5MW/DISCON.IN +++ b/Test_Cases/NREL-5MW/DISCON.IN @@ -1,5 +1,5 @@ ! Controller parameter input file for the NREL-5MW wind turbine -! - File written using ROSCO version 2.6.0 controller tuning logic on 09/20/22 +! - File written using ROSCO version 2.6.0 controller tuning logic on 11/29/22 !------- DEBUG ------------------------------------------------------------ 1 ! LoggingLevel - {0: write no debug files, 1: write standard output .dbg-file, 2: LoggingLevel 1 + ROSCO LocalVars (.dbg2) 3: LoggingLevel 2 + complete avrSWAP-array (.dbg3)} From 827b2814fce9a9adc05adfb4013a5eb3c23a365c Mon Sep 17 00:00:00 2001 From: Alex Clerc Date: Mon, 19 Dec 2022 16:08:54 +0000 Subject: [PATCH 010/224] Update sim.py (#196) Fix gen_power in sim_ws_wd_series so it includes efficiency --- ROSCO_toolbox/sim.py | 1 + 1 file changed, 1 insertion(+) diff --git a/ROSCO_toolbox/sim.py b/ROSCO_toolbox/sim.py index 7ea930cd..39ab71f6 100644 --- a/ROSCO_toolbox/sim.py +++ b/ROSCO_toolbox/sim.py @@ -304,6 +304,7 @@ def sim_ws_wd_series(self, t_array, ws_array, wd_array, # Calculate the power gen_power[i] = gen_speed[i] * gen_torque[i] + gen_power[i] = gen_speed[i] * gen_torque[i] * self.turbine.GenEff / 100 # Update the nacelle position nac_yaw[i] = nac_yaw[i-1] + nac_yawrate[i]*rad2deg*dt From 5ad1d4109e118003784a7badc1010ff7e893fed9 Mon Sep 17 00:00:00 2001 From: dzalkind <65573423+dzalkind@users.noreply.github.com> Date: Thu, 22 Dec 2022 13:25:55 -0700 Subject: [PATCH 011/224] Doc fix (#200) * Correction of Full ROSCO Installation document * Use numpy 1.23 until other things catch up, like openmdao Co-authored-by: sarijalou --- docs/source/install.rst | 12 ++++++------ environment.yml | 2 +- 2 files changed, 7 insertions(+), 7 deletions(-) diff --git a/docs/source/install.rst b/docs/source/install.rst index 12029399..ecd12be2 100644 --- a/docs/source/install.rst +++ b/docs/source/install.rst @@ -182,17 +182,17 @@ Full ROSCO Installation We recommend using the full ROSCO tool-chain. This allows for full use of the provided functions along with the developed python packages and controller code, -Please follow the following steps to install the ROSCO tool-chain. You should do step 3 *or* 4. If you simply want to install the ROSCO toolbox without the controller, do step 3. If you would like to install the ROSCO toolbox and compile the controller simultaneously, do step 4. +Please follow the following steps to install the ROSCO tool-chain. You should do step 2 *or* 3. If you simply want to install the ROSCO toolbox without the controller, do step 3. If you would like to install the ROSCO toolbox and compile the controller simultaneously, do step 2. 1. Create a conda environment for ROSCO .. code-block:: bash - conda config --add channels conda-forge - conda create -y --name rosco-env python=3.8 - conda activate rosco-env + conda config --add channels conda-forge # (Enable Conda-forge Channel For Conda Package Manager) + conda create -y --name rosco-env python=3.8 # (Create a new environment named "rosco-env" that contains Python 3.8) + conda activate rosco-env # (Activate your "rosco-env" environment) -2. Clone and Install the ROSCO toolbox with ROSCO +2. Clone and Install the ROSCO toolbox with ROSCO controller .. code-block:: bash @@ -204,7 +204,7 @@ Please follow the following steps to install the ROSCO tool-chain. You should do conda install -y wisdem=3.5.0 python setup.py install --compile-rosco -3. Clone and Install the ROSCO toolbox without ROSCO +3. Clone and Install the ROSCO toolbox without ROSCO controller .. code-block:: bash diff --git a/environment.yml b/environment.yml index d90d5165..b170dc52 100644 --- a/environment.yml +++ b/environment.yml @@ -4,7 +4,7 @@ channels: dependencies: - matplotlib - - numpy + - numpy==1.23 - pytest - scipy - pyYAML From 9d27a333b3ddcfabbca5aeb177aca0e262824bed Mon Sep 17 00:00:00 2001 From: dzalkind <65573423+dzalkind@users.noreply.github.com> Date: Fri, 23 Dec 2022 11:44:51 -0700 Subject: [PATCH 012/224] OpenFAST v3.3.0 (#202) * Correction of Full ROSCO Installation document * Update FAST_reader, writer, input for 3.3.0 * Use numpy 1.23 until other things catch up, like openmdao * Tidy label to match OpenFAST reg-test * Use OpenFAST 3.3 in CI tests Co-authored-by: sarijalou --- .github/workflows/CI_rosco-pytools.yml | 4 +- ROSCO_toolbox/ofTools/fast_io/FAST_reader.py | 89 ++++++++----------- ROSCO_toolbox/ofTools/fast_io/FAST_writer.py | 48 +++++----- .../IEA-15-240-RWT-UMaineSemi_MoorDyn.dat | 46 +++++----- 4 files changed, 83 insertions(+), 104 deletions(-) diff --git a/.github/workflows/CI_rosco-pytools.yml b/.github/workflows/CI_rosco-pytools.yml index 143fc286..a594ad9d 100644 --- a/.github/workflows/CI_rosco-pytools.yml +++ b/.github/workflows/CI_rosco-pytools.yml @@ -129,7 +129,7 @@ jobs: # Install OpenFAST - name: Install OpenFAST run: | - conda install openfast==3.2.0 + conda install openfast==3.3 # Run examples - name: Run examples @@ -194,7 +194,7 @@ jobs: # Install OpenFAST - name: Install OpenFAST run: | - conda install openfast==3.2.0 + conda install openfast==3.3 # Run ROSCO Testing - name: Run ROSCO testing diff --git a/ROSCO_toolbox/ofTools/fast_io/FAST_reader.py b/ROSCO_toolbox/ofTools/fast_io/FAST_reader.py index 94d12ede..9a9719db 100644 --- a/ROSCO_toolbox/ofTools/fast_io/FAST_reader.py +++ b/ROSCO_toolbox/ofTools/fast_io/FAST_reader.py @@ -2256,7 +2256,6 @@ def read_MoorDyn(self): f.readline() self.fst_vt['MoorDyn']['Echo'] = bool_read(f.readline().split()[0]) f.readline() - self.fst_vt['MoorDyn']['NTypes'] = int_read(f.readline().split()[0]) f.readline() f.readline() self.fst_vt['MoorDyn']['Name'] = [] @@ -2264,77 +2263,67 @@ def read_MoorDyn(self): self.fst_vt['MoorDyn']['MassDen'] = [] self.fst_vt['MoorDyn']['EA'] = [] self.fst_vt['MoorDyn']['BA_zeta'] = [] - self.fst_vt['MoorDyn']['Can'] = [] - self.fst_vt['MoorDyn']['Cat'] = [] - self.fst_vt['MoorDyn']['Cdn'] = [] - self.fst_vt['MoorDyn']['Cdt'] = [] - for i in range(self.fst_vt['MoorDyn']['NTypes']): - data_line = f.readline().strip().split() + self.fst_vt['MoorDyn']['EI'] = [] + self.fst_vt['MoorDyn']['Cd'] = [] + self.fst_vt['MoorDyn']['Ca'] = [] + self.fst_vt['MoorDyn']['CdAx'] = [] + self.fst_vt['MoorDyn']['CaAx'] = [] + data_line = f.readline().strip().split() + while data_line[0][:3] != '---': # OpenFAST searches for ---, so we'll do the same self.fst_vt['MoorDyn']['Name'].append(str(data_line[0])) self.fst_vt['MoorDyn']['Diam'].append(float(data_line[1])) self.fst_vt['MoorDyn']['MassDen'].append(float(data_line[2])) self.fst_vt['MoorDyn']['EA'].append(float(data_line[3])) self.fst_vt['MoorDyn']['BA_zeta'].append(float(data_line[4])) - self.fst_vt['MoorDyn']['Can'].append(float(data_line[5])) - self.fst_vt['MoorDyn']['Cat'].append(float(data_line[6])) - self.fst_vt['MoorDyn']['Cdn'].append(float(data_line[7])) - self.fst_vt['MoorDyn']['Cdt'].append(float(data_line[8])) - f.readline() - self.fst_vt['MoorDyn']['NConnects'] = int_read(f.readline().split()[0]) + self.fst_vt['MoorDyn']['EI'].append(float(data_line[5])) + self.fst_vt['MoorDyn']['Cd'].append(float(data_line[6])) + self.fst_vt['MoorDyn']['Ca'].append(float(data_line[7])) + self.fst_vt['MoorDyn']['CdAx'].append(float(data_line[8])) + self.fst_vt['MoorDyn']['CaAx'].append(float(data_line[9])) + data_line = f.readline().strip().split() f.readline() f.readline() - self.fst_vt['MoorDyn']['Node'] = [] - self.fst_vt['MoorDyn']['Type'] = [] + self.fst_vt['MoorDyn']['Point_ID'] = [] + self.fst_vt['MoorDyn']['Attachment'] = [] self.fst_vt['MoorDyn']['X'] = [] self.fst_vt['MoorDyn']['Y'] = [] self.fst_vt['MoorDyn']['Z'] = [] self.fst_vt['MoorDyn']['M'] = [] self.fst_vt['MoorDyn']['V'] = [] - self.fst_vt['MoorDyn']['FX'] = [] - self.fst_vt['MoorDyn']['FY'] = [] - self.fst_vt['MoorDyn']['FZ'] = [] self.fst_vt['MoorDyn']['CdA'] = [] self.fst_vt['MoorDyn']['CA'] = [] - for i in range(self.fst_vt['MoorDyn']['NConnects']): - data_line = f.readline().strip().split() - self.fst_vt['MoorDyn']['Node'].append(int(data_line[0])) - self.fst_vt['MoorDyn']['Type'].append(str(data_line[1])) + data_line = f.readline().strip().split() + while data_line[0][:3] != '---': # OpenFAST searches for ---, so we'll do the same + self.fst_vt['MoorDyn']['Point_ID'].append(int(data_line[0])) + self.fst_vt['MoorDyn']['Attachment'].append(str(data_line[1])) self.fst_vt['MoorDyn']['X'].append(float(data_line[2])) self.fst_vt['MoorDyn']['Y'].append(float(data_line[3])) self.fst_vt['MoorDyn']['Z'].append(float(data_line[4])) self.fst_vt['MoorDyn']['M'].append(float(data_line[5])) self.fst_vt['MoorDyn']['V'].append(float(data_line[6])) - self.fst_vt['MoorDyn']['FX'].append(float(data_line[7])) - self.fst_vt['MoorDyn']['FY'].append(float(data_line[8])) - self.fst_vt['MoorDyn']['FZ'].append(float(data_line[9])) - self.fst_vt['MoorDyn']['CdA'].append(float(data_line[10])) - self.fst_vt['MoorDyn']['CA'].append(float(data_line[11])) - f.readline() - self.fst_vt['MoorDyn']['NLines'] = int_read(f.readline().split()[0]) - f.readline() - f.readline() - self.fst_vt['MoorDyn']['Line'] = [] - self.fst_vt['MoorDyn']['LineType'] = [] - self.fst_vt['MoorDyn']['UnstrLen'] = [] - self.fst_vt['MoorDyn']['NumSegs'] = [] - self.fst_vt['MoorDyn']['NodeAnch'] = [] - self.fst_vt['MoorDyn']['NodeFair'] = [] - self.fst_vt['MoorDyn']['Outputs'] = [] - self.fst_vt['MoorDyn']['CtrlChan'] = [] - for i in range(self.fst_vt['MoorDyn']['NLines']): + self.fst_vt['MoorDyn']['CdA'].append(float(data_line[7])) + self.fst_vt['MoorDyn']['CA'].append(float(data_line[8])) data_line = f.readline().strip().split() - self.fst_vt['MoorDyn']['Line'].append(int(data_line[0])) + f.readline() + f.readline() + self.fst_vt['MoorDyn']['Line_ID'] = [] + self.fst_vt['MoorDyn']['LineType'] = [] + self.fst_vt['MoorDyn']['AttachA'] = [] + self.fst_vt['MoorDyn']['AttachB'] = [] + self.fst_vt['MoorDyn']['UnstrLen'] = [] + self.fst_vt['MoorDyn']['NumSegs'] = [] + self.fst_vt['MoorDyn']['Outputs'] = [] + data_line = f.readline().strip().split() + while data_line[0][:3] != '---': # OpenFAST searches for ---, so we'll do the same + self.fst_vt['MoorDyn']['Line_ID'].append(int(data_line[0])) self.fst_vt['MoorDyn']['LineType'].append(str(data_line[1])) - self.fst_vt['MoorDyn']['UnstrLen'].append(float(data_line[2])) - self.fst_vt['MoorDyn']['NumSegs'].append(int(data_line[3])) - self.fst_vt['MoorDyn']['NodeAnch'].append(int(data_line[4])) - self.fst_vt['MoorDyn']['NodeFair'].append(int(data_line[5])) + self.fst_vt['MoorDyn']['AttachA'].append(int(data_line[2])) + self.fst_vt['MoorDyn']['AttachB'].append(int(data_line[3])) + self.fst_vt['MoorDyn']['UnstrLen'].append(float(data_line[4])) + self.fst_vt['MoorDyn']['NumSegs'].append(int(data_line[5])) self.fst_vt['MoorDyn']['Outputs'].append(str(data_line[6])) - if len(data_line) > 7: - self.fst_vt['MoorDyn']['CtrlChan'].append(int(data_line[7])) - else: - self.fst_vt['MoorDyn']['CtrlChan'].append(0) - f.readline() + data_line = f.readline().strip().split() + self.fst_vt['MoorDyn']['dtM'] = float_read(f.readline().split()[0]) self.fst_vt['MoorDyn']['kbot'] = float_read(f.readline().split()[0]) self.fst_vt['MoorDyn']['cbot'] = float_read(f.readline().split()[0]) diff --git a/ROSCO_toolbox/ofTools/fast_io/FAST_writer.py b/ROSCO_toolbox/ofTools/fast_io/FAST_writer.py index 6df98654..8380c686 100644 --- a/ROSCO_toolbox/ofTools/fast_io/FAST_writer.py +++ b/ROSCO_toolbox/ofTools/fast_io/FAST_writer.py @@ -1951,54 +1951,48 @@ def write_MoorDyn(self): f.write('Generated with AeroElasticSE FAST driver\n') f.write('{!s:<22} {:<11} {:}'.format(self.fst_vt['MoorDyn']['Echo'], 'Echo', '- echo the input file data (flag)\n')) f.write('----------------------- LINE TYPES ------------------------------------------\n') - f.write('{:<22d} {:<11} {:}'.format(self.fst_vt['MoorDyn']['NTypes'], 'NTypes', '- number of LineTypes\n')) - f.write(" ".join(['{:^11s}'.format(i) for i in ['Name', 'Diam', 'MassDen', 'EA', 'BA/-zeta', 'Can', 'Cat', 'Cdn', 'Cdt']])+'\n') - f.write(" ".join(['{:^11s}'.format(i) for i in ['(-)', '(m)', '(kg/m)', '(N)', '(N-s/-)', '(-)', '(-)', '(-)', '(-)']])+'\n') - for i in range(self.fst_vt['MoorDyn']['NTypes']): + f.write(" ".join(['{:^11s}'.format(i) for i in ['Name', 'Diam', 'MassDen', 'EA', 'BA/-zeta', 'EI', 'Cd', 'Ca', 'CdAx', 'CaAx']])+'\n') + f.write(" ".join(['{:^11s}'.format(i) for i in ['(-)', '(m)', '(kg/m)', '(N)', '(N-s/-)', '(-)', '(-)', '(-)', '(-)', '(-)']])+'\n') + for i in range(len(self.fst_vt['MoorDyn']['Name'])): ln = [] ln.append('{:^11}'.format(self.fst_vt['MoorDyn']['Name'][i])) ln.append('{:^11}'.format(self.fst_vt['MoorDyn']['Diam'][i])) ln.append('{:^11}'.format(self.fst_vt['MoorDyn']['MassDen'][i])) ln.append('{:^11}'.format(self.fst_vt['MoorDyn']['EA'][i])) ln.append('{:^11}'.format(self.fst_vt['MoorDyn']['BA_zeta'][i])) - ln.append('{:^11}'.format(self.fst_vt['MoorDyn']['Can'][i])) - ln.append('{:^11}'.format(self.fst_vt['MoorDyn']['Cat'][i])) - ln.append('{:^11}'.format(self.fst_vt['MoorDyn']['Cdn'][i])) - ln.append('{:^11}'.format(self.fst_vt['MoorDyn']['Cdt'][i])) + ln.append('{:^11}'.format(self.fst_vt['MoorDyn']['EI'][i])) + ln.append('{:^11}'.format(self.fst_vt['MoorDyn']['Cd'][i])) + ln.append('{:^11}'.format(self.fst_vt['MoorDyn']['Ca'][i])) + ln.append('{:^11}'.format(self.fst_vt['MoorDyn']['CdAx'][i])) + ln.append('{:^11}'.format(self.fst_vt['MoorDyn']['CaAx'][i])) f.write(" ".join(ln) + '\n') - f.write('---------------------- CONNECTION PROPERTIES --------------------------------\n') - f.write('{:<22d} {:<11} {:}'.format(self.fst_vt['MoorDyn']['NConnects'], 'NConnects', '- number of connections including anchors and fairleads\n')) - f.write(" ".join(['{:^11s}'.format(i) for i in ['Node', 'Type', 'X', 'Y', 'Z', 'M', 'V', 'FX', 'FY', 'FZ', 'CdA', 'CA']])+'\n') - f.write(" ".join(['{:^11s}'.format(i) for i in ['(-)', '(-)', '(m)', '(m)', '(m)', '(kg)', '(m^3)', '(kN)', '(kN)', '(kN)', '(m^2)', '(-)']])+'\n') - for i in range(self.fst_vt['MoorDyn']['NConnects']): + f.write('---------------------- POINTS --------------------------------\n') + f.write(" ".join(['{:^11s}'.format(i) for i in ['ID', 'Attachment', 'X', 'Y', 'Z', 'M', 'V', 'CdA', 'CA']])+'\n') + f.write(" ".join(['{:^11s}'.format(i) for i in ['(-)', '(-)', '(m)', '(m)', '(m)', '(kg)', '(m^3)', '(m^2)', '(-)']])+'\n') + for i in range(len(self.fst_vt['MoorDyn']['Point_ID'])): ln = [] - ln.append('{:^11d}'.format(self.fst_vt['MoorDyn']['Node'][i])) - ln.append('{:^11}'.format(self.fst_vt['MoorDyn']['Type'][i])) + ln.append('{:^11d}'.format(self.fst_vt['MoorDyn']['Point_ID'][i])) + ln.append('{:^11}'.format(self.fst_vt['MoorDyn']['Attachment'][i])) ln.append('{:^11}'.format(self.fst_vt['MoorDyn']['X'][i])) ln.append('{:^11}'.format(self.fst_vt['MoorDyn']['Y'][i])) ln.append('{:^11}'.format(self.fst_vt['MoorDyn']['Z'][i])) ln.append('{:^11}'.format(self.fst_vt['MoorDyn']['M'][i])) ln.append('{:^11}'.format(self.fst_vt['MoorDyn']['V'][i])) - ln.append('{:^11}'.format(self.fst_vt['MoorDyn']['FX'][i])) - ln.append('{:^11}'.format(self.fst_vt['MoorDyn']['FY'][i])) - ln.append('{:^11}'.format(self.fst_vt['MoorDyn']['FZ'][i])) ln.append('{:^11}'.format(self.fst_vt['MoorDyn']['CdA'][i])) ln.append('{:^11}'.format(self.fst_vt['MoorDyn']['CA'][i])) f.write(" ".join(ln) + '\n') - f.write('---------------------- LINE PROPERTIES --------------------------------------\n') - f.write('{:<22d} {:<11} {:}'.format(self.fst_vt['MoorDyn']['NLines'], 'NLines', '- number of line objects\n')) - f.write(" ".join(['{:^11s}'.format(i) for i in ['Line', 'LineType', 'UnstrLen', 'NumSegs', 'NodeAnch', 'NodeFair', 'Outputs', 'CtrlChan']])+'\n') - f.write(" ".join(['{:^11s}'.format(i) for i in ['(-)', '(-)', '(m)', '(-)', '(-)', '(-)', '(-)', '(-)']])+'\n') - for i in range(self.fst_vt['MoorDyn']['NLines']): + f.write('---------------------- LINES --------------------------------------\n') + f.write(" ".join(['{:^11s}'.format(i) for i in ['Line', 'LineType', 'AttachA', 'AttachB', 'UnstrLen', 'NumSegs', 'Outputs']])+'\n') + f.write(" ".join(['{:^11s}'.format(i) for i in ['(-)', '(-)', '(-)', '(-)', '(m)', '(-)', '(-)']])+'\n') + for i in range(len(self.fst_vt['MoorDyn']['Line_ID'])): ln = [] - ln.append('{:^11d}'.format(self.fst_vt['MoorDyn']['Line'][i])) + ln.append('{:^11d}'.format(self.fst_vt['MoorDyn']['Line_ID'][i])) ln.append('{:^11}'.format(self.fst_vt['MoorDyn']['LineType'][i])) + ln.append('{:^11d}'.format(self.fst_vt['MoorDyn']['AttachA'][i])) + ln.append('{:^11d}'.format(self.fst_vt['MoorDyn']['AttachB'][i])) ln.append('{:^11}'.format(self.fst_vt['MoorDyn']['UnstrLen'][i])) ln.append('{:^11d}'.format(self.fst_vt['MoorDyn']['NumSegs'][i])) - ln.append('{:^11d}'.format(self.fst_vt['MoorDyn']['NodeAnch'][i])) - ln.append('{:^11d}'.format(self.fst_vt['MoorDyn']['NodeFair'][i])) ln.append('{:^11}'.format(self.fst_vt['MoorDyn']['Outputs'][i])) - ln.append('{:^11}'.format(self.fst_vt['MoorDyn']['CtrlChan'][i])) f.write(" ".join(ln) + '\n') f.write('---------------------- SOLVER OPTIONS ---------------------------------------\n') f.write('{:<22} {:<11} {:}'.format(self.fst_vt['MoorDyn']['dtM'], 'dtM', '- time step to use in mooring integration (s)\n')) diff --git a/Test_Cases/IEA-15-240-RWT-UMaineSemi/IEA-15-240-RWT-UMaineSemi_MoorDyn.dat b/Test_Cases/IEA-15-240-RWT-UMaineSemi/IEA-15-240-RWT-UMaineSemi_MoorDyn.dat index 9032a2d8..ecb74bd9 100644 --- a/Test_Cases/IEA-15-240-RWT-UMaineSemi/IEA-15-240-RWT-UMaineSemi_MoorDyn.dat +++ b/Test_Cases/IEA-15-240-RWT-UMaineSemi/IEA-15-240-RWT-UMaineSemi_MoorDyn.dat @@ -1,28 +1,25 @@ ---------------------- MoorDyn Input File ------------------------------------ +--------------------- MoorDyn Input File ------------------------------------ IEA 15 MW offshore reference model on UMaine VolturnUS-S semi-submersible floating platform mooring model- C. Allen UMaine FALSE Echo - echo the input file data (flag) ----------------------- LINE TYPES ------------------------------------------ -1 NTypes - number of LineTypes -Name Diam MassDen EA BA/-zeta Can Cat Cdn Cdt -(-) (m) (kg/m) (N) (N-s/-) (-) (-) (-) (-) -main 0.333 685.00 3.27E+09 -1 0.82 0.27 1.11 0.20 ----------------------- CONNECTION PROPERTIES -------------------------------- -6 NConnects - number of connections including anchors and fairleads -Node Type X Y Z M V FX FY FZ CdA CA -(-) (-) (m) (m) (m) (kg) (m^3) (kN) (kN) (kN) (m^2) (-) -1 Vessel -58.000 0.000 -14.000 0 0 0 0 0 0 0 -2 Fixed -837.600 0.000 -200.000 0 0 0 0 0 0 0 -3 Vessel 29.000 50.229 -14.000 0 0 0 0 0 0 0 -4 Fixed 418.800 725.383 -200.000 0 0 0 0 0 0 0 -5 Vessel 29.000 -50.229 -14.000 0 0 0 0 0 0 0 -6 Fixed 418.800 -725.383 -200.000 0 0 0 0 0 0 0 ----------------------- LINE PROPERTIES -------------------------------------- -3 NLines - number of line objects -Line LineType UnstrLen NumSegs NodeAnch NodeFair Flags/Outputs Control -(-) (-) (m) (-) (-) (-) (-) (-) -1 main 850.00 50 2 1 - 0 -2 main 850.00 50 4 3 - 0 -3 main 850.00 50 6 5 - 0 +Name Diam MassDen EA BA/-zeta EI Cd Ca CdAx CaAx +(-) (m) (kg/m) (N) (N-s/-) (-) (-) (-) (-) (-) +main 0.333 685.00 3.27E+09 -1 0 1.11 0.82 0.2 0.27 +---------------------- POINTS -------------------------------- +ID Type X Y Z M V CdA CA +(-) (-) (m) (m) (m) (kg) (m^3) (m^2) (-) +1 Vessel -58.000 0.000 -14.000 0 0 0 0 +2 Fixed -837.600 0.000 -200.000 0 0 0 0 +3 Vessel 29.000 50.229 -14.000 0 0 0 0 +4 Fixed 418.800 725.383 -200.000 0 0 0 0 +5 Vessel 29.000 -50.229 -14.000 0 0 0 0 +6 Fixed 418.800 -725.383 -200.000 0 0 0 0 +---------------------- LINES -------------------------------------- +ID LineType AttachA AttachB UnstrLen NumSegs Outputs +(-) (-) (-) (-) (m) (-) (-) +1 main 2 1 850.00 50 - +2 main 4 3 850.00 50 - +3 main 6 5 850.00 50 - ---------------------- SOLVER OPTIONS --------------------------------------- 0.001 dtM - time step to use in mooring integration (s) 3.0e6 kbot - bottom stiffness (Pa/m) @@ -31,7 +28,7 @@ Line LineType UnstrLen NumSegs NodeAnch NodeFair Flags/Outputs Control 60.0 TmaxIC - max time for ic gen (s) 4.0 CdScaleIC - factor by which to scale drag coefficients during dynamic relaxation (-) 0.001 threshIC - threshold for IC convergence (-) ------------------------- OUTPUTS -------------------------------------------- +------------------------ OUTPUTS -------------------------------------------- FairTen1 FairTen2 FairTen3 @@ -60,5 +57,4 @@ fx fy fz END -------------------------- need this line -------------------------------------- - +------------------------- need this line -------------------------------------- \ No newline at end of file From 75a648cdfba7e74c55be3674314ae692d2458523 Mon Sep 17 00:00:00 2001 From: Nathaniel deVelder Date: Mon, 16 Jan 2023 20:56:59 -0700 Subject: [PATCH 013/224] AWC First Version, collected changes --- ROSCO/src/Controllers.f90 | 32 ++++++++++++++++++++++++++++---- ROSCO/src/ROSCO_Types.f90 | 6 ++++++ ROSCO/src/ReadSetParameters.f90 | 8 ++++++++ 3 files changed, 42 insertions(+), 4 deletions(-) diff --git a/ROSCO/src/Controllers.f90 b/ROSCO/src/Controllers.f90 index 7568d4df..1346f310 100644 --- a/ROSCO/src/Controllers.f90 +++ b/ROSCO/src/Controllers.f90 @@ -42,6 +42,16 @@ SUBROUTINE PitchControl(avrSWAP, CntrPar, LocalVar, objInst, DebugVar, ErrVar) CHARACTER(*), PARAMETER :: RoutineName = 'PitchControl' + ! Local + REAL(DbKi), PARAMETER :: phi1 = 0.0 ! Phase difference from first to second blade + REAL(DbKi), PARAMETER :: phi2 = 2.0/3.0*PI ! Phase difference from first to second blade + REAL(DbKi), PARAMETER :: phi3 = 4.0/3.0*PI ! Phase difference from first to third blade + REAL(DbKi), DIMENSION(3) :: AWC_angle + DOUBLE COMPLEX, DIMENSION(3) :: AWC_complexangle + DOUBLE COMPLEX :: complexI = (0.0, 1.0) + INTEGER(IntKi) :: Imode ! Index used for looping through AWC modes + REAL(DbKi) :: clockang ! Clock angle for AWC pitching + ! ------- Blade Pitch Controller -------- ! Load PC State IF (LocalVar%PC_State == 1) THEN ! PI BldPitch control @@ -118,6 +128,19 @@ SUBROUTINE PitchControl(avrSWAP, CntrPar, LocalVar, objInst, DebugVar, ErrVar) ENDIF ENDIF + ! Compute the AWC pitch settings + AWC_complexangle = 0.0D0 + DO Imode = 1,CntrPar%AWC_NumModes + clockang = CntrPar%AWC_clockangle(Imode)*PI/180.0_DbKi + AWC_angle(1) = CntrPar%AWC_omega(Imode) * LocalVar%Time - CntrPar%AWC_n(Imode) * (LocalVar%Azimuth + phi1 + clockang) + AWC_angle(2) = CntrPar%AWC_omega(Imode) * LocalVar%Time - CntrPar%AWC_n(Imode) * (LocalVar%Azimuth + phi2 + clockang) + AWC_angle(3) = CntrPar%AWC_omega(Imode) * LocalVar%Time - CntrPar%AWC_n(Imode) * (LocalVar%Azimuth + phi3 + clockang) + ! Add the forcing contribution to AWC_complexangle + DO K = 1,LocalVar%NumBl ! Loop through all blades + AWC_complexangle(K) = AWC_complexangle(K) + CntrPar%AWC_amp(Imode) * EXP(complexI * (AWC_angle(K))) + END DO + END DO + ! Place pitch actuator here, so it can be used with or without open-loop DO K = 1,LocalVar%NumBl ! Loop through all blades, add IPC contribution and limit pitch rate IF (CntrPar%PA_Mode > 0) THEN @@ -141,10 +164,11 @@ SUBROUTINE PitchControl(avrSWAP, CntrPar, LocalVar, objInst, DebugVar, ErrVar) ! Command the pitch demanded from the last ! call to the controller (See Appendix A of Bladed User's Guide): - avrSWAP(42) = LocalVar%PitComAct(1) ! Use the command angles of all blades if using individual pitch - avrSWAP(43) = LocalVar%PitComAct(2) ! " - avrSWAP(44) = LocalVar%PitComAct(3) ! " - avrSWAP(45) = LocalVar%PitComAct(1) ! Use the command angle of blade 1 if using collective pitch + ! AWC added here as well + avrSWAP(42) = LocalVar%PitCom(1) + REAL(AWC_complexangle(1)) ! Use the command angles of all blades if using individual pitch + avrSWAP(43) = LocalVar%PitCom(2) + REAL(AWC_complexangle(2)) ! " + avrSWAP(44) = LocalVar%PitCom(3) + REAL(AWC_complexangle(3)) ! " + avrSWAP(45) = LocalVar%PitCom(1) + REAL(AWC_complexangle(1)) ! Use the command angle of blade 1 if using collective pitch ! Add RoutineName to error message IF (ErrVar%aviFAIL < 0) THEN diff --git a/ROSCO/src/ROSCO_Types.f90 b/ROSCO/src/ROSCO_Types.f90 index 46c26a09..589352bb 100644 --- a/ROSCO/src/ROSCO_Types.f90 +++ b/ROSCO/src/ROSCO_Types.f90 @@ -123,6 +123,12 @@ MODULE ROSCO_Types REAL(DbKi) :: PC_RtTq99 ! 99% of the rated torque value, using for switching between pitch and torque control, [Nm]. REAL(DbKi) :: VS_MaxOMTq ! Maximum torque at the end of the below-rated region 2, [Nm] REAL(DbKi) :: VS_MinOMTq ! Minimum torque at the beginning of the below-rated region 2, [Nm] + REAL(DbKi) :: Test_Input ! Test Var Input + REAL(DbKi), DIMENSION(:), ALLOCATABLE :: AWC_omega ! AWC frequency [rad/s] + REAL(DbKi), DIMENSION(:), ALLOCATABLE :: AWC_amp ! AWC amplitude [deg] + REAL(DbKi), DIMENSION(:), ALLOCATABLE :: AWC_clockangle ! AWC clocking angle [deg] + INTEGER(IntKi), DIMENSION(:), ALLOCATABLE :: AWC_n ! AWC azimuthal mode [-] + INTEGER(IntKi) :: AWC_NumModes ! AWC: Number of modes to include [-] END TYPE ControlParameters TYPE, PUBLIC :: WE diff --git a/ROSCO/src/ReadSetParameters.f90 b/ROSCO/src/ReadSetParameters.f90 index a0ac9e38..92a3eef4 100644 --- a/ROSCO/src/ReadSetParameters.f90 +++ b/ROSCO/src/ReadSetParameters.f90 @@ -390,6 +390,14 @@ SUBROUTINE ReadControlParameterFileSub(CntrPar, zmqVar, accINFILE, accINFILE_siz CALL ParseInput(UnControllerParameters,CurLine,'PA_CornerFreq',accINFILE(1),CntrPar%PA_CornerFreq,ErrVar) CALL ParseInput(UnControllerParameters,CurLine,'PA_Damping',accINFILE(1),CntrPar%PA_Damping,ErrVar) CALL ReadEmptyLine(UnControllerParameters,CurLine) + + !------------ AWC input ------------ + CALL ReadEmptyLine(UnControllerParameters,CurLine) + CALL ParseInput(UnControllerParameters,CurLine,'AWC_NumModes', accINFILE(1),CntrPar%AWC_NumModes, ErrVar) + CALL ParseAry( UnControllerParameters,CurLine,'AWC_n', CntrPar%AWC_n, CntrPar%AWC_NumModes, accINFILE(1), ErrVar) + CALL ParseAry( UnControllerParameters,CurLine,'AWC_omega', CntrPar%AWC_omega, CntrPar%AWC_NumModes, accINFILE(1), ErrVar) + CALL ParseAry( UnControllerParameters,CurLine,'AWC_amp', CntrPar%AWC_amp, CntrPar%AWC_NumModes, accINFILE(1), ErrVar) + CALL ParseAry( UnControllerParameters,CurLine,'AWC_clockangle',CntrPar%AWC_clockangle,CntrPar%AWC_NumModes, accINFILE(1), ErrVar) !------------ External control interface ------------ CALL ReadEmptyLine(UnControllerParameters,CurLine) From 05d7b3b948c12ad40892941b6f92f3b08f5c6894 Mon Sep 17 00:00:00 2001 From: Garrett Barter Date: Wed, 18 Jan 2023 16:15:26 -0700 Subject: [PATCH 014/224] Compatibility with Numpy v1.24 (#208) * compatibility with numpy 1.24 * update CI to newest action, generic gfortran, and python 3.9 * install gfortran on macs * change slashes on windows? * revert slash and shell changes * more path fix * trying quotes * try bash again * specify source dir * trial and error. . . * trial and error. . . * try a different shell? * trial and error * trial and error * trial and error --- .github/workflows/CI_rosco-compile.yml | 33 ++++++++++--------- .github/workflows/CI_rosco-pytools.yml | 22 ++++++------- ROSCO_toolbox/linear/lin_util.py | 5 ++- .../ofTools/fast_io/output_processing.py | 2 +- .../ofTools/fast_io/read_fast_input.py | 14 ++++---- 5 files changed, 41 insertions(+), 35 deletions(-) diff --git a/.github/workflows/CI_rosco-compile.yml b/.github/workflows/CI_rosco-compile.yml index c04abb8f..3e4e70c3 100644 --- a/.github/workflows/CI_rosco-compile.yml +++ b/.github/workflows/CI_rosco-compile.yml @@ -3,9 +3,9 @@ name: CI_rosco-compile # We run CI on push commits on all branches on: [push, pull_request] -# Specify FORTRAN compiler +# Specify FORTRAN compiler, used to be "gfortran-10" env: - FORTRAN_COMPILER: gfortran-10 + FORTRAN_COMPILER: gfortran # A workflow run is made up of one or more jobs that can run sequentially or in parallel jobs: @@ -16,11 +16,11 @@ jobs: fail-fast: true matrix: os: ["ubuntu-latest", "macOS-latest", "windows-latest"] - python-version: ["3.8"] + python-version: ["3.9"] steps: - name: Checkout repository - uses: actions/checkout@v2 + uses: actions/checkout@v3 - name: Setup environment uses: conda-incubator/setup-miniconda@v2 @@ -28,7 +28,7 @@ jobs: miniconda-version: "latest" channels: conda-forge, general auto-update-conda: true - python-version: 3.8 + python-version: 3.9 environment-file: environment.yml # Install ROSCO toolbox @@ -42,19 +42,25 @@ jobs: shell: bash -l {0} run: python ROSCO/rosco_registry/write_registry.py - - name: Add dependencies windows if: true == contains( matrix.os, 'windows') - shell: bash -l {0} run: | conda install -y m2w64-toolchain + - name: Add dependencies windows + if: true == contains( matrix.os, 'mac') + shell: bash -l {0} + run: | + conda install -y gfortran + - name: Setup Workspace - run: cmake -E make_directory ${{runner.workspace}}/ROSCO/ROSCO/build + run: | + cmake -E make_directory ${{runner.workspace}}/ROSCO/ROSCO/build - name: Configure and Build - unix if: false == contains( matrix.os, 'windows') - working-directory: ${{runner.workspace}}/ROSCO/ROSCO/build + shell: bash -l {0} + working-directory: "${{runner.workspace}}/ROSCO/ROSCO/build" run: | cmake \ -DCMAKE_INSTALL_PREFIX:PATH=${{runner.workspace}}/ROSCO/ROSCO/install \ @@ -64,11 +70,8 @@ jobs: - name: Configure and Build - windows if: true == contains( matrix.os, 'windows') - working-directory: ${{runner.workspace}}/ROSCO/ROSCO/build - shell: bash -l {0} + #shell: bash #-l {0} + working-directory: "${{runner.workspace}}/ROSCO/ROSCO/build" run: | - cmake \ - -DCMAKE_INSTALL_PREFIX:PATH=${{runner.workspace}}/ROSCO/ROSCO/install \ - -G "MinGW Makefiles" \ - .. + cmake -G "MinGW Makefiles" -DCMAKE_INSTALL_PREFIX="${{runner.workspace}}/ROSCO/ROSCO/build" .. cmake --build . --target install diff --git a/.github/workflows/CI_rosco-pytools.yml b/.github/workflows/CI_rosco-pytools.yml index a594ad9d..c5c31b1c 100644 --- a/.github/workflows/CI_rosco-pytools.yml +++ b/.github/workflows/CI_rosco-pytools.yml @@ -3,9 +3,9 @@ name: CI_rosco-pytools # We run CI on push commits on all branches on: [push, pull_request] -# Specify FORTRAN compiler +# Specify FORTRAN compiler, used to be "gfortran-10" env: - FC: gfortran-10 + FC: gfortran # A workflow run is made up of one or more jobs that can run sequentially or in parallel jobs: @@ -16,14 +16,14 @@ jobs: fail-fast: true matrix: os: ["ubuntu-latest", "macOS-latest", "windows-latest"] - python-version: ["3.8"] + python-version: ["3.9"] defaults: run: shell: bash -l {0} steps: - name: Checkout repository and submodules - uses: actions/checkout@v2 + uses: actions/checkout@v3 with: submodules: recursive @@ -33,7 +33,7 @@ jobs: miniconda-version: "latest" channels: conda-forge, general auto-update-conda: true - python-version: 3.8 + python-version: 3.9 environment-file: environment.yml @@ -72,14 +72,14 @@ jobs: fail-fast: true matrix: os: ["ubuntu-latest"] #, "macOS-latest"] - python-version: ["3.8"] + python-version: ["3.9"] defaults: run: shell: bash -l {0} steps: - name: Checkout repository and submodules - uses: actions/checkout@v2 + uses: actions/checkout@v3 with: submodules: recursive @@ -89,7 +89,7 @@ jobs: miniconda-version: "latest" channels: conda-forge, general auto-update-conda: true - python-version: 3.8 + python-version: 3.9 environment-file: environment.yml # setup cmake @@ -159,14 +159,14 @@ jobs: fail-fast: true matrix: os: ["ubuntu-latest"] #, "macOS-latest"] - python-version: ["3.8"] + python-version: ["3.9"] defaults: run: shell: bash -l {0} steps: - name: Checkout repository and submodules - uses: actions/checkout@v2 + uses: actions/checkout@v3 with: submodules: recursive @@ -176,7 +176,7 @@ jobs: miniconda-version: "latest" channels: conda-forge, general auto-update-conda: true - python-version: 3.8 + python-version: 3.9 environment-file: environment.yml diff --git a/ROSCO_toolbox/linear/lin_util.py b/ROSCO_toolbox/linear/lin_util.py index 969ea3fa..d8347f00 100644 --- a/ROSCO_toolbox/linear/lin_util.py +++ b/ROSCO_toolbox/linear/lin_util.py @@ -296,7 +296,10 @@ def interp_matrix(x, matrix_3D, q): def _convert_to_ss(sys): - if isinstance(sys, (int, float, complex, np.float)): + if isinstance(sys, (int, float, complex, + np.float64, np.float32, + np.int64, np.int32, + np.complex128, np.complex64)): ss = sp.signal.StateSpace([0], [0], [0], sys) else: ss = sys diff --git a/ROSCO_toolbox/ofTools/fast_io/output_processing.py b/ROSCO_toolbox/ofTools/fast_io/output_processing.py index 1573c1e6..266a9da2 100644 --- a/ROSCO_toolbox/ofTools/fast_io/output_processing.py +++ b/ROSCO_toolbox/ofTools/fast_io/output_processing.py @@ -341,7 +341,7 @@ def load_ascii_output(filename): info['attribute_units'] = [unit[1:-1] for unit in f.readline().split()] # Data, up to end of file or empty line (potential comment line at the end) - data = np.array([l.strip().split() for l in takewhile(lambda x: len(x.strip())>0, f.readlines())]).astype(np.float) + data = np.array([l.strip().split() for l in takewhile(lambda x: len(x.strip())>0, f.readlines())]).astype(np.float_) return data, info diff --git a/ROSCO_toolbox/ofTools/fast_io/read_fast_input.py b/ROSCO_toolbox/ofTools/fast_io/read_fast_input.py index 63a2fd92..c8b76313 100644 --- a/ROSCO_toolbox/ofTools/fast_io/read_fast_input.py +++ b/ROSCO_toolbox/ofTools/fast_io/read_fast_input.py @@ -802,9 +802,9 @@ def readmat(n,m,lines,iStart): self.addKeyVal('nDOF',int(l.split(':')[1])) nDOFCommon=self['nDOF'] elif l.find('!time increment')==0: - self.addKeyVal('dt',np.float(l.split(':')[1])) + self.addKeyVal('dt',np.float_(l.split(':')[1])) elif l.find('!total simulation time')==0: - self.addKeyVal('T',np.float(l.split(':')[1])) + self.addKeyVal('T',np.float_(l.split(':')[1])) else: raise BrokenFormatError('Unexcepted content found on line {}'.format(i)) i+=1 @@ -855,9 +855,9 @@ def detectAndReadAirfoil(self,lines): nTabLines=0 while 14+nTabLines0 : nTabLines +=1 - #data = np.array([lines[i].strip().split() for i in range(14,len(lines)) if len(lines[i])>0]).astype(np.float) - #data = np.array([lines[i].strip().split() for i in takewhile(lambda x: len(lines[i].strip())>0, range(14,len(lines)-1))]).astype(np.float) - data = np.array([lines[i].strip().split() for i in range(14,nTabLines+14)]).astype(np.float) + #data = np.array([lines[i].strip().split() for i in range(14,len(lines)) if len(lines[i])>0]).astype(np.float_) + #data = np.array([lines[i].strip().split() for i in takewhile(lambda x: len(lines[i].strip())>0, range(14,len(lines)-1))]).astype(np.float_) + data = np.array([lines[i].strip().split() for i in range(14,nTabLines+14)]).astype(np.float_) #print(data) d = getDict() d['label'] = 'Polar' @@ -883,9 +883,9 @@ def readBeamDynProps(self,lines,iStart): for j in range(nStations): M[j,0]=float(lines[i]); i+=1; LL = lines[i:i+6] - M[j,1:37]=np.array((' '.join(lines[i:i+6])).split()).astype(np.float) + M[j,1:37]=np.array((' '.join(lines[i:i+6])).split()).astype(np.float_) i+=7 - M[j,37:]=np.array((' '.join(lines[i:i+6])).split()).astype(np.float) + M[j,37:]=np.array((' '.join(lines[i:i+6])).split()).astype(np.float_) i+=7 except: raise WrongFormatError('An error occured while reading section {}/{}'.format(j+1,nStations)) From 0be88d47e4bd1bf246392347e08cf52554606890 Mon Sep 17 00:00:00 2001 From: dzalkind Date: Mon, 23 Jan 2023 12:06:35 -0700 Subject: [PATCH 015/224] Add AWC parameters to registry, regenerate types --- ROSCO/rosco_registry/rosco_types.yaml | 21 +++++++++++++++++++++ ROSCO/src/ROSCO_Types.f90 | 11 +++++------ 2 files changed, 26 insertions(+), 6 deletions(-) diff --git a/ROSCO/rosco_registry/rosco_types.yaml b/ROSCO/rosco_registry/rosco_types.yaml index ea486fd1..ecf2656d 100644 --- a/ROSCO/rosco_registry/rosco_types.yaml +++ b/ROSCO/rosco_registry/rosco_types.yaml @@ -437,6 +437,27 @@ ControlParameters: PA_Damping: <<: *real description: Pitch actuator damping ratio [-, unused if PA_Mode = 1] + + # Active wake control + AWC_NumModes: + <<: *integer + description: AWC- Number of modes to include [-] + AWC_n: + <<: *integer + allocatable: True + description: AWC azimuthal mode [-] + AWC_omega: + <<: *real + allocatable: True + description: AWC frequency [rad/s] + AWC_amp: + <<: *real + allocatable: True + description: AWC amplitude [deg] + AWC_clockangle: + <<: *real + allocatable: True + description: AWC clocking angle [deg] # Pitch actuator error PF_Mode: diff --git a/ROSCO/src/ROSCO_Types.f90 b/ROSCO/src/ROSCO_Types.f90 index bd2afe2c..bf756a1e 100644 --- a/ROSCO/src/ROSCO_Types.f90 +++ b/ROSCO/src/ROSCO_Types.f90 @@ -113,6 +113,11 @@ MODULE ROSCO_Types INTEGER(IntKi) :: PA_Mode ! Pitch actuator mode {0 - not used, 1 - first order filter, 2 - second order filter} REAL(DbKi) :: PA_CornerFreq ! Pitch actuator bandwidth/cut-off frequency [rad/s] REAL(DbKi) :: PA_Damping ! Pitch actuator damping ratio [-, unused if PA_Mode = 1] + INTEGER(IntKi) :: AWC_NumModes ! AWC- Number of modes to include [-] + INTEGER(IntKi), DIMENSION(:), ALLOCATABLE :: AWC_n ! AWC azimuthal mode [-] + REAL(DbKi), DIMENSION(:), ALLOCATABLE :: AWC_omega ! AWC frequency [rad/s] + REAL(DbKi), DIMENSION(:), ALLOCATABLE :: AWC_amp ! AWC amplitude [deg] + REAL(DbKi), DIMENSION(:), ALLOCATABLE :: AWC_clockangle ! AWC clocking angle [deg] INTEGER(IntKi) :: PF_Mode ! Pitch actuator fault mode {0 - not used, 1 - offsets on one or more blades} REAL(DbKi), DIMENSION(:), ALLOCATABLE :: PF_Offsets ! Pitch actuator fault offsets for blade 1-3 [rad/s] INTEGER(IntKi) :: Ext_Mode ! External control mode (0 - not used, 1 - call external control library) @@ -125,12 +130,6 @@ MODULE ROSCO_Types REAL(DbKi) :: PC_RtTq99 ! 99% of the rated torque value, using for switching between pitch and torque control, [Nm]. REAL(DbKi) :: VS_MaxOMTq ! Maximum torque at the end of the below-rated region 2, [Nm] REAL(DbKi) :: VS_MinOMTq ! Minimum torque at the beginning of the below-rated region 2, [Nm] - REAL(DbKi) :: Test_Input ! Test Var Input - REAL(DbKi), DIMENSION(:), ALLOCATABLE :: AWC_omega ! AWC frequency [rad/s] - REAL(DbKi), DIMENSION(:), ALLOCATABLE :: AWC_amp ! AWC amplitude [deg] - REAL(DbKi), DIMENSION(:), ALLOCATABLE :: AWC_clockangle ! AWC clocking angle [deg] - INTEGER(IntKi), DIMENSION(:), ALLOCATABLE :: AWC_n ! AWC azimuthal mode [-] - INTEGER(IntKi) :: AWC_NumModes ! AWC: Number of modes to include [-] END TYPE ControlParameters TYPE, PUBLIC :: WE From 1e802638f3c6c1e8bd831cea97ac7409e4c9bc0e Mon Sep 17 00:00:00 2001 From: dzalkind Date: Mon, 23 Jan 2023 12:06:54 -0700 Subject: [PATCH 016/224] Apply DbKi to COMPLEX --- ROSCO/src/Controllers.f90 | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/ROSCO/src/Controllers.f90 b/ROSCO/src/Controllers.f90 index 9fca1844..f8fa62e2 100644 --- a/ROSCO/src/Controllers.f90 +++ b/ROSCO/src/Controllers.f90 @@ -47,8 +47,8 @@ SUBROUTINE PitchControl(avrSWAP, CntrPar, LocalVar, objInst, DebugVar, ErrVar) REAL(DbKi), PARAMETER :: phi2 = 2.0/3.0*PI ! Phase difference from first to second blade REAL(DbKi), PARAMETER :: phi3 = 4.0/3.0*PI ! Phase difference from first to third blade REAL(DbKi), DIMENSION(3) :: AWC_angle - DOUBLE COMPLEX, DIMENSION(3) :: AWC_complexangle - DOUBLE COMPLEX :: complexI = (0.0, 1.0) + COMPLEX(DbKi), DIMENSION(3) :: AWC_complexangle + COMPLEX(DbKi) :: complexI = (0.0, 1.0) INTEGER(IntKi) :: Imode ! Index used for looping through AWC modes REAL(DbKi) :: clockang ! Clock angle for AWC pitching From 0575d752702b51171d765b9af4e0d421e016d28d Mon Sep 17 00:00:00 2001 From: dzalkind Date: Mon, 23 Jan 2023 12:09:09 -0700 Subject: [PATCH 017/224] Re-organize AWC pitch contribution, before actuator --- ROSCO/src/Controllers.f90 | 9 +++++---- 1 file changed, 5 insertions(+), 4 deletions(-) diff --git a/ROSCO/src/Controllers.f90 b/ROSCO/src/Controllers.f90 index f8fa62e2..930dacf8 100644 --- a/ROSCO/src/Controllers.f90 +++ b/ROSCO/src/Controllers.f90 @@ -138,6 +138,7 @@ SUBROUTINE PitchControl(avrSWAP, CntrPar, LocalVar, objInst, DebugVar, ErrVar) ! Add the forcing contribution to AWC_complexangle DO K = 1,LocalVar%NumBl ! Loop through all blades AWC_complexangle(K) = AWC_complexangle(K) + CntrPar%AWC_amp(Imode) * EXP(complexI * (AWC_angle(K))) + LocalVar%PitCom(K) = LocalVar%PitCom(K) + REAL(AWC_complexangle(K)) END DO END DO @@ -173,10 +174,10 @@ SUBROUTINE PitchControl(avrSWAP, CntrPar, LocalVar, objInst, DebugVar, ErrVar) ! Command the pitch demanded from the last ! call to the controller (See Appendix A of Bladed User's Guide): ! AWC added here as well - avrSWAP(42) = LocalVar%PitCom(1) + REAL(AWC_complexangle(1)) ! Use the command angles of all blades if using individual pitch - avrSWAP(43) = LocalVar%PitCom(2) + REAL(AWC_complexangle(2)) ! " - avrSWAP(44) = LocalVar%PitCom(3) + REAL(AWC_complexangle(3)) ! " - avrSWAP(45) = LocalVar%PitCom(1) + REAL(AWC_complexangle(1)) ! Use the command angle of blade 1 if using collective pitch + avrSWAP(42) = LocalVar%PitComAct(1) ! Use the command angles of all blades if using individual pitch + avrSWAP(43) = LocalVar%PitComAct(2) ! " + avrSWAP(44) = LocalVar%PitComAct(3) ! " + avrSWAP(45) = LocalVar%PitComAct(1) ! Use the command angle of blade 1 if using collective pitch ! Add RoutineName to error message IF (ErrVar%aviFAIL < 0) THEN From 974e271c77f4dfb8b16f4165ba224f133bc5aae1 Mon Sep 17 00:00:00 2001 From: dzalkind Date: Mon, 23 Jan 2023 12:11:03 -0700 Subject: [PATCH 018/224] Separate contribution to PitCom from mode calculation --- ROSCO/src/Controllers.f90 | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/ROSCO/src/Controllers.f90 b/ROSCO/src/Controllers.f90 index 930dacf8..de352d53 100644 --- a/ROSCO/src/Controllers.f90 +++ b/ROSCO/src/Controllers.f90 @@ -142,6 +142,10 @@ SUBROUTINE PitchControl(avrSWAP, CntrPar, LocalVar, objInst, DebugVar, ErrVar) END DO END DO + DO K = 1,LocalVar%NumBl ! Loop through all blades, apply AWC_angle + LocalVar%PitCom(K) = LocalVar%PitCom(K) + REAL(AWC_complexangle(K)) + END DO + ! Place pitch actuator here, so it can be used with or without open-loop DO K = 1,LocalVar%NumBl ! Loop through all blades, add IPC contribution and limit pitch rate IF (CntrPar%PA_Mode > 0) THEN From 515da1797a46979d9e288215ff05f2c918f59809 Mon Sep 17 00:00:00 2001 From: dzalkind Date: Mon, 23 Jan 2023 13:44:08 -0700 Subject: [PATCH 019/224] Make AWC_complexangle a LocalVar for logging --- ROSCO/rosco_registry/rosco_types.yaml | 11 +++++++++++ ROSCO/rosco_registry/write_registry.py | 11 ++++++++++- ROSCO/src/Controllers.f90 | 10 +++++----- ROSCO/src/ROSCO_IO.f90 | 12 ++++++++++-- ROSCO/src/ROSCO_Types.f90 | 1 + 5 files changed, 37 insertions(+), 8 deletions(-) diff --git a/ROSCO/rosco_registry/rosco_types.yaml b/ROSCO/rosco_registry/rosco_types.yaml index ecf2656d..0e6f2b32 100644 --- a/ROSCO/rosco_registry/rosco_types.yaml +++ b/ROSCO/rosco_registry/rosco_types.yaml @@ -12,6 +12,13 @@ default_types: size: 0 # Use this if the type IS an array (size:3 --> REAL(8), BldPitch(3)) allocatable: False equals: + complex: &complex + type: complex + description: + dimension: # Use this if a higher-dimensional allocatable array (dimension:(:,:) --> REAL(8), DIMESION(:,:), ALLOCATABLE) + size: 0 # Use this if the type IS an array (size:3 --> REAL(8), BldPitch(3)) + allocatable: False + equals: float: &float type: float description: @@ -933,6 +940,10 @@ LocalVariables: restart: <<: *logical description: Restart flag + AWC_complexangle: + <<: *complex + description: Complex angle for each blade, sum of modes? + size: 3 WE: <<: *derived_type id: WE diff --git a/ROSCO/rosco_registry/write_registry.py b/ROSCO/rosco_registry/write_registry.py index 09c855b3..41f0bea5 100644 --- a/ROSCO/rosco_registry/write_registry.py +++ b/ROSCO/rosco_registry/write_registry.py @@ -237,7 +237,7 @@ def write_roscoio(yfile): # -- Always prints blade(1) for multi-bladed inputss (e.g. BldPitch(1)) lv_strings = [] for lv_idx, localvar in enumerate(reg['LocalVariables']): - if reg['LocalVariables'][localvar]['type'] in ['integer', 'real']: + if reg['LocalVariables'][localvar]['type'] in ['integer', 'real', 'complex']: lv_strings.append(localvar) file.write(' nLocalVars = {}\n'.format(len(lv_strings))) file.write(' Allocate(LocalVarOutData(nLocalVars))\n') @@ -353,6 +353,15 @@ def read_type(param): f90type += ', DIMENSION(:), ALLOCATABLE' elif param['dimension']: f90type += ', DIMENSION{}'.format(param['dimension']) + elif param['type'] == 'complex': + f90type = 'COMPLEX(DbKi)' + if param['allocatable']: + if param['dimension']: + f90type += ', DIMENSION{}, ALLOCATABLE'.format(param['dimension']) + else: + f90type += ', DIMENSION(:), ALLOCATABLE' + elif param['dimension']: + f90type += ', DIMENSION{}'.format(param['dimension']) elif param['type'] == 'float': f90type = 'REAL(ReKi)' if param['allocatable']: diff --git a/ROSCO/src/Controllers.f90 b/ROSCO/src/Controllers.f90 index de352d53..70c04200 100644 --- a/ROSCO/src/Controllers.f90 +++ b/ROSCO/src/Controllers.f90 @@ -129,21 +129,21 @@ SUBROUTINE PitchControl(avrSWAP, CntrPar, LocalVar, objInst, DebugVar, ErrVar) ENDIF ! Compute the AWC pitch settings - AWC_complexangle = 0.0D0 + LocalVar%AWC_complexangle = 0.0D0 DO Imode = 1,CntrPar%AWC_NumModes clockang = CntrPar%AWC_clockangle(Imode)*PI/180.0_DbKi AWC_angle(1) = CntrPar%AWC_omega(Imode) * LocalVar%Time - CntrPar%AWC_n(Imode) * (LocalVar%Azimuth + phi1 + clockang) AWC_angle(2) = CntrPar%AWC_omega(Imode) * LocalVar%Time - CntrPar%AWC_n(Imode) * (LocalVar%Azimuth + phi2 + clockang) AWC_angle(3) = CntrPar%AWC_omega(Imode) * LocalVar%Time - CntrPar%AWC_n(Imode) * (LocalVar%Azimuth + phi3 + clockang) - ! Add the forcing contribution to AWC_complexangle + ! Add the forcing contribution to LocalVar%AWC_complexangle DO K = 1,LocalVar%NumBl ! Loop through all blades - AWC_complexangle(K) = AWC_complexangle(K) + CntrPar%AWC_amp(Imode) * EXP(complexI * (AWC_angle(K))) - LocalVar%PitCom(K) = LocalVar%PitCom(K) + REAL(AWC_complexangle(K)) + LocalVar%AWC_complexangle(K) = LocalVar%AWC_complexangle(K) + CntrPar%AWC_amp(Imode) * EXP(complexI * (AWC_angle(K))) + LocalVar%PitCom(K) = LocalVar%PitCom(K) + REAL(LocalVar%AWC_complexangle(K)) END DO END DO DO K = 1,LocalVar%NumBl ! Loop through all blades, apply AWC_angle - LocalVar%PitCom(K) = LocalVar%PitCom(K) + REAL(AWC_complexangle(K)) + LocalVar%PitCom(K) = LocalVar%PitCom(K) + REAL(LocalVar%AWC_complexangle(K)) END DO ! Place pitch actuator here, so it can be used with or without open-loop diff --git a/ROSCO/src/ROSCO_IO.f90 b/ROSCO/src/ROSCO_IO.f90 index 6e97878d..3fd4bf7e 100644 --- a/ROSCO/src/ROSCO_IO.f90 +++ b/ROSCO/src/ROSCO_IO.f90 @@ -129,6 +129,9 @@ SUBROUTINE WriteRestartFile(LocalVar, CntrPar, ErrVar, objInst, RootName, size_a WRITE( Un, IOSTAT=ErrStat) LocalVar%ACC_INFILE_SIZE WRITE( Un, IOSTAT=ErrStat) LocalVar%ACC_INFILE WRITE( Un, IOSTAT=ErrStat) LocalVar%restart + WRITE( Un, IOSTAT=ErrStat) LocalVar%AWC_complexangle(1) + WRITE( Un, IOSTAT=ErrStat) LocalVar%AWC_complexangle(2) + WRITE( Un, IOSTAT=ErrStat) LocalVar%AWC_complexangle(3) WRITE( Un, IOSTAT=ErrStat) LocalVar%WE%om_r WRITE( Un, IOSTAT=ErrStat) LocalVar%WE%v_t WRITE( Un, IOSTAT=ErrStat) LocalVar%WE%v_m @@ -311,6 +314,9 @@ SUBROUTINE ReadRestartFile(avrSWAP, LocalVar, CntrPar, objInst, PerfData, RootNa ALLOCATE(LocalVar%ACC_INFILE(LocalVar%ACC_INFILE_SIZE)) READ( Un, IOSTAT=ErrStat) LocalVar%ACC_INFILE READ( Un, IOSTAT=ErrStat) LocalVar%restart + READ( Un, IOSTAT=ErrStat) LocalVar%AWC_complexangle(1) + READ( Un, IOSTAT=ErrStat) LocalVar%AWC_complexangle(2) + READ( Un, IOSTAT=ErrStat) LocalVar%AWC_complexangle(3) READ( Un, IOSTAT=ErrStat) LocalVar%WE%om_r READ( Un, IOSTAT=ErrStat) LocalVar%WE%v_t READ( Un, IOSTAT=ErrStat) LocalVar%WE%v_m @@ -438,7 +444,7 @@ SUBROUTINE Debug(LocalVar, CntrPar, DebugVar, ErrVar, avrSWAP, RootName, size_av '[rad/s]', '[rad/s]', '[m/s]', '[rad]', '[rad]', & '[N/A]', '[N/A]', '[N/A]', '[N/A]', '[rad/s]', & '[deg]', '[deg]', '[deg]', '[N/A]'] - nLocalVars = 69 + nLocalVars = 70 Allocate(LocalVarOutData(nLocalVars)) Allocate(LocalVarOutStrings(nLocalVars)) LocalVarOutData(1) = LocalVar%iStatus @@ -510,6 +516,7 @@ SUBROUTINE Debug(LocalVar, CntrPar, DebugVar, ErrVar, avrSWAP, RootName, size_av LocalVarOutData(67) = LocalVar%Flp_Angle(1) LocalVarOutData(68) = LocalVar%RootMyb_Last(1) LocalVarOutData(69) = LocalVar%ACC_INFILE_SIZE + LocalVarOutData(70) = LocalVar%AWC_complexangle(1) LocalVarOutStrings = [CHARACTER(15) :: 'iStatus', 'Time', 'DT', 'VS_GenPwr', 'GenSpeed', & 'RotSpeed', 'NacHeading', 'NacVane', 'HorWindV', 'rootMOOP', & 'rootMOOPF', 'BlPitch', 'Azimuth', 'NumBl', 'FA_Acc', & @@ -523,7 +530,8 @@ SUBROUTINE Debug(LocalVar, CntrPar, DebugVar, ErrVar, avrSWAP, RootName, size_av 'VS_LastGenTrq', 'VS_LastGenPwr', 'VS_MechGenPwr', 'VS_SpdErrAr', 'VS_SpdErrBr', & 'VS_SpdErr', 'VS_State', 'VS_Rgn3Pitch', 'WE_Vw', 'WE_Vw_F', & 'WE_VwI', 'WE_VwIdot', 'VS_LastGenTrqF', 'Fl_PitCom', 'NACIMU_FA_AccF', & - 'FA_AccF', 'Flp_Angle', 'RootMyb_Last', 'ACC_INFILE_SIZE'] + 'FA_AccF', 'Flp_Angle', 'RootMyb_Last', 'ACC_INFILE_SIZE', 'AWC_complexangle' & + ] ! Initialize debug file IF ((LocalVar%iStatus == 0) .OR. (LocalVar%iStatus == -9)) THEN ! .TRUE. if we're on the first call to the DLL IF (CntrPar%LoggingLevel > 0) THEN diff --git a/ROSCO/src/ROSCO_Types.f90 b/ROSCO/src/ROSCO_Types.f90 index bf756a1e..a2de4a42 100644 --- a/ROSCO/src/ROSCO_Types.f90 +++ b/ROSCO/src/ROSCO_Types.f90 @@ -265,6 +265,7 @@ MODULE ROSCO_Types INTEGER(IntKi) :: ACC_INFILE_SIZE ! Length of parameter input filename CHARACTER, DIMENSION(:), ALLOCATABLE :: ACC_INFILE ! Parameter input filename LOGICAL :: restart ! Restart flag + COMPLEX(DbKi) :: AWC_complexangle(3) ! Complex angle for each blade, sum of modes? TYPE(WE) :: WE ! Wind speed estimator parameters derived type TYPE(FilterParameters) :: FP ! Filter parameters derived type TYPE(piParams) :: piP ! PI parameters derived type From be28641f1c4f5b5350e86b125ce9324e7eacccc3 Mon Sep 17 00:00:00 2001 From: dzalkind <65573423+dzalkind@users.noreply.github.com> Date: Tue, 24 Jan 2023 17:41:42 -0700 Subject: [PATCH 020/224] Allow PA_Mode 1 (#213) --- ROSCO/src/ReadSetParameters.f90 | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ROSCO/src/ReadSetParameters.f90 b/ROSCO/src/ReadSetParameters.f90 index 0bfd59d2..9b00c1f2 100644 --- a/ROSCO/src/ReadSetParameters.f90 +++ b/ROSCO/src/ReadSetParameters.f90 @@ -993,7 +993,7 @@ SUBROUTINE CheckInputs(LocalVar, CntrPar, avrSWAP, ErrVar, size_avcMSG) ! --- Pitch Actuator --- IF (CntrPar%PA_Mode > 0) THEN - IF ((CntrPar%PA_Mode < 0) .OR. (CntrPar%PA_Mode < 2)) THEN + IF ((CntrPar%PA_Mode < 0) .OR. (CntrPar%PA_Mode > 2)) THEN ErrVar%aviFAIL = -1 ErrVar%ErrMsg = 'PA_Mode must be 0, 1, or 2' END IF From e554c1da08c28ebf956eb0986ee6e6bcd0dbb0e3 Mon Sep 17 00:00:00 2001 From: dzalkind <65573423+dzalkind@users.noreply.github.com> Date: Thu, 26 Jan 2023 13:10:06 -0700 Subject: [PATCH 021/224] IPC Saturation Fix [RAAW] (#210) * FOCAL Updates (#64) * Update headers * fix bullets * make uppercase * Update turbine.py (#56) * Update turbine.py This add several lines for fixing the problem of repeated maximum values in the performance tables. This will cause the error (' the length of x and y is different.') of 'interpolate.interp1d.' * Add comments and catch when there are multiple optimal pitch angles Co-authored-by: dzalkind * increment version * Update for OpenFAST v3.0.0 * Update for OpenFAST v3.0.0 * Install OF3.0.0 for tests * update for OF v3.0.0 * add publish to pypi on release * Update to ROSCO v2.3.0 * Update Testing (#58) * Update scripts to run on eagle * Update IEA-15MW semi example: use peak shaving w/ ps_percen=0.8 * Add comparison plots to testing scripts * Update submit script for testing * Update for latest eagle runs * Add future to install dependencies * add TMax to self, define tmin in print_results * run tests in CI * generic ROSCO path * default to overwrite * fix path * import platform * separate run_testing * cleanup, specify lite test * don't run testing in after examples, oops. Co-authored-by: nikhar-abbas <40865984+nikhar-abbas@users.noreply.github.com> Co-authored-by: Nikhar Abbas * increment version * Update for OpenFAST v3.0.0 * Install OF3.0.0 for tests * update for OF v3.0.0 * add publish to pypi on release * Update to ROSCO v2.3.0 * Increment Version, OF3.0 (#57) * increment version * Update for OpenFAST v3.0.0 * Install OF3.0.0 for tests * update for OF v3.0.0 * add publish to pypi on release * Update to ROSCO v2.3.0 * increment version * Update for OpenFAST v3.0.0 * Install OF3.0.0 for tests * update for OF v3.0.0 * add publish to pypi on release * Update to ROSCO v2.3.0 * add ROSCO without submodule * move ROSCO source to ROSCO folder * Move cmake-related files to ROSCO * Add back pesky ErrVar * Remove parameters_files * Merge ROSCO and _toolbox gitignore * Fix .gitignore * Remove Examples/DISCON.IN from git * Fix and point example_01 to Tune_Cases/ * Update verbiage around using ofTools vs. weis * Fix and point example_04 to Tune_Cases/ * Clean up example_06 * Clean up example_07 * Only check FlpCornerFreq if using Flp control, fixes example 05 * Make example_04 consistent with others * Let example_05 run independently from 04 * Clean up example_05, wind files * Add schema and update empty tuning yaml inputs, not connected yet * Integrate schema into turbine, controller, and examples * Only check Fl filter parameters if Fl_Mode > 0, fix example_05 * bump version to 2.3 * Compile ROSCO from ROSCO dir * Rename to CI_rosco * Add omega vs. windspeed functionality * Fix tests: 5MW U_pc and 06 example dir * Make _Toolbox vs_minspeed in rotor frame to match ROSCO * Revert ServoDyn change * change rotor speed constraint to be epsilon * rename for clarity * docs major refresh * fix FA_AccF units in debug file * docs that build locally * Deallocate arrays in ROSCO, check in example_05 * Clean up comments * remove gitmodules * furo theme * furo in requirements * move readthedocs config file, remove furo import in conf.py * add docs requirements file * typo * move index out of source folder * trying to get furo to work * import date * fix versions and titles, cleanup readthedocs requirements * typo fix, remove extras * more cleanup * bump version * no furo extension, "hack" to load RT version * proper toctree paths * specify method * add mock modules * fix typos * update python install requirements * running locally * move index to main docs dir again * update to build locally * error during warnings * automated version * cleanup * remove old docs * re-add docs * simplify * fix figure path * try alabaster * remove archived docs * Add omega vs. windspeed functionality * Fix tests: 5MW U_pc and 06 example dir * more detailed sp.optimize settings * run MBC3 in parallel * restructure driver, run initialization doe for tuning * Try new dlclose function * Update example_05 to run simple simulation twice and check result * Revert deallocation stuff * Close discon library after every sim run * Test examples on macOS and windows * Run examples instead of testing on other platforms * Skip examples in windows for now * update paths and yaml load funciton * Skip mac testing of examples * provide default U_pc for single omega/zeta case * allow for float or list-like pc tuning inputs * Change name in setup.py * WE_Vw unit fix * Pass through kp_float, if desired * Minor fixes: schema error and InputReader defaults * cleeanup for improved stability * check for doe_logs as string in load_DOE * major restructure for rsched_driver class * cleanup verbosity * run serial by default * load_parallel as linturb_option * specific IEA15MW yaml for multi omega * remove unused module imports * fix error message types * lin_file as input * add comments on inputs to LinearTurbineModel init method * remove relative file paths * provide OpenFAST linearizations for IEA15MW UMaineSemi * put plotting in specific function * fix WE_lambda units * add self in on a few necessary variables * creaete example 12 for robust scheduling * try a few mbc3 locations for import * allow list-like or numpy arrays for omega_pc and zeta_pc schedules * create and use recorder setup function * Pass Through Kp_float (#57) * Pass through kp_float, if desired * Minor fixes: schema error and InputReader defaults * fix setup_recorder to work for optimization driver too * Allow pass through of Kp_float = 0 * cleanup om problems, update om0 calc * doe levels as input * negative k_float to account for OF conventions * cleanup print statements * variable name cleanup, use calculated k_float * Add defaults to omega_,zeta_ pc and vs, allow to be numbers * use standard tuning k_float as IC * formatting update * update problem setup methods * cleanup add_dv, enable adding design variables after problem is setup * change optimization step size * more setup restructure * update verbosity * use sphinx-rtd-theme * master doc and sphinx rtd theme * index back to root folder * only ignore install folders * remove hidden toctree * furo theme * update paths * convert rt version to string * update sphinx settings * move conf * furo theme * Mostly a docs update (#61) * rename for clarity * docs major refresh * fix FA_AccF units in debug file * docs that build locally * remove gitmodules * furo theme * furo in requirements * move readthedocs config file, remove furo import in conf.py * add docs requirements file * typo * move index out of source folder * trying to get furo to work * import date * fix versions and titles, cleanup readthedocs requirements * typo fix, remove extras * more cleanup * bump version * no furo extension, "hack" to load RT version * proper toctree paths * specify method * add mock modules * fix typos * update python install requirements * running locally * move index to main docs dir again * update to build locally * error during warnings * automated version * cleanup * remove old docs * re-add docs * simplify * fix figure path * try alabaster * remove archived docs * use sphinx-rtd-theme * master doc and sphinx rtd theme * index back to root folder * only ignore install folders * remove hidden toctree * furo theme * update paths * convert rt version to string * update sphinx settings * move conf * furo theme * Pass through Kp_float = 0 (#59) * Pass through kp_float, if desired * Minor fixes: schema error and InputReader defaults * Allow pass through of Kp_float = 0 * Add flp parameters to schema * Change Fl_Mode default to 0 * Add defaults to omega_,zeta_ pc and vs, allow to be numbers * Allow single pitch tuning values in code, default U_pc to 0 * use nac acceleration for floating feedback * Fix TSR saturation for region 2.5operation * Modify system for constant power operation * Only modify pole for constant power above-rated * Remove GenEff from K calc * Update tuning, use constant power * use load_rosco_yaml * constant power * Fix broken tests * Include Fl_Mode=2 for nacelle pitching feedback * Add FOCAL inputs - hpf on floating feedback - lpf on wind speed estimator - associated schema updates * Set notch and check frequencies when Fl_Mode = 1 (fixes bug) * Skip filter step if there's an error * Update IEA-15MW test case DISCON with focal inputs * Allow Fl_Mode = 2 in ROSCO * Pass through lpf frequency * Add FOCAL tuning yaml * Set Cp contour number of levels * Add FOCAL params to various writers * Update/tune focal yaml * Add scripts for running FAST, tuning various parameters and cases * Add notebook for FAST plotting * Set up step case for testing * Change doubles to C_doubles * Define real and integer kinds, assign to all of ROSCO * Add ADJUSTL to DISCON error message * Fix Fl_Mode == 2 * Fix Fl_Mode == 2 again * Call yaw, flap, and debug only if enabled in DISOCN.IN * Make avrSWAP a ReKi and set constant kinds * Add DISCONs for testing - revert this later * Fix DISCON comparison, before DISCON's were overwritten by model * Rename DEBUG2.dbg to RootName.dbg2 * Update TestCase DISCONs to new input file * Add API change page in docs * Add link to API change on main page * Fix table headers * Fix title underlines * Fix tables again * Fix tables again * Fix version numbering in docs * Simplify FAST_directory in run_FAST * Versioning (#65) * use sphinx-rtd-theme * master doc and sphinx rtd theme * index back to root folder * only ignore install folders * remove hidden toctree * furo theme * update paths * convert rt version to string * update sphinx settings * move conf * furo theme * remove git versioning from cmake * use hard coded rosco_version * update intro write method * set nowrap for intel compilers * Add transfer of error message and clear message after each call * update install instructions * Catch nans in ROSCO at end of WSE * fix conda install typo * cleanup docs * Rename DEBUG2.dbg to RootName.dbg2 * Fix Fl_Mode == 2 * Fix Fl_Mode == 2 again * Allow Fl_Mode = 2 in ROSCO * Set notch and check frequencies when Fl_Mode = 1 (fixes bug) * Update FOCAL tuning yaml * Update TSR * Clean up and doc fix * Remove publish to pypi * Define all constant inputs to functions with kind typing * Generate Test_Case/ inputs automatically * Fix IEA15 DISCON path * Fix example 11 paths * Auto-generate tuning input yaml using schema * Add toolbox_input to doc index * Add toctree * Re-name title of toolbox_input Co-authored-by: Nikhar Abbas Co-authored-by: Xianping Du <38188001+Seager1989@users.noreply.github.com> Co-authored-by: nikhar-abbas <40865984+nikhar-abbas@users.noreply.github.com> * update listcheck method for numpy arrays * Open Loop Control (#98) * create rosco types yaml * Add more descriptions, add integer_c default, cleanup * updates for allocatability and shapes * python scripts to write ROSCO_types.f90 * reemove superfulous modules * use types from ROSCO registry * create rosco types yaml * Add more descriptions, add integer_c default, cleanup * updates for allocatability and shapes * python scripts to write ROSCO_types.f90 * reemove superfulous modules * use types from ROSCO registry * Saturate inputs to WSE. Needs some TLC, but seems to work * Reduce saturation limits on speed, torque * Re-organize, set saturation limits. Working at 3 m/s * Initial add of OL control to ROSCO: builds * Update DISCONs with open loop inputs * Fix file reading for OL_Filename * Add open loop control generation and file writing * Use DISCON_dict for more manageable DISCON file writing * Add open loop example, fix constant timeseries * Make open loop example generate power * Handle relative paths and calling from outside the run directory: - Some helper functions borrowed from OpenFAST, f/ext_control - Updated file writing * Clean up: versions, print statements * Fix SysFiles paths in CMakeLists * Tidy up Ext_DLL names * More Ext_DLL name tidying * Test write_registry.py * Update for OL Control * Move preprocessor lines * add zenodo DOI * Regenerated Types * fix shape * revert filepath change * give all types a size, ProcAddr size = 3 * update types * test registry in compile step * specify default shell * update write_registry path * remove default shell * Document API changes, provide OL input example * Fix example 14 (yaw input) * Add error catching to yaw control * Tidy up OL_Input Reading: error catching, generalize * More yaw control fixes, to model * Checkout develop CMakeLists for ROSCO * Update DISCON.INs for TestCases/ * Revert "Checkout develop CMakeLists for ROSCO" This reverts commit 87a491359d73806e3aaa59b4cfdc00f2838875df. * Revert windows cmake stuff to develop * Fix CMake again * Revert "Revert windows cmake stuff to develop" This reverts commit 39df122449b0e2055f2e12e3ce38a0c010c7bd91. * Make last cmake fix - hopefully Co-authored-by: Nikhar Abbas * Convert WE saved variables to WE type * Put restart flag in localvars * Use saved filter params from LocalVar * save pitcomt last * Move IPC saved variables to localvars * Saved pi controller variables to localvar * Save RootMyb_Last to localvar * ROSCO_IO - initial commit. Include restart and debug functions * Use ROSCO IO and call restart functions * Remove debug from function.f90 * Save ACC Infile info * update for restart capabilities * add rosco_io with restart and debug functions * cleanup debug call * use registry generate types and IO * delete DFController * fix timestep mismatch * remove unnecessaray istatus check * close files * add reg test for restart * add restart option to run_openfast * add testing to CI, ignore generate files * fix fastcall * remove extra commas * specify gfortran-10 * testing flag cleanup * Use lv_strings to generate debug output * Revert "testing flag cleanup" This reverts commit 6f295563832413e96347acd82716f9aadac6d46c. * Revert "specify gfortran-10" This reverts commit 4c3154491523bcd542133ca2bce5803cdc94523f. * minor cleanup * Use kind from constants * Add some comments for clarity * put debug in if statements * separate reg tests from oother tests * Fl_Mode>0 * Remove hard coded values * Add filtered signals and WE_Vw to debug varrs * cd for regtest * Check logging level before calling debug * add fl_pitcom and pc_minpit to debugvars * Turn runFAST into a class * Refactor/simplify CaseLibrary * Restart & registry (#99) * Convert WE saved variables to WE type * Put restart flag in localvars * Use saved filter params from LocalVar * save pitcomt last * Move IPC saved variables to localvars * Saved pi controller variables to localvar * Save RootMyb_Last to localvar * ROSCO_IO - initial commit. Include restart and debug functions * Use ROSCO IO and call restart functions * Remove debug from function.f90 * Save ACC Infile info * update for restart capabilities * add rosco_io with restart and debug functions * cleanup debug call * use registry generate types and IO * delete DFController * fix timestep mismatch * remove unnecessaray istatus check * close files * add reg test for restart * add restart option to run_openfast * add testing to CI, ignore generate files * fix fastcall * remove extra commas * specify gfortran-10 * testing flag cleanup * Use lv_strings to generate debug output * Revert "testing flag cleanup" This reverts commit 6f295563832413e96347acd82716f9aadac6d46c. * Revert "specify gfortran-10" This reverts commit 4c3154491523bcd542133ca2bce5803cdc94523f. * minor cleanup * Use kind from constants * Add some comments for clarity * put debug in if statements * separate reg tests from oother tests * Fl_Mode>0 * Remove hard coded values * Add filtered signals and WE_Vw to debug varrs * cd for regtest * Check logging level before calling debug * add fl_pitcom and pc_minpit to debugvars Co-authored-by: dzalkind * Implement initial pitch actuator * Set up steps case * Break up if statement in open loop pitch (#100) * Break up if statement in open loop pitch * Make torque and yaw consistent with pitch: can start after some time * add bld edgewise freq to robust dict_inputs * Add actuator variable * Print first time step in debug outs * Fix FOCAL yaml * Set actuator to 0.25 Hz bandwidth * Fix ccrotor inputs (#104) * remove interpolation of blade chord and twist * rename aerodynblade inputs * Update surface and DISCON.INs * Fix performance table paths * Allow default inputs (#110) * Allow defaults for AeroDyn inputs * Allow AeroDyn inputs to be floats, too * ipc (#105) * remove interpolation of blade chord and twist * rename aerodynblade inputs * Update surface and DISCON.INs * Fix performance table paths * Add proportional control and cleanup IPC * Add IPC and filtered RootMyc to registry * Better logic for filtering RootMOOP and fix notch filter slopes bug * Add cyclic flap conrol * Fix comments in ColemanTransformInverse * Addd IPC_KP to DISCON.IN * Error checking foro flp or ipc * add mutichannel plotting with tuples * add CMakeFiles to gitignore * Add IPC_KP to api changes * numerical qualifiers for error handling * add IPC gains to schema for pass-through ability * fix variable names * fix ipc gain printing bug * make sure IPC_KP is positive * Update Polars to point to coord files * ignore dbg2 files * Add IEA15MW_OL.yaml * update coord reader/writer * expand pitch_initial to 30 degrees * Add example 13 for IPC * Update cp surfaces and DISCONS * add examples to readme * cleanup and streaamline run_examples * Add IPC tuning vars * Allow IPC to command pitch value below peak shaving saturation limit * shorten simulation time * Fix Material parameter path * Update DISCONs again * Fix OL_Input reading * Set wind speed, rotor speed IC in example 14 * Debug OL reading * Add more debugging lines * Add more debugging lines 2 * Clean up, hone in on debug call * Disable logging level * Update discons - resolve conflict * Print when finished with ROSCO * add control packageg * Use PriPath and RootName to name dbg files * Print AvrSWAP * Revert "Use PriPath and RootName to name dbg files" This reverts commit 062fcaa55b3bf42d44f8a3f163aa883ab9552412. * Disable other examples * Print OL inputs * Allow logging level 3 * Print OL inputs * Make example shorter * Print more stuf * Print shape * Revert "Print OL inputs" This reverts commit 8e2a642bb35e46850f579ca4e69ca6d6fc93f4cc. * Update ROSCO Simulink model with IPC example * refactor flap tuning for normalization methods * improved flap controller filtering * delete extra F_FlpCornerFrerq * Update inputs, reader, and writer for OF 3.1.0 * Make sigma default interp type for multi_sigma * Use openfast 3.1.0 in CI * Fix leak...maybe * Use OF 3.1.0 in testing * Use gfotran for compile * Clean up print statements * Re-enable all examples * Update NREL-5MW AD file * Only check airfoil controls if more than one table * Update BAR models * Revert "Use gfotran for compile" This reverts commit 5a6e2b7e30287a09a09781e2ba12f9b578132e1f. * Install pyFAST for CI * Fix some paths in ex12 * Disable example 12 * Fix example 12 linear path, re-enable * Skip compilers install for mac * Try gfortran-9, no compilers * Try gfortran-10, no compilers * Skip windows compile in pytools * Re-enable windows, use gfortran as FC * Unset FC in windows * Set environment for windows when dependencies installed * Try setting environment in installation * Put conditional env setting in correct place * Try in setup again * Break up tasks: Windows vs. not * Update DISCONs * Update docs with new variables * Add example documentation * Update ROSCO Simulink model for 3.1.0 * Make IEA model float again * Reduce IEA timestep * Match DT to checkpoint time Co-authored-by: dzalkind * Increment version number * Bladed docs (#116) * Added image of Bladed control screen setup * Delete Bladed control screen.png * Adding image of Bladed control screen * Add files via upload * Minor edit 1 * Minor change 2 * Minor change 3 * Minor change 4 * Change 6 * Change 7 * Change 8 * Minor change 9 Co-authored-by: nikhar-abbas <40865984+nikhar-abbas@users.noreply.github.com> Co-authored-by: WillC-DNV <100850534+WillC-DNV@users.noreply.github.com> * Update version in API change docs * Bladed readthedocs (#117) * Added image of Bladed control screen setup * Delete Bladed control screen.png * Adding image of Bladed control screen * Add files via upload * Minor edit 1 * Minor change 2 * Minor change 3 * Minor change 4 * Change 6 * Change 7 * Change 8 * Minor change 9 * Tinker with characters in bladed instructions * Add bladed instructions to index * Change bladed toctree label * Do underline stuff * Make toctree label same as file * Remove colons from headers Co-authored-by: nikhar-abbas <40865984+nikhar-abbas@users.noreply.github.com> Co-authored-by: WillC-DNV <100850534+WillC-DNV@users.noreply.github.com> * Update docs to reflect CI process * Regenerate types, IO with registry * Update registry so first timestep is printed * Update inverted notch to move frequency properly * Saturate inv notch corner frequency at 0 * Add tower damper mode flag * Add Azimuth tracking controller in Simulink * Always enable GenDOF, add options for simp_step * Add sweep for IPC gains and FA damper * Fix NumCoords in FAST_writer * sigma + ipc (#125) * cleanup api change table * Update inverted notch to move frequency properly * Saturate inv notch corner frequency at 0 * add sigma function * Use IPC_Vramp for IPC cut-in * Add IPC_Vramp DISCON inputs * update registry * Update DISCONs * Update docs for API change * Fix IPC_Vramp data type * update comments Co-authored-by: dzalkind * Add turbulent case to runFAST/CaseLibrary * Add peak shaving sweep function * Increase default IPC_IntSat, make input parameter in future * Flip Ct and Cq table allocation * Flip Ct and Cq table allocation (#130) * Regen types * Remove print statements used for debugging * Update input files: IEA model has pitch actuator * Add back flap control (no idea when it was deleted) * Update discons, docs with API change * Add user-defined hh case * Fix AddF0 and RayleighDamp in FAST_reader * Pitch Actuator and IPC updates (#123) * Convert WE saved variables to WE type * Put restart flag in localvars * Use saved filter params from LocalVar * save pitcomt last * Move IPC saved variables to localvars * Saved pi controller variables to localvar * Save RootMyb_Last to localvar * ROSCO_IO - initial commit. Include restart and debug functions * Use ROSCO IO and call restart functions * Remove debug from function.f90 * Save ACC Infile info * update for restart capabilities * add rosco_io with restart and debug functions * cleanup debug call * use registry generate types and IO * delete DFController * fix timestep mismatch * remove unnecessaray istatus check * close files * add reg test for restart * add restart option to run_openfast * add testing to CI, ignore generate files * fix fastcall * remove extra commas * specify gfortran-10 * testing flag cleanup * Use lv_strings to generate debug output * Revert "testing flag cleanup" This reverts commit 6f295563832413e96347acd82716f9aadac6d46c. * Revert "specify gfortran-10" This reverts commit 4c3154491523bcd542133ca2bce5803cdc94523f. * minor cleanup * Use kind from constants * Add some comments for clarity * put debug in if statements * separate reg tests from oother tests * Fl_Mode>0 * Remove hard coded values * Add filtered signals and WE_Vw to debug varrs * cd for regtest * Check logging level before calling debug * add fl_pitcom and pc_minpit to debugvars * Turn runFAST into a class * Refactor/simplify CaseLibrary * Implement initial pitch actuator * Set up steps case * Add actuator variable * Print first time step in debug outs * Fix FOCAL yaml * Set actuator to 0.25 Hz bandwidth * ROSCO 2.5.0 (#115) * FOCAL Updates (#64) * Update headers * fix bullets * make uppercase * Update turbine.py (#56) * Update turbine.py This add several lines for fixing the problem of repeated maximum values in the performance tables. This will cause the error (' the length of x and y is different.') of 'interpolate.interp1d.' * Add comments and catch when there are multiple optimal pitch angles Co-authored-by: dzalkind * increment version * Update for OpenFAST v3.0.0 * Update for OpenFAST v3.0.0 * Install OF3.0.0 for tests * update for OF v3.0.0 * add publish to pypi on release * Update to ROSCO v2.3.0 * Update Testing (#58) * Update scripts to run on eagle * Update IEA-15MW semi example: use peak shaving w/ ps_percen=0.8 * Add comparison plots to testing scripts * Update submit script for testing * Update for latest eagle runs * Add future to install dependencies * add TMax to self, define tmin in print_results * run tests in CI * generic ROSCO path * default to overwrite * fix path * import platform * separate run_testing * cleanup, specify lite test * don't run testing in after examples, oops. Co-authored-by: nikhar-abbas <40865984+nikhar-abbas@users.noreply.github.com> Co-authored-by: Nikhar Abbas * increment version * Update for OpenFAST v3.0.0 * Install OF3.0.0 for tests * update for OF v3.0.0 * add publish to pypi on release * Update to ROSCO v2.3.0 * Increment Version, OF3.0 (#57) * increment version * Update for OpenFAST v3.0.0 * Install OF3.0.0 for tests * update for OF v3.0.0 * add publish to pypi on release * Update to ROSCO v2.3.0 * increment version * Update for OpenFAST v3.0.0 * Install OF3.0.0 for tests * update for OF v3.0.0 * add publish to pypi on release * Update to ROSCO v2.3.0 * add ROSCO without submodule * move ROSCO source to ROSCO folder * Move cmake-related files to ROSCO * Add back pesky ErrVar * Remove parameters_files * Merge ROSCO and _toolbox gitignore * Fix .gitignore * Remove Examples/DISCON.IN from git * Fix and point example_01 to Tune_Cases/ * Update verbiage around using ofTools vs. weis * Fix and point example_04 to Tune_Cases/ * Clean up example_06 * Clean up example_07 * Only check FlpCornerFreq if using Flp control, fixes example 05 * Make example_04 consistent with others * Let example_05 run independently from 04 * Clean up example_05, wind files * Add schema and update empty tuning yaml inputs, not connected yet * Integrate schema into turbine, controller, and examples * Only check Fl filter parameters if Fl_Mode > 0, fix example_05 * bump version to 2.3 * Compile ROSCO from ROSCO dir * Rename to CI_rosco * Add omega vs. windspeed functionality * Fix tests: 5MW U_pc and 06 example dir * Make _Toolbox vs_minspeed in rotor frame to match ROSCO * Revert ServoDyn change * change rotor speed constraint to be epsilon * rename for clarity * docs major refresh * fix FA_AccF units in debug file * docs that build locally * Deallocate arrays in ROSCO, check in example_05 * Clean up comments * remove gitmodules * furo theme * furo in requirements * move readthedocs config file, remove furo import in conf.py * add docs requirements file * typo * move index out of source folder * trying to get furo to work * import date * fix versions and titles, cleanup readthedocs requirements * typo fix, remove extras * more cleanup * bump version * no furo extension, "hack" to load RT version * proper toctree paths * specify method * add mock modules * fix typos * update python install requirements * running locally * move index to main docs dir again * update to build locally * error during warnings * automated version * cleanup * remove old docs * re-add docs * simplify * fix figure path * try alabaster * remove archived docs * Add omega vs. windspeed functionality * Fix tests: 5MW U_pc and 06 example dir * more detailed sp.optimize settings * run MBC3 in parallel * restructure driver, run initialization doe for tuning * Try new dlclose function * Update example_05 to run simple simulation twice and check result * Revert deallocation stuff * Close discon library after every sim run * Test examples on macOS and windows * Run examples instead of testing on other platforms * Skip examples in windows for now * update paths and yaml load funciton * Skip mac testing of examples * provide default U_pc for single omega/zeta case * allow for float or list-like pc tuning inputs * Change name in setup.py * WE_Vw unit fix * Pass through kp_float, if desired * Minor fixes: schema error and InputReader defaults * cleeanup for improved stability * check for doe_logs as string in load_DOE * major restructure for rsched_driver class * cleanup verbosity * run serial by default * load_parallel as linturb_option * specific IEA15MW yaml for multi omega * remove unused module imports * fix error message types * lin_file as input * add comments on inputs to LinearTurbineModel init method * remove relative file paths * provide OpenFAST linearizations for IEA15MW UMaineSemi * put plotting in specific function * fix WE_lambda units * add self in on a few necessary variables * creaete example 12 for robust scheduling * try a few mbc3 locations for import * allow list-like or numpy arrays for omega_pc and zeta_pc schedules * create and use recorder setup function * Pass Through Kp_float (#57) * Pass through kp_float, if desired * Minor fixes: schema error and InputReader defaults * fix setup_recorder to work for optimization driver too * Allow pass through of Kp_float = 0 * cleanup om problems, update om0 calc * doe levels as input * negative k_float to account for OF conventions * cleanup print statements * variable name cleanup, use calculated k_float * Add defaults to omega_,zeta_ pc and vs, allow to be numbers * use standard tuning k_float as IC * formatting update * update problem setup methods * cleanup add_dv, enable adding design variables after problem is setup * change optimization step size * more setup restructure * update verbosity * use sphinx-rtd-theme * master doc and sphinx rtd theme * index back to root folder * only ignore install folders * remove hidden toctree * furo theme * update paths * convert rt version to string * update sphinx settings * move conf * furo theme * Mostly a docs update (#61) * rename for clarity * docs major refresh * fix FA_AccF units in debug file * docs that build locally * remove gitmodules * furo theme * furo in requirements * move readthedocs config file, remove furo import in conf.py * add docs requirements file * typo * move index out of source folder * trying to get furo to work * import date * fix versions and titles, cleanup readthedocs requirements * typo fix, remove extras * more cleanup * bump version * no furo extension, "hack" to load RT version * proper toctree paths * specify method * add mock modules * fix typos * update python install requirements * running locally * move index to main docs dir again * update to build locally * error during warnings * automated version * cleanup * remove old docs * re-add docs * simplify * fix figure path * try alabaster * remove archived docs * use sphinx-rtd-theme * master doc and sphinx rtd theme * index back to root folder * only ignore install folders * remove hidden toctree * furo theme * update paths * convert rt version to string * update sphinx settings * move conf * furo theme * Pass through Kp_float = 0 (#59) * Pass through kp_float, if desired * Minor fixes: schema error and InputReader defaults * Allow pass through of Kp_float = 0 * Add flp parameters to schema * Change Fl_Mode default to 0 * Add defaults to omega_,zeta_ pc and vs, allow to be numbers * Allow single pitch tuning values in code, default U_pc to 0 * use nac acceleration for floating feedback * Fix TSR saturation for region 2.5operation * Modify system for constant power operation * Only modify pole for constant power above-rated * Remove GenEff from K calc * Update tuning, use constant power * use load_rosco_yaml * constant power * Fix broken tests * Include Fl_Mode=2 for nacelle pitching feedback * Add FOCAL inputs - hpf on floating feedback - lpf on wind speed estimator - associated schema updates * Set notch and check frequencies when Fl_Mode = 1 (fixes bug) * Skip filter step if there's an error * Update IEA-15MW test case DISCON with focal inputs * Allow Fl_Mode = 2 in ROSCO * Pass through lpf frequency * Add FOCAL tuning yaml * Set Cp contour number of levels * Add FOCAL params to various writers * Update/tune focal yaml * Add scripts for running FAST, tuning various parameters and cases * Add notebook for FAST plotting * Set up step case for testing * Change doubles to C_doubles * Define real and integer kinds, assign to all of ROSCO * Add ADJUSTL to DISCON error message * Fix Fl_Mode == 2 * Fix Fl_Mode == 2 again * Call yaw, flap, and debug only if enabled in DISOCN.IN * Make avrSWAP a ReKi and set constant kinds * Add DISCONs for testing - revert this later * Fix DISCON comparison, before DISCON's were overwritten by model * Rename DEBUG2.dbg to RootName.dbg2 * Update TestCase DISCONs to new input file * Add API change page in docs * Add link to API change on main page * Fix table headers * Fix title underlines * Fix tables again * Fix tables again * Fix version numbering in docs * Simplify FAST_directory in run_FAST * Versioning (#65) * use sphinx-rtd-theme * master doc and sphinx rtd theme * index back to root folder * only ignore install folders * remove hidden toctree * furo theme * update paths * convert rt version to string * update sphinx settings * move conf * furo theme * remove git versioning from cmake * use hard coded rosco_version * update intro write method * set nowrap for intel compilers * Add transfer of error message and clear message after each call * update install instructions * Catch nans in ROSCO at end of WSE * fix conda install typo * cleanup docs * Rename DEBUG2.dbg to RootName.dbg2 * Fix Fl_Mode == 2 * Fix Fl_Mode == 2 again * Allow Fl_Mode = 2 in ROSCO * Set notch and check frequencies when Fl_Mode = 1 (fixes bug) * Update FOCAL tuning yaml * Update TSR * Clean up and doc fix * Remove publish to pypi * Define all constant inputs to functions with kind typing * Generate Test_Case/ inputs automatically * Fix IEA15 DISCON path * Fix example 11 paths * Auto-generate tuning input yaml using schema * Add toolbox_input to doc index * Add toctree * Re-name title of toolbox_input Co-authored-by: Nikhar Abbas Co-authored-by: Xianping Du <38188001+Seager1989@users.noreply.github.com> Co-authored-by: nikhar-abbas <40865984+nikhar-abbas@users.noreply.github.com> * update listcheck method for numpy arrays * Open Loop Control (#98) * create rosco types yaml * Add more descriptions, add integer_c default, cleanup * updates for allocatability and shapes * python scripts to write ROSCO_types.f90 * reemove superfulous modules * use types from ROSCO registry * create rosco types yaml * Add more descriptions, add integer_c default, cleanup * updates for allocatability and shapes * python scripts to write ROSCO_types.f90 * reemove superfulous modules * use types from ROSCO registry * Saturate inputs to WSE. Needs some TLC, but seems to work * Reduce saturation limits on speed, torque * Re-organize, set saturation limits. Working at 3 m/s * Initial add of OL control to ROSCO: builds * Update DISCONs with open loop inputs * Fix file reading for OL_Filename * Add open loop control generation and file writing * Use DISCON_dict for more manageable DISCON file writing * Add open loop example, fix constant timeseries * Make open loop example generate power * Handle relative paths and calling from outside the run directory: - Some helper functions borrowed from OpenFAST, f/ext_control - Updated file writing * Clean up: versions, print statements * Fix SysFiles paths in CMakeLists * Tidy up Ext_DLL names * More Ext_DLL name tidying * Test write_registry.py * Update for OL Control * Move preprocessor lines * add zenodo DOI * Regenerated Types * fix shape * revert filepath change * give all types a size, ProcAddr size = 3 * update types * test registry in compile step * specify default shell * update write_registry path * remove default shell * Document API changes, provide OL input example * Fix example 14 (yaw input) * Add error catching to yaw control * Tidy up OL_Input Reading: error catching, generalize * More yaw control fixes, to model * Checkout develop CMakeLists for ROSCO * Update DISCON.INs for TestCases/ * Revert "Checkout develop CMakeLists for ROSCO" This reverts commit 87a491359d73806e3aaa59b4cfdc00f2838875df. * Revert windows cmake stuff to develop * Fix CMake again * Revert "Revert windows cmake stuff to develop" This reverts commit 39df122449b0e2055f2e12e3ce38a0c010c7bd91. * Make last cmake fix - hopefully Co-authored-by: Nikhar Abbas * Restart & registry (#99) * Convert WE saved variables to WE type * Put restart flag in localvars * Use saved filter params from LocalVar * save pitcomt last * Move IPC saved variables to localvars * Saved pi controller variables to localvar * Save RootMyb_Last to localvar * ROSCO_IO - initial commit. Include restart and debug functions * Use ROSCO IO and call restart functions * Remove debug from function.f90 * Save ACC Infile info * update for restart capabilities * add rosco_io with restart and debug functions * cleanup debug call * use registry generate types and IO * delete DFController * fix timestep mismatch * remove unnecessaray istatus check * close files * add reg test for restart * add restart option to run_openfast * add testing to CI, ignore generate files * fix fastcall * remove extra commas * specify gfortran-10 * testing flag cleanup * Use lv_strings to generate debug output * Revert "testing flag cleanup" This reverts commit 6f295563832413e96347acd82716f9aadac6d46c. * Revert "specify gfortran-10" This reverts commit 4c3154491523bcd542133ca2bce5803cdc94523f. * minor cleanup * Use kind from constants * Add some comments for clarity * put debug in if statements * separate reg tests from oother tests * Fl_Mode>0 * Remove hard coded values * Add filtered signals and WE_Vw to debug varrs * cd for regtest * Check logging level before calling debug * add fl_pitcom and pc_minpit to debugvars Co-authored-by: dzalkind * Break up if statement in open loop pitch (#100) * Break up if statement in open loop pitch * Make torque and yaw consistent with pitch: can start after some time * add bld edgewise freq to robust dict_inputs * Fix ccrotor inputs (#104) * remove interpolation of blade chord and twist * rename aerodynblade inputs * Update surface and DISCON.INs * Fix performance table paths * Allow default inputs (#110) * Allow defaults for AeroDyn inputs * Allow AeroDyn inputs to be floats, too * ipc (#105) * remove interpolation of blade chord and twist * rename aerodynblade inputs * Update surface and DISCON.INs * Fix performance table paths * Add proportional control and cleanup IPC * Add IPC and filtered RootMyc to registry * Better logic for filtering RootMOOP and fix notch filter slopes bug * Add cyclic flap conrol * Fix comments in ColemanTransformInverse * Addd IPC_KP to DISCON.IN * Error checking foro flp or ipc * add mutichannel plotting with tuples * add CMakeFiles to gitignore * Add IPC_KP to api changes * numerical qualifiers for error handling * add IPC gains to schema for pass-through ability * fix variable names * fix ipc gain printing bug * make sure IPC_KP is positive * Update Polars to point to coord files * ignore dbg2 files * Add IEA15MW_OL.yaml * update coord reader/writer * expand pitch_initial to 30 degrees * Add example 13 for IPC * Update cp surfaces and DISCONS * add examples to readme * cleanup and streaamline run_examples * Add IPC tuning vars * Allow IPC to command pitch value below peak shaving saturation limit * shorten simulation time * Fix Material parameter path * Update DISCONs again * Fix OL_Input reading * Set wind speed, rotor speed IC in example 14 * Debug OL reading * Add more debugging lines * Add more debugging lines 2 * Clean up, hone in on debug call * Disable logging level * Update discons - resolve conflict * Print when finished with ROSCO * add control packageg * Use PriPath and RootName to name dbg files * Print AvrSWAP * Revert "Use PriPath and RootName to name dbg files" This reverts commit 062fcaa55b3bf42d44f8a3f163aa883ab9552412. * Disable other examples * Print OL inputs * Allow logging level 3 * Print OL inputs * Make example shorter * Print more stuf * Print shape * Revert "Print OL inputs" This reverts commit 8e2a642bb35e46850f579ca4e69ca6d6fc93f4cc. * Update ROSCO Simulink model with IPC example * refactor flap tuning for normalization methods * improved flap controller filtering * delete extra F_FlpCornerFrerq * Update inputs, reader, and writer for OF 3.1.0 * Make sigma default interp type for multi_sigma * Use openfast 3.1.0 in CI * Fix leak...maybe * Use OF 3.1.0 in testing * Use gfotran for compile * Clean up print statements * Re-enable all examples * Update NREL-5MW AD file * Only check airfoil controls if more than one table * Update BAR models * Revert "Use gfotran for compile" This reverts commit 5a6e2b7e30287a09a09781e2ba12f9b578132e1f. * Install pyFAST for CI * Fix some paths in ex12 * Disable example 12 * Fix example 12 linear path, re-enable * Skip compilers install for mac * Try gfortran-9, no compilers * Try gfortran-10, no compilers * Skip windows compile in pytools * Re-enable windows, use gfortran as FC * Unset FC in windows * Set environment for windows when dependencies installed * Try setting environment in installation * Put conditional env setting in correct place * Try in setup again * Break up tasks: Windows vs. not * Update DISCONs * Update docs with new variables * Add example documentation * Update ROSCO Simulink model for 3.1.0 * Make IEA model float again * Reduce IEA timestep * Match DT to checkpoint time Co-authored-by: dzalkind * Increment version number * Bladed docs (#116) * Added image of Bladed control screen setup * Delete Bladed control screen.png * Adding image of Bladed control screen * Add files via upload * Minor edit 1 * Minor change 2 * Minor change 3 * Minor change 4 * Change 6 * Change 7 * Change 8 * Minor change 9 Co-authored-by: nikhar-abbas <40865984+nikhar-abbas@users.noreply.github.com> Co-authored-by: WillC-DNV <100850534+WillC-DNV@users.noreply.github.com> * Update version in API change docs * Bladed readthedocs (#117) * Added image of Bladed control screen setup * Delete Bladed control screen.png * Adding image of Bladed control screen * Add files via upload * Minor edit 1 * Minor change 2 * Minor change 3 * Minor change 4 * Change 6 * Change 7 * Change 8 * Minor change 9 * Tinker with characters in bladed instructions * Add bladed instructions to index * Change bladed toctree label * Do underline stuff * Make toctree label same as file * Remove colons from headers Co-authored-by: nikhar-abbas <40865984+nikhar-abbas@users.noreply.github.com> Co-authored-by: WillC-DNV <100850534+WillC-DNV@users.noreply.github.com> * Update docs to reflect CI process Co-authored-by: Nikhar Abbas Co-authored-by: Xianping Du <38188001+Seager1989@users.noreply.github.com> Co-authored-by: nikhar-abbas <40865984+nikhar-abbas@users.noreply.github.com> Co-authored-by: WillC-DNV <100850534+WillC-DNV@users.noreply.github.com> * Fixed wrong formatting of list items (#122) extra newline required between list elements * Regenerate types, IO with registry * Update registry so first timestep is printed * Update inverted notch to move frequency properly * Saturate inv notch corner frequency at 0 * Add tower damper mode flag * Flip Ct and Cq table allocation * Regen types * Remove print statements used for debugging * Update input files: IEA model has pitch actuator * Add back flap control (no idea when it was deleted) * Update discons, docs with API change Co-authored-by: nikhar-abbas <40865984+nikhar-abbas@users.noreply.github.com> Co-authored-by: Nikhar Abbas Co-authored-by: Xianping Du <38188001+Seager1989@users.noreply.github.com> Co-authored-by: WillC-DNV <100850534+WillC-DNV@users.noreply.github.com> Co-authored-by: Gustavo Hylander <74593034+ghylander@users.noreply.github.com> * Add max_torque_factor for constant power control, flexible upper limit * Make update discons relative to tuning yaml * Update AddF0 and NumCoords in FAST_reader/writer * Remove matlab/rotor position control stuff * Add OpenFAST channels that Simulink reads (#135) * Add collective blade pitch signal for WSE, shutdown * Clean up merge: two sigma functions, finish adding collective BP * Use IPC always in IEA-15MW case * Add IPC_SatMode input * Force IPC_SatMode to be an int in writer * Fix IPC_SatMode cherry pick * Fix IPC_SatMode/IntSat description, update DISCONs * Add new IPC_SatModes * Rate limit blade pitch on first time step * Update discons, registry * Move BlPitchC -> BlPitchCMeas(ured) * Update registry description * Remove old update_discons --- ROSCO/rosco_registry/rosco_types.yaml | 9 ++ ROSCO/src/ControllerBlocks.f90 | 8 +- ROSCO/src/Controllers.f90 | 37 +++-- ROSCO/src/Functions.f90 | 12 +- ROSCO/src/ROSCO_IO.f90 | 147 +++++++++--------- ROSCO/src/ROSCO_Types.f90 | 3 + ROSCO/src/ReadSetParameters.f90 | 10 +- ROSCO_toolbox/inputs/toolbox_schema.yaml | 3 + ROSCO_toolbox/utilities.py | 4 +- Test_Cases/BAR_10/BAR_10_DISCON.IN | 7 +- .../DISCON-UMaineSemi.IN | 7 +- .../IEA-15-240-RWT-UMaineSemi_ServoDyn.dat | 2 +- Test_Cases/NREL-5MW/DISCON.IN | 7 +- 13 files changed, 157 insertions(+), 99 deletions(-) diff --git a/ROSCO/rosco_registry/rosco_types.yaml b/ROSCO/rosco_registry/rosco_types.yaml index ea486fd1..81ad0953 100644 --- a/ROSCO/rosco_registry/rosco_types.yaml +++ b/ROSCO/rosco_registry/rosco_types.yaml @@ -136,6 +136,9 @@ ControlParameters: IPC_IntSat: <<: *real description: Integrator saturation (maximum signal amplitude contrbution to pitch from IPC) + IPC_SatMode: + <<: *integer + description: IPC Saturation method IPC Saturation method (0 - no saturation (except by PC_MinPit), 1 - saturate by PS_BldPitchMin, 2 - saturate sotfly (full IPC cycle) by PC_MinPit, 3 - saturate softly by PS_BldPitchMin) IPC_KP: <<: *real description: Integral gain for the individual pitch controller, [-]. @@ -723,6 +726,9 @@ LocalVariables: <<: *real description: Blade pitch [rad] size: 3 + BlPitchCMeas: + <<: *real + description: Mean (collective) blade pitch [rad] Azimuth: <<: *real description: Rotor aziumuth angle [rad] @@ -824,6 +830,9 @@ LocalVariables: <<: *real description: Proportional gain for IPC, after ramp [-] size: 2 + IPC_IntSat: + <<: *real + description: Integrator saturation (maximum signal amplitude contrbution to pitch from IPC) PC_State: <<: *integer description: State of the pitch control system diff --git a/ROSCO/src/ControllerBlocks.f90 b/ROSCO/src/ControllerBlocks.f90 index a62c5366..3e453052 100644 --- a/ROSCO/src/ControllerBlocks.f90 +++ b/ROSCO/src/ControllerBlocks.f90 @@ -206,10 +206,10 @@ SUBROUTINE WindSpeedEstimator(LocalVar, CntrPar, objInst, PerfData, DebugVar, Er WE_Inp_Speed = LocalVar%RotSpeedF END IF - IF (LocalVar%BlPitch(1) < CntrPar%PC_MinPit) THEN + IF (LocalVar%BlPitchCMeas < CntrPar%PC_MinPit) THEN WE_Inp_Pitch = CntrPar%PC_MinPit ELSE - WE_Inp_Pitch = LocalVar%BlPitch(1) + WE_Inp_Pitch = LocalVar%BlPitchCMeas END IF IF (LocalVar%VS_LastGenTrqF < 0.0001 * CntrPar%VS_RtTq) THEN @@ -228,7 +228,7 @@ SUBROUTINE WindSpeedEstimator(LocalVar, CntrPar, objInst, PerfData, DebugVar, Er ! Inversion and Invariance Filter implementation IF (CntrPar%WE_Mode == 1) THEN ! Compute AeroDynTorque - Tau_r = AeroDynTorque(LocalVar%RotSpeedF, LocalVar%BlPitch(1), LocalVar, CntrPar, PerfData, ErrVar) + Tau_r = AeroDynTorque(LocalVar%RotSpeedF, LocalVar%BlPitchCMeas, LocalVar, CntrPar, PerfData, ErrVar) LocalVar%WE_VwIdot = CntrPar%WE_Gamma/CntrPar%WE_Jtot*(LocalVar%VS_LastGenTrq*CntrPar%WE_GearboxRatio - Tau_r) LocalVar%WE_VwI = LocalVar%WE_VwI + LocalVar%WE_VwIdot*LocalVar%DT @@ -413,7 +413,7 @@ REAL(DbKi) FUNCTION Shutdown(LocalVar, CntrPar, objInst) ! Pitch Blades to 90 degrees at max pitch rate if in shutdown mode IF (LocalVar%SD) THEN - Shutdown = LocalVar%BlPitch(1) + CntrPar%PC_MaxRat*LocalVar%DT + Shutdown = LocalVar%BlPitchCMeas + CntrPar%PC_MaxRat*LocalVar%DT IF (MODULO(LocalVar%Time, 10.0_DbKi) == 0) THEN print *, ' ** SHUTDOWN MODE **' ENDIF diff --git a/ROSCO/src/Controllers.f90 b/ROSCO/src/Controllers.f90 index 29eda914..fd7a15f4 100644 --- a/ROSCO/src/Controllers.f90 +++ b/ROSCO/src/Controllers.f90 @@ -96,7 +96,7 @@ SUBROUTINE PitchControl(avrSWAP, CntrPar, LocalVar, objInst, DebugVar, ErrVar) ! Saturate collective pitch commands: LocalVar%PC_PitComT = saturate(LocalVar%PC_PitComT, LocalVar%PC_MinPit, CntrPar%PC_MaxPit) ! Saturate the overall command using the pitch angle limits - LocalVar%PC_PitComT = ratelimit(LocalVar%PC_PitComT, CntrPar%PC_MinRat, CntrPar%PC_MaxRat, LocalVar%DT, LocalVar%restart, LocalVar%rlP,objInst%instRL) ! Saturate the overall command of blade K using the pitch rate limit + LocalVar%PC_PitComT = ratelimit(LocalVar%PC_PitComT, CntrPar%PC_MinRat, CntrPar%PC_MaxRat, LocalVar%DT, LocalVar%restart, LocalVar%rlP,objInst%instRL,LocalVar%BlPitchCMeas) ! Saturate the overall command of blade K using the pitch rate limit LocalVar%PC_PitComT_Last = LocalVar%PC_PitComT ! Combine and saturate all individual pitch commands in software @@ -104,9 +104,15 @@ SUBROUTINE PitchControl(avrSWAP, CntrPar, LocalVar, objInst, DebugVar, ErrVar) LocalVar%PitCom(K) = LocalVar%PC_PitComT + LocalVar%FA_PitCom(K) LocalVar%PitCom(K) = saturate(LocalVar%PitCom(K), LocalVar%PC_MinPit, CntrPar%PC_MaxPit) ! Saturate the command using the pitch satauration limits LocalVar%PitCom(K) = LocalVar%PitCom(K) + LocalVar%IPC_PitComF(K) ! Add IPC - LocalVar%PitCom(K) = saturate(LocalVar%PitCom(K), LocalVar%PC_MinPit, CntrPar%PC_MaxPit) ! Saturate the command using the absolute pitch angle limits - LocalVar%PitCom(K) = ratelimit(LocalVar%PitCom(K), CntrPar%PC_MinRat, CntrPar%PC_MaxRat, LocalVar%DT, LocalVar%restart, LocalVar%rlP,objInst%instRL) ! Saturate the overall command of blade K using the pitch rate limit - END DO + + ! Hard IPC saturation by peak shaving limit + IF (CntrPar%IPC_SatMode == 1) THEN + LocalVar%PitCom(K) = saturate(LocalVar%PitCom(K), LocalVar%PC_MinPit, CntrPar%PC_MaxPit) + END IF + + ! Rate limit + LocalVar%PitCom(K) = ratelimit(LocalVar%PitCom(K), CntrPar%PC_MinRat, CntrPar%PC_MaxRat, LocalVar%DT, LocalVar%restart, LocalVar%rlP,objInst%instRL,LocalVar%BlPitch(K)) ! Saturate the overall command of blade K using the pitch rate limit + END DO ! Open Loop control, use if ! Open loop mode active Using OL blade pitch control @@ -134,9 +140,9 @@ SUBROUTINE PitchControl(avrSWAP, CntrPar, LocalVar, objInst, DebugVar, ErrVar) ! Hardware saturation: using CntrPar%PC_MinPit DO K = 1,LocalVar%NumBl ! Loop through all blades, add IPC contribution and limit pitch rate ! Saturate the pitch command using the overall (hardware) limit - LocalVar%PitComAct(K) = saturate(LocalVar%PitComAct(K), LocalVar%PC_MinPit, CntrPar%PC_MaxPit) + LocalVar%PitComAct(K) = saturate(LocalVar%PitComAct(K), CntrPar%PC_MinPit, CntrPar%PC_MaxPit) ! Saturate the overall command of blade K using the pitch rate limit - LocalVar%PitComAct(K) = ratelimit(LocalVar%PitComAct(K), CntrPar%PC_MinRat, CntrPar%PC_MaxRat, LocalVar%DT, LocalVar%restart, LocalVar%rlP,objInst%instRL) ! Saturate the overall command of blade K using the pitch rate limit + LocalVar%PitComAct(K) = ratelimit(LocalVar%PitComAct(K), CntrPar%PC_MinRat, CntrPar%PC_MaxRat, LocalVar%DT, LocalVar%restart, LocalVar%rlP,objInst%instRL,LocalVar%BlPitch(K)) ! Saturate the overall command of blade K using the pitch rate limit END DO ! Add pitch actuator fault for blade K @@ -413,15 +419,26 @@ SUBROUTINE IPC(CntrPar, LocalVar, objInst, DebugVar, ErrVar) LocalVar%IPC_KP(i) = sigma(LocalVar%WE_Vw, CntrPar%IPC_Vramp(1), CntrPar%IPC_Vramp(2), 0.0_DbKi, CntrPar%IPC_KP(i), ErrVar) LocalVar%IPC_KI(i) = sigma(LocalVar%WE_Vw, CntrPar%IPC_Vramp(1), CntrPar%IPC_Vramp(2), 0.0_DbKi, CntrPar%IPC_KI(i), ErrVar) END DO + + ! Handle saturation limit, depends on IPC_SatMode + IF (CntrPar%IPC_SatMode == 2) THEN + ! Saturate to min allowed pitch angle, softly using IPC_IntSat + LocalVar%IPC_IntSat = min(CntrPar%IPC_IntSat,LocalVar%BlPitchCMeas - CntrPar%PC_MinPit) + ELSEIF (CntrPar%IPC_SatMode == 3) THEN + ! Saturate to peak shaving, softly using IPC_IntSat + LocalVar%IPC_IntSat = min(CntrPar%IPC_IntSat,LocalVar%BlPitchCMeas - LocalVar%PC_MinPit) + ELSE + LocalVar%IPC_IntSat = CntrPar%IPC_IntSat + ENDIF ! Integrate the signal and multiply with the IPC gain IF ((CntrPar%IPC_ControlMode >= 1) .AND. (CntrPar%Y_ControlMode /= 2)) THEN - LocalVar%IPC_axisTilt_1P = PIController(axisTilt_1P, LocalVar%IPC_KP(1), LocalVar%IPC_KI(1), -CntrPar%IPC_IntSat, CntrPar%IPC_IntSat, LocalVar%DT, 0.0_DbKi, LocalVar%piP, LocalVar%restart, objInst%instPI) - LocalVar%IPC_axisYaw_1P = PIController(axisYawF_1P, LocalVar%IPC_KP(1), LocalVar%IPC_KI(1), -CntrPar%IPC_IntSat, CntrPar%IPC_IntSat, LocalVar%DT, 0.0_DbKi, LocalVar%piP, LocalVar%restart, objInst%instPI) + LocalVar%IPC_axisTilt_1P = PIController(axisTilt_1P, LocalVar%IPC_KP(1), LocalVar%IPC_KI(1), -LocalVar%IPC_IntSat, LocalVar%IPC_IntSat, LocalVar%DT, 0.0_DbKi, LocalVar%piP, LocalVar%restart, objInst%instPI) + LocalVar%IPC_axisYaw_1P = PIController(axisYawF_1P, LocalVar%IPC_KP(1), LocalVar%IPC_KI(1), -LocalVar%IPC_IntSat, LocalVar%IPC_IntSat, LocalVar%DT, 0.0_DbKi, LocalVar%piP, LocalVar%restart, objInst%instPI) IF (CntrPar%IPC_ControlMode >= 2) THEN - LocalVar%IPC_axisTilt_2P = PIController(axisTilt_2P, LocalVar%IPC_KP(2), LocalVar%IPC_KI(2), -CntrPar%IPC_IntSat, CntrPar%IPC_IntSat, LocalVar%DT, 0.0_DbKi, LocalVar%piP, LocalVar%restart, objInst%instPI) - LocalVar%IPC_axisYaw_2P = PIController(axisYawF_2P, LocalVar%IPC_KP(2), LocalVar%IPC_KI(2), -CntrPar%IPC_IntSat, CntrPar%IPC_IntSat, LocalVar%DT, 0.0_DbKi, LocalVar%piP, LocalVar%restart, objInst%instPI) + LocalVar%IPC_axisTilt_2P = PIController(axisTilt_2P, LocalVar%IPC_KP(2), LocalVar%IPC_KI(2), -LocalVar%IPC_IntSat, LocalVar%IPC_IntSat, LocalVar%DT, 0.0_DbKi, LocalVar%piP, LocalVar%restart, objInst%instPI) + LocalVar%IPC_axisYaw_2P = PIController(axisYawF_2P, LocalVar%IPC_KP(2), LocalVar%IPC_KI(2), -LocalVar%IPC_IntSat, LocalVar%IPC_IntSat, LocalVar%DT, 0.0_DbKi, LocalVar%piP, LocalVar%restart, objInst%instPI) END IF ELSE LocalVar%IPC_axisTilt_1P = 0.0 diff --git a/ROSCO/src/Functions.f90 b/ROSCO/src/Functions.f90 index eca51839..3e0e225e 100644 --- a/ROSCO/src/Functions.f90 +++ b/ROSCO/src/Functions.f90 @@ -48,7 +48,7 @@ REAL(DbKi) FUNCTION saturate(inputValue, minValue, maxValue) END FUNCTION saturate !------------------------------------------------------------------------------------------------------------------------------- - REAL(DbKi) FUNCTION ratelimit(inputSignal, minRate, maxRate, DT, reset, rlP, inst) + REAL(DbKi) FUNCTION ratelimit(inputSignal, minRate, maxRate, DT, reset, rlP, inst, ResetValue) ! Saturates inputValue. Makes sure it is not smaller than minValue and not larger than maxValue USE ROSCO_Types, ONLY : rlParams @@ -62,13 +62,18 @@ REAL(DbKi) FUNCTION ratelimit(inputSignal, minRate, maxRate, DT, reset, rlP, ins LOGICAL, INTENT(IN) :: reset TYPE(rlParams), INTENT(INOUT) :: rlP INTEGER(IntKi), INTENT(INOUT) :: inst + REAL(DbKi), OPTIONAL, INTENT(IN) :: ResetValue ! Value to base rate limit off if restarting ! Local variables REAL(DbKi) :: rate + REAL(DbKi) :: ResetValue_ + + ResetValue_ = inputSignal + IF (PRESENT(ResetValue)) ResetValue_ = ResetValue IF (reset) THEN - rlP%LastSignal(inst) = inputSignal - ratelimit = inputSignal + rlP%LastSignal(inst) = ResetValue_ + ratelimit = ResetValue_ ELSE rate = (inputSignal - rlP%LastSignal(inst))/DT ! Signal rate (unsaturated) @@ -594,6 +599,7 @@ REAL(DbKi) FUNCTION sigma(x, x0, x1, y0, y1, ErrVar) END FUNCTION sigma + !------------------------------------------------------------------------------------------------------------------------------- ! Copied from NWTC_IO.f90 !> This function returns a character string encoded with today's date in the form dd-mmm-ccyy. diff --git a/ROSCO/src/ROSCO_IO.f90 b/ROSCO/src/ROSCO_IO.f90 index 6e97878d..e852105a 100644 --- a/ROSCO/src/ROSCO_IO.f90 +++ b/ROSCO/src/ROSCO_IO.f90 @@ -53,6 +53,7 @@ SUBROUTINE WriteRestartFile(LocalVar, CntrPar, ErrVar, objInst, RootName, size_a WRITE( Un, IOSTAT=ErrStat) LocalVar%BlPitch(1) WRITE( Un, IOSTAT=ErrStat) LocalVar%BlPitch(2) WRITE( Un, IOSTAT=ErrStat) LocalVar%BlPitch(3) + WRITE( Un, IOSTAT=ErrStat) LocalVar%BlPitchCMeas WRITE( Un, IOSTAT=ErrStat) LocalVar%Azimuth WRITE( Un, IOSTAT=ErrStat) LocalVar%NumBl WRITE( Un, IOSTAT=ErrStat) LocalVar%FA_Acc @@ -93,6 +94,7 @@ SUBROUTINE WriteRestartFile(LocalVar, CntrPar, ErrVar, objInst, RootName, size_a WRITE( Un, IOSTAT=ErrStat) LocalVar%IPC_KI(2) WRITE( Un, IOSTAT=ErrStat) LocalVar%IPC_KP(1) WRITE( Un, IOSTAT=ErrStat) LocalVar%IPC_KP(2) + WRITE( Un, IOSTAT=ErrStat) LocalVar%IPC_IntSat WRITE( Un, IOSTAT=ErrStat) LocalVar%PC_State WRITE( Un, IOSTAT=ErrStat) LocalVar%PitCom(1) WRITE( Un, IOSTAT=ErrStat) LocalVar%PitCom(2) @@ -234,6 +236,7 @@ SUBROUTINE ReadRestartFile(avrSWAP, LocalVar, CntrPar, objInst, PerfData, RootNa READ( Un, IOSTAT=ErrStat) LocalVar%BlPitch(1) READ( Un, IOSTAT=ErrStat) LocalVar%BlPitch(2) READ( Un, IOSTAT=ErrStat) LocalVar%BlPitch(3) + READ( Un, IOSTAT=ErrStat) LocalVar%BlPitchCMeas READ( Un, IOSTAT=ErrStat) LocalVar%Azimuth READ( Un, IOSTAT=ErrStat) LocalVar%NumBl READ( Un, IOSTAT=ErrStat) LocalVar%FA_Acc @@ -274,6 +277,7 @@ SUBROUTINE ReadRestartFile(avrSWAP, LocalVar, CntrPar, objInst, PerfData, RootNa READ( Un, IOSTAT=ErrStat) LocalVar%IPC_KI(2) READ( Un, IOSTAT=ErrStat) LocalVar%IPC_KP(1) READ( Un, IOSTAT=ErrStat) LocalVar%IPC_KP(2) + READ( Un, IOSTAT=ErrStat) LocalVar%IPC_IntSat READ( Un, IOSTAT=ErrStat) LocalVar%PC_State READ( Un, IOSTAT=ErrStat) LocalVar%PitCom(1) READ( Un, IOSTAT=ErrStat) LocalVar%PitCom(2) @@ -438,7 +442,7 @@ SUBROUTINE Debug(LocalVar, CntrPar, DebugVar, ErrVar, avrSWAP, RootName, size_av '[rad/s]', '[rad/s]', '[m/s]', '[rad]', '[rad]', & '[N/A]', '[N/A]', '[N/A]', '[N/A]', '[rad/s]', & '[deg]', '[deg]', '[deg]', '[N/A]'] - nLocalVars = 69 + nLocalVars = 71 Allocate(LocalVarOutData(nLocalVars)) Allocate(LocalVarOutStrings(nLocalVars)) LocalVarOutData(1) = LocalVar%iStatus @@ -453,77 +457,80 @@ SUBROUTINE Debug(LocalVar, CntrPar, DebugVar, ErrVar, avrSWAP, RootName, size_av LocalVarOutData(10) = LocalVar%rootMOOP(1) LocalVarOutData(11) = LocalVar%rootMOOPF(1) LocalVarOutData(12) = LocalVar%BlPitch(1) - LocalVarOutData(13) = LocalVar%Azimuth - LocalVarOutData(14) = LocalVar%NumBl - LocalVarOutData(15) = LocalVar%FA_Acc - LocalVarOutData(16) = LocalVar%NacIMU_FA_Acc - LocalVarOutData(17) = LocalVar%FA_AccHPF - LocalVarOutData(18) = LocalVar%FA_AccHPFI - LocalVarOutData(19) = LocalVar%FA_PitCom(1) - LocalVarOutData(20) = LocalVar%RotSpeedF - LocalVarOutData(21) = LocalVar%GenSpeedF - LocalVarOutData(22) = LocalVar%GenTq - LocalVarOutData(23) = LocalVar%GenTqMeas - LocalVarOutData(24) = LocalVar%GenArTq - LocalVarOutData(25) = LocalVar%GenBrTq - LocalVarOutData(26) = LocalVar%IPC_PitComF(1) - LocalVarOutData(27) = LocalVar%PC_KP - LocalVarOutData(28) = LocalVar%PC_KI - LocalVarOutData(29) = LocalVar%PC_KD - LocalVarOutData(30) = LocalVar%PC_TF - LocalVarOutData(31) = LocalVar%PC_MaxPit - LocalVarOutData(32) = LocalVar%PC_MinPit - LocalVarOutData(33) = LocalVar%PC_PitComT - LocalVarOutData(34) = LocalVar%PC_PitComT_Last - LocalVarOutData(35) = LocalVar%PC_PitComTF - LocalVarOutData(36) = LocalVar%PC_PitComT_IPC(1) - LocalVarOutData(37) = LocalVar%PC_PwrErr - LocalVarOutData(38) = LocalVar%PC_SpdErr - LocalVarOutData(39) = LocalVar%IPC_AxisTilt_1P - LocalVarOutData(40) = LocalVar%IPC_AxisYaw_1P - LocalVarOutData(41) = LocalVar%IPC_AxisTilt_2P - LocalVarOutData(42) = LocalVar%IPC_AxisYaw_2P - LocalVarOutData(43) = LocalVar%IPC_KI(1) - LocalVarOutData(44) = LocalVar%IPC_KP(1) - LocalVarOutData(45) = LocalVar%PC_State - LocalVarOutData(46) = LocalVar%PitCom(1) - LocalVarOutData(47) = LocalVar%PitComAct(1) - LocalVarOutData(48) = LocalVar%SS_DelOmegaF - LocalVarOutData(49) = LocalVar%TestType - LocalVarOutData(50) = LocalVar%VS_MaxTq - LocalVarOutData(51) = LocalVar%VS_LastGenTrq - LocalVarOutData(52) = LocalVar%VS_LastGenPwr - LocalVarOutData(53) = LocalVar%VS_MechGenPwr - LocalVarOutData(54) = LocalVar%VS_SpdErrAr - LocalVarOutData(55) = LocalVar%VS_SpdErrBr - LocalVarOutData(56) = LocalVar%VS_SpdErr - LocalVarOutData(57) = LocalVar%VS_State - LocalVarOutData(58) = LocalVar%VS_Rgn3Pitch - LocalVarOutData(59) = LocalVar%WE_Vw - LocalVarOutData(60) = LocalVar%WE_Vw_F - LocalVarOutData(61) = LocalVar%WE_VwI - LocalVarOutData(62) = LocalVar%WE_VwIdot - LocalVarOutData(63) = LocalVar%VS_LastGenTrqF - LocalVarOutData(64) = LocalVar%Fl_PitCom - LocalVarOutData(65) = LocalVar%NACIMU_FA_AccF - LocalVarOutData(66) = LocalVar%FA_AccF - LocalVarOutData(67) = LocalVar%Flp_Angle(1) - LocalVarOutData(68) = LocalVar%RootMyb_Last(1) - LocalVarOutData(69) = LocalVar%ACC_INFILE_SIZE + LocalVarOutData(13) = LocalVar%BlPitchCMeas + LocalVarOutData(14) = LocalVar%Azimuth + LocalVarOutData(15) = LocalVar%NumBl + LocalVarOutData(16) = LocalVar%FA_Acc + LocalVarOutData(17) = LocalVar%NacIMU_FA_Acc + LocalVarOutData(18) = LocalVar%FA_AccHPF + LocalVarOutData(19) = LocalVar%FA_AccHPFI + LocalVarOutData(20) = LocalVar%FA_PitCom(1) + LocalVarOutData(21) = LocalVar%RotSpeedF + LocalVarOutData(22) = LocalVar%GenSpeedF + LocalVarOutData(23) = LocalVar%GenTq + LocalVarOutData(24) = LocalVar%GenTqMeas + LocalVarOutData(25) = LocalVar%GenArTq + LocalVarOutData(26) = LocalVar%GenBrTq + LocalVarOutData(27) = LocalVar%IPC_PitComF(1) + LocalVarOutData(28) = LocalVar%PC_KP + LocalVarOutData(29) = LocalVar%PC_KI + LocalVarOutData(30) = LocalVar%PC_KD + LocalVarOutData(31) = LocalVar%PC_TF + LocalVarOutData(32) = LocalVar%PC_MaxPit + LocalVarOutData(33) = LocalVar%PC_MinPit + LocalVarOutData(34) = LocalVar%PC_PitComT + LocalVarOutData(35) = LocalVar%PC_PitComT_Last + LocalVarOutData(36) = LocalVar%PC_PitComTF + LocalVarOutData(37) = LocalVar%PC_PitComT_IPC(1) + LocalVarOutData(38) = LocalVar%PC_PwrErr + LocalVarOutData(39) = LocalVar%PC_SpdErr + LocalVarOutData(40) = LocalVar%IPC_AxisTilt_1P + LocalVarOutData(41) = LocalVar%IPC_AxisYaw_1P + LocalVarOutData(42) = LocalVar%IPC_AxisTilt_2P + LocalVarOutData(43) = LocalVar%IPC_AxisYaw_2P + LocalVarOutData(44) = LocalVar%IPC_KI(1) + LocalVarOutData(45) = LocalVar%IPC_KP(1) + LocalVarOutData(46) = LocalVar%IPC_IntSat + LocalVarOutData(47) = LocalVar%PC_State + LocalVarOutData(48) = LocalVar%PitCom(1) + LocalVarOutData(49) = LocalVar%PitComAct(1) + LocalVarOutData(50) = LocalVar%SS_DelOmegaF + LocalVarOutData(51) = LocalVar%TestType + LocalVarOutData(52) = LocalVar%VS_MaxTq + LocalVarOutData(53) = LocalVar%VS_LastGenTrq + LocalVarOutData(54) = LocalVar%VS_LastGenPwr + LocalVarOutData(55) = LocalVar%VS_MechGenPwr + LocalVarOutData(56) = LocalVar%VS_SpdErrAr + LocalVarOutData(57) = LocalVar%VS_SpdErrBr + LocalVarOutData(58) = LocalVar%VS_SpdErr + LocalVarOutData(59) = LocalVar%VS_State + LocalVarOutData(60) = LocalVar%VS_Rgn3Pitch + LocalVarOutData(61) = LocalVar%WE_Vw + LocalVarOutData(62) = LocalVar%WE_Vw_F + LocalVarOutData(63) = LocalVar%WE_VwI + LocalVarOutData(64) = LocalVar%WE_VwIdot + LocalVarOutData(65) = LocalVar%VS_LastGenTrqF + LocalVarOutData(66) = LocalVar%Fl_PitCom + LocalVarOutData(67) = LocalVar%NACIMU_FA_AccF + LocalVarOutData(68) = LocalVar%FA_AccF + LocalVarOutData(69) = LocalVar%Flp_Angle(1) + LocalVarOutData(70) = LocalVar%RootMyb_Last(1) + LocalVarOutData(71) = LocalVar%ACC_INFILE_SIZE LocalVarOutStrings = [CHARACTER(15) :: 'iStatus', 'Time', 'DT', 'VS_GenPwr', 'GenSpeed', & 'RotSpeed', 'NacHeading', 'NacVane', 'HorWindV', 'rootMOOP', & - 'rootMOOPF', 'BlPitch', 'Azimuth', 'NumBl', 'FA_Acc', & - 'NacIMU_FA_Acc', 'FA_AccHPF', 'FA_AccHPFI', 'FA_PitCom', 'RotSpeedF', & - 'GenSpeedF', 'GenTq', 'GenTqMeas', 'GenArTq', 'GenBrTq', & - 'IPC_PitComF', 'PC_KP', 'PC_KI', 'PC_KD', 'PC_TF', & - 'PC_MaxPit', 'PC_MinPit', 'PC_PitComT', 'PC_PitComT_Last', 'PC_PitComTF', & - 'PC_PitComT_IPC', 'PC_PwrErr', 'PC_SpdErr', 'IPC_AxisTilt_1P', 'IPC_AxisYaw_1P', & - 'IPC_AxisTilt_2P', 'IPC_AxisYaw_2P', 'IPC_KI', 'IPC_KP', 'PC_State', & - 'PitCom', 'PitComAct', 'SS_DelOmegaF', 'TestType', 'VS_MaxTq', & - 'VS_LastGenTrq', 'VS_LastGenPwr', 'VS_MechGenPwr', 'VS_SpdErrAr', 'VS_SpdErrBr', & - 'VS_SpdErr', 'VS_State', 'VS_Rgn3Pitch', 'WE_Vw', 'WE_Vw_F', & - 'WE_VwI', 'WE_VwIdot', 'VS_LastGenTrqF', 'Fl_PitCom', 'NACIMU_FA_AccF', & - 'FA_AccF', 'Flp_Angle', 'RootMyb_Last', 'ACC_INFILE_SIZE'] + 'rootMOOPF', 'BlPitch', 'BlPitchCMeas', 'Azimuth', 'NumBl', & + 'FA_Acc', 'NacIMU_FA_Acc', 'FA_AccHPF', 'FA_AccHPFI', 'FA_PitCom', & + 'RotSpeedF', 'GenSpeedF', 'GenTq', 'GenTqMeas', 'GenArTq', & + 'GenBrTq', 'IPC_PitComF', 'PC_KP', 'PC_KI', 'PC_KD', & + 'PC_TF', 'PC_MaxPit', 'PC_MinPit', 'PC_PitComT', 'PC_PitComT_Last', & + 'PC_PitComTF', 'PC_PitComT_IPC', 'PC_PwrErr', 'PC_SpdErr', 'IPC_AxisTilt_1P', & + 'IPC_AxisYaw_1P', 'IPC_AxisTilt_2P', 'IPC_AxisYaw_2P', 'IPC_KI', 'IPC_KP', & + 'IPC_IntSat', 'PC_State', 'PitCom', 'PitComAct', 'SS_DelOmegaF', & + 'TestType', 'VS_MaxTq', 'VS_LastGenTrq', 'VS_LastGenPwr', 'VS_MechGenPwr', & + 'VS_SpdErrAr', 'VS_SpdErrBr', 'VS_SpdErr', 'VS_State', 'VS_Rgn3Pitch', & + 'WE_Vw', 'WE_Vw_F', 'WE_VwI', 'WE_VwIdot', 'VS_LastGenTrqF', & + 'Fl_PitCom', 'NACIMU_FA_AccF', 'FA_AccF', 'Flp_Angle', 'RootMyb_Last', & + 'ACC_INFILE_SIZE'] ! Initialize debug file IF ((LocalVar%iStatus == 0) .OR. (LocalVar%iStatus == -9)) THEN ! .TRUE. if we're on the first call to the DLL IF (CntrPar%LoggingLevel > 0) THEN diff --git a/ROSCO/src/ROSCO_Types.f90 b/ROSCO/src/ROSCO_Types.f90 index 3426ae9f..ad2b631b 100644 --- a/ROSCO/src/ROSCO_Types.f90 +++ b/ROSCO/src/ROSCO_Types.f90 @@ -28,6 +28,7 @@ MODULE ROSCO_Types INTEGER(IntKi) :: IPC_ControlMode ! Turn Individual Pitch Control (IPC) for fatigue load reductions (pitch contribution) {0 - off, 1 - 1P reductions, 2 - 1P+2P reductions} REAL(DbKi), DIMENSION(:), ALLOCATABLE :: IPC_Vramp ! Wind speeds for IPC cut-in sigma function [m/s] REAL(DbKi) :: IPC_IntSat ! Integrator saturation (maximum signal amplitude contrbution to pitch from IPC) + INTEGER(IntKi) :: IPC_SatMode ! IPC Saturation method (0 - no saturation, 1 - saturate by PC_MinPit, 2 - saturate by PS_BldPitchMin) REAL(DbKi), DIMENSION(:), ALLOCATABLE :: IPC_KP ! Integral gain for the individual pitch controller, [-]. REAL(DbKi), DIMENSION(:), ALLOCATABLE :: IPC_KI ! Integral gain for the individual pitch controller, [-]. REAL(DbKi), DIMENSION(:), ALLOCATABLE :: IPC_aziOffset ! Phase offset added to the azimuth angle for the individual pitch controller, [rad]. @@ -200,6 +201,7 @@ MODULE ROSCO_Types REAL(DbKi) :: rootMOOP(3) ! Blade root bending moment [Nm] REAL(DbKi) :: rootMOOPF(3) ! Filtered Blade root bending moment [Nm] REAL(DbKi) :: BlPitch(3) ! Blade pitch [rad] + REAL(DbKi) :: BlPitchCMeas ! Mean (collective) blade pitch [rad] REAL(DbKi) :: Azimuth ! Rotor aziumuth angle [rad] INTEGER(IntKi) :: NumBl ! Number of blades [-] REAL(DbKi) :: FA_Acc ! Tower fore-aft acceleration [m/s^2] @@ -232,6 +234,7 @@ MODULE ROSCO_Types REAL(DbKi) :: IPC_AxisYaw_2P ! Integral of quadrature, 2P REAL(DbKi) :: IPC_KI(2) ! Integral gain for IPC, after ramp [-] REAL(DbKi) :: IPC_KP(2) ! Proportional gain for IPC, after ramp [-] + REAL(DbKi) :: IPC_IntSat ! Integrator saturation (maximum signal amplitude contrbution to pitch from IPC) INTEGER(IntKi) :: PC_State ! State of the pitch control system REAL(DbKi) :: PitCom(3) ! Commanded pitch of each blade the last time the controller was called [rad]. REAL(DbKi) :: PitComAct(3) ! Actuated pitch command of each blade [rad]. diff --git a/ROSCO/src/ReadSetParameters.f90 b/ROSCO/src/ReadSetParameters.f90 index 9b00c1f2..9ba9e80c 100644 --- a/ROSCO/src/ReadSetParameters.f90 +++ b/ROSCO/src/ReadSetParameters.f90 @@ -72,11 +72,13 @@ SUBROUTINE ReadAvrSWAP(avrSWAP, LocalVar, CntrPar) ELSE LocalVar%BlPitch(1) = LocalVar%PitComAct(1) LocalVar%BlPitch(2) = LocalVar%PitComAct(2) - LocalVar%BlPitch(3) = LocalVar%PitComAct(3) + LocalVar%BlPitch(3) = LocalVar%PitComAct(3) END IF ENDIF + LocalVar%BlPitchCMeas = (1 / REAL(LocalVar%NumBl)) * (LocalVar%BlPitch(1) + LocalVar%BlPitch(2) + LocalVar%BlPitch(3)) + IF (LocalVar%iStatus == 0) THEN ! TODO: Technically, LocalVar%Time > 0, too, but this restart is in many places as a reset LocalVar%restart = .True. ELSE @@ -301,6 +303,7 @@ SUBROUTINE ReadControlParameterFileSub(CntrPar, zmqVar, accINFILE, accINFILE_siz !------------------- IPC CONSTANTS ----------------------- CALL ReadEmptyLine(UnControllerParameters,CurLine) CALL ParseAry(UnControllerParameters, CurLine, 'IPC_Vramp', CntrPar%IPC_Vramp, 2, accINFILE(1), ErrVar ) + CALL ParseInput(UnControllerParameters,CurLine,'IPC_SatMode',accINFILE(1),CntrPar%IPC_SatMode,ErrVar) CALL ParseInput(UnControllerParameters,CurLine,'IPC_IntSat',accINFILE(1),CntrPar%IPC_IntSat,ErrVar) CALL ParseAry(UnControllerParameters, CurLine, 'IPC_KP', CntrPar%IPC_KP, 2, accINFILE(1), ErrVar ) CALL ParseAry(UnControllerParameters, CurLine, 'IPC_KI', CntrPar%IPC_KI, 2, accINFILE(1), ErrVar ) @@ -805,6 +808,11 @@ SUBROUTINE CheckInputs(LocalVar, CntrPar, avrSWAP, ErrVar, size_avcMSG) ErrVar%ErrMsg = 'Corner frequency of IPC actuator model must be positive, or set to 0 to disable.' ENDIF + IF (CntrPar%IPC_SatMode < 0 .OR. CntrPar%IPC_SatMode > 3) THEN + ErrVar%aviFAIL = -1 + ErrVar%ErrMsg = 'IPC_SatMode must be 0, 1, 2, or 3.' + ENDIF + IF (CntrPar%IPC_KI(1) < 0.0) THEN ErrVar%aviFAIL = -1 ErrVar%ErrMsg = 'IPC_KI(1) must be zero or greater than zero.' diff --git a/ROSCO_toolbox/inputs/toolbox_schema.yaml b/ROSCO_toolbox/inputs/toolbox_schema.yaml index d88c346e..432785df 100644 --- a/ROSCO_toolbox/inputs/toolbox_schema.yaml +++ b/ROSCO_toolbox/inputs/toolbox_schema.yaml @@ -606,6 +606,9 @@ properties: type: number description: Integrator saturation (maximum signal amplitude contribution to pitch from IPC) units: rad + IPC_SatMode: + type: integer + description: IPC Saturation method (0 - no saturation, 1 - saturate by PC_MinPit, 2 - saturate by PS_BldPitchMin) IPC_KP: type: array items: diff --git a/ROSCO_toolbox/utilities.py b/ROSCO_toolbox/utilities.py index 10ddc7d3..055a76f8 100644 --- a/ROSCO_toolbox/utilities.py +++ b/ROSCO_toolbox/utilities.py @@ -116,7 +116,8 @@ def write_DISCON(turbine, controller, param_file='DISCON.IN', txt_filename='Cp_C file.write('\n') file.write('!------- INDIVIDUAL PITCH CONTROL -----------------------------------------\n') file.write('{}! IPC_Vramp - Start and end wind speeds for cut-in ramp function. First entry: IPC inactive, second entry: IPC fully active. [m/s]\n'.format(''.join('{:<4.6f} '.format(rosco_vt['IPC_Vramp'][i]) for i in range(len(rosco_vt['IPC_Vramp']))))) - file.write('{:<13.1f} ! IPC_IntSat - Integrator saturation (maximum signal amplitude contribution to pitch from IPC), [rad]\n'.format(rosco_vt['IPC_IntSat'])) # Hardcode to 5 degrees + file.write('{:<11d} ! IPC_SatMode - IPC Saturation method (0 - no saturation (except by PC_MinPit), 1 - saturate by PS_BldPitchMin, 2 - saturate sotfly (full IPC cycle) by PC_MinPit, 3 - saturate softly by PS_BldPitchMin)\n'.format(int(rosco_vt['IPC_SatMode']))) # Hardcode to 5 degrees + file.write('{:<13.1f} ! IPC_IntSat - Integrator saturation (maximum signal amplitude contribution to pitch from IPC), [rad]\n'.format(rosco_vt['IPC_IntSat'])) file.write('{}! IPC_KP - Proportional gain for the individual pitch controller: first parameter for 1P reductions, second for 2P reductions, [-]\n'.format(''.join('{:<4.3e} '.format(rosco_vt['IPC_KP'][i]) for i in range(len(rosco_vt['IPC_KP']))))) file.write('{}! IPC_KI - Integral gain for the individual pitch controller: first parameter for 1P reductions, second for 2P reductions, [-]\n'.format(''.join('{:<4.3e} '.format(rosco_vt['IPC_KI'][i]) for i in range(len(rosco_vt['IPC_KI']))))) file.write('{}! IPC_aziOffset - Phase offset added to the azimuth angle for the individual pitch controller, [rad]. \n'.format(''.join('{:<4.6f} '.format(rosco_vt['IPC_aziOffset'][i]) for i in range(len(rosco_vt['IPC_aziOffset']))))) @@ -437,6 +438,7 @@ def DISCON_dict(turbine, controller, txt_filename=None): # ------- INDIVIDUAL PITCH CONTROL ------- DISCON_dict['IPC_Vramp'] = controller.IPC_Vramp DISCON_dict['IPC_IntSat'] = 0.2618 + DISCON_dict['IPC_SatMode'] = 2 DISCON_dict['IPC_KP'] = [controller.Kp_ipc1p, controller.Kp_ipc2p] DISCON_dict['IPC_KI'] = [controller.Ki_ipc1p, controller.Ki_ipc2p] DISCON_dict['IPC_aziOffset'] = [0.0, 0.0] diff --git a/Test_Cases/BAR_10/BAR_10_DISCON.IN b/Test_Cases/BAR_10/BAR_10_DISCON.IN index f05cc03d..e7f5a1bd 100644 --- a/Test_Cases/BAR_10/BAR_10_DISCON.IN +++ b/Test_Cases/BAR_10/BAR_10_DISCON.IN @@ -1,5 +1,5 @@ ! Controller parameter input file for the BAR_10 wind turbine -! - File written using ROSCO version 2.6.0 controller tuning logic on 11/29/22 +! - File written using ROSCO version 2.6.0 controller tuning logic on 01/18/23 !------- DEBUG ------------------------------------------------------------ 1 ! LoggingLevel - {0: write no debug files, 1: write standard output .dbg-file, 2: LoggingLevel 1 + ROSCO LocalVars (.dbg2) 3: LoggingLevel 2 + complete avrSWAP-array (.dbg3)} @@ -53,6 +53,7 @@ !------- INDIVIDUAL PITCH CONTROL ----------------------------------------- 6.618848 8.273560 ! IPC_Vramp - Start and end wind speeds for cut-in ramp function. First entry: IPC inactive, second entry: IPC fully active. [m/s] +2 ! IPC_SatMode - IPC Saturation method (0 - no saturation (except by PC_MinPit), 1 - saturate by PS_BldPitchMin, 2 - saturate sotfly (full IPC cycle) by PC_MinPit, 3 - saturate softly by PS_BldPitchMin) 0.3 ! IPC_IntSat - Integrator saturation (maximum signal amplitude contribution to pitch from IPC), [rad] 2.050e-08 0.000e+00 ! IPC_KP - Proportional gain for the individual pitch controller: first parameter for 1P reductions, second for 2P reductions, [-] 1.450e-09 0.000e+00 ! IPC_KI - Integral gain for the individual pitch controller: first parameter for 1P reductions, second for 2P reductions, [-] @@ -94,8 +95,8 @@ -0.00972164 -0.01031092 -0.01090020 -0.01148948 -0.01207877 -0.01266805 -0.01325733 -0.01384662 -0.01443590 -0.01502518 -0.01561447 -0.01620375 -0.01679303 -0.01738232 -0.01797160 -0.01856088 -0.01915016 -0.01973945 -0.02032873 -0.02091801 -0.02150730 -0.02209658 -0.02268586 -0.02327515 -0.02386443 -0.02445371 -0.02504300 -0.02563228 -0.02622156 -0.02378670 -0.02062296 -0.02541485 -0.03159105 -0.03849962 -0.04595997 -0.05389417 -0.06225884 -0.07101431 -0.08016995 -0.08970426 -0.09955610 -0.10976762 -0.12028100 -0.13120419 -0.14238799 -0.15383228 -0.16572504 -0.17783697 -0.19011487 -0.20289651 -0.21593424 -0.22919262 -0.24255457 -0.25635133 -0.27049546 -0.28482651 -0.29923376 -0.31380076 -0.32862514 -0.34372726 ! WE_FOPoles - First order system poles [1/s] !------- YAW CONTROL ------------------------------------------------------ -0.00000 ! Y_uSwitch - Wind speed to switch between Y_ErrThresh. If zero, only the first value of Y_ErrThresh is used [m/s] -4.000000 8.000000 ! Y_ErrThresh - Yaw error threshold/deadband. Turbine begins to yaw when it passes this. If Y_uSwitch is zero, only the first value is used. [deg]. +0.00000 ! Y_uSwitch - Wind speed to switch between Y_ErrThresh. If zero, only the second value of Y_ErrThresh is used [m/s] +4.000000 8.000000 ! Y_ErrThresh - Yaw error threshold/deadbands. Turbine begins to yaw when it passes this. If Y_uSwitch is zero, only the second value is used. [deg]. 0.00870 ! Y_Rate - Yaw rate [rad/s] 0.00000 ! Y_MErrSet - Integrator saturation (maximum signal amplitude contribution to pitch from yaw-by-IPC), [rad] 0.00000 ! Y_IPC_IntSat - Integrator saturation (maximum signal amplitude contribution to pitch from yaw-by-IPC), [rad] diff --git a/Test_Cases/IEA-15-240-RWT-UMaineSemi/DISCON-UMaineSemi.IN b/Test_Cases/IEA-15-240-RWT-UMaineSemi/DISCON-UMaineSemi.IN index 82eec8be..6be782e5 100644 --- a/Test_Cases/IEA-15-240-RWT-UMaineSemi/DISCON-UMaineSemi.IN +++ b/Test_Cases/IEA-15-240-RWT-UMaineSemi/DISCON-UMaineSemi.IN @@ -1,5 +1,5 @@ ! Controller parameter input file for the IEA-15-240-RWT-UMaineSemi wind turbine -! - File written using ROSCO version 2.6.0 controller tuning logic on 11/29/22 +! - File written using ROSCO version 2.6.0 controller tuning logic on 01/18/23 !------- DEBUG ------------------------------------------------------------ 2 ! LoggingLevel - {0: write no debug files, 1: write standard output .dbg-file, 2: LoggingLevel 1 + ROSCO LocalVars (.dbg2) 3: LoggingLevel 2 + complete avrSWAP-array (.dbg3)} @@ -53,6 +53,7 @@ !------- INDIVIDUAL PITCH CONTROL ----------------------------------------- 8.592000 10.740000 ! IPC_Vramp - Start and end wind speeds for cut-in ramp function. First entry: IPC inactive, second entry: IPC fully active. [m/s] +2 ! IPC_SatMode - IPC Saturation method (0 - no saturation (except by PC_MinPit), 1 - saturate by PS_BldPitchMin, 2 - saturate sotfly (full IPC cycle) by PC_MinPit, 3 - saturate softly by PS_BldPitchMin) 0.3 ! IPC_IntSat - Integrator saturation (maximum signal amplitude contribution to pitch from IPC), [rad] 0.000e+00 0.000e+00 ! IPC_KP - Proportional gain for the individual pitch controller: first parameter for 1P reductions, second for 2P reductions, [-] 0.000e+00 0.000e+00 ! IPC_KI - Integral gain for the individual pitch controller: first parameter for 1P reductions, second for 2P reductions, [-] @@ -94,8 +95,8 @@ -0.02438353 -0.02655283 -0.02872212 -0.03089141 -0.03306071 -0.03523000 -0.03739930 -0.03956859 -0.04173788 -0.04390718 -0.04607647 -0.04824576 -0.05041506 -0.05258435 -0.05475365 -0.05692294 -0.05909223 -0.06126153 -0.06343082 -0.06560011 -0.06776941 -0.06993870 -0.07210800 -0.07427729 -0.07644658 -0.07861588 -0.08078517 -0.08295446 -0.08512376 -0.08490640 -0.05739531 -0.05967534 -0.06643664 -0.07537721 -0.08537869 -0.09664144 -0.10851650 -0.12137925 -0.13453168 -0.14834459 -0.16280188 -0.17753158 -0.19283401 -0.20862160 -0.22461456 -0.24120058 -0.25817445 -0.27538476 -0.29299882 -0.31103587 -0.32941546 -0.34807902 -0.36693717 -0.38625237 -0.40583167 -0.42579305 -0.44596365 -0.46626113 -0.48675074 -0.50756940 ! WE_FOPoles - First order system poles [1/s] !------- YAW CONTROL ------------------------------------------------------ -0.00000 ! Y_uSwitch - Wind speed to switch between Y_ErrThresh. If zero, only the first value of Y_ErrThresh is used [m/s] -4.000000 8.000000 ! Y_ErrThresh - Yaw error threshold/deadband. Turbine begins to yaw when it passes this. If Y_uSwitch is zero, only the first value is used. [deg]. +0.00000 ! Y_uSwitch - Wind speed to switch between Y_ErrThresh. If zero, only the second value of Y_ErrThresh is used [m/s] +4.000000 8.000000 ! Y_ErrThresh - Yaw error threshold/deadbands. Turbine begins to yaw when it passes this. If Y_uSwitch is zero, only the second value is used. [deg]. 0.00870 ! Y_Rate - Yaw rate [rad/s] 0.00000 ! Y_MErrSet - Integrator saturation (maximum signal amplitude contribution to pitch from yaw-by-IPC), [rad] 0.00000 ! Y_IPC_IntSat - Integrator saturation (maximum signal amplitude contribution to pitch from yaw-by-IPC), [rad] diff --git a/Test_Cases/IEA-15-240-RWT-UMaineSemi/IEA-15-240-RWT-UMaineSemi_ServoDyn.dat b/Test_Cases/IEA-15-240-RWT-UMaineSemi/IEA-15-240-RWT-UMaineSemi_ServoDyn.dat index f402ab4b..51a09d4e 100644 --- a/Test_Cases/IEA-15-240-RWT-UMaineSemi/IEA-15-240-RWT-UMaineSemi_ServoDyn.dat +++ b/Test_Cases/IEA-15-240-RWT-UMaineSemi/IEA-15-240-RWT-UMaineSemi_ServoDyn.dat @@ -81,7 +81,7 @@ True GenTiStp - Method to stop the generator {T: timed usin False DLL_Ramp - Whether a linear ramp should be used between DLL_DT time steps [introduces time shift when true] (flag) [used only with Bladed Interface] 9999.9 BPCutoff - Cuttoff frequency for low-pass filter on blade pitch from DLL (Hz) [used only with Bladed Interface] 0.0 NacYaw_North - Reference yaw angle of the nacelle when the upwind end points due North (deg) [used only with Bladed Interface] -0 Ptch_Cntrl - Record 28: Use individual pitch control {0: collective pitch; 1: individual pitch control} (switch) [used only with Bladed Interface] +1 Ptch_Cntrl - Record 28: Use individual pitch control {0: collective pitch; 1: individual pitch control} (switch) [used only with Bladed Interface] 0.0 Ptch_SetPnt - Record 5: Below-rated pitch angle set-point (deg) [used only with Bladed Interface] 0.0 Ptch_Min - Record 6: Minimum pitch angle (deg) [used only with Bladed Interface] 0.0 Ptch_Max - Record 7: Maximum pitch angle (deg) [used only with Bladed Interface] diff --git a/Test_Cases/NREL-5MW/DISCON.IN b/Test_Cases/NREL-5MW/DISCON.IN index 7369eac9..29b3a8e8 100644 --- a/Test_Cases/NREL-5MW/DISCON.IN +++ b/Test_Cases/NREL-5MW/DISCON.IN @@ -1,5 +1,5 @@ ! Controller parameter input file for the NREL-5MW wind turbine -! - File written using ROSCO version 2.6.0 controller tuning logic on 11/29/22 +! - File written using ROSCO version 2.6.0 controller tuning logic on 01/18/23 !------- DEBUG ------------------------------------------------------------ 1 ! LoggingLevel - {0: write no debug files, 1: write standard output .dbg-file, 2: LoggingLevel 1 + ROSCO LocalVars (.dbg2) 3: LoggingLevel 2 + complete avrSWAP-array (.dbg3)} @@ -53,6 +53,7 @@ !------- INDIVIDUAL PITCH CONTROL ----------------------------------------- 9.120000 11.400000 ! IPC_Vramp - Start and end wind speeds for cut-in ramp function. First entry: IPC inactive, second entry: IPC fully active. [m/s] +2 ! IPC_SatMode - IPC Saturation method (0 - no saturation (except by PC_MinPit), 1 - saturate by PS_BldPitchMin, 2 - saturate sotfly (full IPC cycle) by PC_MinPit, 3 - saturate softly by PS_BldPitchMin) 0.3 ! IPC_IntSat - Integrator saturation (maximum signal amplitude contribution to pitch from IPC), [rad] 0.000e+00 0.000e+00 ! IPC_KP - Proportional gain for the individual pitch controller: first parameter for 1P reductions, second for 2P reductions, [-] 0.000e+00 0.000e+00 ! IPC_KI - Integral gain for the individual pitch controller: first parameter for 1P reductions, second for 2P reductions, [-] @@ -94,8 +95,8 @@ -0.01638154 -0.01796321 -0.01954487 -0.02112654 -0.02270820 -0.02428987 -0.02587154 -0.02745320 -0.02903487 -0.03061653 -0.03219820 -0.03377987 -0.03536153 -0.03694320 -0.03852486 -0.04010653 -0.04168820 -0.04326986 -0.04485153 -0.04643319 -0.04801486 -0.04959652 -0.05117819 -0.05275986 -0.05434152 -0.05592319 -0.05758373 -0.05882656 -0.06845507 -0.05992890 0.02094683 0.01327182 0.00285485 -0.00935731 -0.02210773 -0.03573037 -0.04990222 -0.06404904 -0.07899629 -0.09463190 -0.10954192 -0.12525205 -0.14168652 -0.15843395 -0.17415061 -0.19052486 -0.20780146 -0.22581018 -0.24373777 -0.26010871 -0.27706767 -0.29551708 -0.31430599 -0.33428552 -0.35420853 -0.37183729 -0.38936451 -0.40828911 -0.42758878 -0.44818175 ! WE_FOPoles - First order system poles [1/s] !------- YAW CONTROL ------------------------------------------------------ -0.00000 ! Y_uSwitch - Wind speed to switch between Y_ErrThresh. If zero, only the first value of Y_ErrThresh is used [m/s] -4.000000 8.000000 ! Y_ErrThresh - Yaw error threshold/deadband. Turbine begins to yaw when it passes this. If Y_uSwitch is zero, only the first value is used. [deg]. +0.00000 ! Y_uSwitch - Wind speed to switch between Y_ErrThresh. If zero, only the second value of Y_ErrThresh is used [m/s] +4.000000 8.000000 ! Y_ErrThresh - Yaw error threshold/deadbands. Turbine begins to yaw when it passes this. If Y_uSwitch is zero, only the second value is used. [deg]. 0.00870 ! Y_Rate - Yaw rate [rad/s] 0.00000 ! Y_MErrSet - Integrator saturation (maximum signal amplitude contribution to pitch from yaw-by-IPC), [rad] 0.00000 ! Y_IPC_IntSat - Integrator saturation (maximum signal amplitude contribution to pitch from yaw-by-IPC), [rad] From c51ed30ac2145f29106de2fdcaa877234655e27b Mon Sep 17 00:00:00 2001 From: Nathaniel deVelder Date: Fri, 27 Jan 2023 16:24:32 -0700 Subject: [PATCH 022/224] Removed duplicate pitch assignment and removed MinPitch mods for AWC --- ROSCO/src/Controllers.f90 | 8 ++++++-- setup.py | 4 +++- 2 files changed, 9 insertions(+), 3 deletions(-) diff --git a/ROSCO/src/Controllers.f90 b/ROSCO/src/Controllers.f90 index 70c04200..80babd2c 100644 --- a/ROSCO/src/Controllers.f90 +++ b/ROSCO/src/Controllers.f90 @@ -130,6 +130,11 @@ SUBROUTINE PitchControl(avrSWAP, CntrPar, LocalVar, objInst, DebugVar, ErrVar) ! Compute the AWC pitch settings LocalVar%AWC_complexangle = 0.0D0 + + IF (CntrPar%AWC_NumModes > 0) THEN + LocalVar%PC_MinPit = CntrPar%PC_MinPit + ENDIF + DO Imode = 1,CntrPar%AWC_NumModes clockang = CntrPar%AWC_clockangle(Imode)*PI/180.0_DbKi AWC_angle(1) = CntrPar%AWC_omega(Imode) * LocalVar%Time - CntrPar%AWC_n(Imode) * (LocalVar%Azimuth + phi1 + clockang) @@ -138,12 +143,11 @@ SUBROUTINE PitchControl(avrSWAP, CntrPar, LocalVar, objInst, DebugVar, ErrVar) ! Add the forcing contribution to LocalVar%AWC_complexangle DO K = 1,LocalVar%NumBl ! Loop through all blades LocalVar%AWC_complexangle(K) = LocalVar%AWC_complexangle(K) + CntrPar%AWC_amp(Imode) * EXP(complexI * (AWC_angle(K))) - LocalVar%PitCom(K) = LocalVar%PitCom(K) + REAL(LocalVar%AWC_complexangle(K)) END DO END DO DO K = 1,LocalVar%NumBl ! Loop through all blades, apply AWC_angle - LocalVar%PitCom(K) = LocalVar%PitCom(K) + REAL(LocalVar%AWC_complexangle(K)) + LocalVar%PitCom(K) = LocalVar%PitCom(K) + REAL(LocalVar%AWC_complexangle(K)) END DO ! Place pitch actuator here, so it can be used with or without open-loop diff --git a/setup.py b/setup.py index ee681647..8541e6f8 100644 --- a/setup.py +++ b/setup.py @@ -52,7 +52,9 @@ # For the CMake Extensions -this_directory = os.path.abspath(os.path.dirname(__file__)) +# this_directory = os.path.abspath(os.path.dirname(__file__)) +this_directory = "/pscratch/ndeveld/awc/ROSCO" + class CMakeExtension(Extension): def __init__(self, name, sourcedir='', **kwa): From 3155b63ddce3a36f524932922a813c5cfc61dfe0 Mon Sep 17 00:00:00 2001 From: dzalkind <65573423+dzalkind@users.noreply.github.com> Date: Thu, 2 Feb 2023 15:08:14 -0700 Subject: [PATCH 023/224] Add script for updating DISCON versions (#214) * Allow PA_Mode 1 * Add update_discon_version function * Add update_rosco_discons to testing, add example for updating version * Fix tuning_yaml name in example_19 --- Examples/example_19.py | 29 +++++ Examples/example_inputs/DISCON_v2.2.0.IN | 119 ++++++++++++++++++ Examples/run_examples.py | 11 +- .../ofTools/fast_io/update_discons.py | 28 +---- ROSCO_toolbox/tune.py | 88 +++++++++++++ ROSCO_toolbox/utilities.py | 10 ++ 6 files changed, 259 insertions(+), 26 deletions(-) create mode 100644 Examples/example_19.py create mode 100644 Examples/example_inputs/DISCON_v2.2.0.IN create mode 100644 ROSCO_toolbox/tune.py diff --git a/Examples/example_19.py b/Examples/example_19.py new file mode 100644 index 00000000..fbbe67d1 --- /dev/null +++ b/Examples/example_19.py @@ -0,0 +1,29 @@ +''' +----------- XX_update_discon_version ----------------- +Test and demonstrate update_discon_version() function for converting an old ROSCO input +to the current version +''' + +import os +from ROSCO_toolbox.tune import update_discon_version + +this_dir = os.path.dirname(os.path.abspath(__file__)) +rosco_dir = os.path.dirname(this_dir) + + +def main(): + + old_discon_filename = os.path.join(this_dir,'example_inputs','DISCON_v2.2.0.IN') # An IEA-15MW input + + # Tuning yaml can be anything, does not have to correspond to old discon + tuning_yaml = os.path.join(rosco_dir,'Tune_Cases','NREL5MW.yaml') # dummy for now + update_discon_version( + old_discon_filename, + tuning_yaml, + os.path.join(this_dir,'examples_out','18_UPDATED_DISCON.IN') + ) + + + +if __name__ == "__main__": + main() \ No newline at end of file diff --git a/Examples/example_inputs/DISCON_v2.2.0.IN b/Examples/example_inputs/DISCON_v2.2.0.IN new file mode 100644 index 00000000..81cbc148 --- /dev/null +++ b/Examples/example_inputs/DISCON_v2.2.0.IN @@ -0,0 +1,119 @@ +! Controller parameter input file for the IEA-15-240-RWT wind turbine +! - File written using ROSCO Controller tuning logic on 02/25/20 + +!------- 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 ------------------------------------------------- +2 ! F_LPFType - {1: first-order low-pass filter, 2: second-order low-pass filter}, [rad/s] (currently filters generator speed and pitch control signals +2 ! F_NotchType - Notch on the measured generator speed and/or tower fore-aft motion (for floating) {0: disable, 1: generator speed, 2: tower-top fore-aft motion, 3: generator speed and tower-top fore-aft motion} +0 ! IPC_ControlMode - Turn Individual Pitch Control (IPC) for fatigue load reductions (pitch contribution) {0: off, 1: 1P reductions, 2: 1P+2P reductions} +1 ! 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: Immersion and Invariance Estimator, 2: Extended Kalman Filter} +1 ! PS_Mode - Pitch saturation mode {0: no pitch saturation, 1: implement pitch saturation} +0 ! SD_Mode - Shutdown mode {0: no shutdown procedure, 1: pitch to max pitch at shutdown} +0 ! Fl_Mode - Floating specific feedback mode {0: no nacelle velocity feedback, 1: nacelle velocity feedback} +0 ! Flp_Mode - Flap control mode {0: no flap control, 1: steady state flap angle, 2: Proportional flap control} + +!------- FILTERS ---------------------------------------------------------- +1.00810 ! F_LPFCornerFreq - Corner frequency (-3dB point) in the low-pass filters, [rad/s] +0.70000 ! F_LPFDamping - Damping coefficient [used only when F_FilterType = 2] +3.35500 ! F_NotchCornerFreq - Natural frequency of the notch filter, [rad/s] +0.00000 0.25000 ! F_NotchBetaNumDen - Two notch damping values (numerator and denominator, resp) - determines the width and depth of the notch, [-] +0.628320000000 ! F_SSCornerFreq - Corner frequency (-3dB point) in the first order low pass filter for the setpoint smoother, [rad/s]. +0.21300 1.00000 ! F_FlCornerFreq - Natural frequency and damping in the second order low pass filter of the tower-top fore-aft motion for floating feedback control [rad/s, -]. +1.16240 1.00000 ! F_FlpCornerFreq - Corner frequency and damping in the second order low pass filter of the blade root bending moment for flap control [rad/s, -]. + +!------- BLADE PITCH CONTROL ---------------------------------------------- +28 ! PC_GS_n - Amount of gain-scheduling table entries +0.063278 0.090539 0.112201 0.130892 0.147682 0.163130 0.177562 0.191194 0.204189 0.216578 0.228470 0.240017 0.251275 0.262033 0.272673 0.282965 0.293075 0.302964 0.312677 0.322161 0.331649 0.340690 0.349958 0.358737 0.367513 0.376528 0.384789 0.393240 ! PC_GS_angles - Gain-schedule table: pitch angles +-1.222765 -1.056462 -0.919886 -0.805720 -0.708866 -0.625663 -0.553417 -0.490096 -0.434142 -0.384341 -0.339730 -0.299539 -0.263141 -0.230024 -0.199764 -0.172005 -0.146450 -0.122847 -0.100980 -0.080665 -0.061742 -0.044072 -0.027535 -0.012026 0.002549 0.016271 0.029213 0.041440 ! PC_GS_KP - Gain-schedule table: pitch controller kp gains +-0.127742 -0.115205 -0.104909 -0.096302 -0.089000 -0.082728 -0.077281 -0.072508 -0.068289 -0.064535 -0.061172 -0.058142 -0.055398 -0.052901 -0.050620 -0.048527 -0.046601 -0.044821 -0.043173 -0.041641 -0.040215 -0.038883 -0.037636 -0.036467 -0.035368 -0.034333 -0.033358 -0.032436 ! 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 ! 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 ! PC_GS_TF - Gain-schedule table: pitch controller tf gains (derivative filter) +1.570800000000 ! PC_MaxPit - Maximum physical pitch limit, [rad]. +0.000000000000 ! PC_MinPit - Minimum physical pitch limit, [rad]. +0.034900000000 ! PC_MaxRat - Maximum pitch rate (in absolute value) in pitch controller, [rad/s]. +-0.03490000000 ! PC_MinRat - Minimum pitch rate (in absolute value) in pitch controller, [rad/s]. +0.791680000000 ! PC_RefSpd - Desired (reference) HSS speed for pitch controller, [rad/s]. +0.000000000000 ! PC_FinePit - Record 5: Below-rated pitch angle set-point, [rad] +0.017450000000 ! PC_Switch - Angle above lowest minimum pitch angle for switch, [rad] + +!------- 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 ------------------------------------------------ +96.55000000000 ! VS_GenEff - Generator efficiency mechanical power -> electrical power, [should match the efficiency defined in the generator properties!], [%] +19624046.66639 ! VS_ArSatTq - Above rated generator torque PI control saturation, [Nm] +4500000.000000 ! VS_MaxRat - Maximum torque rate (in absolute value) in torque controller, [Nm/s]. +21586451.33303 ! VS_MaxTq - Maximum generator torque in Region 3 (HSS side), [Nm]. +0.000000000000 ! VS_MinTq - Minimum generator (HSS side), [Nm]. +0.523600000000 ! VS_MinOMSpd - Optimal mode minimum speed, cut-in speed towards optimal mode gain path, [rad/s] +34505815.52476 ! VS_Rgn2K - Generator torque constant in Region 2 (HSS side), [N-m/(rad/s)^2] +15000000.00000 ! VS_RtPwr - Wind turbine rated power [W] +19624046.66639 ! VS_RtTq - Rated torque, [Nm]. +0.791680000000 ! VS_RefSpd - Rated generator speed [rad/s] +1 ! VS_n - Number of generator PI torque controller gains +-50437958.66505 ! 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) +-4588245.18720 ! VS_KI - Integral gain for generator PI torque controller [1/rad Nm]. (Only used in the transitional 2.5 region if VS_ControlMode =/ 2) +9.00 ! VS_TSRopt - Power-maximizing region 2 tip-speed-ratio [rad]. + +!------- SETPOINT SMOOTHER --------------------------------------------- +1.00000 ! SS_VSGain - Variable speed torque controller setpoint smoother gain, [-]. +0.00100 ! SS_PCGain - Collective pitch controller setpoint smoother gain, [-]. + +!------- WIND SPEED ESTIMATOR --------------------------------------------- +120.000 ! WE_BladeRadius - Blade length (distance from hub center to blade tip), [m] +1 ! 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] +1.0 ! WE_GearboxRatio - Gearbox ratio [>=1], [-] +318628138.00000 ! 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.IEA15MW.txt" ! PerfFileName - File containing rotor performance tables (Cp,Ct,Cq) +104 48 ! PerfTableSize - Size of rotor performance tables, first number refers to number of blade pitch angles, second number referse to number of tip-speed ratios +44 ! WE_FOPoles_N - Number of first-order system poles used in EKF +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.24 11.74 12.24 12.74 13.24 13.74 14.24 14.74 15.24 15.74 16.24 16.74 17.24 17.74 18.24 18.74 19.24 19.74 20.24 20.74 21.24 21.74 22.24 22.74 23.24 23.74 24.24 24.74 ! WE_FOPoles_v - Wind speeds corresponding to first-order system poles [m/s] +-0.02334364 -0.02723425 -0.03112486 -0.03501546 -0.03890607 -0.04279668 -0.04668728 -0.05057789 -0.05446850 -0.05835911 -0.06224971 -0.06614032 -0.07003093 -0.07392153 -0.07781214 -0.08170275 -0.05441825 -0.05758074 -0.06474714 -0.07383682 -0.08430904 -0.09581400 -0.10815415 -0.12121919 -0.13495759 -0.14915715 -0.16379718 -0.17904114 -0.19494603 -0.21082316 -0.22752972 -0.24440216 -0.26178793 -0.27954029 -0.29769427 -0.31606508 -0.33525667 -0.35396333 -0.37406865 -0.39341852 -0.41345400 -0.43495515 -0.45460302 -0.47551894 ! 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] + +!------- MINIMUM PITCH SATURATION ------------------------------------------- +44 ! PS_BldPitchMin_N - Number of values in minimum blade pitch lookup table (should equal number of values in PS_WindSpeeds and PS_BldPitchMin) +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.24 11.74 12.24 12.74 13.24 13.74 14.24 14.74 15.24 15.74 16.24 16.74 17.24 17.74 18.24 18.74 19.24 19.74 20.24 20.74 21.24 21.74 22.24 22.74 23.24 23.74 24.24 24.74 ! PS_WindSpeeds - Wind speeds corresponding to minimum blade pitch angles [m/s] +0.06108652 0.06108652 0.06108652 0.05672320 0.04799655 0.03926991 0.02617994 0.01308997 0.00000000 0.00000000 0.00000000 0.00000000 0.00000000 0.00000000 0.00000000 0.00000000 0.00000000 0.00000000 0.00000000 0.00000000 0.00000000 0.00000000 0.00000000 0.00000000 0.00000000 0.00000000 0.00000000 0.00000000 0.00000000 0.00000000 0.00000000 0.00000000 0.00000000 0.00000000 0.00000000 0.00000000 0.00000000 0.00000000 0.00000000 0.00000000 0.00000000 0.00000000 0.00000000 0.00000000 ! PS_BldPitchMin - Minimum blade pitch angles [rad] + +!------- SHUTDOWN ----------------------------------------------------------- +0.393240000000 ! SD_MaxPit - Maximum blade pitch angle to initiate shutdown, [rad] +0.418880000000 ! SD_CornerFreq - Cutoff Frequency for first order low-pass filter for blade pitch angle, [rad/s] + +!------- Floating ----------------------------------------------------------- +-9.32196000000 ! Fl_Kp - Nacelle velocity proportional feedback gain [s] + +!------- FLAP ACTUATION ----------------------------------------------------- +0.000000000000 ! Flp_Angle - Initial or steady state flap angle [rad] +0.00000000e+00 ! Flp_Kp - Blade root bending moment proportional gain for flap control [s] +0.00000000e+00 ! Flp_Ki - Flap displacement integral gain for flap control [s] +0.000000000000 ! Flp_MaxPit - Maximum (and minimum) flap pitch angle [rad] \ No newline at end of file diff --git a/Examples/run_examples.py b/Examples/run_examples.py index fc570081..9486b3ee 100644 --- a/Examples/run_examples.py +++ b/Examples/run_examples.py @@ -22,16 +22,25 @@ 'example_16', 'example_17', # NJA: only runs on unix in CI 'example_18', + 'example_19', + 'update_rosco_discons', ] def execute_script(fscript): examples_dir = os.path.dirname(os.path.realpath(__file__)) + test_case_dir = os.path.realpath(os.path.join(os.path.dirname(os.path.realpath(__file__)),'../Test_Cases')) # Go to location due to relative path use for airfoil files print("\n\n") print("NOW RUNNING:", fscript) print() - fullpath = os.path.join(examples_dir, fscript + ".py") + + if fscript in ['update_rosco_discons']: + run_dir = test_case_dir + else: + run_dir = examples_dir + + fullpath = os.path.join(run_dir, fscript + ".py") basepath = os.path.dirname(os.path.realpath(fullpath)) os.chdir(basepath) diff --git a/ROSCO_toolbox/ofTools/fast_io/update_discons.py b/ROSCO_toolbox/ofTools/fast_io/update_discons.py index 901a953a..6c8b6271 100644 --- a/ROSCO_toolbox/ofTools/fast_io/update_discons.py +++ b/ROSCO_toolbox/ofTools/fast_io/update_discons.py @@ -1,37 +1,15 @@ import os # ROSCO toolbox modules -from ROSCO_toolbox import controller as ROSCO_controller -from ROSCO_toolbox import turbine as ROSCO_turbine + from ROSCO_toolbox.utilities import write_DISCON -from ROSCO_toolbox.inputs.validation import load_rosco_yaml +from ROSCO_toolbox.tune import yaml_to_objs def update_discons(tune_to_test_map): # Update a set of discon files # Input is a dict: each key is the tuning yaml and each value is the discon or list of discons for tuning_yaml in tune_to_test_map: - # Load yaml file - inps = load_rosco_yaml(tuning_yaml) - path_params = inps['path_params'] - turbine_params = inps['turbine_params'] - controller_params = inps['controller_params'] - - # Instantiate turbine, controller, and file processing classes - turbine = ROSCO_turbine.Turbine(turbine_params) - controller = ROSCO_controller.Controller(controller_params) - - # Load turbine data from OpenFAST and rotor performance text file - yaml_dir = os.path.dirname(tuning_yaml) # files relative to tuning yaml - turbine.load_from_fast( - path_params['FAST_InputFile'], - os.path.join(yaml_dir,path_params['FAST_directory']), - dev_branch=True, - rot_source='txt', - txt_filename=os.path.join(yaml_dir,path_params['FAST_directory'],path_params['rotor_performance_filename']) - ) - - # Tune controller - controller.tune_controller(turbine) + controller, turbine, path_params = yaml_to_objs(tuning_yaml) # Write parameter input file if not isinstance(tune_to_test_map[tuning_yaml],list): diff --git a/ROSCO_toolbox/tune.py b/ROSCO_toolbox/tune.py new file mode 100644 index 00000000..d5f94a25 --- /dev/null +++ b/ROSCO_toolbox/tune.py @@ -0,0 +1,88 @@ +# Copyright 2019 NREL + +# Licensed under the Apache License, Version 2.0 (the "License"); you may not use +# this file except in compliance with the License. You may obtain a copy of the +# License at http://www.apache.org/licenses/LICENSE-2.0 + +# Unless required by applicable law or agreed to in writing, software distributed +# under the License is distributed on an "AS IS" BASIS, WITHOUT WARRANTIES OR +# CONDITIONS OF ANY KIND, either express or implied. See the License for the +# specific language governing permissions and limitations under the License. + +import os +from ROSCO_toolbox import controller as ROSCO_controller +from ROSCO_toolbox import turbine as ROSCO_turbine +from ROSCO_toolbox.inputs.validation import load_rosco_yaml +from ROSCO_toolbox.utilities import read_DISCON, write_DISCON, DISCON_dict + + +def yaml_to_objs(tuning_yaml): + # Load yaml and return controller, turbine objects + # Basically, tune a whole controller! + + # Load yaml file + inps = load_rosco_yaml(tuning_yaml) + path_params = inps['path_params'] + turbine_params = inps['turbine_params'] + controller_params = inps['controller_params'] + + # Instantiate turbine, controller, and file processing classes + turbine = ROSCO_turbine.Turbine(turbine_params) + controller = ROSCO_controller.Controller(controller_params) + + # Load turbine data from OpenFAST and rotor performance text file + yaml_dir = os.path.dirname(tuning_yaml) # files relative to tuning yaml + turbine.load_from_fast( + path_params['FAST_InputFile'], + os.path.join(yaml_dir,path_params['FAST_directory']), + dev_branch=True, + rot_source='txt', + txt_filename=os.path.join(yaml_dir,path_params['FAST_directory'],path_params['rotor_performance_filename']) + ) + + # Tune controller + controller.tune_controller(turbine) + + return controller, turbine, path_params + +def update_discon_version(file,tuning_yaml,new_discon_filename): + ''''''''' + This function will take a DISCON input from a previous version of ROSCO and conver it to this version + It will not be 100%, requires a check, but still saves time + + ''' + + # Use new defaults for these inputs for various reasons + exclude_list = [ + 'Y_ErrThresh', # translated from float to list of floats in v2.6 + 'WE_CP', + ] + + # Read original DISCON + discon_vt = read_DISCON(file) + + # Tune dummy controller to get objects + controller, turbine, _ = yaml_to_objs(tuning_yaml) + + # Load default inputs + discon_defaults = DISCON_dict(turbine,controller) + + # A simple update doesn't handle type changes + new_discon = {} + for param in discon_defaults: + # If the value is in the original DISCON and not excluded, use the original + if (param in discon_vt) and (param not in exclude_list): + new_discon[param] = discon_vt[param] + + # Otherwise, use the new default + else: + new_discon[param] = discon_defaults[param] + + # Make the DISCON + write_DISCON( + turbine, + controller, + new_discon_filename, + rosco_vt = new_discon, + ) + diff --git a/ROSCO_toolbox/utilities.py b/ROSCO_toolbox/utilities.py index 055a76f8..04cf98f3 100644 --- a/ROSCO_toolbox/utilities.py +++ b/ROSCO_toolbox/utilities.py @@ -28,6 +28,8 @@ import subprocess import ROSCO_toolbox +from wisdem.inputs import load_yaml + # Some useful constants now = datetime.datetime.now() pi = np.pi @@ -381,6 +383,14 @@ def DISCON_dict(turbine, controller, txt_filename=None): Name of rotor performance filename ''' DISCON_dict = {} + + # Populate with available defaults + input_schema = load_yaml(os.path.join(os.path.dirname(__file__),'inputs/toolbox_schema.yaml')) + discon_props = input_schema['properties']['controller_params']['properties']['DISCON']['properties'] + for prop in discon_props: + if 'default' in discon_props[prop]: + DISCON_dict[prop] = discon_props[prop]['default'] + # ------- DEBUG ------- DISCON_dict['LoggingLevel'] = int(controller.LoggingLevel) # ------- CONTROLLER FLAGS ------- From 0c0e466a82638e929e2aa8f7b5e4013c77d09cfe Mon Sep 17 00:00:00 2001 From: Nathaniel deVelder Date: Fri, 3 Feb 2023 15:25:02 -0700 Subject: [PATCH 024/224] Fixes to readsetparams and awc location --- ROSCO/src/Controllers.f90 | 4 +++- ROSCO/src/ReadSetParameters.f90 | 1 + 2 files changed, 4 insertions(+), 1 deletion(-) diff --git a/ROSCO/src/Controllers.f90 b/ROSCO/src/Controllers.f90 index 80babd2c..78c8b7e6 100644 --- a/ROSCO/src/Controllers.f90 +++ b/ROSCO/src/Controllers.f90 @@ -147,7 +147,7 @@ SUBROUTINE PitchControl(avrSWAP, CntrPar, LocalVar, objInst, DebugVar, ErrVar) END DO DO K = 1,LocalVar%NumBl ! Loop through all blades, apply AWC_angle - LocalVar%PitCom(K) = LocalVar%PitCom(K) + REAL(LocalVar%AWC_complexangle(K)) + LocalVar%PitCom(K) = LocalVar%PitCom(K) + REAL(LocalVar%AWC_complexangle(K)) END DO ! Place pitch actuator here, so it can be used with or without open-loop @@ -179,6 +179,8 @@ SUBROUTINE PitchControl(avrSWAP, CntrPar, LocalVar, objInst, DebugVar, ErrVar) END DO END IF + !WRITE (*,*) 'PITCH ANGLE PRE AWC = ',REAL(LocalVar%PitComAct(1)) + ! Command the pitch demanded from the last ! call to the controller (See Appendix A of Bladed User's Guide): ! AWC added here as well diff --git a/ROSCO/src/ReadSetParameters.f90 b/ROSCO/src/ReadSetParameters.f90 index 1007952e..6a8041ac 100644 --- a/ROSCO/src/ReadSetParameters.f90 +++ b/ROSCO/src/ReadSetParameters.f90 @@ -420,6 +420,7 @@ SUBROUTINE ReadControlParameterFileSub(CntrPar, zmqVar, accINFILE, accINFILE_siz CALL ParseAry( UnControllerParameters,CurLine,'AWC_omega', CntrPar%AWC_omega, CntrPar%AWC_NumModes, accINFILE(1), ErrVar) CALL ParseAry( UnControllerParameters,CurLine,'AWC_amp', CntrPar%AWC_amp, CntrPar%AWC_NumModes, accINFILE(1), ErrVar) CALL ParseAry( UnControllerParameters,CurLine,'AWC_clockangle',CntrPar%AWC_clockangle,CntrPar%AWC_NumModes, accINFILE(1), ErrVar) + CALL ReadEmptyLine(UnControllerParameters,CurLine) !------------ External control interface ------------ CALL ReadEmptyLine(UnControllerParameters,CurLine) From 20c9c9d1d410462610ae4b402aeee5993b1f62f1 Mon Sep 17 00:00:00 2001 From: Nathaniel deVelder Date: Fri, 3 Feb 2023 15:39:37 -0700 Subject: [PATCH 025/224] Adding NREL 2.8 127 for AWC testing --- .../Airfoils/NREL-2p8-127_AF00_Coords.txt | 208 ++++++++++++++ .../Airfoils/NREL-2p8-127_AF01_Coords.txt | 208 ++++++++++++++ .../Airfoils/NREL-2p8-127_AF02_Coords.txt | 208 ++++++++++++++ .../Airfoils/NREL-2p8-127_AF03_Coords.txt | 208 ++++++++++++++ .../Airfoils/NREL-2p8-127_AF04_Coords.txt | 208 ++++++++++++++ .../Airfoils/NREL-2p8-127_AF05_Coords.txt | 208 ++++++++++++++ .../Airfoils/NREL-2p8-127_AF06_Coords.txt | 208 ++++++++++++++ .../Airfoils/NREL-2p8-127_AF07_Coords.txt | 208 ++++++++++++++ .../Airfoils/NREL-2p8-127_AF08_Coords.txt | 208 ++++++++++++++ .../Airfoils/NREL-2p8-127_AF09_Coords.txt | 208 ++++++++++++++ .../Airfoils/NREL-2p8-127_AF10_Coords.txt | 208 ++++++++++++++ .../Airfoils/NREL-2p8-127_AF11_Coords.txt | 208 ++++++++++++++ .../Airfoils/NREL-2p8-127_AF12_Coords.txt | 208 ++++++++++++++ .../Airfoils/NREL-2p8-127_AF13_Coords.txt | 208 ++++++++++++++ .../Airfoils/NREL-2p8-127_AF14_Coords.txt | 208 ++++++++++++++ .../Airfoils/NREL-2p8-127_AF15_Coords.txt | 208 ++++++++++++++ .../Airfoils/NREL-2p8-127_AF16_Coords.txt | 208 ++++++++++++++ .../Airfoils/NREL-2p8-127_AF17_Coords.txt | 208 ++++++++++++++ .../Airfoils/NREL-2p8-127_AF18_Coords.txt | 208 ++++++++++++++ .../Airfoils/NREL-2p8-127_AF19_Coords.txt | 208 ++++++++++++++ .../Airfoils/NREL-2p8-127_AF20_Coords.txt | 208 ++++++++++++++ .../Airfoils/NREL-2p8-127_AF21_Coords.txt | 208 ++++++++++++++ .../Airfoils/NREL-2p8-127_AF22_Coords.txt | 208 ++++++++++++++ .../Airfoils/NREL-2p8-127_AF23_Coords.txt | 208 ++++++++++++++ .../Airfoils/NREL-2p8-127_AF24_Coords.txt | 208 ++++++++++++++ .../Airfoils/NREL-2p8-127_AF25_Coords.txt | 208 ++++++++++++++ .../Airfoils/NREL-2p8-127_AF26_Coords.txt | 208 ++++++++++++++ .../Airfoils/NREL-2p8-127_AF27_Coords.txt | 208 ++++++++++++++ .../Airfoils/NREL-2p8-127_AF28_Coords.txt | 208 ++++++++++++++ .../Airfoils/NREL-2p8-127_AF29_Coords.txt | 208 ++++++++++++++ .../NREL-2p8-127_AeroDyn15_Polar_00.dat | 254 ++++++++++++++++++ .../NREL-2p8-127_AeroDyn15_Polar_01.dat | 254 ++++++++++++++++++ .../NREL-2p8-127_AeroDyn15_Polar_02.dat | 254 ++++++++++++++++++ .../NREL-2p8-127_AeroDyn15_Polar_03.dat | 254 ++++++++++++++++++ .../NREL-2p8-127_AeroDyn15_Polar_04.dat | 254 ++++++++++++++++++ .../NREL-2p8-127_AeroDyn15_Polar_05.dat | 254 ++++++++++++++++++ .../NREL-2p8-127_AeroDyn15_Polar_06.dat | 254 ++++++++++++++++++ .../NREL-2p8-127_AeroDyn15_Polar_07.dat | 254 ++++++++++++++++++ .../NREL-2p8-127_AeroDyn15_Polar_08.dat | 254 ++++++++++++++++++ .../NREL-2p8-127_AeroDyn15_Polar_09.dat | 254 ++++++++++++++++++ .../NREL-2p8-127_AeroDyn15_Polar_10.dat | 254 ++++++++++++++++++ .../NREL-2p8-127_AeroDyn15_Polar_11.dat | 254 ++++++++++++++++++ .../NREL-2p8-127_AeroDyn15_Polar_12.dat | 254 ++++++++++++++++++ .../NREL-2p8-127_AeroDyn15_Polar_13.dat | 254 ++++++++++++++++++ .../NREL-2p8-127_AeroDyn15_Polar_14.dat | 254 ++++++++++++++++++ .../NREL-2p8-127_AeroDyn15_Polar_15.dat | 254 ++++++++++++++++++ .../NREL-2p8-127_AeroDyn15_Polar_16.dat | 254 ++++++++++++++++++ .../NREL-2p8-127_AeroDyn15_Polar_17.dat | 254 ++++++++++++++++++ .../NREL-2p8-127_AeroDyn15_Polar_18.dat | 254 ++++++++++++++++++ .../NREL-2p8-127_AeroDyn15_Polar_19.dat | 254 ++++++++++++++++++ .../NREL-2p8-127_AeroDyn15_Polar_20.dat | 254 ++++++++++++++++++ .../NREL-2p8-127_AeroDyn15_Polar_21.dat | 254 ++++++++++++++++++ .../NREL-2p8-127_AeroDyn15_Polar_22.dat | 254 ++++++++++++++++++ .../NREL-2p8-127_AeroDyn15_Polar_23.dat | 254 ++++++++++++++++++ .../NREL-2p8-127_AeroDyn15_Polar_24.dat | 254 ++++++++++++++++++ .../NREL-2p8-127_AeroDyn15_Polar_25.dat | 254 ++++++++++++++++++ .../NREL-2p8-127_AeroDyn15_Polar_26.dat | 254 ++++++++++++++++++ .../NREL-2p8-127_AeroDyn15_Polar_27.dat | 254 ++++++++++++++++++ .../NREL-2p8-127_AeroDyn15_Polar_28.dat | 254 ++++++++++++++++++ .../NREL-2p8-127_AeroDyn15_Polar_29.dat | 254 ++++++++++++++++++ Test_Cases/NREL_2p8_127/NREL-2.8-127.xlsx | Bin 0 -> 14107 bytes .../NREL_2p8_127/NREL-2.8-127_pitch-speed.csv | 31 +++ Test_Cases/NREL_2p8_127/NREL-2p8-127.fst | 71 +++++ .../NREL_2p8_127/NREL-2p8-127_AeroDyn15.dat | 134 +++++++++ .../NREL-2p8-127_AeroDyn15_blade.dat | 36 +++ .../NREL_2p8_127/NREL-2p8-127_Cp_Ct_Cq.txt | 111 ++++++++ .../NREL_2p8_127/NREL-2p8-127_DISCON.IN | 156 +++++++++++ .../NREL_2p8_127/NREL-2p8-127_ElastoDyn.dat | 210 +++++++++++++++ .../NREL-2p8-127_ElastoDyn_blade.dat | 62 +++++ .../NREL-2p8-127_ElastoDyn_tower.dat | 50 ++++ .../NREL_2p8_127/NREL-2p8-127_InflowFile.dat | 57 ++++ .../NREL_2p8_127/NREL-2p8-127_ServoDyn.dat | 110 ++++++++ 72 files changed, 14888 insertions(+) create mode 100644 Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF00_Coords.txt create mode 100644 Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF01_Coords.txt create mode 100644 Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF02_Coords.txt create mode 100644 Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF03_Coords.txt create mode 100644 Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF04_Coords.txt create mode 100644 Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF05_Coords.txt create mode 100644 Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF06_Coords.txt create mode 100644 Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF07_Coords.txt create mode 100644 Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF08_Coords.txt create mode 100644 Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF09_Coords.txt create mode 100644 Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF10_Coords.txt create mode 100644 Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF11_Coords.txt create mode 100644 Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF12_Coords.txt create mode 100644 Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF13_Coords.txt create mode 100644 Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF14_Coords.txt create mode 100644 Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF15_Coords.txt create mode 100644 Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF16_Coords.txt create mode 100644 Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF17_Coords.txt create mode 100644 Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF18_Coords.txt create mode 100644 Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF19_Coords.txt create mode 100644 Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF20_Coords.txt create mode 100644 Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF21_Coords.txt create mode 100644 Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF22_Coords.txt create mode 100644 Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF23_Coords.txt create mode 100644 Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF24_Coords.txt create mode 100644 Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF25_Coords.txt create mode 100644 Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF26_Coords.txt create mode 100644 Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF27_Coords.txt create mode 100644 Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF28_Coords.txt create mode 100644 Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF29_Coords.txt create mode 100644 Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_00.dat create mode 100644 Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_01.dat create mode 100644 Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_02.dat create mode 100644 Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_03.dat create mode 100644 Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_04.dat create mode 100644 Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_05.dat create mode 100644 Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_06.dat create mode 100644 Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_07.dat create mode 100644 Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_08.dat create mode 100644 Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_09.dat create mode 100644 Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_10.dat create mode 100644 Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_11.dat create mode 100644 Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_12.dat create mode 100644 Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_13.dat create mode 100644 Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_14.dat create mode 100644 Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_15.dat create mode 100644 Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_16.dat create mode 100644 Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_17.dat create mode 100644 Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_18.dat create mode 100644 Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_19.dat create mode 100644 Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_20.dat create mode 100644 Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_21.dat create mode 100644 Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_22.dat create mode 100644 Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_23.dat create mode 100644 Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_24.dat create mode 100644 Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_25.dat create mode 100644 Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_26.dat create mode 100644 Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_27.dat create mode 100644 Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_28.dat create mode 100644 Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_29.dat create mode 100644 Test_Cases/NREL_2p8_127/NREL-2.8-127.xlsx create mode 100644 Test_Cases/NREL_2p8_127/NREL-2.8-127_pitch-speed.csv create mode 100644 Test_Cases/NREL_2p8_127/NREL-2p8-127.fst create mode 100644 Test_Cases/NREL_2p8_127/NREL-2p8-127_AeroDyn15.dat create mode 100644 Test_Cases/NREL_2p8_127/NREL-2p8-127_AeroDyn15_blade.dat create mode 100644 Test_Cases/NREL_2p8_127/NREL-2p8-127_Cp_Ct_Cq.txt create mode 100644 Test_Cases/NREL_2p8_127/NREL-2p8-127_DISCON.IN create mode 100644 Test_Cases/NREL_2p8_127/NREL-2p8-127_ElastoDyn.dat create mode 100644 Test_Cases/NREL_2p8_127/NREL-2p8-127_ElastoDyn_blade.dat create mode 100644 Test_Cases/NREL_2p8_127/NREL-2p8-127_ElastoDyn_tower.dat create mode 100644 Test_Cases/NREL_2p8_127/NREL-2p8-127_InflowFile.dat create mode 100644 Test_Cases/NREL_2p8_127/NREL-2p8-127_ServoDyn.dat diff --git a/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF00_Coords.txt b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF00_Coords.txt new file mode 100644 index 00000000..e9309e03 --- /dev/null +++ b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF00_Coords.txt @@ -0,0 +1,208 @@ + 201 NumCoords ! The number of coordinates in the airfoil shape file (including an extra coordinate for airfoil reference). Set to zero if coordinates not included. +! ......... x-y coordinates are next if NumCoords > 0 ............. +! x-y coordinate of airfoil reference +! x/c y/c + 0.500000 0 +! coordinates of airfoil shape +! interpolation to 200 points +! x/c y/c + 1.00000000000000e+00 1.39471767468535e-15 + 9.99492456366675e-01 -2.24148318097192e-02 + 9.97998442938042e-01 -4.47793322876220e-02 + 9.95467925285309e-01 -6.70365581798988e-02 + 9.91981297584349e-01 -8.91473650534134e-02 + 9.87535715129057e-01 -1.11060278052329e-01 + 9.82077318711035e-01 -1.32710580192188e-01 + 9.75645752125599e-01 -1.54053421230182e-01 + 9.68327814997901e-01 -1.75062933826036e-01 + 9.60169311985103e-01 -1.95709072524484e-01 + 9.51019761347344e-01 -2.15876183412258e-01 + 9.41032965384679e-01 -2.35574562290692e-01 + 9.30228135178293e-01 -2.54760790502087e-01 + 9.18600973249388e-01 -2.73373623585437e-01 + 9.06286773024904e-01 -2.91445285668231e-01 + 8.93185468322794e-01 -3.08852284793353e-01 + 8.79429131687551e-01 -3.25629671028512e-01 + 8.65020010482894e-01 -3.41723774803256e-01 + 8.50001183978561e-01 -3.57112177867390e-01 + 8.34409947013148e-01 -3.71770913166281e-01 + 8.18263641617925e-01 -3.85648552858056e-01 + 8.01628456968450e-01 -3.98748400170390e-01 + 7.84595497003635e-01 -4.11125308634395e-01 + 7.67122879759481e-01 -4.22652791316593e-01 + 7.49310431319132e-01 -4.33396610986265e-01 + 7.31192318835036e-01 -4.43343955969101e-01 + 7.12809122212147e-01 -4.52489087671710e-01 + 6.94192882766294e-01 -4.60805480273623e-01 + 6.75356426213553e-01 -4.68221413716844e-01 + 6.56401839622218e-01 -4.74887730613940e-01 + 6.37339053739694e-01 -4.80732155257960e-01 + 6.18216799132259e-01 -4.85797045327747e-01 + 5.99072127289441e-01 -4.90092245328121e-01 + 5.79920098443495e-01 -4.93529601024917e-01 + 5.60830239179689e-01 -4.96308798320980e-01 + 5.41809841204068e-01 -4.98254021026852e-01 + 5.22902255947823e-01 -4.99468302412137e-01 + 5.04138617740840e-01 -4.99969461095629e-01 + 4.85547896236042e-01 -4.99782528766859e-01 + 4.67157180742230e-01 -4.98932207272937e-01 + 4.48992436485026e-01 -4.97429938215178e-01 + 4.31090922803529e-01 -4.95199601187320e-01 + 4.13451809735344e-01 -4.92443613818918e-01 + 3.96103805194879e-01 -4.89121761104649e-01 + 3.79096627499341e-01 -4.85124024486578e-01 + 3.62407327470865e-01 -4.80659331665282e-01 + 3.46066636516655e-01 -4.75685087833417e-01 + 3.30096115507155e-01 -4.70203747355840e-01 + 3.14480352866339e-01 -4.64314583285520e-01 + 2.99254081643518e-01 -4.57980939909463e-01 + 2.84450426976392e-01 -4.51177575409728e-01 + 2.70052866033160e-01 -4.43988939168408e-01 + 2.56066550501318e-01 -4.36445000343028e-01 + 2.42483923277781e-01 -4.28590357469827e-01 + 2.29353790045290e-01 -4.20376016737305e-01 + 2.16603264062538e-01 -4.11943400950387e-01 + 2.04317853658681e-01 -4.03192627249739e-01 + 1.92459446608375e-01 -3.94201135001427e-01 + 1.81000889336564e-01 -3.85028191464174e-01 + 1.69975424985927e-01 -3.75644842886581e-01 + 1.59391096347033e-01 -3.66066250246720e-01 + 1.49207465402409e-01 -3.56350787229031e-01 + 1.39487797355366e-01 -3.46454046169616e-01 + 1.30120240319336e-01 -3.36494792306467e-01 + 1.21215059211584e-01 -3.26386152642893e-01 + 1.12658598266997e-01 -3.16237746353461e-01 + 1.04576031217800e-01 -3.05961432628231e-01 + 9.68117255237024e-02 -2.95688054408038e-01 + 8.94183192669232e-02 -2.85386126810182e-01 + 8.24692613312736e-02 -2.75012912186705e-01 + 7.58031535914957e-02 -2.64686382950272e-01 + 6.95265332165359e-02 -2.54344021225804e-01 + 6.36014773641337e-02 -2.44016481364265e-01 + 5.79875426758039e-02 -2.33733614688635e-01 + 5.27214572831349e-02 -2.23480055785704e-01 + 4.77407756799443e-02 -2.13293199734344e-01 + 4.30911198450984e-02 -2.03156079856565e-01 + 3.87383767680824e-02 -1.93089031734237e-01 + 3.47120078049050e-02 -1.83082592300236e-01 + 3.09831915833964e-02 -1.73156756176345e-01 + 2.73972939643108e-02 -1.63368018994347e-01 + 2.42148186237083e-02 -1.53628642008223e-01 + 2.11591799216729e-02 -1.44034525093811e-01 + 1.84468268040835e-02 -1.34516182856983e-01 + 1.59138335980001e-02 -1.25130288878497e-01 + 1.36131610235361e-02 -1.15857640369663e-01 + 1.14838295959446e-02 -1.06718459753818e-01 + 9.63946848246122e-03 -9.76879552179587e-02 + 7.95426403181202e-03 -8.87933378901162e-02 + 6.48712578142165e-03 -8.00260463587484e-02 + 5.16242415846458e-03 -7.13984274261874e-02 + 3.96141128417998e-03 -6.29131069298763e-02 + 2.94206395570219e-03 -5.45622661453796e-02 + 2.13806552335743e-03 -4.63439971542207e-02 + 1.44971764281537e-03 -3.82678090225701e-02 + 9.19962693446690e-04 -3.03318166757594e-02 + 5.13539051739693e-04 -2.25365794204782e-02 + 2.28620066730956e-04 -1.48836875697269e-02 + 7.90911911777832e-05 -7.37097402213213e-03 + 0.00000000000000e+00 0.00000000000000e+00 + 7.90677652262213e-05 7.36950623430851e-03 + 2.28464565111448e-04 1.48777524287952e-02 + 5.12873373489222e-04 2.25230881526787e-02 + 9.18597455380868e-04 3.03075781606325e-02 + 1.44666023734530e-03 3.82295855300727e-02 + 2.13316604432083e-03 4.62883932406539e-02 + 2.93360033162344e-03 5.44859437589187e-02 + 3.94803817877652e-03 6.28126278437423e-02 + 5.14351598889891e-03 7.12701576675508e-02 + 6.46190285472730e-03 7.98662577301812e-02 + 7.91902151822289e-03 8.85987369572577e-02 + 9.59444803793060e-03 9.74544221488751e-02 + 1.14235102541198e-02 1.06442996258128e-01 + 1.35337735871235e-02 1.15536956454720e-01 + 1.58224157496375e-02 1.24758221029162e-01 + 1.83235379987219e-02 1.34093489066500e-01 + 2.10204849111940e-02 1.43552196795823e-01 + 2.40367775427033e-02 1.53088940216613e-01 + 2.71877316554608e-02 1.62764372071491e-01 + 3.07399015207509e-02 1.72484170230167e-01 + 3.44190712967375e-02 1.82342411230462e-01 + 3.84042462872392e-02 1.92272935169736e-01 + 4.26949602499204e-02 2.02267606430067e-01 + 4.72829519098945e-02 2.12327253752788e-01 + 5.21982679528133e-02 2.22432953038477e-01 + 5.73926065743804e-02 2.32603305860823e-01 + 6.29241217245761e-02 2.42803072101294e-01 + 6.87643637125652e-02 2.53043124634065e-01 + 7.49396649714102e-02 2.63302631639567e-01 + 8.15067225995126e-02 2.73538864194590e-01 + 8.83465340790937e-02 2.83822725719936e-01 + 9.56069618941523e-02 2.94046380437990e-01 + 1.03242517429104e-01 3.04232736766140e-01 + 1.11181349110592e-01 3.14429033366110e-01 + 1.19600191231908e-01 3.24484491634080e-01 + 1.28332959831487e-01 3.34525491878455e-01 + 1.37529624980321e-01 3.44409800526354e-01 + 1.47054393871766e-01 3.54250702832129e-01 + 1.57068458906247e-01 3.63878030450328e-01 + 1.67434000189824e-01 3.73414748310375e-01 + 1.78267900010996e-01 3.82720355055487e-01 + 1.89470766243389e-01 3.91888095042532e-01 + 2.01116356758227e-01 4.00815766784955e-01 + 2.13142982412971e-01 4.09560128320329e-01 + 2.25647591527817e-01 4.17962490202192e-01 + 2.38508303803600e-01 4.26178518900819e-01 + 2.51815542326035e-01 4.34041451446706e-01 + 2.65513873471791e-01 4.41613730534841e-01 + 2.79625890849574e-01 4.48822548308045e-01 + 2.94122344676086e-01 4.55688297738170e-01 + 3.09025395595222e-01 4.62123018507889e-01 + 3.24322980248437e-01 4.68104987140686e-01 + 3.39961508551486e-01 4.73721797521014e-01 + 3.55970212497486e-01 4.78842188217134e-01 + 3.72330405840910e-01 4.83451204703119e-01 + 3.89018592148974e-01 4.87553971207526e-01 + 4.06028086432003e-01 4.91073750593815e-01 + 4.23330061515063e-01 4.94038626508448e-01 + 4.40892507832343e-01 4.96523552581426e-01 + 4.58722088973087e-01 4.98299627767656e-01 + 4.76781800214759e-01 4.99452452619975e-01 + 4.95047752165150e-01 4.99958293491181e-01 + 5.13494417346180e-01 4.99806115294212e-01 + 5.32095125341593e-01 4.98977641113232e-01 + 5.50821128028667e-01 4.97448239777686e-01 + 5.69628317431665e-01 4.95095914136444e-01 + 5.88509798330163e-01 4.92097041935332e-01 + 6.07423091269127e-01 4.88360764967307e-01 + 6.26315879676062e-01 4.83792644100844e-01 + 6.45179027618201e-01 4.78506342917923e-01 + 6.63949992276556e-01 4.72397468589394e-01 + 6.82596771397553e-01 4.65480454296126e-01 + 7.01105667898352e-01 4.57821533331759e-01 + 7.19390458980571e-01 4.49306560335264e-01 + 7.37449386734799e-01 4.40021763716986e-01 + 7.55233287450602e-01 4.29949280199755e-01 + 7.72675183085231e-01 4.19055842892285e-01 + 7.89810876588208e-01 4.07465502995371e-01 + 8.06484809364324e-01 3.95019026978122e-01 + 8.22749466427636e-01 3.81863671783111e-01 + 8.38549437843995e-01 3.67985948498897e-01 + 8.53822843141276e-01 3.53376712171519e-01 + 8.68482698282576e-01 3.38013117891467e-01 + 8.82527277768971e-01 3.21961416297325e-01 + 8.95954036277289e-01 3.05275366473099e-01 + 9.08757285533517e-01 2.87998251390473e-01 + 9.20757624348661e-01 2.70058949061020e-01 + 9.32077214908394e-01 2.51596702608668e-01 + 9.42611287438903e-01 2.32595879244925e-01 + 9.52349414910574e-01 2.13103474747613e-01 + 9.61237529561560e-01 1.93147648123409e-01 + 9.69168871294468e-01 1.72736199342553e-01 + 9.76326703713309e-01 1.51992962994221e-01 + 9.82585730197106e-01 1.30917869381533e-01 + 9.87884002029843e-01 1.09544033639734e-01 + 9.92202667894419e-01 8.79209963846691e-02 + 9.95599172262122e-01 6.61100082160239e-02 + 9.98052102758341e-01 4.41573284776160e-02 + 9.99507690675012e-01 2.21028728366928e-02 + 1.00000000000000e+00 1.39471767468535e-15 diff --git a/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF01_Coords.txt b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF01_Coords.txt new file mode 100644 index 00000000..c0c8ddad --- /dev/null +++ b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF01_Coords.txt @@ -0,0 +1,208 @@ + 201 NumCoords ! The number of coordinates in the airfoil shape file (including an extra coordinate for airfoil reference). Set to zero if coordinates not included. +! ......... x-y coordinates are next if NumCoords > 0 ............. +! x-y coordinate of airfoil reference +! x/c y/c + 0.489474 0 +! coordinates of airfoil shape +! interpolation to 200 points +! x/c y/c + 1.00000000000000e+00 -3.16421772612390e-03 + 9.99110945270443e-01 -2.47105920697162e-02 + 9.97576994375339e-01 -4.67993845022092e-02 + 9.95459944687624e-01 -6.84337167356077e-02 + 9.91976392334682e-01 -9.00657715770117e-02 + 9.87532357694084e-01 -1.11371691742356e-01 + 9.82073007117098e-01 -1.32004290598503e-01 + 9.75632495177376e-01 -1.51997295578341e-01 + 9.68304625227921e-01 -1.71396793768580e-01 + 9.60134319308372e-01 -1.90350472287492e-01 + 9.50973174570070e-01 -2.10503605813256e-01 + 9.40976075096518e-01 -2.30186416006723e-01 + 9.30161994799789e-01 -2.49354345164969e-01 + 9.18526548050635e-01 -2.67946053746076e-01 + 9.06204685559811e-01 -2.85993589913206e-01 + 8.93096814131007e-01 -3.03374276912405e-01 + 8.79335004439212e-01 -3.20123403157046e-01 + 8.64921830314282e-01 -3.36188237142695e-01 + 8.49900429191050e-01 -3.51546887620593e-01 + 8.34308004668356e-01 -3.66174875302933e-01 + 8.18161715887287e-01 -3.80020141794273e-01 + 8.01527591100297e-01 -3.93086268689914e-01 + 7.84496904773810e-01 -4.04786375894643e-01 + 7.67028251214628e-01 -4.15444728414506e-01 + 7.49221098481114e-01 -4.25443666639427e-01 + 7.31109312546861e-01 -4.34681496122239e-01 + 7.12733221739921e-01 -4.43095560497414e-01 + 6.94124804992610e-01 -4.50716083967267e-01 + 6.75296861217813e-01 -4.57507733373021e-01 + 6.56351220288612e-01 -4.63629797162085e-01 + 6.37297642282493e-01 -4.69021650406962e-01 + 6.18184579076336e-01 -4.73661711191075e-01 + 5.99048824748551e-01 -4.77500682555689e-01 + 5.79905140141725e-01 -4.80476298777868e-01 + 5.60822552266790e-01 -4.82821100897016e-01 + 5.41807779672030e-01 -4.84393609336454e-01 + 5.23137860195204e-01 -4.85340334737817e-01 + 5.04895615780131e-01 -4.85677059437076e-01 + 4.86822413494681e-01 -4.85372268979213e-01 + 4.68943246111643e-01 -4.84434587337354e-01 + 4.51281215228627e-01 -4.82849729526095e-01 + 4.33869791962394e-01 -4.80550261086293e-01 + 4.16708291601139e-01 -4.77756903947675e-01 + 3.99821942290793e-01 -4.74438844863898e-01 + 3.83021226581361e-01 -4.70501187606855e-01 + 3.66510028690683e-01 -4.66117838259083e-01 + 3.50339822528374e-01 -4.61229488062895e-01 + 3.34529434920323e-01 -4.55868065561778e-01 + 3.19060580350289e-01 -4.50137865005078e-01 + 3.03961951611492e-01 -4.44019094016567e-01 + 2.89263477671933e-01 -4.37498086693495e-01 + 2.74954691526094e-01 -4.30627011410182e-01 + 2.61045693322669e-01 -4.23408038064864e-01 + 2.47531081353258e-01 -4.15862808513859e-01 + 2.34454873671549e-01 -4.07946420300901e-01 + 2.21749536060482e-01 -3.99796724707317e-01 + 2.09495761009538e-01 -3.91329723402531e-01 + 1.97654805990354e-01 -3.82623286493885e-01 + 1.86194798835722e-01 -3.73767309376824e-01 + 1.75143832165431e-01 -3.64767492631537e-01 + 1.64510931825440e-01 -3.55619768853155e-01 + 1.54264662143747e-01 -3.46336240294808e-01 + 1.44469444171873e-01 -3.36855727877300e-01 + 1.35016546824907e-01 -3.27295058357275e-01 + 1.26007074796798e-01 -3.17588898325485e-01 + 1.17335095261661e-01 -3.07850346569760e-01 + 1.09122191907664e-01 -2.97988397774553e-01 + 1.01228904610188e-01 -2.88095133738336e-01 + 9.37005857644255e-02 -2.78149751233394e-01 + 8.65952060326960e-02 -2.68149983931702e-01 + 7.97470493709899e-02 -2.58245516255184e-01 + 7.32564041991407e-02 -2.48375945846845e-01 + 6.71103398619902e-02 -2.38520800068324e-01 + 6.12956358739206e-02 -2.28273089593854e-01 + 5.58512861647731e-02 -2.18035625337734e-01 + 5.06986492562267e-02 -2.07863675578317e-01 + 4.58459063482147e-02 -1.97741417265822e-01 + 4.12374651654770e-02 -1.87689118226564e-01 + 3.69363886388660e-02 -1.77695953267912e-01 + 3.29623755477581e-02 -1.67780856055308e-01 + 2.91933599630294e-02 -1.58000033452927e-01 + 2.58326584607911e-02 -1.48266339522027e-01 + 2.25688351721396e-02 -1.39011630549253e-01 + 1.95732992520596e-02 -1.30105462233865e-01 + 1.67610738246130e-02 -1.21314096800611e-01 + 1.42583321073789e-02 -1.12582415338248e-01 + 1.19908166431120e-02 -1.03925933593292e-01 + 9.99928542511028e-03 -9.53469054771868e-02 + 8.12764378342123e-03 -8.68845733614765e-02 + 6.50553857600199e-03 -7.85191937270735e-02 + 5.17572423597908e-03 -7.02483867655549e-02 + 3.97140784027181e-03 -6.20650797672678e-02 + 2.94862431147953e-03 -5.39399963412825e-02 + 2.14055966565164e-03 -4.58470093224122e-02 + 1.45003537340197e-03 -3.78838208911683e-02 + 9.20097460438803e-04 -3.00188642323400e-02 + 5.13569518013506e-04 -2.22872670431334e-02 + 2.24854144698289e-04 -1.47090799938054e-02 + 7.16420419797124e-05 -7.28122005805669e-03 + 0.00000000000000e+00 0.00000000000000e+00 + 8.30667337145912e-05 7.28493907761252e-03 + 2.40621206193159e-04 1.47085612205429e-02 + 5.29850643501296e-04 2.22690666161207e-02 + 9.37552646642290e-04 2.99680567436069e-02 + 1.46364423687516e-03 3.78031462162717e-02 + 2.13415396408500e-03 4.57718293152885e-02 + 2.98505302314019e-03 5.38762991811228e-02 + 4.08049090961046e-03 6.21031222356185e-02 + 5.32348409326103e-03 7.04621026477038e-02 + 6.68540525770168e-03 7.89717384981979e-02 + 8.16349050305524e-03 8.76289039370964e-02 + 9.84115364385886e-03 9.63974146736541e-02 + 1.17664515759166e-02 1.05263924316241e-01 + 1.40318228128144e-02 1.14211150659918e-01 + 1.64404096111178e-02 1.23297936682812e-01 + 1.90063994463009e-02 1.32535275404535e-01 + 2.17243347773833e-02 1.41923218754833e-01 + 2.47531082013638e-02 1.51382020977074e-01 + 2.79876147869340e-02 1.60929925146753e-01 + 3.16880968401645e-02 1.70478068315566e-01 + 3.55350251674146e-02 1.80153130476464e-01 + 3.96263775536540e-02 1.89947425730580e-01 + 4.39456143792258e-02 1.99882812309296e-01 + 4.85239794021445e-02 2.09908181416265e-01 + 5.34534137951630e-02 2.19944265641675e-01 + 5.87462885442388e-02 2.29964197658055e-01 + 6.44270496014028e-02 2.39969754830107e-01 + 7.04097222861749e-02 2.50025763168648e-01 + 7.66631835969947e-02 2.60165429986364e-01 + 8.32549959691082e-02 2.70336561512274e-01 + 9.01101313435420e-02 2.80563309640775e-01 + 9.74049202740261e-02 2.90697579494236e-01 + 1.05114698051431e-01 3.00743368754403e-01 + 1.13145220439572e-01 3.10785648613665e-01 + 1.21630315794086e-01 3.20725544551961e-01 + 1.30390853479517e-01 3.30702112547975e-01 + 1.39590645856004e-01 3.40558753101048e-01 + 1.49124870362037e-01 3.50362123732590e-01 + 1.59154982855993e-01 3.59921913101712e-01 + 1.69544432069570e-01 3.69399060590938e-01 + 1.80386709779081e-01 3.78695988921857e-01 + 1.91579763428791e-01 3.87884300501059e-01 + 2.03215759235826e-01 3.96833543919666e-01 + 2.15253430564785e-01 4.05547214951462e-01 + 2.27772014189445e-01 4.13882927583771e-01 + 2.40642603224139e-01 4.22086896802528e-01 + 2.53939036577503e-01 4.30033802762336e-01 + 2.67609972467099e-01 4.37691285847929e-01 + 2.81557875539761e-01 4.44965913565754e-01 + 2.95881178190567e-01 4.51813642422346e-01 + 3.10595953223466e-01 4.58226822092898e-01 + 3.25692615194284e-01 4.64358752082265e-01 + 3.41122510103875e-01 4.70166093755745e-01 + 3.56906920161226e-01 4.75457819601108e-01 + 3.73028060365530e-01 4.80296533840550e-01 + 3.89466547847528e-01 4.84640854961732e-01 + 4.06216915276230e-01 4.88245022885247e-01 + 4.23329613709593e-01 4.91316221321931e-01 + 4.40890014276592e-01 4.94066031076244e-01 + 4.58716932230117e-01 4.96120177384477e-01 + 4.76773550105776e-01 4.97493108926328e-01 + 4.95036075072470e-01 4.98220076856676e-01 + 5.13479009238266e-01 4.98328313435672e-01 + 5.32075794301084e-01 4.97686119534454e-01 + 5.50797707737235e-01 4.96272617324986e-01 + 5.69600641150388e-01 4.94015215318247e-01 + 5.88477721457098e-01 4.91029243067188e-01 + 6.07386635657425e-01 4.87295372664773e-01 + 6.26275242831597e-01 4.82792184672487e-01 + 6.45134391494005e-01 4.77579799714536e-01 + 6.63901695169446e-01 4.71560607238906e-01 + 6.82545269979229e-01 4.64770350611842e-01 + 7.01051428389662e-01 4.57262911241947e-01 + 7.19334097084216e-01 4.48930414817246e-01 + 7.37391465413848e-01 4.39841141799307e-01 + 7.55174481191430e-01 4.29986432588973e-01 + 7.72616437803403e-01 4.19381365239015e-01 + 7.89753200934423e-01 4.08201692944460e-01 + 8.06429273866882e-01 3.96269530921693e-01 + 8.22696674409171e-01 3.83630606068877e-01 + 8.38499958578817e-01 3.70228814924312e-01 + 8.53777444028247e-01 3.56113546193772e-01 + 8.68442280245945e-01 3.41287951489090e-01 + 8.82492540270293e-01 3.25786277344664e-01 + 8.95925498965556e-01 3.09679894523524e-01 + 9.08735247378820e-01 2.93027554712345e-01 + 9.20742332422719e-01 2.75162884784513e-01 + 9.32068464518384e-01 2.56731572981429e-01 + 9.42608539274729e-01 2.37762434632290e-01 + 9.52774207875208e-01 2.18302108340019e-01 + 9.62859775973639e-01 1.98379401591706e-01 + 9.70800878118612e-01 1.77985574843893e-01 + 9.77526560026023e-01 1.57228723263127e-01 + 9.83348702581913e-01 1.35262496314977e-01 + 9.88287866680976e-01 1.12048580600310e-01 + 9.92312239757846e-01 8.89420954512888e-02 + 9.95598399807970e-01 6.64089965678724e-02 + 9.97884993829918e-01 4.40785443080142e-02 + 9.99371468236542e-01 2.18636293439463e-02 + 1.00000000000000e+00 -1.46513661216579e-04 diff --git a/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF02_Coords.txt b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF02_Coords.txt new file mode 100644 index 00000000..3d277f48 --- /dev/null +++ b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF02_Coords.txt @@ -0,0 +1,208 @@ + 201 NumCoords ! The number of coordinates in the airfoil shape file (including an extra coordinate for airfoil reference). Set to zero if coordinates not included. +! ......... x-y coordinates are next if NumCoords > 0 ............. +! x-y coordinate of airfoil reference +! x/c y/c + 0.405419 0 +! coordinates of airfoil shape +! interpolation to 200 points +! x/c y/c + 1.00000000000000e+00 -1.94964271094086e-02 + 9.96919760277077e-01 -3.64826077995756e-02 + 9.94667087130123e-01 -5.60719522447348e-02 + 9.94761079761680e-01 -7.41287339133444e-02 + 9.91487644632361e-01 -9.30111065602699e-02 + 9.87177265536021e-01 -1.10830801551200e-01 + 9.81618438289038e-01 -1.25618285586318e-01 + 9.74359531938626e-01 -1.37858592038257e-01 + 9.66196197839873e-01 -1.48011073720888e-01 + 9.57084778530041e-01 -1.57244213613537e-01 + 9.47030628319075e-01 -1.76163809587731e-01 + 9.36255994779871e-01 -1.94451554089259e-01 + 9.24755229326704e-01 -2.12084822033116e-01 + 9.12514414231155e-01 -2.28979937705261e-01 + 8.99641900735580e-01 -2.45152777431143e-01 + 8.86071424135137e-01 -2.60541847813049e-01 + 8.71933069994702e-01 -2.75199084385032e-01 + 8.57249287582935e-01 -2.89132205047948e-01 + 8.42064402212172e-01 -3.02348165923965e-01 + 8.26409062460493e-01 -3.14787448920772e-01 + 8.10288808146397e-01 -3.26359904138149e-01 + 7.93758629967803e-01 -3.37091676397995e-01 + 7.76918356342850e-01 -3.44291222218988e-01 + 7.59756850873003e-01 -3.49997131324565e-01 + 7.42348874985586e-01 -3.55640730349542e-01 + 7.24708863089766e-01 -3.60706166782752e-01 + 7.06860528348044e-01 -3.64855413158321e-01 + 6.88831517526942e-01 -3.68409151382566e-01 + 6.70633473983476e-01 -3.71524443372096e-01 + 6.52350564072767e-01 -3.74401784953206e-01 + 6.33982188894777e-01 -3.77065482741049e-01 + 6.15559054509071e-01 -3.79168407766431e-01 + 5.97101918875316e-01 -3.80350473776001e-01 + 5.78607712056559e-01 -3.80687774167715e-01 + 5.60114269360246e-01 -3.80570858605504e-01 + 5.41594988940669e-01 -3.80067548433720e-01 + 5.24491038376215e-01 -3.79537588218947e-01 + 5.09243386421893e-01 -3.78981564014641e-01 + 4.94142523233296e-01 -3.78083193106923e-01 + 4.79201400260462e-01 -3.76755219694438e-01 + 4.64426672033553e-01 -3.74840429494636e-01 + 4.49830052252528e-01 -3.72341501685922e-01 + 4.35411690443212e-01 -3.69564589340833e-01 + 4.21176828920086e-01 -3.66527761938651e-01 + 4.06104752722998e-01 -3.63217644680091e-01 + 3.91187261313758e-01 -3.59606140139742e-01 + 3.76543272121399e-01 -3.55540172858436e-01 + 3.62174951181275e-01 -3.51199859300841e-01 + 3.48051575371203e-01 -3.46733492501332e-01 + 3.34166838440425e-01 -3.42236418543471e-01 + 3.20531094536529e-01 -3.37752409778483e-01 + 3.07166374335585e-01 -3.33138685551140e-01 + 2.94106366929472e-01 -3.28233453302116e-01 + 2.81356553687748e-01 -3.22927037164433e-01 + 2.68929414080849e-01 -3.17210399237509e-01 + 2.56792257622504e-01 -3.11199667576809e-01 + 2.44988366773819e-01 -3.04908147192347e-01 + 2.33487068586780e-01 -2.98398015474454e-01 + 2.22244174627754e-01 -2.91908544458142e-01 + 2.11259238518723e-01 -2.85624154835144e-01 + 2.00540109534862e-01 -2.79445232131323e-01 + 1.90099108400639e-01 -2.73144271821139e-01 + 1.79974500726159e-01 -2.66577875347765e-01 + 1.69915683501289e-01 -2.59834415460592e-01 + 1.60172080930679e-01 -2.52962962830656e-01 + 1.50692746390245e-01 -2.46077778027207e-01 + 1.41572171628772e-01 -2.39083657564268e-01 + 1.32782528972732e-01 -2.31868964518358e-01 + 1.24316300642292e-01 -2.24479019688654e-01 + 1.16125227242430e-01 -2.17115852851904e-01 + 1.08022185325659e-01 -2.10062937367560e-01 + 1.00068510946488e-01 -2.03253136991591e-01 + 9.24181923986685e-02 -1.96403291468797e-01 + 8.52292314707568e-02 -1.87525621188063e-01 + 7.85442356694309e-02 -1.78452955788562e-01 + 7.21826484759061e-02 -1.69371289606163e-01 + 6.59224769279808e-02 -1.60339488949538e-01 + 5.95888908522178e-02 -1.51375335195636e-01 + 5.34570839330547e-02 -1.42381729136260e-01 + 4.78323253460157e-02 -1.33307333331388e-01 + 4.27773110897719e-02 -1.24183705410093e-01 + 3.81406060607182e-02 -1.14969947782298e-01 + 3.34394858942616e-02 -1.07833476412008e-01 + 2.85905771976062e-02 -1.02443290523446e-01 + 2.39758840800528e-02 -9.70665624082339e-02 + 2.00924464828600e-02 -9.14418911635026e-02 + 1.67774266077405e-02 -8.55577600333846e-02 + 1.37085226488790e-02 -7.95717583471716e-02 + 1.06047400652709e-02 -7.35922291670351e-02 + 7.90398428387208e-03 -6.75352052422909e-02 + 6.19892209075347e-03 -6.13137254015921e-02 + 4.74163822479280e-03 -5.48650139398457e-02 + 3.46348797721600e-03 -4.81553931473352e-02 + 2.35439809271567e-03 -4.11318098186878e-02 + 1.48284350464362e-03 -3.41609786643930e-02 + 9.33668904559450e-04 -2.70825630260840e-02 + 5.16784288069033e-04 -2.00607976197347e-02 + 2.03224808289276e-04 -1.32008980839843e-02 + 2.88583219323030e-05 -6.51695336105137e-03 + 0.00000000000000e+00 0.00000000000000e+00 + 1.06034557788935e-04 6.54242344402049e-03 + 3.10442109886626e-04 1.32200621240131e-02 + 6.27358526355077e-04 2.00270586046359e-02 + 1.04642059582819e-03 2.69584070704927e-02 + 1.56119077029123e-03 3.40044020355773e-02 + 2.20965204677518e-03 4.11549554928511e-02 + 3.41098060660727e-03 4.84144618046186e-02 + 5.03360788709283e-03 5.57589214681263e-02 + 6.61245394229265e-03 6.32348735880216e-02 + 8.28994979066480e-03 7.08911179309667e-02 + 9.96034393771960e-03 7.87021820009504e-02 + 1.17636547160994e-02 8.65345063094756e-02 + 1.43612220190213e-02 9.42922806414463e-02 + 1.76430317064128e-02 1.02026805686471e-01 + 2.08737235707927e-02 1.09949354414078e-01 + 2.39097774660482e-02 1.18163715137690e-01 + 2.68277855724522e-02 1.26610148817642e-01 + 3.00184157320084e-02 1.35071752122783e-01 + 3.38529447168762e-02 1.43382634408088e-01 + 3.85374178015213e-02 1.51512804458775e-01 + 4.35193302635381e-02 1.59709865654183e-01 + 4.83524785822808e-02 1.68285035077358e-01 + 5.28925514814938e-02 1.77785241588636e-01 + 5.74509623742945e-02 1.87519752029641e-01 + 6.25207280441538e-02 1.96995257755178e-01 + 6.84864459272233e-02 2.05895125589205e-01 + 7.51749747555155e-02 2.14483369522917e-01 + 8.21424789239981e-02 2.23186204375288e-01 + 8.89480736036874e-02 2.32391482476344e-01 + 9.57168879662020e-02 2.41977056322773e-01 + 1.02682866347355e-01 2.51651269226778e-01 + 1.10220820704945e-01 2.61011250036727e-01 + 1.18407958380338e-01 2.69947451121491e-01 + 1.26881602570982e-01 2.78784626441245e-01 + 1.35660947758076e-01 2.87754998986677e-01 + 1.44539262453658e-01 2.97066755412224e-01 + 1.53710627262191e-01 3.06476813639894e-01 + 1.63224044690801e-01 3.15759213512801e-01 + 1.73217608842146e-01 3.24616725514123e-01 + 1.83592362834056e-01 3.33425258716891e-01 + 1.94325962262670e-01 3.42337881360872e-01 + 2.05324011045863e-01 3.51288753587316e-01 + 2.16730097076787e-01 3.60001663577674e-01 + 2.28586578632938e-01 3.68187843125944e-01 + 2.40883113525511e-01 3.75812546015869e-01 + 2.53496856322201e-01 3.83600826529355e-01 + 2.66426205569999e-01 3.91650072271809e-01 + 2.79648785252606e-01 3.99396772979447e-01 + 2.92654108132638e-01 4.06655149783746e-01 + 3.05982927892807e-01 4.13055764549372e-01 + 3.19616352211114e-01 4.19007565475870e-01 + 3.33559027388770e-01 4.25557700509835e-01 + 3.47790649521039e-01 4.31983019768178e-01 + 3.62286841731615e-01 4.37810261240227e-01 + 3.77034995262049e-01 4.43528144955168e-01 + 3.92039353236568e-01 4.48820541528545e-01 + 4.07301441870269e-01 4.52540541894158e-01 + 4.23279474819674e-01 4.55820048720622e-01 + 4.40634468309514e-01 4.59564402113604e-01 + 4.58216729640812e-01 4.62715547857050e-01 + 4.76002112543622e-01 4.64915551067932e-01 + 4.93972301744354e-01 4.66495076484244e-01 + 5.12102601808104e-01 4.67675381916421e-01 + 5.30374260454303e-01 4.67718175971608e-01 + 5.48760443148615e-01 4.66664714353419e-01 + 5.67217438731546e-01 4.64745135086648e-01 + 5.85739737161608e-01 4.61729462619936e-01 + 6.04297036727046e-01 4.57963754355715e-01 + 6.22849821404431e-01 4.53804771006538e-01 + 6.41387754588488e-01 4.49034662925732e-01 + 6.59860243895401e-01 4.43612634661173e-01 + 6.78243902722125e-01 4.37681519215445e-01 + 6.96525620003880e-01 4.31223433182484e-01 + 7.14630615751572e-01 4.24172943475969e-01 + 7.32553281453510e-01 4.16497772874745e-01 + 7.50252988657587e-01 4.08237425290133e-01 + 7.67683365695193e-01 3.99660004830094e-01 + 7.84884705771043e-01 3.91177827246511e-01 + 8.01707686882478e-01 3.82511987837697e-01 + 8.18171045140217e-01 3.73184018737277e-01 + 8.34218184325793e-01 3.62939454140551e-01 + 8.49803537682218e-01 3.52119100925938e-01 + 8.64853102337230e-01 3.40870213182952e-01 + 8.79352542615986e-01 3.29069212973395e-01 + 8.93288312520579e-01 3.16847374518213e-01 + 9.06641281797077e-01 3.04310322344821e-01 + 9.19235341950085e-01 2.88747970901776e-01 + 9.31163314413939e-01 2.72527797669352e-01 + 9.42304292794809e-01 2.55835364954767e-01 + 9.55213979558356e-01 2.38692901385650e-01 + 9.72177046241266e-01 2.21180379624901e-01 + 9.80174206699236e-01 2.02148008484942e-01 + 9.84417859316093e-01 1.80623200933622e-01 + 9.87730786501502e-01 1.53965422157644e-01 + 9.90607437911417e-01 1.22548669883815e-01 + 9.92941558866010e-01 9.10997252988497e-02 + 9.95524996439665e-01 6.60081316645982e-02 + 9.96925214206640e-01 4.30168042831882e-02 + 9.98589083226293e-01 2.09101531114029e-02 + 1.00000000000000e+00 -1.10918874127508e-04 diff --git a/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF03_Coords.txt b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF03_Coords.txt new file mode 100644 index 00000000..3574f261 --- /dev/null +++ b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF03_Coords.txt @@ -0,0 +1,208 @@ + 201 NumCoords ! The number of coordinates in the airfoil shape file (including an extra coordinate for airfoil reference). Set to zero if coordinates not included. +! ......... x-y coordinates are next if NumCoords > 0 ............. +! x-y coordinate of airfoil reference +! x/c y/c + 0.300072 0 +! coordinates of airfoil shape +! interpolation to 200 points +! x/c y/c + 1.00000000000000e+00 -2.35717905236513e-02 + 9.95894264742224e-01 -3.92526822859504e-02 + 9.92356907783760e-01 -5.58972397758731e-02 + 9.91832649399724e-01 -7.22796935620756e-02 + 9.89065767280758e-01 -8.98751886421859e-02 + 9.85303518885023e-01 -1.06063296906901e-01 + 9.79227294864432e-01 -1.18115211299191e-01 + 9.68317731645526e-01 -1.26727180688080e-01 + 9.56870605029902e-01 -1.32551970200501e-01 + 9.44399782765251e-01 -1.37235805042327e-01 + 9.31376191661979e-01 -1.49921669278151e-01 + 9.18131472990873e-01 -1.62163429513691e-01 + 9.04532462534647e-01 -1.73794296481196e-01 + 8.90513850343901e-01 -1.84548505419301e-01 + 8.76094083221940e-01 -1.94369351614981e-01 + 8.61295443643247e-01 -2.03387259424766e-01 + 8.46228194041534e-01 -2.11697233177751e-01 + 8.30943028446170e-01 -2.19423235960492e-01 + 8.15464579238373e-01 -2.26583810092412e-01 + 7.99805091304501e-01 -2.33034629864386e-01 + 7.83949186991882e-01 -2.38634111936675e-01 + 7.67924901075415e-01 -2.43491491542901e-01 + 7.51827610435101e-01 -2.46922502098554e-01 + 7.35700766231654e-01 -2.49967384402370e-01 + 7.19557581083962e-01 -2.53049973028183e-01 + 7.03374920806515e-01 -2.55675693783315e-01 + 6.87141084317211e-01 -2.57511647636345e-01 + 6.70872708173025e-01 -2.58916159150435e-01 + 6.54584120557027e-01 -2.60070409267096e-01 + 6.38316166451763e-01 -2.61147805145693e-01 + 6.22053812145135e-01 -2.62242468065543e-01 + 6.05795467035195e-01 -2.62984971699304e-01 + 5.89535785963171e-01 -2.62980782780771e-01 + 5.73249959911008e-01 -2.62338277960480e-01 + 5.56924435273058e-01 -2.61412073870956e-01 + 5.40499557828918e-01 -2.60380178738677e-01 + 5.25124338707629e-01 -2.59541047800324e-01 + 5.11278184667223e-01 -2.58859241415762e-01 + 4.97568404605392e-01 -2.58048556490882e-01 + 4.84002314517955e-01 -2.56975419244797e-01 + 4.70578871550198e-01 -2.55452441773426e-01 + 4.57299606722912e-01 -2.53575365177959e-01 + 4.44165059993117e-01 -2.51608626178359e-01 + 4.31171120115011e-01 -2.49565341878899e-01 + 4.17960046660827e-01 -2.47435089625259e-01 + 4.04894573177154e-01 -2.45125131039407e-01 + 3.92025010140446e-01 -2.42462612691433e-01 + 3.79343869682045e-01 -2.39595692647852e-01 + 3.66822492601097e-01 -2.36738334901165e-01 + 3.54437597401984e-01 -2.34084096374542e-01 + 3.42188016976202e-01 -2.31663337492797e-01 + 3.30106565812339e-01 -2.29245864019644e-01 + 3.18228608318416e-01 -2.26607512965020e-01 + 3.06561819529862e-01 -2.23599397180190e-01 + 2.95096087112862e-01 -2.20264450363764e-01 + 2.83822976873035e-01 -2.16705858133672e-01 + 2.72749367112427e-01 -2.12987917599575e-01 + 2.61871015332779e-01 -2.09105223071590e-01 + 2.51166620646972e-01 -2.05257087666955e-01 + 2.40624400846784e-01 -2.01625484971293e-01 + 2.30238432660905e-01 -1.98140713780569e-01 + 2.20026112530791e-01 -1.94584499409339e-01 + 2.09976055390476e-01 -1.90827834894363e-01 + 1.99702136630218e-01 -1.86888650453711e-01 + 1.89635587559752e-01 -1.82831573590219e-01 + 1.79772976644460e-01 -1.78716242047549e-01 + 1.70166626869497e-01 -1.74489311956110e-01 + 1.60857736786573e-01 -1.70006317401921e-01 + 1.51803109355095e-01 -1.65351581130296e-01 + 1.42904673719036e-01 -1.60741881001108e-01 + 1.34016689385335e-01 -1.56400925252111e-01 + 1.25172927433342e-01 -1.52235477594800e-01 + 1.16585145327233e-01 -1.47936269496174e-01 + 1.08455437817872e-01 -1.42606858442656e-01 + 1.00797932241528e-01 -1.36869866343013e-01 + 9.34220406155034e-02 -1.30998286551843e-01 + 8.60634069002927e-02 -1.25203141666258e-01 + 7.85543380199848e-02 -1.19513567026171e-01 + 7.12090438710948e-02 -1.13679449812632e-01 + 6.43781714721257e-02 -1.07497988597386e-01 + 5.81748969271094e-02 -1.00901485941624e-01 + 5.23111625072034e-02 -9.40070595698379e-02 + 4.63848694510659e-02 -8.87274392056592e-02 + 4.02274234777820e-02 -8.49827667220595e-02 + 3.43402499368400e-02 -8.12041215315654e-02 + 2.92122911092120e-02 -7.70335607862094e-02 + 2.46619896023326e-02 -7.24469162604508e-02 + 2.03998728457045e-02 -6.76744757448659e-02 + 1.62083083553108e-02 -6.28569220857654e-02 + 1.24122747710821e-02 -5.78802307117992e-02 + 9.59261999542548e-03 -5.26178555647791e-02 + 7.30477546051285e-03 -4.69809514049654e-02 + 5.24424677887566e-03 -4.11640833368231e-02 + 3.22154066429621e-03 -3.53189852766165e-02 + 1.65180206365193e-03 -2.94779767104117e-02 + 1.00171614777338e-03 -2.35012775997985e-02 + 5.33709082287082e-04 -1.74789869612144e-02 + 1.93102071972421e-04 -1.15157513977575e-02 + 8.83513173800652e-06 -5.67716919165800e-03 + 0.00000000000000e+00 0.00000000000000e+00 + 1.16783719135356e-04 5.69723987547027e-03 + 3.43118960628982e-04 1.15219848562656e-02 + 6.72993148161244e-04 1.74602777849096e-02 + 1.09737183733306e-03 2.34963725200926e-02 + 1.60684348093023e-03 2.96112825450017e-02 + 2.45643493250886e-03 3.57965862211899e-02 + 3.99538452491140e-03 4.20591838228941e-02 + 5.93173609093872e-03 4.83922212075131e-02 + 7.78831860532396e-03 5.48405525131736e-02 + 9.77944638510934e-03 6.14059674486418e-02 + 1.18236157695499e-02 6.80196332226401e-02 + 1.41090606785859e-02 7.45698337168348e-02 + 1.73056541184598e-02 8.10186811443194e-02 + 2.11847229777394e-02 8.74687230723911e-02 + 2.49676864074981e-02 9.40869839667322e-02 + 2.84682042956027e-02 1.00930111245539e-01 + 3.18331846418495e-02 1.07898963211733e-01 + 3.54793253397875e-02 1.14828880543840e-01 + 3.98821847361107e-02 1.21582993745491e-01 + 4.51314595122883e-02 1.28212190706429e-01 + 5.07378731779770e-02 1.34892120261391e-01 + 5.60731260647946e-02 1.41960877640708e-01 + 6.09722950181842e-02 1.50342170540091e-01 + 6.58438293017437e-02 1.58942245558348e-01 + 7.12537393230430e-02 1.67161944148746e-01 + 7.76600623439659e-02 1.74624850622013e-01 + 8.48496220471092e-02 1.81687450473830e-01 + 9.23057704681641e-02 1.88867715176475e-01 + 9.94459240673263e-02 1.96648864845365e-01 + 1.06388932256554e-01 2.04900423667625e-01 + 1.13500915840888e-01 2.13208533649742e-01 + 1.21190173762834e-01 2.21120456132424e-01 + 1.29552662653441e-01 2.28502274929156e-01 + 1.38071878683882e-01 2.35719905821540e-01 + 1.46821747467612e-01 2.43114116431733e-01 + 1.55674346023180e-01 2.50880294859766e-01 + 1.64742508530083e-01 2.58798876919177e-01 + 1.74100620712751e-01 2.66555316753591e-01 + 1.83827637281412e-01 2.73887896215538e-01 + 1.93900930930976e-01 2.81137679364482e-01 + 2.04279807701489e-01 2.88489630315669e-01 + 2.14917904141514e-01 2.95836142276111e-01 + 2.25877633648094e-01 3.02970528418131e-01 + 2.37175240693611e-01 3.09614749723245e-01 + 2.48781997761441e-01 3.15783316315385e-01 + 2.60667851543173e-01 3.22097199193517e-01 + 2.72834283839390e-01 3.28652682218705e-01 + 2.85283064783479e-01 3.34865419367518e-01 + 2.97847251117894e-01 3.40624356479022e-01 + 3.10710643373344e-01 3.45634518095723e-01 + 3.23837985214461e-01 3.50222642863971e-01 + 3.37240583535417e-01 3.55267130987121e-01 + 3.50911402546816e-01 3.60167827153803e-01 + 3.64804696483725e-01 3.64587389850643e-01 + 3.78910279118625e-01 3.69073483105304e-01 + 3.93243450766671e-01 3.73200860402215e-01 + 4.07809010689417e-01 3.75729715812861e-01 + 4.23000375070936e-01 3.77751754255469e-01 + 4.39328786730662e-01 3.80141190316103e-01 + 4.55813610039226e-01 3.82101412277872e-01 + 4.72460251929427e-01 3.83235896264865e-01 + 4.89254536599454e-01 3.83843952964464e-01 + 5.06163834453059e-01 3.84146352307061e-01 + 5.23189394372787e-01 3.83285841342889e-01 + 5.40310058634680e-01 3.81443701603978e-01 + 5.57486522435475e-01 3.79033596004446e-01 + 5.74715352025665e-01 3.75685474236072e-01 + 5.92000372484674e-01 3.71765261705014e-01 + 6.09337554036771e-01 3.67670925407177e-01 + 6.26712711199081e-01 3.63152537787024e-01 + 6.44112689354547e-01 3.58249400169114e-01 + 6.61537902878510e-01 3.53105856660785e-01 + 6.78976015503225e-01 3.47670000178051e-01 + 6.96388219208155e-01 3.41916005228908e-01 + 7.13758174635815e-01 3.35774011869113e-01 + 7.31072071555730e-01 3.29291743909179e-01 + 7.48347054469357e-01 3.22782481179152e-01 + 7.65635234168385e-01 3.16597107059741e-01 + 7.82817938077837e-01 3.10445909406222e-01 + 7.99822649562144e-01 3.03782942002751e-01 + 8.16599499725996e-01 2.96387728717845e-01 + 8.33162654038272e-01 2.88615543528075e-01 + 8.49499238755804e-01 2.80681153424459e-01 + 8.65575980032653e-01 2.72460131547320e-01 + 8.81365101325771e-01 2.64006588773166e-01 + 8.96830625839868e-01 2.55349206752237e-01 + 9.11860293545010e-01 2.45521741551255e-01 + 9.26493285460369e-01 2.35422284498711e-01 + 9.40627758148684e-01 2.25124409413752e-01 + 9.56355816041677e-01 2.14591442921710e-01 + 9.76537617843118e-01 2.04082237971755e-01 + 9.84561014127750e-01 1.89606914519805e-01 + 9.87643053296840e-01 1.67544521992612e-01 + 9.89781643689051e-01 1.41487907300533e-01 + 9.91693019433194e-01 1.13998602352113e-01 + 9.93236086227859e-01 8.40282639292492e-02 + 9.95181038506289e-01 6.17158184066358e-02 + 9.96476028162972e-01 4.13392188133469e-02 + 9.98222919558243e-01 2.12790182529935e-02 + 1.00000000000000e+00 1.60547379486788e-03 diff --git a/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF04_Coords.txt b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF04_Coords.txt new file mode 100644 index 00000000..7c0a13b7 --- /dev/null +++ b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF04_Coords.txt @@ -0,0 +1,208 @@ + 201 NumCoords ! The number of coordinates in the airfoil shape file (including an extra coordinate for airfoil reference). Set to zero if coordinates not included. +! ......... x-y coordinates are next if NumCoords > 0 ............. +! x-y coordinate of airfoil reference +! x/c y/c + 0.250000 0 +! coordinates of airfoil shape +! interpolation to 200 points +! x/c y/c + 1.00000000000000e+00 -2.27521504445117e-02 + 9.95825558916260e-01 -3.85996552852628e-02 + 9.91908351102147e-01 -5.44969196641126e-02 + 9.88416628115054e-01 -7.07599158572808e-02 + 9.85866922904108e-01 -8.82610141031158e-02 + 9.82725730996461e-01 -1.04331474026742e-01 + 9.75943584414250e-01 -1.16192160119479e-01 + 9.60562898886437e-01 -1.24553806205324e-01 + 9.45502094163868e-01 -1.30081821439202e-01 + 9.29689968161834e-01 -1.34454116305964e-01 + 9.13964300425632e-01 -1.38792987259912e-01 + 8.98614488822684e-01 -1.43791084896220e-01 + 8.83335037065323e-01 -1.48845719057247e-01 + 8.67989583131007e-01 -1.53392395893884e-01 + 8.52512977524852e-01 -1.57285196860484e-01 + 8.36980556973450e-01 -1.60814946557067e-01 + 8.21468173261859e-01 -1.64100703909415e-01 + 8.06005351604761e-01 -1.67267075710542e-01 + 7.90569523846495e-01 -1.70238657955313e-01 + 7.75160420278176e-01 -1.72833393586880e-01 + 7.59765591487754e-01 -1.74956177670212e-01 + 7.44400605416898e-01 -1.76801895913143e-01 + 7.29116033776629e-01 -1.78610693133524e-01 + 7.13947989837457e-01 -1.80610582068115e-01 + 6.98879169529179e-01 -1.82683486229382e-01 + 6.83885725014230e-01 -1.84453890742002e-01 + 6.68948266000129e-01 -1.85692240974458e-01 + 6.54077597403275e-01 -1.86675765092582e-01 + 6.39298560836104e-01 -1.87505908577295e-01 + 6.24631617962163e-01 -1.88281679546669e-01 + 6.10073346044509e-01 -1.89102453976540e-01 + 5.95625793495472e-01 -1.89726467074718e-01 + 5.81293508075112e-01 -1.89890541527727e-01 + 5.67078321487802e-01 -1.89672724652735e-01 + 5.52984605219614e-01 -1.89300253242408e-01 + 5.39018740189456e-01 -1.88942147239663e-01 + 5.25163688284825e-01 -1.88679571252767e-01 + 5.11413609207518e-01 -1.88425702489593e-01 + 4.97799177395975e-01 -1.88101973722528e-01 + 4.84327325660904e-01 -1.87580974813977e-01 + 4.70996488304439e-01 -1.86734079403737e-01 + 4.57807499457728e-01 -1.85719999075378e-01 + 4.44760927152842e-01 -1.84696486770858e-01 + 4.31852022455883e-01 -1.83635353168758e-01 + 4.19090901616490e-01 -1.82470445502636e-01 + 4.06491363898788e-01 -1.81170983464115e-01 + 3.94068316367388e-01 -1.79605967544454e-01 + 3.81813043724431e-01 -1.77780857103527e-01 + 3.69699449630328e-01 -1.75956382315867e-01 + 3.57702913407548e-01 -1.74362578401297e-01 + 3.45820758127239e-01 -1.72975266565004e-01 + 3.34085173594801e-01 -1.71599837205798e-01 + 3.22528762317999e-01 -1.70053358838540e-01 + 3.11158458585437e-01 -1.68229483638464e-01 + 2.99960205902575e-01 -1.66205813724721e-01 + 2.88929664556996e-01 -1.64083038925404e-01 + 2.78065429500551e-01 -1.61919157747390e-01 + 2.67372016639914e-01 -1.59640340608867e-01 + 2.56838483482072e-01 -1.57303663087410e-01 + 2.46452895340118e-01 -1.54979944998565e-01 + 2.36204329661831e-01 -1.52707294515853e-01 + 2.26105799104062e-01 -1.50433273332383e-01 + 2.16178334826531e-01 -1.48092285325409e-01 + 2.06440462240654e-01 -1.45637282290730e-01 + 1.96869285515018e-01 -1.43086175320475e-01 + 1.87473435872977e-01 -1.40444127091679e-01 + 1.78262653731453e-01 -1.37710428849814e-01 + 1.69252630220208e-01 -1.34804420084564e-01 + 1.60413244437104e-01 -1.31813387053438e-01 + 1.51703588066681e-01 -1.28882641840022e-01 + 1.43077619868567e-01 -1.26142317505189e-01 + 1.34558223959049e-01 -1.23515015039303e-01 + 1.26236077097364e-01 -1.20786093116937e-01 + 1.18187874855922e-01 -1.17753964310198e-01 + 1.10394900564033e-01 -1.14389083257162e-01 + 1.02776771116232e-01 -1.10926463752281e-01 + 9.52576323187684e-02 -1.07596450900910e-01 + 8.77890248291223e-02 -1.04462641719461e-01 + 8.04931796353551e-02 -1.01301294317992e-01 + 7.35128190911369e-02 -9.78736275580912e-02 + 6.68963895240495e-02 -9.40003856565595e-02 + 6.05009896751561e-02 -8.99475473560910e-02 + 5.41691079982236e-02 -8.60337352895419e-02 + 4.77847233189376e-02 -8.24016920600191e-02 + 4.16000737650022e-02 -7.87323954691971e-02 + 3.58929498807395e-02 -7.46615383996122e-02 + 3.05718156448606e-02 -7.01640817880520e-02 + 2.55841457444921e-02 -6.54750339821926e-02 + 2.08026533112682e-02 -6.07371500023589e-02 + 1.63439586202605e-02 -5.58344930848473e-02 + 1.26739780200523e-02 -5.06379447657982e-02 + 9.64255085974439e-03 -4.50568616338899e-02 + 6.95205676239145e-03 -3.93718854579150e-02 + 4.20584482318000e-03 -3.38153278580581e-02 + 1.88154483510298e-03 -2.82556740113477e-02 + 1.09259224757715e-03 -2.25793808835637e-02 + 5.57027370894427e-04 -1.68301482885243e-02 + 1.92532044605606e-04 -1.11001611628179e-02 + 7.52083255272135e-06 -5.47188430262417e-03 + 0.00000000000000e+00 0.00000000000000e+00 + 1.17486562914811e-04 5.48679985210707e-03 + 3.45293358213107e-04 1.10987098718478e-02 + 6.76028572561267e-04 1.68193159983466e-02 + 1.10074682910982e-03 2.26297904761801e-02 + 1.60992601121548e-03 2.85087154571350e-02 + 2.67599544106549e-03 3.44493853796572e-02 + 4.39289337028668e-03 4.04593247588465e-02 + 6.27509694854768e-03 4.65396355123101e-02 + 8.18501856800657e-03 5.27292560994769e-02 + 1.03189035753580e-02 5.90079710526583e-02 + 1.27370291299606e-02 6.52938850681379e-02 + 1.55557604269686e-02 7.14974882867604e-02 + 1.89758697009180e-02 7.76144942393735e-02 + 2.27125265955629e-02 8.37568225375172e-02 + 2.64205973892604e-02 9.00529677985623e-02 + 3.01282733583995e-02 9.65285394067050e-02 + 3.39926189539913e-02 1.03078210289796e-01 + 3.81573198488582e-02 1.09576659446866e-01 + 4.27861195062449e-02 1.15924379625249e-01 + 4.78311663375292e-02 1.22194138387785e-01 + 5.30764574325103e-02 1.28517196960692e-01 + 5.83111363244493e-02 1.35033938551462e-01 + 6.35760553124462e-02 1.41734309721268e-01 + 6.90274085645503e-02 1.48474163992816e-01 + 7.48336167040122e-02 1.55069663963807e-01 + 8.11611766171277e-02 1.61401120064374e-01 + 8.79191588167710e-02 1.67593332097610e-01 + 9.48826093561019e-02 1.73826214118695e-01 + 1.01844855099363e-01 1.80284855885651e-01 + 1.08870960569728e-01 1.86945163887416e-01 + 1.16112032555569e-01 1.93604681567356e-01 + 1.23730351466839e-01 2.00035948444507e-01 + 1.31824094660795e-01 2.06181698317671e-01 + 1.40296730825128e-01 2.12179485190627e-01 + 1.48993250461499e-01 2.18163657713048e-01 + 1.57819272344995e-01 2.24246096031123e-01 + 1.66852794875010e-01 2.30358166418523e-01 + 1.76155620082319e-01 2.36368608053698e-01 + 1.85787867463952e-01 2.42168413364266e-01 + 1.95750148009566e-01 2.47820613232954e-01 + 2.06011532032752e-01 2.53317180198825e-01 + 2.16542581694721e-01 2.58641479671493e-01 + 2.27367855996913e-01 2.63825228256786e-01 + 2.38481776223131e-01 2.68855474330982e-01 + 2.49861589948929e-01 2.73698630151439e-01 + 2.61511196031386e-01 2.78418546610769e-01 + 2.73444081521194e-01 2.82942196705218e-01 + 2.85666898746156e-01 2.87119018069479e-01 + 2.98200734062047e-01 2.91001132958173e-01 + 3.11032065305424e-01 2.94621877568295e-01 + 3.24124539258925e-01 2.97872294592512e-01 + 3.37489921714358e-01 3.00767227942365e-01 + 3.51122091139916e-01 3.03395484009736e-01 + 3.64973840498426e-01 3.05782280483364e-01 + 3.79035138325125e-01 3.08249753379266e-01 + 3.93322041497236e-01 3.10433221242496e-01 + 4.07839547608925e-01 3.11538517913751e-01 + 4.22602719706730e-01 3.12017813468019e-01 + 4.37571388858179e-01 3.12308843703191e-01 + 4.52705694129202e-01 3.12333639153740e-01 + 4.68022386434649e-01 3.11853160827979e-01 + 4.83493649847560e-01 3.10957551960417e-01 + 4.99066517917555e-01 3.09764580509872e-01 + 5.14753065556197e-01 3.07600736594501e-01 + 5.30536608928272e-01 3.04749547523736e-01 + 5.46385724990049e-01 3.01659366948820e-01 + 5.62295818718890e-01 2.97977515095747e-01 + 5.78294553201899e-01 2.93910589456047e-01 + 5.94402144736603e-01 2.89716319978192e-01 + 6.10601043028817e-01 2.85246570693586e-01 + 6.26909980423233e-01 2.80596756484263e-01 + 6.43345516347184e-01 2.75862073462143e-01 + 6.59894609560225e-01 2.70990265506853e-01 + 6.76549242992279e-01 2.65977472599385e-01 + 6.93285667658481e-01 2.60762532727095e-01 + 7.10113002149428e-01 2.55379870427853e-01 + 7.27101101620968e-01 2.50077155704390e-01 + 7.44309174064674e-01 2.45048240418275e-01 + 7.61658961677203e-01 2.40058424294836e-01 + 7.79018980351826e-01 2.34727092866611e-01 + 7.96358584077290e-01 2.28942034208237e-01 + 8.13753854561790e-01 2.22958342564097e-01 + 8.31270319341910e-01 2.17014377218330e-01 + 8.48885104644356e-01 2.11048726086036e-01 + 8.66584330124259e-01 2.05031932644156e-01 + 8.84350172928721e-01 1.98925268297828e-01 + 9.02193707353903e-01 1.92773917580206e-01 + 9.20157773678337e-01 1.86723259912781e-01 + 9.38246381637406e-01 1.80792430732304e-01 + 9.56399217082597e-01 1.74918496768106e-01 + 9.76798363881330e-01 1.69533670492790e-01 + 9.84828566855567e-01 1.59247090588959e-01 + 9.87839059292136e-01 1.39199540261784e-01 + 9.89905373069722e-01 1.17616603808733e-01 + 9.91757893422502e-01 9.85412138534034e-02 + 9.93252480473954e-01 7.94410871228046e-02 + 9.94743975611726e-01 6.01627278016894e-02 + 9.96445705560557e-01 4.08626126297221e-02 + 9.98198658774545e-01 2.15548416438615e-02 + 1.00000000000000e+00 2.24462872737125e-03 diff --git a/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF05_Coords.txt b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF05_Coords.txt new file mode 100644 index 00000000..e390be98 --- /dev/null +++ b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF05_Coords.txt @@ -0,0 +1,208 @@ + 201 NumCoords ! The number of coordinates in the airfoil shape file (including an extra coordinate for airfoil reference). Set to zero if coordinates not included. +! ......... x-y coordinates are next if NumCoords > 0 ............. +! x-y coordinate of airfoil reference +! x/c y/c + 0.250000 0 +! coordinates of airfoil shape +! interpolation to 200 points +! x/c y/c + 1.00000000000000e+00 -1.79613835013314e-02 + 9.96961558343373e-01 -3.53902489488287e-02 + 9.92023630619313e-01 -4.91929101534255e-02 + 9.84379446083511e-01 -6.00348210114478e-02 + 9.75468141678190e-01 -7.09859658723328e-02 + 9.66631278884337e-01 -8.10763642717688e-02 + 9.55798039282918e-01 -8.89193213483636e-02 + 9.40573198850503e-01 -9.51466796435252e-02 + 9.25558881802059e-01 -9.98612000663832e-02 + 9.10156047961303e-01 -1.03818167988873e-01 + 8.94845249828711e-01 -1.07053770498790e-01 + 8.79788764043181e-01 -1.10793970812780e-01 + 8.64816289515449e-01 -1.14657288651007e-01 + 8.49854909867423e-01 -1.18332319693786e-01 + 8.34868122131193e-01 -1.21755694040649e-01 + 8.19932031659274e-01 -1.25185347068945e-01 + 8.05100969303777e-01 -1.28769954116135e-01 + 7.90321333537330e-01 -1.32315399189505e-01 + 7.75523132904363e-01 -1.35552178535652e-01 + 7.60741767498039e-01 -1.38522987025004e-01 + 7.46023130239504e-01 -1.41378450540013e-01 + 7.31401419294347e-01 -1.44351973608261e-01 + 7.16841539978852e-01 -1.47259170049408e-01 + 7.02302981796658e-01 -1.49894404232336e-01 + 6.87793305289350e-01 -1.52332219473336e-01 + 6.73332858807799e-01 -1.54446440090132e-01 + 6.58925185976507e-01 -1.56177321792256e-01 + 6.44572195057741e-01 -1.57666344545681e-01 + 6.30298458454963e-01 -1.58910640661020e-01 + 6.16114416580374e-01 -1.59951057500702e-01 + 6.02026953030919e-01 -1.60900948878695e-01 + 5.88050398086629e-01 -1.61711857451049e-01 + 5.74189109055960e-01 -1.62294350346538e-01 + 5.60448390812326e-01 -1.62664500132555e-01 + 5.46836999554392e-01 -1.62937231340188e-01 + 5.33367864981090e-01 -1.63248884154172e-01 + 5.19932409233419e-01 -1.63449902911388e-01 + 5.06477442605548e-01 -1.63417485627504e-01 + 4.93144035884787e-01 -1.63328228686621e-01 + 4.79941368474168e-01 -1.63060331436217e-01 + 4.66871737010151e-01 -1.62569827406711e-01 + 4.53934990999079e-01 -1.62070487200764e-01 + 4.41133168558923e-01 -1.61632173585030e-01 + 4.28463654391992e-01 -1.61187532275481e-01 + 4.15933178526276e-01 -1.60548880877149e-01 + 4.03555052687744e-01 -1.59798188531010e-01 + 3.91342756149186e-01 -1.58846604242981e-01 + 3.79289683322135e-01 -1.57540790079054e-01 + 3.67375264219574e-01 -1.56189884356924e-01 + 3.55580233434555e-01 -1.55081224503574e-01 + 3.43903993529589e-01 -1.54105712386970e-01 + 3.32371689603571e-01 -1.53109720354745e-01 + 3.21008399939002e-01 -1.51964778739524e-01 + 3.09818365007830e-01 -1.50611104402699e-01 + 2.98789403182843e-01 -1.49154888767305e-01 + 2.87915260467706e-01 -1.47707797499490e-01 + 2.77192797094198e-01 -1.46295028972452e-01 + 2.66634642137323e-01 -1.44782680901920e-01 + 2.56243230473741e-01 -1.43092118304113e-01 + 2.46011513861498e-01 -1.41179312266907e-01 + 2.35923227561334e-01 -1.39187527359477e-01 + 2.25978716650481e-01 -1.37235092846332e-01 + 2.16205677937271e-01 -1.35310903535781e-01 + 2.06778722942050e-01 -1.33322871209808e-01 + 1.97516042359716e-01 -1.31227497717662e-01 + 1.88427440008692e-01 -1.28991125900883e-01 + 1.79502980110518e-01 -1.26649399614310e-01 + 1.70733325816940e-01 -1.24213566866553e-01 + 1.62098170428490e-01 -1.21762260683871e-01 + 1.53596861253099e-01 -1.19338023194216e-01 + 1.45242024458811e-01 -1.16964714586022e-01 + 1.37059827832412e-01 -1.14553161865558e-01 + 1.29058111671005e-01 -1.12011104818429e-01 + 1.21217330976586e-01 -1.09333580954571e-01 + 1.13490793020045e-01 -1.06582482287198e-01 + 1.05872478787586e-01 -1.03835726838741e-01 + 9.84312049808396e-02 -1.01090373016527e-01 + 9.12178971287871e-02 -9.82756005290104e-02 + 8.42187577306301e-02 -9.53136441369315e-02 + 7.73955759457572e-02 -9.22209615041234e-02 + 7.07054294736601e-02 -8.89789985808886e-02 + 6.41548755011769e-02 -8.56689842703127e-02 + 5.77914057011829e-02 -8.22370633159429e-02 + 5.16081911372133e-02 -7.87250303745277e-02 + 4.56080027670407e-02 -7.51373524837015e-02 + 3.97932691904809e-02 -7.13640514386860e-02 + 3.41289275285710e-02 -6.73803370811387e-02 + 2.88546712589916e-02 -6.31532691299288e-02 + 2.39831240698773e-02 -5.86665495096452e-02 + 1.94527821619992e-02 -5.39591200958821e-02 + 1.53491720497801e-02 -4.90523270599134e-02 + 1.16943357256612e-02 -4.38406284119954e-02 + 8.65365253109135e-03 -3.84459455205228e-02 + 5.92370160379059e-03 -3.30114750896427e-02 + 3.46212829965803e-03 -2.75812253497000e-02 + 1.58454458640205e-03 -2.21027074392882e-02 + 7.35715040582169e-04 -1.65321192119310e-02 + 2.97907005116705e-04 -1.09279875504530e-02 + 5.30676565098627e-05 -5.39101103138609e-03 + 0.00000000000000e+00 0.00000000000000e+00 + 9.16249484271071e-05 5.39472463076042e-03 + 2.97114014867658e-04 1.09125341734703e-02 + 6.07765485359921e-04 1.65347368419011e-02 + 1.01319685944283e-03 2.22398721797630e-02 + 1.57860720361388e-03 2.80048570638302e-02 + 2.85770205402702e-03 3.38268128923488e-02 + 4.60485640943450e-03 3.97136792782237e-02 + 6.36963363495096e-03 4.56791798263678e-02 + 8.27460103313730e-03 5.17469828248211e-02 + 1.04559502964479e-02 5.78621045555090e-02 + 1.30787206403767e-02 6.39307928915866e-02 + 1.62476019915294e-02 6.99136016610049e-02 + 1.97064472281925e-02 7.58656576746356e-02 + 2.32055551437451e-02 8.18956044570781e-02 + 2.67780264071069e-02 8.80520763606948e-02 + 3.05536180174887e-02 9.43034458705317e-02 + 3.46895645314508e-02 1.00552628487572e-01 + 3.91594998227274e-02 1.06753941085293e-01 + 4.38513894815309e-02 1.12886816803394e-01 + 4.86469345513260e-02 1.19031991526595e-01 + 5.35662818491533e-02 1.25246183971636e-01 + 5.86765310389434e-02 1.31515765400035e-01 + 6.41158119407387e-02 1.37430772030919e-01 + 6.98941360883445e-02 1.43254800103538e-01 + 7.59170877123488e-02 1.49053754727573e-01 + 8.21227682881698e-02 1.54888203928039e-01 + 8.85359454387846e-02 1.60747975413262e-01 + 9.51513059583106e-02 1.66598125672197e-01 + 1.01977161405040e-01 1.72421724747484e-01 + 1.09029076244286e-01 1.78602175887026e-01 + 1.16324626112349e-01 1.84952513492490e-01 + 1.23886862179539e-01 1.91028384041450e-01 + 1.31793661272858e-01 1.96904454248269e-01 + 1.40137015144785e-01 2.02603209487098e-01 + 1.48722392856665e-01 2.08131821762515e-01 + 1.57498055037009e-01 2.13566417662387e-01 + 1.66499738307440e-01 2.18924804988545e-01 + 1.75746807567001e-01 2.24209223798866e-01 + 1.85282812844636e-01 2.29419693016131e-01 + 1.95126003842738e-01 2.34424150993428e-01 + 2.05278382458868e-01 2.39064246909332e-01 + 2.15728458898676e-01 2.43395275762812e-01 + 2.26448399402852e-01 2.47609942869563e-01 + 2.37390616140716e-01 2.51915193162418e-01 + 2.48555223136142e-01 2.56240468008173e-01 + 2.59983581489374e-01 2.60218095713622e-01 + 2.71719323509248e-01 2.63616598352372e-01 + 2.83748575426622e-01 2.66632889055311e-01 + 2.96041798832288e-01 2.69453390481384e-01 + 3.08575060192042e-01 2.72409404922417e-01 + 3.21340186072523e-01 2.75012415222477e-01 + 3.34353685398402e-01 2.76492953153595e-01 + 3.47617985877095e-01 2.77530644029356e-01 + 3.61086047806733e-01 2.78478291157024e-01 + 3.74735967198890e-01 2.79421812258223e-01 + 3.88584839416611e-01 2.80075134954841e-01 + 4.02610569745306e-01 2.80158921396025e-01 + 4.16769966222890e-01 2.79426952940989e-01 + 4.31000767416746e-01 2.77780180205803e-01 + 4.45367430099069e-01 2.75892299873811e-01 + 4.59886426162136e-01 2.73764712702610e-01 + 4.74522704612306e-01 2.71235104254327e-01 + 4.89216780464507e-01 2.68272718312492e-01 + 5.03966776199603e-01 2.64447118696879e-01 + 5.18806020666685e-01 2.60200052632834e-01 + 5.33757172542646e-01 2.56033656152525e-01 + 5.48800417061940e-01 2.51670207782890e-01 + 5.63928433117745e-01 2.47052734150705e-01 + 5.79139293361131e-01 2.42196437539003e-01 + 5.94438582209324e-01 2.37156310638374e-01 + 6.09857099330908e-01 2.32081069158076e-01 + 6.25400870520805e-01 2.26991368536271e-01 + 6.41058606965589e-01 2.21852557624183e-01 + 6.56827119257239e-01 2.16670545580237e-01 + 6.72692401163725e-01 2.11435826592181e-01 + 6.88658261530256e-01 2.06153724323127e-01 + 7.04768588597026e-01 2.00939949019601e-01 + 7.21023238876672e-01 1.95698405223399e-01 + 7.37357768356274e-01 1.90224737500501e-01 + 7.53717588941763e-01 1.84447648187462e-01 + 7.70112763502082e-01 1.78479680783297e-01 + 7.86578143910845e-01 1.72394810225689e-01 + 8.03184229023836e-01 1.66738239461448e-01 + 8.19942143394421e-01 1.61342896059017e-01 + 8.36804795974800e-01 1.55942560425342e-01 + 8.53725343344330e-01 1.50402193026770e-01 + 8.70748946763591e-01 1.44842377351049e-01 + 8.87946529574867e-01 1.39474077514211e-01 + 9.05306293149628e-01 1.34235143291426e-01 + 9.22545067587843e-01 1.28920314434417e-01 + 9.40600734347715e-01 1.23754776734464e-01 + 9.53048939484955e-01 1.16864623799960e-01 + 9.63077773676104e-01 1.06395431570647e-01 + 9.72474093255454e-01 9.57868792253965e-02 + 9.81179655916868e-01 8.60931773916215e-02 + 9.88539472463695e-01 7.50338503152747e-02 + 9.93965264664499e-01 5.85418242094117e-02 + 9.96759513501900e-01 4.07113376276323e-02 + 9.98822819206952e-01 2.22334005961241e-02 + 1.00000000000000e+00 3.03882619127306e-03 diff --git a/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF06_Coords.txt b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF06_Coords.txt new file mode 100644 index 00000000..9931444e --- /dev/null +++ b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF06_Coords.txt @@ -0,0 +1,208 @@ + 201 NumCoords ! The number of coordinates in the airfoil shape file (including an extra coordinate for airfoil reference). Set to zero if coordinates not included. +! ......... x-y coordinates are next if NumCoords > 0 ............. +! x-y coordinate of airfoil reference +! x/c y/c + 0.250000 0 +! coordinates of airfoil shape +! interpolation to 200 points +! x/c y/c + 1.00000000000000e+00 -1.13904183263968e-02 + 9.97616112402170e-01 -3.02925242439361e-02 + 9.92090053782966e-01 -4.09226344496437e-02 + 9.78779505574386e-01 -4.46317953566502e-02 + 9.62630848882990e-01 -4.78657079982365e-02 + 9.48002016685502e-01 -5.14602797602320e-02 + 9.33316247673508e-01 -5.51593031128816e-02 + 9.18496232612161e-01 -5.92254605712216e-02 + 9.03703201804367e-01 -6.31663589833213e-02 + 8.88853928485311e-01 -6.68255900117923e-02 + 8.74049386501296e-01 -7.05161511584427e-02 + 8.59334016743915e-01 -7.43874436875609e-02 + 8.44688974778042e-01 -7.83626507822871e-02 + 8.30107202160351e-01 -8.23961121367229e-02 + 8.15594575089335e-01 -8.65047449737667e-02 + 8.01218061118175e-01 -9.08578559827087e-02 + 7.87017154459310e-01 -9.56014747506557e-02 + 7.72867465331189e-01 -1.00310586221221e-01 + 7.58658127516040e-01 -1.04602689055293e-01 + 7.44454533959962e-01 -1.08689082390743e-01 + 7.30359770774575e-01 -1.12881924651599e-01 + 7.16430384005105e-01 -1.17399987158617e-01 + 7.02548411333571e-01 -1.21769749655608e-01 + 6.88587907939929e-01 -1.25508162707915e-01 + 6.74579309967017e-01 -1.28831256546796e-01 + 6.60588643228054e-01 -1.31814109374650e-01 + 6.46644883677572e-01 -1.34518684272535e-01 + 6.32738136446085e-01 -1.36970560657454e-01 + 6.18888539380060e-01 -1.39099781158483e-01 + 6.05094599842353e-01 -1.40925423892468e-01 + 5.91370497948358e-01 -1.42548078837611e-01 + 5.77742681423787e-01 -1.44039268742623e-01 + 5.64210789942644e-01 -1.45418710112677e-01 + 5.50776369602557e-01 -1.46660362777981e-01 + 5.37444968071300e-01 -1.47785036756530e-01 + 5.24218800582908e-01 -1.48883649416298e-01 + 5.11096793180140e-01 -1.49725747746255e-01 + 4.98077600261809e-01 -1.50190862529385e-01 + 4.85165286248710e-01 -1.50548451423256e-01 + 4.72371838173648e-01 -1.50709025323563e-01 + 4.59704855658886e-01 -1.50660182339889e-01 + 4.47162353937939e-01 -1.50610036032676e-01 + 4.34748236821129e-01 -1.50574316591260e-01 + 4.22462962227877e-01 -1.50466331413989e-01 + 4.10307413565604e-01 -1.50120854962051e-01 + 3.98293549815832e-01 -1.49646376138536e-01 + 3.86431947049557e-01 -1.48985011501092e-01 + 3.74719035040848e-01 -1.47937284203969e-01 + 3.63143253860895e-01 -1.46805960127425e-01 + 3.51694487399415e-01 -1.45836094033469e-01 + 3.40375820106151e-01 -1.44917425523182e-01 + 3.29200242436979e-01 -1.43946965381053e-01 + 3.18179373560524e-01 -1.42835461865229e-01 + 3.07312147043483e-01 -1.41563685586535e-01 + 2.96589198655950e-01 -1.40239218363699e-01 + 2.86000302805324e-01 -1.38971039533067e-01 + 2.75538569884689e-01 -1.37776349074027e-01 + 2.65231088919120e-01 -1.36509074431539e-01 + 2.55105124935306e-01 -1.35017464348563e-01 + 2.45163330716385e-01 -1.33182240433968e-01 + 2.35380065561362e-01 -1.31184297306223e-01 + 2.25731797335499e-01 -1.29236565554543e-01 + 2.16212918345480e-01 -1.27375368900912e-01 + 2.06869737828596e-01 -1.25493378403087e-01 + 1.97692792848475e-01 -1.23508013308052e-01 + 1.88692178275185e-01 -1.21356126184016e-01 + 1.79852140135191e-01 -1.19094041300472e-01 + 1.71155287788632e-01 -1.16810198318667e-01 + 1.62583572203815e-01 -1.14572084308225e-01 + 1.54148627233356e-01 -1.12333771605582e-01 + 1.45882282736195e-01 -1.10017484528559e-01 + 1.37813705509852e-01 -1.07521934723333e-01 + 1.29924389454779e-01 -1.04868618458173e-01 + 1.22160459722846e-01 -1.02232244909791e-01 + 1.14462997638161e-01 -9.97769981877239e-02 + 1.06850950889400e-01 -9.74418050455991e-02 + 9.94456540823707e-02 -9.49708378396853e-02 + 9.23374027952569e-02 -9.21230511653797e-02 + 8.54657300321368e-02 -8.89658600035733e-02 + 7.87212757634630e-02 -8.58036899472230e-02 + 7.20187471524862e-02 -8.28315669774048e-02 + 6.54246409525636e-02 -7.99018939763046e-02 + 5.90704249471530e-02 -7.68099610722217e-02 + 5.30035679474469e-02 -7.34323254403719e-02 + 4.71239339609886e-02 -6.99340905790686e-02 + 4.13031360007540e-02 -6.65329912958667e-02 + 3.55234699482794e-02 -6.32184019501613e-02 + 3.01619829327107e-02 -5.96139288290971e-02 + 2.53031775785438e-02 -5.54778043544704e-02 + 2.08048174587776e-02 -5.10511978893060e-02 + 1.65388584263945e-02 -4.65627010925328e-02 + 1.26090766129194e-02 -4.18918267420981e-02 + 9.43378362085923e-03 -3.69337921085883e-02 + 6.78961770854852e-03 -3.16963231219606e-02 + 4.34237637716249e-03 -2.64747404683854e-02 + 1.85598728281019e-03 -2.13060647449452e-02 + 8.70334950751159e-04 -1.60204557614650e-02 + 3.78614157542381e-04 -1.06258278582999e-02 + 8.34360366869797e-05 -5.24793360453415e-03 + 0.00000000000000e+00 0.00000000000000e+00 + 7.67236867486678e-05 5.23517737179421e-03 + 2.69353450923468e-04 1.05899507024689e-02 + 5.68432823980679e-04 1.60424452959359e-02 + 9.62751245980932e-04 2.15677746016270e-02 + 1.56056154959061e-03 2.71408610938964e-02 + 2.93760353810514e-03 3.27643997804523e-02 + 4.68388731306286e-03 3.84466954603457e-02 + 6.39829873698727e-03 4.42192833035362e-02 + 8.30088094239591e-03 5.00830587126182e-02 + 1.04968991067837e-02 5.59331418219662e-02 + 1.31905356506929e-02 6.16590402853706e-02 + 1.64944927228985e-02 6.72926557763616e-02 + 1.99584847680105e-02 7.29780548965268e-02 + 2.33603947254173e-02 7.88193742129969e-02 + 2.68842534255446e-02 8.47441200649158e-02 + 3.06808954672960e-02 9.06322348821772e-02 + 3.49084527320684e-02 9.63920127695594e-02 + 3.94874921561364e-02 1.02093915910307e-01 + 4.41979239135200e-02 1.07851341351126e-01 + 4.88991643814045e-02 1.13771751479133e-01 + 5.37085410028852e-02 1.19785527662613e-01 + 5.87799300044820e-02 1.25738707322743e-01 + 6.42723709032797e-02 1.31439519919589e-01 + 7.01563729259333e-02 1.37001677458821e-01 + 7.62522111785621e-02 1.42563767678454e-01 + 8.24142000324228e-02 1.48247461470601e-01 + 8.87141756594531e-02 1.54005995560218e-01 + 9.52252089668619e-02 1.59738341000206e-01 + 1.02012827165119e-01 1.65362107222581e-01 + 1.09071839770933e-01 1.71005609066199e-01 + 1.16382532480666e-01 1.76625410480436e-01 + 1.23929157304783e-01 1.82119310647882e-01 + 1.31734456855347e-01 1.87537907766897e-01 + 1.39830632988419e-01 1.92818237288258e-01 + 1.48208290383940e-01 1.97881178099860e-01 + 1.56890640982985e-01 2.02754105050709e-01 + 1.65833248340983e-01 2.07492675263682e-01 + 1.74977872658223e-01 2.12167028768671e-01 + 1.84339215056554e-01 2.16828518735710e-01 + 1.93969002461360e-01 2.21262214470146e-01 + 2.03927738995053e-01 2.25232399682506e-01 + 2.14233998923319e-01 2.28819156679255e-01 + 2.24768775871601e-01 2.32298339432912e-01 + 2.35414724132119e-01 2.35983917716678e-01 + 2.46214765126001e-01 2.39788864290029e-01 + 2.57273968847626e-01 2.43131931500378e-01 + 2.68683262153020e-01 2.45701077047944e-01 + 2.80394161446840e-01 2.47884449864113e-01 + 2.92298014116652e-01 2.49928845873406e-01 + 3.04358015522582e-01 2.52310200009780e-01 + 3.16612004841116e-01 2.54366837382113e-01 + 3.29084707645504e-01 2.54944026733475e-01 + 3.41791574758934e-01 2.55013657780952e-01 + 3.54686633087091e-01 2.55077224740846e-01 + 3.67732287456134e-01 2.55080989890258e-01 + 3.80947927549799e-01 2.54809270763009e-01 + 3.94277125966556e-01 2.54299155434133e-01 + 4.07679990408069e-01 2.52964484309584e-01 + 4.21176069905831e-01 2.50460618119005e-01 + 4.34780235148961e-01 2.47779904156950e-01 + 4.48508915785030e-01 2.45032787159418e-01 + 4.62324554197701e-01 2.41951247240081e-01 + 4.76168679634616e-01 2.38443526187009e-01 + 4.90026518395832e-01 2.34310030235241e-01 + 5.03986607097025e-01 2.29965169629546e-01 + 5.18124607276385e-01 2.25794521855877e-01 + 5.32402710892978e-01 2.21622952392128e-01 + 5.46773333755108e-01 2.17288635068298e-01 + 5.61209497775237e-01 2.12697198172799e-01 + 5.75739948251087e-01 2.07963361115272e-01 + 5.90401181915651e-01 2.03229629742975e-01 + 6.05186266686445e-01 1.98479319175866e-01 + 6.20086166342671e-01 1.93692356863453e-01 + 6.35097907187523e-01 1.88871403344983e-01 + 6.50216806205491e-01 1.84017547463539e-01 + 6.65438113197408e-01 1.79123980133843e-01 + 6.80773250934036e-01 1.74228906733020e-01 + 6.96172960729631e-01 1.69180559493466e-01 + 7.11585661998256e-01 1.63830547989403e-01 + 7.27034942498605e-01 1.58268579741071e-01 + 7.42558721683669e-01 1.52649157462292e-01 + 7.58144383438193e-01 1.46939483520203e-01 + 7.73847783484881e-01 1.41394650866481e-01 + 7.89701647082685e-01 1.36067884587493e-01 + 8.05635711733308e-01 1.30738018396962e-01 + 8.21581445293506e-01 1.25220232868624e-01 + 8.37586124515025e-01 1.19666988037264e-01 + 8.53726898147738e-01 1.14318888381174e-01 + 8.69963585585765e-01 1.09065119635605e-01 + 8.86190226070913e-01 1.03619764994052e-01 + 9.02483979686875e-01 9.80682052774082e-02 + 9.18558853276680e-01 9.26538040770285e-02 + 9.34548045768020e-01 8.73262649268327e-02 + 9.50649300724702e-01 8.23994229326946e-02 + 9.66427399966504e-01 7.70749674918775e-02 + 9.80999886673880e-01 6.90076199367232e-02 + 9.92612066213372e-01 5.56165891750792e-02 + 9.96940327203726e-01 4.00048120288691e-02 + 9.99182455606956e-01 2.29517217456512e-02 + 1.00000000000000e+00 4.20817591936930e-03 diff --git a/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF07_Coords.txt b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF07_Coords.txt new file mode 100644 index 00000000..ce777e0d --- /dev/null +++ b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF07_Coords.txt @@ -0,0 +1,208 @@ + 201 NumCoords ! The number of coordinates in the airfoil shape file (including an extra coordinate for airfoil reference). Set to zero if coordinates not included. +! ......... x-y coordinates are next if NumCoords > 0 ............. +! x-y coordinate of airfoil reference +! x/c y/c + 0.250000 0 +! coordinates of airfoil shape +! interpolation to 200 points +! x/c y/c + 1.00000000000000e+00 -7.22169847721207e-03 + 9.93657635607014e-01 -9.80951552444892e-03 + 9.85015925953616e-01 -1.30850106016452e-02 + 9.68838039545111e-01 -1.84611077131393e-02 + 9.50612974422184e-01 -2.33823451641766e-02 + 9.34054843802496e-01 -2.68598144161353e-02 + 9.17904876813281e-01 -2.92032016919475e-02 + 9.02410145568755e-01 -3.25195649501926e-02 + 8.86984531818462e-01 -3.63341125283542e-02 + 8.71653146034245e-01 -4.02779399999799e-02 + 8.56421678685942e-01 -4.44297430955853e-02 + 8.41297341579872e-01 -4.88277542480629e-02 + 8.26299922405764e-01 -5.34725994663518e-02 + 8.11418218122957e-01 -5.83063399795375e-02 + 7.96668059771363e-01 -6.33518858746505e-02 + 7.82093073102221e-01 -6.86691608646314e-02 + 7.67715947269790e-01 -7.43397495082482e-02 + 7.53432129505621e-01 -8.00400824090274e-02 + 7.39140921507287e-01 -8.54783114096485e-02 + 7.24887781938029e-01 -9.07927090242104e-02 + 7.10763647733484e-01 -9.62089130617438e-02 + 6.96813846978418e-01 -1.01849003923843e-01 + 6.82926720247006e-01 -1.07345616986875e-01 + 6.68987494011958e-01 -1.12341932591132e-01 + 6.55015055372256e-01 -1.16974857778111e-01 + 6.41069653036586e-01 -1.21324695308618e-01 + 6.27178381576740e-01 -1.25441039708115e-01 + 6.13325927341839e-01 -1.29300851927610e-01 + 5.99526121249635e-01 -1.32836295356277e-01 + 5.85782516774879e-01 -1.36082768510397e-01 + 5.72099418530029e-01 -1.39062285229702e-01 + 5.58500671454668e-01 -1.41826434136283e-01 + 5.44989585070756e-01 -1.44410477552523e-01 + 5.31572041625452e-01 -1.46801987807261e-01 + 5.18249443006677e-01 -1.48965339749430e-01 + 5.05024114284701e-01 -1.51306014609625e-01 + 4.91903544204855e-01 -1.53396356865900e-01 + 4.78886537168064e-01 -1.55029927452596e-01 + 4.65973152938946e-01 -1.56361009079535e-01 + 4.53179119201583e-01 -1.57373248363793e-01 + 4.40511641089995e-01 -1.58032071375895e-01 + 4.27973254627328e-01 -1.58511320266496e-01 + 4.15569568070292e-01 -1.58830392050982e-01 + 4.03305571015855e-01 -1.58908632350926e-01 + 3.91181433267754e-01 -1.58751137788738e-01 + 3.79208355061609e-01 -1.58402513518675e-01 + 3.67395164279636e-01 -1.57823599361342e-01 + 3.55740722338427e-01 -1.56880132251604e-01 + 3.44238533276691e-01 -1.55825370105009e-01 + 3.32890410142460e-01 -1.54776742866931e-01 + 3.21695626476537e-01 -1.53702620246411e-01 + 3.10660511859208e-01 -1.52547932345675e-01 + 2.99792418198384e-01 -1.51236406478805e-01 + 2.89088689354766e-01 -1.49773471325457e-01 + 2.78543651775726e-01 -1.48236644042898e-01 + 2.68149273917489e-01 -1.46704827592144e-01 + 2.57896406226205e-01 -1.45208435280521e-01 + 2.47810593764685e-01 -1.43640086484094e-01 + 2.37924398764870e-01 -1.41871396589496e-01 + 2.28243375505465e-01 -1.39800943847393e-01 + 2.18746002754731e-01 -1.37561331679565e-01 + 2.09407739643021e-01 -1.35323082679671e-01 + 2.00204632082914e-01 -1.33142628436607e-01 + 1.91097767708039e-01 -1.30937919464830e-01 + 1.82170786872752e-01 -1.28640807136328e-01 + 1.73438864168049e-01 -1.26185420973317e-01 + 1.64887367765774e-01 -1.23622391399294e-01 + 1.56497023195920e-01 -1.21049752796620e-01 + 1.48258982483410e-01 -1.18508626502639e-01 + 1.40184001337527e-01 -1.15939910025142e-01 + 1.32310114080237e-01 -1.13239907331215e-01 + 1.24637510518848e-01 -1.10361154607051e-01 + 1.17138359086711e-01 -1.07372231954189e-01 + 1.09808401127193e-01 -1.04399442414758e-01 + 1.02594618944679e-01 -1.01600341650075e-01 + 9.54864171319728e-02 -9.89295946584694e-02 + 8.85996519559139e-02 -9.61035248577797e-02 + 8.20051916775647e-02 -9.28926032526868e-02 + 7.56369542864789e-02 -8.94141742247751e-02 + 6.94224285943848e-02 -8.59586167133803e-02 + 6.33063696107793e-02 -8.27169512241728e-02 + 5.73252083536456e-02 -7.95397742824449e-02 + 5.15865051316583e-02 -7.61848830062020e-02 + 4.61300367417238e-02 -7.25118010504582e-02 + 4.08738115912319e-02 -6.87276051345213e-02 + 3.57389328883182e-02 -6.50758836466640e-02 + 3.07040311089050e-02 -6.15616444241208e-02 + 2.60327010981162e-02 -5.78249541857669e-02 + 2.18044848917305e-02 -5.36151169153552e-02 + 1.79125721708463e-02 -4.91694235722464e-02 + 1.42640650272980e-02 -4.47148049333326e-02 + 1.09301665102860e-02 -4.01661895085117e-02 + 8.21488787888461e-03 -3.53822053138899e-02 + 5.97345205176603e-03 -3.03209729737249e-02 + 3.91406699176672e-03 -2.52857837799812e-02 + 1.81775566819190e-03 -2.03309654023002e-02 + 9.12160954949108e-04 -1.52977122324043e-02 + 4.02582765125064e-04 -1.01721928519313e-02 + 8.81962189848521e-05 -5.04398886153351e-03 + 0.00000000000000e+00 0.00000000000000e+00 + 7.88481242318804e-05 4.71135299425895e-03 + 2.80754052876520e-04 9.46261288508707e-03 + 6.13006828585368e-04 1.43031715472917e-02 + 1.05300322116593e-03 1.92164339057439e-02 + 1.65902417833529e-03 2.41858280981452e-02 + 2.88604628288041e-03 2.92144066457047e-02 + 4.45666746110958e-03 3.43052576770996e-02 + 6.03753907265340e-03 3.94795983867471e-02 + 7.82960449484624e-03 4.47233966620429e-02 + 9.91655407404961e-03 4.99442035624549e-02 + 1.24284772687387e-02 5.50687705625851e-02 + 1.54763292167825e-02 6.01250554953811e-02 + 1.86843960997679e-02 6.52596352562490e-02 + 2.18962093706069e-02 7.05324271196803e-02 + 2.52784929759404e-02 7.58378592538172e-02 + 2.89300636094216e-02 8.10694276026404e-02 + 3.29484021469950e-02 8.61824529289475e-02 + 3.72852782429899e-02 9.12501336825606e-02 + 4.17870700061248e-02 9.63840447729288e-02 + 4.63496453037568e-02 1.01661284055219e-01 + 5.10435239639925e-02 1.07009882208275e-01 + 5.59875070986280e-02 1.12277397844824e-01 + 6.13148588789216e-02 1.17455631946297e-01 + 6.70010356595760e-02 1.22519800002061e-01 + 7.29051769183183e-02 1.27568059236526e-01 + 7.89112995425554e-02 1.32686684152645e-01 + 8.50741136975359e-02 1.37843119031058e-01 + 9.14578688138890e-02 1.42951013415473e-01 + 9.81151304128743e-02 1.47950651124437e-01 + 1.05022936124011e-01 1.52865251715801e-01 + 1.12182877397443e-01 1.57757291795771e-01 + 1.19585877721620e-01 1.62614046073641e-01 + 1.27214720177563e-01 1.67446356419965e-01 + 1.35051758382265e-01 1.72165225608851e-01 + 1.43176044526092e-01 1.76678814786360e-01 + 1.51634312233503e-01 1.80984672889066e-01 + 1.60356678124586e-01 1.85147263518180e-01 + 1.69269127559869e-01 1.89234816532284e-01 + 1.78381320346887e-01 1.93269420198442e-01 + 1.87736592934877e-01 1.97097647600736e-01 + 1.97403400646351e-01 2.00521431354757e-01 + 2.07414560220724e-01 2.03579949812533e-01 + 2.17637947930063e-01 2.06524316560926e-01 + 2.27957250958957e-01 2.09606621172829e-01 + 2.38424311306026e-01 2.12738917135585e-01 + 2.49140241428875e-01 2.15458447992728e-01 + 2.60193207505178e-01 2.17511148705191e-01 + 2.71533533873424e-01 2.19224005878087e-01 + 2.83047744346193e-01 2.20787015818953e-01 + 2.94701890510800e-01 2.22583472274857e-01 + 3.06540852849821e-01 2.24096763539104e-01 + 3.18587112400968e-01 2.24415002618965e-01 + 3.30855654708830e-01 2.24301491408268e-01 + 3.43310579183658e-01 2.24139847149895e-01 + 3.55916656194316e-01 2.23898337931694e-01 + 3.68688998774519e-01 2.23408427293927e-01 + 3.81572695782548e-01 2.22730323737716e-01 + 3.94527023625166e-01 2.21420378888789e-01 + 4.07577420363382e-01 2.19229578580146e-01 + 4.20747484227582e-01 2.16905927479625e-01 + 4.34048855640024e-01 2.14517519518509e-01 + 4.47450165980170e-01 2.11864556981160e-01 + 4.60905424804169e-01 2.08876051783214e-01 + 4.74402418451617e-01 2.05501088301643e-01 + 4.88022240093813e-01 2.01966908762110e-01 + 5.01834194639075e-01 1.98470477662966e-01 + 5.15805558738129e-01 1.94947715634616e-01 + 5.29888183465374e-01 1.91277769157688e-01 + 5.44052932281682e-01 1.87389757043223e-01 + 5.58325058597065e-01 1.83339503703845e-01 + 5.72736421684721e-01 1.79233707897876e-01 + 5.87278008452787e-01 1.75063217405684e-01 + 6.01942226550589e-01 1.70800025984236e-01 + 6.16726346705862e-01 1.66455074142313e-01 + 6.31625058034417e-01 1.61970282233741e-01 + 6.46632291278635e-01 1.57504594571016e-01 + 6.61751041325077e-01 1.53059152834824e-01 + 6.76936236795835e-01 1.48499192638019e-01 + 6.92147476339639e-01 1.43724258513413e-01 + 7.07422281167433e-01 1.38823871106520e-01 + 7.22793007484622e-01 1.33869944353296e-01 + 7.38235455101973e-01 1.28814615957645e-01 + 7.53788409699974e-01 1.23522467900944e-01 + 7.69480657356214e-01 1.18283395144514e-01 + 7.85257633409310e-01 1.13044577909845e-01 + 8.01060519005720e-01 1.07644700685774e-01 + 8.16924009082326e-01 1.02213067786408e-01 + 8.32899942925333e-01 9.69408719881597e-02 + 8.48952317457811e-01 9.17358463767536e-02 + 8.65002071649512e-01 8.63711864178634e-02 + 8.80969831955332e-01 8.09281767032574e-02 + 8.97584200496906e-01 7.56224024173498e-02 + 9.14568727916341e-01 7.04186437860226e-02 + 9.31904847981603e-01 6.55248665698794e-02 + 9.49305251019172e-01 6.03216786607366e-02 + 9.66164153664091e-01 4.90247665870267e-02 + 9.80884725394935e-01 3.29696041722759e-02 + 9.88910360671404e-01 2.19933114134784e-02 + 9.94960172555627e-01 1.27529106155588e-02 + 1.00000000000000e+00 4.45165609285943e-03 diff --git a/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF08_Coords.txt b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF08_Coords.txt new file mode 100644 index 00000000..478fc66c --- /dev/null +++ b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF08_Coords.txt @@ -0,0 +1,208 @@ + 201 NumCoords ! The number of coordinates in the airfoil shape file (including an extra coordinate for airfoil reference). Set to zero if coordinates not included. +! ......... x-y coordinates are next if NumCoords > 0 ............. +! x-y coordinate of airfoil reference +! x/c y/c + 0.250000 0 +! coordinates of airfoil shape +! interpolation to 200 points +! x/c y/c + 1.00000000000000e+00 -5.11794789304784e-03 + 9.87005763971439e-01 -5.16840068225131e-03 + 9.73038425383534e-01 -5.32849535777342e-03 + 9.56081318146453e-01 -5.65516774424684e-03 + 9.38258725113225e-01 -6.13509187042994e-03 + 9.21098802615238e-01 -7.37719929228484e-03 + 9.04171761208617e-01 -9.67764145296581e-03 + 8.87610187611954e-01 -1.28830910336964e-02 + 8.71194318647985e-01 -1.68426370240972e-02 + 8.54930444958429e-01 -2.12840484397517e-02 + 8.38825194115695e-01 -2.61486444777100e-02 + 8.22890453894495e-01 -3.14203814417820e-02 + 8.07149028562320e-01 -3.70963167232995e-02 + 7.91559160728296e-01 -4.30129343317612e-02 + 7.76134809703913e-01 -4.91784530431020e-02 + 7.60882930217529e-01 -5.55441031998046e-02 + 7.45808391148759e-01 -6.21129397508765e-02 + 7.30872703797860e-01 -6.87753213244312e-02 + 7.16019391262118e-01 -7.53975930760553e-02 + 7.01249601839577e-01 -8.19653842497797e-02 + 6.86602027371248e-01 -8.85381279067066e-02 + 6.72088450727254e-01 -9.51198902776138e-02 + 6.57658826413606e-01 -1.01580704997215e-01 + 6.43273510875851e-01 -1.07825082904111e-01 + 6.28922441703606e-01 -1.13838136909654e-01 + 6.14629543830024e-01 -1.19633865914327e-01 + 6.00402302207097e-01 -1.25204051915514e-01 + 5.86224990574980e-01 -1.30504150242841e-01 + 5.72102688198421e-01 -1.35489694904769e-01 + 5.58056462396552e-01 -1.40219795793820e-01 + 5.44068657963509e-01 -1.44621519921740e-01 + 5.30149292300862e-01 -1.48688195730507e-01 + 5.16309904342871e-01 -1.52448246865224e-01 + 5.02564054060932e-01 -1.55921626814940e-01 + 4.88906214250242e-01 -1.59037421835638e-01 + 4.75341042823127e-01 -1.62423955617231e-01 + 4.61888620093194e-01 -1.65573917902269e-01 + 4.48549276031540e-01 -1.68227765214179e-01 + 4.35323450667154e-01 -1.70397650719714e-01 + 4.22231621477117e-01 -1.72138327387660e-01 + 4.09276701428819e-01 -1.73387571753102e-01 + 3.96470584896236e-01 -1.74281084442316e-01 + 3.83820866691607e-01 -1.74849339228191e-01 + 3.71337084681443e-01 -1.75019751577656e-01 + 3.59023523674681e-01 -1.74968047652900e-01 + 3.46890000105156e-01 -1.74665880146742e-01 + 3.34945069696063e-01 -1.74085229376070e-01 + 3.23189763794252e-01 -1.73173272026349e-01 + 3.11618801432831e-01 -1.72128336356160e-01 + 3.00245771337945e-01 -1.70930259894987e-01 + 2.89061607633421e-01 -1.69632705367369e-01 + 2.78070348777523e-01 -1.68223429598176e-01 + 2.67282084006707e-01 -1.66631651581257e-01 + 2.56695506216341e-01 -1.64880753133419e-01 + 2.46309210866574e-01 -1.63007736992023e-01 + 2.36121268527904e-01 -1.61049692711949e-01 + 2.26122324781829e-01 -1.59049566833247e-01 + 2.16324437766268e-01 -1.56951849123834e-01 + 2.06745907176088e-01 -1.54690861611926e-01 + 1.97389066205685e-01 -1.52226909705892e-01 + 1.88247721921604e-01 -1.49614702715995e-01 + 1.79314005605731e-01 -1.46926220464477e-01 + 1.70566694081349e-01 -1.44223107768427e-01 + 1.61987928073239e-01 -1.41464913845606e-01 + 1.53613637192824e-01 -1.38621916691031e-01 + 1.45465791115612e-01 -1.35641236981406e-01 + 1.37531633873771e-01 -1.32555619747964e-01 + 1.29789500501668e-01 -1.29438714378930e-01 + 1.22244457727610e-01 -1.26295657217261e-01 + 1.14904434138070e-01 -1.23092443693640e-01 + 1.07815146473205e-01 -1.19743795226088e-01 + 1.00932689591638e-01 -1.16291158229989e-01 + 9.42157410411242e-02 -1.12813381113546e-01 + 8.77349155613034e-02 -1.09269854169755e-01 + 8.14482559337302e-02 -1.05747275959770e-01 + 7.53019277572595e-02 -1.02291481938668e-01 + 6.93966080685775e-02 -9.87222833516028e-02 + 6.37676017649456e-02 -9.49332169892506e-02 + 5.83449527155066e-02 -9.10314379469155e-02 + 5.31177088421891e-02 -8.71178387550273e-02 + 4.80761779909361e-02 -8.32564851010753e-02 + 4.32072188935750e-02 -7.94169605594471e-02 + 3.85782245145711e-02 -7.54792072837812e-02 + 3.42154217216861e-02 -7.13768818016279e-02 + 3.00688981057734e-02 -6.72145109220034e-02 + 2.61374641397527e-02 -6.30734442017404e-02 + 2.23928752768931e-02 -5.89691912908124e-02 + 1.89178199388277e-02 -5.47792526393842e-02 + 1.57782895775260e-02 -5.03896663818205e-02 + 1.29264432287037e-02 -4.59030547514804e-02 + 1.03316751650313e-02 -4.14081472593511e-02 + 8.01095482796203e-03 -3.68823744341440e-02 + 6.08150946456878e-03 -3.22776443558319e-02 + 4.52036674400099e-03 -2.75690188527804e-02 + 3.11828349938427e-03 -2.29033385892524e-02 + 1.72653564695298e-03 -1.83027858589327e-02 + 9.36354454312048e-04 -1.37093359958523e-02 + 4.16310542075031e-04 -9.11214382596928e-03 + 9.05200308349797e-05 -4.53311172713394e-03 + 0.00000000000000e+00 0.00000000000000e+00 + 8.23110428241997e-05 3.97993478406906e-03 + 2.98468273940176e-04 7.93603235163689e-03 + 6.81113520909810e-04 1.19732402957132e-02 + 1.19041733235376e-03 1.60895922280325e-02 + 1.80832364157979e-03 2.02825181518579e-02 + 2.76834570722558e-03 2.45519466760042e-02 + 3.99985774071954e-03 2.88929320741292e-02 + 5.33098003226254e-03 3.32996052893721e-02 + 6.90917800997795e-03 3.77505431103084e-02 + 8.77992723995089e-03 4.22046062180702e-02 + 1.09457919494102e-02 4.66556914052094e-02 + 1.35126204924888e-02 5.10795304396620e-02 + 1.62412425116766e-02 5.55670056227592e-02 + 1.90868246244520e-02 6.01139718284135e-02 + 2.21802651667868e-02 6.46464708799812e-02 + 2.55327767469641e-02 6.91387827146383e-02 + 2.91390326059276e-02 7.36166345104199e-02 + 3.30039777104017e-02 7.80809269502797e-02 + 3.70896196513728e-02 8.25444208474574e-02 + 4.13563599588328e-02 8.70143468541920e-02 + 4.57942488220187e-02 9.15057079185578e-02 + 5.04601677621719e-02 9.59562675686702e-02 + 5.54400970779884e-02 1.00346688860753e-01 + 6.07171145906721e-02 1.04660979867235e-01 + 6.62216553378991e-02 1.08935080787161e-01 + 7.18940181674464e-02 1.13200789970514e-01 + 7.77574457722054e-02 1.17447559516479e-01 + 8.38582528706480e-02 1.21612209930337e-01 + 9.02250315657730e-02 1.25670302033989e-01 + 9.68042562433391e-02 1.29880982393018e-01 + 1.03635628099521e-01 1.34244912721725e-01 + 1.10722912321640e-01 1.38498319800975e-01 + 1.18029172437582e-01 1.42690766816319e-01 + 1.25557277062529e-01 1.46757468146931e-01 + 1.33346382566007e-01 1.50646937087769e-01 + 1.41422111706339e-01 1.54348524617411e-01 + 1.49738752822182e-01 1.57926503716025e-01 + 1.58261307252747e-01 1.61412895932014e-01 + 1.67014562834699e-01 1.64759052986503e-01 + 1.75997148265051e-01 1.67949166953076e-01 + 1.85241674734378e-01 1.70882184716457e-01 + 1.94781635865444e-01 1.73518364853247e-01 + 2.04539228304846e-01 1.76027713882885e-01 + 2.14458567307343e-01 1.78522958537949e-01 + 2.24570098428163e-01 1.80925955576210e-01 + 2.34913847146583e-01 1.83050172483361e-01 + 2.45534451193117e-01 1.84760209750302e-01 + 2.56409639618004e-01 1.86197622355102e-01 + 2.67481214281869e-01 1.87445374261523e-01 + 2.78729550445907e-01 1.88701260713293e-01 + 2.90174585689315e-01 1.89727304194648e-01 + 3.01827744802688e-01 1.90098148646786e-01 + 3.13693266853199e-01 1.90148247690122e-01 + 3.25752387770815e-01 1.90049748389473e-01 + 3.37985999295062e-01 1.89850482601187e-01 + 3.50399511022203e-01 1.89420380078704e-01 + 3.62964646417233e-01 1.88761112183883e-01 + 3.75659599317119e-01 1.87699877039682e-01 + 3.88493946311551e-01 1.86138748269845e-01 + 4.01479623369996e-01 1.84435211491590e-01 + 4.14618975626936e-01 1.82594846533824e-01 + 4.27893504473755e-01 1.80517499301112e-01 + 4.41277817165844e-01 1.78160355503343e-01 + 4.54769684184117e-01 1.75569963848603e-01 + 4.68402276532037e-01 1.72797452588699e-01 + 4.82204018250152e-01 1.69896570381480e-01 + 4.96163589481294e-01 1.66904476133250e-01 + 5.10254815759577e-01 1.63749683743645e-01 + 5.24457636672397e-01 1.60385631582868e-01 + 5.38778999812109e-01 1.56819010856189e-01 + 5.53239404956048e-01 1.53135112253065e-01 + 5.67833029385625e-01 1.49336436080728e-01 + 5.82554003323792e-01 1.45391901778675e-01 + 5.97398824215910e-01 1.41321960812472e-01 + 6.12357976569945e-01 1.37030889241381e-01 + 6.27427066223596e-01 1.32799780757966e-01 + 6.42609031829815e-01 1.28608187585689e-01 + 6.57884967455200e-01 1.24319134244053e-01 + 6.73222159445380e-01 1.19854473146893e-01 + 6.88646887911997e-01 1.15297096039949e-01 + 7.04172277874646e-01 1.10673352001207e-01 + 7.19774747820223e-01 1.05929035833374e-01 + 7.35472858003156e-01 1.00901982607120e-01 + 7.51283076871008e-01 9.58585566601091e-02 + 7.67180686513965e-01 9.08137757626553e-02 + 7.83126081044713e-01 8.56561702301634e-02 + 7.99132991302778e-01 8.04660870681737e-02 + 8.15219075008360e-01 7.53413348195255e-02 + 8.31361072829366e-01 7.02307546393778e-02 + 8.47517852331182e-01 6.50201985415269e-02 + 8.63656467507866e-01 5.97821549429307e-02 + 8.80097857298869e-01 5.46370739285706e-02 + 8.96698968133781e-01 4.95450131245877e-02 + 9.13428903265378e-01 4.45899999689061e-02 + 9.30165973653682e-01 3.95022753998810e-02 + 9.46677106385649e-01 3.35856041834030e-02 + 9.62366570300102e-01 2.64891184968628e-02 + 9.75524413777782e-01 1.96392571440591e-02 + 9.87942439431026e-01 1.23546891949117e-02 + 1.00000000000000e+00 4.46208092342662e-03 diff --git a/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF09_Coords.txt b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF09_Coords.txt new file mode 100644 index 00000000..ad8befd3 --- /dev/null +++ b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF09_Coords.txt @@ -0,0 +1,208 @@ + 201 NumCoords ! The number of coordinates in the airfoil shape file (including an extra coordinate for airfoil reference). Set to zero if coordinates not included. +! ......... x-y coordinates are next if NumCoords > 0 ............. +! x-y coordinate of airfoil reference +! x/c y/c + 0.250000 0 +! coordinates of airfoil shape +! interpolation to 200 points +! x/c y/c + 1.00000000000000e+00 -4.48290689425684e-03 + 9.82685147820042e-01 -8.53514315789639e-04 + 9.65074173125769e-01 1.52396515243919e-03 + 9.47131369847641e-01 2.38186310542476e-03 + 9.29079738392991e-01 1.98605407767317e-03 + 9.11136932686656e-01 5.84573053769325e-04 + 8.93331110552002e-01 -1.81559310542060e-03 + 8.75696926836349e-01 -5.03012545181162e-03 + 8.58278441614373e-01 -9.07756072898963e-03 + 8.41065780811555e-01 -1.37558503877734e-02 + 8.24066502389336e-01 -1.89558446797954e-02 + 8.07294332368906e-01 -2.46418157238813e-02 + 7.90771378093859e-01 -3.08020117323259e-02 + 7.74436098064809e-01 -3.72183726376832e-02 + 7.58302300968262e-01 -4.38908526083423e-02 + 7.42347203951615e-01 -5.07231917195430e-02 + 7.26567046543587e-01 -5.76828350641104e-02 + 7.10965565373373e-01 -6.47638335469136e-02 + 6.95519902088750e-01 -7.19078088118299e-02 + 6.80200852515995e-01 -7.90264679400814e-02 + 6.65009538158461e-01 -8.60993846853897e-02 + 6.49932728810378e-01 -9.30770840488921e-02 + 6.34965245124027e-01 -9.99452370375686e-02 + 6.20121473822035e-01 -1.06734816345267e-01 + 6.05369724148523e-01 -1.13358005108072e-01 + 5.90709203181047e-01 -1.19793368271858e-01 + 5.76132232588897e-01 -1.26003318443933e-01 + 5.61623485073142e-01 -1.31936337860336e-01 + 5.47180334826478e-01 -1.37560084850570e-01 + 5.32836011294100e-01 -1.42944693135479e-01 + 5.18557682393933e-01 -1.47974227654401e-01 + 5.04345019178191e-01 -1.52613115006628e-01 + 4.90215407430556e-01 -1.56884809310840e-01 + 4.76188015830545e-01 -1.60825115471635e-01 + 4.62253033665051e-01 -1.64349593909143e-01 + 4.48417515713528e-01 -1.67663331883973e-01 + 4.34710843069829e-01 -1.70667352837079e-01 + 4.21135345763282e-01 -1.73250013095204e-01 + 4.07692539196562e-01 -1.75369441774164e-01 + 3.94406397743186e-01 -1.77099957202116e-01 + 3.81276986557577e-01 -1.78362483813652e-01 + 3.68322783092766e-01 -1.79242115776658e-01 + 3.55553206107463e-01 -1.79749612515479e-01 + 3.42979242027837e-01 -1.79808674233742e-01 + 3.30609148150643e-01 -1.79674534400684e-01 + 3.18449580230503e-01 -1.79275909211052e-01 + 3.06509322655533e-01 -1.78584001099644e-01 + 2.94791175146716e-01 -1.77599602041753e-01 + 2.83289821555050e-01 -1.76476773548797e-01 + 2.72024535692418e-01 -1.75094998486103e-01 + 2.60982410030143e-01 -1.73562091072792e-01 + 2.50165091041909e-01 -1.71897518205597e-01 + 2.39583243413264e-01 -1.70036954342752e-01 + 2.29235853918176e-01 -1.68016721779713e-01 + 2.19124464871966e-01 -1.65842406240233e-01 + 2.09249588884711e-01 -1.63520913043737e-01 + 1.99602392919692e-01 -1.61103792507202e-01 + 1.90186989829693e-01 -1.58574244986568e-01 + 1.81007010664238e-01 -1.55917942725202e-01 + 1.72062553557725e-01 -1.53140009241234e-01 + 1.63359202368110e-01 -1.50235559165085e-01 + 1.54898392347029e-01 -1.47206088517032e-01 + 1.46661235477579e-01 -1.44116632162527e-01 + 1.38647675436818e-01 -1.40957746936569e-01 + 1.30857477642150e-01 -1.37727894684008e-01 + 1.23314150088703e-01 -1.34386012966235e-01 + 1.16005990278055e-01 -1.30951821112718e-01 + 1.08910846474458e-01 -1.27479847786535e-01 + 1.02040340343061e-01 -1.23952846372826e-01 + 9.53986311193279e-02 -1.20357474728516e-01 + 8.90323993394245e-02 -1.16626303852397e-01 + 8.28767305111376e-02 -1.12854160647330e-01 + 7.68844182301344e-02 -1.09120085561990e-01 + 7.11597965516513e-02 -1.05283382260545e-01 + 6.56696750940585e-02 -1.01384532327587e-01 + 6.03433734169027e-02 -9.75228716647275e-02 + 5.52631810751249e-02 -9.35945518645845e-02 + 5.04374628719753e-02 -8.95752445382964e-02 + 4.58017138657216e-02 -8.55532445604049e-02 + 4.13825063739979e-02 -8.15090777857146e-02 + 3.71903771573731e-02 -7.74330944997390e-02 + 3.31831498539127e-02 -7.33695626942466e-02 + 2.94044512619656e-02 -6.92770916723935e-02 + 2.58722600796746e-02 -6.51347604857932e-02 + 2.25572604740764e-02 -6.09795630283635e-02 + 1.94959660050299e-02 -5.67979807916763e-02 + 1.66549185470222e-02 -5.26131319251651e-02 + 1.40190892255552e-02 -4.84378076871468e-02 + 1.16391072588897e-02 -4.42393355742390e-02 + 9.50228788811488e-03 -4.00394598279192e-02 + 7.61750558427819e-03 -3.58461293746517e-02 + 5.96961734277674e-03 -3.16700112648946e-02 + 4.57051426408954e-03 -2.75182493553630e-02 + 3.46220550430262e-03 -2.33803588641517e-02 + 2.49916702260785e-03 -1.93106678103887e-02 + 1.63033961162431e-03 -1.53141667384712e-02 + 9.45407884520976e-04 -1.13883102313619e-02 + 4.21430261701436e-04 -7.52929844595465e-03 + 9.13381590902419e-05 -3.73175381667205e-03 + 0.00000000000000e+00 0.00000000000000e+00 + 8.39329452090013e-05 3.54374461053228e-03 + 3.06764956816802e-04 7.13454764013681e-03 + 7.13012164714768e-04 1.08029006119544e-02 + 1.25477699565490e-03 1.45538137640591e-02 + 1.87824996211846e-03 1.83913428617193e-02 + 2.64208856620242e-03 2.23137326727634e-02 + 3.57895258939452e-03 2.63122664551712e-02 + 4.70335330309463e-03 3.03676984106315e-02 + 6.09496820298392e-03 3.44560592490469e-02 + 7.77012954132717e-03 3.85621978759486e-02 + 9.64425945479125e-03 4.27121086824562e-02 + 1.18165673299811e-02 4.68542778685051e-02 + 1.41500458554206e-02 5.10499179457540e-02 + 1.66757939188311e-02 5.52650509642601e-02 + 1.94944358078314e-02 5.94454470327604e-02 + 2.25601750791306e-02 6.36068555875123e-02 + 2.57991449009508e-02 6.78079383217997e-02 + 2.92507958725958e-02 7.20111307917660e-02 + 3.29560547332662e-02 7.61771155635355e-02 + 3.69223016317185e-02 8.02789497263063e-02 + 4.10868701381863e-02 8.43778345265497e-02 + 4.54636094053712e-02 8.84590735779314e-02 + 5.01015073543740e-02 9.24805126256261e-02 + 5.49864471213822e-02 9.64435890880417e-02 + 6.01030437388835e-02 1.00355103021560e-01 + 6.54365794824045e-02 1.04221338170475e-01 + 7.09866408760679e-02 1.08042054278353e-01 + 7.67848489938729e-02 1.11764924267835e-01 + 8.28419567185367e-02 1.15382031398279e-01 + 8.90827233315631e-02 1.19090347853174e-01 + 9.55745973139600e-02 1.22782565847220e-01 + 1.02331435541202e-01 1.26329878276425e-01 + 1.09301721897512e-01 1.29816008658284e-01 + 1.16503807036038e-01 1.33194917983426e-01 + 1.23946109720764e-01 1.36448961986286e-01 + 1.31637302974835e-01 1.39553652375047e-01 + 1.39550632997968e-01 1.42570826391307e-01 + 1.47682542702398e-01 1.45498302111650e-01 + 1.56069518605229e-01 1.48227377016446e-01 + 1.64675258837698e-01 1.50862919805664e-01 + 1.73503763301154e-01 1.53381044924379e-01 + 1.82588549258338e-01 1.55672292390839e-01 + 1.91896032540898e-01 1.57837375775528e-01 + 2.01419018649528e-01 1.59879697369963e-01 + 2.11170879173786e-01 1.61737676480272e-01 + 2.21142920533604e-01 1.63440457557596e-01 + 2.31344785241530e-01 1.64936734040921e-01 + 2.41776812876277e-01 1.66222595255920e-01 + 2.52425332490408e-01 1.67302947561355e-01 + 2.63282507223669e-01 1.68244340945048e-01 + 2.74348610121382e-01 1.69012303782361e-01 + 2.85626365865730e-01 1.69515492111364e-01 + 2.97112155171042e-01 1.69781263535723e-01 + 3.08800622317762e-01 1.69842332018192e-01 + 3.20686150985499e-01 1.69794894735041e-01 + 3.32766911432096e-01 1.69536965688287e-01 + 3.45035577717233e-01 1.69036525986778e-01 + 3.57485836149525e-01 1.68290434604480e-01 + 3.70115165868763e-01 1.67285953978053e-01 + 3.82926121840238e-01 1.66129716711123e-01 + 3.95913836963527e-01 1.64788643586246e-01 + 4.09070495847257e-01 1.63222025400885e-01 + 4.22386727818900e-01 1.61413466981118e-01 + 4.35868199635534e-01 1.59446587441237e-01 + 4.49510425897221e-01 1.57282538740608e-01 + 4.63310011853810e-01 1.54890791219506e-01 + 4.77272395344154e-01 1.52355017486446e-01 + 4.91388930511577e-01 1.49650569804520e-01 + 5.05646917362174e-01 1.46740875171855e-01 + 5.20039269071302e-01 1.43601845074114e-01 + 5.34577578408399e-01 1.40310816694090e-01 + 5.49258664193118e-01 1.36874027194232e-01 + 5.64078723855862e-01 1.33285076105752e-01 + 5.79033365779676e-01 1.29550827646836e-01 + 5.94111062600388e-01 1.25620789009221e-01 + 6.09309105749297e-01 1.21600186027117e-01 + 6.24630556848364e-01 1.17501437763810e-01 + 6.40076803181406e-01 1.13310521064511e-01 + 6.55621511472488e-01 1.08956689246299e-01 + 6.71282434069662e-01 1.04519499702055e-01 + 6.87058502926135e-01 1.00008908785847e-01 + 7.02927846961763e-01 9.53686490689770e-02 + 7.18895804076489e-01 9.05798419248120e-02 + 7.34971135576913e-01 8.57455415670096e-02 + 7.51152054267092e-01 8.08966931334801e-02 + 7.67413928372726e-01 7.59701046314968e-02 + 7.83757964100345e-01 7.09983525490587e-02 + 8.00181412903085e-01 6.60019195388936e-02 + 8.16674324716874e-01 6.09715410793434e-02 + 8.33223797983461e-01 5.58863227273931e-02 + 8.49836681673719e-01 5.08054192889429e-02 + 8.66528789392319e-01 4.57720870242744e-02 + 8.83272682730090e-01 4.07491338740728e-02 + 9.00052750797641e-01 3.57316517957309e-02 + 9.16852440088815e-01 3.07020031399376e-02 + 9.33648056912371e-01 2.56007231641426e-02 + 9.50397160534152e-01 2.04803293247181e-02 + 9.66974356849030e-01 1.53946239244196e-02 + 9.83503121344171e-01 1.03013893225374e-02 + 1.00000000000000e+00 5.19104209295961e-03 diff --git a/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF10_Coords.txt b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF10_Coords.txt new file mode 100644 index 00000000..2306aabb --- /dev/null +++ b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF10_Coords.txt @@ -0,0 +1,208 @@ + 201 NumCoords ! The number of coordinates in the airfoil shape file (including an extra coordinate for airfoil reference). Set to zero if coordinates not included. +! ......... x-y coordinates are next if NumCoords > 0 ............. +! x-y coordinate of airfoil reference +! x/c y/c + 0.250000 0 +! coordinates of airfoil shape +! interpolation to 200 points +! x/c y/c + 1.00000000000000e+00 -4.86297327722780e-03 + 9.80511984509124e-01 -9.31133134220648e-04 + 9.60815932067473e-01 1.58783899675626e-03 + 9.41263727013327e-01 2.45977643583330e-03 + 9.21908373952958e-01 2.02318714366812e-03 + 9.02633195879556e-01 5.53907693277352e-04 + 8.83548952910911e-01 -1.92622687280061e-03 + 8.64676068654257e-01 -5.23592974327322e-03 + 8.46074367845829e-01 -9.38251493217475e-03 + 8.27741297597062e-01 -1.41772631793085e-02 + 8.09672007216587e-01 -1.94973257087956e-02 + 7.91873336657596e-01 -2.52977908683563e-02 + 7.74367735549103e-01 -3.15620058422089e-02 + 7.57090038050940e-01 -3.80736794610610e-02 + 7.40059721602248e-01 -4.48406933947372e-02 + 7.23230579889469e-01 -5.17449963666943e-02 + 7.06605015919964e-01 -5.87716939723825e-02 + 6.90194826941935e-01 -6.59021942385170e-02 + 6.73996889494706e-01 -7.30893135249750e-02 + 6.57970960213318e-01 -8.02435270068158e-02 + 6.42102769339429e-01 -8.73411845286708e-02 + 6.26367045194948e-01 -9.43282695074803e-02 + 6.10778899846100e-01 -1.01198731702759e-01 + 5.95374122609830e-01 -1.07986550525514e-01 + 5.80108917172105e-01 -1.14593528787722e-01 + 5.64977322759140e-01 -1.21007184170168e-01 + 5.49963599827458e-01 -1.27184493648524e-01 + 5.35054509500322e-01 -1.33078736790999e-01 + 5.20240239002187e-01 -1.38649489081145e-01 + 5.05557788087488e-01 -1.43964284458764e-01 + 4.90970256041941e-01 -1.48911007050803e-01 + 4.76472728677462e-01 -1.53449856278318e-01 + 4.62084942212174e-01 -1.57602665694934e-01 + 4.47828765294808e-01 -1.61403714230558e-01 + 4.33694515609551e-01 -1.64768180098576e-01 + 4.19692014900672e-01 -1.67312421586961e-01 + 4.05855041232298e-01 -1.69438167354179e-01 + 3.92188826102844e-01 -1.71236764964869e-01 + 3.78696783687713e-01 -1.72680366966462e-01 + 3.65404165992181e-01 -1.73828350111621e-01 + 3.52309960259442e-01 -1.74603832845386e-01 + 3.39434352269169e-01 -1.75046402850823e-01 + 3.26788044378576e-01 -1.75133825786606e-01 + 3.14377288520538e-01 -1.74796806544884e-01 + 3.02214001378326e-01 -1.74281937784550e-01 + 2.90296958909308e-01 -1.73520780939566e-01 + 2.78635485836657e-01 -1.72477429763394e-01 + 2.67233529810193e-01 -1.71175577799686e-01 + 2.56083711507059e-01 -1.69740287783202e-01 + 2.45202102031515e-01 -1.68009517278914e-01 + 2.34579105150908e-01 -1.66103858628628e-01 + 2.24212170859206e-01 -1.64059794305773e-01 + 2.14107895836219e-01 -1.61831060401740e-01 + 2.04263429104938e-01 -1.59459845656682e-01 + 1.94681903392709e-01 -1.56932790054656e-01 + 1.85360827376149e-01 -1.54246702766653e-01 + 1.76292980865286e-01 -1.51449979369351e-01 + 1.67482564557179e-01 -1.48544746675442e-01 + 1.58917391100164e-01 -1.45558949901677e-01 + 1.50597215806486e-01 -1.42512007742927e-01 + 1.42535487762553e-01 -1.39364415484843e-01 + 1.34732399664726e-01 -1.36087431797309e-01 + 1.27168245136680e-01 -1.32747266345250e-01 + 1.19842841419690e-01 -1.29351677052803e-01 + 1.12750494865106e-01 -1.25924352574772e-01 + 1.05909796567034e-01 -1.22436413682471e-01 + 9.93094805058807e-02 -1.18882766273095e-01 + 9.29294502220848e-02 -1.15306400616325e-01 + 8.67798712020860e-02 -1.11683261666515e-01 + 8.08601043456327e-02 -1.08010634641524e-01 + 7.52105971387069e-02 -1.04233041725997e-01 + 6.97707736814900e-02 -1.00453870449379e-01 + 6.44954666632857e-02 -9.67461879884846e-02 + 5.94792621751988e-02 -9.29557913115884e-02 + 5.46968806556035e-02 -8.91053349016699e-02 + 5.00889983595891e-02 -8.52955052036599e-02 + 4.57150288715163e-02 -8.14584893545538e-02 + 4.15643801762247e-02 -7.76015601232226e-02 + 3.75882055097653e-02 -7.37928505464360e-02 + 3.38275455149990e-02 -6.99786331700560e-02 + 3.02887595308436e-02 -6.61394551074094e-02 + 2.69209980985916e-02 -6.23365636550792e-02 + 2.37600762514079e-02 -5.85464923862813e-02 + 2.08209273086278e-02 -5.47566143699477e-02 + 1.80843181668748e-02 -5.09866904767273e-02 + 1.55871667540216e-02 -4.72112704231235e-02 + 1.32930091997276e-02 -4.34579786243884e-02 + 1.11671609158122e-02 -3.97587139427468e-02 + 9.24302286361386e-03 -3.60973970879580e-02 + 7.52099695998262e-03 -3.24775010120743e-02 + 6.02824547033773e-03 -2.88913977885378e-02 + 4.73760869802884e-03 -2.53555749353871e-02 + 3.63179948486746e-03 -2.18830234339889e-02 + 2.76343151147194e-03 -1.84654987945057e-02 + 2.02988502957333e-03 -1.51380631574757e-02 + 1.46813569910251e-03 -1.19064518890580e-02 + 8.92625474122533e-04 -8.77454309044243e-03 + 3.99065689084287e-04 -5.74363785175138e-03 + 8.70943828190601e-05 -2.81422588679827e-03 + 0.00000000000000e+00 0.00000000000000e+00 + 8.02187075687612e-05 3.23896444371914e-03 + 2.92360984112174e-04 6.64836967518462e-03 + 6.77158021962086e-04 1.01332887079749e-02 + 1.19066014968889e-03 1.36987991407504e-02 + 1.78076395507241e-03 1.73491673472808e-02 + 2.40903747756074e-03 2.10824160991588e-02 + 3.12276106703853e-03 2.48895553910672e-02 + 4.07783832276212e-03 2.87525459149076e-02 + 5.29086782469029e-03 3.26492458807703e-02 + 6.76340526224963e-03 3.65661596791223e-02 + 8.38018584402884e-03 4.05288053998209e-02 + 1.02253241413783e-02 4.44891365322827e-02 + 1.22248587000671e-02 4.85018949098202e-02 + 1.44438730234543e-02 5.25327300962284e-02 + 1.69548467514969e-02 5.65334970723320e-02 + 1.96931133190989e-02 6.05207316239289e-02 + 2.25638609500651e-02 6.45491498636593e-02 + 2.56161511220727e-02 6.85831866314810e-02 + 2.89202819428702e-02 7.25851847243638e-02 + 3.25062523751746e-02 7.65285938527960e-02 + 3.62951761898641e-02 8.04726459274233e-02 + 4.02846009364239e-02 8.44024704703390e-02 + 4.45007879918332e-02 8.82780700165274e-02 + 4.89247556185767e-02 9.21060334637697e-02 + 5.35723096647886e-02 9.58897521485476e-02 + 5.84592407255586e-02 9.96298721593641e-02 + 6.35713075613679e-02 1.03329002883886e-01 + 6.89278104673831e-02 1.06940810225108e-01 + 7.45312963741614e-02 1.10457519647787e-01 + 8.03023396546418e-02 1.13808960354886e-01 + 8.63179073064753e-02 1.16806322489047e-01 + 9.25972420849028e-02 1.19687016346367e-01 + 9.90811043339423e-02 1.22544358196588e-01 + 1.05787895955984e-01 1.25340806259942e-01 + 1.12724232239356e-01 1.28073095299648e-01 + 1.19892971306548e-01 1.30703114138229e-01 + 1.27273440293726e-01 1.33288917717216e-01 + 1.34877152315313e-01 1.35805891937509e-01 + 1.42744011141429e-01 1.38116832152479e-01 + 1.50823603558752e-01 1.40392690357772e-01 + 1.59107761029883e-01 1.42661149234078e-01 + 1.67629352696633e-01 1.44772172686264e-01 + 1.76377704606620e-01 1.46774529039623e-01 + 1.85370180781539e-01 1.48614215130669e-01 + 1.94612923349638e-01 1.50247989477911e-01 + 2.04074586490007e-01 1.51818931098813e-01 + 2.13747530977158e-01 1.53313183639193e-01 + 2.23645236800479e-01 1.54647357802947e-01 + 2.33775728681758e-01 1.55792644992903e-01 + 2.44138440260482e-01 1.56752241560042e-01 + 2.54726045330669e-01 1.57590263699543e-01 + 2.65537343044850e-01 1.58361624334313e-01 + 2.76567564773377e-01 1.58942652997736e-01 + 2.87817345414617e-01 1.59319971716534e-01 + 2.99290232425583e-01 1.59589784224439e-01 + 3.10982335287392e-01 1.59671340810000e-01 + 3.22895608718648e-01 1.59537343958620e-01 + 3.35033089062765e-01 1.59236217541811e-01 + 3.47389002674619e-01 1.58767154984173e-01 + 3.59961889407242e-01 1.58139657212231e-01 + 3.72743440456310e-01 1.57309327495217e-01 + 3.85733458057802e-01 1.56248726075227e-01 + 3.98930703138098e-01 1.54975303437308e-01 + 4.12345184105345e-01 1.53551512089131e-01 + 4.25954142961272e-01 1.51935725721345e-01 + 4.39739441903326e-01 1.50056917065730e-01 + 4.53714268006763e-01 1.47990332900825e-01 + 4.67878910856137e-01 1.45763613299970e-01 + 4.82224623597588e-01 1.43333415389031e-01 + 4.96738039338005e-01 1.40653686928458e-01 + 5.11425301120766e-01 1.37802798976480e-01 + 5.26284017534203e-01 1.34778098917954e-01 + 5.41313223595069e-01 1.31616771414899e-01 + 5.56506191866471e-01 1.28282935128933e-01 + 5.71853456832878e-01 1.24814251336103e-01 + 5.87352855179168e-01 1.21054902047869e-01 + 6.03005431727672e-01 1.17060565551195e-01 + 6.18822144334829e-01 1.12966378040271e-01 + 6.34781882100071e-01 1.08702844246632e-01 + 6.50899402129147e-01 1.04349818477932e-01 + 6.67165890781568e-01 9.99118836260051e-02 + 6.83560340804585e-01 9.53341953789793e-02 + 7.00082231463252e-01 9.07664656077491e-02 + 7.16736439213004e-01 8.61324826330526e-02 + 7.33532609513889e-01 8.14583044049984e-02 + 7.50453705328182e-01 7.67128793620926e-02 + 7.67496896127474e-01 7.18988453285231e-02 + 7.84651539969057e-01 6.69901347588158e-02 + 8.01917466461742e-01 6.20117979514114e-02 + 8.19294924371077e-01 5.69943186539853e-02 + 8.36792306469474e-01 5.19801638256853e-02 + 8.54409507470158e-01 4.69691610485990e-02 + 8.72138737961771e-01 4.19401147746978e-02 + 8.89967727577875e-01 3.68416407164412e-02 + 9.07923286973654e-01 3.17741055104095e-02 + 9.26040022335196e-01 2.69066169756247e-02 + 9.44348788456134e-01 2.21078957421789e-02 + 9.62867272385349e-01 1.70474154188180e-02 + 9.81428540150012e-01 1.18282222218164e-02 + 1.00000000000000e+00 6.42193222596370e-03 diff --git a/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF11_Coords.txt b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF11_Coords.txt new file mode 100644 index 00000000..cea9e099 --- /dev/null +++ b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF11_Coords.txt @@ -0,0 +1,208 @@ + 201 NumCoords ! The number of coordinates in the airfoil shape file (including an extra coordinate for airfoil reference). Set to zero if coordinates not included. +! ......... x-y coordinates are next if NumCoords > 0 ............. +! x-y coordinate of airfoil reference +! x/c y/c + 0.250000 0 +! coordinates of airfoil shape +! interpolation to 200 points +! x/c y/c + 1.00000000000000e+00 -5.69525046509396e-03 + 9.78806538918783e-01 -1.52333707624982e-03 + 9.57388982524555e-01 1.12180524962487e-03 + 9.36194732688498e-01 2.02641546982668e-03 + 9.15272729634671e-01 1.50711995585143e-03 + 8.94450817639587e-01 -1.31121257641393e-04 + 8.73855886372089e-01 -2.82614463352886e-03 + 8.53513143501759e-01 -6.40839878682634e-03 + 8.33476839211981e-01 -1.08310870429086e-02 + 8.13756218644144e-01 -1.59345264947230e-02 + 7.94338172931301e-01 -2.15617459883902e-02 + 7.75223162367073e-01 -2.76433664245668e-02 + 7.56430809853826e-01 -3.41498879519738e-02 + 7.37902039055167e-01 -4.08770619092354e-02 + 7.19666804126832e-01 -4.78568465131379e-02 + 7.01658130282083e-01 -5.49136484928595e-02 + 6.83899927259984e-01 -6.20881481267653e-02 + 6.66390228117896e-01 -6.93121843337415e-02 + 6.49139979076653e-01 -7.65617633025002e-02 + 6.32111246018286e-01 -8.37529658171195e-02 + 6.15288445442940e-01 -9.08626791271311e-02 + 5.98643467384132e-01 -9.78302135918077e-02 + 5.82199702299186e-01 -1.04659155113551e-01 + 5.65994720552908e-01 -1.11376506607751e-01 + 5.49978071618322e-01 -1.17862982731167e-01 + 5.34153023591067e-01 -1.24136613279468e-01 + 5.18499703066478e-01 -1.30142303625889e-01 + 5.03010433237196e-01 -1.35847983922864e-01 + 4.87668238679784e-01 -1.41188236613217e-01 + 4.72507803295827e-01 -1.46221700598355e-01 + 4.57497896342093e-01 -1.50852564976543e-01 + 4.42633017601021e-01 -1.55032379104410e-01 + 4.27932599332219e-01 -1.58778956843575e-01 + 4.13418848394650e-01 -1.62120173617977e-01 + 3.99086452753069e-01 -1.64971636857931e-01 + 3.84948831136274e-01 -1.67048827443987e-01 + 3.71039880058497e-01 -1.68671738056494e-01 + 3.57369018629051e-01 -1.69925952664825e-01 + 3.43942688850799e-01 -1.70795813632049e-01 + 3.30784793117660e-01 -1.71334788788157e-01 + 3.17893696334626e-01 -1.71490756553470e-01 + 3.05286580000178e-01 -1.71294197311131e-01 + 2.92974406928141e-01 -1.70717197421300e-01 + 2.80951411412875e-01 -1.69737797343376e-01 + 2.69233585663057e-01 -1.68548716430126e-01 + 2.57805947668032e-01 -1.67130702113460e-01 + 2.46678614080578e-01 -1.65444540916611e-01 + 2.35855708755702e-01 -1.63515711588020e-01 + 2.25324636807488e-01 -1.61458171344871e-01 + 2.15089578214410e-01 -1.59139131505499e-01 + 2.05150257762253e-01 -1.56651810005603e-01 + 1.95498465637821e-01 -1.54032321793723e-01 + 1.86133303884814e-01 -1.51267800061800e-01 + 1.77048514682184e-01 -1.48396307898530e-01 + 1.68247904545403e-01 -1.45397772039655e-01 + 1.59721997054468e-01 -1.42280347630919e-01 + 1.51466704551609e-01 -1.39072008137626e-01 + 1.43490819529254e-01 -1.35772826875173e-01 + 1.35761290420028e-01 -1.32454355349041e-01 + 1.28278100435328e-01 -1.29124976897121e-01 + 1.21061925252952e-01 -1.25731442239843e-01 + 1.14106782713019e-01 -1.22244231683582e-01 + 1.07392996712928e-01 -1.18723433818558e-01 + 1.00921587269965e-01 -1.15182636140660e-01 + 9.46841600395731e-02 -1.11678741751433e-01 + 8.86904020175527e-02 -1.08199712602269e-01 + 8.29295937403109e-02 -1.04690677290643e-01 + 7.73855253774526e-02 -1.01182355772936e-01 + 7.20632038828038e-02 -9.76537898724569e-02 + 6.69567872583836e-02 -9.41087513314784e-02 + 6.20974140669556e-02 -9.05039743293917e-02 + 5.74408846245436e-02 -8.69216814878245e-02 + 5.29472035657151e-02 -8.34211011266652e-02 + 4.86830821705248e-02 -7.98783109729412e-02 + 4.46330074510540e-02 -7.63028087621810e-02 + 4.07611793756051e-02 -7.27687863405534e-02 + 3.71009763948847e-02 -6.92364489374634e-02 + 3.36248359360092e-02 -6.57310546071755e-02 + 3.03041413909075e-02 -6.22959704284829e-02 + 2.71879524688719e-02 -5.88684263115360e-02 + 2.42717576545455e-02 -5.54343443189173e-02 + 2.15027525196933e-02 -5.20540051592585e-02 + 1.89137313912481e-02 -4.87090785971533e-02 + 1.65182266978350e-02 -4.53887621601851e-02 + 1.43049162404917e-02 -4.21042791351809e-02 + 1.23028427731255e-02 -3.88313724591694e-02 + 1.04741934250062e-02 -3.55976591947433e-02 + 8.78311115027676e-03 -3.24338519377945e-02 + 7.24533815833448e-03 -2.93330391673238e-02 + 5.86947854914707e-03 -2.62910386079313e-02 + 4.69611128198702e-03 -2.32928044536227e-02 + 3.68981688144507e-03 -2.03556383168934e-02 + 2.82187228866077e-03 -1.74932823095649e-02 + 2.14089095819824e-03 -1.46985911948591e-02 + 1.57630652997499e-03 -1.19942243149679e-02 + 1.18984777333983e-03 -9.38552769920999e-03 + 7.38439523884420e-04 -6.87678063790083e-03 + 3.33591616922490e-04 -4.47097508153630e-03 + 7.46901189097683e-05 -2.17087537934301e-03 + 0.00000000000000e+00 0.00000000000000e+00 + 6.92412634353660e-05 2.74621576665460e-03 + 2.49543457687775e-04 5.67381024680127e-03 + 5.69195748818264e-04 8.67143602234610e-03 + 9.96695834445714e-04 1.17435040095864e-02 + 1.48928310396865e-03 1.48940750374214e-02 + 1.98849119023728e-03 1.81207435789369e-02 + 2.54959257779418e-03 2.14141902325502e-02 + 3.34181357652084e-03 2.47615483193398e-02 + 4.35138049766192e-03 2.81462543893500e-02 + 5.57852652609682e-03 3.15563440839828e-02 + 6.92222649894473e-03 3.50119837686661e-02 + 8.43795113911303e-03 3.84786497098604e-02 + 1.00930905567546e-02 4.19960985164764e-02 + 1.19621589285143e-02 4.55325565150444e-02 + 1.40852578757622e-02 4.90549107074214e-02 + 1.64039291216290e-02 5.25767354668559e-02 + 1.88398593495795e-02 5.61372533386474e-02 + 2.14333380897448e-02 5.97116148591461e-02 + 2.42465708836148e-02 6.32736158904520e-02 + 2.73128417251185e-02 6.68021029337550e-02 + 3.05634247430033e-02 7.03446938508445e-02 + 3.40012367549624e-02 7.38799559097142e-02 + 3.76412740591324e-02 7.73776756177052e-02 + 4.14526743416006e-02 8.08567034039700e-02 + 4.54648935651470e-02 8.43141185886057e-02 + 4.97138325875744e-02 8.77373418115587e-02 + 5.41781481654145e-02 9.11359855290002e-02 + 5.88644478021621e-02 9.44797733214635e-02 + 6.37759842093246e-02 9.77593136724116e-02 + 6.88488483685858e-02 1.00823224034846e-01 + 7.41507917548021e-02 1.03488541051867e-01 + 7.97016770601785e-02 1.06075588555681e-01 + 8.54487989072580e-02 1.08666353687266e-01 + 9.14085009112059e-02 1.11233062570593e-01 + 9.75916624744935e-02 1.13770253357497e-01 + 1.03999187359272e-01 1.16244616416147e-01 + 1.10612131361174e-01 1.18708964579629e-01 + 1.17449024487558e-01 1.21131135964468e-01 + 1.24546888925588e-01 1.23387153002500e-01 + 1.31860808435011e-01 1.25637788779435e-01 + 1.39382107499695e-01 1.27944947022874e-01 + 1.47138451129947e-01 1.30161879268156e-01 + 1.55130130177100e-01 1.32297385813300e-01 + 1.63380895148427e-01 1.34288717996456e-01 + 1.71895347851209e-01 1.36104388754837e-01 + 1.80641095940374e-01 1.37908869745374e-01 + 1.89607443624250e-01 1.39694681869496e-01 + 1.98815192027444e-01 1.41352012545062e-01 + 2.08277829742442e-01 1.42856034753896e-01 + 2.17998788821085e-01 1.44187980224416e-01 + 2.27971555762112e-01 1.45430091516579e-01 + 2.38195302318094e-01 1.46673887296536e-01 + 2.48670661039287e-01 1.47744688351893e-01 + 2.59395614367826e-01 1.48645867466862e-01 + 2.70380513809449e-01 1.49438453642673e-01 + 2.81625107704732e-01 1.50057622177488e-01 + 2.93131175607184e-01 1.50496964150777e-01 + 3.04908162749787e-01 1.50795041350106e-01 + 3.16953693264067e-01 1.50926867573051e-01 + 3.29263945095546e-01 1.50884243661390e-01 + 3.41831054632093e-01 1.50627191696395e-01 + 3.54660098331472e-01 1.50114926580935e-01 + 3.67749572260908e-01 1.49411069482863e-01 + 3.81111124669245e-01 1.48516691724055e-01 + 3.94719101684341e-01 1.47440799158347e-01 + 4.08554267680281e-01 1.46095627806137e-01 + 4.22629583420339e-01 1.44515583307731e-01 + 4.36948565719152e-01 1.42787868414573e-01 + 4.51504717292113e-01 1.40851047954471e-01 + 4.66284547735849e-01 1.38636208645556e-01 + 4.81291098416158e-01 1.36225156460815e-01 + 4.96521243549536e-01 1.33595494775405e-01 + 5.11977506070676e-01 1.30819756217691e-01 + 5.27648084830866e-01 1.27801959456686e-01 + 5.43529232837187e-01 1.24624712255092e-01 + 5.59617766329048e-01 1.21167360031619e-01 + 5.75910930604750e-01 1.17465675967471e-01 + 5.92420943986219e-01 1.13641307775934e-01 + 6.09129433020705e-01 1.09627607546218e-01 + 6.26048292506993e-01 1.05505710212843e-01 + 6.43163878485665e-01 1.01266416248930e-01 + 6.60456216477355e-01 9.68592270720327e-02 + 6.77923642030845e-01 9.24805992427934e-02 + 6.95566193064319e-01 8.80054199530201e-02 + 7.13393826614235e-01 8.34592506694026e-02 + 7.31389719769680e-01 7.88141754388108e-02 + 7.49549904053857e-01 7.40757159847257e-02 + 7.67859592973647e-01 6.92056573065396e-02 + 7.86320983784494e-01 6.42470162878310e-02 + 8.04932658647533e-01 5.92311705291700e-02 + 8.23696980505892e-01 5.41849164919753e-02 + 8.42611206733270e-01 4.91017607941500e-02 + 8.61674584002276e-01 4.39898310628447e-02 + 8.80870637502453e-01 3.87781149653440e-02 + 9.00229080614011e-01 3.35800045674166e-02 + 9.19795776538293e-01 2.86236343997086e-02 + 9.39609936409794e-01 2.37339679553963e-02 + 9.59701477871013e-01 1.84898366266777e-02 + 9.79845921697258e-01 1.30253668628043e-02 + 1.00000000000000e+00 7.30191104279453e-03 diff --git a/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF12_Coords.txt b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF12_Coords.txt new file mode 100644 index 00000000..0559474f --- /dev/null +++ b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF12_Coords.txt @@ -0,0 +1,208 @@ + 201 NumCoords ! The number of coordinates in the airfoil shape file (including an extra coordinate for airfoil reference). Set to zero if coordinates not included. +! ......... x-y coordinates are next if NumCoords > 0 ............. +! x-y coordinate of airfoil reference +! x/c y/c + 0.250000 0 +! coordinates of airfoil shape +! interpolation to 200 points +! x/c y/c + 1.00000000000000e+00 -6.59289903496683e-03 + 9.77462574493223e-01 -2.16354893719578e-03 + 9.54655435704073e-01 6.29155968453326e-04 + 9.32021629665813e-01 1.58147595579106e-03 + 9.09641132745904e-01 9.68321497165801e-04 + 8.87387976484538e-01 -8.61665541778709e-04 + 8.65383162362486e-01 -3.80055493480974e-03 + 8.43662068878266e-01 -7.69211321552455e-03 + 8.22270394573964e-01 -1.24281363324318e-02 + 8.01229047333685e-01 -1.78818932097066e-02 + 7.80519648544988e-01 -2.38576889999194e-02 + 7.60137450727518e-01 -3.02583777838988e-02 + 7.40098281598073e-01 -3.70398802849335e-02 + 7.20352027908950e-01 -4.40116142510090e-02 + 7.00939656244907e-01 -5.12328611067571e-02 + 6.81776953494553e-01 -5.84627261960696e-02 + 6.62912611308619e-01 -6.58049585843197e-02 + 6.44324407874433e-01 -7.31351438149378e-02 + 6.26033587000552e-01 -8.04556049946791e-02 + 6.08009280948661e-01 -8.76887844187042e-02 + 5.90240034355429e-01 -9.48121792091236e-02 + 5.72698730868021e-01 -1.01757526822754e-01 + 5.55411618765222e-01 -1.08539348714150e-01 + 5.38410505295645e-01 -1.15176730540461e-01 + 5.21641137664166e-01 -1.21526455119343e-01 + 5.05120327854410e-01 -1.27641178842136e-01 + 4.88826034147189e-01 -1.33452107654868e-01 + 4.72756829324759e-01 -1.38943797888081e-01 + 4.56889462779481e-01 -1.44022468696136e-01 + 4.41254283784751e-01 -1.48736664468832e-01 + 4.25828763295902e-01 -1.53009077959500e-01 + 4.10608396875106e-01 -1.56781442021245e-01 + 3.95611341439966e-01 -1.60067008778474e-01 + 3.80859198346160e-01 -1.62886386652726e-01 + 3.66352119576184e-01 -1.65155670170054e-01 + 3.52107005040102e-01 -1.66902005730228e-01 + 3.38156214714513e-01 -1.68180087712901e-01 + 3.24513341344794e-01 -1.69002675432013e-01 + 3.11187922762876e-01 -1.69365388971009e-01 + 2.98201656691272e-01 -1.69321104984817e-01 + 2.85552513851790e-01 -1.68850434152112e-01 + 2.73253227372360e-01 -1.67989608645765e-01 + 2.61314584364762e-01 -1.66716467434525e-01 + 2.49717456201525e-01 -1.65067768351444e-01 + 2.38481581724083e-01 -1.63168950410788e-01 + 2.27577633315906e-01 -1.61061577397165e-01 + 2.17016518468669e-01 -1.58704919182658e-01 + 2.06802133386028e-01 -1.56117655460340e-01 + 1.96916073521044e-01 -1.53408634182298e-01 + 1.87348745914297e-01 -1.50498802686717e-01 + 1.78110341897585e-01 -1.47440177216010e-01 + 1.69187136270505e-01 -1.44263475400156e-01 + 1.60570365998313e-01 -1.40988056631572e-01 + 1.52250193619772e-01 -1.37644886570335e-01 + 1.44230669463642e-01 -1.34212542197887e-01 + 1.36494686486109e-01 -1.30715956516135e-01 + 1.29041497441893e-01 -1.27160062404650e-01 + 1.21885590388894e-01 -1.23534314732798e-01 + 1.14973606123809e-01 -1.19946512938672e-01 + 1.08305921585264e-01 -1.16388074461917e-01 + 1.01909359633608e-01 -1.12800979544153e-01 + 9.57707298096185e-02 -1.09166779555742e-01 + 8.98707927414503e-02 -1.05536283052279e-01 + 8.42125339933439e-02 -1.01922663598644e-01 + 7.87856905027138e-02 -9.84078143770367e-02 + 7.35906514404928e-02 -9.49953343228512e-02 + 6.86172317695538e-02 -9.15875578296713e-02 + 6.38533217988130e-02 -8.82040084294520e-02 + 5.92980557795527e-02 -8.48301665574652e-02 + 5.49408872977093e-02 -8.14740098816748e-02 + 5.08036836099950e-02 -7.81032042579184e-02 + 4.68610047073478e-02 -7.47702209343977e-02 + 4.30785112607683e-02 -7.15190729392446e-02 + 3.94919427630735e-02 -6.82684814540532e-02 + 3.60951095929823e-02 -6.50177741480466e-02 + 3.28772361824951e-02 -6.18076334563007e-02 + 2.98476901787584e-02 -5.86203472715078e-02 + 2.69646970034140e-02 -5.54923720162200e-02 + 2.42190323125321e-02 -5.24435068585061e-02 + 2.16645901488774e-02 -4.94116456937637e-02 + 1.92850652097574e-02 -4.63923677020781e-02 + 1.70282894977093e-02 -4.34389302947373e-02 + 1.49260602838669e-02 -4.05334871230597e-02 + 1.29912536138279e-02 -3.76649194227854e-02 + 1.12187903727820e-02 -3.48395240965275e-02 + 9.62813430202066e-03 -3.20378388982212e-02 + 8.18092003399821e-03 -2.92857015336182e-02 + 6.84633398695211e-03 -2.66067373303015e-02 + 5.62450310894219e-03 -2.40002771296278e-02 + 4.52964061799434e-03 -2.14585557295876e-02 + 3.61249392215131e-03 -1.89621107862018e-02 + 2.83156382020768e-03 -1.65274274071386e-02 + 2.15391143043915e-03 -1.41677824378179e-02 + 1.61971733933399e-03 -1.18767840274053e-02 + 1.18249367536328e-03 -9.66762809531005e-03 + 9.00276584579961e-04 -7.54452003683207e-03 + 5.63461991934761e-04 -5.51056387158645e-03 + 2.59288533302532e-04 -3.56890304558222e-03 + 6.06131716837195e-05 -1.72224692907942e-03 + 0.00000000000000e+00 0.00000000000000e+00 + 5.67835389889402e-05 2.23388026035764e-03 + 2.00952097149670e-04 4.61469303956217e-03 + 4.46675038797624e-04 7.05931530631234e-03 + 7.76575926534887e-04 9.57140139412797e-03 + 1.15849680432229e-03 1.21547788698366e-02 + 1.54614500966935e-03 1.48065561530573e-02 + 2.00070260770825e-03 1.75170400276963e-02 + 2.65215356260171e-03 2.02792339598468e-02 + 3.47323279235998e-03 2.30829050644064e-02 + 4.46819146620787e-03 2.59178267189914e-02 + 5.56561856863645e-03 2.87980918982248e-02 + 6.79056284994487e-03 3.17045231575689e-02 + 8.13858873349298e-03 3.46598711622827e-02 + 9.68330745830288e-03 3.76352864715079e-02 + 1.14346994907591e-02 4.06147151377888e-02 + 1.33491940226201e-02 4.36083707829037e-02 + 1.53772074549925e-02 4.66378931168147e-02 + 1.75443628317557e-02 4.96905933565631e-02 + 1.98915287956748e-02 5.27532648459689e-02 + 2.24474950353453e-02 5.58108786203703e-02 + 2.51624414470984e-02 5.88978723678661e-02 + 2.80522645924001e-02 6.19853661991399e-02 + 3.11264629746060e-02 6.50542499375811e-02 + 3.43410667421415e-02 6.81372889799119e-02 + 3.77308203466917e-02 7.12243994705516e-02 + 4.13453068432654e-02 7.42879931829202e-02 + 4.51595000908772e-02 7.73456299876008e-02 + 4.91686920501722e-02 8.03852564794801e-02 + 5.33801809367164e-02 8.33956461149312e-02 + 5.77512987175583e-02 8.62331801696985e-02 + 6.23344808339581e-02 8.87547541886008e-02 + 6.71482925323690e-02 9.12346139217212e-02 + 7.21514064313091e-02 9.37368421170488e-02 + 7.73578208727705e-02 9.62429430485729e-02 + 8.27840233215640e-02 9.87392024812666e-02 + 8.84305455042329e-02 1.01203971113129e-01 + 9.42784521040168e-02 1.03684898058958e-01 + 1.00349482885677e-01 1.06148999300961e-01 + 1.06675746455941e-01 1.08500173174811e-01 + 1.13224681689826e-01 1.10860453971563e-01 + 1.19991569273127e-01 1.13309399912637e-01 + 1.26997678082753e-01 1.15723096597717e-01 + 1.34248487747998e-01 1.18083169460431e-01 + 1.41766455235735e-01 1.20337838546890e-01 + 1.49556942766775e-01 1.22463305444449e-01 + 1.57594884531095e-01 1.24605078711964e-01 + 1.65872323102866e-01 1.26751754125367e-01 + 1.74414303121935e-01 1.28791936379402e-01 + 1.83232973200224e-01 1.30716996095475e-01 + 1.92334031181005e-01 1.32504394318715e-01 + 2.01714845882273e-01 1.34221597554837e-01 + 2.11376563986695e-01 1.35950985429642e-01 + 2.21327073690106e-01 1.37513571507823e-01 + 2.31558674587867e-01 1.38949208546669e-01 + 2.42086808461520e-01 1.40274988342984e-01 + 2.52916621133675e-01 1.41437460216382e-01 + 2.64046135586957e-01 1.42454319791249e-01 + 2.75489341566209e-01 1.43333195335266e-01 + 2.87249360771650e-01 1.44017218149413e-01 + 2.99320864102740e-01 1.44510983023378e-01 + 3.11697880289428e-01 1.44782627217238e-01 + 3.24389216406290e-01 1.44771773129655e-01 + 3.37389885735918e-01 1.44584432506276e-01 + 3.50711947471814e-01 1.44154382165419e-01 + 3.64333063360102e-01 1.43552910023117e-01 + 3.78238232522780e-01 1.42687210105816e-01 + 3.92437161035743e-01 1.41543861735063e-01 + 4.06934048908587e-01 1.40264190680221e-01 + 4.21723746945062e-01 1.38767747462759e-01 + 4.36795000699457e-01 1.36967177057565e-01 + 4.52149019127696e-01 1.34947664351219e-01 + 4.67781452534759e-01 1.32666334029277e-01 + 4.83698128848859e-01 1.30225012111576e-01 + 4.99881720532700e-01 1.27468428284761e-01 + 5.16334894694303e-01 1.24505686672269e-01 + 5.33052962546645e-01 1.21341841759092e-01 + 5.50029162636473e-01 1.17972273560778e-01 + 5.67273658847011e-01 1.14454109134925e-01 + 5.84769489731911e-01 1.10723931887335e-01 + 6.02525985564944e-01 1.06864330068656e-01 + 6.20526328831323e-01 1.02850463209321e-01 + 6.38751539751037e-01 9.86367644668299e-02 + 6.57200727073522e-01 9.44111760430084e-02 + 6.75869233343243e-01 9.00585516397063e-02 + 6.94763003002744e-01 8.56060946859686e-02 + 7.13862552225269e-01 8.10172115726413e-02 + 7.33163934294235e-01 7.63128882283146e-02 + 7.52650023865557e-01 7.14576086673483e-02 + 7.72322163431510e-01 6.65036673628003e-02 + 7.92171758296376e-01 6.14635847757860e-02 + 8.12193610513406e-01 5.63508957281089e-02 + 8.32382188739325e-01 5.11679507532475e-02 + 8.52739781790815e-01 4.59537194411629e-02 + 8.73243502309430e-01 4.06300736331539e-02 + 8.93910339588305e-01 3.52818185648098e-02 + 9.14779694269379e-01 3.01276312748428e-02 + 9.35880709193391e-01 2.50231519126587e-02 + 9.57228053275711e-01 1.95608523563538e-02 + 9.78615505631340e-01 1.38731920021658e-02 + 1.00000000000000e+00 7.91978608447872e-03 diff --git a/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF13_Coords.txt b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF13_Coords.txt new file mode 100644 index 00000000..1e2d3601 --- /dev/null +++ b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF13_Coords.txt @@ -0,0 +1,208 @@ + 201 NumCoords ! The number of coordinates in the airfoil shape file (including an extra coordinate for airfoil reference). Set to zero if coordinates not included. +! ......... x-y coordinates are next if NumCoords > 0 ............. +! x-y coordinate of airfoil reference +! x/c y/c + 0.250000 0 +! coordinates of airfoil shape +! interpolation to 200 points +! x/c y/c + 1.00000000000000e+00 -7.43253554058350e-03 + 9.76403943349399e-01 -2.76411676761089e-03 + 9.52484559548605e-01 1.70901095140179e-04 + 9.28638752659537e-01 1.17264141488701e-03 + 9.04989311213425e-01 4.70169949588895e-04 + 8.81494872571301e-01 -1.54228412257468e-03 + 8.58261823976117e-01 -4.71323858688598e-03 + 8.35336988680772e-01 -8.89913342673737e-03 + 8.12757098532986e-01 -1.39333287845482e-02 + 7.90553516827622e-01 -1.97204508402206e-02 + 7.68704378080380e-01 -2.60279549350672e-02 + 7.47200735959936e-01 -3.27322719971618e-02 + 7.26054587908095e-01 -3.97754488388574e-02 + 7.05225114492986e-01 -4.69799082848601e-02 + 6.84763435154875e-01 -5.44309327674479e-02 + 6.64571290619340e-01 -6.18254862513697e-02 + 6.44721094918900e-01 -6.93273346207594e-02 + 6.25169625290117e-01 -7.67585322065482e-02 + 6.05945813175358e-01 -8.41464455288096e-02 + 5.87027171152179e-01 -9.14195705532406e-02 + 5.68408265127836e-01 -9.85559847621229e-02 + 5.50064494090816e-01 -1.05480219170930e-01 + 5.32022391078534e-01 -1.12217201602923e-01 + 5.14305379706589e-01 -1.18778483581882e-01 + 4.96856985375564e-01 -1.24998074174480e-01 + 4.79708052221339e-01 -1.30961580748527e-01 + 4.62835414864543e-01 -1.36587172753257e-01 + 4.46243569969428e-01 -1.41875228138195e-01 + 4.29903985709251e-01 -1.46704975300093e-01 + 4.13842250877566e-01 -1.51115352601705e-01 + 3.98044961478621e-01 -1.55046661039126e-01 + 3.82509179271707e-01 -1.58431291993384e-01 + 3.67251501006871e-01 -1.61278156599173e-01 + 3.52292583349217e-01 -1.63600947933904e-01 + 3.37637965766980e-01 -1.65316224048267e-01 + 3.23307637097987e-01 -1.66752310164544e-01 + 3.09331872759859e-01 -1.67700911633119e-01 + 2.95728021634658e-01 -1.68102591062499e-01 + 2.82508440825120e-01 -1.67965908456118e-01 + 2.69692479373679e-01 -1.67345872254253e-01 + 2.57277849131547e-01 -1.66258775918654e-01 + 2.45272663136680e-01 -1.64751212632708e-01 + 2.33687365765199e-01 -1.62810360546622e-01 + 2.22490214641063e-01 -1.60532132121801e-01 + 2.11704186735648e-01 -1.57971495180763e-01 + 2.01286775160185e-01 -1.55229506262782e-01 + 1.91249599793888e-01 -1.52264499706685e-01 + 1.81596180932401e-01 -1.49084933070302e-01 + 1.72302626179722e-01 -1.45794670174339e-01 + 1.63346132459904e-01 -1.42374113100026e-01 + 1.54746809674797e-01 -1.38830155258698e-01 + 1.46486022194054e-01 -1.35188632600945e-01 + 1.38547760953462e-01 -1.31493700970626e-01 + 1.30918888826124e-01 -1.27769213465648e-01 + 1.23603494162898e-01 -1.23994562827742e-01 + 1.16577318947649e-01 -1.20210273993055e-01 + 1.09842714794822e-01 -1.16401422895844e-01 + 1.03419770202037e-01 -1.12543409822447e-01 + 9.72370562742986e-02 -1.08770274872843e-01 + 9.12953749434174e-02 -1.05058596046523e-01 + 8.56266337766400e-02 -1.01348959545830e-01 + 8.02107080494107e-02 -9.76386287937753e-02 + 7.50289238576886e-02 -9.39674688861899e-02 + 7.00863608932403e-02 -9.03441792141839e-02 + 6.53714233337561e-02 -8.68604994148313e-02 + 6.08759530256630e-02 -8.35323692737949e-02 + 5.65902415275960e-02 -8.02398098638649e-02 + 5.25059651925724e-02 -7.69927063770997e-02 + 4.86166628447913e-02 -7.37837554314917e-02 + 4.49077582947745e-02 -7.06237618527845e-02 + 4.13927777039596e-02 -6.74897039413312e-02 + 3.80641981810206e-02 -6.44036061372499e-02 + 3.48929832724408e-02 -6.13951848582158e-02 + 3.18856459672562e-02 -5.84268249770528e-02 + 2.90442132262908e-02 -5.54899494869964e-02 + 2.63811004580753e-02 -5.25920709101139e-02 + 2.38848880530692e-02 -4.97328732122965e-02 + 2.15021569942004e-02 -4.69560380557319e-02 + 1.92408086204874e-02 -4.42606273044788e-02 + 1.71577483979552e-02 -4.15892362716984e-02 + 1.52256501903280e-02 -3.89479589361177e-02 + 1.33940150325620e-02 -3.63811619058724e-02 + 1.16945968480858e-02 -3.38694685065991e-02 + 1.01399947277134e-02 -3.14005699954941e-02 + 8.73005199067174e-03 -2.89778491430780e-02 + 7.47487782179956e-03 -2.65876880354154e-02 + 6.33594551826867e-03 -2.42535714842850e-02 + 5.28961501167165e-03 -2.19902421680995e-02 + 4.32280168968960e-03 -1.98014211395919e-02 + 3.45367866450521e-03 -1.76778349381210e-02 + 2.74078600109631e-03 -1.55973088719527e-02 + 2.13806582939436e-03 -1.35749028237675e-02 + 1.61183106799287e-03 -1.16229600944032e-02 + 1.19278741801813e-03 -9.73562172682337e-03 + 8.52780015436871e-04 -7.91879592506294e-03 + 6.34492750095705e-04 -6.17534236909210e-03 + 3.96951815978446e-04 -4.50663935247869e-03 + 1.88581057949551e-04 -2.91531619917444e-03 + 4.72174234786785e-05 -1.40304801253723e-03 + 0.00000000000000e+00 0.00000000000000e+00 + 4.49286575851582e-05 1.76091109368109e-03 + 1.54712126205946e-04 3.62140154224627e-03 + 3.30083241230729e-04 5.53978075065709e-03 + 5.67107864039499e-04 7.51898308153193e-03 + 8.43717618992945e-04 9.56261412743599e-03 + 1.13820712865826e-03 1.16673197751854e-02 + 1.51620497309045e-03 1.38230510834726e-02 + 2.05010390234215e-03 1.60283976006057e-02 + 2.70761333894050e-03 1.82791506633120e-02 + 3.49886357702170e-03 2.05667372944473e-02 + 4.38563597305350e-03 2.28994709759180e-02 + 5.36480583545219e-03 2.52727779283164e-02 + 6.45176350756975e-03 2.76932258096428e-02 + 7.71493839934877e-03 3.01347479048045e-02 + 9.13811424494260e-03 3.25975238107331e-02 + 1.06948081659682e-02 3.50885690282112e-02 + 1.23665030939463e-02 3.76127912846818e-02 + 1.41631103789096e-02 4.01690740091098e-02 + 1.61006676743100e-02 4.27565790645424e-02 + 1.82006253144294e-02 4.53661056474953e-02 + 2.04339011456132e-02 4.80195490755358e-02 + 2.28313083356356e-02 5.06809426782037e-02 + 2.53998275561691e-02 5.33417422932120e-02 + 2.80831554197667e-02 5.60479549242059e-02 + 3.09172689371117e-02 5.87826801739081e-02 + 3.39613669672685e-02 6.15040472448373e-02 + 3.71885488983873e-02 6.42371788378289e-02 + 4.05844892078012e-02 6.69873627303355e-02 + 4.41615443337093e-02 6.97416261506273e-02 + 4.78986121512040e-02 7.24009578305107e-02 + 5.18317438541022e-02 7.48725582194455e-02 + 5.59775247308777e-02 7.73346153272878e-02 + 6.03069307314000e-02 7.98322938773953e-02 + 6.48317249020550e-02 8.23552542934740e-02 + 6.95740177949655e-02 8.48797840519584e-02 + 7.45346746264872e-02 8.73976434260533e-02 + 7.96940411568568e-02 8.99518601786404e-02 + 8.50751411244750e-02 9.25115521139639e-02 + 9.07047952097347e-02 9.50119363718962e-02 + 9.65644778591387e-02 9.75280567202470e-02 + 1.02654922362443e-01 1.00141176068606e-01 + 1.08991128382069e-01 1.02759655535384e-01 + 1.15580811141506e-01 1.05350177915118e-01 + 1.22442015345549e-01 1.07879078703890e-01 + 1.29581761141198e-01 1.10327867455967e-01 + 1.36985125957807e-01 1.12805201120027e-01 + 1.44649070157922e-01 1.15294515341388e-01 + 1.52601162527081e-01 1.17695162751273e-01 + 1.60849467906986e-01 1.20016136499640e-01 + 1.69400994120977e-01 1.22239166511633e-01 + 1.78257906944928e-01 1.24404435861666e-01 + 1.87423810521919e-01 1.26566367432406e-01 + 1.96913917030033e-01 1.28565322487382e-01 + 2.06714122721902e-01 1.30480002121111e-01 + 2.16843733267671e-01 1.32284460248505e-01 + 2.27313503043412e-01 1.33932897606815e-01 + 2.38116555091135e-01 1.35466082264203e-01 + 2.49270187442578e-01 1.36855347383195e-01 + 2.60783364777495e-01 1.38015044037685e-01 + 2.72649760913212e-01 1.38972898742601e-01 + 2.84865722003232e-01 1.39703902024797e-01 + 2.97442765366165e-01 1.40129901393810e-01 + 3.10371404770489e-01 1.40389901175565e-01 + 3.23663550383385e-01 1.40356686531760e-01 + 3.37302478141465e-01 1.40159944002643e-01 + 3.51279258331868e-01 1.39708203283014e-01 + 3.65599383240653e-01 1.38942103586727e-01 + 3.80266593353821e-01 1.38048333465819e-01 + 3.95276573569828e-01 1.36930305581693e-01 + 4.10621082225397e-01 1.35488514837408e-01 + 4.26300213083275e-01 1.33810605435263e-01 + 4.42308306311055e-01 1.31836152808260e-01 + 4.58654091580520e-01 1.29693294983505e-01 + 4.75315068619854e-01 1.27173492402662e-01 + 4.92299980112839e-01 1.24408547660075e-01 + 5.09602575838928e-01 1.21522453981813e-01 + 5.27212395134502e-01 1.18468930195838e-01 + 5.45136348862968e-01 1.15242151997318e-01 + 5.63358188082521e-01 1.11781777741663e-01 + 5.81885057318307e-01 1.08171778668078e-01 + 6.00697978768359e-01 1.04372430246799e-01 + 6.19778853163952e-01 1.00342858722927e-01 + 6.39128296470107e-01 9.62399740334075e-02 + 6.58737479416311e-01 9.19824964120890e-02 + 6.78606901768962e-01 8.76000132289643e-02 + 6.98713465939465e-01 8.30431156104294e-02 + 7.19053735025290e-01 7.83520462505258e-02 + 7.39609238737388e-01 7.34999974962512e-02 + 7.60379187011757e-01 6.85439537095766e-02 + 7.81346186916718e-01 6.34710892603186e-02 + 8.02497578082114e-01 5.82840033620211e-02 + 8.23825251477110e-01 5.29994283777580e-02 + 8.45332549847506e-01 4.76847762917876e-02 + 8.66989872326120e-01 4.22607936796464e-02 + 8.88796133601469e-01 3.67689289229451e-02 + 9.10777419149797e-01 3.13903865017990e-02 + 9.32946008475891e-01 2.60399205588807e-02 + 9.55291210260545e-01 2.03661935434009e-02 + 9.77655302958250e-01 1.44867409656004e-02 + 1.00000000000000e+00 8.36305924051618e-03 diff --git a/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF14_Coords.txt b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF14_Coords.txt new file mode 100644 index 00000000..21ac9bc9 --- /dev/null +++ b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF14_Coords.txt @@ -0,0 +1,208 @@ + 201 NumCoords ! The number of coordinates in the airfoil shape file (including an extra coordinate for airfoil reference). Set to zero if coordinates not included. +! ......... x-y coordinates are next if NumCoords > 0 ............. +! x-y coordinate of airfoil reference +! x/c y/c + 0.250000 0 +! coordinates of airfoil shape +! interpolation to 200 points +! x/c y/c + 1.00000000000000e+00 -8.14836236062521e-03 + 9.75605454220754e-01 -3.27870018079412e-03 + 9.50836784314451e-01 -2.20900988818551e-04 + 9.26031070036306e-01 8.25225422744434e-04 + 9.01354150415546e-01 4.63723364948677e-05 + 8.76856729032888e-01 -2.12212287818620e-03 + 8.52628325860033e-01 -5.49153345932107e-03 + 8.28726407818510e-01 -9.92913740060339e-03 + 8.05179636734850e-01 -1.52183220368432e-02 + 7.82028005324449e-01 -2.12905294714742e-02 + 7.59247407101620e-01 -2.78817020291902e-02 + 7.36825672022388e-01 -3.48456742332678e-02 + 7.14771415904034e-01 -4.21126282820779e-02 + 6.93052137845832e-01 -4.95161086094975e-02 + 6.71727481343893e-01 -5.71636330448956e-02 + 6.50688318620596e-01 -6.46990238340603e-02 + 6.30027418222565e-01 -7.23373717103563e-02 + 6.09682760834827e-01 -7.98549524801710e-02 + 5.89688828203817e-01 -8.73005491504785e-02 + 5.70031102500545e-01 -9.46078346312720e-02 + 5.50710313744022e-01 -1.01755382714016e-01 + 5.31704773200269e-01 -1.08661561649762e-01 + 5.13040076772302e-01 -1.15360198522277e-01 + 4.94731072648672e-01 -1.21856401857074e-01 + 4.76720063365871e-01 -1.27964705191137e-01 + 4.59050447577727e-01 -1.33798894725046e-01 + 4.41698554665827e-01 -1.39265991429221e-01 + 4.24673935956588e-01 -1.44379903497306e-01 + 4.07943877996459e-01 -1.48996777520091e-01 + 3.91529590322889e-01 -1.53147337031555e-01 + 3.75425881926708e-01 -1.56786941146897e-01 + 3.59631453908511e-01 -1.59839992659012e-01 + 3.44161400760639e-01 -1.62311690399160e-01 + 3.29035392588028e-01 -1.64209813619226e-01 + 3.14263667203509e-01 -1.65451316764320e-01 + 2.99868746495612e-01 -1.66506903639003e-01 + 2.85878821421829e-01 -1.67028933600720e-01 + 2.72314348501668e-01 -1.66931590818852e-01 + 2.59190034344532e-01 -1.66240903049082e-01 + 2.46523097896223e-01 -1.65015711658322e-01 + 2.34311085993631e-01 -1.63309762544107e-01 + 2.22557973039563e-01 -1.61179016172101e-01 + 2.11273825191574e-01 -1.58619367104621e-01 + 2.00416162834866e-01 -1.55781295522583e-01 + 1.90010573443506e-01 -1.52649361562255e-01 + 1.80003508496110e-01 -1.49375875213019e-01 + 1.70407177602816e-01 -1.45918068123790e-01 + 1.61224702358730e-01 -1.42273052042672e-01 + 1.52427517023986e-01 -1.38535454147255e-01 + 1.43981471299467e-01 -1.34741684356880e-01 + 1.35915137076383e-01 -1.30853570083458e-01 + 1.28205843380849e-01 -1.26896454867671e-01 + 1.20831500156688e-01 -1.22926515095291e-01 + 1.13776200252657e-01 -1.18962260383654e-01 + 1.07043970465416e-01 -1.14984403533098e-01 + 1.00604490983182e-01 -1.11043538945192e-01 + 9.44627247382671e-02 -1.07112169597954e-01 + 8.86436371027153e-02 -1.03150305327463e-01 + 8.30609551236505e-02 -9.93048193507565e-02 + 7.77158685764800e-02 -9.55452265219299e-02 + 7.26442623777319e-02 -9.18109492601984e-02 + 6.78200455328382e-02 -8.81164194990571e-02 + 6.32251003858072e-02 -8.44890217245990e-02 + 5.88664059457334e-02 -8.09291839835693e-02 + 5.47314426912757e-02 -7.75147830298754e-02 + 5.08048887650857e-02 -7.42689802432870e-02 + 4.70774277960059e-02 -7.10840961776320e-02 + 4.35439177679982e-02 -6.79622663696009e-02 + 4.01931090877671e-02 -6.49028866719955e-02 + 3.70071961558051e-02 -6.19186097345931e-02 + 3.39928055580254e-02 -5.89938489520709e-02 + 3.11577683019826e-02 -5.61235560760588e-02 + 2.84775442869274e-02 -5.33253098749644e-02 + 2.59337722860059e-02 -5.06003306707210e-02 + 2.35351879537169e-02 -4.79341414523893e-02 + 2.13137371577664e-02 -4.53052669924546e-02 + 1.92412232739687e-02 -4.27265135238339e-02 + 1.72551808149047e-02 -4.02460777005286e-02 + 1.53775125192213e-02 -3.78461069409167e-02 + 1.36669286314092e-02 -3.54751904767474e-02 + 1.20867763486272e-02 -3.31490567840202e-02 + 1.05884996763417e-02 -3.09033988993154e-02 + 9.20425453765281e-03 -2.87165660887120e-02 + 7.94657176624660e-03 -2.65748008857490e-02 + 6.81901031712526e-03 -2.44798541378323e-02 + 5.82356366307817e-03 -2.24237272913497e-02 + 4.92174384636360e-03 -2.04275731539013e-02 + 4.09719664088157e-03 -1.84975012786712e-02 + 3.32633841273745e-03 -1.66402354620686e-02 + 2.63006056419046e-03 -1.48461343785805e-02 + 2.07265379541992e-03 -1.30914265545919e-02 + 1.60475669651842e-03 -1.13896387204853e-02 + 1.19362491575511e-03 -9.75207784151342e-03 + 8.61158304775857e-04 -8.17325143675256e-03 + 5.92658871339785e-04 -6.65366840829812e-03 + 4.11941085518658e-04 -5.19491140252507e-03 + 2.54556569896829e-04 -3.79658841465355e-03 + 1.28113832478964e-04 -2.46056989256330e-03 + 3.57617220409199e-05 -1.18717030094207e-03 + 0.00000000000000e+00 0.00000000000000e+00 + 3.47906660476153e-05 1.35864880901149e-03 + 1.15168885058535e-04 2.77417290109050e-03 + 2.30376916315236e-04 4.24252249803400e-03 + 3.87976131495443e-04 5.76601626174964e-03 + 5.74526506204122e-04 7.34806995808761e-03 + 7.95654255520616e-04 8.98493392763457e-03 + 1.12021971636174e-03 1.06662550219730e-02 + 1.56154664930487e-03 1.23953998641279e-02 + 2.08683544746350e-03 1.41733115513416e-02 + 2.71224085851922e-03 1.59928312616081e-02 + 3.43035954718513e-03 1.78573300023999e-02 + 4.21435009067654e-03 1.97747226754239e-02 + 5.09317032805970e-03 2.17377376445490e-02 + 6.12872222137403e-03 2.37226879106243e-02 + 7.28358292664935e-03 2.57436355827732e-02 + 8.54729910157088e-03 2.78048612104546e-02 + 9.92972828959359e-03 2.98969637573703e-02 + 1.14264946100910e-02 3.20287229123090e-02 + 1.30302058764849e-02 3.42098777797921e-02 + 1.47545509310666e-02 3.64362116507928e-02 + 1.65895142682137e-02 3.87188939282128e-02 + 1.85799091430884e-02 4.10158975075125e-02 + 2.07318790579148e-02 4.33277140117620e-02 + 2.29786410496385e-02 4.57116743283601e-02 + 2.53553835037421e-02 4.81450487278177e-02 + 2.79278776797602e-02 5.05737523231150e-02 + 3.06684104757498e-02 5.30293753541954e-02 + 3.35549896302923e-02 5.55320353345598e-02 + 3.66048832549710e-02 5.80672661628428e-02 + 3.98160878278975e-02 6.05922518843348e-02 + 4.32097657635900e-02 6.30632131339738e-02 + 4.68004477364611e-02 6.55508747412392e-02 + 5.05703468888338e-02 6.80833115592091e-02 + 5.45293129960311e-02 7.06568325856674e-02 + 5.87044042125043e-02 7.32381347585862e-02 + 6.30971043353738e-02 7.58315677252795e-02 + 6.76867916036615e-02 7.84763490181517e-02 + 7.24967292572105e-02 8.11447924400529e-02 + 7.75489190519818e-02 8.38012218025252e-02 + 8.28379430912991e-02 8.64755853792752e-02 + 8.83700160522555e-02 8.92311260118967e-02 + 9.41546877815251e-02 9.20147089552618e-02 + 1.00200275044183e-01 9.47925250920637e-02 + 1.06519506627458e-01 9.75499482587641e-02 + 1.13121273553931e-01 1.00272215404985e-01 + 1.20000865270765e-01 1.03022793377647e-01 + 1.27160568795956e-01 1.05784624380971e-01 + 1.34629377330607e-01 1.08475019956957e-01 + 1.42410501436542e-01 1.11115501827654e-01 + 1.50511658880668e-01 1.13695222223560e-01 + 1.58939652295794e-01 1.16224524312285e-01 + 1.67700467710513e-01 1.18723937489766e-01 + 1.76815783980035e-01 1.21067625942295e-01 + 1.86265538652919e-01 1.23365512977448e-01 + 1.96071866452217e-01 1.25554708540608e-01 + 2.06250547051562e-01 1.27593275787970e-01 + 2.16789870603760e-01 1.29541754711146e-01 + 2.27709471480002e-01 1.31337948456032e-01 + 2.39023607624358e-01 1.32877774715532e-01 + 2.50725312099806e-01 1.34211878219550e-01 + 2.62813163393733e-01 1.35317273908679e-01 + 2.75300589304416e-01 1.36105292149500e-01 + 2.88173680979742e-01 1.36733482190757e-01 + 3.01443959248928e-01 1.37027602201975e-01 + 3.15100693572125e-01 1.37162360722735e-01 + 3.29141136015704e-01 1.37051985111160e-01 + 3.43566633885766e-01 1.36597826483452e-01 + 3.58379996607331e-01 1.36020493099717e-01 + 3.73577404766437e-01 1.35212892447741e-01 + 3.89153622315017e-01 1.34072142153192e-01 + 4.05108094120761e-01 1.32686673560345e-01 + 4.21433969423481e-01 1.30984053441620e-01 + 4.38142341403862e-01 1.29118324458878e-01 + 4.55206328011914e-01 1.26836633577195e-01 + 4.72639853963158e-01 1.24300133080523e-01 + 4.90435271070256e-01 1.21679117794261e-01 + 5.08579010309887e-01 1.18895867110872e-01 + 5.27074571229468e-01 1.15918274965440e-01 + 5.45906008138401e-01 1.12688629331682e-01 + 5.65078719861412e-01 1.09292084145262e-01 + 5.84572298052518e-01 1.05676186408607e-01 + 6.04369364403524e-01 1.01804075775369e-01 + 6.24472197888980e-01 9.77950051523939e-02 + 6.44868545310258e-01 9.36084798785348e-02 + 6.65553461692358e-01 8.92765243340495e-02 + 6.86500234562328e-01 8.47365603510263e-02 + 7.07706100172094e-01 8.00475004561028e-02 + 7.29151865146187e-01 7.51929614727690e-02 + 7.50834276036418e-01 7.02319315014268e-02 + 7.72727461247450e-01 6.51263205099363e-02 + 7.94812249063048e-01 5.98701925922095e-02 + 8.17078362972243e-01 5.44954720205527e-02 + 8.39529154287222e-01 4.90934541266714e-02 + 8.62128984506176e-01 4.35866611147249e-02 + 8.84858418262504e-01 3.79716307048406e-02 + 9.07728679674592e-01 3.23837149939797e-02 + 9.30734095888120e-01 2.68027303925987e-02 + 9.53837027134021e-01 2.09467195741978e-02 + 9.76936319972422e-01 1.49132298932001e-02 + 1.00000000000000e+00 8.66710884250080e-03 diff --git a/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF15_Coords.txt b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF15_Coords.txt new file mode 100644 index 00000000..670d0c5a --- /dev/null +++ b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF15_Coords.txt @@ -0,0 +1,208 @@ + 201 NumCoords ! The number of coordinates in the airfoil shape file (including an extra coordinate for airfoil reference). Set to zero if coordinates not included. +! ......... x-y coordinates are next if NumCoords > 0 ............. +! x-y coordinate of airfoil reference +! x/c y/c + 0.250000 0 +! coordinates of airfoil shape +! interpolation to 200 points +! x/c y/c + 1.00000000000000e+00 -8.57879977773810e-03 + 9.75180222150308e-01 -3.03879904135747e-03 + 9.49954708363444e-01 -1.26002872729501e-04 + 9.24617663626292e-01 6.10122226095701e-04 + 8.99362589909934e-01 -2.13375521927681e-04 + 8.74301657857705e-01 -2.47307597608542e-03 + 8.49512831893362e-01 -5.95848312946069e-03 + 8.25060132654372e-01 -1.05432097366251e-02 + 8.00967349009157e-01 -1.59814342852104e-02 + 7.77279396459348e-01 -2.22202726470426e-02 + 7.53971146353458e-01 -2.89772479518455e-02 + 7.31028686926424e-01 -3.60929872413459e-02 + 7.08458616265561e-01 -4.34907379085029e-02 + 6.86233439551971e-01 -5.10105449101421e-02 + 6.64417721038235e-01 -5.87729225500483e-02 + 6.42896424356607e-01 -6.63906320145616e-02 + 6.21774241465352e-01 -7.41087631455492e-02 + 6.00977841522425e-01 -8.16768344389446e-02 + 5.80544552788493e-01 -8.91561467273735e-02 + 5.60464827414216e-01 -9.64833988179528e-02 + 5.40743392390515e-01 -1.03637454592294e-01 + 5.21360556780428e-01 -1.10533080197566e-01 + 5.02340910284044e-01 -1.17209304289204e-01 + 4.83693742857298e-01 -1.23667469493609e-01 + 4.65360905225594e-01 -1.29710726001548e-01 + 4.47393349439378e-01 -1.35469330395386e-01 + 4.29767286515700e-01 -1.40843787417424e-01 + 4.12495217820767e-01 -1.45855913618906e-01 + 3.95542115741603e-01 -1.50348364394606e-01 + 3.78926510481714e-01 -1.54347061753637e-01 + 3.62648170482185e-01 -1.57816166203811e-01 + 3.46706871509637e-01 -1.60675411249642e-01 + 3.31116764742986e-01 -1.62927825900264e-01 + 3.15896874263702e-01 -1.64577732807176e-01 + 3.01060219418983e-01 -1.65542318105973e-01 + 2.86630760513041e-01 -1.66019067198897e-01 + 2.72635352957487e-01 -1.65852810272617e-01 + 2.59096229086319e-01 -1.65053656791642e-01 + 2.46029444917578e-01 -1.63674484017382e-01 + 2.33450927162206e-01 -1.61779021413358e-01 + 2.21358148093932e-01 -1.59458179997197e-01 + 2.09752590238530e-01 -1.56768645463127e-01 + 1.98644065634366e-01 -1.53708652225252e-01 + 1.87983838111383e-01 -1.50468466633829e-01 + 1.77798959359292e-01 -1.46968929468240e-01 + 1.68029515979667e-01 -1.43391369897358e-01 + 1.58688054711323e-01 -1.39690800395147e-01 + 1.49777434120809e-01 -1.35854606762879e-01 + 1.41266364582040e-01 -1.31957036662395e-01 + 1.33114043882986e-01 -1.28072240442312e-01 + 1.25353982091811e-01 -1.24123605323377e-01 + 1.17961213252232e-01 -1.20147065379440e-01 + 1.10910137898332e-01 -1.16185429245801e-01 + 1.04183249914720e-01 -1.12256793878014e-01 + 9.77845035922472e-02 -1.08341834070059e-01 + 9.16800568181114e-02 -1.04487577173595e-01 + 8.58763837804680e-02 -1.00669929174109e-01 + 8.04013343441990e-02 -9.68347298049542e-02 + 7.51601956348723e-02 -9.31177415424908e-02 + 7.01543935952098e-02 -8.94997948476300e-02 + 6.54219938355571e-02 -8.59156686036492e-02 + 6.09334040261291e-02 -8.23945222782936e-02 + 5.66708598548473e-02 -7.89496641080547e-02 + 5.26424925924951e-02 -7.55684130212430e-02 + 4.88353267109018e-02 -7.22706692662718e-02 + 4.52299098002129e-02 -6.90769445598798e-02 + 4.18171486326621e-02 -6.59585470797291e-02 + 3.85937390562270e-02 -6.29132740880722e-02 + 3.55456313710721e-02 -5.99446421848028e-02 + 3.26532165695984e-02 -5.70661627728155e-02 + 2.99191791468483e-02 -5.42663897359114e-02 + 2.73603366698335e-02 -5.15240489459803e-02 + 2.49547621710270e-02 -4.88496591224952e-02 + 2.26696019923393e-02 -4.62677203676052e-02 + 2.05173895362584e-02 -4.37606410408951e-02 + 1.85413689047946e-02 -4.12897613211990e-02 + 1.67039255897644e-02 -3.88748760932536e-02 + 1.49376604499564e-02 -3.65661749206043e-02 + 1.32724098833742e-02 -3.43362370571288e-02 + 1.17676398242478e-02 -3.21379214236623e-02 + 1.03812841619170e-02 -2.99928372995567e-02 + 9.06612278982865e-03 -2.79311924288680e-02 + 7.85471709046639e-03 -2.59296320464281e-02 + 6.75962346486767e-03 -2.39733845222929e-02 + 5.78638085277238e-03 -2.20635808604033e-02 + 4.93219411743517e-03 -2.01957483008656e-02 + 4.15866656660073e-03 -1.83895524002002e-02 + 3.45414954175195e-03 -1.66456540575484e-02 + 2.78923310544400e-03 -1.49722402872741e-02 + 2.18613805623396e-03 -1.33598127496920e-02 + 1.71216161569515e-03 -1.17839473069557e-02 + 1.31624248102220e-03 -1.02571525116732e-02 + 9.66801840458578e-04 -8.79003718291119e-03 + 6.80319528299336e-04 -7.37728839044000e-03 + 4.49100581451274e-04 -6.01658261674601e-03 + 2.83701305712447e-04 -4.70870707990412e-03 + 1.71327286198412e-04 -3.45212068865394e-03 + 9.27710524239121e-05 -2.24812638028363e-03 + 2.90659238934096e-05 -1.09605843814913e-03 + 0.00000000000000e+00 0.00000000000000e+00 + 2.88650625107761e-05 1.11148823849564e-03 + 9.20560654498922e-05 2.26693180022457e-03 + 1.72099085901139e-04 3.47224142051019e-03 + 2.83274561762190e-04 4.72937588738418e-03 + 4.17185695243679e-04 6.04164001396517e-03 + 5.97882203243190e-04 7.40505294611765e-03 + 8.95891727887411e-04 8.80908372794426e-03 + 1.28619996129368e-03 1.02598911578957e-02 + 1.73718091964475e-03 1.17614295105485e-02 + 2.26889766516844e-03 1.33073665302488e-02 + 2.89290184609361e-03 1.48981843737658e-02 + 3.56863592046535e-03 1.65490975122241e-02 + 4.33167262281806e-03 1.82447453137629e-02 + 5.23928473841845e-03 1.99628317108720e-02 + 6.24211877712485e-03 2.17255330691366e-02 + 7.33964056226407e-03 2.35355313731346e-02 + 8.55899423724526e-03 2.53750621882832e-02 + 9.88712266524690e-03 2.72586895159738e-02 + 1.13020867063170e-02 2.92023348035768e-02 + 1.28124619939745e-02 3.12046945194575e-02 + 1.44198946335000e-02 3.32706688249579e-02 + 1.61778638266544e-02 3.53546883232132e-02 + 1.80925347692918e-02 3.74625260070275e-02 + 2.00910255479398e-02 3.96581315151937e-02 + 2.22073480805733e-02 4.19153679037419e-02 + 2.45104741518688e-02 4.41730112135886e-02 + 2.69725227219957e-02 4.64664319277826e-02 + 2.95672369905170e-02 4.88244154637241e-02 + 3.23149834672359e-02 5.12316228766112e-02 + 3.52251763885414e-02 5.36850922615401e-02 + 3.83099350602331e-02 5.61720264031417e-02 + 4.15824489104227e-02 5.86905077324653e-02 + 4.50317770709382e-02 6.12582681605947e-02 + 4.86666503586395e-02 6.38753760166677e-02 + 5.25170727043328e-02 6.65025186818970e-02 + 5.65850189187534e-02 6.91518398462091e-02 + 6.08491647683366e-02 7.18603850558563e-02 + 6.53325801131270e-02 7.46028792309043e-02 + 7.00543348142427e-02 7.73615611579748e-02 + 7.50171013293054e-02 8.01381142978750e-02 + 8.02306159895163e-02 8.29454075566739e-02 + 8.57012088705319e-02 8.57724141117260e-02 + 9.14370395472359e-02 8.86083733592826e-02 + 9.74471306573141e-02 9.14506955541571e-02 + 1.03741642665461e-01 9.42869115799166e-02 + 1.10322431016719e-01 9.71366683959768e-02 + 1.17195331455295e-01 9.99963817208149e-02 + 1.24389884664589e-01 1.02804765589993e-01 + 1.31905935056049e-01 1.05580086008781e-01 + 1.39751456026638e-01 1.08317196263952e-01 + 1.47936168023821e-01 1.11006216128796e-01 + 1.56467558128623e-01 1.13642271424664e-01 + 1.65371163914618e-01 1.16141616432774e-01 + 1.74623252652850e-01 1.18621015919461e-01 + 1.84247428093051e-01 1.20997142483866e-01 + 1.94262496093302e-01 1.23226242267470e-01 + 2.04653672488981e-01 1.25380363541681e-01 + 2.15441765864240e-01 1.27378959185081e-01 + 2.26644243180055e-01 1.29123968217828e-01 + 2.38253845273158e-01 1.30674870254090e-01 + 2.50270552701415e-01 1.31999307783067e-01 + 2.62708751790901e-01 1.33015597369151e-01 + 2.75551725512235e-01 1.33872159509066e-01 + 2.88810665433822e-01 1.34378959676908e-01 + 3.02478807217932e-01 1.34723171413855e-01 + 3.16557400521368e-01 1.34828318979527e-01 + 3.31045159681679e-01 1.34573337077908e-01 + 3.45944140981529e-01 1.34191735267806e-01 + 3.61250730235273e-01 1.33577791174796e-01 + 3.76961614806380e-01 1.32641039909018e-01 + 3.93075978637921e-01 1.31467341415961e-01 + 4.09586247490783e-01 1.29983874522969e-01 + 4.26504850189084e-01 1.28372193187690e-01 + 4.43802359792042e-01 1.26353263881723e-01 + 4.61495724587332e-01 1.24138877363526e-01 + 4.79576454948711e-01 1.21758646632159e-01 + 4.98029186432348e-01 1.19133369177162e-01 + 5.16855180283856e-01 1.16301424988927e-01 + 5.36038549215196e-01 1.13206639039446e-01 + 5.55583719652262e-01 1.09934856544340e-01 + 5.75469608979237e-01 1.06426184782536e-01 + 5.95679247848144e-01 1.02646109224194e-01 + 6.16216032509872e-01 9.86875548679134e-02 + 6.37065764297449e-01 9.45384567802663e-02 + 6.58220009598337e-01 9.02324184327279e-02 + 6.79649739397516e-01 8.56983061171984e-02 + 7.01352675498130e-01 8.10067998035236e-02 + 7.23309367720016e-01 7.61487654794268e-02 + 7.45514874390413e-01 7.11835831183337e-02 + 7.67937997489119e-01 6.60570021231055e-02 + 7.90555709099499e-01 6.07584149955232e-02 + 8.13356480155146e-01 5.53297489402000e-02 + 8.36343320325429e-01 4.98760881816722e-02 + 8.59476947043660e-01 4.43220559191783e-02 + 8.82726076021484e-01 3.86348982394945e-02 + 9.06091895800112e-01 3.29178055135213e-02 + 9.29556869258233e-01 2.71942568107446e-02 + 9.53065562517705e-01 2.12312867691710e-02 + 9.76555746470235e-01 1.51116304681152e-02 + 1.00000000000000e+00 8.80279316603190e-03 diff --git a/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF16_Coords.txt b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF16_Coords.txt new file mode 100644 index 00000000..c1f50c91 --- /dev/null +++ b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF16_Coords.txt @@ -0,0 +1,208 @@ + 201 NumCoords ! The number of coordinates in the airfoil shape file (including an extra coordinate for airfoil reference). Set to zero if coordinates not included. +! ......... x-y coordinates are next if NumCoords > 0 ............. +! x-y coordinate of airfoil reference +! x/c y/c + 0.250000 0 +! coordinates of airfoil shape +! interpolation to 200 points +! x/c y/c + 1.00000000000000e+00 -7.93823528916634e-03 + 9.75306611523266e-01 -3.07804362808370e-03 + 9.50254896398834e-01 2.12362996603380e-05 + 9.25086956564820e-01 1.10034879293892e-03 + 8.99988535976524e-01 4.37422920277549e-04 + 8.75072599857149e-01 -1.69228312874642e-03 + 8.50417485943084e-01 -5.02575124436309e-03 + 8.26088106219083e-01 -9.48963995265479e-03 + 8.02111382252523e-01 -1.48157088586162e-02 + 7.78533224241522e-01 -2.09559594834436e-02 + 7.55333131164625e-01 -2.76360667094703e-02 + 7.32498770899621e-01 -3.46931927585546e-02 + 7.10037524800713e-01 -4.20512954807589e-02 + 6.87921684496055e-01 -4.95447286109428e-02 + 6.66209179710118e-01 -5.72757010622818e-02 + 6.44793205529505e-01 -6.48779142100834e-02 + 6.23770247083330e-01 -7.25767710634749e-02 + 6.03070773283972e-01 -8.01314038494710e-02 + 5.82725782097447e-01 -8.75866260531345e-02 + 5.62727405516286e-01 -9.48842528629214e-02 + 5.43080423918886e-01 -1.02003644748097e-01 + 5.23763733755852e-01 -1.08853301029009e-01 + 5.04803219809205e-01 -1.15477844917736e-01 + 4.86206982188546e-01 -1.21874673443526e-01 + 4.67921007083763e-01 -1.27856568331733e-01 + 4.49992820623389e-01 -1.33542654805615e-01 + 4.32401794865636e-01 -1.38840810792771e-01 + 4.15160522435188e-01 -1.43774009354166e-01 + 3.98236888852800e-01 -1.48190991673080e-01 + 3.81648251477225e-01 -1.52112731931741e-01 + 3.65396878028470e-01 -1.55516473547203e-01 + 3.49482408564341e-01 -1.58321238170515e-01 + 3.33919160469124e-01 -1.60534240376794e-01 + 3.18725408829206e-01 -1.62165537784395e-01 + 3.03913049141917e-01 -1.63131873998207e-01 + 2.89504737395872e-01 -1.62983765163967e-01 + 2.75525761184225e-01 -1.62070670020849e-01 + 2.61996790164123e-01 -1.60600815773790e-01 + 2.48932908441187e-01 -1.58650156209932e-01 + 2.36348800371720e-01 -1.56288718478177e-01 + 2.24242074483076e-01 -1.53625685704211e-01 + 2.12614132311826e-01 -1.50704613076576e-01 + 2.01474116266847e-01 -1.47515164268461e-01 + 1.90775946871820e-01 -1.44259340711770e-01 + 1.80545164370369e-01 -1.40816254075015e-01 + 1.70726148932411e-01 -1.37356122795043e-01 + 1.61329495142793e-01 -1.33838435774938e-01 + 1.52357448812365e-01 -1.30248116217731e-01 + 1.43781676609354e-01 -1.26622879278557e-01 + 1.35562251699688e-01 -1.23048941083730e-01 + 1.27731865989209e-01 -1.19425293871551e-01 + 1.20263781459649e-01 -1.15816680044401e-01 + 1.13136940952170e-01 -1.12220007869416e-01 + 1.06332983042845e-01 -1.08662489701008e-01 + 9.98554576560956e-02 -1.05123339035014e-01 + 9.36729639947835e-02 -1.01629914852298e-01 + 8.77889829403561e-02 -9.81820383630434e-02 + 8.22313494306295e-02 -9.47155808667247e-02 + 7.69114078116147e-02 -9.13308647018588e-02 + 7.18269333109061e-02 -8.80418761209455e-02 + 6.70154064102991e-02 -8.47739827365595e-02 + 6.24469306153174e-02 -8.15646647777206e-02 + 5.81057659587854e-02 -7.84140549690817e-02 + 5.40009405345228e-02 -7.52947049856435e-02 + 5.01151207789006e-02 -7.21659059076321e-02 + 4.64322700792648e-02 -6.90335942126407e-02 + 4.29462331812666e-02 -6.59671142994205e-02 + 3.96515804572136e-02 -6.29681996718810e-02 + 3.65329345743545e-02 -6.00437178811974e-02 + 3.35738970738148e-02 -5.72025031652544e-02 + 3.07754335365257e-02 -5.44358564951100e-02 + 2.81537659173496e-02 -5.17226337871633e-02 + 2.56886770890630e-02 -4.90717427799052e-02 + 2.33482991143229e-02 -4.65080355566962e-02 + 2.11432730232991e-02 -4.40159414301263e-02 + 1.91121471256101e-02 -4.15606205415437e-02 + 1.72228999311958e-02 -3.91575871889248e-02 + 1.54064395993220e-02 -3.68520424585129e-02 + 1.36928020357784e-02 -3.46229069295389e-02 + 1.21373998162167e-02 -3.24269429373621e-02 + 1.07044618156111e-02 -3.02820978142858e-02 + 9.34868730826734e-03 -2.82170700487391e-02 + 8.09806623056062e-03 -2.62111289422148e-02 + 6.96372181943001e-03 -2.42506526569285e-02 + 5.96056834155680e-03 -2.23318948971137e-02 + 5.06965708895582e-03 -2.04584451649110e-02 + 4.26820207826318e-03 -1.86422076010040e-02 + 3.54215279838966e-03 -1.68853270402674e-02 + 2.85815863780286e-03 -1.51976459649791e-02 + 2.24323664486902e-03 -1.35681174800671e-02 + 1.75728174742475e-03 -1.19752101824980e-02 + 1.34793914004162e-03 -1.04318177524506e-02 + 9.90510266959983e-04 -8.94698512072236e-03 + 6.97578703019438e-04 -7.51579339168028e-03 + 4.64357280248315e-04 -6.13612031461294e-03 + 2.88591972559368e-04 -4.81032939412014e-03 + 1.72652071928442e-04 -3.53504260318557e-03 + 9.21726822772373e-05 -2.31236956248856e-03 + 2.89749158143047e-05 -1.14152595228739e-03 + 0.00000000000000e+00 0.00000000000000e+00 + 2.89846382908482e-05 1.09904377509191e-03 + 9.25460105131971e-05 2.26825426701565e-03 + 1.77372928637046e-04 3.48749114259613e-03 + 2.94928045666597e-04 4.75871421546040e-03 + 4.43018528169673e-04 6.08403094200768e-03 + 6.38312963887756e-04 7.46056696755252e-03 + 9.47163065524872e-04 8.87928204628239e-03 + 1.36292248354851e-03 1.03385546497900e-02 + 1.83694236418441e-03 1.18499779537360e-02 + 2.40074018468558e-03 1.34014033663973e-02 + 3.05594814662641e-03 1.49976678162017e-02 + 3.77032037989221e-03 1.66497807270228e-02 + 4.57488786576987e-03 1.83443029444178e-02 + 5.51906408703589e-03 2.00632619669774e-02 + 6.56072342496301e-03 2.18246212199481e-02 + 7.69623508636216e-03 2.36337857570079e-02 + 8.95571256166709e-03 2.54702712422116e-02 + 1.03262325097732e-02 2.73482935706184e-02 + 1.17850925399475e-02 2.92850723449938e-02 + 1.33375184491728e-02 3.12822963331383e-02 + 1.49920040237809e-02 3.33377667408644e-02 + 1.67963509381930e-02 3.54114606810732e-02 + 1.87564987080519e-02 3.75086023081501e-02 + 2.08048274019325e-02 3.96894126704762e-02 + 2.29716484700822e-02 4.19312226540401e-02 + 2.53216431358212e-02 4.41765315953156e-02 + 2.78298220840403e-02 4.64577629177545e-02 + 3.04725601623169e-02 4.88011066487437e-02 + 3.32695085116736e-02 5.11918075676120e-02 + 3.62304186897929e-02 5.36280031772383e-02 + 3.93644755511771e-02 5.61022315336534e-02 + 4.26868496705988e-02 5.86057232062309e-02 + 4.61876578605174e-02 6.11553846039597e-02 + 4.98741851089849e-02 6.37532547016415e-02 + 5.37745202719990e-02 6.63631960936247e-02 + 5.78890274684652e-02 6.90003260469755e-02 + 6.22045848623571e-02 7.16867591984326e-02 + 6.67395204425100e-02 7.44058004604966e-02 + 7.15094552811985e-02 7.71467339233253e-02 + 7.65211067667525e-02 7.99024876975873e-02 + 8.17838450454122e-02 8.26301768788084e-02 + 8.73028349577319e-02 8.53481713528125e-02 + 9.30858323711997e-02 8.80783750999101e-02 + 9.91416946670507e-02 9.08176986892974e-02 + 1.05480595351981e-01 9.35548293971554e-02 + 1.12106860649107e-01 9.62797051576990e-02 + 1.19024136382428e-01 9.90174394136982e-02 + 1.26260042330622e-01 1.01725417281737e-01 + 1.33816269566989e-01 1.04399273374098e-01 + 1.41700663462267e-01 1.07033756577881e-01 + 1.49922921245669e-01 1.09617507912382e-01 + 1.58490745848084e-01 1.12140288851728e-01 + 1.67427226610566e-01 1.14558206235614e-01 + 1.76710282027346e-01 1.16962741891360e-01 + 1.86363310666109e-01 1.19272582161213e-01 + 1.96405140293252e-01 1.21436031107907e-01 + 2.06821300548881e-01 1.23525479904894e-01 + 2.17631928576255e-01 1.25464812094116e-01 + 2.28852962522468e-01 1.27193749895941e-01 + 2.40477755282815e-01 1.28758039445176e-01 + 2.52507693678930e-01 1.30101102154715e-01 + 2.64955599100463e-01 1.31171639589549e-01 + 2.77806279246518e-01 1.32075007668201e-01 + 2.91070185192249e-01 1.32646573696457e-01 + 3.04740840328737e-01 1.33041903853136e-01 + 3.18819477395129e-01 1.33195283275007e-01 + 3.33304350362167e-01 1.32986169941820e-01 + 3.48197166977535e-01 1.32632958624357e-01 + 3.63493940108890e-01 1.32044025079949e-01 + 3.79191584895447e-01 1.31162317872549e-01 + 3.95288926848852e-01 1.30062172860921e-01 + 4.11778548872039e-01 1.28686018034213e-01 + 4.28672318266481e-01 1.27234783277367e-01 + 4.45941423639317e-01 1.25432754513171e-01 + 4.63601280756515e-01 1.23542253443373e-01 + 4.81644473880432e-01 1.21300435261224e-01 + 5.00056154441041e-01 1.18664422872359e-01 + 5.18836063389421e-01 1.15815814392759e-01 + 5.37969499408613e-01 1.12707530577688e-01 + 5.57460349222905e-01 1.09422776572642e-01 + 5.77288515939648e-01 1.05906885195990e-01 + 5.97436626517306e-01 1.02120358117792e-01 + 6.17906665003925e-01 9.81468229100023e-02 + 6.38686205928774e-01 9.39865902403502e-02 + 6.59766571546815e-01 8.96723879840407e-02 + 6.81119084918578e-01 8.51320545501444e-02 + 7.02741779443877e-01 8.04384800208977e-02 + 7.24615479257981e-01 7.55830551158126e-02 + 7.46734371501449e-01 7.06203776437117e-02 + 7.69068303705288e-01 6.55004145708381e-02 + 7.91594648342087e-01 6.02131883818753e-02 + 8.14301397875068e-01 5.47976161070736e-02 + 8.37189869304468e-01 4.93502115779818e-02 + 8.60223965891098e-01 4.38110631161306e-02 + 8.83371421758982e-01 3.81398145030035e-02 + 9.06633371381850e-01 3.24408481950457e-02 + 9.29989733000046e-01 2.67257978266275e-02 + 9.53387742290786e-01 2.07144753192261e-02 + 9.76768638918538e-01 1.45035303709754e-02 + 1.00000000000000e+00 8.08144847432573e-03 diff --git a/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF17_Coords.txt b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF17_Coords.txt new file mode 100644 index 00000000..e8398cd3 --- /dev/null +++ b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF17_Coords.txt @@ -0,0 +1,208 @@ + 201 NumCoords ! The number of coordinates in the airfoil shape file (including an extra coordinate for airfoil reference). Set to zero if coordinates not included. +! ......... x-y coordinates are next if NumCoords > 0 ............. +! x-y coordinate of airfoil reference +! x/c y/c + 0.250000 0 +! coordinates of airfoil shape +! interpolation to 200 points +! x/c y/c + 1.00000000000000e+00 -5.45301418050398e-03 + 9.75817754636844e-01 -1.07014594571340e-03 + 9.51454474857096e-01 1.91024365189180e-03 + 9.26967643090702e-01 3.00968706555777e-03 + 9.02511079251701e-01 2.94654327425755e-03 + 8.78192574605997e-01 1.33458056758987e-03 + 8.54093368263713e-01 -1.40182384869508e-03 + 8.30280803054358e-01 -5.36722915654211e-03 + 8.06793858998891e-01 -1.02284409757101e-02 + 7.83681486977920e-01 -1.59512159380425e-02 + 7.60940204843493e-01 -2.22950822168370e-02 + 7.38563657479683e-01 -2.90867632401626e-02 + 7.16562339357988e-01 -3.62524846703740e-02 + 6.94907137649732e-01 -4.36064241543176e-02 + 6.73631134029173e-01 -5.11811692579687e-02 + 6.52658302378040e-01 -5.86920124341470e-02 + 6.32053668313489e-01 -6.62866061150648e-02 + 6.11762998595842e-01 -7.37633434906679e-02 + 5.91793833227140e-01 -8.11048412074493e-02 + 5.72143812615339e-01 -8.82708930236720e-02 + 5.52817394328116e-01 -9.52421061177968e-02 + 5.33788045856372e-01 -1.01905267173908e-01 + 5.15086541349180e-01 -1.08323876177549e-01 + 4.96717352144744e-01 -1.14481204108679e-01 + 4.78641616276281e-01 -1.20227783933246e-01 + 4.60893396881899e-01 -1.25639100003988e-01 + 4.43463621570381e-01 -1.30651726403441e-01 + 4.26364855167011e-01 -1.35291421458868e-01 + 4.09575905165181e-01 -1.39432097972120e-01 + 3.93110179140291e-01 -1.43077401925812e-01 + 3.76978460385483e-01 -1.46251273376598e-01 + 3.61179752938969e-01 -1.48871519397112e-01 + 3.45729101934949e-01 -1.50960869674387e-01 + 3.30642129005544e-01 -1.52550649026425e-01 + 3.15926278476078e-01 -1.53556648571138e-01 + 3.01599265716078e-01 -1.53406493492377e-01 + 2.87680819991451e-01 -1.52565505829207e-01 + 2.74185684558165e-01 -1.51262467818296e-01 + 2.61125227450442e-01 -1.49553952675144e-01 + 2.48509753994654e-01 -1.47518928364719e-01 + 2.36337378313774e-01 -1.45239165168132e-01 + 2.24609516585392e-01 -1.42744892161473e-01 + 2.13332897224055e-01 -1.40016001929494e-01 + 2.02471916601662e-01 -1.37246042052315e-01 + 1.92046415499529e-01 -1.34302336350696e-01 + 1.82017241046991e-01 -1.31316990852076e-01 + 1.72387811926573e-01 -1.28277098407418e-01 + 1.63158168703259e-01 -1.25175025059640e-01 + 1.54311116670428e-01 -1.22008726981644e-01 + 1.45810745366912e-01 -1.18882519862654e-01 + 1.37686151480707e-01 -1.15678943069290e-01 + 1.29904396960524e-01 -1.12501052056401e-01 + 1.22461453799045e-01 -1.09296875694661e-01 + 1.15336029025638e-01 -1.06110381969955e-01 + 1.08530206086421e-01 -1.02923068284723e-01 + 1.02021937517086e-01 -9.97477261452737e-02 + 9.58035794795516e-02 -9.66087731597880e-02 + 8.99025563208008e-02 -9.34345462961179e-02 + 8.42533694191495e-02 -9.03001520357529e-02 + 7.88404210406804e-02 -8.72478321301334e-02 + 7.36987958956943e-02 -8.41967679007426e-02 + 6.87979160132652e-02 -8.11907184984598e-02 + 6.41293950735861e-02 -7.82219427896279e-02 + 5.97053948052580e-02 -7.52557475365361e-02 + 5.54927030145125e-02 -7.23200756561499e-02 + 5.14882701745751e-02 -6.94055630007988e-02 + 4.76966523729130e-02 -6.65204388093482e-02 + 4.41044276154980e-02 -6.36813418052842e-02 + 4.06917094514561e-02 -6.09068675236080e-02 + 3.74540490762733e-02 -5.81886656057259e-02 + 3.43866063044132e-02 -5.55275845558965e-02 + 3.15023235573427e-02 -5.29049733067924e-02 + 2.87869138658892e-02 -5.03247145633268e-02 + 2.62138854996644e-02 -4.78100517604238e-02 + 2.37865060486491e-02 -4.53531589485433e-02 + 2.15247839409282e-02 -4.29352820557746e-02 + 1.94182671926051e-02 -4.05554813845574e-02 + 1.73965234398919e-02 -3.82405266496950e-02 + 1.54853588645235e-02 -3.59936663761455e-02 + 1.37247140912916e-02 -3.37853520929274e-02 + 1.21016771194090e-02 -3.16194081025936e-02 + 1.05781206388565e-02 -2.95197185049363e-02 + 9.16563324054632e-03 -2.74753790222862e-02 + 7.87017740303867e-03 -2.54771064952531e-02 + 6.73874368242485e-03 -2.35033804471445e-02 + 5.69708622898664e-03 -2.15868085403806e-02 + 4.77713369380707e-03 -1.97111181309851e-02 + 3.95637742176391e-03 -1.78845743446675e-02 + 3.18867965744800e-03 -1.61229116929551e-02 + 2.51755355177319e-03 -1.44093804163539e-02 + 1.97561081401136e-03 -1.27330821562174e-02 + 1.50680513040740e-03 -1.11084517063373e-02 + 1.11087123697807e-03 -9.53891013699422e-03 + 7.87187928013208e-04 -8.02095919047579e-03 + 5.40440313749341e-04 -6.55353655736207e-03 + 3.24451588791395e-04 -5.14486804718090e-03 + 1.88916042874488e-04 -3.78501062412031e-03 + 9.46340362822307e-05 -2.47910069070381e-03 + 2.95523038007147e-05 -1.22605370486567e-03 + 0.00000000000000e+00 0.00000000000000e+00 + 3.01481344622130e-05 1.17505317893727e-03 + 9.71702652511514e-05 2.42646619372459e-03 + 2.03793338171215e-04 3.72885439165868e-03 + 3.50357301196391e-04 5.08422545353897e-03 + 5.56726492329121e-04 6.49032410794411e-03 + 8.10159355539692e-04 7.94834859081885e-03 + 1.16155592002565e-03 9.45472898904353e-03 + 1.67637488199947e-03 1.09790644306452e-02 + 2.24350076193863e-03 1.25604990644086e-02 + 2.93581026563085e-03 1.41655243002384e-02 + 3.71628942355257e-03 1.58152478828471e-02 + 4.58474262640831e-03 1.75044149307111e-02 + 5.55488305863393e-03 1.92276009432552e-02 + 6.64802371618967e-03 2.09824655006495e-02 + 7.84988650655681e-03 2.27705789972541e-02 + 9.14426750365521e-03 2.46074952599354e-02 + 1.05699641486623e-02 2.64638140414759e-02 + 1.21156298219846e-02 2.83517697847890e-02 + 1.37576162529760e-02 3.02925689186482e-02 + 1.54895733386299e-02 3.22984799032679e-02 + 1.73435567726879e-02 3.43421258897796e-02 + 1.93455202749544e-02 3.64041907098984e-02 + 2.15005396192731e-02 3.84872450496868e-02 + 2.37609732142698e-02 4.06370705630654e-02 + 2.61438022753388e-02 4.28440907355414e-02 + 2.86976791253163e-02 4.50652887339507e-02 + 3.14081825116334e-02 4.73218530627499e-02 + 3.42618133903517e-02 4.96294249787890e-02 + 3.72752122579656e-02 5.19754897747939e-02 + 4.04579457665667e-02 5.43568206182997e-02 + 4.38096061596044e-02 5.67814925288692e-02 + 4.73527794655686e-02 5.92252949852968e-02 + 5.10805893305958e-02 6.17034102753216e-02 + 5.49951734742978e-02 6.42246281779437e-02 + 5.91172562090566e-02 6.67651820406855e-02 + 6.34412452148952e-02 6.93500711466022e-02 + 6.79840941864798e-02 7.19471001376835e-02 + 7.27468469458395e-02 7.45705996505986e-02 + 7.77328868720285e-02 7.72333440704537e-02 + 8.29626933019556e-02 7.98998610400721e-02 + 8.84438437146468e-02 8.25516267432993e-02 + 9.41776411888755e-02 8.52039636550780e-02 + 1.00170421380160e-01 8.78676504969935e-02 + 1.06430934474038e-01 9.05393436776120e-02 + 1.12969233548496e-01 9.32086710673799e-02 + 1.19797828219200e-01 9.58462247530667e-02 + 1.26911894255357e-01 9.84958150865328e-02 + 1.34331983632213e-01 1.01128226770770e-01 + 1.42066987117710e-01 1.03723117625941e-01 + 1.50124262102595e-01 1.06274763475707e-01 + 1.58513048529723e-01 1.08770852235264e-01 + 1.67241646522678e-01 1.11196896421823e-01 + 1.76323718493828e-01 1.13540445285679e-01 + 1.85743681389525e-01 1.15873278276396e-01 + 1.95524016824630e-01 1.18115770052045e-01 + 2.05683255342811e-01 1.20208699038275e-01 + 2.16208468120044e-01 1.22224461173209e-01 + 2.27117207800504e-01 1.24090288616604e-01 + 2.38419423158324e-01 1.25782649954125e-01 + 2.50110734150605e-01 1.27336011108803e-01 + 2.62197488700551e-01 1.28669969942400e-01 + 2.74686682065653e-01 1.29764427838693e-01 + 2.87569054903857e-01 1.30681368424973e-01 + 3.00852399367078e-01 1.31283757276969e-01 + 3.14530771437150e-01 1.31692707165930e-01 + 3.28604824690067e-01 1.31851460992892e-01 + 3.43071468150563e-01 1.31640913718290e-01 + 3.57931242815408e-01 1.31256435294713e-01 + 3.73178779264493e-01 1.30614578750586e-01 + 3.88811577543217e-01 1.29697152615801e-01 + 4.04827176697756e-01 1.28553939360805e-01 + 4.21218824620110e-01 1.27145088813715e-01 + 4.37996175755373e-01 1.25658971878768e-01 + 4.55132979373076e-01 1.23843182272296e-01 + 4.72638679585242e-01 1.21926903878881e-01 + 4.90509890590074e-01 1.19631762561332e-01 + 5.08733867924661e-01 1.16939647488128e-01 + 5.27305087603049e-01 1.14015126381095e-01 + 5.46213184288326e-01 1.10843992328087e-01 + 5.65460187911138e-01 1.07498826395060e-01 + 5.85029675577305e-01 1.03944942811554e-01 + 6.04902749493555e-01 1.00126044902967e-01 + 6.25076084848418e-01 9.60954974978452e-02 + 6.45543971739222e-01 9.18933165314899e-02 + 6.66297289512585e-01 8.75484886184110e-02 + 6.87308946494649e-01 8.29877474141992e-02 + 7.08578048914644e-01 7.82894566836472e-02 + 7.30086443256557e-01 7.34459663833689e-02 + 7.51825357054199e-01 6.84945162374382e-02 + 7.73769138587997e-01 6.34023849460844e-02 + 7.95897100069124e-01 5.81625974308282e-02 + 8.18195637696294e-01 5.28018830946166e-02 + 8.40659948231990e-01 4.73841857178122e-02 + 8.63266034014869e-01 4.19041191703725e-02 + 8.85979573720097e-01 3.62991883120328e-02 + 9.08802830149653e-01 3.06806974342369e-02 + 9.31707972602122e-01 2.50135348041367e-02 + 9.54654320230810e-01 1.88471626322655e-02 + 9.77590603702380e-01 1.23214474808323e-02 + 1.00000000000000e+00 5.52162384629112e-03 diff --git a/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF18_Coords.txt b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF18_Coords.txt new file mode 100644 index 00000000..87813ee7 --- /dev/null +++ b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF18_Coords.txt @@ -0,0 +1,208 @@ + 201 NumCoords ! The number of coordinates in the airfoil shape file (including an extra coordinate for airfoil reference). Set to zero if coordinates not included. +! ......... x-y coordinates are next if NumCoords > 0 ............. +! x-y coordinate of airfoil reference +! x/c y/c + 0.250000 0 +! coordinates of airfoil shape +! interpolation to 200 points +! x/c y/c + 1.00000000000000e+00 -2.37767599414968e-03 + 9.76446819562239e-01 1.18667276573974e-03 + 9.52930798636692e-01 3.80478847156908e-03 + 9.29282208028914e-01 5.37628501132393e-03 + 9.05615578666939e-01 6.07272680933467e-03 + 8.82032334216335e-01 5.18874855240369e-03 + 8.58617284514100e-01 3.26660678111755e-03 + 8.35440764035589e-01 2.67187094232616e-05 + 8.12556593166433e-01 -4.15650599841566e-03 + 7.90017464961696e-01 -9.25945431510779e-03 + 7.67840842437519e-01 -1.50885188225015e-02 + 7.46027726392422e-01 -2.14593261524176e-02 + 7.24592442618031e-01 -2.82974871754426e-02 + 7.03504149817637e-01 -3.53964569024539e-02 + 6.82765349116846e-01 -4.26998988823194e-02 + 6.62337893926518e-01 -5.00271216489902e-02 + 6.42248092575011e-01 -5.74239730292741e-02 + 6.22460538916900e-01 -6.47395984745764e-02 + 6.02953903187687e-01 -7.18789103015881e-02 + 5.83732605013996e-01 -7.88228152136706e-02 + 5.64800704679662e-01 -8.55519158464723e-02 + 5.46124988243235e-01 -9.19284463008494e-02 + 5.27742247208307e-01 -9.80364414989111e-02 + 5.09652486976343e-01 -1.03841306232240e-01 + 4.91835492986616e-01 -1.09243363075515e-01 + 4.74308759446067e-01 -1.14261681915081e-01 + 4.57077435404333e-01 -1.18870892627075e-01 + 4.40154051473917e-01 -1.23098817274973e-01 + 4.23530856843343e-01 -1.26854027870635e-01 + 4.07216398081170e-01 -1.30119328171116e-01 + 3.91231938614656e-01 -1.32976005720577e-01 + 3.75575699731328e-01 -1.35342726415398e-01 + 3.60263622208770e-01 -1.37261172568907e-01 + 3.45308062067250e-01 -1.38788502251440e-01 + 3.30710985565161e-01 -1.39841337156737e-01 + 3.16484027641533e-01 -1.40100625734666e-01 + 3.02640076917013e-01 -1.39862266369132e-01 + 2.89186583012941e-01 -1.39252768782004e-01 + 2.76130340586499e-01 -1.38286107582322e-01 + 2.63476265682543e-01 -1.37049216008764e-01 + 2.51223094661652e-01 -1.35572490644241e-01 + 2.39372261720154e-01 -1.33875529784685e-01 + 2.27927524364597e-01 -1.31931209492906e-01 + 2.16866171615739e-01 -1.29910205264487e-01 + 2.06201029914413e-01 -1.27692002391941e-01 + 1.95913212312204e-01 -1.25358568326782e-01 + 1.85997306093273e-01 -1.22934748923442e-01 + 1.76450637821784e-01 -1.20426052562665e-01 + 1.67269721120968e-01 -1.17795029832047e-01 + 1.58423588488400e-01 -1.15164333199127e-01 + 1.49936911969762e-01 -1.12408754691065e-01 + 1.41769123119841e-01 -1.09669875291307e-01 + 1.33937151744594e-01 -1.06851502319845e-01 + 1.26416097012572e-01 -1.04016679034228e-01 + 1.19206237571905e-01 -1.01151657303313e-01 + 1.12297037125044e-01 -9.82587192113124e-02 + 1.05667160617742e-01 -9.53856625792421e-02 + 9.93435270819619e-02 -9.24557770413018e-02 + 9.32891373053101e-02 -8.95249953967126e-02 + 8.74719354214747e-02 -8.66600851213458e-02 + 8.19240576596432e-02 -8.37764095161515e-02 + 7.66140873543626e-02 -8.09233249988340e-02 + 7.15426883354032e-02 -7.80879536266522e-02 + 6.67258789024077e-02 -7.52313564677441e-02 + 6.21109049974624e-02 -7.24930414546405e-02 + 5.77107003282204e-02 -6.98465745441758e-02 + 5.35430034534783e-02 -6.71846452282005e-02 + 4.95845561568290e-02 -6.45422361158792e-02 + 4.58099226060605e-02 -6.19523763970443e-02 + 4.22293604618921e-02 -5.93855665933846e-02 + 3.88308843695516e-02 -5.68544053787320e-02 + 3.56234006217278e-02 -5.43433098462299e-02 + 3.25999205074709e-02 -5.18499783811972e-02 + 2.97405688058144e-02 -4.93956746514801e-02 + 2.70395385980955e-02 -4.69821041730334e-02 + 2.44940212404595e-02 -4.46103096861655e-02 + 2.21201103864747e-02 -4.22591015257432e-02 + 1.98580479062668e-02 -3.99325658782353e-02 + 1.77168686887470e-02 -3.76638917235478e-02 + 1.57157807032474e-02 -3.54403779106754e-02 + 1.38676651671849e-02 -3.32484674991874e-02 + 1.21441938253155e-02 -3.11061195104619e-02 + 1.05378361076491e-02 -2.90145230640159e-02 + 9.04844929893957e-03 -2.69697346212576e-02 + 7.75683497330708e-03 -2.49283589829342e-02 + 6.52980280782892e-03 -2.29587165235158e-02 + 5.45989916249106e-03 -2.10098573697542e-02 + 4.51688987743758e-03 -1.90975789024075e-02 + 3.64156821001467e-03 -1.72448669660278e-02 + 2.89517955356030e-03 -1.54279532736546e-02 + 2.27709187814676e-03 -1.36490255771574e-02 + 1.72915425508911e-03 -1.19244153221547e-02 + 1.27964769399565e-03 -1.02506222817353e-02 + 9.12717177077437e-04 -8.62589658032073e-03 + 6.43670432858475e-04 -7.05048038051019e-03 + 3.75496964177492e-04 -5.53981424307094e-03 + 2.12451593354277e-04 -4.07587556179559e-03 + 9.85747212878459e-05 -2.66752580611053e-03 + 3.05204163981267e-05 -1.31331094969237e-03 + 0.00000000000000e+00 0.00000000000000e+00 + 3.15800516939920e-05 1.28536935659477e-03 + 1.02861345468154e-04 2.63794919245206e-03 + 2.36308992810849e-04 4.04267190102204e-03 + 4.18574204776478e-04 5.50160407333578e-03 + 6.96667127526426e-04 7.00712121949262e-03 + 1.02165107805804e-03 8.56543372145463e-03 + 1.42540966556040e-03 1.01797040162715e-02 + 2.06214142058454e-03 1.17841124321626e-02 + 2.74385305341704e-03 1.34517101595850e-02 + 3.59432216104703e-03 1.51227008126668e-02 + 4.52897284835177e-03 1.68382166645950e-02 + 5.58705383071816e-03 1.85729863183344e-02 + 6.76096524288088e-03 2.03314489250025e-02 + 8.03743675144860e-03 2.21305025010730e-02 + 9.43646227409209e-03 2.39515425026592e-02 + 1.09263641031346e-02 2.58226128735423e-02 + 1.25566270365459e-02 2.77033405353925e-02 + 1.43178449292754e-02 2.96035213537207e-02 + 1.61852054142408e-02 3.15492683526132e-02 + 1.81381119035080e-02 3.35658704424136e-02 + 2.02376177807679e-02 3.55949640883938e-02 + 2.24827884412515e-02 3.76427169254937e-02 + 2.48776366499191e-02 3.97084340106233e-02 + 2.73991082013164e-02 4.18201264039935e-02 + 3.00477787622335e-02 4.39843306813997e-02 + 3.28525738533268e-02 4.61758552907474e-02 + 3.58120783592458e-02 4.84020618976064e-02 + 3.89252554594669e-02 5.06656093643179e-02 + 4.22050404438107e-02 5.29567403882480e-02 + 4.56607724006619e-02 5.52705490464994e-02 + 4.92802379264876e-02 5.76342317329541e-02 + 5.30951492645608e-02 6.00045745431363e-02 + 5.71023305776689e-02 6.23946378850674e-02 + 6.12975848311221e-02 6.48215197669438e-02 + 6.56925727776909e-02 6.72766782487322e-02 + 7.02743714952992e-02 6.97972744317459e-02 + 7.50969486986961e-02 7.22842735310359e-02 + 8.01400765487782e-02 7.47901896085021e-02 + 8.53920774693246e-02 7.73567066055900e-02 + 9.08903676568554e-02 7.99133996484751e-02 + 9.66403183510142e-02 8.24936560307861e-02 + 1.02638479952074e-01 8.50997650283062e-02 + 1.08889440257636e-01 8.77162219327400e-02 + 1.15401817527268e-01 9.03394906080130e-02 + 1.22185516627081e-01 9.29598512750285e-02 + 1.29263118491494e-01 9.55337809970597e-02 + 1.36619374775123e-01 9.81184385458023e-02 + 1.44266139092389e-01 1.00694502173312e-01 + 1.52221162890854e-01 1.03229848289691e-01 + 1.60491203003249e-01 1.05718276956696e-01 + 1.69084936589124e-01 1.08146601356303e-01 + 1.78011398738398e-01 1.10496847084347e-01 + 1.87272650122097e-01 1.12780737463291e-01 + 1.96861105345526e-01 1.15054643125002e-01 + 2.06798117527740e-01 1.17240543617190e-01 + 2.17101851419760e-01 1.19273158884218e-01 + 2.27761275369060e-01 1.21224134069861e-01 + 2.38790761271252e-01 1.23023413411139e-01 + 2.50192886766329e-01 1.24678047176873e-01 + 2.61966061889217e-01 1.26213824812832e-01 + 2.74122740201456e-01 1.27530811823120e-01 + 2.86662746727198e-01 1.28636005140460e-01 + 2.99584123829558e-01 1.29553120390120e-01 + 3.12891391317914e-01 1.30171094917509e-01 + 3.26579260634688e-01 1.30578353143042e-01 + 3.40647672578538e-01 1.30725411590738e-01 + 3.55091880946261e-01 1.30496104164832e-01 + 3.69910990811779e-01 1.30058415062081e-01 + 3.85097931570468e-01 1.29333718130797e-01 + 4.00650923113019e-01 1.28339370562823e-01 + 4.16565921229797e-01 1.27096432683427e-01 + 4.32836992216272e-01 1.25581769969023e-01 + 4.49471067150447e-01 1.23948898925125e-01 + 4.66445046714551e-01 1.21982635824263e-01 + 4.83761025693294e-01 1.19827800217627e-01 + 5.01420577935565e-01 1.17377223728947e-01 + 5.19413548507589e-01 1.14623284584942e-01 + 5.37727933854121e-01 1.11613572571558e-01 + 5.56358704938187e-01 1.08373804583437e-01 + 5.75305606530518e-01 1.04960916116859e-01 + 5.94556737334723e-01 1.01364726003763e-01 + 6.14091323042302e-01 9.75131887392979e-02 + 6.33899505217000e-01 9.34229607669790e-02 + 6.53983838820148e-01 8.91779646388802e-02 + 6.74334658110115e-01 8.48016108581404e-02 + 6.94926822402831e-01 8.02237288972718e-02 + 7.15760758260989e-01 7.55262386365138e-02 + 7.36819570375329e-01 7.07027052448581e-02 + 7.58090843885297e-01 6.57693336437398e-02 + 7.79554466153280e-01 6.07141783168916e-02 + 8.01192136630880e-01 5.55343914786427e-02 + 8.22988286990664e-01 5.02420511779286e-02 + 8.44930581805388e-01 4.48622679286764e-02 + 8.67009913774751e-01 3.94519467741740e-02 + 8.89189431928600e-01 3.39266635119004e-02 + 9.11472787704912e-01 2.84011627846064e-02 + 9.33822613763039e-01 2.27894520303026e-02 + 9.56213100416208e-01 1.64551756972167e-02 + 9.78602197523542e-01 9.57262213328838e-03 + 1.00000000000000e+00 2.38801343162379e-03 diff --git a/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF19_Coords.txt b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF19_Coords.txt new file mode 100644 index 00000000..ffdbb0d3 --- /dev/null +++ b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF19_Coords.txt @@ -0,0 +1,208 @@ + 201 NumCoords ! The number of coordinates in the airfoil shape file (including an extra coordinate for airfoil reference). Set to zero if coordinates not included. +! ......... x-y coordinates are next if NumCoords > 0 ............. +! x-y coordinate of airfoil reference +! x/c y/c + 0.250000 0 +! coordinates of airfoil shape +! interpolation to 200 points +! x/c y/c + 1.00000000000000e+00 -3.68399389995869e-04 + 9.76857008771838e-01 2.66731162732446e-03 + 9.53893452982560e-01 5.08228579069216e-03 + 9.30791447416205e-01 6.92341917618193e-03 + 9.07639904153749e-01 8.15655615709104e-03 + 8.84536094791801e-01 7.92264904224889e-03 + 8.61567157501965e-01 6.68493011849853e-03 + 8.38805377497580e-01 4.13452337383163e-03 + 8.16314251999226e-01 5.97915678772836e-04 + 7.94148914190988e-01 -3.89604633156816e-03 + 7.72340484630481e-01 -9.19436001700492e-03 + 7.50894760627057e-01 -1.51087969475548e-02 + 7.29828566229855e-01 -2.15579885729289e-02 + 7.09109933074187e-01 -2.83298125964794e-02 + 6.88721421877958e-01 -3.53036886233563e-02 + 6.68649585846097e-01 -4.23737071775973e-02 + 6.48895487241817e-01 -4.95075181376893e-02 + 6.29435996348719e-01 -5.65920614554448e-02 + 6.10230958530276e-01 -6.34793436033746e-02 + 5.91289213882662e-01 -7.01620809295741e-02 + 5.72614563636092e-01 -7.66179006666135e-02 + 5.54169437142293e-01 -8.26972170912674e-02 + 5.35994549591891e-01 -8.84922462055237e-02 + 5.18086994319589e-01 -9.39558134124888e-02 + 5.00438716025881e-01 -9.90271375426639e-02 + 4.83056404950572e-01 -1.03683276789266e-01 + 4.65954483401666e-01 -1.07928967059445e-01 + 4.49145459682817e-01 -1.11790741247148e-01 + 4.32630347798518e-01 -1.15206880360019e-01 + 4.16414524640443e-01 -1.18147531896552e-01 + 4.00526087330994e-01 -1.20731141532653e-01 + 3.84962746755882e-01 -1.22881481336833e-01 + 3.69741027707524e-01 -1.24652317902417e-01 + 3.54871156825438e-01 -1.26116996793257e-01 + 3.40351528329817e-01 -1.27196549851457e-01 + 3.26189812343215e-01 -1.27831505011485e-01 + 3.12394436962796e-01 -1.28135125466097e-01 + 2.98968095909353e-01 -1.28135971204913e-01 + 2.85914601715587e-01 -1.27815225606007e-01 + 2.73235356281731e-01 -1.27263263044964e-01 + 2.60929501705741e-01 -1.26470643765030e-01 + 2.48998483933274e-01 -1.25450275622875e-01 + 2.37444123255251e-01 -1.24173437692176e-01 + 2.26252115496294e-01 -1.22785796310441e-01 + 2.15430713313732e-01 -1.21185221143952e-01 + 2.04974244392958e-01 -1.19412349992892e-01 + 1.94871537400587e-01 -1.17520737121037e-01 + 1.85118149204518e-01 -1.15527561249974e-01 + 1.75719532106264e-01 -1.13369650618129e-01 + 1.66647941717989e-01 -1.11180617405335e-01 + 1.57925164945130e-01 -1.08833224985739e-01 + 1.49505657854053e-01 -1.06498338398972e-01 + 1.41420016040231e-01 -1.04044619127328e-01 + 1.33640986123984e-01 -1.01549904565748e-01 + 1.26167669913614e-01 -9.90049839819346e-02 + 1.18997037103723e-01 -9.64015758401574e-02 + 1.12098825120963e-01 -9.38093390294696e-02 + 1.05499623500676e-01 -9.11479135507931e-02 + 9.91810164066800e-02 -8.84508376192239e-02 + 9.31002162531755e-02 -8.58102997394773e-02 + 8.72874366774390e-02 -8.31377449587737e-02 + 8.17107141333520e-02 -8.04892138256785e-02 + 7.63766137075373e-02 -7.78449994839546e-02 + 7.13036684223055e-02 -7.51579825759147e-02 + 6.64263817165701e-02 -7.26018598042667e-02 + 6.17681093546461e-02 -7.01301752855594e-02 + 5.73551856813564e-02 -6.76137828225569e-02 + 5.31579386553926e-02 -6.50996263715978e-02 + 4.91473139049403e-02 -6.26301467575107e-02 + 4.53431586149581e-02 -6.01620539688450e-02 + 4.17288283387378e-02 -5.77156085161925e-02 + 3.83105975635588e-02 -5.52772281229456e-02 + 3.50862364938885e-02 -5.28405786158374e-02 + 3.20401842818251e-02 -5.04256327322228e-02 + 2.91607168682362e-02 -4.80403110926350e-02 + 2.64301474681941e-02 -4.56985651824556e-02 + 2.38818791314998e-02 -4.33660011061808e-02 + 2.14869187314351e-02 -4.10319139878904e-02 + 1.92210251217201e-02 -3.87490158345328e-02 + 1.70866204440822e-02 -3.65155909889459e-02 + 1.51088856667703e-02 -3.43067488660566e-02 + 1.32677571342121e-02 -3.21365849699287e-02 + 1.15452964783661e-02 -3.00141740624550e-02 + 9.93785550135011e-03 -2.79390543678102e-02 + 8.53733963199581e-03 -2.58535670157040e-02 + 7.18971942545551e-03 -2.38493192760235e-02 + 6.01408812501931e-03 -2.18527495788709e-02 + 4.98035831239796e-03 -1.98845668008135e-02 + 4.02595523871816e-03 -1.79724851036912e-02 + 3.21872354864114e-03 -1.60881596868680e-02 + 2.53699895316356e-03 -1.42423112550335e-02 + 1.92596838800982e-03 -1.24525079880165e-02 + 1.42958340648342e-03 -1.07107365453782e-02 + 1.02402066973875e-03 -9.01638710474725e-03 + 7.29515457680132e-04 -7.37055242509973e-03 + 4.22134415351005e-04 -5.79337753090592e-03 + 2.34596295265449e-04 -4.26157143671717e-03 + 1.02904903665998e-04 -2.78642458580164e-03 + 3.16491042877115e-05 -1.36624202526467e-03 + 0.00000000000000e+00 0.00000000000000e+00 + 3.25137502262144e-05 1.36126836315680e-03 + 1.06572281496749e-04 2.77981521878749e-03 + 2.57511209208200e-04 4.25126635289481e-03 + 4.63055841935316e-04 5.77772676962173e-03 + 7.87917070457592e-04 7.34807091678409e-03 + 1.15955675201046e-03 8.97177740531396e-03 + 1.59745861466139e-03 1.06563985806526e-02 + 2.31368504535807e-03 1.23130195245482e-02 + 3.07011367084607e-03 1.40368009141934e-02 + 4.02371261501702e-03 1.57508050961990e-02 + 5.05889266777718e-03 1.75092215738978e-02 + 6.24062268199277e-03 1.92737269450562e-02 + 7.54740536677814e-03 2.10551920713005e-02 + 8.94341992064346e-03 2.28830596185717e-02 + 1.04710077300238e-02 2.47255697363701e-02 + 1.20884012253117e-02 2.66189106966348e-02 + 1.38520540216189e-02 2.85155544569944e-02 + 1.57538252832241e-02 3.04237067797815e-02 + 1.77681435802238e-02 3.23726800924697e-02 + 1.98651227360326e-02 3.43962534435927e-02 + 2.21247244203388e-02 3.64158580641648e-02 + 2.45284811789666e-02 3.84542786038096e-02 + 2.70797126293869e-02 4.05086907274035e-02 + 2.97713970613449e-02 4.25955179697784e-02 + 3.25934127100249e-02 4.47318036374387e-02 + 3.55618220018821e-02 4.69039793632072e-02 + 3.86836906268538e-02 4.91103908591560e-02 + 4.19661079042882e-02 5.13452316640530e-02 + 4.54195931002610e-02 5.36005424735060e-02 + 4.90533369175556e-02 5.58703224938828e-02 + 5.28474279411799e-02 5.81942364368840e-02 + 5.68395292704747e-02 6.05166790176710e-02 + 6.10288780337881e-02 6.28493270475509e-02 + 6.54071465451169e-02 6.52146960136306e-02 + 6.99800855562079e-02 6.76141714293276e-02 + 7.47299921393616e-02 7.00928446530985e-02 + 7.97349694380070e-02 7.25080974627385e-02 + 8.49609191753247e-02 7.49373418732565e-02 + 9.03863431014392e-02 7.74411126435351e-02 + 9.60597012920897e-02 7.99261936987175e-02 + 1.01984926382490e-01 8.24310363129346e-02 + 1.08155469732798e-01 8.49653756451838e-02 + 1.14574779429234e-01 8.75131666717048e-02 + 1.21251387707475e-01 9.00699473431387e-02 + 1.28195102790333e-01 9.26263962880819e-02 + 1.35435072734491e-01 9.51218497619305e-02 + 1.42949252027610e-01 9.76304862957753e-02 + 1.50743822415266e-01 1.00143225443294e-01 + 1.58842313055751e-01 1.02614343572487e-01 + 1.67251089180853e-01 1.05037311736569e-01 + 1.75978460980627e-01 1.07398386544002e-01 + 1.85033942788463e-01 1.09676903953931e-01 + 1.94412030223010e-01 1.11906753065792e-01 + 2.04110352857490e-01 1.14127897662318e-01 + 2.14149527961947e-01 1.16265117747636e-01 + 2.24547481767990e-01 1.18248683868967e-01 + 2.35294419696161e-01 1.20148148534840e-01 + 2.46402639597428e-01 1.21897385397864e-01 + 2.57869912676765e-01 1.23526834665610e-01 + 2.69696468272276e-01 1.25053947368743e-01 + 2.81898741199044e-01 1.26364975026619e-01 + 2.94471881045941e-01 1.27487690783284e-01 + 3.07418691339119e-01 1.28414307575311e-01 + 3.20741558118385e-01 1.29056641751163e-01 + 3.34435620226968e-01 1.29474248027250e-01 + 3.48500353688656e-01 1.29624393334326e-01 + 3.62929932989329e-01 1.29396296126059e-01 + 3.77722526892471e-01 1.28930828553253e-01 + 3.92869955516012e-01 1.28156113952553e-01 + 4.08370908134265e-01 1.27114694902152e-01 + 4.24220308156953e-01 1.25806236875891e-01 + 4.40412755529192e-01 1.24220713149001e-01 + 4.56953405525328e-01 1.22475796836960e-01 + 4.73821213743432e-01 1.20395388434913e-01 + 4.91013482752600e-01 1.18050411789495e-01 + 5.08535020400488e-01 1.15490643648704e-01 + 5.26377360286358e-01 1.12710340482628e-01 + 5.44524273775329e-01 1.09660985096774e-01 + 5.62974211427790e-01 1.06393299108221e-01 + 5.81725427948974e-01 1.02949051041186e-01 + 6.00768970403698e-01 9.93338710397741e-02 + 6.20082840879561e-01 9.54749572480719e-02 + 6.39652920613148e-01 9.13660653707297e-02 + 6.59487153767914e-01 8.71101696164325e-02 + 6.79575519171002e-01 8.27251675441617e-02 + 6.99894148304263e-01 7.81515132973927e-02 + 7.20444328669405e-01 7.34673024705215e-02 + 7.41209985385736e-01 6.86669596077010e-02 + 7.62176328526465e-01 6.37536068656100e-02 + 7.83326857277745e-01 5.87278224664763e-02 + 8.04644827719480e-01 5.35902846761059e-02 + 8.26113390531774e-01 4.83441901136536e-02 + 8.47715298834171e-01 4.29917435480749e-02 + 8.69451154762037e-01 3.76211700207279e-02 + 8.91282457860132e-01 3.21440170875230e-02 + 9.13213765042928e-01 2.66674634778728e-02 + 9.35201490491600e-01 2.10851818173222e-02 + 9.57229521434730e-01 1.46843783125432e-02 + 9.79261819214701e-01 7.64883901865307e-03 + 1.00000000000000e+00 3.48671814865888e-04 diff --git a/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF20_Coords.txt b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF20_Coords.txt new file mode 100644 index 00000000..8e86a6c9 --- /dev/null +++ b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF20_Coords.txt @@ -0,0 +1,208 @@ + 201 NumCoords ! The number of coordinates in the airfoil shape file (including an extra coordinate for airfoil reference). Set to zero if coordinates not included. +! ......... x-y coordinates are next if NumCoords > 0 ............. +! x-y coordinate of airfoil reference +! x/c y/c + 0.250000 0 +! coordinates of airfoil shape +! interpolation to 200 points +! x/c y/c + 1.00000000000000e+00 -1.16970450232154e-05 + 9.76925950475657e-01 2.89849629928081e-03 + 9.54056302293072e-01 5.27987438372875e-03 + 9.31048128850624e-01 7.19864995910977e-03 + 9.07985124166376e-01 8.59432633354728e-03 + 8.84963341017396e-01 8.76245996738773e-03 + 8.62070108500804e-01 7.89821744156301e-03 + 8.39377957233181e-01 5.82757272129634e-03 + 8.16952105741759e-01 2.74131006023888e-03 + 7.94848134812973e-01 -1.31047187114084e-03 + 7.73099762468629e-01 -6.19594038201392e-03 + 7.51713796559463e-01 -1.17316935887704e-02 + 7.30707465507159e-01 -1.78243181962159e-02 + 7.10048880246723e-01 -2.42736757420121e-02 + 6.89717065485909e-01 -3.09377224920066e-02 + 6.69703185975444e-01 -3.77351051006435e-02 + 6.50003630817286e-01 -4.46004260244532e-02 + 6.30597616366455e-01 -5.14349380887498e-02 + 6.11441818070351e-01 -5.80781149510869e-02 + 5.92545822192135e-01 -6.45215136200802e-02 + 5.73913326684091e-01 -7.07373461559128e-02 + 5.55506287086248e-01 -7.65813023757692e-02 + 5.37365867311171e-01 -8.21381752489661e-02 + 5.19488675136997e-01 -8.73572229383648e-02 + 5.01868935197649e-01 -9.21948826265366e-02 + 4.84511382435821e-01 -9.66125856407465e-02 + 4.67432104979211e-01 -1.00628904032081e-01 + 4.50643532673488e-01 -1.04265668268842e-01 + 4.34148314472208e-01 -1.07478023174613e-01 + 4.17951273380630e-01 -1.10235646319524e-01 + 4.02081583043242e-01 -1.12662589853757e-01 + 3.86536904904201e-01 -1.14691181363898e-01 + 3.71333778363175e-01 -1.16376698317397e-01 + 3.56481987324237e-01 -1.17794019293702e-01 + 3.41979279301955e-01 -1.18871441512321e-01 + 3.27832555060862e-01 -1.19600488549061e-01 + 3.14049364730407e-01 -1.20059113518256e-01 + 3.00631508155208e-01 -1.20254220188729e-01 + 2.87582216544618e-01 -1.20159958866052e-01 + 2.74902221193761e-01 -1.19865036371322e-01 + 2.62590720444375e-01 -1.19348842067133e-01 + 2.50649124402496e-01 -1.18621135823199e-01 + 2.39078845345792e-01 -1.17656533028436e-01 + 2.27867184439070e-01 -1.16582394562078e-01 + 2.17021456811297e-01 -1.15308380050123e-01 + 2.06538387308884e-01 -1.13853615562753e-01 + 1.96405791960340e-01 -1.12282176086080e-01 + 1.86618882329224e-01 -1.10617167094150e-01 + 1.77184649555781e-01 -1.08781185951076e-01 + 1.68076082704334e-01 -1.06908773866295e-01 + 1.59314215217802e-01 -1.04873638045081e-01 + 1.50852862448295e-01 -1.02861593237538e-01 + 1.42724842088730e-01 -1.00718365786054e-01 + 1.34902608040035e-01 -9.85287421796948e-02 + 1.27384992592018e-01 -9.62861825827909e-02 + 1.20170299874457e-01 -9.39710611432170e-02 + 1.13226789857415e-01 -9.16709983326127e-02 + 1.06580720474888e-01 -8.93032875865484e-02 + 1.00217178769272e-01 -8.68749312381822e-02 + 9.40916537592124e-02 -8.45028367434999e-02 + 8.82337163668553e-02 -8.20944117938331e-02 + 8.26115051483221e-02 -7.97126340550203e-02 + 7.72312330966435e-02 -7.73288341051596e-02 + 7.21130677350178e-02 -7.48833638768388e-02 + 6.71894736753951e-02 -7.24763209375136e-02 + 6.24856412277135e-02 -7.00416636170101e-02 + 5.80294161668677e-02 -6.75572914548322e-02 + 5.37899973283964e-02 -6.50720675769313e-02 + 4.97376985419173e-02 -6.26297954371682e-02 + 4.58940560730263e-02 -6.01849905424522e-02 + 4.22416037500420e-02 -5.77591819336826e-02 + 3.87861465552347e-02 -5.53392550403537e-02 + 3.55262959996525e-02 -5.29181938435960e-02 + 3.24472582872532e-02 -5.05155931301242e-02 + 2.95362641509762e-02 -4.81404755119313e-02 + 2.67729953169852e-02 -4.58090684459152e-02 + 2.41939083904648e-02 -4.34848129849921e-02 + 2.18141572031663e-02 -4.11543813853988e-02 + 1.95673854713824e-02 -3.88737506338495e-02 + 1.74477564779088e-02 -3.66431614312941e-02 + 1.54752345352323e-02 -3.44358303125963e-02 + 1.36342551938651e-02 -3.22650844102067e-02 + 1.19084234941661e-02 -3.01413804853732e-02 + 1.02942941011661e-02 -2.80648529097022e-02 + 8.86743811777817e-03 -2.59756933328882e-02 + 7.49856900534070e-03 -2.39690434637317e-02 + 6.29098663294263e-03 -2.19677989083217e-02 + 5.22308841935517e-03 -1.99933475331875e-02 + 4.24008866088351e-03 -1.80740827427679e-02 + 3.40280642281631e-03 -1.61810689964114e-02 + 2.68688998868729e-03 -1.43265021403969e-02 + 2.04591034039661e-03 -1.25280222785356e-02 + 1.52162287314027e-03 -1.07769333035290e-02 + 1.09208473544427e-03 -9.07280332309622e-03 + 7.75103994536751e-04 -7.41691607941299e-03 + 4.52353374589913e-04 -5.83014500820004e-03 + 2.49723979775574e-04 -4.28843531366952e-03 + 1.06661955669598e-04 -2.80345353766615e-03 + 3.27195725030880e-05 -1.37348955310638e-03 + 0.00000000000000e+00 0.00000000000000e+00 + 3.26413884329373e-05 1.37318323731147e-03 + 1.07225011317394e-04 2.80153107572479e-03 + 2.61262892040196e-04 4.28285015690166e-03 + 4.70931448264386e-04 5.81923659176159e-03 + 8.04058189317705e-04 7.39899934408296e-03 + 1.18395464357889e-03 9.03211811477640e-03 + 1.62790475131778e-03 1.07268695231018e-02 + 2.35805156291858e-03 1.23907220018351e-02 + 3.12729867551767e-03 1.41221855611746e-02 + 4.09811443518625e-03 1.58417552692127e-02 + 5.15013525889198e-03 1.76056029553215e-02 + 6.35251451470470e-03 1.93733209765600e-02 + 7.68136628992783e-03 2.11568889489349e-02 + 9.09705641338774e-03 2.29878091550079e-02 + 1.06457219627370e-02 2.48321471768241e-02 + 1.22840569946196e-02 2.67273324555485e-02 + 1.40693975554630e-02 2.86248786440320e-02 + 1.59938671904845e-02 3.05326851588142e-02 + 1.80320179344073e-02 3.24804018390111e-02 + 2.01525184247463e-02 3.45030950602257e-02 + 2.24382250539517e-02 3.65190950131922e-02 + 2.48676010790424e-02 3.85540869978262e-02 + 2.74438995195706e-02 4.06048186992883e-02 + 3.01630613080321e-02 4.26855478409807e-02 + 3.30131439394830e-02 4.48150556811931e-02 + 3.60078117153417e-02 4.69819958893802e-02 + 3.91555926213345e-02 4.91831364532758e-02 + 4.24650818770967e-02 5.14111490804253e-02 + 4.59463399533206e-02 5.36584113782445e-02 + 4.96085019195341e-02 5.59187875417100e-02 + 5.34304029583731e-02 5.82339756158755e-02 + 5.74506053673470e-02 6.05464382961678e-02 + 6.16688433559805e-02 6.28675145510649e-02 + 6.60761101690652e-02 6.52205906481849e-02 + 7.06771229650270e-02 6.76087786085493e-02 + 7.54534564656442e-02 7.00783385211843e-02 + 8.04871181124642e-02 7.24796963744080e-02 + 8.57417937708899e-02 7.48942120614805e-02 + 9.11943707542743e-02 7.73854695174959e-02 + 9.68950720892806e-02 7.98566713262581e-02 + 1.02847573387230e-01 8.22876079010535e-02 + 1.09044858215908e-01 8.47210179791181e-02 + 1.15490222891971e-01 8.71750070246340e-02 + 1.22192184613505e-01 8.96434844224979e-02 + 1.29160511286559e-01 9.21174420433711e-02 + 1.36425397154230e-01 9.45156825723323e-02 + 1.43963785764342e-01 9.69333711278718e-02 + 1.51780847657248e-01 9.93726343552587e-02 + 1.59901053759045e-01 1.01772022005663e-01 + 1.68330718517798e-01 1.04124856132688e-01 + 1.77078093160315e-01 1.06417242140794e-01 + 1.86152768336554e-01 1.08626721316434e-01 + 1.95547957086479e-01 1.10808018380726e-01 + 2.05262344651788e-01 1.12982949744755e-01 + 2.15316288411784e-01 1.15080703683943e-01 + 2.25727640430810e-01 1.17028842247463e-01 + 2.36486953294469e-01 1.18893468221244e-01 + 2.47606103597236e-01 1.20613966312300e-01 + 2.59082067962401e-01 1.22236590592394e-01 + 2.70915428466803e-01 1.23770388922269e-01 + 2.83123302721779e-01 1.25093790952213e-01 + 2.95700040272605e-01 1.26248167564620e-01 + 3.08649339579229e-01 1.27202204411106e-01 + 3.21973207911371e-01 1.27886002490200e-01 + 3.35666915940575e-01 1.28336009455904e-01 + 3.49729856148137e-01 1.28515938919406e-01 + 3.64156044605897e-01 1.28322082434802e-01 + 3.78943465936109e-01 1.27872557734258e-01 + 3.94083763263825e-01 1.27105654197604e-01 + 4.09575696342703e-01 1.26076864381629e-01 + 4.25414011369775e-01 1.24776753517338e-01 + 4.41593423933488e-01 1.23203803654028e-01 + 4.58118698550793e-01 1.21453065442532e-01 + 4.74969289264106e-01 1.19379481227578e-01 + 4.92141581296370e-01 1.17024136753557e-01 + 5.09640928459442e-01 1.14468473774205e-01 + 5.27459181191729e-01 1.11706370002499e-01 + 5.45579400762510e-01 1.08675938318902e-01 + 5.64000646601103e-01 1.05430671339811e-01 + 5.82720846933108e-01 1.02001576810010e-01 + 6.01731586141294e-01 9.83969151548686e-02 + 6.21010755973352e-01 9.45591973944104e-02 + 6.40543478738464e-01 9.04796724759952e-02 + 6.60338537645302e-01 8.62499884007561e-02 + 6.80385825453853e-01 8.18833516289867e-02 + 7.00661796733097e-01 7.73360839181257e-02 + 7.21167806331622e-01 7.26753969763489e-02 + 7.41887916488567e-01 6.78960039061239e-02 + 7.62806892564257e-01 6.29998067215964e-02 + 7.83908861634844e-01 5.79878832722068e-02 + 8.05177351436274e-01 5.28629172742288e-02 + 8.26595261100184e-01 4.76276642630319e-02 + 8.48144449629654e-01 4.22843337759070e-02 + 8.69827140629476e-01 3.69111819966000e-02 + 8.91604637206406e-01 3.14360883953754e-02 + 9.13481489167149e-01 2.59485561418769e-02 + 9.35413129302637e-01 2.03601258502341e-02 + 9.57385180896840e-01 1.40200210251241e-02 + 9.79362661611973e-01 7.10265085432084e-03 + 1.00000000000000e+00 -1.07577592503420e-05 diff --git a/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF21_Coords.txt b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF21_Coords.txt new file mode 100644 index 00000000..388e7950 --- /dev/null +++ b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF21_Coords.txt @@ -0,0 +1,208 @@ + 201 NumCoords ! The number of coordinates in the airfoil shape file (including an extra coordinate for airfoil reference). Set to zero if coordinates not included. +! ......... x-y coordinates are next if NumCoords > 0 ............. +! x-y coordinate of airfoil reference +! x/c y/c + 0.250000 0 +! coordinates of airfoil shape +! interpolation to 200 points +! x/c y/c + 1.00000000000000e+00 -2.84740725711342e-05 + 9.76865338872185e-01 2.85428304137865e-03 + 9.53929219800446e-01 5.24327408174464e-03 + 9.30868587354945e-01 7.20751732930949e-03 + 9.07757786371386e-01 8.68022664963385e-03 + 8.84685981963589e-01 9.16779767337892e-03 + 8.61737273650503e-01 8.59878745573448e-03 + 8.38982716451081e-01 6.97032631101525e-03 + 8.16487465310072e-01 4.27790070293695e-03 + 7.94307280144394e-01 5.98958387499667e-04 + 7.72478209244049e-01 -3.92421216988763e-03 + 7.51009294443888e-01 -9.11447969158894e-03 + 7.29917171589636e-01 -1.48652160246661e-02 + 7.09173987466613e-01 -2.09915209310793e-02 + 6.88759055777041e-01 -2.73426738600162e-02 + 6.68666517410726e-01 -3.38483930358717e-02 + 6.48890300856279e-01 -4.04237940323079e-02 + 6.29411879426884e-01 -4.69774888101651e-02 + 6.10190624345359e-01 -5.33527496658855e-02 + 5.91235514841636e-01 -5.95364517406264e-02 + 5.72549427006805e-01 -6.54947690043992e-02 + 5.54098681203993e-01 -7.10990749251103e-02 + 5.35920827161821e-01 -7.64189417500869e-02 + 5.18012958869965e-01 -8.14046707993908e-02 + 5.00370906490186e-01 -8.60216565775983e-02 + 4.82998993642838e-01 -9.02272377996711e-02 + 4.65913482233682e-01 -9.40474533539546e-02 + 4.49125729712078e-01 -9.74967264248575e-02 + 4.32639419880572e-01 -1.00542965307158e-01 + 4.16459539589475e-01 -1.03161374243716e-01 + 4.00613215473433e-01 -1.05466420900906e-01 + 3.85098707684728e-01 -1.07402177176065e-01 + 3.69931266330609e-01 -1.09020571824359e-01 + 3.55119768331056e-01 -1.10391209715929e-01 + 3.40661821755905e-01 -1.11451999694907e-01 + 3.26563430473896e-01 -1.12194090288857e-01 + 3.12830956759217e-01 -1.12692769163857e-01 + 2.99465542002860e-01 -1.12952761784846e-01 + 2.86469704616211e-01 -1.12949992221423e-01 + 2.73843543674708e-01 -1.12766407873851e-01 + 2.61586025508254e-01 -1.12380265536283e-01 + 2.49698014015215e-01 -1.11799275824114e-01 + 2.38180021002129e-01 -1.11005012677545e-01 + 2.27020875450809e-01 -1.10103654156307e-01 + 2.16226137874301e-01 -1.09019236030612e-01 + 2.05793116599237e-01 -1.07760935076377e-01 + 1.95709833948425e-01 -1.06391330139806e-01 + 1.85971073779880e-01 -1.04935019609158e-01 + 1.76583031796272e-01 -1.03315378553033e-01 + 1.67520981485238e-01 -1.01654758321660e-01 + 1.58802515906259e-01 -9.98409591053214e-02 + 1.50385000970262e-01 -9.80499859448751e-02 + 1.42298158727063e-01 -9.61306196719593e-02 + 1.34516269147850e-01 -9.41634136087469e-02 + 1.27037305703638e-01 -9.21442045117529e-02 + 1.19859512781939e-01 -9.00492381147093e-02 + 1.12952800949352e-01 -8.79682875564088e-02 + 1.06339499636755e-01 -8.58264580885655e-02 + 1.00007414389900e-01 -8.36143627290609e-02 + 9.39147764330701e-02 -8.14516604635932e-02 + 8.80868393032252e-02 -7.92537536059723e-02 + 8.24946159428780e-02 -7.70801723815972e-02 + 7.71274250919293e-02 -7.49012538073132e-02 + 7.20190535116052e-02 -7.26564811445412e-02 + 6.71057079852937e-02 -7.03934414720974e-02 + 6.24118140095744e-02 -6.80431207723954e-02 + 5.79644757418812e-02 -6.56460890316721e-02 + 5.37333540900433e-02 -6.32481286299431e-02 + 4.96893756299879e-02 -6.08884959776765e-02 + 4.58534457561426e-02 -5.85255201649711e-02 + 4.22083319889390e-02 -5.61793213837462e-02 + 3.87596121937182e-02 -5.38383821901660e-02 + 3.55057922281837e-02 -5.14962236665323e-02 + 3.24322743559543e-02 -4.91703134749231e-02 + 2.95264783129621e-02 -4.68695823371802e-02 + 2.67683318695932e-02 -4.46098816905116e-02 + 2.41934701367245e-02 -4.23573844305122e-02 + 2.18548607049960e-02 -4.00989773901928e-02 + 1.96524338700715e-02 -3.78875178579182e-02 + 1.75755260431319e-02 -3.57232070150690e-02 + 1.56358377059865e-02 -3.35811088781324e-02 + 1.38207984844720e-02 -3.14734077737011e-02 + 1.21180061661380e-02 -2.94102107211683e-02 + 1.05254874189780e-02 -2.73912953793136e-02 + 9.09360929036987e-03 -2.53625298476404e-02 + 7.72181822309867e-03 -2.34101512080760e-02 + 6.49763138245874e-03 -2.14641052056444e-02 + 5.40871842169344e-03 -1.95429445805207e-02 + 4.40961919998241e-03 -1.76727016085954e-02 + 3.55040219006997e-03 -1.58276863888619e-02 + 2.80808183134115e-03 -1.40194239937278e-02 + 2.14649703528823e-03 -1.22634144788593e-02 + 1.59920737776881e-03 -1.05527195276620e-02 + 1.14930375044154e-03 -8.88654178716626e-03 + 8.10231534512569e-04 -7.26673074294147e-03 + 4.78895883677518e-04 -5.71256790934727e-03 + 2.63639401109400e-04 -4.20252872193405e-03 + 1.11557989496940e-04 -2.74745794723513e-03 + 3.44756369415605e-05 -1.34604561592499e-03 + 0.00000000000000e+00 0.00000000000000e+00 + 3.20816693922806e-05 1.34573179197360e-03 + 1.07094538044363e-04 2.74581135191723e-03 + 2.61023002477552e-04 4.19787122797409e-03 + 4.70744609715971e-04 5.70378084563639e-03 + 8.02668778110153e-04 7.25269694625556e-03 + 1.18211679499553e-03 8.85342213515878e-03 + 1.62613136894154e-03 1.05133892427942e-02 + 2.35095850098151e-03 1.21472955138763e-02 + 3.11291707163376e-03 1.38451043913963e-02 + 4.06681615370234e-03 1.55343607101053e-02 + 5.10318321837548e-03 1.72662509388141e-02 + 6.28537915014080e-03 1.90038719565046e-02 + 7.59081076018542e-03 2.07586526711072e-02 + 8.98284133346192e-03 2.25595390649685e-02 + 1.05048772029216e-02 2.43750659231944e-02 + 1.21173705320911e-02 2.62396209517460e-02 + 1.38724687721741e-02 2.81092919141236e-02 + 1.57628531446385e-02 2.99916503138032e-02 + 1.77668024925910e-02 3.19129888938685e-02 + 1.98560304119069e-02 3.39051089397272e-02 + 2.21065209505667e-02 3.58935725801445e-02 + 2.44975644102754e-02 3.79031615747998e-02 + 2.70332347408878e-02 3.99299291146165e-02 + 2.97109628466766e-02 4.19867024992787e-02 + 3.25200587654925e-02 4.40903080891470e-02 + 3.54726867654753e-02 4.62315479726106e-02 + 3.85766530005811e-02 4.84076241040826e-02 + 4.18413693987001e-02 5.06110330462258e-02 + 4.52764942398936e-02 5.28343865988492e-02 + 4.88907425761762e-02 5.50724163659514e-02 + 5.26646691476036e-02 5.73640816538310e-02 + 5.66345029639527e-02 5.96558451069643e-02 + 6.08009395375298e-02 6.19577340085226e-02 + 6.51558010698599e-02 6.42917617552471e-02 + 6.97040980071108e-02 6.66604081412036e-02 + 7.44292782322818e-02 6.91063981945018e-02 + 7.94075911539318e-02 7.14919169255233e-02 + 8.46064336120551e-02 7.38912356977943e-02 + 9.00046646171667e-02 7.63634375717562e-02 + 9.56495329755105e-02 7.88186816028507e-02 + 1.01544707534728e-01 8.12061081549737e-02 + 1.07684393957011e-01 8.35823621854077e-02 + 1.14072629815357e-01 8.59820974163730e-02 + 1.20717936678019e-01 8.83984296232361e-02 + 1.27629750106332e-01 9.08236951338500e-02 + 1.34836465041941e-01 9.31733181108972e-02 + 1.42317922535003e-01 9.55435716133629e-02 + 1.50079297300981e-01 9.79421782603361e-02 + 1.58143784516036e-01 1.00304899967289e-01 + 1.66517972957835e-01 1.02624809036553e-01 + 1.75210207161683e-01 1.04888579553756e-01 + 1.84229946037827e-01 1.07074677598208e-01 + 1.93571360679093e-01 1.09243451986783e-01 + 2.03234945574175e-01 1.11402415125159e-01 + 2.13239205546370e-01 1.13491436907172e-01 + 2.23601537222704e-01 1.15440504439587e-01 + 2.34314315339563e-01 1.17306503096526e-01 + 2.45388676682413e-01 1.19037311828905e-01 + 2.56822498877269e-01 1.20681072953816e-01 + 2.68616771371790e-01 1.22241825144540e-01 + 2.80788220103666e-01 1.23601558631169e-01 + 2.93331680600211e-01 1.24805212165338e-01 + 3.06251511490344e-01 1.25807926970102e-01 + 3.19549745336724e-01 1.26554338608240e-01 + 3.33222453479109e-01 1.27061326118213e-01 + 3.47269018943833e-01 1.27298091243991e-01 + 3.61683948293755e-01 1.27170458380383e-01 + 3.76464979016090e-01 1.26770572192297e-01 + 3.91604054165987e-01 1.26048320133488e-01 + 4.07099743027696e-01 1.25063728629558e-01 + 4.22946891110087e-01 1.23804897872974e-01 + 4.39140508807244e-01 1.22276792353123e-01 + 4.55684294155409e-01 1.20554509111602e-01 + 4.72559601516541e-01 1.18524015966612e-01 + 4.89761912975334e-01 1.16207419090395e-01 + 5.07296139266516e-01 1.13684964275664e-01 + 5.25154357085284e-01 1.10950890395180e-01 + 5.43320252389640e-01 1.07950681161174e-01 + 5.61792716627316e-01 1.04735757711390e-01 + 5.80568803339265e-01 1.01328525940682e-01 + 5.99640262789189e-01 9.77381351876646e-02 + 6.18986539924185e-01 9.39237635066851e-02 + 6.38592769146560e-01 8.98769749368346e-02 + 6.58465976460566e-01 8.56827556065770e-02 + 6.78595728050462e-01 8.13433005574353e-02 + 6.98959863838616e-01 7.68298671125305e-02 + 7.19558497677296e-01 7.21964039086358e-02 + 7.40375559459272e-01 6.74380995266311e-02 + 7.61395509952232e-01 6.25588162368450e-02 + 7.82602242599360e-01 5.75571816126900e-02 + 8.03979199523738e-01 5.24376017015890e-02 + 8.25508947220265e-01 4.72044836666912e-02 + 8.47173082201993e-01 4.18658829372147e-02 + 8.68972243269945e-01 3.64790803343795e-02 + 8.90869140608345e-01 3.09938752249591e-02 + 9.12865896627548e-01 2.54780934053288e-02 + 9.34919781152421e-01 1.98727453143736e-02 + 9.57016514682770e-01 1.36303405789984e-02 + 9.79120888238619e-01 6.90832082291697e-03 + 1.00000000000000e+00 3.57170593908316e-05 diff --git a/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF22_Coords.txt b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF22_Coords.txt new file mode 100644 index 00000000..ee67f764 --- /dev/null +++ b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF22_Coords.txt @@ -0,0 +1,208 @@ + 201 NumCoords ! The number of coordinates in the airfoil shape file (including an extra coordinate for airfoil reference). Set to zero if coordinates not included. +! ......... x-y coordinates are next if NumCoords > 0 ............. +! x-y coordinate of airfoil reference +! x/c y/c + 0.250000 0 +! coordinates of airfoil shape +! interpolation to 200 points +! x/c y/c + 1.00000000000000e+00 -1.37905772906987e-04 + 9.76725991935908e-01 2.75905550847849e-03 + 9.53631351611733e-01 5.18607754339260e-03 + 9.30439467907717e-01 7.21116637405844e-03 + 9.07208132179710e-01 8.76441631458846e-03 + 8.84013496158046e-01 9.51161259804528e-03 + 8.60933319861523e-01 9.19547841137385e-03 + 8.38035712490432e-01 7.96595476402018e-03 + 8.15385168895348e-01 5.62847327150540e-03 + 7.93037657818789e-01 2.28558101061580e-03 + 7.71032949299981e-01 -1.90093741181228e-03 + 7.49384114270963e-01 -6.76049461633643e-03 + 7.28106510273087e-01 -1.21725858076415e-02 + 7.07180107191085e-01 -1.79684774976327e-02 + 6.86585882704839e-01 -2.39949416112886e-02 + 6.66322327664117e-01 -3.01870419451860e-02 + 6.46380042253330e-01 -3.64467876017566e-02 + 6.26744157329858e-01 -4.26868759536930e-02 + 6.07380274045402e-01 -4.87646156436792e-02 + 5.88295958690534e-01 -5.46605390281692e-02 + 5.69492521413567e-01 -6.03344111379996e-02 + 5.50944917753757e-01 -6.56813210738157e-02 + 5.32683529719922e-01 -7.07499443242120e-02 + 5.14706548079326e-01 -7.54948621351449e-02 + 4.97012214427392e-01 -7.98856360729547e-02 + 4.79604661938784e-01 -8.38829246167327e-02 + 4.62499971271577e-01 -8.75164861473946e-02 + 4.45707439025159e-01 -9.07910364185073e-02 + 4.29232251749769e-01 -9.36853302638665e-02 + 4.13079887518895e-01 -9.61843197334282e-02 + 3.97273156999330e-01 -9.83823772625506e-02 + 3.81811499955324e-01 -1.00238171273862e-01 + 3.66707654879754e-01 -1.01796983957391e-01 + 3.51968873020320e-01 -1.03118493586559e-01 + 3.37592692843044e-01 -1.04152291381984e-01 + 3.23583613955391e-01 -1.04892228070397e-01 + 3.09945962441104e-01 -1.05403595252986e-01 + 2.96679877893668e-01 -1.05689666745533e-01 + 2.83786673843868e-01 -1.05732022868329e-01 + 2.71265428998315e-01 -1.05601326789481e-01 + 2.59114641005256e-01 -1.05279433841182e-01 + 2.47334122817983e-01 -1.04772898258849e-01 + 2.35922762413987e-01 -1.04073450080798e-01 + 2.24871859339431e-01 -1.03261410015675e-01 + 2.14183854398850e-01 -1.02280347491613e-01 + 2.03856443420195e-01 -1.01137855951245e-01 + 1.93878365466042e-01 -9.98859412460872e-02 + 1.84243680326433e-01 -9.85473584321357e-02 + 1.74956557366324e-01 -9.70603160684741e-02 + 1.65996483607503e-01 -9.55230954068784e-02 + 1.57374597017771e-01 -9.38510527263059e-02 + 1.49055367342827e-01 -9.21872601100961e-02 + 1.41061804544547e-01 -9.04086149008263e-02 + 1.33371830662132e-01 -8.85813343893779e-02 + 1.25981833168783e-01 -8.67037376102544e-02 + 1.18889524396252e-01 -8.47556746420726e-02 + 1.12068484997073e-01 -8.28134777714908e-02 + 1.05533508673527e-01 -8.08202882655789e-02 + 9.92765954754487e-02 -7.87616970055698e-02 + 9.32618460232315e-02 -7.67377034670206e-02 + 8.75063188947793e-02 -7.46839878289475e-02 + 8.19865845292902e-02 -7.26460887111042e-02 + 7.66696758964058e-02 -7.06018837113606e-02 + 7.16044906719353e-02 -6.85025449105124e-02 + 6.67363367619081e-02 -6.63816283727544e-02 + 6.20862671655154e-02 -6.41837626120213e-02 + 5.76781158267178e-02 -6.19465872092337e-02 + 5.34835811930607e-02 -5.97092958338184e-02 + 4.94762917876905e-02 -5.75018783824138e-02 + 4.56743711349976e-02 -5.52907634791866e-02 + 4.20616172369434e-02 -5.30929364276299e-02 + 3.86426064710656e-02 -5.08998396737268e-02 + 3.54153788093397e-02 -4.87062512082961e-02 + 3.23662010540160e-02 -4.65256202361847e-02 + 2.94833263627923e-02 -4.43663553536911e-02 + 2.67477674550665e-02 -4.22428674968400e-02 + 2.41915370057616e-02 -4.01273164512632e-02 + 2.18857573818062e-02 -3.80078237337925e-02 + 1.97179884024849e-02 -3.59301627477569e-02 + 1.76757845498892e-02 -3.38938481159999e-02 + 1.57641027306169e-02 -3.18781262584388e-02 + 1.39724593422236e-02 -2.98931987545935e-02 + 1.22918968479213e-02 -2.79480618328304e-02 + 1.07221372201749e-02 -2.60416137215328e-02 + 9.28872160500910e-03 -2.41314304207875e-02 + 7.91630048953282e-03 -2.22853322080103e-02 + 6.67953167608040e-03 -2.04480781470025e-02 + 5.57389618300349e-03 -1.86324963909326e-02 + 4.56332093730877e-03 -1.68598162507488e-02 + 3.68524480226045e-03 -1.51108431623255e-02 + 2.91938579202685e-03 -1.33953381237321e-02 + 2.24116079129066e-03 -1.17246173969605e-02 + 1.67248583161617e-03 -1.00953735229212e-02 + 1.20324454848532e-03 -8.50604304796152e-03 + 8.41606529174913e-04 -6.95951603892573e-03 + 5.04718335749302e-04 -5.47175146445821e-03 + 2.77648316387901e-04 -4.02638290581776e-03 + 1.17748797893260e-04 -2.63253995295761e-03 + 3.69468292642352e-05 -1.28969548263411e-03 + 0.00000000000000e+00 0.00000000000000e+00 + 3.09535021918612e-05 1.28936436929246e-03 + 1.06637401949987e-04 2.63142100210815e-03 + 2.59964572072159e-04 4.02351019908418e-03 + 4.69920111426106e-04 5.46706336175963e-03 + 7.96541452526313e-04 6.95306199333623e-03 + 1.17401205379525e-03 8.48786363886347e-03 + 1.61831089593917e-03 1.00770346353190e-02 + 2.32333874774940e-03 1.16504559884271e-02 + 3.06712959817167e-03 1.32804282822632e-02 + 3.98276803748560e-03 1.49090049113570e-02 + 4.98344743343845e-03 1.65770603791945e-02 + 6.11996090735756e-03 1.82551557640217e-02 + 7.37297343445192e-03 1.99533035573824e-02 + 8.71286539087883e-03 2.16948370578646e-02 + 1.01765501551493e-02 2.34537701968742e-02 + 1.17322670694759e-02 2.52581891303742e-02 + 1.34217992141067e-02 2.70733747583812e-02 + 1.52388298301360e-02 2.89063564237294e-02 + 1.71688461558914e-02 3.07767937542747e-02 + 1.91899331878790e-02 3.27097377805680e-02 + 2.13638093661363e-02 3.46457797783486e-02 + 2.36723297656305e-02 3.66070405437775e-02 + 2.61211854117630e-02 3.85883561887161e-02 + 2.87097811699761e-02 4.06004475067315e-02 + 3.14304301249726e-02 4.26557978654197e-02 + 3.42931270832587e-02 4.47486944963130e-02 + 3.73038188445460e-02 4.68776749211300e-02 + 4.04730361230994e-02 4.90353694174481e-02 + 4.38097981156242e-02 5.12147401773910e-02 + 4.73220204778543e-02 5.34122475810596e-02 + 5.09939923040230e-02 5.56608916859612e-02 + 5.48571252255563e-02 5.79155152658394e-02 + 5.89138291139096e-02 6.01837002893103e-02 + 6.31577497344129e-02 6.24845191863370e-02 + 6.75947899647940e-02 6.48186842922515e-02 + 7.22122652229698e-02 6.72216823767386e-02 + 7.70740114758716e-02 6.95807319849553e-02 + 8.21553322345438e-02 7.19550902719777e-02 + 8.74394236745447e-02 7.43941379373109e-02 + 9.29672017196781e-02 7.68226772209049e-02 + 9.87424021686052e-02 7.91978116359561e-02 + 1.04761752867740e-01 8.15667320414124e-02 + 1.11030780081871e-01 8.39572315421679e-02 + 1.17558018563720e-01 8.63625746301939e-02 + 1.24352270186846e-01 8.87774608495421e-02 + 1.31438105054613e-01 9.11321173164249e-02 + 1.38801313550205e-01 9.35029309525731e-02 + 1.46447393656373e-01 9.58971156573319e-02 + 1.54396766312990e-01 9.82613258248415e-02 + 1.62656569565700e-01 1.00588261686332e-01 + 1.71235347766832e-01 1.02865843879122e-01 + 1.80142279870852e-01 1.05076149462146e-01 + 1.89373799652761e-01 1.07269345993908e-01 + 1.98933590722142e-01 1.09443191127768e-01 + 2.08836636556623e-01 1.11554276573076e-01 + 2.19099471288483e-01 1.13540075332887e-01 + 2.29717904676441e-01 1.15442617819263e-01 + 2.40701766215834e-01 1.17220973164961e-01 + 2.52050933191971e-01 1.18911560197852e-01 + 2.63767077262110e-01 1.20517086973916e-01 + 2.75865949946677e-01 1.21934154882854e-01 + 2.88343581116220e-01 1.23201688742876e-01 + 3.01205334203085e-01 1.24270880831573e-01 + 3.14453408998862e-01 1.25097439258154e-01 + 3.28085392677879e-01 1.25681829879209e-01 + 3.42100675917614e-01 1.25997636647737e-01 + 3.56494768423971e-01 1.25962526629538e-01 + 3.71264984512598e-01 1.25638758942093e-01 + 3.86403905621335e-01 1.24988484201363e-01 + 4.01909708696471e-01 1.24068994185517e-01 + 4.17777487590764e-01 1.22870793211783e-01 + 4.34002789914367e-01 1.21403723025625e-01 + 4.50587361686721e-01 1.19722425477543e-01 + 4.67516097146081e-01 1.17745691253289e-01 + 4.84783008098729e-01 1.15478338348871e-01 + 5.02391973551338e-01 1.12996226374276e-01 + 5.20335411416213e-01 1.10293881931109e-01 + 5.38598443680468e-01 1.07327040011182e-01 + 5.57179445389403e-01 1.04143490655964e-01 + 5.76073870986909e-01 1.00758354775127e-01 + 5.95273625837750e-01 9.71818954906031e-02 + 6.14761209512960e-01 9.33892639430016e-02 + 6.34522016454894e-01 8.93721485884786e-02 + 6.54559394245177e-01 8.52121018071187e-02 + 6.74862300856641e-01 8.08992604208061e-02 + 6.95411169374383e-01 7.64180821116692e-02 + 7.16203679512635e-01 7.18100281693020e-02 + 7.37223461079002e-01 6.70709646616096e-02 + 7.58454521150695e-01 6.22070114365566e-02 + 7.79880103179641e-01 5.72143218232588e-02 + 8.01483398149160e-01 5.20988678810583e-02 + 8.23246404130259e-01 4.68667510151217e-02 + 8.45150485874660e-01 4.15319681044740e-02 + 8.67192695150624e-01 3.61314252690582e-02 + 8.89338539461505e-01 3.06353825258196e-02 + 9.11585423298854e-01 2.50909095333333e-02 + 9.33894494503434e-01 1.94679731415527e-02 + 9.56251121560769e-01 1.33384432495636e-02 + 9.78619325570430e-01 6.83697775457594e-03 + 1.00000000000000e+00 2.05198748460235e-04 diff --git a/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF23_Coords.txt b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF23_Coords.txt new file mode 100644 index 00000000..b7ccee65 --- /dev/null +++ b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF23_Coords.txt @@ -0,0 +1,208 @@ + 201 NumCoords ! The number of coordinates in the airfoil shape file (including an extra coordinate for airfoil reference). Set to zero if coordinates not included. +! ......... x-y coordinates are next if NumCoords > 0 ............. +! x-y coordinate of airfoil reference +! x/c y/c + 0.250000 0 +! coordinates of airfoil shape +! interpolation to 200 points +! x/c y/c + 1.00000000000000e+00 -3.89631805446465e-04 + 9.76523223440909e-01 2.57752479218257e-03 + 9.53190468875220e-01 5.08428616099728e-03 + 9.29793700110228e-01 7.19463079459903e-03 + 9.06373069230989e-01 8.83683936265999e-03 + 8.82989474321167e-01 9.75643931673717e-03 + 8.59712867174704e-01 9.61496203663975e-03 + 8.36607653336429e-01 8.67096288412905e-03 + 8.13736696364153e-01 6.61459865723342e-03 + 7.91156003915796e-01 3.56436965978782e-03 + 7.68908626920759e-01 -3.19229213119966e-04 + 7.47012054504006e-01 -4.87284377280892e-03 + 7.25479893786865e-01 -9.96177887707548e-03 + 7.04301598747634e-01 -1.54349458980302e-02 + 6.83461873027533e-01 -2.11434442792537e-02 + 6.62962284386421e-01 -2.70203050251467e-02 + 6.42791629284883e-01 -3.29619235742479e-02 + 6.22938362223096e-01 -3.88812963489969e-02 + 6.03377191897424e-01 -4.46577924076831e-02 + 5.84113605921901e-01 -5.02638611712951e-02 + 5.65147058057943e-01 -5.56526737727627e-02 + 5.46463242401931e-01 -6.07476183166026e-02 + 5.28083600651341e-01 -6.55730561886808e-02 + 5.10007892084025e-01 -7.00900567751652e-02 + 4.92236196987507e-01 -7.42679957358169e-02 + 4.74773357090323e-01 -7.80766311425804e-02 + 4.57634431292357e-01 -8.15460818492506e-02 + 4.40826245471248e-01 -8.46702707193481e-02 + 4.24355029015101e-01 -8.74363864527718e-02 + 4.08227124292632e-01 -8.98419112116650e-02 + 3.92459570866590e-01 -9.19539503766752e-02 + 3.77053268096062e-01 -9.37469616449339e-02 + 3.62017890326388e-01 -9.52572816145339e-02 + 3.47358922971653e-01 -9.65314596619472e-02 + 3.33074130797390e-01 -9.75316311345544e-02 + 3.19166552441191e-01 -9.82568017865109e-02 + 3.05638457789601e-01 -9.87570424765259e-02 + 2.92489196946871e-01 -9.90352109981780e-02 + 2.79718896446607e-01 -9.90816142636686e-02 + 2.67325715523272e-01 -9.89532661236331e-02 + 2.55307554299133e-01 -9.86395210813088e-02 + 2.43662963759620e-01 -9.81468679323721e-02 + 2.32389051593200e-01 -9.74790188542946e-02 + 2.21479352444559e-01 -9.66892453470001e-02 + 2.10932960713701e-01 -9.57430626738486e-02 + 2.00746891023561e-01 -9.46523604003965e-02 + 1.90911241857401e-01 -9.34530543544128e-02 + 1.81419357741535e-01 -9.21641429584474e-02 + 1.72272201518936e-01 -9.07467422355202e-02 + 1.63454036160759e-01 -8.92690930011261e-02 + 1.54968504898213e-01 -8.76805069244906e-02 + 1.46789032362938e-01 -8.60792825829244e-02 + 1.38929389926432e-01 -8.43836334579841e-02 + 1.31372073509835e-01 -8.26402323580097e-02 + 1.24111669738838e-01 -8.08497501671892e-02 + 1.17144601558583e-01 -7.89996633722882e-02 + 1.10449627383806e-01 -7.71449373419936e-02 + 1.04032527949034e-01 -7.52514037061188e-02 + 9.78887241867816e-02 -7.33057936883226e-02 + 9.19902897469441e-02 -7.13774864507213e-02 + 8.63446174524882e-02 -6.94278850804577e-02 + 8.09349931912135e-02 -6.74837749535468e-02 + 7.57176279736417e-02 -6.55345654926341e-02 + 7.07422636872318e-02 -6.35487599075303e-02 + 6.59681013466920e-02 -6.15577280140700e-02 + 6.14091796784638e-02 -5.95276219887417e-02 + 5.70825310884753e-02 -5.74696232341217e-02 + 5.29640917916176e-02 -5.54139826908802e-02 + 4.90331099431885e-02 -5.33787557780121e-02 + 4.53019232083321e-02 -5.13412852201466e-02 + 4.17564728311483e-02 -4.93141304770355e-02 + 3.83992522495016e-02 -4.72921118209637e-02 + 3.52273324651378e-02 -4.52718650652909e-02 + 3.22287783868937e-02 -4.32621299402485e-02 + 2.93935765607861e-02 -4.12701495319455e-02 + 2.67049962322860e-02 -3.93074868211488e-02 + 2.41875159700224e-02 -3.73546300420540e-02 + 2.19051355335849e-02 -3.54024649802942e-02 + 1.97596598780863e-02 -3.34865723449696e-02 + 1.77404917592603e-02 -3.16046902103228e-02 + 1.58480959117786e-02 -2.97420661384396e-02 + 1.40731937772208e-02 -2.79068578544306e-02 + 1.24092192372854e-02 -2.61060448917434e-02 + 1.08572800374988e-02 -2.43371683353192e-02 + 9.42416939885715e-03 -2.25730887258294e-02 + 8.05945666798942e-03 -2.08575096912792e-02 + 6.81900211726789e-03 -1.91549248355902e-02 + 5.70427188596224e-03 -1.74708678303986e-02 + 4.68929550551071e-03 -1.58203951766527e-02 + 3.79718481534846e-03 -1.41925025018919e-02 + 3.01254414274189e-03 -1.25940941416061e-02 + 2.32306506044275e-03 -1.10313592778986e-02 + 1.73616370284593e-03 -9.50573827422768e-03 + 1.25001115654578e-03 -8.01464961151014e-03 + 8.66582941084615e-04 -6.56215809631841e-03 + 5.27892943221305e-04 -5.15982819826281e-03 + 2.90620181051750e-04 -3.79793930383067e-03 + 1.24304967749036e-04 -2.48335242246912e-03 + 3.96737576866571e-05 -1.21650060438702e-03 + 0.00000000000000e+00 0.00000000000000e+00 + 2.95189184277812e-05 1.21614429607452e-03 + 1.05767060451514e-04 2.48286216056600e-03 + 2.57762778152470e-04 3.79720959162143e-03 + 4.68204860110995e-04 5.16008910759149e-03 + 7.83797140932723e-04 6.56497526010459e-03 + 1.15715502367995e-03 8.01500849124157e-03 + 1.60204509969143e-03 9.51313492711731e-03 + 2.26838290451738e-03 1.10094565184360e-02 + 2.98389530162135e-03 1.25531639212653e-02 + 3.84468300573088e-03 1.41052049491652e-02 + 4.79382432709198e-03 1.56929490788932e-02 + 5.86480251491728e-03 1.72970451450205e-02 + 7.04339712537743e-03 1.89252483507722e-02 + 8.31036366558127e-03 2.05930697348407e-02 + 9.69288686144440e-03 2.22822382309425e-02 + 1.11694244157683e-02 2.40125728679872e-02 + 1.27687195678609e-02 2.57610052570714e-02 + 1.44855480622724e-02 2.75340521574697e-02 + 1.63141117762223e-02 2.93431371358707e-02 + 1.82409459730255e-02 3.12044757360750e-02 + 2.03090129151232e-02 3.30784440112194e-02 + 2.25047656211822e-02 3.49825288350549e-02 + 2.48358954405978e-02 3.69102907266350e-02 + 2.73027851057594e-02 3.88709280586456e-02 + 2.99022786432083e-02 4.08708020979388e-02 + 3.26428835363264e-02 4.29073735254742e-02 + 3.55275801260422e-02 4.49815642845116e-02 + 3.85675366725734e-02 4.70868993056664e-02 + 4.17712151330545e-02 4.92166052451779e-02 + 4.51455848984656e-02 5.13693116705787e-02 + 4.86800832975236e-02 5.35697871829730e-02 + 5.23998258242555e-02 5.57840039693155e-02 + 5.63090699963194e-02 5.80167300546564e-02 + 6.04040077958621e-02 6.02830393557848e-02 + 6.46921254503434e-02 6.25806625362446e-02 + 6.91657933196187e-02 6.49357139206047e-02 + 7.38718601029010e-02 6.72692279831682e-02 + 7.87963189404003e-02 6.96202880139496e-02 + 8.39284216127343e-02 7.20249986111878e-02 + 8.93005278379212e-02 7.44277079926884e-02 + 9.49165785178080e-02 7.68080305069524e-02 + 1.00776596462740e-01 7.91941589367465e-02 + 1.06887992955234e-01 8.15979852235107e-02 + 1.13259326028114e-01 8.40133348371362e-02 + 1.19898645623439e-01 8.64376453292622e-02 + 1.26825363129969e-01 8.88246082279034e-02 + 1.34032996617006e-01 9.12209273262398e-02 + 1.41527923866446e-01 9.36300218950618e-02 + 1.49326736108375e-01 9.60160327660242e-02 + 1.57437264377705e-01 9.83712642438628e-02 + 1.65868324600152e-01 1.00685218752554e-01 + 1.74628718266615e-01 1.02944937223580e-01 + 1.83718250107745e-01 1.05182085806860e-01 + 1.93143977808745e-01 1.07387673596204e-01 + 2.02916723675256e-01 1.09537420256945e-01 + 2.13052007685298e-01 1.11578803647391e-01 + 2.23549653724373e-01 1.13536674601117e-01 + 2.34418102657221e-01 1.15382216081547e-01 + 2.45660047881914e-01 1.17132423550172e-01 + 2.57277821794247e-01 1.18790833197830e-01 + 2.69285661481619e-01 1.20274563173763e-01 + 2.81681435328113e-01 1.21610792504416e-01 + 2.94471299405458e-01 1.22753207590004e-01 + 3.07657839217654e-01 1.23665554126748e-01 + 3.21240423603742e-01 1.24335192568048e-01 + 3.35218492732312e-01 1.24739126354752e-01 + 3.49588853515411e-01 1.24807697648437e-01 + 3.64348393745959e-01 1.24573091480070e-01 + 3.79490557018895e-01 1.24009550543367e-01 + 3.95013008833302e-01 1.23166425873097e-01 + 4.10911230551784e-01 1.22040125894596e-01 + 4.27181368064296e-01 1.20643690185419e-01 + 4.43822979334143e-01 1.19012214211741e-01 + 4.60825027599087e-01 1.17096430824897e-01 + 4.78180176231373e-01 1.14887296599190e-01 + 4.95890785853081e-01 1.12452966207322e-01 + 5.13949537326196e-01 1.09787047252637e-01 + 5.32343642071341e-01 1.06859196176221e-01 + 5.51070553747742e-01 1.03710967331665e-01 + 5.70123937401839e-01 1.00351455565678e-01 + 5.89495628773574e-01 9.67909361070087e-02 + 6.09171898570426e-01 9.30211098562286e-02 + 6.29138822745811e-01 8.90355090111987e-02 + 6.49394868003684e-01 8.49035724050775e-02 + 6.69928293397831e-01 8.06107601158379e-02 + 6.90722533013325e-01 7.61534793554206e-02 + 7.11772271356487e-01 7.15640092699005e-02 + 7.33060707027799e-01 6.68388174833136e-02 + 7.54571508751324e-01 6.19858692115997e-02 + 7.76286826841553e-01 5.69994231785712e-02 + 7.98189415948090e-01 5.18865779509044e-02 + 8.20260703237170e-01 4.66547433653687e-02 + 8.42482201370411e-01 4.13224819490564e-02 + 8.64845816185461e-01 3.59114363001708e-02 + 8.87320554539452e-01 3.04068317544367e-02 + 9.09898081718863e-01 2.48403197190891e-02 + 9.32544737844051e-01 1.92037035893727e-02 + 9.55244628007707e-01 1.31962135682704e-02 + 9.77960328149588e-01 6.92447736867692e-03 + 1.00000000000000e+00 5.33569410323788e-04 diff --git a/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF24_Coords.txt b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF24_Coords.txt new file mode 100644 index 00000000..dee2a673 --- /dev/null +++ b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF24_Coords.txt @@ -0,0 +1,208 @@ + 201 NumCoords ! The number of coordinates in the airfoil shape file (including an extra coordinate for airfoil reference). Set to zero if coordinates not included. +! ......... x-y coordinates are next if NumCoords > 0 ............. +! x-y coordinate of airfoil reference +! x/c y/c + 0.250000 0 +! coordinates of airfoil shape +! interpolation to 200 points +! x/c y/c + 1.00000000000000e+00 -7.50291333776672e-04 + 9.76298896194702e-01 2.32889115261073e-03 + 9.52696096636841e-01 4.94521028450639e-03 + 9.29060312605788e-01 7.15692894407718e-03 + 9.05417910316586e-01 8.89067899641578e-03 + 8.81816184123139e-01 9.89569835581813e-03 + 8.58317705959904e-01 9.84322267766306e-03 + 8.34983301808537e-01 9.04823588658875e-03 + 8.11873434560873e-01 7.18374392840931e-03 + 7.89043919534343e-01 4.37297375841967e-03 + 7.66539540795448e-01 7.44223479357781e-04 + 7.44381391909662e-01 -3.54660860602751e-03 + 7.22581240917263e-01 -8.35156649411918e-03 + 7.01137346622867e-01 -1.35373495193734e-02 + 6.80039693873756e-01 -1.89641771354476e-02 + 6.59290364533785e-01 -2.45571754348028e-02 + 6.38878859868852e-01 -3.02132879449722e-02 + 6.18795535800661e-01 -3.58428941592947e-02 + 5.99025214360609e-01 -4.13502377144402e-02 + 5.79571063345178e-01 -4.66989833430834e-02 + 5.60430857912260e-01 -5.18361266758138e-02 + 5.41600549487872e-01 -5.67126894278324e-02 + 5.23093012388221e-01 -6.13292557711388e-02 + 5.04909716783247e-01 -6.56538953621398e-02 + 4.87051293227111e-01 -6.96530548678958e-02 + 4.69524243044734e-01 -7.33080529423055e-02 + 4.52341821294675e-01 -7.66472468360973e-02 + 4.35508589614116e-01 -7.96544207222355e-02 + 4.19030914862448e-01 -8.23226920725703e-02 + 4.02916228417393e-01 -8.46623466695113e-02 + 3.87175637539370e-01 -8.67119738820041e-02 + 3.71811428132166e-01 -8.84606569575440e-02 + 3.56830409304917e-01 -8.99353602919689e-02 + 3.42236645717252e-01 -9.11689881156119e-02 + 3.28028443529475e-01 -9.21352973252990e-02 + 3.14207871794200e-01 -9.28394446226089e-02 + 3.00775731152437e-01 -9.33148765751533e-02 + 2.87731091983130e-01 -9.35649492324365e-02 + 2.75073270707374e-01 -9.35897732815692e-02 + 2.62799911559184e-01 -9.34332051784304e-02 + 2.50908328649408e-01 -9.30938200207195e-02 + 2.39395914296969e-01 -9.25789080830780e-02 + 2.28258324217990e-01 -9.19038525166016e-02 + 2.17490357613613e-01 -9.10978135960199e-02 + 2.07088466750961e-01 -9.01469095785202e-02 + 1.97047806459751e-01 -8.90697005309464e-02 + 1.87360260340612e-01 -8.78852780089872e-02 + 1.78018682210870e-01 -8.66086122363040e-02 + 1.69020258315682e-01 -8.52244126115397e-02 + 1.60353331264926e-01 -8.37720812851559e-02 + 1.52014939197557e-01 -8.22330718969560e-02 + 1.43987185788990e-01 -8.06620558758565e-02 + 1.36274091000982e-01 -7.90182608959080e-02 + 1.28862566102960e-01 -7.73292710854366e-02 + 1.21745655831401e-01 -7.55977296970018e-02 + 1.14917898957625e-01 -7.38189265766767e-02 + 1.08363637615901e-01 -7.20267149673762e-02 + 1.02080415985040e-01 -7.02081908521227e-02 + 9.60650562136330e-02 -6.83524876726988e-02 + 9.02979483004230e-02 -6.64992618936153e-02 + 8.47777986078614e-02 -6.46338463331624e-02 + 7.94941040279597e-02 -6.27654801484029e-02 + 7.44102991938022e-02 -6.08945434432346e-02 + 6.95582747844778e-02 -5.90057327945389e-02 + 6.49131793283190e-02 -5.71216563862163e-02 + 6.04794197269670e-02 -5.52290978859873e-02 + 5.62646886835696e-02 -5.33218521504249e-02 + 5.22507416096869e-02 -5.14208493808622e-02 + 4.84245433996503e-02 -4.95323182851412e-02 + 4.47904867206598e-02 -4.76449015546858e-02 + 4.13374558635882e-02 -4.57663829252569e-02 + 3.80650840253715e-02 -4.38944940923365e-02 + 3.49691116419480e-02 -4.20279518522186e-02 + 3.20400727373755e-02 -4.01712967041496e-02 + 2.92703341033774e-02 -3.83301218257238e-02 + 2.66462635908786e-02 -3.65121714900467e-02 + 2.41819941212201e-02 -3.47068073590117e-02 + 2.19143199986438e-02 -3.29088330701643e-02 + 1.97796258019261e-02 -3.11426553752093e-02 + 1.77718675728929e-02 -2.94033561455842e-02 + 1.58892791802320e-02 -2.76827467855728e-02 + 1.41231129715086e-02 -2.59874713046408e-02 + 1.24680257561555e-02 -2.43219224431366e-02 + 1.09259070704779e-02 -2.26820710355976e-02 + 9.49343298356482e-03 -2.10561306903018e-02 + 8.14503768413817e-03 -1.94635072722990e-02 + 6.90999917273266e-03 -1.78889094607232e-02 + 5.79390475471148e-03 -1.63307209071248e-02 + 4.78106804114271e-03 -1.47978940894094e-02 + 3.88016584757143e-03 -1.32873649605637e-02 + 3.08233798054177e-03 -1.18026200908121e-02 + 2.38686534170238e-03 -1.03450301564476e-02 + 1.78599805341179e-03 -8.92081233071476e-03 + 1.28652156378685e-03 -7.52634471004791e-03 + 8.83996769448488e-04 -6.16669016705767e-03 + 5.46612029292912e-04 -4.84894257335285e-03 + 3.01376049559927e-04 -3.56996967423148e-03 + 1.30154076571712e-04 -2.33432457843823e-03 + 4.21374163304318e-05 -1.14334359217422e-03 + 0.00000000000000e+00 0.00000000000000e+00 + 2.81157574964881e-05 1.14295937760577e-03 + 1.04621923266427e-04 2.33440626401102e-03 + 2.54739066947636e-04 3.57120735782472e-03 + 4.65849257103884e-04 4.85377645755166e-03 + 7.66296706792806e-04 6.17820210329396e-03 + 1.13400710680486e-03 7.54436835218198e-03 + 1.57970905045129e-03 8.95240763421855e-03 + 2.19446599887451e-03 1.03731283301651e-02 + 2.87705684559474e-03 1.18324568030195e-02 + 3.67789371859726e-03 1.33102740954264e-02 + 4.57036584246313e-03 1.48203416608747e-02 + 5.56967498060080e-03 1.63537813005310e-02 + 6.66759090523285e-03 1.79156766085822e-02 + 7.85649334745409e-03 1.95131911485843e-02 + 9.15255477687989e-03 2.11363600124788e-02 + 1.05445488424763e-02 2.27966579112874e-02 + 1.20486064407746e-02 2.44823719840950e-02 + 1.36603871932619e-02 2.61996974106957e-02 + 1.53821576127598e-02 2.79522040521000e-02 + 1.72090722971723e-02 2.97472094765997e-02 + 1.91651219523706e-02 3.15651260035317e-02 + 2.12426156558742e-02 3.34176370326924e-02 + 2.34511443758688e-02 3.52973320141773e-02 + 2.57904895361023e-02 3.72130957307203e-02 + 2.82626509750913e-02 3.91646919322919e-02 + 3.08759739857624e-02 4.11514060005145e-02 + 3.36299253040576e-02 4.31771896078588e-02 + 3.65354985842998e-02 4.52371794325495e-02 + 3.96008704268746e-02 4.73246766888027e-02 + 4.28321561070921e-02 4.94404029988426e-02 + 4.62242346874908e-02 5.16004112773017e-02 + 4.97958902647260e-02 5.37820404238713e-02 + 5.35528496536011e-02 5.59876066111493e-02 + 5.74940264314054e-02 5.82280097517281e-02 + 6.16289114941267e-02 6.04973177565880e-02 + 6.59549586653717e-02 6.28123067599801e-02 + 7.05011791699481e-02 6.51291026479873e-02 + 7.52646676807933e-02 6.74659569979716e-02 + 8.02411483868892e-02 6.98450349458632e-02 + 8.54541005536459e-02 7.22307435968477e-02 + 9.09077876598320e-02 7.46202759272474e-02 + 9.66055445093218e-02 7.70252439848328e-02 + 1.02556617968726e-01 7.94445037398437e-02 + 1.08769595464231e-01 8.18723919264446e-02 + 1.15251846243329e-01 8.43087989893419e-02 + 1.22017436032429e-01 8.67299569776199e-02 + 1.29067606508560e-01 8.91543819424277e-02 + 1.36410072520413e-01 9.15812636222036e-02 + 1.44057372467977e-01 9.39916412991629e-02 + 1.52018009642350e-01 9.63774884768607e-02 + 1.60301083370340e-01 9.87298228910894e-02 + 1.68915004119298e-01 1.01040503878498e-01 + 1.77863375679202e-01 1.03322385460583e-01 + 1.87155863329685e-01 1.05561389941643e-01 + 1.96799541214523e-01 1.07750710152026e-01 + 2.06809021346131e-01 1.09847473640509e-01 + 2.17187694050625e-01 1.11860752579225e-01 + 2.27942920264959e-01 1.13772677888835e-01 + 2.39080425704280e-01 1.15580120940451e-01 + 2.50602978823008e-01 1.17288028936626e-01 + 2.62523055501980e-01 1.18833856236034e-01 + 2.74840647475125e-01 1.20232024719622e-01 + 2.87562192937226e-01 1.21441226349321e-01 + 3.00690830602118e-01 1.22430852727519e-01 + 3.14227523639263e-01 1.23178402093805e-01 + 3.28171801048535e-01 1.23663484726724e-01 + 3.42521760498053e-01 1.23828016318311e-01 + 3.57273986043832e-01 1.23678074838371e-01 + 3.72422815778781e-01 1.23198599341217e-01 + 3.87965402200350e-01 1.22429097089126e-01 + 4.03897678601998e-01 1.21373131778580e-01 + 4.20216289788358e-01 1.20045527577897e-01 + 4.36918952632428e-01 1.18464558254558e-01 + 4.53998170716250e-01 1.16608654175239e-01 + 4.71445818375774e-01 1.14459171027755e-01 + 4.89262561234794e-01 1.12074715982259e-01 + 5.07441163553935e-01 1.09446574254448e-01 + 5.25971148178741e-01 1.06560361311888e-01 + 5.44848798428680e-01 1.03449434794008e-01 + 5.64066277235567e-01 1.00118102629513e-01 + 5.83615080942241e-01 9.65751507526858e-02 + 6.03485053765207e-01 9.28288280428212e-02 + 6.23663294928140e-01 8.88766391764726e-02 + 6.44143290404599e-01 8.47640847275778e-02 + 6.64912691365091e-01 8.04820587812154e-02 + 6.85957565742361e-01 7.60375257877561e-02 + 7.07269770163650e-01 7.14578896712954e-02 + 7.28832031023755e-01 6.67399716333503e-02 + 7.50627928640914e-01 6.18927779581912e-02 + 7.72638273090132e-01 5.69095365551616e-02 + 7.94845273313031e-01 5.17979358377091e-02 + 8.17229952512696e-01 4.65661010560639e-02 + 8.39774418012758e-01 4.12350839199444e-02 + 8.62464948057395e-01 3.58183297895103e-02 + 8.85273913513708e-01 3.03089834179839e-02 + 9.08187630633643e-01 2.47304583972593e-02 + 9.31177783406441e-01 1.90863321564750e-02 + 9.54226411846771e-01 1.31957781659379e-02 + 9.77294204499900e-01 7.13558621173920e-03 + 1.00000000000000e+00 9.69484227912823e-04 diff --git a/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF25_Coords.txt b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF25_Coords.txt new file mode 100644 index 00000000..f5baf458 --- /dev/null +++ b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF25_Coords.txt @@ -0,0 +1,208 @@ + 201 NumCoords ! The number of coordinates in the airfoil shape file (including an extra coordinate for airfoil reference). Set to zero if coordinates not included. +! ......... x-y coordinates are next if NumCoords > 0 ............. +! x-y coordinate of airfoil reference +! x/c y/c + 0.250000 0 +! coordinates of airfoil shape +! interpolation to 200 points +! x/c y/c + 1.00000000000000e+00 -1.09250671868000e-03 + 9.76115586099618e-01 2.09600510332978e-03 + 9.52288294552172e-01 4.81417885933177e-03 + 9.28450060797343e-01 7.11490117592222e-03 + 9.04619297601449e-01 8.92329765774539e-03 + 8.80834074284664e-01 9.95340950185301e-03 + 8.57151659839586e-01 9.92756319875484e-03 + 8.33630254563209e-01 9.17783270101517e-03 + 8.10328015134571e-01 7.42012067290446e-03 + 7.87300463622396e-01 4.77516783787571e-03 + 7.64592703953390e-01 1.32624859090481e-03 + 7.42228033108644e-01 -2.77682728463799e-03 + 7.20216772646893e-01 -7.37607048945225e-03 + 6.98563400687629e-01 -1.23524458090196e-02 + 6.77262887692173e-01 -1.75755523866722e-02 + 6.56316064999009e-01 -2.29614286738159e-02 + 6.35714570806867e-01 -2.84102836191219e-02 + 6.15449288352083e-01 -3.38290876998397e-02 + 5.95513325480546e-01 -3.91424755035297e-02 + 5.75907942700664e-01 -4.43068439562326e-02 + 5.56629760363534e-01 -4.92645154005323e-02 + 5.37682173510500e-01 -5.39873548651573e-02 + 5.19071820661838e-01 -5.84578413099440e-02 + 5.00801555954315e-01 -6.26495762564164e-02 + 4.82871601768206e-01 -6.65256315806630e-02 + 4.65290321806567e-01 -7.00771541943242e-02 + 4.48069107802193e-01 -7.33303008744292e-02 + 4.31210942377935e-01 -7.62613694929760e-02 + 4.14721717256527e-01 -7.88670112627226e-02 + 3.98609830485640e-01 -8.11674486204708e-02 + 3.82881803238740e-01 -8.31789010896421e-02 + 3.67540922501510e-01 -8.49011792837672e-02 + 3.52591959359744e-01 -8.63538669976877e-02 + 3.38038125513927e-01 -8.75591661511401e-02 + 3.23878337769632e-01 -8.84993826488772e-02 + 3.10114246734585e-01 -8.91848244796117e-02 + 2.96745918134662e-01 -8.96356484654719e-02 + 2.83772536979569e-01 -8.98560569285609e-02 + 2.71193048529533e-01 -8.98541970412896e-02 + 2.59004966514683e-01 -8.96641882545778e-02 + 2.47205169565799e-01 -8.92924468430343e-02 + 2.35790240472659e-01 -8.87473051941079e-02 + 2.24754947680772e-01 -8.80529555951448e-02 + 2.14094425301211e-01 -8.72214656839783e-02 + 2.03803579375793e-01 -8.62541002544239e-02 + 1.93875405543264e-01 -8.51751516327919e-02 + 1.84303408655320e-01 -8.39908637540001e-02 + 1.75080215317279e-01 -8.27132159406177e-02 + 1.66199793240435e-01 -8.13445725448274e-02 + 1.57653122663062e-01 -7.99033042566852e-02 + 1.49432819276280e-01 -7.83940014030634e-02 + 1.41527369025976e-01 -7.68397516570057e-02 + 1.33933094840571e-01 -7.52295246442809e-02 + 1.26640143243466e-01 -7.35770567956669e-02 + 1.19640559393263e-01 -7.18863418890472e-02 + 1.12927077813054e-01 -7.01581195662533e-02 + 1.06488519837237e-01 -6.84113181275732e-02 + 1.00316701895756e-01 -6.66480482070258e-02 + 9.44082133574360e-02 -6.48587314973944e-02 + 8.87499483874507e-02 -6.30623827083626e-02 + 8.33346753623294e-02 -6.12610269188888e-02 + 7.81562621654159e-02 -5.94517874653428e-02 + 7.31951432238743e-02 -5.76424972836634e-02 + 6.84577626403403e-02 -5.58286777757905e-02 + 6.39326342358596e-02 -5.40173864513933e-02 + 5.96152121769926e-02 -5.22094494493164e-02 + 5.55045079578264e-02 -5.03979483760663e-02 + 5.15876859053906e-02 -4.85965280700871e-02 + 4.78588835860377e-02 -4.68025488097465e-02 + 4.43151088293809e-02 -4.50134393598166e-02 + 4.09479814741917e-02 -4.32331507155101e-02 + 3.77544761371438e-02 -4.14613164257821e-02 + 3.47290964996220e-02 -3.96983685901773e-02 + 3.18646716164714e-02 -3.79460007064151e-02 + 2.91557807064150e-02 -3.62082493349325e-02 + 2.65916717593254e-02 -3.44893521422311e-02 + 2.41768614668749e-02 -3.27857249071581e-02 + 2.19169363744281e-02 -3.10958697248329e-02 + 1.97853574099944e-02 -2.94351217148795e-02 + 1.77809502328637e-02 -2.77959928991413e-02 + 1.59012923654057e-02 -2.61756147968822e-02 + 1.41377791124355e-02 -2.45798265623274e-02 + 1.24854340081653e-02 -2.30107015135764e-02 + 1.09463949529226e-02 -2.14628875680232e-02 + 9.51420326071247e-03 -1.99362443503988e-02 + 8.18367131774184e-03 -1.84317002704562e-02 + 6.95781355369571e-03 -1.69495477016988e-02 + 5.84461757031922e-03 -1.54828594722959e-02 + 4.83675987451319e-03 -1.40360192911298e-02 + 3.93148210889690e-03 -1.26118037509212e-02 + 3.12597705524147e-03 -1.12107577936507e-02 + 2.42827959498203e-03 -9.83080813631348e-03 + 1.81848159181735e-03 -8.48180028772974e-03 + 1.31026857339993e-03 -7.15931186006862e-03 + 8.94028566689473e-04 -5.86904696569661e-03 + 5.59139659541858e-04 -4.61467241237522e-03 + 3.08713803920484e-04 -3.39799797587375e-03 + 1.34284352600275e-04 -2.22180755581035e-03 + 4.38766782931077e-05 -1.08808364043886e-03 + 0.00000000000000e+00 0.00000000000000e+00 + 2.70754963215136e-05 1.08767660334744e-03 + 1.03580808069746e-04 2.22228516879441e-03 + 2.51928419550096e-04 3.40061010146026e-03 + 4.63659613080425e-04 4.62272156443479e-03 + 7.50030014672317e-04 5.88676081458818e-03 + 1.11249110649511e-03 7.19012596240712e-03 + 1.55894767722491e-03 8.53069940774572e-03 + 2.12648113335517e-03 9.89524770439861e-03 + 2.78122395867452e-03 1.12920178518460e-02 + 3.53349472781731e-03 1.27152234032320e-02 + 4.37986080892483e-03 1.41682764668305e-02 + 5.32108740225112e-03 1.56504595401408e-02 + 6.35403104634295e-03 1.71645723270603e-02 + 7.48065465647005e-03 1.87111343722309e-02 + 8.70798790603196e-03 2.02868357356723e-02 + 1.00326625323290e-02 2.18967960271385e-02 + 1.14615517896570e-02 2.35376948845036e-02 + 1.29908498121995e-02 2.52156066282122e-02 + 1.46285017870635e-02 2.69284106702504e-02 + 1.63762840007771e-02 2.86766604856462e-02 + 1.82437127611806e-02 3.04560704781735e-02 + 2.02283271437812e-02 3.22731904280343e-02 + 2.23410892379826e-02 3.41200707129672e-02 + 2.45803161096591e-02 3.60061322399834e-02 + 2.69523034357121e-02 3.79258490183542e-02 + 2.94661214249216e-02 3.98790227559557e-02 + 3.21182316854737e-02 4.18723073706309e-02 + 3.49189765158157e-02 4.39025161395751e-02 + 3.78764907558025e-02 4.59628851663624e-02 + 4.09963031658456e-02 4.80556676923546e-02 + 4.42775927892050e-02 5.01900205707697e-02 + 4.77343365858657e-02 5.23520241988731e-02 + 5.13731297355052e-02 5.45423734775189e-02 + 5.51950546654045e-02 5.67687018233320e-02 + 5.92113866358186e-02 5.90218736527301e-02 + 6.34234392442166e-02 6.13116302117422e-02 + 6.78462003333466e-02 6.36214314140050e-02 + 7.24854173464343e-02 6.59533657552206e-02 + 7.73419721841157e-02 6.83186401819959e-02 + 8.24324258544088e-02 7.06971481688955e-02 + 8.77613607346135e-02 7.30926428047549e-02 + 9.33346253668055e-02 7.55076582271502e-02 + 9.91628221387800e-02 7.79350885797270e-02 + 1.05254564598752e-01 8.03695380742510e-02 + 1.11616753158002e-01 8.28125781644698e-02 + 1.18259294307182e-01 8.52558088653510e-02 + 1.25189263783572e-01 8.76985152086404e-02 + 1.32415679289748e-01 9.01369747472587e-02 + 1.39947873838956e-01 9.25638030881446e-02 + 1.47794845481183e-01 9.49707607832480e-02 + 1.55965915271520e-01 9.73499622034032e-02 + 1.64469189511735e-01 9.96967278841057e-02 + 1.73311416702080e-01 1.02010530578746e-01 + 1.82503742461270e-01 1.04273623478212e-01 + 1.92050672615684e-01 1.06491541481398e-01 + 2.01966200947807e-01 1.08628345168654e-01 + 2.12256126598972e-01 1.10681929211142e-01 + 2.22927191842667e-01 1.12642214263348e-01 + 2.33987552164155e-01 1.14491142152048e-01 + 2.45440161850974e-01 1.16234688095526e-01 + 2.57296008031495e-01 1.17825202458106e-01 + 2.69556869203747e-01 1.19267427279133e-01 + 2.82229070262522e-01 1.20524379694892e-01 + 2.95316275100028e-01 1.21569011458766e-01 + 3.08820531899773e-01 1.22372406982529e-01 + 3.22741461950530e-01 1.22915930928339e-01 + 3.37078134209340e-01 1.23149875849477e-01 + 3.51826981727722e-01 1.23062131822088e-01 + 3.66983039246985e-01 1.22645337613189e-01 + 3.82543070599223e-01 1.21930860322884e-01 + 3.98503391798556e-01 1.20928153680211e-01 + 4.14860961126985e-01 1.19652845240075e-01 + 4.31612326060530e-01 1.18111343121154e-01 + 4.48752327492312e-01 1.16301638158787e-01 + 4.66272601249854e-01 1.14199654104434e-01 + 4.84172419107913e-01 1.11855636518184e-01 + 5.02444493519843e-01 1.09258193501888e-01 + 5.21080236029992e-01 1.06406605973784e-01 + 5.40074886324364e-01 1.03326688418026e-01 + 5.59419655929053e-01 1.00019465978113e-01 + 5.79105612175721e-01 9.64916235087976e-02 + 5.99125173361441e-01 9.27647911198193e-02 + 6.19466430557399e-01 8.88409323564860e-02 + 6.40119041978738e-01 8.47390121899819e-02 + 6.61070257644903e-01 8.04603243420791e-02 + 6.82307901055849e-01 7.60197144231869e-02 + 7.03821798847536e-01 7.14430901975401e-02 + 7.25594294352276e-01 6.67273876453086e-02 + 7.47609060933277e-01 6.18819437827459e-02 + 7.69845737824426e-01 5.68996656088332e-02 + 7.92286051630428e-01 5.17884210392101e-02 + 8.14910827049322e-01 4.65565586752961e-02 + 8.37702906504111e-01 4.12259060670082e-02 + 8.60644007466582e-01 3.58073758391948e-02 + 8.83708956400804e-01 3.02965383060978e-02 + 9.06880276867715e-01 2.47142694962048e-02 + 9.30133788123677e-01 1.90677931913939e-02 + 9.53449456906722e-01 1.32665027689235e-02 + 9.76786262644257e-01 7.36258542738043e-03 + 1.00000000000000e+00 1.36768088735877e-03 diff --git a/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF26_Coords.txt b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF26_Coords.txt new file mode 100644 index 00000000..cf7fc7ad --- /dev/null +++ b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF26_Coords.txt @@ -0,0 +1,208 @@ + 201 NumCoords ! The number of coordinates in the airfoil shape file (including an extra coordinate for airfoil reference). Set to zero if coordinates not included. +! ......... x-y coordinates are next if NumCoords > 0 ............. +! x-y coordinate of airfoil reference +! x/c y/c + 0.250000 0 +! coordinates of airfoil shape +! interpolation to 200 points +! x/c y/c + 1.00000000000000e+00 -1.24163918250367e-03 + 9.76041165887563e-01 1.99488268803741e-03 + 9.52121914098850e-01 4.75706252222044e-03 + 9.28199957236603e-01 7.09542956274019e-03 + 9.04291190262318e-01 8.93443745793852e-03 + 8.80430343444036e-01 9.96657729426452e-03 + 8.56672689113696e-01 9.94290435584814e-03 + 8.33075425877888e-01 9.19689625764953e-03 + 8.09695700165266e-01 7.47347691185626e-03 + 7.86588885771507e-01 4.89111440127801e-03 + 7.63799981052509e-01 1.51070336812985e-03 + 7.41353018207342e-01 -2.52044512396319e-03 + 7.19257743648676e-01 -7.04038680187796e-03 + 6.97520950922480e-01 -1.19358851549070e-02 + 6.76139778430185e-01 -1.70807096849569e-02 + 6.55114191085606e-01 -2.23867022793893e-02 + 6.34437029834687e-01 -2.77559055040500e-02 + 6.14099171583599e-01 -3.30936716419077e-02 + 5.94097092702040e-01 -3.83329090713677e-02 + 5.74431276878783e-01 -4.34270288627529e-02 + 5.55097922205893e-01 -4.83165117769746e-02 + 5.36103244219295e-01 -5.29813461185869e-02 + 5.17451514118577e-01 -5.73969020907143e-02 + 4.99146144876149e-01 -6.15389789381977e-02 + 4.81187008959400e-01 -6.53691205567300e-02 + 4.63583334863196e-01 -6.88825029007271e-02 + 4.46345674250821e-01 -7.21042694778078e-02 + 4.29476426936704e-01 -7.50078286995993e-02 + 4.12981165598887e-01 -7.75910433182066e-02 + 3.96868697220895e-01 -7.98780646047934e-02 + 3.81143737274277e-01 -8.18762285984978e-02 + 3.65809950832190e-01 -8.35894755418217e-02 + 3.50871346715946e-01 -8.50344502846749e-02 + 3.36330856482784e-01 -8.62291005970239e-02 + 3.22187680974826e-01 -8.71590314211491e-02 + 3.08443381198299e-01 -8.78366569779970e-02 + 2.95097824515779e-01 -8.82768172546241e-02 + 2.82150316172696e-01 -8.84841421890272e-02 + 2.69599713195053e-01 -8.84700415928376e-02 + 2.57443538674293e-01 -8.82648900755557e-02 + 2.45678503760535e-01 -8.78783328013873e-02 + 2.34300892069519e-01 -8.73191978590562e-02 + 2.23305176083759e-01 -8.66151143715721e-02 + 2.12686475906400e-01 -8.57717042278548e-02 + 2.02439201431732e-01 -8.47960575058360e-02 + 1.92555334399891e-01 -8.37147804336106e-02 + 1.83029072759030e-01 -8.25291243560209e-02 + 1.73852988185549e-01 -8.12499391500962e-02 + 1.65019713285519e-01 -7.98863532611348e-02 + 1.56521149653515e-01 -7.84487425858802e-02 + 1.48348326905127e-01 -7.69504193661685e-02 + 1.40492169632055e-01 -7.54025801721342e-02 + 1.32945934195466e-01 -7.38053647018080e-02 + 1.25701000521494e-01 -7.21672889164535e-02 + 1.18749063872964e-01 -7.04928479452887e-02 + 1.12082069469409e-01 -6.87847420009533e-02 + 1.05690639166719e-01 -6.70564170338887e-02 + 9.95644793751720e-02 -6.53155594973088e-02 + 9.36997891046597e-02 -6.35528503057422e-02 + 8.80860404700645e-02 -6.17798179936638e-02 + 8.27138402760154e-02 -6.00046280095742e-02 + 7.75786796919451e-02 -5.82199952095701e-02 + 7.26702775903076e-02 -5.64364109081874e-02 + 6.79824154250675e-02 -5.46532131450536e-02 + 6.35091047142614e-02 -5.28689233118743e-02 + 5.92419326453291e-02 -5.10893765254210e-02 + 5.51761610142073e-02 -4.93108527891892e-02 + 5.13012904354392e-02 -4.75441103336549e-02 + 4.76145565870374e-02 -4.57830799218584e-02 + 4.41097775457074e-02 -4.40286611417737e-02 + 4.07797547228364e-02 -4.22832639538696e-02 + 3.76203144073222e-02 -4.05471915450099e-02 + 3.46254260858043e-02 -3.88215755752492e-02 + 3.17889101119942e-02 -3.71070792104368e-02 + 2.91063013242030e-02 -3.54070623086104e-02 + 2.65680917385227e-02 -3.37242560099722e-02 + 2.41746444824902e-02 -3.20578976536326e-02 + 2.19171444247013e-02 -3.04080975483655e-02 + 1.97858149698125e-02 -2.87865206302891e-02 + 1.77816785975911e-02 -2.71845498672619e-02 + 1.59022597396959e-02 -2.56014672844354e-02 + 1.41389646872167e-02 -2.40428780632352e-02 + 1.24868469400250e-02 -2.25098697316461e-02 + 1.09480652882895e-02 -2.09965445874096e-02 + 9.51590058520777e-03 -1.95072970846173e-02 + 8.19359579424781e-03 -1.80358499675050e-02 + 6.97242094431141e-03 -1.65886214694131e-02 + 5.86117299541770e-03 -1.51566425360256e-02 + 4.85595721623195e-03 -1.37425320553921e-02 + 3.94940941742267e-03 -1.23512986917568e-02 + 3.14133805635955e-03 -1.09822611963997e-02 + 2.44321685058300e-03 -9.63205407941857e-03 + 1.83022786901874e-03 -8.31193681735096e-03 + 1.31884419349740e-03 -7.01717270777278e-03 + 8.97352130663886e-04 -5.75368875832799e-03 + 5.63740815773768e-04 -4.52380901007206e-03 + 3.11436976892490e-04 -3.33125476138120e-03 + 1.35836193808489e-04 -2.17811670838639e-03 + 4.45280502729537e-05 -1.06661993857544e-03 + 0.00000000000000e+00 0.00000000000000e+00 + 2.66760054509128e-05 1.06620363196370e-03 + 1.03135511949883e-04 2.17873971903504e-03 + 2.50714385917578e-04 3.33437480200911e-03 + 4.62713811117844e-04 4.53305150068868e-03 + 7.43003875184307e-04 5.77372654297466e-03 + 1.10319761909825e-03 7.05282637820245e-03 + 1.54998013794877e-03 8.36733050300788e-03 + 2.09725226970234e-03 9.71027755670584e-03 + 2.74048621866142e-03 1.10830229161061e-02 + 3.47313095950444e-03 1.24853542942127e-02 + 4.30082217565610e-03 1.39166476275545e-02 + 5.21857196014794e-03 1.53794131710022e-02 + 6.22534316879645e-03 1.68755017759930e-02 + 7.32700741881788e-03 1.84027736911195e-02 + 8.52685165419718e-03 1.99605923185556e-02 + 9.82457508956703e-03 2.15515967524936e-02 + 1.12235177290181e-02 2.31756834085188e-02 + 1.27200503919435e-02 2.48389080154999e-02 + 1.43242279905998e-02 2.65369959399126e-02 + 1.60404245440130e-02 2.82678634249202e-02 + 1.78725008542331e-02 3.00332073110525e-02 + 1.98202147599872e-02 3.18374092114472e-02 + 2.18950460972363e-02 3.36723552878899e-02 + 2.40945084991586e-02 3.55478542511501e-02 + 2.64266594338935e-02 3.74562543671355e-02 + 2.89010475331631e-02 3.93973576550753e-02 + 3.15128856164724e-02 4.13789637240956e-02 + 3.42721423161374e-02 4.33986437239279e-02 + 3.71869766220148e-02 4.54495802606190e-02 + 4.02627031087678e-02 4.75346101784617e-02 + 4.35002150116920e-02 4.96601391986086e-02 + 4.69116164095437e-02 5.18156791609964e-02 + 5.05037836700218e-02 5.40013488484752e-02 + 5.42786678950318e-02 5.62234865342880e-02 + 5.82483001631071e-02 5.84716108883904e-02 + 6.24154978875846e-02 6.07527350834376e-02 + 6.67896743600186e-02 6.30611281243319e-02 + 7.13799999231155e-02 6.53925012153297e-02 + 7.61894222215938e-02 6.77537053720447e-02 + 8.12317662654453e-02 7.01307269242542e-02 + 8.65117557737097e-02 7.25279882775677e-02 + 9.20362184425747e-02 7.49454680746529e-02 + 9.78162759593724e-02 7.73748306064237e-02 + 1.03860552928939e-01 7.98107486389235e-02 + 1.10175778191298e-01 8.22554075072582e-02 + 1.16770214549517e-01 8.47058953467228e-02 + 1.23653203755665e-01 8.71546056154831e-02 + 1.30834337594950e-01 8.95968004923253e-02 + 1.38321670606146e-01 9.20292431191944e-02 + 1.46124389981669e-01 9.44436195002828e-02 + 1.54251904677806e-01 9.68324582790219e-02 + 1.62712200809751e-01 9.91923751629681e-02 + 1.71513312218537e-01 1.01517930059788e-01 + 1.80666845834493e-01 1.03789912148757e-01 + 1.90176370985942e-01 1.06018468666417e-01 + 2.00055657032727e-01 1.08170258618851e-01 + 2.10311372495842e-01 1.10238994003200e-01 + 2.20950065131051e-01 1.12217532980930e-01 + 2.31980866532305e-01 1.14082146312415e-01 + 2.43406769821147e-01 1.15839163095632e-01 + 2.55238147077280e-01 1.17446579677784e-01 + 2.67477513281741e-01 1.18905422327083e-01 + 2.80131073498889e-01 1.20180419750751e-01 + 2.93202720534022e-01 1.21245816208447e-01 + 3.06694896295832e-01 1.22070353231193e-01 + 3.20607263770737e-01 1.22636054133308e-01 + 3.34939268318345e-01 1.22896410171916e-01 + 3.49687302556342e-01 1.22832514196396e-01 + 3.64846676687070e-01 1.22439952772840e-01 + 3.80414003309436e-01 1.21746813551104e-01 + 3.96385756696833e-01 1.20764922463268e-01 + 4.12759002166226e-01 1.19510124555119e-01 + 4.29529884389691e-01 1.17984334619021e-01 + 4.46694073835668e-01 1.16192944649426e-01 + 4.64243196738119e-01 1.14110111055027e-01 + 4.82175957113290e-01 1.11782567369759e-01 + 5.00485020623298e-01 1.09197665297171e-01 + 5.19162565566196e-01 1.06360394677582e-01 + 5.38203389191021e-01 1.03293317692501e-01 + 5.57598376049888e-01 9.99962209759983e-02 + 5.77338386735964e-01 9.64747451695822e-02 + 5.97416810267783e-01 9.27560007851153e-02 + 6.17822173815498e-01 8.88440305009192e-02 + 6.38542633624223e-01 8.47454500445900e-02 + 6.59565297378976e-01 8.04670393872135e-02 + 6.80878616121945e-01 7.60267543210821e-02 + 7.02471652655181e-01 7.14503788937509e-02 + 7.24326595397154e-01 6.67348588383987e-02 + 7.46427190977622e-01 6.18895589890343e-02 + 7.68752587046382e-01 5.69073596180092e-02 + 7.91284306570890e-01 5.17961434205325e-02 + 8.14003121917812e-01 4.65642776255388e-02 + 8.36892227450033e-01 4.12336544355374e-02 + 8.59931497183523e-01 3.58149763309393e-02 + 8.83096691520270e-01 3.03040139923268e-02 + 9.06368918443855e-01 2.47214332231998e-02 + 9.29725626335315e-01 1.90747607002302e-02 + 9.53145857383183e-01 1.33087425250220e-02 + 9.76587861324942e-01 7.46542536535991e-03 + 1.00000000000000e+00 1.53835660395088e-03 diff --git a/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF27_Coords.txt b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF27_Coords.txt new file mode 100644 index 00000000..a8559b09 --- /dev/null +++ b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF27_Coords.txt @@ -0,0 +1,208 @@ + 201 NumCoords ! The number of coordinates in the airfoil shape file (including an extra coordinate for airfoil reference). Set to zero if coordinates not included. +! ......... x-y coordinates are next if NumCoords > 0 ............. +! x-y coordinate of airfoil reference +! x/c y/c + 0.250000 0 +! coordinates of airfoil shape +! interpolation to 200 points +! x/c y/c + 1.00000000000000e+00 -1.24164223325347e-03 + 9.76041164392396e-01 1.99488062082566e-03 + 9.52121910751731e-01 4.75706135335948e-03 + 9.28199952199219e-01 7.09542915865422e-03 + 9.04291183649571e-01 8.93443767118390e-03 + 8.80430335305919e-01 9.96657750751068e-03 + 8.56672679460919e-01 9.94290456909515e-03 + 8.33075414701384e-01 9.19689647089799e-03 + 8.09695687435274e-01 7.47347776900502e-03 + 7.86588871455130e-01 4.89111649401108e-03 + 7.63799965113471e-01 1.51070681640460e-03 + 7.41353000623285e-01 -2.52044025059049e-03 + 7.19257724385752e-01 -7.04038035491660e-03 + 6.97520929992240e-01 -1.19358771025367e-02 + 6.76139755888505e-01 -1.70807000809784e-02 + 6.55114166969036e-01 -2.23866910906930e-02 + 6.34437004205735e-01 -2.77558927368869e-02 + 6.14099144503465e-01 -3.30936572688430e-02 + 5.94097064299627e-01 -3.83328932311329e-02 + 5.74431247267374e-01 -4.34270116338703e-02 + 5.55097891490535e-01 -4.83164932012163e-02 + 5.36103212560625e-01 -5.29813263991864e-02 + 5.17451481630547e-01 -5.73968812892901e-02 + 4.99146111683925e-01 -6.15389571602501e-02 + 4.81186975180132e-01 -6.53690978763222e-02 + 4.63583300631990e-01 -6.88824794729917e-02 + 4.46345639685456e-01 -7.21042454369658e-02 + 4.29476392143564e-01 -7.50078041225779e-02 + 4.12981130677270e-01 -7.75910183051978e-02 + 3.96868662278405e-01 -7.98780393343755e-02 + 3.81143702382537e-01 -8.18762030718283e-02 + 3.65809916070270e-01 -8.35894498418953e-02 + 3.50871312147949e-01 -8.50344244357429e-02 + 3.36330822167539e-01 -8.62290745383426e-02 + 3.22187646977060e-01 -8.71590051574009e-02 + 3.08443347581371e-01 -8.78366305562361e-02 + 2.95097791339595e-01 -8.82767906155356e-02 + 2.82150283499973e-01 -8.84841152823162e-02 + 2.69599681087069e-01 -8.84700144337475e-02 + 2.57443507192848e-01 -8.82648626051867e-02 + 2.45678472964112e-01 -8.78783050259134e-02 + 2.34300862010750e-01 -8.73191697949781e-02 + 2.23305146809674e-01 -8.66150861037270e-02 + 2.12686447462944e-01 -8.57716757140843e-02 + 2.02439173855586e-01 -8.47960288193625e-02 + 1.92555307706631e-01 -8.37147516939257e-02 + 1.83029046978344e-01 -8.25290955835651e-02 + 1.73852963346223e-01 -8.12499103431124e-02 + 1.65019689389359e-01 -7.98863245514951e-02 + 1.56521126720043e-01 -7.84487139477401e-02 + 1.48348304923117e-01 -7.69503909453266e-02 + 1.40492148638460e-01 -7.54025518805833e-02 + 1.32945914165942e-01 -7.38053366709304e-02 + 1.25700981456047e-01 -7.21672611749456e-02 + 1.18749045764871e-01 -7.04928205316870e-02 + 1.12082052295785e-01 -6.87847149917338e-02 + 1.05690622940757e-01 -6.70563903986223e-02 + 9.95644640688240e-02 -6.53155333147837e-02 + 9.36997746804533e-02 -6.35528246583057e-02 + 8.80860269419856e-02 -6.17797928182627e-02 + 8.27138276159543e-02 -6.00046033630738e-02 + 7.75786679035966e-02 -5.82199710630611e-02 + 7.26702668766427e-02 -5.64363872841197e-02 + 6.79824057221827e-02 -5.46531901393429e-02 + 6.35090960690899e-02 -5.28689008362057e-02 + 5.92419250258708e-02 -5.10893545882387e-02 + 5.51761543119222e-02 -4.93108314830338e-02 + 5.13012845894761e-02 -4.75440896934531e-02 + 4.76145515997845e-02 -4.57830599145488e-02 + 4.41097733544431e-02 -4.40286418035125e-02 + 4.07797512889574e-02 -4.22832452899324e-02 + 3.76203116687853e-02 -4.05471735735779e-02 + 3.46254239696624e-02 -3.88215583285753e-02 + 3.17889085655347e-02 -3.71070627007449e-02 + 2.91063003142196e-02 -3.54070465342894e-02 + 2.65680912572024e-02 -3.37242409387003e-02 + 2.41746444372365e-02 -3.20578833095496e-02 + 2.19171444247057e-02 -3.04080839884921e-02 + 1.97858149698170e-02 -2.87865078379770e-02 + 1.77816785975956e-02 -2.71845378027204e-02 + 1.59022597397006e-02 -2.56014559510294e-02 + 1.41389646872214e-02 -2.40428674601252e-02 + 1.24868469400299e-02 -2.25098598379508e-02 + 1.09480652882944e-02 -2.09965353712404e-02 + 9.51590058521273e-03 -1.95072886041607e-02 + 8.19359596476239e-03 -1.80358421377615e-02 + 6.97242121388991e-03 -1.65886143273830e-02 + 5.86117330807756e-03 -1.51566360782969e-02 + 4.85595758514205e-03 -1.37425262435773e-02 + 3.94940976333073e-03 -1.23512935315688e-02 + 3.14133835342164e-03 -1.09822566687452e-02 + 2.44321714150649e-03 -9.63205013980954e-03 + 1.83022809796061e-03 -8.31193344939125e-03 + 1.31884436057794e-03 -7.01716988880847e-03 + 8.97352193736273e-04 -5.75368646998309e-03 + 5.63740905842356e-04 -4.52380720725293e-03 + 3.11437030347409e-04 -3.33125343689109e-03 + 1.35836224347021e-04 -2.17811584123553e-03 + 4.45280630750671e-05 -1.06661951254253e-03 + 0.00000000000000e+00 0.00000000000000e+00 + 2.66759975469128e-05 1.06620320574453e-03 + 1.03135502882502e-04 2.17873885472331e-03 + 2.50714361136359e-04 3.33437348745562e-03 + 4.62713791811825e-04 4.53304972124580e-03 + 7.43003731765193e-04 5.77372430028259e-03 + 1.10319742939756e-03 7.05282365458086e-03 + 1.54997995490141e-03 8.36732726269284e-03 + 2.09725167376054e-03 9.71027388884010e-03 + 2.74048539040992e-03 1.10830187729024e-02 + 3.47312973743479e-03 1.24853497385656e-02 + 4.30082057862358e-03 1.39166426421534e-02 + 5.21856989199968e-03 1.53794078029284e-02 + 6.22534057591764e-03 1.68754960531490e-02 + 7.32700432621982e-03 1.84027675881834e-02 + 8.52684801153103e-03 1.99605858637636e-02 + 9.82457090745577e-03 2.15515899247781e-02 + 1.12235129483028e-02 2.31756762504219e-02 + 1.27200449567995e-02 2.48389005693531e-02 + 1.43242218865420e-02 2.65369882056060e-02 + 1.60404178082626e-02 2.82678553499417e-02 + 1.78724934115684e-02 3.00331989618528e-02 + 1.98202065802740e-02 3.18374006104675e-02 + 2.18950371605342e-02 3.36723464545640e-02 + 2.40944987682683e-02 3.55478452136134e-02 + 2.64266489071067e-02 3.74562451109318e-02 + 2.89010362193680e-02 3.93973481646352e-02 + 3.15128734993139e-02 4.13789540071277e-02 + 3.42721293711695e-02 4.33986338037802e-02 + 3.71869628254960e-02 4.54495701594197e-02 + 4.02626884327817e-02 4.75345999298599e-02 + 4.35001994625931e-02 4.96601287812404e-02 + 4.69115999564798e-02 5.18156686218105e-02 + 5.05037662874084e-02 5.40013382232845e-02 + 5.42786495746735e-02 5.62234758330505e-02 + 5.82482809121614e-02 5.84716000937855e-02 + 6.24154777430842e-02 6.07527241240193e-02 + 6.67896532476333e-02 6.30611171442784e-02 + 7.13799778368031e-02 6.53924902316809e-02 + 7.61893991966636e-02 6.77536943148228e-02 + 8.12317422826271e-02 7.01307158448530e-02 + 8.65117308166364e-02 7.25279772295263e-02 + 9.20361925143298e-02 7.49454570665521e-02 + 9.78162490733068e-02 7.73748196288702e-02 + 1.03860525098628e-01 7.98107376836716e-02 + 1.10175749426971e-01 8.22553965780306e-02 + 1.16770184828620e-01 8.47058845532950e-02 + 1.23653173100621e-01 8.71545949342700e-02 + 1.30834306039958e-01 8.95967898803351e-02 + 1.38321638159842e-01 9.20292326136635e-02 + 1.46124356656426e-01 9.44436091370127e-02 + 1.54251870487751e-01 9.68324481019705e-02 + 1.62712165766615e-01 9.91923652415109e-02 + 1.71513276359922e-01 1.01517920367561e-01 + 1.80666809206519e-01 1.03789902629961e-01 + 1.90176333616483e-01 1.06018459355824e-01 + 2.00055618945293e-01 1.08170249602257e-01 + 2.10311333730825e-01 1.10238985284240e-01 + 2.20950025725240e-01 1.12217524621099e-01 + 2.31980826542045e-01 1.14082138261491e-01 + 2.43406729303366e-01 1.15839155310084e-01 + 2.55238106076494e-01 1.17446572225308e-01 + 2.67477471857320e-01 1.18905415201973e-01 + 2.80131031707401e-01 1.20180412981259e-01 + 2.93202678436719e-01 1.21245809848125e-01 + 3.06694853961626e-01 1.22070347287731e-01 + 3.20607221269401e-01 1.22636048627399e-01 + 3.34939225727116e-01 1.22896405187495e-01 + 3.49687259951759e-01 1.22832509683795e-01 + 3.64846634151165e-01 1.22439948740756e-01 + 3.80413960921238e-01 1.21746809942571e-01 + 3.96385714538567e-01 1.20764919268824e-01 + 4.12758960322157e-01 1.19510121769152e-01 + 4.29529842936380e-01 1.17984332147218e-01 + 4.46694032865700e-01 1.16192942543521e-01 + 4.64243156344356e-01 1.14110109333428e-01 + 4.82175917377177e-01 1.11782565979692e-01 + 5.00484981625201e-01 1.09197664159710e-01 + 5.19162527401886e-01 1.06360393829411e-01 + 5.38203351947280e-01 1.03293317103930e-01 + 5.57598339807246e-01 9.99962205928791e-02 + 5.77338351570623e-01 9.64747449157602e-02 + 5.97416776275050e-01 9.27560006949552e-02 + 6.17822141099620e-01 8.88440306520127e-02 + 6.38542602259551e-01 8.47454502578335e-02 + 6.59565267437110e-01 8.04670396004571e-02 + 6.80878587686638e-01 7.60267545343259e-02 + 7.02471625795160e-01 7.14503791069948e-02 + 7.24326570178040e-01 6.67348590516426e-02 + 7.46427167466697e-01 6.18895592022783e-02 + 7.68752565300964e-01 5.69073598312532e-02 + 7.91284286644164e-01 5.17961436337766e-02 + 8.14003103862062e-01 4.65642778387828e-02 + 8.36892211324902e-01 4.12336546487814e-02 + 8.59931483011660e-01 3.58149765441833e-02 + 8.83096679342750e-01 3.03040142055707e-02 + 9.06368908273977e-01 2.47214334364437e-02 + 9.29725618218844e-01 1.90747609134739e-02 + 9.53145851346865e-01 1.33087434425404e-02 + 9.76587857380671e-01 7.46542748662253e-03 + 1.00000000000000e+00 1.53836008119114e-03 diff --git a/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF28_Coords.txt b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF28_Coords.txt new file mode 100644 index 00000000..a8559b09 --- /dev/null +++ b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF28_Coords.txt @@ -0,0 +1,208 @@ + 201 NumCoords ! The number of coordinates in the airfoil shape file (including an extra coordinate for airfoil reference). Set to zero if coordinates not included. +! ......... x-y coordinates are next if NumCoords > 0 ............. +! x-y coordinate of airfoil reference +! x/c y/c + 0.250000 0 +! coordinates of airfoil shape +! interpolation to 200 points +! x/c y/c + 1.00000000000000e+00 -1.24164223325347e-03 + 9.76041164392396e-01 1.99488062082566e-03 + 9.52121910751731e-01 4.75706135335948e-03 + 9.28199952199219e-01 7.09542915865422e-03 + 9.04291183649571e-01 8.93443767118390e-03 + 8.80430335305919e-01 9.96657750751068e-03 + 8.56672679460919e-01 9.94290456909515e-03 + 8.33075414701384e-01 9.19689647089799e-03 + 8.09695687435274e-01 7.47347776900502e-03 + 7.86588871455130e-01 4.89111649401108e-03 + 7.63799965113471e-01 1.51070681640460e-03 + 7.41353000623285e-01 -2.52044025059049e-03 + 7.19257724385752e-01 -7.04038035491660e-03 + 6.97520929992240e-01 -1.19358771025367e-02 + 6.76139755888505e-01 -1.70807000809784e-02 + 6.55114166969036e-01 -2.23866910906930e-02 + 6.34437004205735e-01 -2.77558927368869e-02 + 6.14099144503465e-01 -3.30936572688430e-02 + 5.94097064299627e-01 -3.83328932311329e-02 + 5.74431247267374e-01 -4.34270116338703e-02 + 5.55097891490535e-01 -4.83164932012163e-02 + 5.36103212560625e-01 -5.29813263991864e-02 + 5.17451481630547e-01 -5.73968812892901e-02 + 4.99146111683925e-01 -6.15389571602501e-02 + 4.81186975180132e-01 -6.53690978763222e-02 + 4.63583300631990e-01 -6.88824794729917e-02 + 4.46345639685456e-01 -7.21042454369658e-02 + 4.29476392143564e-01 -7.50078041225779e-02 + 4.12981130677270e-01 -7.75910183051978e-02 + 3.96868662278405e-01 -7.98780393343755e-02 + 3.81143702382537e-01 -8.18762030718283e-02 + 3.65809916070270e-01 -8.35894498418953e-02 + 3.50871312147949e-01 -8.50344244357429e-02 + 3.36330822167539e-01 -8.62290745383426e-02 + 3.22187646977060e-01 -8.71590051574009e-02 + 3.08443347581371e-01 -8.78366305562361e-02 + 2.95097791339595e-01 -8.82767906155356e-02 + 2.82150283499973e-01 -8.84841152823162e-02 + 2.69599681087069e-01 -8.84700144337475e-02 + 2.57443507192848e-01 -8.82648626051867e-02 + 2.45678472964112e-01 -8.78783050259134e-02 + 2.34300862010750e-01 -8.73191697949781e-02 + 2.23305146809674e-01 -8.66150861037270e-02 + 2.12686447462944e-01 -8.57716757140843e-02 + 2.02439173855586e-01 -8.47960288193625e-02 + 1.92555307706631e-01 -8.37147516939257e-02 + 1.83029046978344e-01 -8.25290955835651e-02 + 1.73852963346223e-01 -8.12499103431124e-02 + 1.65019689389359e-01 -7.98863245514951e-02 + 1.56521126720043e-01 -7.84487139477401e-02 + 1.48348304923117e-01 -7.69503909453266e-02 + 1.40492148638460e-01 -7.54025518805833e-02 + 1.32945914165942e-01 -7.38053366709304e-02 + 1.25700981456047e-01 -7.21672611749456e-02 + 1.18749045764871e-01 -7.04928205316870e-02 + 1.12082052295785e-01 -6.87847149917338e-02 + 1.05690622940757e-01 -6.70563903986223e-02 + 9.95644640688240e-02 -6.53155333147837e-02 + 9.36997746804533e-02 -6.35528246583057e-02 + 8.80860269419856e-02 -6.17797928182627e-02 + 8.27138276159543e-02 -6.00046033630738e-02 + 7.75786679035966e-02 -5.82199710630611e-02 + 7.26702668766427e-02 -5.64363872841197e-02 + 6.79824057221827e-02 -5.46531901393429e-02 + 6.35090960690899e-02 -5.28689008362057e-02 + 5.92419250258708e-02 -5.10893545882387e-02 + 5.51761543119222e-02 -4.93108314830338e-02 + 5.13012845894761e-02 -4.75440896934531e-02 + 4.76145515997845e-02 -4.57830599145488e-02 + 4.41097733544431e-02 -4.40286418035125e-02 + 4.07797512889574e-02 -4.22832452899324e-02 + 3.76203116687853e-02 -4.05471735735779e-02 + 3.46254239696624e-02 -3.88215583285753e-02 + 3.17889085655347e-02 -3.71070627007449e-02 + 2.91063003142196e-02 -3.54070465342894e-02 + 2.65680912572024e-02 -3.37242409387003e-02 + 2.41746444372365e-02 -3.20578833095496e-02 + 2.19171444247057e-02 -3.04080839884921e-02 + 1.97858149698170e-02 -2.87865078379770e-02 + 1.77816785975956e-02 -2.71845378027204e-02 + 1.59022597397006e-02 -2.56014559510294e-02 + 1.41389646872214e-02 -2.40428674601252e-02 + 1.24868469400299e-02 -2.25098598379508e-02 + 1.09480652882944e-02 -2.09965353712404e-02 + 9.51590058521273e-03 -1.95072886041607e-02 + 8.19359596476239e-03 -1.80358421377615e-02 + 6.97242121388991e-03 -1.65886143273830e-02 + 5.86117330807756e-03 -1.51566360782969e-02 + 4.85595758514205e-03 -1.37425262435773e-02 + 3.94940976333073e-03 -1.23512935315688e-02 + 3.14133835342164e-03 -1.09822566687452e-02 + 2.44321714150649e-03 -9.63205013980954e-03 + 1.83022809796061e-03 -8.31193344939125e-03 + 1.31884436057794e-03 -7.01716988880847e-03 + 8.97352193736273e-04 -5.75368646998309e-03 + 5.63740905842356e-04 -4.52380720725293e-03 + 3.11437030347409e-04 -3.33125343689109e-03 + 1.35836224347021e-04 -2.17811584123553e-03 + 4.45280630750671e-05 -1.06661951254253e-03 + 0.00000000000000e+00 0.00000000000000e+00 + 2.66759975469128e-05 1.06620320574453e-03 + 1.03135502882502e-04 2.17873885472331e-03 + 2.50714361136359e-04 3.33437348745562e-03 + 4.62713791811825e-04 4.53304972124580e-03 + 7.43003731765193e-04 5.77372430028259e-03 + 1.10319742939756e-03 7.05282365458086e-03 + 1.54997995490141e-03 8.36732726269284e-03 + 2.09725167376054e-03 9.71027388884010e-03 + 2.74048539040992e-03 1.10830187729024e-02 + 3.47312973743479e-03 1.24853497385656e-02 + 4.30082057862358e-03 1.39166426421534e-02 + 5.21856989199968e-03 1.53794078029284e-02 + 6.22534057591764e-03 1.68754960531490e-02 + 7.32700432621982e-03 1.84027675881834e-02 + 8.52684801153103e-03 1.99605858637636e-02 + 9.82457090745577e-03 2.15515899247781e-02 + 1.12235129483028e-02 2.31756762504219e-02 + 1.27200449567995e-02 2.48389005693531e-02 + 1.43242218865420e-02 2.65369882056060e-02 + 1.60404178082626e-02 2.82678553499417e-02 + 1.78724934115684e-02 3.00331989618528e-02 + 1.98202065802740e-02 3.18374006104675e-02 + 2.18950371605342e-02 3.36723464545640e-02 + 2.40944987682683e-02 3.55478452136134e-02 + 2.64266489071067e-02 3.74562451109318e-02 + 2.89010362193680e-02 3.93973481646352e-02 + 3.15128734993139e-02 4.13789540071277e-02 + 3.42721293711695e-02 4.33986338037802e-02 + 3.71869628254960e-02 4.54495701594197e-02 + 4.02626884327817e-02 4.75345999298599e-02 + 4.35001994625931e-02 4.96601287812404e-02 + 4.69115999564798e-02 5.18156686218105e-02 + 5.05037662874084e-02 5.40013382232845e-02 + 5.42786495746735e-02 5.62234758330505e-02 + 5.82482809121614e-02 5.84716000937855e-02 + 6.24154777430842e-02 6.07527241240193e-02 + 6.67896532476333e-02 6.30611171442784e-02 + 7.13799778368031e-02 6.53924902316809e-02 + 7.61893991966636e-02 6.77536943148228e-02 + 8.12317422826271e-02 7.01307158448530e-02 + 8.65117308166364e-02 7.25279772295263e-02 + 9.20361925143298e-02 7.49454570665521e-02 + 9.78162490733068e-02 7.73748196288702e-02 + 1.03860525098628e-01 7.98107376836716e-02 + 1.10175749426971e-01 8.22553965780306e-02 + 1.16770184828620e-01 8.47058845532950e-02 + 1.23653173100621e-01 8.71545949342700e-02 + 1.30834306039958e-01 8.95967898803351e-02 + 1.38321638159842e-01 9.20292326136635e-02 + 1.46124356656426e-01 9.44436091370127e-02 + 1.54251870487751e-01 9.68324481019705e-02 + 1.62712165766615e-01 9.91923652415109e-02 + 1.71513276359922e-01 1.01517920367561e-01 + 1.80666809206519e-01 1.03789902629961e-01 + 1.90176333616483e-01 1.06018459355824e-01 + 2.00055618945293e-01 1.08170249602257e-01 + 2.10311333730825e-01 1.10238985284240e-01 + 2.20950025725240e-01 1.12217524621099e-01 + 2.31980826542045e-01 1.14082138261491e-01 + 2.43406729303366e-01 1.15839155310084e-01 + 2.55238106076494e-01 1.17446572225308e-01 + 2.67477471857320e-01 1.18905415201973e-01 + 2.80131031707401e-01 1.20180412981259e-01 + 2.93202678436719e-01 1.21245809848125e-01 + 3.06694853961626e-01 1.22070347287731e-01 + 3.20607221269401e-01 1.22636048627399e-01 + 3.34939225727116e-01 1.22896405187495e-01 + 3.49687259951759e-01 1.22832509683795e-01 + 3.64846634151165e-01 1.22439948740756e-01 + 3.80413960921238e-01 1.21746809942571e-01 + 3.96385714538567e-01 1.20764919268824e-01 + 4.12758960322157e-01 1.19510121769152e-01 + 4.29529842936380e-01 1.17984332147218e-01 + 4.46694032865700e-01 1.16192942543521e-01 + 4.64243156344356e-01 1.14110109333428e-01 + 4.82175917377177e-01 1.11782565979692e-01 + 5.00484981625201e-01 1.09197664159710e-01 + 5.19162527401886e-01 1.06360393829411e-01 + 5.38203351947280e-01 1.03293317103930e-01 + 5.57598339807246e-01 9.99962205928791e-02 + 5.77338351570623e-01 9.64747449157602e-02 + 5.97416776275050e-01 9.27560006949552e-02 + 6.17822141099620e-01 8.88440306520127e-02 + 6.38542602259551e-01 8.47454502578335e-02 + 6.59565267437110e-01 8.04670396004571e-02 + 6.80878587686638e-01 7.60267545343259e-02 + 7.02471625795160e-01 7.14503791069948e-02 + 7.24326570178040e-01 6.67348590516426e-02 + 7.46427167466697e-01 6.18895592022783e-02 + 7.68752565300964e-01 5.69073598312532e-02 + 7.91284286644164e-01 5.17961436337766e-02 + 8.14003103862062e-01 4.65642778387828e-02 + 8.36892211324902e-01 4.12336546487814e-02 + 8.59931483011660e-01 3.58149765441833e-02 + 8.83096679342750e-01 3.03040142055707e-02 + 9.06368908273977e-01 2.47214334364437e-02 + 9.29725618218844e-01 1.90747609134739e-02 + 9.53145851346865e-01 1.33087434425404e-02 + 9.76587857380671e-01 7.46542748662253e-03 + 1.00000000000000e+00 1.53836008119114e-03 diff --git a/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF29_Coords.txt b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF29_Coords.txt new file mode 100644 index 00000000..a8559b09 --- /dev/null +++ b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF29_Coords.txt @@ -0,0 +1,208 @@ + 201 NumCoords ! The number of coordinates in the airfoil shape file (including an extra coordinate for airfoil reference). Set to zero if coordinates not included. +! ......... x-y coordinates are next if NumCoords > 0 ............. +! x-y coordinate of airfoil reference +! x/c y/c + 0.250000 0 +! coordinates of airfoil shape +! interpolation to 200 points +! x/c y/c + 1.00000000000000e+00 -1.24164223325347e-03 + 9.76041164392396e-01 1.99488062082566e-03 + 9.52121910751731e-01 4.75706135335948e-03 + 9.28199952199219e-01 7.09542915865422e-03 + 9.04291183649571e-01 8.93443767118390e-03 + 8.80430335305919e-01 9.96657750751068e-03 + 8.56672679460919e-01 9.94290456909515e-03 + 8.33075414701384e-01 9.19689647089799e-03 + 8.09695687435274e-01 7.47347776900502e-03 + 7.86588871455130e-01 4.89111649401108e-03 + 7.63799965113471e-01 1.51070681640460e-03 + 7.41353000623285e-01 -2.52044025059049e-03 + 7.19257724385752e-01 -7.04038035491660e-03 + 6.97520929992240e-01 -1.19358771025367e-02 + 6.76139755888505e-01 -1.70807000809784e-02 + 6.55114166969036e-01 -2.23866910906930e-02 + 6.34437004205735e-01 -2.77558927368869e-02 + 6.14099144503465e-01 -3.30936572688430e-02 + 5.94097064299627e-01 -3.83328932311329e-02 + 5.74431247267374e-01 -4.34270116338703e-02 + 5.55097891490535e-01 -4.83164932012163e-02 + 5.36103212560625e-01 -5.29813263991864e-02 + 5.17451481630547e-01 -5.73968812892901e-02 + 4.99146111683925e-01 -6.15389571602501e-02 + 4.81186975180132e-01 -6.53690978763222e-02 + 4.63583300631990e-01 -6.88824794729917e-02 + 4.46345639685456e-01 -7.21042454369658e-02 + 4.29476392143564e-01 -7.50078041225779e-02 + 4.12981130677270e-01 -7.75910183051978e-02 + 3.96868662278405e-01 -7.98780393343755e-02 + 3.81143702382537e-01 -8.18762030718283e-02 + 3.65809916070270e-01 -8.35894498418953e-02 + 3.50871312147949e-01 -8.50344244357429e-02 + 3.36330822167539e-01 -8.62290745383426e-02 + 3.22187646977060e-01 -8.71590051574009e-02 + 3.08443347581371e-01 -8.78366305562361e-02 + 2.95097791339595e-01 -8.82767906155356e-02 + 2.82150283499973e-01 -8.84841152823162e-02 + 2.69599681087069e-01 -8.84700144337475e-02 + 2.57443507192848e-01 -8.82648626051867e-02 + 2.45678472964112e-01 -8.78783050259134e-02 + 2.34300862010750e-01 -8.73191697949781e-02 + 2.23305146809674e-01 -8.66150861037270e-02 + 2.12686447462944e-01 -8.57716757140843e-02 + 2.02439173855586e-01 -8.47960288193625e-02 + 1.92555307706631e-01 -8.37147516939257e-02 + 1.83029046978344e-01 -8.25290955835651e-02 + 1.73852963346223e-01 -8.12499103431124e-02 + 1.65019689389359e-01 -7.98863245514951e-02 + 1.56521126720043e-01 -7.84487139477401e-02 + 1.48348304923117e-01 -7.69503909453266e-02 + 1.40492148638460e-01 -7.54025518805833e-02 + 1.32945914165942e-01 -7.38053366709304e-02 + 1.25700981456047e-01 -7.21672611749456e-02 + 1.18749045764871e-01 -7.04928205316870e-02 + 1.12082052295785e-01 -6.87847149917338e-02 + 1.05690622940757e-01 -6.70563903986223e-02 + 9.95644640688240e-02 -6.53155333147837e-02 + 9.36997746804533e-02 -6.35528246583057e-02 + 8.80860269419856e-02 -6.17797928182627e-02 + 8.27138276159543e-02 -6.00046033630738e-02 + 7.75786679035966e-02 -5.82199710630611e-02 + 7.26702668766427e-02 -5.64363872841197e-02 + 6.79824057221827e-02 -5.46531901393429e-02 + 6.35090960690899e-02 -5.28689008362057e-02 + 5.92419250258708e-02 -5.10893545882387e-02 + 5.51761543119222e-02 -4.93108314830338e-02 + 5.13012845894761e-02 -4.75440896934531e-02 + 4.76145515997845e-02 -4.57830599145488e-02 + 4.41097733544431e-02 -4.40286418035125e-02 + 4.07797512889574e-02 -4.22832452899324e-02 + 3.76203116687853e-02 -4.05471735735779e-02 + 3.46254239696624e-02 -3.88215583285753e-02 + 3.17889085655347e-02 -3.71070627007449e-02 + 2.91063003142196e-02 -3.54070465342894e-02 + 2.65680912572024e-02 -3.37242409387003e-02 + 2.41746444372365e-02 -3.20578833095496e-02 + 2.19171444247057e-02 -3.04080839884921e-02 + 1.97858149698170e-02 -2.87865078379770e-02 + 1.77816785975956e-02 -2.71845378027204e-02 + 1.59022597397006e-02 -2.56014559510294e-02 + 1.41389646872214e-02 -2.40428674601252e-02 + 1.24868469400299e-02 -2.25098598379508e-02 + 1.09480652882944e-02 -2.09965353712404e-02 + 9.51590058521273e-03 -1.95072886041607e-02 + 8.19359596476239e-03 -1.80358421377615e-02 + 6.97242121388991e-03 -1.65886143273830e-02 + 5.86117330807756e-03 -1.51566360782969e-02 + 4.85595758514205e-03 -1.37425262435773e-02 + 3.94940976333073e-03 -1.23512935315688e-02 + 3.14133835342164e-03 -1.09822566687452e-02 + 2.44321714150649e-03 -9.63205013980954e-03 + 1.83022809796061e-03 -8.31193344939125e-03 + 1.31884436057794e-03 -7.01716988880847e-03 + 8.97352193736273e-04 -5.75368646998309e-03 + 5.63740905842356e-04 -4.52380720725293e-03 + 3.11437030347409e-04 -3.33125343689109e-03 + 1.35836224347021e-04 -2.17811584123553e-03 + 4.45280630750671e-05 -1.06661951254253e-03 + 0.00000000000000e+00 0.00000000000000e+00 + 2.66759975469128e-05 1.06620320574453e-03 + 1.03135502882502e-04 2.17873885472331e-03 + 2.50714361136359e-04 3.33437348745562e-03 + 4.62713791811825e-04 4.53304972124580e-03 + 7.43003731765193e-04 5.77372430028259e-03 + 1.10319742939756e-03 7.05282365458086e-03 + 1.54997995490141e-03 8.36732726269284e-03 + 2.09725167376054e-03 9.71027388884010e-03 + 2.74048539040992e-03 1.10830187729024e-02 + 3.47312973743479e-03 1.24853497385656e-02 + 4.30082057862358e-03 1.39166426421534e-02 + 5.21856989199968e-03 1.53794078029284e-02 + 6.22534057591764e-03 1.68754960531490e-02 + 7.32700432621982e-03 1.84027675881834e-02 + 8.52684801153103e-03 1.99605858637636e-02 + 9.82457090745577e-03 2.15515899247781e-02 + 1.12235129483028e-02 2.31756762504219e-02 + 1.27200449567995e-02 2.48389005693531e-02 + 1.43242218865420e-02 2.65369882056060e-02 + 1.60404178082626e-02 2.82678553499417e-02 + 1.78724934115684e-02 3.00331989618528e-02 + 1.98202065802740e-02 3.18374006104675e-02 + 2.18950371605342e-02 3.36723464545640e-02 + 2.40944987682683e-02 3.55478452136134e-02 + 2.64266489071067e-02 3.74562451109318e-02 + 2.89010362193680e-02 3.93973481646352e-02 + 3.15128734993139e-02 4.13789540071277e-02 + 3.42721293711695e-02 4.33986338037802e-02 + 3.71869628254960e-02 4.54495701594197e-02 + 4.02626884327817e-02 4.75345999298599e-02 + 4.35001994625931e-02 4.96601287812404e-02 + 4.69115999564798e-02 5.18156686218105e-02 + 5.05037662874084e-02 5.40013382232845e-02 + 5.42786495746735e-02 5.62234758330505e-02 + 5.82482809121614e-02 5.84716000937855e-02 + 6.24154777430842e-02 6.07527241240193e-02 + 6.67896532476333e-02 6.30611171442784e-02 + 7.13799778368031e-02 6.53924902316809e-02 + 7.61893991966636e-02 6.77536943148228e-02 + 8.12317422826271e-02 7.01307158448530e-02 + 8.65117308166364e-02 7.25279772295263e-02 + 9.20361925143298e-02 7.49454570665521e-02 + 9.78162490733068e-02 7.73748196288702e-02 + 1.03860525098628e-01 7.98107376836716e-02 + 1.10175749426971e-01 8.22553965780306e-02 + 1.16770184828620e-01 8.47058845532950e-02 + 1.23653173100621e-01 8.71545949342700e-02 + 1.30834306039958e-01 8.95967898803351e-02 + 1.38321638159842e-01 9.20292326136635e-02 + 1.46124356656426e-01 9.44436091370127e-02 + 1.54251870487751e-01 9.68324481019705e-02 + 1.62712165766615e-01 9.91923652415109e-02 + 1.71513276359922e-01 1.01517920367561e-01 + 1.80666809206519e-01 1.03789902629961e-01 + 1.90176333616483e-01 1.06018459355824e-01 + 2.00055618945293e-01 1.08170249602257e-01 + 2.10311333730825e-01 1.10238985284240e-01 + 2.20950025725240e-01 1.12217524621099e-01 + 2.31980826542045e-01 1.14082138261491e-01 + 2.43406729303366e-01 1.15839155310084e-01 + 2.55238106076494e-01 1.17446572225308e-01 + 2.67477471857320e-01 1.18905415201973e-01 + 2.80131031707401e-01 1.20180412981259e-01 + 2.93202678436719e-01 1.21245809848125e-01 + 3.06694853961626e-01 1.22070347287731e-01 + 3.20607221269401e-01 1.22636048627399e-01 + 3.34939225727116e-01 1.22896405187495e-01 + 3.49687259951759e-01 1.22832509683795e-01 + 3.64846634151165e-01 1.22439948740756e-01 + 3.80413960921238e-01 1.21746809942571e-01 + 3.96385714538567e-01 1.20764919268824e-01 + 4.12758960322157e-01 1.19510121769152e-01 + 4.29529842936380e-01 1.17984332147218e-01 + 4.46694032865700e-01 1.16192942543521e-01 + 4.64243156344356e-01 1.14110109333428e-01 + 4.82175917377177e-01 1.11782565979692e-01 + 5.00484981625201e-01 1.09197664159710e-01 + 5.19162527401886e-01 1.06360393829411e-01 + 5.38203351947280e-01 1.03293317103930e-01 + 5.57598339807246e-01 9.99962205928791e-02 + 5.77338351570623e-01 9.64747449157602e-02 + 5.97416776275050e-01 9.27560006949552e-02 + 6.17822141099620e-01 8.88440306520127e-02 + 6.38542602259551e-01 8.47454502578335e-02 + 6.59565267437110e-01 8.04670396004571e-02 + 6.80878587686638e-01 7.60267545343259e-02 + 7.02471625795160e-01 7.14503791069948e-02 + 7.24326570178040e-01 6.67348590516426e-02 + 7.46427167466697e-01 6.18895592022783e-02 + 7.68752565300964e-01 5.69073598312532e-02 + 7.91284286644164e-01 5.17961436337766e-02 + 8.14003103862062e-01 4.65642778387828e-02 + 8.36892211324902e-01 4.12336546487814e-02 + 8.59931483011660e-01 3.58149765441833e-02 + 8.83096679342750e-01 3.03040142055707e-02 + 9.06368908273977e-01 2.47214334364437e-02 + 9.29725618218844e-01 1.90747609134739e-02 + 9.53145851346865e-01 1.33087434425404e-02 + 9.76587857380671e-01 7.46542748662253e-03 + 1.00000000000000e+00 1.53836008119114e-03 diff --git a/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_00.dat b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_00.dat new file mode 100644 index 00000000..b23ba71d --- /dev/null +++ b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_00.dat @@ -0,0 +1,254 @@ +! ------------ AirfoilInfo v1.01.x Input File ---------------------------------- +! AeroElasticSE FAST driver +! line +! line +! ------------------------------------------------------------------------------ +DEFAULT InterpOrd ! Interpolation order to use for quasi-steady table lookup {1=linear; 3=cubic spline; "default"} [default=3] +1 NonDimArea ! The non-dimensional area of the airfoil (area/chord^2) (set to 1.0 if unsure or unneeded) +@"NREL-2p8-127_AF00_Coords.txt" NumCoords ! The number of coordinates in the airfoil shape file. Set to zero if coordinates not included. +AF00_BL.txt BL_file ! The file name including the boundary layer characteristics of the profile. Ignored if the aeroacoustic module is not called. +1 NumTabs ! Number of airfoil tables in this file. Each table must have lines for Re and Ctrl. +! ------------------------------------------------------------------------------ +! data for table 1 +! ------------------------------------------------------------------------------ +6.000000 Re ! Reynolds number in millions +0 Ctrl ! Control setting (must be 0 for current AirfoilInfo) +True InclUAdata ! Is unsteady aerodynamics data included in this table? If TRUE, then include 30 UA coefficients below this line +!........................................ +0.000000 alpha0 ! 0-lift angle of attack, depends on airfoil. +0.000000 alpha1 ! Angle of attack at f=0.7, (approximately the stall angle) for AOA>alpha0. (deg) +0.000000 alpha2 ! Angle of attack at f=0.7, (approximately the stall angle) for AOA1] +0.000000 S2 ! Constant in the f curve best-fit for AOA> alpha1; by definition it depends on the airfoil. [ignored if UAMod<>1] +0.000000 S3 ! Constant in the f curve best-fit for alpha2<=AOA< alpha0; by definition it depends on the airfoil. [ignored if UAMod<>1] +0.000000 S4 ! Constant in the f curve best-fit for AOA< alpha2; by definition it depends on the airfoil. [ignored if UAMod<>1] +0.000000 Cn1 ! Critical value of C0n at leading edge separation. It should be extracted from airfoil data at a given Mach and Reynolds number. It can be calculated from the static value of Cn at either the break in the pitching moment or the loss of chord force at the onset of stall. It is close to the condition of maximum lift of the airfoil at low Mach numbers. +0.000000 Cn2 ! As Cn1 for negative AOAs. +Default St_sh ! Strouhal's shedding frequency constant. [default = 0.19] +0.000000 Cd0 ! 2D drag coefficient value at 0-lift. +0.000000 Cm0 ! 2D pitching moment coefficient about 1/4-chord location, at 0-lift, positive if nose up. [If the aerodynamics coefficients table does not include a column for Cm, this needs to be set to 0.0] +0.000000 k0 ! Constant in the \hat(x)_cp curve best-fit; = (\hat(x)_AC-0.25). [ignored if UAMod<>1] +0.000000 k1 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k2 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k3 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k1_hat ! Constant in the expression of Cc due to leading edge vortex effects. [ignored if UAMod<>1] +Default x_cp_bar ! Constant in the expression of \hat(x)_cp^v. [ignored if UAMod<>1, default = 0.2] +Default UACutout ! Angle of attack above which unsteady aerodynamics are disabled (deg). [Specifying the string "Default" sets UACutout to 45 degrees] +Default filtCutOff ! Cut-off frequency (-3 dB corner frequency) for low-pass filtering the AoA input to UA, as well as the 1st and 2nd derivatives (Hz) [default = 20] +!........................................ +! Table of aerodynamics coefficients +200 NumAlf ! Number of data lines in the following table +! Alpha Cl Cd Cm +! (deg) (-) (-) (-) +-1.80000000000000e+02 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-1.77000000000000e+02 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-1.74000000000000e+02 0.00000000000000e+00 5.00000000000000e-01 -2.77555756156289e-17 +-1.71000000000000e+02 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-1.68000000000000e+02 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-1.65000000000000e+02 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-1.62000000000000e+02 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-1.59000000000000e+02 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-1.56000000000000e+02 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-1.53000000000000e+02 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-1.50000000000000e+02 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-1.47000000000000e+02 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-1.44000000000000e+02 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-1.41000000000000e+02 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-1.38000000000000e+02 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-1.35000000000000e+02 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-1.32000000000000e+02 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-1.29000000000000e+02 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-1.26000000000000e+02 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-1.23000000000000e+02 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-1.20000000000000e+02 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-1.17000000000000e+02 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-1.14000000000000e+02 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-1.11000000000000e+02 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-1.08000000000000e+02 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-1.05000000000000e+02 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-1.02000000000000e+02 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-9.90000000000000e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-9.60000000000000e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-9.30000000000000e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-9.00000000000000e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-8.70000000000000e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-8.40000000000000e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-8.10000000000000e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-7.80000000000000e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-7.50000000000000e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-7.20000000000000e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-6.90000000000000e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-6.60000000000000e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-6.30000000000000e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-6.00000000000000e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-5.70000000000000e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-5.40000000000000e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-5.10000000000000e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-4.80000000000000e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-4.50000000000000e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-4.20000000000000e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-3.90000000000000e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-3.60000000000000e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-3.30000000000000e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-3.00000000000000e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-2.93939393939394e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-2.87878787878788e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-2.81818181818182e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-2.75757575757576e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-2.69696969696970e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-2.63636363636364e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-2.57575757575758e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-2.51515151515151e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-2.45454545454545e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-2.39393939393939e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-2.33333333333333e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-2.27272727272727e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-2.21212121212121e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-2.15151515151515e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-2.09090909090909e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-2.03030303030303e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-1.96969696969697e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-1.90909090909091e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-1.84848484848485e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-1.78787878787879e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-1.72727272727273e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-1.66666666666667e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-1.60606060606061e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-1.54545454545455e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-1.48484848484848e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-1.42424242424242e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-1.36363636363636e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-1.30303030303030e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-1.24242424242424e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-1.18181818181818e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-1.12121212121212e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-1.06060606060606e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-1.00000000000000e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-9.39393939393939e+00 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-8.78787878787879e+00 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-8.18181818181818e+00 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-7.57575757575758e+00 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-6.96969696969697e+00 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-6.36363636363636e+00 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-5.75757575757576e+00 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-5.15151515151515e+00 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-4.54545454545454e+00 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-3.93939393939394e+00 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-3.33333333333333e+00 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-2.72727272727273e+00 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-2.12121212121212e+00 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-1.51515151515152e+00 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-9.09090909090912e-01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-3.03030303030302e-01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 3.03030303030302e-01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 9.09090909090912e-01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 1.51515151515152e+00 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 2.12121212121212e+00 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 2.72727272727273e+00 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 3.33333333333333e+00 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 3.93939393939394e+00 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 4.54545454545455e+00 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 5.15151515151515e+00 1.11022302462516e-16 5.00000000000000e-01 0.00000000000000e+00 + 5.75757575757576e+00 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 6.36363636363637e+00 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 6.96969696969697e+00 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 7.57575757575757e+00 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 8.18181818181818e+00 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 8.78787878787879e+00 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 9.39393939393939e+00 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 1.00000000000000e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 1.06060606060606e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 1.12121212121212e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 1.18181818181818e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 1.24242424242424e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 1.30303030303030e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 1.36363636363636e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 1.42424242424242e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 1.48484848484848e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 1.54545454545455e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 1.60606060606061e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 1.66666666666667e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 1.72727272727273e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 1.78787878787879e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 1.84848484848485e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 1.90909090909091e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 1.96969696969697e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 2.03030303030303e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 2.09090909090909e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 2.15151515151515e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 2.21212121212121e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 2.27272727272727e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 2.33333333333333e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 2.39393939393939e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 2.45454545454545e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 2.51515151515151e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 2.57575757575758e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 2.63636363636364e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 2.69696969696970e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 2.75757575757576e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 2.81818181818182e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 2.87878787878788e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 2.93939393939394e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 3.00000000000000e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 3.30000000000000e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 3.60000000000000e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 3.90000000000000e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 4.20000000000000e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 4.50000000000000e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 4.80000000000000e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 5.10000000000000e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 5.40000000000000e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 5.70000000000000e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 6.00000000000000e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 6.30000000000000e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 6.60000000000000e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 6.90000000000000e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 7.20000000000000e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 7.50000000000000e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 7.80000000000000e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 8.10000000000000e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 8.40000000000000e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 8.70000000000000e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 9.00000000000000e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 9.30000000000000e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 9.60000000000000e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 9.90000000000000e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 1.02000000000000e+02 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 1.05000000000000e+02 2.77555756156289e-17 5.00000000000000e-01 0.00000000000000e+00 + 1.08000000000000e+02 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 1.11000000000000e+02 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 1.14000000000000e+02 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 1.17000000000000e+02 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 1.20000000000000e+02 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 1.23000000000000e+02 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 1.26000000000000e+02 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 1.29000000000000e+02 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 1.32000000000000e+02 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 1.35000000000000e+02 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 1.38000000000000e+02 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 1.41000000000000e+02 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 1.44000000000000e+02 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 1.47000000000000e+02 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 1.50000000000000e+02 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 1.53000000000000e+02 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 1.56000000000000e+02 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 1.59000000000000e+02 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 1.62000000000000e+02 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 1.65000000000000e+02 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 1.68000000000000e+02 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 1.71000000000000e+02 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 1.74000000000000e+02 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 1.77000000000000e+02 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 1.80000000000000e+02 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 diff --git a/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_01.dat b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_01.dat new file mode 100644 index 00000000..b197c637 --- /dev/null +++ b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_01.dat @@ -0,0 +1,254 @@ +! ------------ AirfoilInfo v1.01.x Input File ---------------------------------- +! AeroElasticSE FAST driver +! line +! line +! ------------------------------------------------------------------------------ +DEFAULT InterpOrd ! Interpolation order to use for quasi-steady table lookup {1=linear; 3=cubic spline; "default"} [default=3] +1 NonDimArea ! The non-dimensional area of the airfoil (area/chord^2) (set to 1.0 if unsure or unneeded) +@"NREL-2p8-127_AF01_Coords.txt" NumCoords ! The number of coordinates in the airfoil shape file. Set to zero if coordinates not included. +AF01_BL.txt BL_file ! The file name including the boundary layer characteristics of the profile. Ignored if the aeroacoustic module is not called. +1 NumTabs ! Number of airfoil tables in this file. Each table must have lines for Re and Ctrl. +! ------------------------------------------------------------------------------ +! data for table 1 +! ------------------------------------------------------------------------------ +6.000000 Re ! Reynolds number in millions +0 Ctrl ! Control setting (must be 0 for current AirfoilInfo) +True InclUAdata ! Is unsteady aerodynamics data included in this table? If TRUE, then include 30 UA coefficients below this line +!........................................ +0.000000 alpha0 ! 0-lift angle of attack, depends on airfoil. +0.000000 alpha1 ! Angle of attack at f=0.7, (approximately the stall angle) for AOA>alpha0. (deg) +0.000000 alpha2 ! Angle of attack at f=0.7, (approximately the stall angle) for AOA1] +0.000000 S2 ! Constant in the f curve best-fit for AOA> alpha1; by definition it depends on the airfoil. [ignored if UAMod<>1] +0.000000 S3 ! Constant in the f curve best-fit for alpha2<=AOA< alpha0; by definition it depends on the airfoil. [ignored if UAMod<>1] +0.000000 S4 ! Constant in the f curve best-fit for AOA< alpha2; by definition it depends on the airfoil. [ignored if UAMod<>1] +0.000000 Cn1 ! Critical value of C0n at leading edge separation. It should be extracted from airfoil data at a given Mach and Reynolds number. It can be calculated from the static value of Cn at either the break in the pitching moment or the loss of chord force at the onset of stall. It is close to the condition of maximum lift of the airfoil at low Mach numbers. +0.000000 Cn2 ! As Cn1 for negative AOAs. +Default St_sh ! Strouhal's shedding frequency constant. [default = 0.19] +0.000000 Cd0 ! 2D drag coefficient value at 0-lift. +0.000000 Cm0 ! 2D pitching moment coefficient about 1/4-chord location, at 0-lift, positive if nose up. [If the aerodynamics coefficients table does not include a column for Cm, this needs to be set to 0.0] +0.000000 k0 ! Constant in the \hat(x)_cp curve best-fit; = (\hat(x)_AC-0.25). [ignored if UAMod<>1] +0.000000 k1 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k2 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k3 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k1_hat ! Constant in the expression of Cc due to leading edge vortex effects. [ignored if UAMod<>1] +Default x_cp_bar ! Constant in the expression of \hat(x)_cp^v. [ignored if UAMod<>1, default = 0.2] +Default UACutout ! Angle of attack above which unsteady aerodynamics are disabled (deg). [Specifying the string "Default" sets UACutout to 45 degrees] +Default filtCutOff ! Cut-off frequency (-3 dB corner frequency) for low-pass filtering the AoA input to UA, as well as the 1st and 2nd derivatives (Hz) [default = 20] +!........................................ +! Table of aerodynamics coefficients +200 NumAlf ! Number of data lines in the following table +! Alpha Cl Cd Cm +! (deg) (-) (-) (-) +-1.80000000000000e+02 0.00000000000000e+00 4.98298540333591e-01 0.00000000000000e+00 +-1.77000000000000e+02 6.22917411225319e-03 4.99373778033698e-01 7.76775909182493e-03 +-1.74000000000000e+02 1.25154154596942e-02 4.99419482735902e-01 1.56066808333025e-02 +-1.71000000000000e+02 1.87731622461588e-02 4.99461965511715e-01 2.34100699534240e-02 +-1.68000000000000e+02 2.34094297732302e-02 4.99530448606310e-01 2.52436698228222e-02 +-1.65000000000000e+02 2.72360674222744e-02 4.99608171404762e-01 2.40924447430971e-02 +-1.62000000000000e+02 3.10637475603965e-02 4.99680051763820e-01 2.29412064713014e-02 +-1.59000000000000e+02 3.36494201711338e-02 4.99754234730512e-01 2.21517716457378e-02 +-1.56000000000000e+02 3.37510782194723e-02 4.99836914626034e-01 2.20859314734659e-02 +-1.53000000000000e+02 3.38548418745498e-02 4.99908331389323e-01 2.20200907982144e-02 +-1.50000000000000e+02 3.39610598736408e-02 4.99965130046894e-01 2.19542509808981e-02 +-1.47000000000000e+02 3.40022351252792e-02 5.01549605455131e-01 2.23645223424130e-02 +-1.44000000000000e+02 3.40443360294749e-02 5.07633704084372e-01 2.27747952710201e-02 +-1.41000000000000e+02 3.40874558144093e-02 5.13717849193324e-01 2.31850713339235e-02 +-1.38000000000000e+02 3.36790582106382e-02 5.20009950681803e-01 2.35945800253753e-02 +-1.35000000000000e+02 3.30448480367859e-02 5.26406029938182e-01 2.40037050326582e-02 +-1.32000000000000e+02 3.24110462717851e-02 5.32802182487933e-01 2.44128347281493e-02 +-1.29000000000000e+02 3.14966524820477e-02 5.39025691193689e-01 2.47587684454421e-02 +-1.26000000000000e+02 3.00203897774573e-02 5.44903911391262e-01 2.49783099065228e-02 +-1.23000000000000e+02 2.85442923527018e-02 5.47997043443126e-01 2.51978496904198e-02 +-1.20000000000000e+02 2.70683874187890e-02 5.50390438255170e-01 2.54173886357562e-02 +-1.17000000000000e+02 2.48208058238953e-02 5.51842311486022e-01 2.53547661804404e-02 +-1.14000000000000e+02 2.25732865469572e-02 5.53294177329843e-01 2.52921434125441e-02 +-1.11000000000000e+02 2.03258601363591e-02 5.54746032082366e-01 2.52295211230444e-02 +-1.08000000000000e+02 1.77044555792872e-02 5.55339410798165e-01 2.49510697467495e-02 +-1.05000000000000e+02 1.48960397658858e-02 5.55503544958830e-01 2.45647021836766e-02 +-1.02000000000000e+02 1.20876828091304e-02 5.55667677238678e-01 2.41783390479984e-02 +-9.90000000000000e+01 9.19392120485563e-03 5.55336597556942e-01 2.36900749881812e-02 +-9.60000000000000e+01 6.12926766887735e-03 5.54015072501802e-01 2.29980046662208e-02 +-9.30000000000000e+01 3.06463754512461e-03 5.52693557542367e-01 2.23059396312876e-02 +-9.00000000000000e+01 1.91272727247280e-08 5.51372047630695e-01 2.15841433608613e-02 +-8.70000000000000e+01 -3.06463440848635e-03 5.52693556189802e-01 2.16338466189352e-02 +-8.40000000000000e+01 -6.12927623833141e-03 5.54015076197080e-01 2.16677916947745e-02 +-8.10000000000000e+01 -9.19389465618328e-03 5.55336586108752e-01 2.16947509086332e-02 +-7.80000000000000e+01 -1.20876692076357e-02 5.55667678033613e-01 2.14919425433851e-02 +-7.50000000000000e+01 -1.48960583459338e-02 5.55503543872940e-01 2.11742464233755e-02 +-7.20000000000000e+01 -1.77044419776618e-02 5.55339411593092e-01 2.08565539438687e-02 +-6.90000000000000e+01 -2.03258406672883e-02 5.54746044659799e-01 2.04334687101240e-02 +-6.60000000000000e+01 -2.25732928313413e-02 5.53294173270158e-01 1.97995893374298e-02 +-6.30000000000000e+01 -2.48208206936227e-02 5.51842301880517e-01 1.91657099647355e-02 +-6.00000000000000e+01 -2.70683971825928e-02 5.50390422420595e-01 1.85318284698429e-02 +-5.70000000000000e+01 -2.85443021178706e-02 5.47997027608551e-01 1.76503617476530e-02 +-5.40000000000000e+01 -3.00203995438562e-02 5.44903872501265e-01 1.67688916585075e-02 +-5.10000000000000e+01 -3.14966622493741e-02 5.39025652303692e-01 1.58874148353996e-02 +-4.80000000000000e+01 -3.24110456233041e-02 5.32802189034552e-01 1.48845508415255e-02 +-4.50000000000000e+01 -3.30448401226552e-02 5.26406109778172e-01 1.38209952131320e-02 +-4.20000000000000e+01 -3.36790575613502e-02 5.20009957227964e-01 1.27574273972622e-02 +-3.90000000000000e+01 -3.40874557757088e-02 5.13717843800706e-01 1.16502587670957e-02 +-3.60000000000000e+01 -3.40443359103789e-02 5.07633687072646e-01 1.04558679399742e-02 +-3.30000000000000e+01 -3.40022354063646e-02 5.01549646541201e-01 9.26149992360155e-03 +-3.00000000000000e+01 -3.39610593176495e-02 4.99965129704843e-01 8.06710800308781e-03 +-2.93939393939394e+01 -3.39393842149473e-02 4.99955039870966e-01 7.77133972459921e-03 +-2.87878787878788e+01 -3.39178226626962e-02 4.99944209186026e-01 7.47170990628286e-03 +-2.81818181818182e+01 -3.38963709780943e-02 4.99932679692807e-01 7.17234251862615e-03 +-2.75757575757576e+01 -3.38750252088939e-02 4.99920490061147e-01 6.87323704771576e-03 +-2.69696969696970e+01 -3.38537822279900e-02 4.99907676487852e-01 6.57440256765985e-03 +-2.63636363636364e+01 -3.38326389844070e-02 4.99894272577114e-01 6.27584744506084e-03 +-2.57575757575758e+01 -3.38115926180026e-02 4.99880309637533e-01 5.97758105595668e-03 +-2.51515151515151e+01 -3.37906402717716e-02 4.99865816763762e-01 5.67961122622956e-03 +-2.45454545454545e+01 -3.37697787305793e-02 4.99850820740502e-01 5.38193913346827e-03 +-2.39393939393939e+01 -3.37490052565293e-02 4.99835346782305e-01 5.08457126751900e-03 +-2.33333333333333e+01 -3.37283172206986e-02 4.99819418446624e-01 4.78751430822279e-03 +-2.27272727272727e+01 -3.37077120977687e-02 4.99803057767734e-01 4.49077513241954e-03 +-2.21212121212121e+01 -3.36871874609726e-02 4.99786285377891e-01 4.19436082126422e-03 +-2.15151515151515e+01 -3.36667405096286e-02 4.99769120219361e-01 3.89827188626708e-03 +-2.09090909090909e+01 -3.36463693546679e-02 4.99751580718914e-01 3.60252094397359e-03 +-2.03030303030303e+01 -3.36260719547005e-02 4.99733684020483e-01 3.30711743419011e-03 +-1.96969696969697e+01 -3.29941770005342e-02 4.99715928910410e-01 2.97198266169500e-03 +-1.90909090909091e+01 -3.17509544740198e-02 4.99698118180787e-01 2.59700694849448e-03 +-1.84848484848485e+01 -3.05081921751880e-02 4.99679692312574e-01 2.22228885632221e-03 +-1.78787878787879e+01 -2.92658434632383e-02 4.99660638867322e-01 1.84786105360303e-03 +-1.72727272727273e+01 -2.80238734929002e-02 4.99640945159408e-01 1.47377573016103e-03 +-1.66666666666667e+01 -2.67823588448486e-02 4.99620599927312e-01 1.10014144572659e-03 +-1.60606060606061e+01 -2.55413203393379e-02 4.99599590742328e-01 7.27083418764568e-04 +-1.54545454545455e+01 -2.43008440419113e-02 4.99577905993521e-01 3.54797120669601e-04 +-1.48484848484848e+01 -2.30608787869031e-02 4.99555531346250e-01 4.21684305218460e-05 +-1.42424242424242e+01 -2.18214069842467e-02 4.99532452564366e-01 2.71911216522822e-05 +-1.36363636363636e+01 -2.05833091301585e-02 4.99508671393742e-01 1.42264537010822e-05 +-1.30303030303030e+01 -1.93442785240345e-02 4.99484131275150e-01 4.31295864732214e-06 +-1.24242424242424e+01 -1.81074797005703e-02 4.99458875874706e-01 -1.61041962405105e-04 +-1.18181818181818e+01 -1.68699463185017e-02 4.99432832875225e-01 -7.83817617224051e-04 +-1.12121212121212e+01 -1.56337784253251e-02 4.99406027440083e-01 -1.40654332027136e-03 +-1.06060606060606e+01 -1.43985688202720e-02 4.99052692242324e-01 -2.02931540870597e-03 +-1.00000000000000e+01 -1.31630022724158e-02 4.97993704507194e-01 -2.65204851654948e-03 +-9.39393939393939e+00 -1.11477228175490e-02 4.96487069320693e-01 -2.55646323442072e-03 +-8.78787878787879e+00 -9.13290842766007e-03 4.94977661180442e-01 -2.46147157009362e-03 +-8.18181818181818e+00 -7.12154268363285e-03 4.93467019568035e-01 -2.36566761577865e-03 +-7.57575757575758e+00 -5.11266117893152e-03 4.91954998300813e-01 -2.26283387170764e-03 +-6.96969696969697e+00 -3.10698824489412e-03 4.90440242965021e-01 -2.08181170391097e-03 +-6.36363636363636e+00 -1.10309834514044e-03 4.88921311313049e-01 -1.89874522974860e-03 +-5.75757575757576e+00 -3.00747474205360e-04 4.87401751405469e-01 -1.71567088819378e-03 +-5.15151515151515e+00 -2.21631176101127e-04 4.85879616962190e-01 -1.53403240787112e-03 +-4.54545454545454e+00 -1.49616631477367e-04 4.84353891592103e-01 -1.35030844364575e-03 +-3.93939393939394e+00 -8.68897616353509e-05 4.82825709613375e-01 -1.16711649919569e-03 +-3.33333333333333e+00 -3.06390387180330e-05 4.81485638756053e-01 -1.06097220254243e-03 +-2.72727272727273e+00 2.49883470329266e-03 4.81081167821070e-01 -1.11471300781816e-03 +-2.12121212121212e+00 9.70229526683138e-03 4.81205260595194e-01 -1.25146797918653e-03 +-1.51515151515152e+00 1.69064135086061e-02 4.81329323131111e-01 -1.47373619873665e-03 +-9.09090909090912e-01 2.15687752025109e-02 4.81450361624086e-01 -1.68081905636486e-03 +-3.03030303030302e-01 2.42404595537528e-02 4.81560887996981e-01 -1.90313415400156e-03 + 3.03030303030302e-01 2.69131749150450e-02 4.81684879937810e-01 -2.12376124690789e-03 + 9.09090909090912e-01 2.95856638229001e-02 4.81808857865227e-01 -2.33301661078614e-03 + 1.51515151515152e+00 3.22398936101882e-02 4.81929840079279e-01 -2.55120165338738e-03 + 2.12121212121212e+00 3.66675784640552e-02 4.81924986740543e-01 -2.77391835793390e-03 + 2.72727272727273e+00 4.19698427928253e-02 4.81879454613869e-01 -2.98510710550669e-03 + 3.33333333333333e+00 4.72717179522425e-02 4.81833922593971e-01 -3.18573614963958e-03 + 3.93939393939394e+00 5.25753326357400e-02 4.81775728360497e-01 -3.38638186200821e-03 + 4.54545454545455e+00 5.78765746006633e-02 4.81728632143155e-01 -3.59889201718914e-03 + 5.15151515151515e+00 6.31803800322498e-02 4.81680617938285e-01 -3.79953830438974e-03 + 5.75757575757576e+00 6.78668119866628e-02 4.81626107889307e-01 -4.03804041841606e-03 + 6.36363636363637e+00 7.15042486961224e-02 4.81584603835809e-01 -4.34980617905866e-03 + 6.96969696969697e+00 7.49998526302299e-02 4.81530576563388e-01 -4.66507085142508e-03 + 7.57575757575757e+00 7.85534281259633e-02 4.81489207644286e-01 -4.96022383060956e-03 + 8.18181818181818e+00 8.27222397693518e-02 4.81442706653469e-01 -5.12210053319802e-03 + 8.78787878787879e+00 8.59673537796770e-02 4.81485608223198e-01 -5.30026887591891e-03 + 9.39393939393939e+00 8.63938854494780e-02 4.81734888790963e-01 -5.58390579608546e-03 + 1.00000000000000e+01 8.61476310716953e-02 4.82033636040847e-01 -5.89351913489291e-03 + 1.06060606060606e+01 1.14640664678628e-02 4.86367761950627e-01 -4.32401101558585e-03 + 1.12121212121212e+01 1.77109990487445e-03 4.90977291638818e-01 -5.52690415533776e-05 + 1.18181818181818e+01 1.63608094150530e-03 4.94596563237555e-01 -4.71568484033090e-05 + 1.24242424242424e+01 5.38023265894621e-02 4.97637007791052e-01 -7.01427597271410e-05 + 1.30303030303030e+01 7.07102583465799e-02 4.99408388908304e-01 -2.78511851302713e-04 + 1.36363636363636e+01 6.81632004936948e-02 4.99466710089213e-01 -3.41458399817878e-04 + 1.42424242424242e+01 6.49592840496404e-02 4.99515392758744e-01 -3.60890382699212e-04 + 1.48484848484848e+01 6.00226087507924e-02 4.99558582755279e-01 -3.80502489146672e-04 + 1.54545454545455e+01 5.42932388358678e-02 4.99595173447000e-01 -3.60569709918067e-04 + 1.60606060606061e+01 4.89399852015463e-02 4.99626659734195e-01 -3.74707069218248e-04 + 1.66666666666667e+01 4.90264804982352e-02 4.99643029856566e-01 -8.14570485140793e-04 + 1.72727272727273e+01 4.89767434358854e-02 4.99658738397009e-01 -1.29542584308036e-03 + 1.78787878787879e+01 4.87601917929942e-02 4.99673710331708e-01 -1.82640692279492e-03 + 1.84848484848485e+01 4.85448822816922e-02 4.99688486075466e-01 -2.35860501303099e-03 + 1.90909090909091e+01 4.83300562227171e-02 4.99703072863703e-01 -2.89167774847090e-03 + 1.96969696969697e+01 4.81154623433704e-02 4.99717479015725e-01 -3.42523467641370e-03 + 2.03030303030303e+01 4.80233231913679e-02 4.99733684020482e-01 -3.86916331990858e-03 + 2.09090909090909e+01 4.80535318777004e-02 4.99751580718914e-01 -4.22318641357654e-03 + 2.15151515151515e+01 4.80838465710918e-02 4.99769120219361e-01 -4.57757988364418e-03 + 2.21212121212121e+01 4.81142702027946e-02 4.99786285377891e-01 -4.93233346765168e-03 + 2.27272727272727e+01 4.81448054735174e-02 4.99803057767734e-01 -5.28743306710894e-03 + 2.33333333333333e+01 4.81754564360106e-02 4.99819418446624e-01 -5.64287905507360e-03 + 2.39393939393939e+01 4.82062265821584e-02 4.99835346782305e-01 -5.99866390348971e-03 + 2.45454545454545e+01 4.82371195457987e-02 4.99850820740502e-01 -6.35478030087519e-03 + 2.51515151515151e+01 4.82681391100110e-02 4.99865816763762e-01 -6.71122114458926e-03 + 2.57575757575758e+01 4.82992892148572e-02 4.99880309637533e-01 -7.06797953342872e-03 + 2.63636363636364e+01 4.83305745045125e-02 4.99894272577114e-01 -7.42505490046007e-03 + 2.69696969696970e+01 4.83619990851020e-02 4.99907676487852e-01 -7.78243869417755e-03 + 2.75757575757576e+01 4.83935670617676e-02 4.99920490061147e-01 -8.14012048538783e-03 + 2.81818181818182e+01 4.84252828173819e-02 4.99932679692807e-01 -8.49809103217069e-03 + 2.87878787878788e+01 4.84571508417891e-02 4.99944209186026e-01 -8.85634022554155e-03 + 2.93939393939394e+01 4.84891768440017e-02 4.99955039870966e-01 -9.21486940940596e-03 + 3.00000000000000e+01 4.85213661255990e-02 4.99965129704843e-01 -9.57367290978077e-03 + 3.30000000000000e+01 4.85783850925221e-02 5.01549646541201e-01 -1.08893308683242e-02 + 3.60000000000000e+01 4.86367279082047e-02 5.07633687072646e-01 -1.21830696545693e-02 + 3.90000000000000e+01 4.86965308414856e-02 5.13717843800706e-01 -1.34715855024972e-02 + 4.20000000000000e+01 4.81074542024269e-02 5.20009957227964e-01 -1.45755410030633e-02 + 4.50000000000000e+01 4.71938349445183e-02 5.26406109778172e-01 -1.55872262614513e-02 + 4.80000000000000e+01 4.62807992978572e-02 5.32802189034552e-01 -1.65988999268877e-02 + 5.10000000000000e+01 4.49696537236258e-02 5.39025652303692e-01 -1.75196039279897e-02 + 5.40000000000000e+01 4.28613244897533e-02 5.44903872501265e-01 -1.82583627521897e-02 + 5.70000000000000e+01 4.07532301242102e-02 5.47997027608551e-01 -1.89971159327085e-02 + 6.00000000000000e+01 3.86454092273193e-02 5.50390422420595e-01 -1.97358662914081e-02 + 6.30000000000000e+01 3.54441639493027e-02 5.51842301880517e-01 -2.01991699310181e-02 + 6.60000000000000e+01 3.22429963032422e-02 5.53294173270158e-01 -2.06624712096125e-02 + 6.90000000000000e+01 2.90419479592744e-02 5.54746044659799e-01 -2.11257724882070e-02 + 7.20000000000000e+01 2.52997639160426e-02 5.55339411593092e-01 -2.14026262276280e-02 + 7.50000000000000e+01 2.12869899032544e-02 5.55503543872940e-01 -2.15862600142917e-02 + 7.80000000000000e+01 1.72742065965976e-02 5.55667678033613e-01 -2.17698959052524e-02 + 8.10000000000000e+01 1.31391516042592e-02 5.55336586108752e-01 -2.18644734045035e-02 + 8.40000000000000e+01 8.75945317316178e-03 5.54015076197080e-01 -2.17809402678169e-02 + 8.70000000000000e+01 4.37972128358576e-03 5.52693556189802e-01 -2.16904207186265e-02 + 9.00000000000000e+01 -1.91272727377706e-08 5.51372047630695e-01 -2.15841433608613e-02 + 9.30000000000000e+01 -3.06463754512461e-03 5.52693557542367e-01 -2.23059396312876e-02 + 9.60000000000000e+01 -6.12926766887736e-03 5.54015072501802e-01 -2.29980046662208e-02 + 9.90000000000000e+01 -9.19392120485563e-03 5.55336597556942e-01 -2.36900749881812e-02 + 1.02000000000000e+02 -1.20876828091304e-02 5.55667677238678e-01 -2.41783390479984e-02 + 1.05000000000000e+02 -1.48960397658858e-02 5.55503544958831e-01 -2.45647021836766e-02 + 1.08000000000000e+02 -1.77044555792872e-02 5.55339410798165e-01 -2.49510697467495e-02 + 1.11000000000000e+02 -2.03258601363591e-02 5.54746032082366e-01 -2.52295211230444e-02 + 1.14000000000000e+02 -2.25732865469573e-02 5.53294177329843e-01 -2.52921434125440e-02 + 1.17000000000000e+02 -2.48208058238953e-02 5.51842311486022e-01 -2.53547661804404e-02 + 1.20000000000000e+02 -2.70683874187890e-02 5.50390438255170e-01 -2.54173886357562e-02 + 1.23000000000000e+02 -2.85442923527018e-02 5.47997043443125e-01 -2.51978496904198e-02 + 1.26000000000000e+02 -3.00203897774573e-02 5.44903911391262e-01 -2.49783099065228e-02 + 1.29000000000000e+02 -3.14966524820477e-02 5.39025691193689e-01 -2.47587684454421e-02 + 1.32000000000000e+02 -3.24110462717851e-02 5.32802182487933e-01 -2.44128347281493e-02 + 1.35000000000000e+02 -3.30448480367859e-02 5.26406029938182e-01 -2.40037050326582e-02 + 1.38000000000000e+02 -3.36790582106382e-02 5.20009950681803e-01 -2.35945800253753e-02 + 1.41000000000000e+02 -3.40874558144093e-02 5.13717849193324e-01 -2.31850713339234e-02 + 1.44000000000000e+02 -3.40443360294749e-02 5.07633704084372e-01 -2.27747952710201e-02 + 1.47000000000000e+02 -3.40022351252792e-02 5.01549605455131e-01 -2.23645223424130e-02 + 1.50000000000000e+02 -3.39610598736408e-02 4.99965130046894e-01 -2.19542509808981e-02 + 1.53000000000000e+02 -3.38548418745498e-02 4.99908331389323e-01 -2.20200907982144e-02 + 1.56000000000000e+02 -3.37510782194723e-02 4.99836914626034e-01 -2.20859314734659e-02 + 1.59000000000000e+02 -3.36494201711338e-02 4.99754234730512e-01 -2.21517716457378e-02 + 1.62000000000000e+02 -3.10637475603964e-02 4.99680051763820e-01 -2.42417639918563e-02 + 1.65000000000000e+02 -2.72360674222744e-02 4.99608171404762e-01 -2.73438495435689e-02 + 1.68000000000000e+02 -2.34094297732302e-02 4.99530448606310e-01 -3.04458995483989e-02 + 1.71000000000000e+02 -1.87731622461588e-02 4.99461965511715e-01 -2.92625874417800e-02 + 1.74000000000000e+02 -1.25154154596942e-02 4.99419482735902e-01 -1.95083510416281e-02 + 1.77000000000000e+02 -6.22917411225319e-03 4.99373778033698e-01 -9.70969886478117e-03 + 1.80000000000000e+02 0.00000000000000e+00 4.98298540333591e-01 0.00000000000000e+00 diff --git a/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_02.dat b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_02.dat new file mode 100644 index 00000000..3b06888a --- /dev/null +++ b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_02.dat @@ -0,0 +1,254 @@ +! ------------ AirfoilInfo v1.01.x Input File ---------------------------------- +! AeroElasticSE FAST driver +! line +! line +! ------------------------------------------------------------------------------ +DEFAULT InterpOrd ! Interpolation order to use for quasi-steady table lookup {1=linear; 3=cubic spline; "default"} [default=3] +1 NonDimArea ! The non-dimensional area of the airfoil (area/chord^2) (set to 1.0 if unsure or unneeded) +@"NREL-2p8-127_AF02_Coords.txt" NumCoords ! The number of coordinates in the airfoil shape file. Set to zero if coordinates not included. +AF02_BL.txt BL_file ! The file name including the boundary layer characteristics of the profile. Ignored if the aeroacoustic module is not called. +1 NumTabs ! Number of airfoil tables in this file. Each table must have lines for Re and Ctrl. +! ------------------------------------------------------------------------------ +! data for table 1 +! ------------------------------------------------------------------------------ +6.000000 Re ! Reynolds number in millions +0 Ctrl ! Control setting (must be 0 for current AirfoilInfo) +True InclUAdata ! Is unsteady aerodynamics data included in this table? If TRUE, then include 30 UA coefficients below this line +!........................................ +0.000000 alpha0 ! 0-lift angle of attack, depends on airfoil. +0.000000 alpha1 ! Angle of attack at f=0.7, (approximately the stall angle) for AOA>alpha0. (deg) +0.000000 alpha2 ! Angle of attack at f=0.7, (approximately the stall angle) for AOA1] +0.000000 S2 ! Constant in the f curve best-fit for AOA> alpha1; by definition it depends on the airfoil. [ignored if UAMod<>1] +0.000000 S3 ! Constant in the f curve best-fit for alpha2<=AOA< alpha0; by definition it depends on the airfoil. [ignored if UAMod<>1] +0.000000 S4 ! Constant in the f curve best-fit for AOA< alpha2; by definition it depends on the airfoil. [ignored if UAMod<>1] +0.000000 Cn1 ! Critical value of C0n at leading edge separation. It should be extracted from airfoil data at a given Mach and Reynolds number. It can be calculated from the static value of Cn at either the break in the pitching moment or the loss of chord force at the onset of stall. It is close to the condition of maximum lift of the airfoil at low Mach numbers. +0.000000 Cn2 ! As Cn1 for negative AOAs. +Default St_sh ! Strouhal's shedding frequency constant. [default = 0.19] +0.000000 Cd0 ! 2D drag coefficient value at 0-lift. +0.000000 Cm0 ! 2D pitching moment coefficient about 1/4-chord location, at 0-lift, positive if nose up. [If the aerodynamics coefficients table does not include a column for Cm, this needs to be set to 0.0] +0.000000 k0 ! Constant in the \hat(x)_cp curve best-fit; = (\hat(x)_AC-0.25). [ignored if UAMod<>1] +0.000000 k1 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k2 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k3 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k1_hat ! Constant in the expression of Cc due to leading edge vortex effects. [ignored if UAMod<>1] +Default x_cp_bar ! Constant in the expression of \hat(x)_cp^v. [ignored if UAMod<>1, default = 0.2] +Default UACutout ! Angle of attack above which unsteady aerodynamics are disabled (deg). [Specifying the string "Default" sets UACutout to 45 degrees] +Default filtCutOff ! Cut-off frequency (-3 dB corner frequency) for low-pass filtering the AoA input to UA, as well as the 1st and 2nd derivatives (Hz) [default = 20] +!........................................ +! Table of aerodynamics coefficients +200 NumAlf ! Number of data lines in the following table +! Alpha Cl Cd Cm +! (deg) (-) (-) (-) +-1.80000000000000e+02 0.00000000000000e+00 4.43994184250602e-01 0.00000000000000e+00 +-1.77000000000000e+02 5.28218858836285e-02 4.51778947168691e-01 6.31301215186523e-02 +-1.74000000000000e+02 1.06127688082721e-01 4.54846200132976e-01 1.26838596030369e-01 +-1.71000000000000e+02 1.59191863314727e-01 4.57721687001980e-01 1.90258289868333e-01 +-1.68000000000000e+02 1.97447618139026e-01 4.62593607482116e-01 2.03998727898909e-01 +-1.65000000000000e+02 2.28363691552126e-01 4.68241882193770e-01 1.92900117855920e-01 +-1.62000000000000e+02 2.59339036364168e-01 4.73545480231159e-01 1.81801380632199e-01 +-1.59000000000000e+02 2.79820337838342e-01 4.79170658239085e-01 1.73519743179148e-01 +-1.56000000000000e+02 2.79311457907633e-01 4.85668590966138e-01 1.70872209970165e-01 +-1.53000000000000e+02 2.78926753637668e-01 4.91502040321387e-01 1.68224656535610e-01 +-1.50000000000000e+02 2.78686833504982e-01 4.96473066155593e-01 1.65577105058638e-01 +-1.47000000000000e+02 2.78482617289417e-01 5.10449666953889e-01 1.68109661007669e-01 +-1.44000000000000e+02 2.78333002128108e-01 5.51477403517201e-01 1.70642226630173e-01 +-1.41000000000000e+02 2.78243478183707e-01 5.92505453513528e-01 1.73174811600312e-01 +-1.38000000000000e+02 2.74638204421170e-01 6.34935844279750e-01 1.76256259812944e-01 +-1.35000000000000e+02 2.69271830313825e-01 6.78067402586119e-01 1.79612138533394e-01 +-1.32000000000000e+02 2.63929918544127e-01 7.21199455141732e-01 1.82968055709224e-01 +-1.29000000000000e+02 2.56353341244360e-01 7.63167294790495e-01 1.86036517826043e-01 +-1.26000000000000e+02 2.44267095501969e-01 8.02806703094638e-01 1.88530068460767e-01 +-1.23000000000000e+02 2.32190027809931e-01 8.30095142617392e-01 1.91023600046048e-01 +-1.20000000000000e+02 2.20124030074996e-01 8.54280447094884e-01 1.93517122106963e-01 +-1.17000000000000e+02 2.01822771772063e-01 8.71322712892104e-01 1.94226310566758e-01 +-1.14000000000000e+02 1.83524830303930e-01 8.88364899623064e-01 1.94935492828237e-01 +-1.11000000000000e+02 1.65231494534441e-01 9.05406956162956e-01 1.95644669672032e-01 +-1.08000000000000e+02 1.43911689592217e-01 9.15698197853296e-01 1.94815640807175e-01 +-1.05000000000000e+02 1.21077486266499e-01 9.22613980715162e-01 1.93217497375608e-01 +-1.02000000000000e+02 9.82451183513876e-02 9.29529684328913e-01 1.91619372257204e-01 +-9.90000000000000e+01 7.47225598413416e-02 9.32477260333714e-01 1.89218782642220e-01 +-9.60000000000000e+01 4.98149331461973e-02 9.27488409240135e-01 1.85213229275117e-01 +-9.30000000000000e+01 2.49074967312809e-02 9.22499596258566e-01 1.81207706508184e-01 +-9.00000000000000e+01 1.55454756347091e-07 9.17510802332658e-01 1.75447976882559e-01 +-8.70000000000000e+01 -2.49074712386065e-02 9.22499591152534e-01 1.75821854055456e-01 +-8.40000000000000e+01 -4.98150027934706e-02 9.27488423190074e-01 1.75265803096445e-01 +-8.10000000000000e+01 -7.47223440699950e-02 9.32477217115983e-01 1.74297623848041e-01 +-7.80000000000000e+01 -9.82450077740596e-02 9.29529717823434e-01 1.71657379233808e-01 +-7.50000000000000e+01 -1.21077637330475e-01 9.22613934961229e-01 1.68181073081051e-01 +-7.20000000000000e+01 -1.43911579000158e-01 9.15698231347477e-01 1.64704806763536e-01 +-6.90000000000000e+01 -1.65231336083193e-01 9.05407103798478e-01 1.60521039551036e-01 +-6.60000000000000e+01 -1.83524881462789e-01 8.88364851969969e-01 1.54922212612248e-01 +-6.30000000000000e+01 -2.01822892842596e-01 8.71322600141459e-01 1.49323385673460e-01 +-6.00000000000000e+01 -2.20124109861353e-01 8.54280287086177e-01 1.43724546113009e-01 +-5.70000000000000e+01 -2.32190107676827e-01 8.30094982608685e-01 1.36653206413885e-01 +-5.40000000000000e+01 -2.44267175435753e-01 8.02806440842389e-01 1.29581839704227e-01 +-5.10000000000000e+01 -2.56353421232862e-01 7.63167032538246e-01 1.22510418973089e-01 +-4.80000000000000e+01 -2.63929913090152e-01 7.21199499288443e-01 1.14843085027639e-01 +-4.50000000000000e+01 -2.69271763474185e-01 6.78067940982074e-01 1.06877804052201e-01 +-4.20000000000000e+01 -2.74638198917296e-01 6.34935888423376e-01 9.89124318011671e-02 +-3.90000000000000e+01 -2.78243478234639e-01 5.92505417148744e-01 9.07777362760891e-02 +-3.60000000000000e+01 -2.78333002465160e-01 5.51477288799700e-01 8.23042410827366e-02 +-3.30000000000000e+01 -2.78482616088909e-01 5.10449944015222e-01 7.38309077181307e-02 +-3.00000000000000e+01 -2.78686834724237e-01 4.96473034437446e-01 6.53574058853759e-02 +-2.93939393939394e+01 -2.78722484884278e-01 4.95550482915159e-01 6.31590888898999e-02 +-2.87878787878788e+01 -2.78764834228033e-01 4.94584223091226e-01 6.07329510056277e-02 +-2.81818181818182e+01 -2.78813665479675e-01 4.93576735381485e-01 5.83222958533192e-02 +-2.75757575757576e+01 -2.78868771825416e-01 4.92530294643563e-01 5.59273989519316e-02 +-2.69696969696970e+01 -2.78929953713021e-01 4.91447040145689e-01 5.35486208968168e-02 +-2.63636363636364e+01 -2.78997019845282e-01 4.90328957261459e-01 5.11863242110430e-02 +-2.57575757575758e+01 -2.79069786417323e-01 4.89177896868326e-01 4.88408872710036e-02 +-2.51515151515151e+01 -2.79148077344780e-01 4.87995577350176e-01 4.65126844314689e-02 +-2.45454545454545e+01 -2.79231725535284e-01 4.86783573310055e-01 4.42020473048908e-02 +-2.39393939393939e+01 -2.79320569460013e-01 4.85543372341575e-01 4.19093587754535e-02 +-2.33333333333333e+01 -2.79414454019281e-01 4.84276364273540e-01 3.96350129365467e-02 +-2.27272727272727e+01 -2.79513230225828e-01 4.82983849071519e-01 3.73794155039853e-02 +-2.21212121212121e+01 -2.79616754906648e-01 4.81667043985251e-01 3.51429842476471e-02 +-2.15151515151515e+01 -2.79724892952109e-01 4.80327059059195e-01 3.29260988660576e-02 +-2.09090909090909e+01 -2.79837510321443e-01 4.78964987050167e-01 3.07292415847816e-02 +-2.03030303030303e+01 -2.79954479045127e-01 4.77581841281423e-01 2.85528819253764e-02 +-1.96969696969697e+01 -2.75171456546404e-01 4.76241678491924e-01 2.59885541142665e-02 +-1.90909090909091e+01 -2.65502607041286e-01 4.74932861964715e-01 2.30296767768801e-02 +-1.84848484848485e+01 -2.55857808543395e-01 4.73587766414009e-01 2.00850651071971e-02 +-1.78787878787879e+01 -2.46237593082487e-01 4.72205644697461e-01 1.71576346825735e-02 +-1.72727272727273e+01 -2.36642641160737e-01 4.70785737308274e-01 1.42512880441333e-02 +-1.66666666666667e+01 -2.27074552079369e-01 4.69327391673071e-01 1.13715515436610e-02 +-1.60606060606061e+01 -2.17534554179683e-01 4.67829874530176e-01 8.52581274757511e-03 +-1.54545454545455e+01 -2.08024441493220e-01 4.66292514169838e-01 5.72461577042921e-03 +-1.48484848484848e+01 -1.98545026218225e-01 4.64714449362364e-01 3.24301314993957e-03 +-1.42424242424242e+01 -1.89097459745549e-01 4.63094831340957e-01 2.15754331667197e-03 +-1.36363636363636e+01 -1.79689119603896e-01 4.61433905636119e-01 1.19082104448867e-03 +-1.30303030303030e+01 -1.70305930436414e-01 4.59727952028918e-01 4.04096803450701e-04 +-1.24242424242424e+01 -1.60970739714131e-01 4.57980061533300e-01 -1.08597634782590e-03 +-1.18181818181818e+01 -1.51665423337775e-01 4.56185474694515e-01 -5.28562481853854e-03 +-1.12121212121212e+01 -1.42405828637851e-01 4.54346018736465e-01 -9.48493644261989e-03 +-1.06060606060606e+01 -1.33190990892009e-01 4.51015638941563e-01 -1.36845608636440e-02 +-1.00000000000000e+01 -1.24014684903561e-01 4.44510346744821e-01 -1.78839224215030e-02 +-9.39393939393939e+00 -1.08436489679061e-01 4.35608923797464e-01 -1.72393490814751e-02 +-8.78787878787879e+00 -9.29541316307449e-02 4.26594514374539e-01 -1.65987787657685e-02 +-8.18181818181818e+00 -7.76026887758120e-02 4.17469560995041e-01 -1.59527308236021e-02 +-7.57575757575758e+00 -6.23970752419446e-02 4.08227566266090e-01 -1.52754905468310e-02 +-6.96969696969697e+00 -4.73685296749869e-02 3.98853223979206e-01 -1.42539284761816e-02 +-6.36363636363636e+00 -3.25421758356058e-02 3.89329220025460e-01 -1.32208969139180e-02 +-5.75757575757576e+00 -2.32883547306756e-02 3.79669167553607e-01 -1.21878209564984e-02 +-5.15151515151515e+00 -1.75463818719779e-02 3.69851724588186e-01 -1.11628011971168e-02 +-4.54545454545454e+00 -1.22231690324848e-02 3.59859373530705e-01 -1.01275683268214e-02 +-3.93939393939394e+00 -7.44825163485882e-03 3.49689752142525e-01 -9.09398161623545e-03 +-3.33333333333333e+00 -2.91658839268368e-03 3.40624828035861e-01 -8.49251566568143e-03 +-2.72727272727273e+00 1.68507347052569e-02 3.37851584545355e-01 -9.05855564667579e-03 +-2.12121212121212e+00 6.54268180916555e-02 3.38696970690453e-01 -1.01724248228530e-02 +-1.51515151515152e+00 1.14007336489887e-01 3.39540888251967e-01 -1.18440226132878e-02 +-9.09090909090912e-01 1.51313727007511e-01 3.40364324377504e-01 -1.33594433207991e-02 +-3.03030303030302e-01 1.79793106660581e-01 3.41119901467205e-01 -1.49439775633901e-02 + 3.03030303030302e-01 2.08277227321411e-01 3.41959802485552e-01 -1.65190153005760e-02 + 9.09090909090912e-01 2.36761120877396e-01 3.42798375876233e-01 -1.80436696564668e-02 + 1.51515151515152e+00 2.62099120009543e-01 3.43615726098759e-01 -1.96089791867871e-02 + 2.12121212121212e+00 2.98214942887010e-01 3.43590036955630e-01 -2.12433569551258e-02 + 2.72727272727273e+00 3.41265305298494e-01 3.43282612273994e-01 -2.28522580646574e-02 + 3.33333333333333e+00 3.84321941282732e-01 3.42975023524515e-01 -2.44142825317703e-02 + 3.93939393939394e+00 4.27399321163861e-01 3.42588020332646e-01 -2.59764367716794e-02 + 4.54545454545455e+00 4.70462749288264e-01 3.42270335299019e-01 -2.75887619844635e-02 + 5.15151515151515e+00 5.13550609798191e-01 3.41947566135864e-01 -2.91509206998043e-02 + 5.75757575757576e+00 5.51690452105184e-01 3.41583432622427e-01 -3.09254291087337e-02 + 6.36363636363637e+00 5.81502121097488e-01 3.41302193452691e-01 -3.30991045572195e-02 + 6.96969696969697e+00 6.10301560112658e-01 3.40942615842003e-01 -3.52998315891569e-02 + 7.57575757575757e+00 6.39640830053245e-01 3.40662394282476e-01 -3.74120160931164e-02 + 8.18181818181818e+00 6.73716922359672e-01 3.40349350542629e-01 -3.89332211349433e-02 + 8.78787878787879e+00 7.00575005999923e-01 3.40649231227702e-01 -4.05874368999055e-02 + 9.39393939393939e+00 7.05980518760212e-01 3.42347265627704e-01 -4.28334247556514e-02 + 1.00000000000000e+01 7.06877424431301e-01 3.44374177297010e-01 -4.52251156741810e-02 + 1.06060606060606e+01 2.24043543681458e-01 3.72918111447314e-01 -3.53747047936440e-02 + 1.12121212121212e+01 1.40264660669456e-01 4.01951061572017e-01 -4.64618913321433e-03 + 1.18181818181818e+01 1.31385056875955e-01 4.23992085353333e-01 -4.07850695907500e-03 + 1.24242424242424e+01 4.46038012430764e-01 4.42283118524471e-01 -5.50420221929163e-03 + 1.30303030303030e+01 5.55998373281915e-01 4.54419475361305e-01 -7.26003568693194e-03 + 1.36363636363636e+01 5.44188127636130e-01 4.58360923643072e-01 -7.86408309600584e-03 + 1.42424242424242e+01 5.27942944540329e-01 4.61684804811602e-01 -8.24435657376023e-03 + 1.48484848484848e+01 4.89688648561149e-01 4.64663565131384e-01 -8.63252791099281e-03 + 1.54545454545455e+01 4.48737588342535e-01 4.67211594818839e-01 -8.81024773998454e-03 + 1.60606060606061e+01 4.12943834077636e-01 4.69433759746416e-01 -9.21685653350780e-03 + 1.66666666666667e+01 4.12507412476758e-01 4.70665756115078e-01 -1.23356902066896e-02 + 1.72727272727273e+01 4.11140315107920e-01 4.71853296753582e-01 -1.57410394707879e-02 + 1.78787878787879e+01 4.08617622571655e-01 4.72990750025282e-01 -1.94979904601476e-02 + 1.84848484848485e+01 4.06114881343676e-01 4.74116453453578e-01 -2.33119670538974e-02 + 1.90909090909091e+01 4.03627419358201e-01 4.75230998047512e-01 -2.71766217490092e-02 + 1.96969696969697e+01 4.01154151508036e-01 4.76335071600720e-01 -3.10855411393017e-02 + 2.03030303030303e+01 3.99841450263120e-01 4.77581841281423e-01 -3.43354943821136e-02 + 2.09090909090909e+01 3.99682666388390e-01 4.78964987050167e-01 -3.69103854071785e-02 + 2.15151515151515e+01 3.99530136656685e-01 4.80327059059195e-01 -3.95071276844189e-02 + 2.21212121212121e+01 3.99384045127721e-01 4.81667043985251e-01 -4.21252206930270e-02 + 2.27272727272727e+01 3.99244584495002e-01 4.82983849071519e-01 -4.47641473640253e-02 + 2.33333333333333e+01 3.99111949378307e-01 4.84276364273540e-01 -4.74235100634337e-02 + 2.39393939393939e+01 3.98986345789788e-01 4.85543372341575e-01 -5.01028646553693e-02 + 2.45454545454545e+01 3.98867988116513e-01 4.86783573310055e-01 -5.28017797812506e-02 + 2.51515151515151e+01 3.98757099550410e-01 4.87995577350176e-01 -5.55198364035922e-02 + 2.57575757575758e+01 3.98653912544980e-01 4.89177896868326e-01 -5.82566273692076e-02 + 2.63636363636364e+01 3.98558667733390e-01 4.90328957261459e-01 -6.10118045012879e-02 + 2.69696969696970e+01 3.98471618483357e-01 4.91447040145689e-01 -6.37849681601756e-02 + 2.75757575757576e+01 3.98393029231929e-01 4.92530294643563e-01 -6.65757129024393e-02 + 2.81818181818182e+01 3.98323175239888e-01 4.93576735381485e-01 -6.93836508624560e-02 + 2.87878787878788e+01 3.98262343636652e-01 4.94584223091226e-01 -7.22083954498178e-02 + 2.93939393939394e+01 3.98210832316413e-01 4.95550482915159e-01 -7.50496587540483e-02 + 3.00000000000000e+01 3.98168954058675e-01 4.96473034437446e-01 -7.79071060247789e-02 + 3.30000000000000e+01 3.97861629624178e-01 5.10449944015222e-01 -8.85000759993798e-02 + 3.60000000000000e+01 3.97632504408999e-01 5.51477288799700e-01 -9.78012526556367e-02 + 3.90000000000000e+01 3.97489452250910e-01 5.92505417148744e-01 -1.06793009320285e-01 + 4.20000000000000e+01 3.92296355524120e-01 6.34935888423376e-01 -1.14716558885029e-01 + 4.50000000000000e+01 3.84572561868948e-01 6.78067940982074e-01 -1.22106077030729e-01 + 4.80000000000000e+01 3.76882670622963e-01 7.21199499288443e-01 -1.29495510499575e-01 + 5.10000000000000e+01 3.66020533668567e-01 7.63167032538246e-01 -1.36361479578265e-01 + 5.40000000000000e+01 3.48758349336931e-01 8.02806440842389e-01 -1.42180486224307e-01 + 5.70000000000000e+01 3.31509203268269e-01 8.30094982608685e-01 -1.47999448416575e-01 + 6.00000000000000e+01 3.14275781966473e-01 8.54280287086177e-01 -1.53818388382123e-01 + 6.30000000000000e+01 2.88206454299320e-01 8.71322600141459e-01 -1.57969229855332e-01 + 6.60000000000000e+01 2.62142183925970e-01 8.88364851969969e-01 -1.62120057030290e-01 + 6.90000000000000e+01 2.36084952068339e-01 9.05407103798478e-01 -1.66270884205247e-01 + 7.20000000000000e+01 2.05649772307401e-01 9.15698231347478e-01 -1.69225081057529e-01 + 7.50000000000000e+01 1.73023749638975e-01 9.22613934961229e-01 -1.71580987245091e-01 + 7.80000000000000e+01 1.40399517677831e-01 9.29529717823434e-01 -1.73936920429460e-01 + 8.10000000000000e+01 1.06786972533886e-01 9.32477217115983e-01 -1.75676992294215e-01 + 8.40000000000000e+01 7.11914675762680e-02 9.27488423190074e-01 -1.76185384031098e-01 + 8.70000000000000e+01 3.55956906886392e-02 9.22499591152534e-01 -1.76281636984940e-01 + 9.00000000000000e+01 -1.55454756453089e-07 9.17510802332658e-01 -1.75447976882559e-01 + 9.30000000000000e+01 -2.49074967312808e-02 9.22499596258566e-01 -1.81207706508184e-01 + 9.60000000000000e+01 -4.98149331461974e-02 9.27488409240135e-01 -1.85213229275117e-01 + 9.90000000000000e+01 -7.47225598413417e-02 9.32477260333714e-01 -1.89218782642220e-01 + 1.02000000000000e+02 -9.82451183513876e-02 9.29529684328913e-01 -1.91619372257204e-01 + 1.05000000000000e+02 -1.21077486266499e-01 9.22613980715162e-01 -1.93217497375608e-01 + 1.08000000000000e+02 -1.43911689592217e-01 9.15698197853296e-01 -1.94815640807175e-01 + 1.11000000000000e+02 -1.65231494534441e-01 9.05406956162956e-01 -1.95644669672032e-01 + 1.14000000000000e+02 -1.83524830303930e-01 8.88364899623064e-01 -1.94935492828237e-01 + 1.17000000000000e+02 -2.01822771772063e-01 8.71322712892104e-01 -1.94226310566758e-01 + 1.20000000000000e+02 -2.20124030074997e-01 8.54280447094884e-01 -1.93517122106963e-01 + 1.23000000000000e+02 -2.32190027809931e-01 8.30095142617392e-01 -1.91023600046048e-01 + 1.26000000000000e+02 -2.44267095501969e-01 8.02806703094638e-01 -1.88530068460767e-01 + 1.29000000000000e+02 -2.56353341244360e-01 7.63167294790494e-01 -1.86036517826043e-01 + 1.32000000000000e+02 -2.63929918544127e-01 7.21199455141732e-01 -1.82968055709224e-01 + 1.35000000000000e+02 -2.69271830313825e-01 6.78067402586119e-01 -1.79612138533394e-01 + 1.38000000000000e+02 -2.74638204421170e-01 6.34935844279749e-01 -1.76256259812944e-01 + 1.41000000000000e+02 -2.78243478183707e-01 5.92505453513527e-01 -1.73174811600312e-01 + 1.44000000000000e+02 -2.78333002128108e-01 5.51477403517201e-01 -1.70642226630173e-01 + 1.47000000000000e+02 -2.78482617289417e-01 5.10449666953889e-01 -1.68109661007669e-01 + 1.50000000000000e+02 -2.78686833504982e-01 4.96473066155593e-01 -1.65577105058638e-01 + 1.53000000000000e+02 -2.78926753637668e-01 4.91502040321387e-01 -1.68224656535610e-01 + 1.56000000000000e+02 -2.79311457907633e-01 4.85668590966138e-01 -1.70872209970165e-01 + 1.59000000000000e+02 -2.79820337838342e-01 4.79170658239085e-01 -1.73519743179148e-01 + 1.62000000000000e+02 -2.59339036364167e-01 4.73545480231159e-01 -1.92371270010081e-01 + 1.65000000000000e+02 -2.28363691552126e-01 4.68241882193770e-01 -2.19324930692370e-01 + 1.68000000000000e+02 -1.97447618139026e-01 4.62593607482116e-01 -2.46278282511930e-01 + 1.71000000000000e+02 -1.59191863314727e-01 4.57721687001980e-01 -2.37822862335416e-01 + 1.74000000000000e+02 -1.06127688082721e-01 4.54846200132976e-01 -1.58548245037961e-01 + 1.77000000000000e+02 -5.28218858836285e-02 4.51778947168691e-01 -7.89126518983154e-02 + 1.80000000000000e+02 0.00000000000000e+00 4.43994184250602e-01 0.00000000000000e+00 diff --git a/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_03.dat b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_03.dat new file mode 100644 index 00000000..1c63fe2f --- /dev/null +++ b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_03.dat @@ -0,0 +1,254 @@ +! ------------ AirfoilInfo v1.01.x Input File ---------------------------------- +! AeroElasticSE FAST driver +! line +! line +! ------------------------------------------------------------------------------ +DEFAULT InterpOrd ! Interpolation order to use for quasi-steady table lookup {1=linear; 3=cubic spline; "default"} [default=3] +1 NonDimArea ! The non-dimensional area of the airfoil (area/chord^2) (set to 1.0 if unsure or unneeded) +@"NREL-2p8-127_AF03_Coords.txt" NumCoords ! The number of coordinates in the airfoil shape file. Set to zero if coordinates not included. +AF03_BL.txt BL_file ! The file name including the boundary layer characteristics of the profile. Ignored if the aeroacoustic module is not called. +1 NumTabs ! Number of airfoil tables in this file. Each table must have lines for Re and Ctrl. +! ------------------------------------------------------------------------------ +! data for table 1 +! ------------------------------------------------------------------------------ +6.000000 Re ! Reynolds number in millions +0 Ctrl ! Control setting (must be 0 for current AirfoilInfo) +True InclUAdata ! Is unsteady aerodynamics data included in this table? If TRUE, then include 30 UA coefficients below this line +!........................................ +0.000000 alpha0 ! 0-lift angle of attack, depends on airfoil. +0.000000 alpha1 ! Angle of attack at f=0.7, (approximately the stall angle) for AOA>alpha0. (deg) +0.000000 alpha2 ! Angle of attack at f=0.7, (approximately the stall angle) for AOA1] +0.000000 S2 ! Constant in the f curve best-fit for AOA> alpha1; by definition it depends on the airfoil. [ignored if UAMod<>1] +0.000000 S3 ! Constant in the f curve best-fit for alpha2<=AOA< alpha0; by definition it depends on the airfoil. [ignored if UAMod<>1] +0.000000 S4 ! Constant in the f curve best-fit for AOA< alpha2; by definition it depends on the airfoil. [ignored if UAMod<>1] +0.000000 Cn1 ! Critical value of C0n at leading edge separation. It should be extracted from airfoil data at a given Mach and Reynolds number. It can be calculated from the static value of Cn at either the break in the pitching moment or the loss of chord force at the onset of stall. It is close to the condition of maximum lift of the airfoil at low Mach numbers. +0.000000 Cn2 ! As Cn1 for negative AOAs. +Default St_sh ! Strouhal's shedding frequency constant. [default = 0.19] +0.000000 Cd0 ! 2D drag coefficient value at 0-lift. +0.000000 Cm0 ! 2D pitching moment coefficient about 1/4-chord location, at 0-lift, positive if nose up. [If the aerodynamics coefficients table does not include a column for Cm, this needs to be set to 0.0] +0.000000 k0 ! Constant in the \hat(x)_cp curve best-fit; = (\hat(x)_AC-0.25). [ignored if UAMod<>1] +0.000000 k1 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k2 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k3 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k1_hat ! Constant in the expression of Cc due to leading edge vortex effects. [ignored if UAMod<>1] +Default x_cp_bar ! Constant in the expression of \hat(x)_cp^v. [ignored if UAMod<>1, default = 0.2] +Default UACutout ! Angle of attack above which unsteady aerodynamics are disabled (deg). [Specifying the string "Default" sets UACutout to 45 degrees] +Default filtCutOff ! Cut-off frequency (-3 dB corner frequency) for low-pass filtering the AoA input to UA, as well as the 1st and 2nd derivatives (Hz) [default = 20] +!........................................ +! Table of aerodynamics coefficients +200 NumAlf ! Number of data lines in the following table +! Alpha Cl Cd Cm +! (deg) (-) (-) (-) +-1.80000000000000e+02 0.00000000000000e+00 2.86667939639823e-01 0.00000000000000e+00 +-1.77000000000000e+02 1.03993393584518e-01 2.98099548900633e-01 1.09870530503698e-01 +-1.74000000000000e+02 2.08939500216179e-01 3.07632373564454e-01 2.20747616176905e-01 +-1.71000000000000e+02 3.13409902357768e-01 3.16774623015665e-01 3.31122113148220e-01 +-1.68000000000000e+02 3.85054442612432e-01 3.34234373573580e-01 3.53101024359159e-01 +-1.65000000000000e+02 4.40412121695890e-01 3.55419527359135e-01 3.30883174396667e-01 +-1.62000000000000e+02 4.95885499788614e-01 3.75931646834106e-01 3.08665069836311e-01 +-1.59000000000000e+02 5.30626275353240e-01 3.98846265744607e-01 2.91144350600985e-01 +-1.56000000000000e+02 5.23897762918947e-01 4.27014220182996e-01 2.83018243112307e-01 +-1.53000000000000e+02 5.17411720704259e-01 4.53884562381070e-01 2.74892073545017e-01 +-1.50000000000000e+02 5.11208424965791e-01 4.79070665595520e-01 2.66765899031848e-01 +-1.47000000000000e+02 5.07722631231294e-01 5.14614980861448e-01 2.69838067335530e-01 +-1.44000000000000e+02 5.04343461108966e-01 5.71996674202226e-01 2.72910247373812e-01 +-1.41000000000000e+02 5.01081625048703e-01 6.29378805912717e-01 2.75982450882136e-01 +-1.38000000000000e+02 4.92453728624275e-01 6.88722261711689e-01 2.80934437546522e-01 +-1.35000000000000e+02 4.81136499725427e-01 7.49046375576140e-01 2.86826311975596e-01 +-1.32000000000000e+02 4.69867035979492e-01 8.09371180701211e-01 2.92718253920303e-01 +-1.29000000000000e+02 4.54938482726295e-01 8.68067709113985e-01 2.98486582390899e-01 +-1.26000000000000e+02 4.32612975232015e-01 9.23507676366582e-01 3.04007683325731e-01 +-1.23000000000000e+02 4.10305382623877e-01 9.74580839620112e-01 3.09528742082194e-01 +-1.20000000000000e+02 3.88019404664959e-01 1.02455678086533e+00 3.15049779750259e-01 +-1.17000000000000e+02 3.55328226413339e-01 1.06294869915767e+00 3.18312911803281e-01 +-1.14000000000000e+02 3.22643517723842e-01 1.10134044814828e+00 3.21576026976400e-01 +-1.11000000000000e+02 2.89967780617592e-01 1.13973190385125e+00 3.24839117221471e-01 +-1.08000000000000e+02 2.52261395940272e-01 1.16675109608688e+00 3.25784702971782e-01 +-1.05000000000000e+02 2.12037421291888e-01 1.18808406999478e+00 3.25571518828366e-01 +-1.02000000000000e+02 1.71816981097322e-01 1.20941679944765e+00 3.25358337127833e-01 +-9.90000000000000e+01 1.30505705696886e-01 1.22393767216320e+00 3.23791373077473e-01 +-9.60000000000000e+01 8.70036173585535e-02 1.22483453634678e+00 3.19516785688025e-01 +-9.30000000000000e+01 4.35018613516539e-02 1.22573139367882e+00 3.15242230954016e-01 +-9.00000000000000e+01 2.71507463396801e-07 1.22662824758516e+00 3.07541711312162e-01 +-8.70000000000000e+01 -4.35018168277582e-02 1.22573139459675e+00 3.06500259153458e-01 +-8.40000000000000e+01 -8.70037390000840e-02 1.22483453383895e+00 3.03642638678455e-01 +-8.10000000000000e+01 -1.30505328844274e-01 1.22393767993261e+00 2.99980148628166e-01 +-7.80000000000000e+01 -1.71816786310515e-01 1.20941690276751e+00 2.93732912001213e-01 +-7.50000000000000e+01 -2.12037687400372e-01 1.18808392885856e+00 2.86193257479784e-01 +-7.20000000000000e+01 -2.52261201124482e-01 1.16675119940570e+00 2.78653689355799e-01 +-6.90000000000000e+01 -2.89967497594430e-01 1.13973223643685e+00 2.70131045852760e-01 +-6.60000000000000e+01 -3.22643609105459e-01 1.10134034079787e+00 2.59642171088866e-01 +-6.30000000000000e+01 -3.55328442677626e-01 1.06294844515890e+00 2.49153296324973e-01 +-6.00000000000000e+01 -3.88019552026475e-01 1.02455645022712e+00 2.38664407299212e-01 +-5.70000000000000e+01 -4.10305530142687e-01 9.74580508981902e-01 2.26511664589643e-01 +-5.40000000000000e+01 -4.32613122881359e-01 9.23507309578663e-01 2.14358875460006e-01 +-5.10000000000000e+01 -4.54938630482502e-01 8.68067342326065e-01 2.02205993489526e-01 +-4.80000000000000e+01 -4.69867024471485e-01 8.09371242445124e-01 1.89666602848052e-01 +-4.50000000000000e+01 -4.81136358743375e-01 7.49047128580672e-01 1.76933964082825e-01 +-4.20000000000000e+01 -4.92453717018877e-01 6.88722323451287e-01 1.64201179411986e-01 +-3.90000000000000e+01 -5.01081627884301e-01 6.29378755052664e-01 1.51481884585662e-01 +-3.60000000000000e+01 -5.04343470398699e-01 5.71996513757487e-01 1.38789326350142e-01 +-3.30000000000000e+01 -5.07722608040306e-01 5.14615368361460e-01 1.26097010519998e-01 +-3.00000000000000e+01 -5.11208459117473e-01 4.79070493417508e-01 1.13404444471583e-01 +-2.93939393939394e+01 -5.12436596980431e-01 4.74141998928450e-01 1.10133084143430e-01 +-2.87878787878788e+01 -5.13677818293272e-01 4.69128142491057e-01 1.06416791520792e-01 +-2.81818181818182e+01 -5.14931698718120e-01 4.64033768336758e-01 1.02730736544464e-01 +-2.75757575757576e+01 -5.16197857581441e-01 4.58863256541541e-01 9.90754777938710e-02 +-2.69696969696970e+01 -5.17475891884770e-01 4.53620820905796e-01 9.54517077990795e-02 +-2.63636363636364e+01 -5.18765418068804e-01 4.48310365722169e-01 9.18601257810618e-02 +-2.57575757575758e+01 -5.20066063887109e-01 4.42935541572834e-01 8.83014589939624e-02 +-2.51515151515151e+01 -5.21377478812960e-01 4.37499722355814e-01 8.47764326963560e-02 +-2.45454545454545e+01 -5.22699356428834e-01 4.32005929515122e-01 8.12857120895547e-02 +-2.39393939393939e+01 -5.24031381270285e-01 4.26457068308669e-01 7.78300449431755e-02 +-2.33333333333333e+01 -5.25373250428924e-01 4.20855853060512e-01 7.44102009183187e-02 +-2.27272727272727e+01 -5.26724672933875e-01 4.15204822592555e-01 7.10269723745852e-02 +-2.21212121212121e+01 -5.28085369169450e-01 4.09506354183381e-01 6.76811752130597e-02 +-2.15151515151515e+01 -5.29455101817919e-01 4.03762544083001e-01 6.43735744019926e-02 +-2.09090909090909e+01 -5.30833589187798e-01 3.97975580174912e-01 6.11050941602448e-02 +-2.03030303030303e+01 -5.32220574716406e-01 3.92147459389974e-01 5.78766456029426e-02 +-1.96969696969697e+01 -5.25041853310013e-01 3.86734130344610e-01 5.36740381794206e-02 +-1.90909090909091e+01 -5.09325030771277e-01 3.81712847911617e-01 4.84844307653104e-02 +-1.84848484848485e+01 -4.93655025441404e-01 3.76620832907035e-01 4.33226553930925e-02 +-1.78787878787879e+01 -4.78033039651211e-01 3.71456499045297e-01 3.81944365371004e-02 +-1.72727272727273e+01 -4.62460538476065e-01 3.66218257085999e-01 3.31074211396244e-02 +-1.66666666666667e+01 -4.46940500203995e-01 3.60904945553023e-01 2.80723751195183e-02 +-1.60606060606061e+01 -4.31475323775307e-01 3.55515132392443e-01 2.31037263323430e-02 +-1.54545454545455e+01 -4.16068349642614e-01 3.50047632879528e-01 1.82220369706882e-02 +-1.48484848484848e+01 -4.00721354508913e-01 3.44500616736217e-01 1.35484980910323e-02 +-1.42424242424242e+01 -3.85436695885767e-01 3.38872341578923e-01 9.50016605244364e-03 +-1.36363636363636e+01 -3.70224538567261e-01 3.33164648622073e-01 5.68381330007907e-03 +-1.30303030303030e+01 -3.55069373476952e-01 3.27366609646139e-01 2.21886814225965e-03 +-1.24242424242424e+01 -3.39999733693878e-01 3.21489179943910e-01 -1.51885448689381e-03 +-1.18181818181818e+01 -3.24995626539620e-01 3.15518354985586e-01 -7.39251364704825e-03 +-1.12121212121212e+01 -3.10077560762327e-01 3.09460976947365e-01 -1.32657016910330e-02 +-1.06060606060606e+01 -2.95245474304323e-01 3.02802644980894e-01 -1.91393272151166e-02 +-1.00000000000000e+01 -2.80494800381428e-01 2.94941318686088e-01 -2.50125850968491e-02 +-9.39393939393939e+00 -2.53378368416910e-01 2.85498339501372e-01 -2.41110800948355e-02 +-8.78787878787879e+00 -2.26455617318188e-01 2.75839796452712e-01 -2.32151737520043e-02 +-8.18181818181818e+00 -1.99780347135765e-01 2.65960153502913e-01 -2.23116063606220e-02 +-7.57575757575758e+00 -1.73389839145603e-01 2.55848927836634e-01 -2.13969572586265e-02 +-6.96969696969697e+00 -1.47345183372831e-01 2.45482961997361e-01 -2.03679525995866e-02 +-6.36363636363636e+00 -1.21705108097721e-01 2.34834463036821e-01 -1.93275559307849e-02 +-5.75757575757576e+00 -9.84583488516512e-02 2.23910273504550e-01 -1.82871145503072e-02 +-5.15151515151515e+00 -7.69804748827422e-02 2.12678155631259e-01 -1.72546758160953e-02 +-4.54545454545454e+00 -5.63182850040337e-02 2.01106147724455e-01 -1.62156816231646e-02 +-3.93939393939394e+00 -3.67302227953779e-02 1.89186489694562e-01 -1.51750925589128e-02 +-3.33333333333333e+00 -1.62909510485965e-02 1.78416547415723e-01 -1.45633390580307e-02 +-2.72727272727273e+00 2.35675611773452e-02 1.75058203392890e-01 -1.57637846300459e-02 +-2.12121212121212e+00 9.15064277602737e-02 1.76056082872914e-01 -1.78244951342892e-02 +-1.51515151515152e+00 1.59451497183287e-01 1.77051126032286e-01 -2.03910649409379e-02 +-9.09090909090912e-01 2.23403602833365e-01 1.78026120925083e-01 -2.27493568922369e-02 +-3.03030303030302e-01 2.84237891949164e-01 1.78938378727225e-01 -2.51368568675113e-02 + 3.03030303030302e-01 3.45074372567327e-01 1.79925592577568e-01 -2.75148616917628e-02 + 9.09090909090912e-01 4.05913145027735e-01 1.80910163063640e-01 -2.98751951472708e-02 + 1.51515151515152e+00 4.60391564367498e-01 1.81869640777608e-01 -3.22531226669864e-02 + 2.12121212121212e+00 5.26159436695712e-01 1.81867217039864e-01 -3.48049504623527e-02 + 2.72727272727273e+00 6.00837730272748e-01 1.81506752812675e-01 -3.74260524663783e-02 + 3.33333333333333e+00 6.75529949068352e-01 1.81145950978939e-01 -4.00304350025881e-02 + 3.93939393939394e+00 7.50255901253955e-01 1.80716836967219e-01 -4.26350339105715e-02 + 4.54545454545455e+00 8.24966195051160e-01 1.80347288666951e-01 -4.52499112015484e-02 + 5.15151515151515e+00 8.99712588876260e-01 1.79976785308154e-01 -4.78545175714740e-02 + 5.75757575757576e+00 9.67968657716851e-01 1.79568694884216e-01 -5.06699455716737e-02 + 6.36363636363637e+00 1.02536319902264e+00 1.79238042626890e-01 -5.38531921907918e-02 + 6.96969696969697e+00 1.08152198541483e+00 1.78841802101979e-01 -5.70812124887872e-02 + 7.57575757575757e+00 1.13835718017464e+00 1.78513776681022e-01 -6.02799006382464e-02 + 8.18181818181818e+00 1.20034525413988e+00 1.78155584214918e-01 -6.32698190171098e-02 + 8.78787878787879e+00 1.25229031916550e+00 1.78543028590070e-01 -6.64922350787756e-02 + 9.39393939393939e+00 1.27694825197027e+00 1.80574010062172e-01 -7.03025346844773e-02 + 1.00000000000000e+01 1.29634873488058e+00 1.82986102023255e-01 -7.42574649964911e-02 + 1.06060606060606e+01 7.61428140940585e-01 2.15852259319746e-01 -6.42507106934242e-02 + 1.12121212121212e+01 6.15718379411708e-01 2.48106113414377e-01 -2.23104303837720e-02 + 1.18181818181818e+01 5.89645960609568e-01 2.71990713431963e-01 -2.03506593942910e-02 + 1.24242424242424e+01 8.40078452027123e-01 2.92157538787909e-01 -2.37998425692650e-02 + 1.30303030303030e+01 9.36540372696081e-01 3.08975183148329e-01 -2.65133219580019e-02 + 1.36363636363636e+01 9.30793183702627e-01 3.21455925212482e-01 -2.79339590650596e-02 + 1.42424242424242e+01 9.21535598013246e-01 3.32263191328175e-01 -2.92269843086423e-02 + 1.48484848484848e+01 8.79920211959341e-01 3.42195165358544e-01 -3.05512733483560e-02 + 1.54545454545455e+01 8.39112171194525e-01 3.50890504854493e-01 -3.17289039382959e-02 + 1.60606060606061e+01 8.05866011124999e-01 3.58713280531263e-01 -3.32426789378008e-02 + 1.66666666666667e+01 8.00847317731894e-01 3.63662607459754e-01 -3.82620408096336e-02 + 1.72727272727273e+01 7.94727809634000e-01 3.68473291646017e-01 -4.36253357634993e-02 + 1.78787878787879e+01 7.87227516277651e-01 3.73122818099744e-01 -4.94117560810391e-02 + 1.84848484848485e+01 7.79760973975816e-01 3.77747724480973e-01 -5.53090732287109e-02 + 1.90909090909091e+01 7.72322946522647e-01 3.82350733174758e-01 -6.13053346702226e-02 + 1.96969696969697e+01 7.64912514438728e-01 3.86935069316851e-01 -6.73885480064952e-02 + 2.03030303030303e+01 7.60227909567809e-01 3.92147459389974e-01 -7.23552962067858e-02 + 2.09090909090909e+01 7.58256171990743e-01 3.97975580174912e-01 -7.61741534254430e-02 + 2.15151515151515e+01 7.56296648702810e-01 4.03762544083001e-01 -8.00356859572341e-02 + 2.21212121212121e+01 7.54349708693408e-01 4.09506354183381e-01 -8.39389232226646e-02 + 2.27272727272727e+01 7.52415756848464e-01 4.15204822592555e-01 -8.78828761836009e-02 + 2.33333333333333e+01 7.50495135179352e-01 4.20855853060512e-01 -9.18667405374683e-02 + 2.39393939393939e+01 7.48588246026085e-01 4.26457068308669e-01 -9.58896488905942e-02 + 2.45454545454545e+01 7.46695508084816e-01 4.32005929515122e-01 -9.99507588032690e-02 + 2.51515151515151e+01 7.44817357247520e-01 4.37499722355814e-01 -1.04049251898781e-01 + 2.57575757575758e+01 7.42954247493942e-01 4.42935541572834e-01 -1.08184333010354e-01 + 2.63636363636364e+01 7.41106620219380e-01 4.48310365722169e-01 -1.12355301356762e-01 + 2.69696969696970e+01 7.39274979765670e-01 4.53620820905796e-01 -1.16561383374543e-01 + 2.75757575757576e+01 7.37459861618629e-01 4.58863256541540e-01 -1.20801801101431e-01 + 2.81818181818182e+01 7.35661817641651e-01 4.64033768336758e-01 -1.25075807437783e-01 + 2.87878787878788e+01 7.33881427635071e-01 4.69128142491057e-01 -1.29382661238589e-01 + 2.93939393939394e+01 7.32119240063399e-01 4.74141998928450e-01 -1.33721775955579e-01 + 3.00000000000000e+01 7.30375865782397e-01 4.79070493417508e-01 -1.38092497824076e-01 + 3.30000000000000e+01 7.25362478438806e-01 5.14615368361460e-01 -1.54403266201777e-01 + 3.60000000000000e+01 7.20501914137933e-01 5.71996513757487e-01 -1.68191263513666e-01 + 3.90000000000000e+01 7.15809365515503e-01 6.29378755052664e-01 -1.81374882567390e-01 + 4.20000000000000e+01 7.03433185279059e-01 6.88722323451288e-01 -1.93418520707176e-01 + 4.50000000000000e+01 6.87204092577322e-01 7.49047128580672e-01 -2.04892279627535e-01 + 4.80000000000000e+01 6.71041224113679e-01 8.09371242445124e-01 -2.16365907069522e-01 + 5.10000000000000e+01 6.49672046103066e-01 8.68067342326066e-01 -2.27288040920096e-01 + 5.40000000000000e+01 6.17781812255886e-01 9.23507309578663e-01 -2.37107152133572e-01 + 5.70000000000000e+01 5.85917028103372e-01 9.74580508981902e-01 -2.46926188334836e-01 + 6.00000000000000e+01 5.54082947327309e-01 1.02455645022712e+00 -2.56745187030279e-01 + 6.30000000000000e+01 5.07474214362050e-01 1.06294844515890e+00 -2.64611277891633e-01 + 6.60000000000000e+01 4.60875379522342e-01 1.10134034079787e+00 -2.72477352013468e-01 + 6.90000000000000e+01 4.14290290845089e-01 1.13973223643685e+00 -2.80343426135302e-01 + 7.20000000000000e+01 3.60455499151900e-01 1.16675119940570e+00 -2.86657663083315e-01 + 7.50000000000000e+01 3.02992179274825e-01 1.18808392885856e+00 -2.92196013212590e-01 + 7.80000000000000e+01 2.45532428311787e-01 1.20941690276751e+00 -2.97734426806946e-01 + 8.10000000000000e+01 1.86507133137001e-01 1.22393767993261e+00 -3.02380776716557e-01 + 8.40000000000000e+01 1.24338355198263e-01 1.22483453383895e+00 -3.05243060833536e-01 + 8.70000000000000e+01 6.21691023243765e-02 1.22573139459675e+00 -3.07300455628019e-01 + 9.00000000000000e+01 -2.71507463581614e-07 1.22662824758516e+00 -3.07541711312162e-01 + 9.30000000000000e+01 -4.35018613516539e-02 1.22573139367882e+00 -3.15242230954016e-01 + 9.60000000000000e+01 -8.70036173585537e-02 1.22483453634678e+00 -3.19516785688025e-01 + 9.90000000000000e+01 -1.30505705696887e-01 1.22393767216320e+00 -3.23791373077473e-01 + 1.02000000000000e+02 -1.71816981097322e-01 1.20941679944765e+00 -3.25358337127833e-01 + 1.05000000000000e+02 -2.12037421291888e-01 1.18808406999478e+00 -3.25571518828366e-01 + 1.08000000000000e+02 -2.52261395940272e-01 1.16675109608688e+00 -3.25784702971782e-01 + 1.11000000000000e+02 -2.89967780617593e-01 1.13973190385125e+00 -3.24839117221471e-01 + 1.14000000000000e+02 -3.22643517723843e-01 1.10134044814828e+00 -3.21576026976400e-01 + 1.17000000000000e+02 -3.55328226413339e-01 1.06294869915767e+00 -3.18312911803281e-01 + 1.20000000000000e+02 -3.88019404664959e-01 1.02455678086533e+00 -3.15049779750259e-01 + 1.23000000000000e+02 -4.10305382623878e-01 9.74580839620111e-01 -3.09528742082193e-01 + 1.26000000000000e+02 -4.32612975232015e-01 9.23507676366582e-01 -3.04007683325731e-01 + 1.29000000000000e+02 -4.54938482726295e-01 8.68067709113984e-01 -2.98486582390899e-01 + 1.32000000000000e+02 -4.69867035979492e-01 8.09371180701210e-01 -2.92718253920303e-01 + 1.35000000000000e+02 -4.81136499725427e-01 7.49046375576140e-01 -2.86826311975596e-01 + 1.38000000000000e+02 -4.92453728624275e-01 6.88722261711688e-01 -2.80934437546522e-01 + 1.41000000000000e+02 -5.01081625048703e-01 6.29378805912717e-01 -2.75982450882136e-01 + 1.44000000000000e+02 -5.04343461108966e-01 5.71996674202226e-01 -2.72910247373812e-01 + 1.47000000000000e+02 -5.07722631231294e-01 5.14614980861448e-01 -2.69838067335530e-01 + 1.50000000000000e+02 -5.11208424965791e-01 4.79070665595519e-01 -2.66765899031848e-01 + 1.53000000000000e+02 -5.17411720704259e-01 4.53884562381070e-01 -2.74892073545017e-01 + 1.56000000000000e+02 -5.23897762918947e-01 4.27014220182996e-01 -2.83018243112307e-01 + 1.59000000000000e+02 -5.30626275353240e-01 3.98846265744607e-01 -2.91144350600985e-01 + 1.62000000000000e+02 -4.95885499788614e-01 3.75931646834106e-01 -3.27060715613266e-01 + 1.65000000000000e+02 -4.40412121695890e-01 3.55419527359135e-01 -3.76872444414846e-01 + 1.68000000000000e+02 -3.85054442612432e-01 3.34234373573580e-01 -4.26683602422472e-01 + 1.71000000000000e+02 -3.13409902357768e-01 3.16774623015665e-01 -4.13902641435275e-01 + 1.74000000000000e+02 -2.08939500216179e-01 3.07632373564454e-01 -2.75934520221132e-01 + 1.77000000000000e+02 -1.03993393584518e-01 2.98099548900633e-01 -1.37338163129622e-01 + 1.80000000000000e+02 0.00000000000000e+00 2.86667939639823e-01 0.00000000000000e+00 diff --git a/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_04.dat b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_04.dat new file mode 100644 index 00000000..abbe8560 --- /dev/null +++ b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_04.dat @@ -0,0 +1,254 @@ +! ------------ AirfoilInfo v1.01.x Input File ---------------------------------- +! AeroElasticSE FAST driver +! line +! line +! ------------------------------------------------------------------------------ +DEFAULT InterpOrd ! Interpolation order to use for quasi-steady table lookup {1=linear; 3=cubic spline; "default"} [default=3] +1 NonDimArea ! The non-dimensional area of the airfoil (area/chord^2) (set to 1.0 if unsure or unneeded) +@"NREL-2p8-127_AF04_Coords.txt" NumCoords ! The number of coordinates in the airfoil shape file. Set to zero if coordinates not included. +AF04_BL.txt BL_file ! The file name including the boundary layer characteristics of the profile. Ignored if the aeroacoustic module is not called. +1 NumTabs ! Number of airfoil tables in this file. Each table must have lines for Re and Ctrl. +! ------------------------------------------------------------------------------ +! data for table 1 +! ------------------------------------------------------------------------------ +6.000000 Re ! Reynolds number in millions +0 Ctrl ! Control setting (must be 0 for current AirfoilInfo) +True InclUAdata ! Is unsteady aerodynamics data included in this table? If TRUE, then include 30 UA coefficients below this line +!........................................ +0.000000 alpha0 ! 0-lift angle of attack, depends on airfoil. +0.000000 alpha1 ! Angle of attack at f=0.7, (approximately the stall angle) for AOA>alpha0. (deg) +0.000000 alpha2 ! Angle of attack at f=0.7, (approximately the stall angle) for AOA1] +0.000000 S2 ! Constant in the f curve best-fit for AOA> alpha1; by definition it depends on the airfoil. [ignored if UAMod<>1] +0.000000 S3 ! Constant in the f curve best-fit for alpha2<=AOA< alpha0; by definition it depends on the airfoil. [ignored if UAMod<>1] +0.000000 S4 ! Constant in the f curve best-fit for AOA< alpha2; by definition it depends on the airfoil. [ignored if UAMod<>1] +0.000000 Cn1 ! Critical value of C0n at leading edge separation. It should be extracted from airfoil data at a given Mach and Reynolds number. It can be calculated from the static value of Cn at either the break in the pitching moment or the loss of chord force at the onset of stall. It is close to the condition of maximum lift of the airfoil at low Mach numbers. +0.000000 Cn2 ! As Cn1 for negative AOAs. +Default St_sh ! Strouhal's shedding frequency constant. [default = 0.19] +0.000000 Cd0 ! 2D drag coefficient value at 0-lift. +0.000000 Cm0 ! 2D pitching moment coefficient about 1/4-chord location, at 0-lift, positive if nose up. [If the aerodynamics coefficients table does not include a column for Cm, this needs to be set to 0.0] +0.000000 k0 ! Constant in the \hat(x)_cp curve best-fit; = (\hat(x)_AC-0.25). [ignored if UAMod<>1] +0.000000 k1 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k2 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k3 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k1_hat ! Constant in the expression of Cc due to leading edge vortex effects. [ignored if UAMod<>1] +Default x_cp_bar ! Constant in the expression of \hat(x)_cp^v. [ignored if UAMod<>1, default = 0.2] +Default UACutout ! Angle of attack above which unsteady aerodynamics are disabled (deg). [Specifying the string "Default" sets UACutout to 45 degrees] +Default filtCutOff ! Cut-off frequency (-3 dB corner frequency) for low-pass filtering the AoA input to UA, as well as the 1st and 2nd derivatives (Hz) [default = 20] +!........................................ +! Table of aerodynamics coefficients +200 NumAlf ! Number of data lines in the following table +! Alpha Cl Cd Cm +! (deg) (-) (-) (-) +-1.80000000000000e+02 0.00000000000000e+00 1.52890685398725e-01 0.00000000000000e+00 +-1.77000000000000e+02 1.31704479748411e-01 1.63763723652671e-01 1.19452717008645e-01 +-1.74000000000000e+02 2.64615541683425e-01 1.74744683765139e-01 2.39999774321882e-01 +-1.71000000000000e+02 3.96924138305795e-01 1.85683483417484e-01 3.60000410445527e-01 +-1.68000000000000e+02 4.83692709572010e-01 2.10410090026251e-01 3.83359490424043e-01 +-1.65000000000000e+02 5.47678400067375e-01 2.42039936419247e-01 3.58398920279377e-01 +-1.62000000000000e+02 6.11661936785840e-01 2.73684904094820e-01 3.33438064107582e-01 +-1.59000000000000e+02 6.49147890945894e-01 3.10889487497261e-01 3.13527249627107e-01 +-1.56000000000000e+02 6.33627994109589e-01 3.59203284556557e-01 3.03716295849012e-01 +-1.53000000000000e+02 6.18102771363694e-01 4.07545900233725e-01 2.93905168850931e-01 +-1.50000000000000e+02 6.02571440780362e-01 4.55925647601040e-01 2.84093898343018e-01 +-1.47000000000000e+02 5.93851743225456e-01 5.14758887292997e-01 2.87063352917468e-01 +-1.44000000000000e+02 5.85129730070885e-01 5.73263830376554e-01 2.90032783400607e-01 +-1.41000000000000e+02 5.76405140982154e-01 6.31769220410934e-01 2.93002194449487e-01 +-1.38000000000000e+02 5.62958434932229e-01 6.92274906461514e-01 2.98271914144742e-01 +-1.35000000000000e+02 5.47150816004827e-01 7.53780736462377e-01 3.04691792390807e-01 +-1.32000000000000e+02 5.31341994964165e-01 8.15287271265272e-01 3.11111734292256e-01 +-1.29000000000000e+02 5.11898674393990e-01 8.75134136992628e-01 3.17501821606841e-01 +-1.26000000000000e+02 4.85188015388141e-01 9.31661656684178e-01 3.23832218317126e-01 +-1.23000000000000e+02 4.58477182925037e-01 9.88188744534565e-01 3.30162566296010e-01 +-1.20000000000000e+02 4.31765994733252e-01 1.04471561647244e+00 3.36492889647229e-01 +-1.17000000000000e+02 3.94568156643264e-01 1.08888387091091e+00 3.40603620297433e-01 +-1.14000000000000e+02 3.57370304957649e-01 1.13305193246859e+00 3.44714328600463e-01 +-1.11000000000000e+02 3.20172552298473e-01 1.17721965661140e+00 3.48825002561235e-01 +-1.08000000000000e+02 2.77962126266291e-01 1.20912806034645e+00 3.50515840614408e-01 +-1.05000000000000e+02 2.33245372677999e-01 1.23490671052890e+00 3.50996730156169e-01 +-1.02000000000000e+02 1.88529066354869e-01 1.26068506531321e+00 3.51477592241862e-01 +-9.90000000000000e+01 1.42846269453300e-01 1.27908367222767e+00 3.50498451065250e-01 +-9.60000000000000e+01 9.52306422330625e-02 1.28272246374676e+00 3.46599247549748e-01 +-9.30000000000000e+01 4.76153787695439e-02 1.28636122746753e+00 3.42699970222382e-01 +-9.00000000000000e+01 2.97181093101284e-07 1.28999997728939e+00 3.38877476679819e-01 +-8.70000000000000e+01 -4.76153300354876e-02 1.28636123119179e+00 3.34288189245273e-01 +-8.40000000000000e+01 -9.52307753769642e-02 1.28272245357189e+00 3.29739597523247e-01 +-8.10000000000000e+01 -1.42845856965667e-01 1.27908370375002e+00 3.25207993177059e-01 +-7.80000000000000e+01 -1.88528849782130e-01 1.26068519016437e+00 3.17955441758359e-01 +-7.50000000000000e+01 -2.33245668518482e-01 1.23490653998066e+00 3.09344032062908e-01 +-7.20000000000000e+01 -2.77961909696404e-01 1.20912818519635e+00 3.00732721046221e-01 +-6.90000000000000e+01 -3.20172230052935e-01 1.17722003923687e+00 2.91121626468145e-01 +-6.60000000000000e+01 -3.57370408969930e-01 1.13305180896654e+00 2.79510882896335e-01 +-6.30000000000000e+01 -3.94568402742750e-01 1.08888357869621e+00 2.67900139324525e-01 +-6.00000000000000e+01 -4.31766171454802e-01 1.04471524249362e+00 2.56289382389432e-01 +-5.70000000000000e+01 -4.58477359643245e-01 9.88188370555741e-01 2.43119604599202e-01 +-5.40000000000000e+01 -4.85188192105633e-01 9.31661282701068e-01 2.29949776504115e-01 +-5.10000000000000e+01 -5.11898851109208e-01 8.75133763009519e-01 2.16779847798548e-01 +-4.80000000000000e+01 -5.31341959036239e-01 8.15287334218715e-01 2.03370614403917e-01 +-4.50000000000000e+01 -5.47150557766459e-01 7.53781504217852e-01 1.89841732510719e-01 +-4.20000000000000e+01 -5.62958388264277e-01 6.92274969410558e-01 1.76312695587616e-01 +-3.90000000000000e+01 -5.76405141219782e-01 6.31769168555292e-01 1.62884018923624e-01 +-3.60000000000000e+01 -5.85129736228324e-01 5.73263666791100e-01 1.49655804982024e-01 +-3.30000000000000e+01 -5.93851682613004e-01 5.14759282378343e-01 1.36427843675875e-01 +-3.00000000000000e+01 -6.02571527674987e-01 4.55925302880350e-01 1.23199622280574e-01 +-2.93939393939394e+01 -6.05709742968724e-01 4.46148292728679e-01 1.20183218217587e-01 +-2.87878787878788e+01 -6.08847690581429e-01 4.36373153786693e-01 1.17176335932680e-01 +-2.81818181818182e+01 -6.11985380005597e-01 4.26599779864539e-01 1.14168793413229e-01 +-2.75757575757576e+01 -6.15122858980615e-01 4.16827876718823e-01 1.11160516192624e-01 +-2.69696969696970e+01 -6.18260109619839e-01 4.07057465245291e-01 1.08151524224604e-01 +-2.63636363636364e+01 -6.21397122656834e-01 3.97288544820632e-01 1.05141828538283e-01 +-2.57575757575758e+01 -6.24533844014296e-01 3.87521148707597e-01 1.02131448274330e-01 +-2.51515151515151e+01 -6.27670245374249e-01 3.77755259564324e-01 9.91203848845818e-02 +-2.45454545454545e+01 -6.30806424352339e-01 3.67990641254345e-01 9.61085707127930e-02 +-2.39393939393939e+01 -6.33942376901069e-01 3.58227230091829e-01 9.30959891641372e-02 +-2.33333333333333e+01 -6.37078020453462e-01 3.48464966576383e-01 9.00826225283333e-02 +-2.27272727272727e+01 -6.40213455369502e-01 3.38703795054776e-01 8.70684539419758e-02 +-2.21212121212121e+01 -6.43348687727384e-01 3.28943663414953e-01 8.40534654418665e-02 +-2.15151515151515e+01 -6.46483666873065e-01 3.19184299164519e-01 8.10375681805418e-02 +-2.09090909090909e+01 -6.49618442068989e-01 3.09425824234104e-01 7.80207956612929e-02 +-2.03030303030303e+01 -6.52753032833882e-01 2.99668251498965e-01 7.50031458623772e-02 +-1.96969696969697e+01 -6.46281639088916e-01 2.90949411270925e-01 7.04968593518714e-02 +-1.90909090909091e+01 -6.30204218160431e-01 2.83269742867490e-01 6.45023032212650e-02 +-1.84848484848485e+01 -6.14126582290594e-01 2.75592004359402e-01 5.85074349929442e-02 +-1.78787878787879e+01 -5.98047856789765e-01 2.67915828822348e-01 5.25118142631482e-02 +-1.72727272727273e+01 -5.81967302635588e-01 2.60240916364328e-01 4.65150110129194e-02 +-1.66666666666667e+01 -5.65885606263078e-01 2.52567649498003e-01 4.05170693283586e-02 +-1.60606060606061e+01 -5.49802714208954e-01 2.44896059615267e-01 3.45176730639480e-02 +-1.54545454545455e+01 -5.33719399306242e-01 2.37226574370814e-01 2.85166866132808e-02 +-1.48484848484848e+01 -5.17634634029050e-01 2.29558765259197e-01 2.25131018007247e-02 +-1.42424242424242e+01 -5.01547801579493e-01 2.21892402675115e-01 1.65057329856289e-02 +-1.36363636363636e+01 -4.85463674091492e-01 2.14231747747893e-01 1.04934903363307e-02 +-1.30303030303030e+01 -4.69370079236432e-01 2.06565470271126e-01 4.47314506258597e-03 +-1.24242424242424e+01 -4.53283193318206e-01 1.98908867060531e-01 -1.54613211877309e-03 +-1.18181818181818e+01 -4.37187366788929e-01 1.91247369015575e-01 -7.53424241146752e-03 +-1.12121212121212e+01 -4.21093768204950e-01 1.83591167142366e-01 -1.35218680172613e-02 +-1.06060606060606e+01 -4.04998617109735e-01 1.75937905154481e-01 -1.95099338612331e-02 +-1.00000000000000e+01 -3.88896565106125e-01 1.68281357120578e-01 -2.54976171334784e-02 +-9.39393939393939e+00 -3.56980581536747e-01 1.60570608546530e-01 -2.45787021969936e-02 +-8.78787878787879e+00 -3.25052844156906e-01 1.52859809151608e-01 -2.36654666080170e-02 +-8.18181818181818e+00 -2.93123808227596e-01 1.45152920413788e-01 -2.27443554637733e-02 +-7.57575757575758e+00 -2.61189540733289e-01 1.37458302486576e-01 -2.18232254306519e-02 +-6.96969696969697e+00 -2.29253315550365e-01 1.29770338259547e-01 -2.09121948405043e-02 +-6.36363636363636e+00 -1.97299114478799e-01 1.22078681072535e-01 -1.99910067472643e-02 +-5.75757575757576e+00 -1.65337094409309e-01 1.14401642642313e-01 -1.90688307982063e-02 +-5.15151515151515e+00 -1.33363372258401e-01 1.06731125985166e-01 -1.81553134789971e-02 +-4.54545454545454e+00 -1.01365853608070e-01 9.90577635911853e-02 -1.72377886839538e-02 +-3.93939393939394e+00 -6.93567841681647e-02 9.14006376859695e-02 -1.63172897943185e-02 +-3.33333333333333e+00 -3.31807555093951e-02 8.46570826009648e-02 -1.57731499131537e-02 +-2.72727272727273e+00 2.39727377628819e-02 8.25273948895898e-02 -1.71381638240559e-02 +-2.12121212121212e+00 9.32486327068270e-02 8.31141750981614e-02 -1.96272564550678e-02 +-1.51515151515152e+00 1.62528583105757e-01 8.37008175454388e-02 -2.21076923365064e-02 +-9.09090909090912e-01 2.31797235397626e-01 8.42859193789413e-02 -2.45940451844470e-02 +-3.03030303030302e-01 3.01068246865505e-01 8.48656437169153e-02 -2.70868281606804e-02 + 3.03030303030302e-01 3.70338484450812e-01 8.54523328928443e-02 -2.95712433598367e-02 + 9.09090909090912e-01 4.39610300212106e-01 8.60391036829737e-02 -3.20559148731745e-02 + 1.51515151515152e+00 5.09192579530866e-01 8.66138848674114e-02 -3.45449324288621e-02 + 2.12121212121212e+00 5.86406064228343e-01 8.66581954835795e-02 -3.72379475609113e-02 + 2.72727272727273e+00 6.67209757832241e-01 8.64425327187755e-02 -4.00378706815080e-02 + 3.33333333333333e+00 7.48006310769884e-01 8.62268646743108e-02 -4.28376526659724e-02 + 3.93939393939394e+00 8.28814559558240e-01 8.60123335176102e-02 -4.56376672559721e-02 + 4.54545454545455e+00 9.09607713918266e-01 8.57976670724705e-02 -4.84274348252293e-02 + 5.15151515151515e+00 9.90415750809011e-01 8.55913123524140e-02 -5.12274574370195e-02 + 5.75757575757576e+00 1.06840447148798e+00 8.53816156813169e-02 -5.42125455584405e-02 + 6.36363636363637e+00 1.14160400255878e+00 8.51849910150180e-02 -5.75066351634233e-02 + 6.96969696969697e+00 1.21413721717018e+00 8.49944037839137e-02 -6.08487619763315e-02 + 7.57575757575757e+00 1.28664609286845e+00 8.48025295082906e-02 -6.41936917237977e-02 + 8.18181818181818e+00 1.35907367282053e+00 8.46074089108589e-02 -6.75395926025836e-02 + 8.78787878787879e+00 1.42498875451348e+00 8.48939582739108e-02 -7.11385484353892e-02 + 9.39393939393939e+00 1.47790044040096e+00 8.61562125019175e-02 -7.52537462367865e-02 + 1.00000000000000e+01 1.52761951021426e+00 8.76527806305783e-02 -7.94958935415669e-02 + 1.06060606060606e+01 1.21037111221097e+00 1.08368637158632e-01 -7.47780360782507e-02 + 1.12121212121212e+01 1.06745252059869e+00 1.30650270554887e-01 -4.13744293556483e-02 + 1.18181818181818e+01 1.04047682231151e+00 1.48602204458626e-01 -3.87322662567038e-02 + 1.24242424242424e+01 1.02050139325215e+00 1.65510670067403e-01 -4.07401587716326e-02 + 1.30303030303030e+01 1.00956882423978e+00 1.81609086020050e-01 -4.27814866733380e-02 + 1.36363636363636e+01 1.00743778578338e+00 1.96445539032532e-01 -4.48202992152467e-02 + 1.42424242424242e+01 1.00757475615447e+00 2.09842058498476e-01 -4.68758763258071e-02 + 1.48484848484848e+01 1.00899715128062e+00 2.22621760789065e-01 -4.89826947132140e-02 + 1.54545454545455e+01 1.01148957933609e+00 2.34179209308161e-01 -5.10542451445077e-02 + 1.60606060606061e+01 1.01288900592554e+00 2.45010338785109e-01 -5.35062027787723e-02 + 1.66666666666667e+01 1.00195252813289e+00 2.52941797110189e-01 -5.94879954798757e-02 + 1.72727272727273e+01 9.90372353173637e-01 2.60712604214289e-01 -6.56606862514200e-02 + 1.78787878787879e+01 9.78006308087524e-01 2.68286875927460e-01 -7.20666332697287e-02 + 1.84848484848485e+01 9.65644506690629e-01 2.75856403296140e-01 -7.84749075877025e-02 + 1.90909090909091e+01 9.53284332352213e-01 2.83426080329155e-01 -8.48813171286689e-02 + 1.96969696969697e+01 9.40924882807228e-01 2.91001781071828e-01 -9.12808153392477e-02 + 2.03030303030303e+01 9.32508485341658e-01 2.99668251498965e-01 -9.63197520692682e-02 + 2.09090909090909e+01 9.28035612370247e-01 3.09425824234104e-01 -9.99987465351088e-02 + 2.15151515151515e+01 9.23562474293211e-01 3.19184299164519e-01 -1.03676821203003e-01 + 2.21212121212121e+01 9.19089043051198e-01 3.28943663414953e-01 -1.07353977654978e-01 + 2.27272727272727e+01 9.14615247866511e-01 3.38703795054776e-01 -1.11030178126034e-01 + 2.33333333333333e+01 9.10141161527127e-01 3.48464966576383e-01 -1.14705513496165e-01 + 2.39393939393939e+01 9.05666775287466e-01 3.58227230091829e-01 -1.18380002566973e-01 + 2.45454545454545e+01 9.01191945397226e-01 3.67990641254345e-01 -1.22053668013310e-01 + 2.51515151515151e+01 8.96716790059191e-01 3.77755259564324e-01 -1.25726522238022e-01 + 2.57575757575758e+01 8.92241315022274e-01 3.87521148707597e-01 -1.29398582102913e-01 + 2.63636363636364e+01 8.87765380758913e-01 3.97288544820632e-01 -1.33069928789038e-01 + 2.69696969696970e+01 8.83289027675016e-01 4.07057465245291e-01 -1.36740556769150e-01 + 2.75757575757576e+01 8.78812332951360e-01 4.16827876718823e-01 -1.40410439162852e-01 + 2.81818181818182e+01 8.74335309658910e-01 4.26599779864539e-01 -1.44079560303650e-01 + 2.87878787878788e+01 8.69857983172985e-01 4.36373153786694e-01 -1.47747893479490e-01 + 2.93939393939394e+01 8.65380285398246e-01 4.46148292728679e-01 -1.51415526599333e-01 + 3.00000000000000e+01 8.60902202671727e-01 4.55925302880350e-01 -1.55082474171227e-01 + 3.30000000000000e+01 8.48397959434636e-01 5.14759282378343e-01 -1.68663399184894e-01 + 3.60000000000000e+01 8.35890707575628e-01 5.73263666791100e-01 -1.82298027595826e-01 + 3.90000000000000e+01 8.23379662232036e-01 6.31769168555292e-01 -1.95945868274559e-01 + 4.20000000000000e+01 8.04154954731604e-01 6.92274969410558e-01 -2.08554266597334e-01 + 4.50000000000000e+01 7.81573458480718e-01 7.53781504217852e-01 -2.20643060705334e-01 + 4.80000000000000e+01 7.58990915560083e-01 8.15287334218715e-01 -2.32731716287242e-01 + 5.10000000000000e+01 7.31215839592101e-01 8.75133763009519e-01 -2.44320755354886e-01 + 5.40000000000000e+01 6.93057699659601e-01 9.31661282701068e-01 -2.54910529274792e-01 + 5.70000000000000e+01 6.54899314951571e-01 9.88188370555741e-01 -2.65500222295077e-01 + 6.00000000000000e+01 6.16740425757725e-01 1.04471524249362e+00 -2.76089874865860e-01 + 6.30000000000000e+01 5.63629556606820e-01 1.08888357869621e+00 -2.84820525032635e-01 + 6.60000000000000e+01 5.10518346428343e-01 1.13305180896654e+00 -2.93551159264809e-01 + 6.90000000000000e+01 4.57406844501805e-01 1.17722003923687e+00 -3.02281793496983e-01 + 7.20000000000000e+01 3.97127599293486e-01 1.20912818519635e+00 -3.09472835540815e-01 + 7.50000000000000e+01 3.33264710335960e-01 1.23490653998066e+00 -3.15894113007981e-01 + 7.80000000000000e+01 2.69400999928860e-01 1.26068519016437e+00 -3.22315464057870e-01 + 8.10000000000000e+01 2.04142652815547e-01 1.27908370375002e+00 -3.27816939705399e-01 + 8.40000000000000e+01 1.36095393510895e-01 1.28272245357189e+00 -3.31478728044814e-01 + 8.70000000000000e+01 6.80476143629091e-02 1.28636123119179e+00 -3.35157787608892e-01 + 9.00000000000000e+01 -2.97181093302924e-07 1.28999997728939e+00 -3.38875766435868e-01 + 9.30000000000000e+01 -4.76153787695439e-02 1.28636122746753e+00 -3.42699882733940e-01 + 9.60000000000000e+01 -9.52306422330627e-02 1.28272246374676e+00 -3.46597404225314e-01 + 9.90000000000000e+01 -1.42846269453301e-01 1.27908367222767e+00 -3.50494955491782e-01 + 1.02000000000000e+02 -1.88529066354869e-01 1.26068506531321e+00 -3.51472552278717e-01 + 1.05000000000000e+02 -2.33245372677999e-01 1.23490671052890e+00 -3.50990203444848e-01 + 1.08000000000000e+02 -2.77962126266291e-01 1.20912806034645e+00 -3.50507849083669e-01 + 1.11000000000000e+02 -3.20172552298473e-01 1.17721965661140e+00 -3.48815656358806e-01 + 1.14000000000000e+02 -3.57370304957649e-01 1.13305193246859e+00 -3.44703823754748e-01 + 1.17000000000000e+02 -3.94568156643264e-01 1.08888387091091e+00 -3.40591959738759e-01 + 1.20000000000000e+02 -4.31765994733252e-01 1.04471561647244e+00 -3.36480075676600e-01 + 1.23000000000000e+02 -4.58477182925037e-01 9.88188744534564e-01 -3.30149032834181e-01 + 1.26000000000000e+02 -4.85188015388141e-01 9.31661656684178e-01 -3.23817965809434e-01 + 1.29000000000000e+02 -5.11898674393990e-01 8.75134136992627e-01 -3.17486850418223e-01 + 1.32000000000000e+02 -5.31341994964165e-01 8.15287271265271e-01 -3.11096424528303e-01 + 1.35000000000000e+02 -5.47150816004827e-01 7.53780736462377e-01 -3.04676343460043e-01 + 1.38000000000000e+02 -5.62958434932230e-01 6.92274906461514e-01 -2.98256335959350e-01 + 1.41000000000000e+02 -5.76405140982154e-01 6.31769220410933e-01 -2.92986730247466e-01 + 1.44000000000000e+02 -5.85129730070885e-01 5.73263830376554e-01 -2.90017937448097e-01 + 1.47000000000000e+02 -5.93851743225456e-01 5.14758887292997e-01 -2.87049167328765e-01 + 1.50000000000000e+02 -6.02571440780362e-01 4.55925647601039e-01 -2.84080408549046e-01 + 1.53000000000000e+02 -6.18102771363694e-01 4.07545900233725e-01 -2.93893652756478e-01 + 1.56000000000000e+02 -6.33627994109589e-01 3.59203284556557e-01 -3.03706889264038e-01 + 1.59000000000000e+02 -6.49147890945894e-01 3.10889487497261e-01 -3.13520050804901e-01 + 1.62000000000000e+02 -6.11662753189298e-01 2.73684904094820e-01 -3.53432900875577e-01 + 1.65000000000000e+02 -5.47687466921444e-01 2.42039936419247e-01 -4.08395849769896e-01 + 1.68000000000000e+02 -4.83692709572010e-01 2.10410090026251e-01 -4.63358168842291e-01 + 1.71000000000000e+02 -3.96924138305795e-01 1.85683483417484e-01 -4.50000513056908e-01 + 1.74000000000000e+02 -2.64615541683425e-01 1.74744683765139e-01 -2.99999717902353e-01 + 1.77000000000000e+02 -1.31704479748411e-01 1.63763723652671e-01 -1.49315896260807e-01 + 1.80000000000000e+02 0.00000000000000e+00 1.52890685398725e-01 0.00000000000000e+00 diff --git a/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_05.dat b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_05.dat new file mode 100644 index 00000000..28ca6bdb --- /dev/null +++ b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_05.dat @@ -0,0 +1,254 @@ +! ------------ AirfoilInfo v1.01.x Input File ---------------------------------- +! AeroElasticSE FAST driver +! line +! line +! ------------------------------------------------------------------------------ +DEFAULT InterpOrd ! Interpolation order to use for quasi-steady table lookup {1=linear; 3=cubic spline; "default"} [default=3] +1 NonDimArea ! The non-dimensional area of the airfoil (area/chord^2) (set to 1.0 if unsure or unneeded) +@"NREL-2p8-127_AF05_Coords.txt" NumCoords ! The number of coordinates in the airfoil shape file. Set to zero if coordinates not included. +AF05_BL.txt BL_file ! The file name including the boundary layer characteristics of the profile. Ignored if the aeroacoustic module is not called. +1 NumTabs ! Number of airfoil tables in this file. Each table must have lines for Re and Ctrl. +! ------------------------------------------------------------------------------ +! data for table 1 +! ------------------------------------------------------------------------------ +6.000000 Re ! Reynolds number in millions +0 Ctrl ! Control setting (must be 0 for current AirfoilInfo) +True InclUAdata ! Is unsteady aerodynamics data included in this table? If TRUE, then include 30 UA coefficients below this line +!........................................ +-2.550758 alpha0 ! 0-lift angle of attack, depends on airfoil. +11.972792 alpha1 ! Angle of attack at f=0.7, (approximately the stall angle) for AOA>alpha0. (deg) +-3.390653 alpha2 ! Angle of attack at f=0.7, (approximately the stall angle) for AOA1] +0.000000 S2 ! Constant in the f curve best-fit for AOA> alpha1; by definition it depends on the airfoil. [ignored if UAMod<>1] +0.000000 S3 ! Constant in the f curve best-fit for alpha2<=AOA< alpha0; by definition it depends on the airfoil. [ignored if UAMod<>1] +0.000000 S4 ! Constant in the f curve best-fit for AOA< alpha2; by definition it depends on the airfoil. [ignored if UAMod<>1] +1.577585 Cn1 ! Critical value of C0n at leading edge separation. It should be extracted from airfoil data at a given Mach and Reynolds number. It can be calculated from the static value of Cn at either the break in the pitching moment or the loss of chord force at the onset of stall. It is close to the condition of maximum lift of the airfoil at low Mach numbers. +-0.698181 Cn2 ! As Cn1 for negative AOAs. +Default St_sh ! Strouhal's shedding frequency constant. [default = 0.19] +0.047738 Cd0 ! 2D drag coefficient value at 0-lift. +-0.017884 Cm0 ! 2D pitching moment coefficient about 1/4-chord location, at 0-lift, positive if nose up. [If the aerodynamics coefficients table does not include a column for Cm, this needs to be set to 0.0] +0.000000 k0 ! Constant in the \hat(x)_cp curve best-fit; = (\hat(x)_AC-0.25). [ignored if UAMod<>1] +0.000000 k1 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k2 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k3 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k1_hat ! Constant in the expression of Cc due to leading edge vortex effects. [ignored if UAMod<>1] +Default x_cp_bar ! Constant in the expression of \hat(x)_cp^v. [ignored if UAMod<>1, default = 0.2] +Default UACutout ! Angle of attack above which unsteady aerodynamics are disabled (deg). [Specifying the string "Default" sets UACutout to 45 degrees] +Default filtCutOff ! Cut-off frequency (-3 dB corner frequency) for low-pass filtering the AoA input to UA, as well as the 1st and 2nd derivatives (Hz) [default = 20] +!........................................ +! Table of aerodynamics coefficients +200 NumAlf ! Number of data lines in the following table +! Alpha Cl Cd Cm +! (deg) (-) (-) (-) +-1.80000000000000e+02 0.00000000000000e+00 5.30927947138125e-02 0.00000000000000e+00 +-1.77000000000000e+02 1.43244990746609e-01 5.69851238094485e-02 1.19452717008645e-01 +-1.74000000000000e+02 2.87802289582396e-01 6.09656699428337e-02 2.39999774321882e-01 +-1.71000000000000e+02 4.31704332512692e-01 6.49763275693468e-02 3.60000410445527e-01 +-1.68000000000000e+02 5.23499707930916e-01 8.50931388592694e-02 3.82638556679456e-01 +-1.65000000000000e+02 5.83384432077198e-01 1.13322899941877e-01 3.56596594332269e-01 +-1.62000000000000e+02 6.43053795138515e-01 1.41646320077994e-01 3.30554333566108e-01 +-1.59000000000000e+02 6.78451069490567e-01 1.78095963395456e-01 3.09470086171798e-01 +-1.56000000000000e+02 6.58893043506451e-01 2.30735614552766e-01 2.98273249714432e-01 +-1.53000000000000e+02 6.39361023231318e-01 2.83555584049004e-01 2.87022407877401e-01 +-1.50000000000000e+02 6.19863301663139e-01 3.36609283159026e-01 2.75697034623494e-01 +-1.47000000000000e+02 6.09009472068249e-01 4.01283048649868e-01 2.78062585683198e-01 +-1.44000000000000e+02 5.98171151079133e-01 4.63879476339314e-01 2.80408703728939e-01 +-1.41000000000000e+02 5.87351226752077e-01 5.26476382236643e-01 2.82731729240854e-01 +-1.38000000000000e+02 5.72330730353409e-01 5.91679697265480e-01 2.87760801862453e-01 +-1.35000000000000e+02 5.55209533057542e-01 6.58186211572688e-01 2.94147772624518e-01 +-1.32000000000000e+02 5.38097371011921e-01 7.24693487985318e-01 3.00529378672850e-01 +-1.29000000000000e+02 5.17511317766740e-01 7.89812599804369e-01 3.07049734636571e-01 +-1.26000000000000e+02 4.89961725795433e-01 8.52155375838165e-01 3.13857858392341e-01 +-1.23000000000000e+02 4.62416171597766e-01 9.14497675605232e-01 3.20665726887359e-01 +-1.20000000000000e+02 4.34875524108853e-01 9.76839737247837e-01 3.27473323520141e-01 +-1.17000000000000e+02 3.97141252418688e-01 1.02744833950730e+00 3.32448774893895e-01 +-1.14000000000000e+02 3.59408610235184e-01 1.07805672550782e+00 3.37422939191108e-01 +-1.11000000000000e+02 3.21678367338784e-01 1.12866472489365e+00 3.42395452802871e-01 +-1.08000000000000e+02 2.79088060479540e-01 1.16729127063990e+00 3.45105968655180e-01 +-1.05000000000000e+02 2.34067147859934e-01 1.19992699833297e+00 3.46678811680518e-01 +-1.02000000000000e+02 1.89047548243342e-01 1.23256235205249e+00 3.48239595384036e-01 +-9.90000000000000e+01 1.43131704344168e-01 1.25788743783553e+00 3.48340383273987e-01 +-9.60000000000000e+01 9.54209316759962e-02 1.26859167109942e+00 3.45525190946857e-01 +-9.30000000000000e+01 4.77105235832516e-02 1.27929582258901e+00 3.42653176080977e-01 +-9.00000000000000e+01 2.97774918887840e-07 1.28999993319219e+00 3.41171513503408e-01 +-8.70000000000000e+01 -4.77104747518152e-02 1.27929583354468e+00 3.34817796856754e-01 +-8.40000000000000e+01 -9.54210650859458e-02 1.26859164116800e+00 3.29193185522394e-01 +-8.10000000000000e+01 -1.43131291032302e-01 1.25788753056483e+00 3.23300885206925e-01 +-7.80000000000000e+01 -1.89047330204813e-01 1.23256251011385e+00 3.14255422250019e-01 +-7.50000000000000e+01 -2.34067445710414e-01 1.19992678241918e+00 3.04545364776568e-01 +-7.20000000000000e+01 -2.79087842435176e-01 1.16729142869966e+00 2.94835418571366e-01 +-6.90000000000000e+01 -3.21678040492873e-01 1.12866516331131e+00 2.84308787573372e-01 +-6.60000000000000e+01 -3.59408715740005e-01 1.07805658399745e+00 2.72148720112555e-01 +-6.30000000000000e+01 -3.97141502062332e-01 1.02744800468359e+00 2.59988652651739e-01 +-6.00000000000000e+01 -4.34875706297759e-01 9.76839324796023e-01 2.47828577510345e-01 +-5.70000000000000e+01 -4.62416353822370e-01 9.14497263153418e-01 2.34772451636168e-01 +-5.40000000000000e+01 -4.89961908050355e-01 8.52154963381625e-01 2.21716275891253e-01 +-5.10000000000000e+01 -5.17511500044336e-01 7.89812187347829e-01 2.08660000404101e-01 +-4.80000000000000e+01 -5.38086518717761e-01 7.24693556057142e-01 1.95844288146640e-01 +-4.50000000000000e+01 -5.55175897952576e-01 6.58187041749934e-01 1.83148853637833e-01 +-4.20000000000000e+01 -5.72313983328070e-01 5.91679765332548e-01 1.70453273649745e-01 +-3.90000000000000e+01 -5.87347123075626e-01 5.26476326754529e-01 1.58085355571838e-01 +-3.60000000000000e+01 -5.98161176797901e-01 4.63879301313675e-01 1.46372520769741e-01 +-3.30000000000000e+01 -6.09008454841632e-01 4.01283471365111e-01 1.34659909662040e-01 +-3.00000000000000e+01 -6.19863411384585e-01 3.36608903265194e-01 1.22947070166372e-01 +-2.93939393939394e+01 -6.23846756639890e-01 3.25869060451884e-01 1.20313440786885e-01 +-2.87878787878788e+01 -6.27838778995726e-01 3.15141051259396e-01 1.17614452112613e-01 +-2.81818181818182e+01 -6.31839641876821e-01 3.04424204137947e-01 1.14912699050432e-01 +-2.75757575757576e+01 -6.35836270597920e-01 2.93717682812228e-01 1.12207880384010e-01 +-2.69696969696970e+01 -6.39833911454526e-01 2.83021034017517e-01 1.09499798315900e-01 +-2.63636363636364e+01 -6.43837810956875e-01 2.72333814688203e-01 1.06788280516258e-01 +-2.57575757575758e+01 -6.47833727204863e-01 2.61655649661799e-01 1.04073092351849e-01 +-2.51515151515151e+01 -6.51811878050700e-01 2.50986136645096e-01 1.01353965974111e-01 +-2.45454545454545e+01 -6.55792402610431e-01 2.40324660439802e-01 9.86307582663180e-02 +-2.39393939393939e+01 -6.59769329462643e-01 2.29670818293622e-01 9.59032541531653e-02 +-2.33333333333333e+01 -6.63693753618085e-01 2.19024233923185e-01 9.31708867916564e-02 +-2.27272727272727e+01 -6.67617282194909e-01 2.08384555374766e-01 9.04338238763716e-02 +-2.21212121212121e+01 -6.71539925846911e-01 1.97751453089189e-01 8.76919095450044e-02 +-2.15151515151515e+01 -6.75391364530441e-01 1.87124374677434e-01 8.49442500011879e-02 +-2.09090909090909e+01 -6.79225055311131e-01 1.76503213160456e-01 8.21911480032724e-02 +-2.03030303030303e+01 -6.83058586454578e-01 1.65887757170172e-01 7.94326338508051e-02 +-1.96969696969697e+01 -6.77179366626525e-01 1.57936143099498e-01 7.50259515023840e-02 +-1.90909090909091e+01 -6.61588812956316e-01 1.52651370129665e-01 6.89730817674315e-02 +-1.84848484848485e+01 -6.45998974297365e-01 1.47376694007528e-01 6.29169683694159e-02 +-1.78787878787879e+01 -6.30407947197086e-01 1.42112026219737e-01 5.68565081215708e-02 +-1.72727272727273e+01 -6.14814081267429e-01 1.36857330079429e-01 5.07903974899203e-02 +-1.66666666666667e+01 -5.99217230522637e-01 1.31613040740835e-01 4.47175106901892e-02 +-1.60606060606061e+01 -5.83616581541072e-01 1.26379356727811e-01 3.86359166779271e-02 +-1.54545454545455e+01 -5.68012174444683e-01 1.21156750685727e-01 3.25431989869031e-02 +-1.48484848484848e+01 -5.52402341156080e-01 1.15945116537827e-01 2.64350024320926e-02 +-1.42424242424242e+01 -5.36785838629193e-01 1.10744490215081e-01 2.03050549247369e-02 +-1.36363636363636e+01 -5.21164946554597e-01 1.05556831744732e-01 1.41441663106941e-02 +-1.30303030303030e+01 -5.05532268418259e-01 1.00377944456418e-01 7.93532744678689e-03 +-1.24242424242424e+01 -4.89896163495659e-01 9.52139797533199e-02 1.73252780437516e-03 +-1.18181818181818e+01 -4.74247226456870e-01 9.00595351969602e-02 -4.26939729837575e-03 +-1.12121212121212e+01 -4.58591426990099e-01 8.49188835204796e-02 -1.02684318086498e-02 +-1.06060606060606e+01 -4.42925008308680e-01 7.97910287467256e-02 -1.62647493676347e-02 +-1.00000000000000e+01 -4.27245419806289e-01 7.46743204034461e-02 -2.22564315863916e-02 +-9.39393939393939e+00 -3.94450071012984e-01 7.15761244145179e-02 -2.16020013916610e-02 +-8.78787878787879e+00 -3.61709763635419e-01 6.85053420395361e-02 -2.09365369698145e-02 +-8.18181818181818e+00 -3.29004774877055e-01 6.54609123314964e-02 -2.02303412864217e-02 +-7.57575757575758e+00 -2.96719457325792e-01 6.35194996651035e-02 -1.95537154607737e-02 +-6.96969696969697e+00 -2.64607645997063e-01 6.22646687778469e-02 -1.89056408818654e-02 +-6.36363636363636e+00 -2.32580527152297e-01 6.06079991204510e-02 -1.81689497551464e-02 +-5.75757575757576e+00 -2.00633174166183e-01 5.86072762325081e-02 -1.69119223172787e-02 +-5.15151515151515e+00 -1.68866114677660e-01 5.62255812194239e-02 -1.65526782796882e-02 +-4.54545454545454e+00 -1.37461932635248e-01 5.36929428917852e-02 -1.61977017355170e-02 +-3.93939393939394e+00 -1.06758451318221e-01 5.10791375965595e-02 -1.58364616756710e-02 +-3.33333333333333e+00 -7.62685548653199e-02 4.84672024181126e-02 -1.56131840112851e-02 +-2.72727272727273e+00 -2.30465602521035e-02 4.76318232912975e-02 -1.71370109715407e-02 +-2.12121212121212e+00 5.60835187551921e-02 4.79951799533595e-02 -1.97007210491168e-02 +-1.51515151515152e+00 1.33973262951602e-01 4.82654676882718e-02 -2.19439082938550e-02 +-9.09090909090912e-01 2.11028087723967e-01 4.85254853369285e-02 -2.42243917401695e-02 +-3.03030303030302e-01 2.87261368924859e-01 4.88198593001318e-02 -2.64441305820696e-02 + 3.03030303030302e-01 3.62683470094018e-01 4.90303436956597e-02 -2.86606885206110e-02 + 9.09090909090912e-01 4.37199562095510e-01 4.92283898912697e-02 -3.09291436006373e-02 + 1.51515151515152e+00 5.13610653178412e-01 4.93813249350217e-02 -3.31627344995039e-02 + 2.12121212121212e+00 5.93819523225117e-01 4.94346635643130e-02 -3.56399268252573e-02 + 2.72727272727273e+00 6.74386743494600e-01 4.93129308208056e-02 -3.83078247443938e-02 + 3.33333333333333e+00 7.54945044010580e-01 4.91755144944948e-02 -4.10234230183793e-02 + 3.93939393939394e+00 8.35509088091445e-01 4.91056624497743e-02 -4.37392469039279e-02 + 4.54545454545455e+00 9.16064316845785e-01 4.89398733238135e-02 -4.63880027667541e-02 + 5.15151515151515e+00 9.96625787614405e-01 4.87886086060796e-02 -4.91038344328945e-02 + 5.75757575757576e+00 1.07656301546343e+00 4.86681788543757e-02 -5.18876441202431e-02 + 6.36363636363637e+00 1.15542943443492e+00 4.84580270970572e-02 -5.47393555777829e-02 + 6.96969696969697e+00 1.23410923793262e+00 4.83167054847680e-02 -5.76374031069491e-02 + 7.57575757575757e+00 1.31245193672788e+00 4.80332030687119e-02 -6.06302767966048e-02 + 8.18181818181818e+00 1.38759943761324e+00 4.77434147182263e-02 -6.42287509236700e-02 + 8.78787878787879e+00 1.45873318731176e+00 4.76208649517908e-02 -6.80810236266958e-02 + 9.39393939393939e+00 1.52667302662998e+00 4.74125681417122e-02 -7.21235138863210e-02 + 1.00000000000000e+01 1.59364179899341e+00 4.69592426109806e-02 -7.62125968301386e-02 + 1.06060606060606e+01 1.53266180129203e+00 5.17795621500542e-02 -7.64122517246057e-02 + 1.12121212121212e+01 1.50662714460046e+00 5.81185911119093e-02 -6.22473445320763e-02 + 1.18181818181818e+01 1.52196088499542e+00 6.47040938908333e-02 -6.38501972207365e-02 + 1.24242424242424e+01 1.06125737520671e+00 7.27011070641862e-02 -5.06632430902114e-02 + 1.30303030303030e+01 9.86623647198398e-01 7.99581638241099e-02 -5.02161054006635e-02 + 1.36363636363636e+01 9.95413895615537e-01 8.64252489342137e-02 -5.25392814360008e-02 + 1.42424242424242e+01 1.00924723452713e+00 9.21833608579365e-02 -5.50345279620461e-02 + 1.48484848484848e+01 1.02661321711400e+00 9.75776888323979e-02 -5.76003393676277e-02 + 1.54545454545455e+01 1.05138532349845e+00 1.02292972150637e-01 -6.01726803278759e-02 + 1.60606060606061e+01 1.07964132412529e+00 1.07181768900225e-01 -6.30677892912717e-02 + 1.66666666666667e+01 1.06432412273203e+00 1.15493817389282e-01 -6.88775293421371e-02 + 1.72727272727273e+01 1.04867809191367e+00 1.23747525118351e-01 -7.47996579324639e-02 + 1.78787878787879e+01 1.03269240545081e+00 1.31928776633279e-01 -8.08557118437613e-02 + 1.84848484848485e+01 1.01640007994456e+00 1.40110699660449e-01 -8.69627224737571e-02 + 1.90909090909091e+01 1.00063944099394e+00 1.48295486938811e-01 -9.30638334648102e-02 + 1.96969696969697e+01 9.85938420719178e-01 1.56485775705632e-01 -9.91101057357213e-02 + 2.03030303030303e+01 9.75860062476632e-01 1.65887757170172e-01 -1.03774527782874e-01 + 2.09090909090909e+01 9.70385523569138e-01 1.76503213160456e-01 -1.07066137517572e-01 + 2.15151515151515e+01 9.64910741287637e-01 1.87124374677434e-01 -1.10360436221179e-01 + 2.21212121212121e+01 9.59410539374443e-01 1.97751453089189e-01 -1.13658562031653e-01 + 2.27272727272727e+01 9.53808409121640e-01 2.08384555374766e-01 -1.16963451063534e-01 + 2.33333333333333e+01 9.48205009566551e-01 2.19024233923185e-01 -1.20268180130586e-01 + 2.39393939393939e+01 9.42600325574261e-01 2.29670818293622e-01 -1.23572752917098e-01 + 2.45454545454545e+01 9.36920460742092e-01 2.40324660439802e-01 -1.26879595000076e-01 + 2.51515151515151e+01 9.31235454127077e-01 2.50986136645096e-01 -1.30185781900636e-01 + 2.57575757575758e+01 9.25553857527951e-01 2.61655649661799e-01 -1.33491111669471e-01 + 2.63636363636364e+01 9.19846852026574e-01 2.72333814688203e-01 -1.36796376983463e-01 + 2.69696969696970e+01 9.14128444983841e-01 2.83021034017517e-01 -1.40101150711351e-01 + 2.75757575757576e+01 9.08419019689508e-01 2.93717682812228e-01 -1.43405050790712e-01 + 2.81818181818182e+01 9.02711061316296e-01 3.04424204137947e-01 -1.46708310397499e-01 + 2.87878787878788e+01 8.96997060076054e-01 3.15141051259396e-01 -1.50011073235030e-01 + 2.93939393939394e+01 8.91295747727463e-01 3.25869060451884e-01 -1.53313276996418e-01 + 3.00000000000000e+01 8.85606890090034e-01 3.36608903265194e-01 -1.56615109400843e-01 + 3.30000000000000e+01 8.70046621612218e-01 4.01283471365112e-01 -1.68896662349608e-01 + 3.60000000000000e+01 8.54497762357662e-01 4.63879301313675e-01 -1.80807931817999e-01 + 3.90000000000000e+01 8.38996891272377e-01 5.26476326754529e-01 -1.92637317529328e-01 + 4.20000000000000e+01 8.17522301694096e-01 5.91679765332548e-01 -2.03957651916238e-01 + 4.50000000000000e+01 7.93066546402043e-01 6.58187041749934e-01 -2.15023567058536e-01 + 4.80000000000000e+01 7.68679932146205e-01 7.24693556057142e-01 -2.26089355395965e-01 + 5.10000000000000e+01 7.39303717872206e-01 7.89812187347829e-01 -2.36920708472379e-01 + 5.40000000000000e+01 6.99944452555873e-01 8.52154963381625e-01 -2.47283175955455e-01 + 5.70000000000000e+01 6.60590914392139e-01 9.14497263153418e-01 -2.57645564275396e-01 + 6.00000000000000e+01 6.21244336348351e-01 9.76839324796023e-01 -2.68007913014073e-01 + 6.30000000000000e+01 5.67342239658887e-01 1.02744800468359e+00 -2.77212112250156e-01 + 6.60000000000000e+01 5.13442407001332e-01 1.07805658399745e+00 -2.86416301559060e-01 + 6.90000000000000e+01 4.59545925192930e-01 1.12866516331131e+00 -2.95620490867964e-01 + 7.20000000000000e+01 3.98720080252567e-01 1.16729142869966e+00 -3.03676557424305e-01 + 7.50000000000000e+01 3.34428749413491e-01 1.19992678241918e+00 -3.11158586107968e-01 + 7.80000000000000e+01 2.70137761942138e-01 1.23256251011385e+00 -3.18640700529719e-01 + 8.10000000000000e+01 2.04550434150108e-01 1.25788753056483e+00 -3.25335532450249e-01 + 8.40000000000000e+01 1.36367248239496e-01 1.26859164116800e+00 -3.30455853712348e-01 + 8.70000000000000e+01 6.81835415395329e-02 1.27929583354468e+00 -3.35467708982822e-01 + 9.00000000000000e+01 -2.97774919089685e-07 1.28999993319219e+00 -3.40233119894460e-01 + 9.30000000000000e+01 -4.77105235832516e-02 1.27929582258901e+00 -3.42605172055241e-01 + 9.60000000000000e+01 -9.54209316759964e-02 1.26859167109942e+00 -3.44513777418663e-01 + 9.90000000000000e+01 -1.43131704344168e-01 1.25788743783553e+00 -3.46422397362864e-01 + 1.02000000000000e+02 -1.89047548243342e-01 1.23256235205249e+00 -3.45474218431042e-01 + 1.05000000000000e+02 -2.34067147859934e-01 1.19992699833297e+00 -3.43097670996285e-01 + 1.08000000000000e+02 -2.79088060479540e-01 1.16729127063990e+00 -3.40721096328304e-01 + 1.11000000000000e+02 -3.21678367338785e-01 1.12866472489365e+00 -3.37267285780153e-01 + 1.14000000000000e+02 -3.59408610235184e-01 1.07805672550782e+00 -3.31659036281393e-01 + 1.17000000000000e+02 -3.97141252418688e-01 1.02744833950730e+00 -3.26050743938977e-01 + 1.20000000000000e+02 -4.34875524108853e-01 9.76839737247837e-01 -3.20442427056780e-01 + 1.23000000000000e+02 -4.62416171597766e-01 9.14497675605232e-01 -3.13240052857952e-01 + 1.26000000000000e+02 -4.89961725795433e-01 8.52155375838165e-01 -3.06037651148621e-01 + 1.29000000000000e+02 -5.17511317766740e-01 7.89812599804369e-01 -2.98835194416227e-01 + 1.32000000000000e+02 -5.38097371011921e-01 7.24693487985317e-01 -2.92129065581036e-01 + 1.35000000000000e+02 -5.55209533057542e-01 6.58186211572688e-01 -2.85671100106641e-01 + 1.38000000000000e+02 -5.72330730353409e-01 5.91679697265480e-01 -2.79213208633931e-01 + 1.41000000000000e+02 -5.87351226752077e-01 5.26476382236642e-01 -2.74246677538335e-01 + 1.44000000000000e+02 -5.98171151079133e-01 4.63879476339314e-01 -2.72262879298565e-01 + 1.47000000000000e+02 -6.09009472068249e-01 4.01283048649868e-01 -2.70279096213984e-01 + 1.50000000000000e+02 -6.19863301663139e-01 3.36609283159026e-01 -2.68295320706727e-01 + 1.53000000000000e+02 -6.39361023231318e-01 2.83555584049004e-01 -2.80703642982803e-01 + 1.56000000000000e+02 -6.58893043506451e-01 2.30735614552766e-01 -2.93111951398230e-01 + 1.59000000000000e+02 -6.78451069490567e-01 1.78095963395456e-01 -3.05520165022309e-01 + 1.62000000000000e+02 -6.43501747482713e-01 1.41646320077994e-01 -3.47725013460614e-01 + 1.65000000000000e+02 -5.88359323471862e-01 1.13322899941877e-01 -4.04828431301629e-01 + 1.68000000000000e+02 -5.23499707930916e-01 8.50931388592694e-02 -4.61931194793028e-01 + 1.71000000000000e+02 -4.31704332512692e-01 6.49763275693468e-02 -4.50000513056908e-01 + 1.74000000000000e+02 -2.87802289582396e-01 6.09656699428337e-02 -2.99999717902353e-01 + 1.77000000000000e+02 -1.43244990746609e-01 5.69851238094485e-02 -1.49315896260807e-01 + 1.80000000000000e+02 0.00000000000000e+00 5.30927947138125e-02 0.00000000000000e+00 diff --git a/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_06.dat b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_06.dat new file mode 100644 index 00000000..28b7cb05 --- /dev/null +++ b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_06.dat @@ -0,0 +1,254 @@ +! ------------ AirfoilInfo v1.01.x Input File ---------------------------------- +! AeroElasticSE FAST driver +! line +! line +! ------------------------------------------------------------------------------ +DEFAULT InterpOrd ! Interpolation order to use for quasi-steady table lookup {1=linear; 3=cubic spline; "default"} [default=3] +1 NonDimArea ! The non-dimensional area of the airfoil (area/chord^2) (set to 1.0 if unsure or unneeded) +@"NREL-2p8-127_AF06_Coords.txt" NumCoords ! The number of coordinates in the airfoil shape file. Set to zero if coordinates not included. +AF06_BL.txt BL_file ! The file name including the boundary layer characteristics of the profile. Ignored if the aeroacoustic module is not called. +1 NumTabs ! Number of airfoil tables in this file. Each table must have lines for Re and Ctrl. +! ------------------------------------------------------------------------------ +! data for table 1 +! ------------------------------------------------------------------------------ +6.000000 Re ! Reynolds number in millions +0 Ctrl ! Control setting (must be 0 for current AirfoilInfo) +True InclUAdata ! Is unsteady aerodynamics data included in this table? If TRUE, then include 30 UA coefficients below this line +!........................................ +0.000000 alpha0 ! 0-lift angle of attack, depends on airfoil. +0.000000 alpha1 ! Angle of attack at f=0.7, (approximately the stall angle) for AOA>alpha0. (deg) +0.000000 alpha2 ! Angle of attack at f=0.7, (approximately the stall angle) for AOA1] +0.000000 S2 ! Constant in the f curve best-fit for AOA> alpha1; by definition it depends on the airfoil. [ignored if UAMod<>1] +0.000000 S3 ! Constant in the f curve best-fit for alpha2<=AOA< alpha0; by definition it depends on the airfoil. [ignored if UAMod<>1] +0.000000 S4 ! Constant in the f curve best-fit for AOA< alpha2; by definition it depends on the airfoil. [ignored if UAMod<>1] +0.000000 Cn1 ! Critical value of C0n at leading edge separation. It should be extracted from airfoil data at a given Mach and Reynolds number. It can be calculated from the static value of Cn at either the break in the pitching moment or the loss of chord force at the onset of stall. It is close to the condition of maximum lift of the airfoil at low Mach numbers. +0.000000 Cn2 ! As Cn1 for negative AOAs. +Default St_sh ! Strouhal's shedding frequency constant. [default = 0.19] +0.000000 Cd0 ! 2D drag coefficient value at 0-lift. +0.000000 Cm0 ! 2D pitching moment coefficient about 1/4-chord location, at 0-lift, positive if nose up. [If the aerodynamics coefficients table does not include a column for Cm, this needs to be set to 0.0] +0.000000 k0 ! Constant in the \hat(x)_cp curve best-fit; = (\hat(x)_AC-0.25). [ignored if UAMod<>1] +0.000000 k1 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k2 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k3 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k1_hat ! Constant in the expression of Cc due to leading edge vortex effects. [ignored if UAMod<>1] +Default x_cp_bar ! Constant in the expression of \hat(x)_cp^v. [ignored if UAMod<>1, default = 0.2] +Default UACutout ! Angle of attack above which unsteady aerodynamics are disabled (deg). [Specifying the string "Default" sets UACutout to 45 degrees] +Default filtCutOff ! Cut-off frequency (-3 dB corner frequency) for low-pass filtering the AoA input to UA, as well as the 1st and 2nd derivatives (Hz) [default = 20] +!........................................ +! Table of aerodynamics coefficients +200 NumAlf ! Number of data lines in the following table +! Alpha Cl Cd Cm +! (deg) (-) (-) (-) +-1.80000000000000e+02 0.00000000000000e+00 1.04451467064788e-02 0.00000000000000e+00 +-1.77000000000000e+02 1.47157007613739e-01 1.04872308588687e-02 1.19452717008645e-01 +-1.74000000000000e+02 2.95662162415483e-01 1.05303966409131e-02 2.39999774321882e-01 +-1.71000000000000e+02 4.43494166290477e-01 1.05740045222718e-02 3.60000410445527e-01 +-1.68000000000000e+02 5.36848745324298e-01 2.74506298830325e-02 3.81279166438973e-01 +-1.65000000000000e+02 6.01560063853722e-01 5.27443629674667e-02 3.53198134597150e-01 +-1.62000000000000e+02 6.66223778858103e-01 7.80396220376046e-02 3.25116780970332e-01 +-1.59000000000000e+02 7.02316612456853e-01 1.12504063201209e-01 3.01860860228524e-01 +-1.56000000000000e+02 6.79726083437648e-01 1.65305735070101e-01 2.88248798735499e-01 +-1.53000000000000e+02 6.57149315796707e-01 2.18110193131311e-01 2.74623662647778e-01 +-1.50000000000000e+02 6.34589659449874e-01 2.70917973756332e-01 2.60980583690885e-01 +-1.47000000000000e+02 6.22060969336252e-01 3.35899150571673e-01 2.62488656920504e-01 +-1.44000000000000e+02 6.09539332292595e-01 4.00853059956420e-01 2.63992059057429e-01 +-1.41000000000000e+02 5.97025743089158e-01 4.65807465559123e-01 2.65489913378387e-01 +-1.38000000000000e+02 5.80704075775906e-01 5.33717517969207e-01 2.70296859813583e-01 +-1.35000000000000e+02 5.62478076348152e-01 6.03105387787129e-01 2.76759519512185e-01 +-1.32000000000000e+02 5.44255597967036e-01 6.72494052728241e-01 2.83220945160593e-01 +-1.29000000000000e+02 5.22678505700544e-01 7.40650991852422e-01 2.90064291270315e-01 +-1.26000000000000e+02 4.94385901691070e-01 8.06344473485986e-01 2.97673949948684e-01 +-1.23000000000000e+02 4.66094993647798e-01 8.72037453255156e-01 3.05283501600632e-01 +-1.20000000000000e+02 4.37806027109449e-01 9.37730182101509e-01 3.12892965044744e-01 +-1.17000000000000e+02 3.99577421117098e-01 9.92049662822417e-01 3.19211276900007e-01 +-1.14000000000000e+02 3.61349504390741e-01 1.04636891381409e+00 3.25529257918674e-01 +-1.11000000000000e+02 3.23122662358267e-01 1.10068774984251e+00 3.31846802734848e-01 +-1.08000000000000e+02 2.80173308571465e-01 1.14318523690795e+00 3.36136841670906e-01 +-1.05000000000000e+02 2.34862463623927e-01 1.17977195947738e+00 3.39411510930403e-01 +-1.02000000000000e+02 1.89552426493172e-01 1.21635826279871e+00 3.42683246088910e-01 +-9.90000000000000e+01 1.43411370176115e-01 1.24567433198225e+00 3.44537199174708e-01 +-9.60000000000000e+01 9.56073752226676e-02 1.26044961797812e+00 3.43556506874831e-01 +-9.30000000000000e+01 4.78037454869307e-02 1.27522479109913e+00 3.42562148033031e-01 +-9.00000000000000e+01 2.98356743247137e-07 1.28999990778373e+00 3.41794286215052e-01 +-8.70000000000000e+01 -4.78036965600822e-02 1.27522480622146e+00 3.34958722226529e-01 +-8.40000000000000e+01 -9.56075088932874e-02 1.26044957666313e+00 3.28241304934322e-01 +-8.10000000000000e+01 -1.43410956056677e-01 1.24567445997852e+00 3.21434171665192e-01 +-7.80000000000000e+01 -1.89552207046124e-01 1.21635843999553e+00 3.12123499707622e-01 +-7.50000000000000e+01 -2.34862763393904e-01 1.17977171742431e+00 3.01780409905885e-01 +-7.20000000000000e+01 -2.80173089123731e-01 1.14318541410297e+00 2.91437438626359e-01 +-6.90000000000000e+01 -3.23122331202990e-01 1.10068822040718e+00 2.80383282644346e-01 +-6.60000000000000e+01 -3.61349611282076e-01 1.04636876192745e+00 2.67906699019381e-01 +-6.30000000000000e+01 -3.99577674034013e-01 9.92049303447725e-01 2.55430115394417e-01 +-6.00000000000000e+01 -4.37806214260738e-01 9.37729747481855e-01 2.42953527363207e-01 +-5.70000000000000e+01 -4.66095180812632e-01 8.72037018635503e-01 2.29962886841547e-01 +-5.40000000000000e+01 -4.94386088868899e-01 8.06344038861353e-01 2.16972196699283e-01 +-5.10000000000000e+01 -5.22678692887195e-01 7.40650557227788e-01 2.03981407315058e-01 +-4.80000000000000e+01 -5.44252972972638e-01 6.72494123749236e-01 1.91507677333331e-01 +-4.50000000000000e+01 -5.62469809216957e-01 6.03106253931314e-01 1.79292468742977e-01 +-4.20000000000000e+01 -5.80700032781224e-01 5.33717588985239e-01 1.67077120176337e-01 +-3.90000000000000e+01 -5.97024764718039e-01 4.65807407987464e-01 1.55320402968213e-01 +-3.60000000000000e+01 -6.09536960661095e-01 4.00852878339035e-01 1.44480717872626e-01 +-3.30000000000000e+01 -6.22060657674661e-01 3.35899589207050e-01 1.33641239795822e-01 +-3.00000000000000e+01 -6.34589785519217e-01 2.70917595996388e-01 1.22801551597028e-01 +-2.93939393939394e+01 -6.39157128083239e-01 2.60249253715867e-01 1.20443684761723e-01 +-2.87878787878788e+01 -6.43726970234920e-01 2.49581068160403e-01 1.18056074979326e-01 +-2.81818181818182e+01 -6.48299337915072e-01 2.38913030435958e-01 1.15668753051161e-01 +-2.75757575757576e+01 -6.52871145565939e-01 2.28244918383301e-01 1.13281631608806e-01 +-2.69696969696970e+01 -6.57443601591947e-01 2.17576846610789e-01 1.10894703470960e-01 +-2.63636363636364e+01 -6.62017925284925e-01 2.06908899722581e-01 1.08507963151374e-01 +-2.57575757575758e+01 -6.66590638057245e-01 1.96241193383532e-01 1.06121395705389e-01 +-2.51515151515151e+01 -6.71159355283587e-01 1.85573782554301e-01 1.03734968840955e-01 +-2.45454545454545e+01 -6.75728973211485e-01 1.74906478164995e-01 1.01348641226412e-01 +-2.39393939393939e+01 -6.80298045453838e-01 1.64239274881544e-01 9.89623846880801e-02 +-2.33333333333333e+01 -6.84854798199331e-01 1.53572167720432e-01 9.65760871231664e-02 +-2.27272727272727e+01 -6.89411636551734e-01 1.42905152020367e-01 9.41898138397285e-02 +-2.21212121212121e+01 -6.93968554262710e-01 1.32238223416651e-01 9.18035530549137e-02 +-2.15151515151515e+01 -6.98508709947078e-01 1.21571133361270e-01 8.94170767131999e-02 +-2.09090909090909e+01 -7.03044892648499e-01 1.10904061345980e-01 8.70305146317220e-02 +-2.03030303030303e+01 -7.07581304739425e-01 1.00237064894968e-01 8.46439121010197e-02 +-1.96969696969697e+01 -7.02434146497075e-01 9.30822479646328e-02 8.04176563008526e-02 +-1.90909090909091e+01 -6.87605029081401e-01 8.94394535867222e-02 7.43518989818734e-02 +-1.84848484848485e+01 -6.72778074386064e-01 8.57969669339951e-02 6.82864549586822e-02 +-1.78787878787879e+01 -6.57952316652420e-01 8.21546025938098e-02 6.22210099648385e-02 +-1.72727272727273e+01 -6.43126950262024e-01 7.85122065549102e-02 5.61553003431422e-02 +-1.66666666666667e+01 -6.28302519055304e-01 7.48699483442050e-02 5.00895983301152e-02 +-1.60606060606061e+01 -6.13478902955351e-01 7.12278305909537e-02 4.40238940514546e-02 +-1.54545454545455e+01 -5.98656762623450e-01 6.75860437894719e-02 3.79584834371826e-02 +-1.48484848484848e+01 -5.83835116087009e-01 6.39443715968832e-02 3.18929726477928e-02 +-1.42424242424242e+01 -5.69013374770912e-01 6.03026916613097e-02 2.58271029097552e-02 +-1.36363636363636e+01 -5.54192788419233e-01 5.66613031319075e-02 1.97612536677373e-02 +-1.30303030303030e+01 -5.39371304159858e-01 5.30198014190618e-02 1.36946491482892e-02 +-1.24242424242424e+01 -5.24551543111039e-01 4.93787366739739e-02 7.62887531626830e-03 +-1.18181818181818e+01 -5.09730889357631e-01 4.57375886003972e-02 1.56582884204670e-03 +-1.12121212121212e+01 -4.94911816881562e-01 4.20969074071858e-02 -4.49615178689840e-03 +-1.06060606060606e+01 -4.80091928606605e-01 3.84561282662129e-02 -1.05578228942103e-02 +-1.00000000000000e+01 -4.65272615271009e-01 3.48157175645994e-02 -1.66180951849822e-02 +-9.39393939393939e+00 -4.33015231009942e-01 3.42187656030196e-02 -1.65076215545108e-02 +-8.78787878787879e+00 -4.00776603293592e-01 3.36221501328585e-02 -1.63940097647302e-02 +-8.18181818181818e+00 -3.68550425214672e-01 3.30196417584014e-02 -1.62766322067477e-02 +-7.57575757575758e+00 -3.36434279469676e-01 3.26768333428082e-02 -1.61640703650675e-02 +-6.96969696969697e+00 -3.04375048369348e-01 3.24942948584592e-02 -1.60544597500587e-02 +-6.36363636363636e+00 -2.72349727408693e-01 3.22072522033381e-02 -1.59243774119394e-02 +-5.75757575757576e+00 -2.40358355463915e-01 3.18276476040425e-02 -1.56691283801087e-02 +-5.15151515151515e+00 -2.08432296047144e-01 3.13466648471733e-02 -1.56292523082999e-02 +-4.54545454545454e+00 -1.76609965524745e-01 3.08120593078346e-02 -1.55984117030112e-02 +-3.93939393939394e+00 -1.44997595632154e-01 3.02529210905892e-02 -1.55594122431336e-02 +-3.33333333333333e+00 -1.13863635347939e-01 2.96208324027153e-02 -1.55210128993654e-02 +-2.72727272727273e+00 -5.99893192871201e-02 2.93065185564550e-02 -1.71363467068633e-02 +-2.12121212121212e+00 2.27564888093693e-02 2.93538954238316e-02 -1.97749354532020e-02 +-1.51515151515152e+00 1.05200007924397e-01 2.93787983393214e-02 -2.18495371988307e-02 +-9.09090909090912e-01 1.87443112873824e-01 2.94162855389729e-02 -2.40114002927046e-02 +-3.03030303030302e-01 2.69492451080518e-01 2.95149670076408e-02 -2.60738132222027e-02 + 3.03030303030302e-01 3.51341217387514e-01 2.95252389442168e-02 -2.81360338847481e-02 + 9.09090909090912e-01 4.32977146923541e-01 2.95324300033464e-02 -3.02799067329311e-02 + 1.51515151515152e+00 5.14818629228781e-01 2.95320187044063e-02 -3.23663227732926e-02 + 2.12121212121212e+00 5.95875970346463e-01 2.96220237683965e-02 -3.47191596720360e-02 + 2.72727272727273e+00 6.76364098276864e-01 2.96076377124260e-02 -3.73109856941127e-02 + 3.33333333333333e+00 7.56846420931681e-01 2.95894663968510e-02 -3.99780779670709e-02 + 3.93939393939394e+00 8.37335412739111e-01 2.96601655289752e-02 -4.26453918217197e-02 + 4.54545454545455e+00 9.17819291031016e-01 2.96450963882609e-02 -4.52128978330237e-02 + 5.15151515151515e+00 9.98308476294268e-01 2.96479816058189e-02 -4.78802193292873e-02 + 5.75757575757576e+00 1.07878507397145e+00 2.96910810658735e-02 -5.05480539440911e-02 + 6.36363636363637e+00 1.15925721789623e+00 2.96540309894699e-02 -5.31448705442736e-02 + 6.96969696969697e+00 1.23972406223336e+00 2.97108111966689e-02 -5.57870430345416e-02 + 7.57575757575757e+00 1.31979653762893e+00 2.96607700932776e-02 -5.85770647543249e-02 + 8.18181818181818e+00 1.39574347837112e+00 2.96344899473148e-02 -6.23210696280249e-02 + 8.78787878787879e+00 1.46845278922940e+00 2.96855555923576e-02 -6.63193015468805e-02 + 9.39393939393939e+00 1.54113668312882e+00 2.96488360635837e-02 -7.03198982848751e-02 + 1.00000000000000e+01 1.61380661140144e+00 2.95365970912785e-02 -7.43207867311127e-02 + 1.06060606060606e+01 1.66835969927735e+00 2.93338363207452e-02 -7.80346111337379e-02 + 1.12121212121212e+01 1.70692741182872e+00 2.93798828283306e-02 -8.05927498314898e-02 + 1.18181818181818e+01 1.74587632218544e+00 3.01307604443737e-02 -8.45839669704818e-02 + 1.24242424242424e+01 1.09782720012007e+00 3.33105797425031e-02 -6.18259975113200e-02 + 1.30303030303030e+01 9.73402814155888e-01 3.56492113840093e-02 -5.87718757586572e-02 + 1.36363636363636e+01 9.88485823361229e-01 3.73441347002030e-02 -6.12633502425757e-02 + 1.42424242424242e+01 1.01090647828627e+00 3.86537299612605e-02 -6.40712596029900e-02 + 1.48484848484848e+01 1.04282842508625e+00 3.96717899749230e-02 -6.69529521512987e-02 + 1.54545454545455e+01 1.08269042899909e+00 4.02778502988878e-02 -7.00292393429914e-02 + 1.60606060606061e+01 1.12069441651250e+00 4.15211136336744e-02 -7.34124817337401e-02 + 1.66666666666667e+01 1.10428631804948e+00 4.97349677981258e-02 -7.89834353690655e-02 + 1.72727272727273e+01 1.08784286827117e+00 5.79481890360755e-02 -8.45666402360810e-02 + 1.78787878787879e+01 1.07137007227413e+00 6.61606214571691e-02 -9.01640784321922e-02 + 1.84848484848485e+01 1.05482456124854e+00 7.43726955221486e-02 -9.57806291561119e-02 + 1.90909090909091e+01 1.03840773749638e+00 8.25847845613570e-02 -1.01399088671180e-01 + 1.96969696969697e+01 1.02224607479530e+00 9.07973366722597e-02 -1.07003526290174e-01 + 2.03030303030303e+01 1.01092702064250e+00 1.00237064894968e-01 -1.11264195300182e-01 + 2.09090909090909e+01 1.00444584016781e+00 1.10904061345980e-01 -1.14182224296970e-01 + 2.15151515151515e+01 9.97964986040765e-01 1.21571133361270e-01 -1.17102244903151e-01 + 2.21212121212121e+01 9.91478442890709e-01 1.32238223416651e-01 -1.20024488822164e-01 + 2.27272727272727e+01 9.84967906725073e-01 1.42905152020367e-01 -1.22949596706990e-01 + 2.33333333333333e+01 9.78457485279851e-01 1.53572167720432e-01 -1.25875923784615e-01 + 2.39393939393939e+01 9.71947187592677e-01 1.64239274881544e-01 -1.28803443608322e-01 + 2.45454545454545e+01 9.65419250819274e-01 1.74906478164995e-01 -1.31732713112496e-01 + 2.51515151515151e+01 9.58890536835396e-01 1.85573782554301e-01 -1.34663003015135e-01 + 2.57575757575758e+01 9.52363117111773e-01 1.96241193383532e-01 -1.37594239679627e-01 + 2.63636363636364e+01 9.45829985373321e-01 2.06908899722581e-01 -1.40526626180439e-01 + 2.69696969696970e+01 9.39294556254110e-01 2.17576846610789e-01 -1.43460023904971e-01 + 2.75757575757576e+01 9.32761808370637e-01 2.28244918383301e-01 -1.46394293444329e-01 + 2.81818181818182e+01 9.26229995246710e-01 2.38913030435957e-01 -1.49329450107358e-01 + 2.87878787878788e+01 9.19697387107103e-01 2.49581068160403e-01 -1.52265482124334e-01 + 2.93939393939394e+01 9.13168404913080e-01 2.60249253715867e-01 -1.55202396247522e-01 + 3.00000000000000e+01 9.06643011580764e-01 2.70917595996388e-01 -1.58140217032240e-01 + 3.30000000000000e+01 8.88688675426252e-01 3.35899589207050e-01 -1.69129145388514e-01 + 3.60000000000000e+01 8.70742215903117e-01 4.00852878339035e-01 -1.79949350188385e-01 + 3.90000000000000e+01 8.52812326157355e-01 4.65807407987464e-01 -1.90730956251902e-01 + 4.20000000000000e+01 8.29505265359302e-01 5.33717588985240e-01 -2.01309118189523e-01 + 4.50000000000000e+01 8.03510457214686e-01 6.03106253931314e-01 -2.11785658405499e-01 + 4.80000000000000e+01 7.77534592624486e-01 6.72494123749237e-01 -2.22262078570281e-01 + 5.10000000000000e+01 7.46744805516537e-01 7.40650557227789e-01 -2.32656858855358e-01 + 5.40000000000000e+01 7.06322608215230e-01 8.06344038861353e-01 -2.42888354132579e-01 + 5.70000000000000e+01 6.65902819356557e-01 8.72037018635503e-01 -2.53119771247217e-01 + 6.00000000000000e+01 6.25485786688918e-01 9.37729747481856e-01 -2.63351149280861e-01 + 6.30000000000000e+01 5.70855611235508e-01 9.92049303447725e-01 -2.72828203817710e-01 + 6.60000000000000e+01 5.16226204482826e-01 1.04636876192745e+00 -2.82305251888810e-01 + 6.90000000000000e+01 4.61598036952559e-01 1.10068822040718e+00 -2.91782299959910e-01 + 7.20000000000000e+01 4.00255485500037e-01 1.14318541410298e+00 -3.00336786931006e-01 + 7.50000000000000e+01 3.35555531395701e-01 1.17977171742431e+00 -3.08430012238153e-01 + 7.80000000000000e+01 2.70855228914286e-01 1.21635843999553e+00 -3.16523330287215e-01 + 8.10000000000000e+01 2.04949941366059e-01 1.24567445997852e+00 -3.23905764836268e-01 + 8.40000000000000e+01 1.36633587012766e-01 1.26044957666313e+00 -3.29866481455659e-01 + 8.70000000000000e+01 6.83167107824974e-02 1.27522480622146e+00 -3.35775778267908e-01 + 9.00000000000000e+01 -2.98356743449189e-07 1.28999990778373e+00 -3.41568552350958e-01 + 9.30000000000000e+01 -4.78037454869307e-02 1.27522479109913e+00 -3.42550600496776e-01 + 9.60000000000000e+01 -9.56073752226678e-02 1.26044961797812e+00 -3.43313207813819e-01 + 9.90000000000000e+01 -1.43411370176115e-01 1.24567433198225e+00 -3.44075820956797e-01 + 1.02000000000000e+02 -1.89552426493172e-01 1.21635826279871e+00 -3.42018024992642e-01 + 1.05000000000000e+02 -2.34862463623927e-01 1.17977195947738e+00 -3.38550055015947e-01 + 1.08000000000000e+02 -2.80173308571465e-01 1.14318523690795e+00 -3.35082045299249e-01 + 1.11000000000000e+02 -3.23122662358267e-01 1.10068774984251e+00 -3.30613204224884e-01 + 1.14000000000000e+02 -3.61349504390742e-01 1.04636891381409e+00 -3.24142730917994e-01 + 1.17000000000000e+02 -3.99577421117098e-01 9.92049662822417e-01 -3.17672208180576e-01 + 1.20000000000000e+02 -4.37806027109449e-01 9.37730182101508e-01 -3.11201658314193e-01 + 1.23000000000000e+02 -4.66094993647798e-01 8.72037453255156e-01 -3.03497229746074e-01 + 1.26000000000000e+02 -4.94385901691070e-01 8.06344473485986e-01 -2.95792771749784e-01 + 1.29000000000000e+02 -5.22678505700545e-01 7.40650991852421e-01 -2.88088254894948e-01 + 1.32000000000000e+02 -5.44255597967036e-01 6.72494052728240e-01 -2.81200220471366e-01 + 1.35000000000000e+02 -5.62478076348152e-01 6.03105387787129e-01 -2.74720426295997e-01 + 1.38000000000000e+02 -5.80704075775906e-01 5.33717517969206e-01 -2.68240706372448e-01 + 1.41000000000000e+02 -5.97025743089158e-01 4.65807465559123e-01 -2.63448804520033e-01 + 1.44000000000000e+02 -6.09539332292595e-01 4.00853059956420e-01 -2.62032552505631e-01 + 1.47000000000000e+02 -6.22060969336252e-01 3.35899150571673e-01 -2.60616311310659e-01 + 1.50000000000000e+02 -6.34589659449874e-01 2.70917973756332e-01 -2.59200075525210e-01 + 1.53000000000000e+02 -6.57149315796707e-01 2.18110193131311e-01 -2.73103661656341e-01 + 1.56000000000000e+02 -6.79726083437648e-01 1.65305735070101e-01 -2.87007230377031e-01 + 1.59000000000000e+02 -7.02316612456853e-01 1.12504063201209e-01 -3.00910692883565e-01 + 1.62000000000000e+02 -6.66331535360941e-01 7.80396220376046e-02 -3.44436173003965e-01 + 1.65000000000000e+02 -6.02756791375368e-01 5.27443629674667e-02 -4.02772912450035e-01 + 1.68000000000000e+02 -5.36848745324298e-01 2.74506298830325e-02 -4.61108983413823e-01 + 1.71000000000000e+02 -4.43494166290477e-01 1.05740045222718e-02 -4.50000513056908e-01 + 1.74000000000000e+02 -2.95662162415483e-01 1.05303966409131e-02 -2.99999717902353e-01 + 1.77000000000000e+02 -1.47157007613739e-01 1.04872308588687e-02 -1.49315896260807e-01 + 1.80000000000000e+02 0.00000000000000e+00 1.04451467064788e-02 0.00000000000000e+00 diff --git a/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_07.dat b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_07.dat new file mode 100644 index 00000000..d854bfa0 --- /dev/null +++ b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_07.dat @@ -0,0 +1,254 @@ +! ------------ AirfoilInfo v1.01.x Input File ---------------------------------- +! AeroElasticSE FAST driver +! line +! line +! ------------------------------------------------------------------------------ +DEFAULT InterpOrd ! Interpolation order to use for quasi-steady table lookup {1=linear; 3=cubic spline; "default"} [default=3] +1 NonDimArea ! The non-dimensional area of the airfoil (area/chord^2) (set to 1.0 if unsure or unneeded) +@"NREL-2p8-127_AF07_Coords.txt" NumCoords ! The number of coordinates in the airfoil shape file. Set to zero if coordinates not included. +AF07_BL.txt BL_file ! The file name including the boundary layer characteristics of the profile. Ignored if the aeroacoustic module is not called. +1 NumTabs ! Number of airfoil tables in this file. Each table must have lines for Re and Ctrl. +! ------------------------------------------------------------------------------ +! data for table 1 +! ------------------------------------------------------------------------------ +6.000000 Re ! Reynolds number in millions +0 Ctrl ! Control setting (must be 0 for current AirfoilInfo) +True InclUAdata ! Is unsteady aerodynamics data included in this table? If TRUE, then include 30 UA coefficients below this line +!........................................ +-2.175483 alpha0 ! 0-lift angle of attack, depends on airfoil. +12.034907 alpha1 ! Angle of attack at f=0.7, (approximately the stall angle) for AOA>alpha0. (deg) +-4.017330 alpha2 ! Angle of attack at f=0.7, (approximately the stall angle) for AOA1] +0.000000 S2 ! Constant in the f curve best-fit for AOA> alpha1; by definition it depends on the airfoil. [ignored if UAMod<>1] +0.000000 S3 ! Constant in the f curve best-fit for alpha2<=AOA< alpha0; by definition it depends on the airfoil. [ignored if UAMod<>1] +0.000000 S4 ! Constant in the f curve best-fit for AOA< alpha2; by definition it depends on the airfoil. [ignored if UAMod<>1] +1.598379 Cn1 ! Critical value of C0n at leading edge separation. It should be extracted from airfoil data at a given Mach and Reynolds number. It can be calculated from the static value of Cn at either the break in the pitching moment or the loss of chord force at the onset of stall. It is close to the condition of maximum lift of the airfoil at low Mach numbers. +-0.740046 Cn2 ! As Cn1 for negative AOAs. +Default St_sh ! Strouhal's shedding frequency constant. [default = 0.19] +0.019639 Cd0 ! 2D drag coefficient value at 0-lift. +-0.026025 Cm0 ! 2D pitching moment coefficient about 1/4-chord location, at 0-lift, positive if nose up. [If the aerodynamics coefficients table does not include a column for Cm, this needs to be set to 0.0] +0.000000 k0 ! Constant in the \hat(x)_cp curve best-fit; = (\hat(x)_AC-0.25). [ignored if UAMod<>1] +0.000000 k1 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k2 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k3 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k1_hat ! Constant in the expression of Cc due to leading edge vortex effects. [ignored if UAMod<>1] +Default x_cp_bar ! Constant in the expression of \hat(x)_cp^v. [ignored if UAMod<>1, default = 0.2] +Default UACutout ! Angle of attack above which unsteady aerodynamics are disabled (deg). [Specifying the string "Default" sets UACutout to 45 degrees] +Default filtCutOff ! Cut-off frequency (-3 dB corner frequency) for low-pass filtering the AoA input to UA, as well as the 1st and 2nd derivatives (Hz) [default = 20] +!........................................ +! Table of aerodynamics coefficients +200 NumAlf ! Number of data lines in the following table +! Alpha Cl Cd Cm +! (deg) (-) (-) (-) +-1.80000000000000e+02 0.00000000000000e+00 2.33914127688100e-02 0.00000000000000e+00 +-1.77000000000000e+02 1.43031527763221e-01 2.33914127688100e-02 1.19163615697548e-01 +-1.74000000000000e+02 2.87990892106934e-01 2.66846196171584e-02 2.39999774321882e-01 +-1.71000000000000e+02 4.31987088278764e-01 3.65643482753360e-02 3.60000410445527e-01 +-1.68000000000000e+02 5.31545849874829e-01 5.84098652013656e-02 3.64532897060852e-01 +-1.65000000000000e+02 6.11268538666348e-01 8.62381366029380e-02 3.11332656605488e-01 +-1.62000000000000e+02 6.94600133989169e-01 1.14066726893083e-01 2.58131725599959e-01 +-1.59000000000000e+02 7.40824462046985e-01 1.50632267952715e-01 2.21242462675373e-01 +-1.56000000000000e+02 7.16139659509821e-01 2.04671414989218e-01 2.16831447428975e-01 +-1.53000000000000e+02 6.91423868529968e-01 2.58710851852227e-01 2.12177598920349e-01 +-1.50000000000000e+02 6.66670110194854e-01 3.12750462408367e-01 2.07242736249593e-01 +-1.47000000000000e+02 6.52900940317335e-01 3.79139090101126e-01 2.11698220689362e-01 +-1.44000000000000e+02 6.39116027015019e-01 4.45527909875772e-01 2.16157774411608e-01 +-1.41000000000000e+02 6.25312980734950e-01 5.11917113827909e-01 2.20622202461720e-01 +-1.38000000000000e+02 6.07728072005134e-01 5.81216719268110e-01 2.27857968655088e-01 +-1.35000000000000e+02 5.88252908821619e-01 6.51971519548278e-01 2.36476173369762e-01 +-1.32000000000000e+02 5.68769160282536e-01 7.22726946114877e-01 2.45092460374068e-01 +-1.29000000000000e+02 5.45846532434262e-01 7.92131150298341e-01 2.54083304617287e-01 +-1.26000000000000e+02 5.16059865398949e-01 8.58832903295187e-01 2.63823977750305e-01 +-1.23000000000000e+02 4.86270063393777e-01 9.25534146724964e-01 2.73560128804467e-01 +-1.20000000000000e+02 4.56476301826173e-01 9.92235135380730e-01 2.83291214803044e-01 +-1.17000000000000e+02 4.16489600596796e-01 1.04694876887339e+00 2.91917422175410e-01 +-1.14000000000000e+02 3.76501801901982e-01 1.10166216993032e+00 3.00538465312235e-01 +-1.11000000000000e+02 3.36512597958186e-01 1.15637515301294e+00 3.09153340377474e-01 +-1.08000000000000e+02 2.91693025082505e-01 1.19874087754264e+00 3.15840388222425e-01 +-1.05000000000000e+02 2.44458666678294e-01 1.23493287877690e+00 3.21561919471006e-01 +-1.02000000000000e+02 1.97224219276773e-01 1.27112446528618e+00 3.27278150969725e-01 +-9.90000000000000e+01 1.49160540417765e-01 1.29974121708087e+00 3.31577776566796e-01 +-9.60000000000000e+01 9.94402497296759e-02 1.31320797134044e+00 3.33053601420033e-01 +-9.30000000000000e+01 4.97202158283082e-02 1.32667462272159e+00 3.34536430978363e-01 +-9.00000000000000e+01 3.10317978578370e-07 1.34014122266447e+00 3.35516468539213e-01 +-8.70000000000000e+01 -4.97201649399637e-02 1.32667463650466e+00 3.30914309585675e-01 +-8.40000000000000e+01 -9.94403887586856e-02 1.31320793368439e+00 3.25875044063013e-01 +-8.10000000000000e+01 -1.49160109697721e-01 1.29974133374151e+00 3.20684674998472e-01 +-7.80000000000000e+01 -1.97223990505980e-01 1.27112464057129e+00 3.14068969100332e-01 +-7.50000000000000e+01 -2.44458979176423e-01 1.23493263933526e+00 3.06188477394521e-01 +-7.20000000000000e+01 -2.91692796320390e-01 1.19874105282597e+00 2.98307891491871e-01 +-6.90000000000000e+01 -3.36512251521935e-01 1.15637562699211e+00 2.89561021929827e-01 +-6.60000000000000e+01 -3.76501913717355e-01 1.10166201694156e+00 2.79081514110173e-01 +-6.30000000000000e+01 -4.16489865150498e-01 1.04694840689101e+00 2.68601883289040e-01 +-6.00000000000000e+01 -4.56476498955521e-01 9.92234694090483e-01 2.58122183245595e-01 +-5.70000000000000e+01 -4.86270260493495e-01 9.25533705434717e-01 2.46741658278199e-01 +-5.40000000000000e+01 -5.16060062475956e-01 8.58832461999884e-01 2.35361028339939e-01 +-5.10000000000000e+01 -5.45846729491953e-01 7.92130709003037e-01 2.23980188458352e-01 +-4.80000000000000e+01 -5.69289853059557e-01 7.22744238735752e-01 2.13008982600553e-01 +-4.50000000000000e+01 -5.89557703094231e-01 6.52015452980456e-01 2.02242587171249e-01 +-4.20000000000000e+01 -6.08251798068365e-01 5.81234011749336e-01 1.91868319013648e-01 +-3.90000000000000e+01 -6.25416926876934e-01 5.11597466281429e-01 1.81968105360702e-01 +-3.60000000000000e+01 -6.39316913259601e-01 4.44496914459934e-01 1.73264272171102e-01 +-3.30000000000000e+01 -6.52916432542900e-01 3.78198211323207e-01 1.65338571395536e-01 +-3.00000000000000e+01 -6.66670235178609e-01 3.12750067745499e-01 1.58271579799568e-01 +-2.93939393939394e+01 -6.71047367933391e-01 3.01438712775986e-01 1.57020885663939e-01 +-2.87878787878788e+01 -6.75419095195018e-01 2.90127357806473e-01 1.55835649782268e-01 +-2.81818181818182e+01 -6.79785363067838e-01 2.78816002836960e-01 1.54649678410992e-01 +-2.75757575757576e+01 -6.84281237628547e-01 2.67629852848922e-01 1.53624988893004e-01 +-2.69696969696970e+01 -6.88830733728478e-01 2.56497366741980e-01 1.52669124180276e-01 +-2.63636363636364e+01 -6.93376184149147e-01 2.45364880635039e-01 1.51712730581928e-01 +-2.57575757575758e+01 -6.98037897852729e-01 2.34311621831173e-01 1.50875935757439e-01 +-2.51515151515151e+01 -7.02877385944567e-01 2.23377185516994e-01 1.50218827286969e-01 +-2.45454545454545e+01 -7.07714903614937e-01 2.12442749202814e-01 1.49561371313348e-01 +-2.39393939393939e+01 -7.12595164217054e-01 2.01529837369162e-01 1.48943431555047e-01 +-2.33333333333333e+01 -7.17876308107891e-01 1.90810650027497e-01 1.48683703309005e-01 +-2.27272727272727e+01 -7.23157231061198e-01 1.80091462685832e-01 1.48423779056222e-01 +-2.21212121212121e+01 -7.28437947560357e-01 1.69372275344166e-01 1.48163680826540e-01 +-2.15151515151515e+01 -7.31713351978921e-01 1.58838231776999e-01 1.48337985994225e-01 +-2.09090909090909e+01 -7.34245840474427e-01 1.48350486062725e-01 1.48620871862006e-01 +-2.03030303030303e+01 -7.38065551990425e-01 1.37862740348452e-01 1.48903686939429e-01 +-1.96969696969697e+01 -7.32808819200495e-01 1.29918930302428e-01 1.44712603991306e-01 +-1.90909090909091e+01 -7.18361958000880e-01 1.24518912013222e-01 1.36047824693694e-01 +-1.84848484848485e+01 -7.04189587691779e-01 1.19119156714805e-01 1.27383320623159e-01 +-1.78787878787879e+01 -6.90170520790039e-01 1.13719385941933e-01 1.18718587275407e-01 +-1.72727272727273e+01 -6.76245095637824e-01 1.08319367652727e-01 1.10053115983160e-01 +-1.66666666666667e+01 -6.62381424994436e-01 1.02255720988610e-01 1.01387526517949e-01 +-1.60606060606061e+01 -6.48560316531438e-01 9.61448175238969e-02 9.27217646524863e-02 +-1.54545454545455e+01 -6.34969522120538e-01 9.03872009230254e-02 8.40561496211227e-02 +-1.48484848484848e+01 -6.21508539218862e-01 8.48230957038706e-02 7.53901059090511e-02 +-1.42424242424242e+01 -6.08408366025162e-01 7.96630711027307e-02 6.67232674713552e-02 +-1.36363636363636e+01 -5.95447218953895e-01 7.45632229779760e-02 5.80562179472338e-02 +-1.30303030303030e+01 -5.82646323386179e-01 6.95101444417735e-02 4.93879760859292e-02 +-1.24242424242424e+01 -5.70051253619176e-01 6.44104289730139e-02 4.07195611654372e-02 +-1.18181818181818e+01 -5.57661981483822e-01 5.92219660335435e-02 3.20496569255294e-02 +-1.12121212121212e+01 -5.45521148334811e-01 5.38126013913541e-02 2.33792067297271e-02 +-1.06060606060606e+01 -5.33770601268997e-01 4.82803386350898e-02 1.47062382307926e-02 +-1.00000000000000e+01 -5.22536282520595e-01 4.27091715581483e-02 6.03175191196416e-03 +-9.39393939393939e+00 -4.98663010113629e-01 3.97762979408636e-02 1.46216346791845e-03 +-8.78787878787879e+00 -4.74896579071385e-01 3.69498939396144e-02 -3.11443204072278e-03 +-8.18181818181818e+00 -4.50184735644143e-01 3.36609587046423e-02 -7.71668568938825e-03 +-7.57575757575758e+00 -4.16320862490726e-01 3.11984229016655e-02 -1.02342715344042e-02 +-6.96969696969697e+00 -3.78533908672691e-01 2.88846280067247e-02 -1.18586821223915e-02 +-6.36363636363636e+00 -3.41308425879108e-01 2.66987274834274e-02 -1.37039177713602e-02 +-5.75757575757576e+00 -3.03292128777548e-01 2.47793566352644e-02 -1.57278639083592e-02 +-5.15151515151515e+00 -2.63917787982752e-01 2.33543465327187e-02 -1.65422055989149e-02 +-4.54545454545454e+00 -2.22824817551322e-01 2.20950859887883e-02 -1.76054229676369e-02 +-3.93939393939394e+00 -1.80668798888092e-01 2.09756580073103e-02 -1.88443435684976e-02 +-3.33333333333333e+00 -1.34176568044395e-01 2.04804489661257e-02 -2.02207166542285e-02 +-2.72727272727273e+00 -7.19453798936780e-02 2.00079017312406e-02 -2.28911294526880e-02 +-2.12121212121212e+00 7.07606911784324e-03 1.96027557312253e-02 -2.63328024672574e-02 +-1.51515151515152e+00 8.73289871843104e-02 1.94248148430849e-02 -2.91753660865235e-02 +-9.09090909090912e-01 1.68214610603894e-01 1.93209749444206e-02 -3.21126237712362e-02 +-3.03030303030302e-01 2.49847575674565e-01 1.93085263731067e-02 -3.50069460021776e-02 + 3.03030303030302e-01 3.32076661864978e-01 1.92708245709109e-02 -3.78355127682451e-02 + 9.09090909090912e-01 4.14967913083368e-01 1.92564396323649e-02 -4.06506905185218e-02 + 1.51515151515152e+00 4.97503403994561e-01 1.93240509371219e-02 -4.34545183162005e-02 + 2.12121212121212e+00 5.78017026165593e-01 1.94699699516029e-02 -4.63887820732702e-02 + 2.72727272727273e+00 6.57982538458257e-01 1.95636992876711e-02 -4.91776418225647e-02 + 3.33333333333333e+00 7.37634840577441e-01 1.96859030314327e-02 -5.19181781483109e-02 + 3.93939393939394e+00 8.17042150325575e-01 1.99153209631174e-02 -5.45755311911616e-02 + 4.54545454545455e+00 8.95773550489732e-01 2.01574613792028e-02 -5.71758300930519e-02 + 5.15151515151515e+00 9.74202606524190e-01 2.04147221937826e-02 -5.98020954890244e-02 + 5.75757575757576e+00 1.05192610299832e+00 2.06935862917398e-02 -6.22831373010045e-02 + 6.36363636363637e+00 1.12864853703975e+00 2.09894711710230e-02 -6.45992855497388e-02 + 6.96969696969697e+00 1.20469677736454e+00 2.13767147820252e-02 -6.68719079346452e-02 + 7.57575757575757e+00 1.27852391355893e+00 2.18254003510820e-02 -6.92881289021872e-02 + 8.18181818181818e+00 1.34843619913274e+00 2.23379405478464e-02 -7.23998694538348e-02 + 8.78787878787879e+00 1.41389258501910e+00 2.29917029483263e-02 -7.57224146801624e-02 + 9.39393939393939e+00 1.47693105199554e+00 2.42669452043504e-02 -7.90940633281295e-02 + 1.00000000000000e+01 1.53866152751405e+00 2.58158538548453e-02 -8.24968128995006e-02 + 1.06060606060606e+01 1.58175634209111e+00 2.78715872133015e-02 -8.63366627353863e-02 + 1.12121212121212e+01 1.60853428444793e+00 2.99227788852005e-02 -9.25178530036142e-02 + 1.18181818181818e+01 1.62618116680780e+00 3.25599114107023e-02 -9.61254605123986e-02 + 1.24242424242424e+01 1.17081115183266e+00 3.76946916781032e-02 -7.96133950050748e-02 + 1.30303030303030e+01 1.07057266006274e+00 4.25731273306023e-02 -7.63714447703372e-02 + 1.36363636363636e+01 1.07323785139661e+00 4.76558461605604e-02 -7.83786809582152e-02 + 1.42424242424242e+01 1.08209790208772e+00 5.26403136632421e-02 -8.07401047567165e-02 + 1.48484848484848e+01 1.10354986974947e+00 5.77455347083801e-02 -8.32982121847380e-02 + 1.54545454545455e+01 1.13090095347719e+00 6.28922160620656e-02 -8.70718045668990e-02 + 1.60606060606061e+01 1.15290331847775e+00 6.85681445746570e-02 -9.13408073485258e-02 + 1.66666666666667e+01 1.13888783926795e+00 7.88844991137046e-02 -9.76066740175176e-02 + 1.72727272727273e+01 1.12569869109310e+00 8.91882738787458e-02 -1.03672038183508e-01 + 1.78787878787879e+01 1.11348996181680e+00 9.94766732049302e-02 -1.09493916588364e-01 + 1.84848484848485e+01 1.10412272552069e+00 1.09722110128521e-01 -1.14392819645911e-01 + 1.90909090909091e+01 1.09417618957362e+00 1.19712328172831e-01 -1.19171119055800e-01 + 1.96969696969697e+01 1.07815671838533e+00 1.28316705476137e-01 -1.24569996191147e-01 + 2.03030303030303e+01 1.06590918336347e+00 1.37862740348452e-01 -1.28927442015208e-01 + 2.09090909090909e+01 1.05744457824252e+00 1.48350486062725e-01 -1.32240940695518e-01 + 2.15151515151515e+01 1.04897922606013e+00 1.58838231776999e-01 -1.35550005581577e-01 + 2.21212121212121e+01 1.04069744082963e+00 1.69372275344167e-01 -1.38809930873424e-01 + 2.27272727272727e+01 1.03315254333471e+00 1.80091462685832e-01 -1.41886753748031e-01 + 2.33333333333333e+01 1.02560734768900e+00 1.90810650027497e-01 -1.44960808190677e-01 + 2.39393939393939e+01 1.01806183295191e+00 2.01529837369162e-01 -1.48032154260591e-01 + 2.45454545454545e+01 1.01108909354267e+00 2.12442749202814e-01 -1.50974394253646e-01 + 2.51515151515151e+01 1.00417741009351e+00 2.23377185516994e-01 -1.53900389859026e-01 + 2.57575757575758e+01 9.97262895226883e-01 2.34311621831173e-01 -1.56824213640932e-01 + 2.63636363636364e+01 9.90602272243490e-01 2.45364880635039e-01 -1.59691865247193e-01 + 2.69696969696970e+01 9.84107677556836e-01 2.56497366741980e-01 -1.62521495117230e-01 + 2.75757575757576e+01 9.77607274768511e-01 2.67629852848922e-01 -1.65349122555614e-01 + 2.81818181818182e+01 9.71183535418784e-01 2.78816002836960e-01 -1.68157082819057e-01 + 2.87878787878788e+01 9.64945123677017e-01 2.90127357806473e-01 -1.70921894375263e-01 + 2.93939393939394e+01 9.58698873686608e-01 3.01438712775986e-01 -1.73684689615452e-01 + 3.00000000000000e+01 9.52444862477794e-01 3.12750067745499e-01 -1.76445418513927e-01 + 3.30000000000000e+01 9.32757112804349e-01 3.78198211323207e-01 -1.87615870546037e-01 + 3.60000000000000e+01 9.13290569721045e-01 4.44496914459934e-01 -1.99008415557536e-01 + 3.90000000000000e+01 8.93393781094339e-01 5.11597466281430e-01 -2.09904410150492e-01 + 4.20000000000000e+01 8.68886648478033e-01 5.81234011749336e-01 -2.20659088173443e-01 + 4.50000000000000e+01 8.42222962046853e-01 6.52015452980456e-01 -2.31358509305899e-01 + 4.80000000000000e+01 8.13311107256429e-01 7.22744238735752e-01 -2.42008926938194e-01 + 5.10000000000000e+01 7.79848244960539e-01 7.92130709003037e-01 -2.52553412425687e-01 + 5.40000000000000e+01 7.37292615749320e-01 8.58832461999884e-01 -2.62871600790229e-01 + 5.70000000000000e+01 6.94732715144264e-01 9.25533705434717e-01 -2.73198801942233e-01 + 6.00000000000000e+01 6.52167283863280e-01 9.92234694090484e-01 -2.83534193702832e-01 + 6.30000000000000e+01 5.95021513422317e-01 1.04694840689101e+00 -2.92939646889504e-01 + 6.60000000000000e+01 5.37873671092777e-01 1.10166201694156e+00 -3.02353620386315e-01 + 6.90000000000000e+01 4.80723120327637e-01 1.15637562699211e+00 -3.11775458141060e-01 + 7.20000000000000e+01 4.16702853573743e-01 1.19874105282597e+00 -3.20152624301910e-01 + 7.50000000000000e+01 3.49248630212311e-01 1.23493263933526e+00 -3.28012827849872e-01 + 7.80000000000000e+01 2.81792775389929e-01 1.27112464057129e+00 -3.35882005640500e-01 + 8.10000000000000e+01 2.13139309353073e-01 1.29974133374152e+00 -3.42992209540911e-01 + 8.40000000000000e+01 1.42093279928522e-01 1.31320793368439e+00 -3.48577487448998e-01 + 8.70000000000000e+01 7.10465847027829e-02 1.32667463650466e+00 -3.54286237278487e-01 + 9.00000000000000e+01 -3.10317978790605e-07 1.34014122266447e+00 -3.60261329275921e-01 + 9.30000000000000e+01 -4.97202158283082e-02 1.32667462272159e+00 -3.60939509181810e-01 + 9.60000000000000e+01 -9.94402497296761e-02 1.31320797134044e+00 -3.62101276854683e-01 + 9.90000000000000e+01 -1.49160540417765e-01 1.29974121708087e+00 -3.63263116762426e-01 + 1.02000000000000e+02 -1.97224219276773e-01 1.27112446528618e+00 -3.61500175595017e-01 + 1.05000000000000e+02 -2.44458666678294e-01 1.23493287877690e+00 -3.58275028210518e-01 + 1.08000000000000e+02 -2.91693025082505e-01 1.19874087754264e+00 -3.55049870683841e-01 + 1.11000000000000e+02 -3.36512597958186e-01 1.15637515301294e+00 -3.50765979419127e-01 + 1.14000000000000e+02 -3.76501801901982e-01 1.10166216993032e+00 -3.44364638786946e-01 + 1.17000000000000e+02 -4.16489600596796e-01 1.04694876887339e+00 -3.37963575060275e-01 + 1.20000000000000e+02 -4.56476301826173e-01 9.92235135380730e-01 -3.31562852852576e-01 + 1.23000000000000e+02 -4.86270063393777e-01 9.25534146724963e-01 -3.23780752167797e-01 + 1.26000000000000e+02 -5.16059865398949e-01 8.58832903295187e-01 -3.15999386352538e-01 + 1.29000000000000e+02 -5.45846532434262e-01 7.92131150298340e-01 -3.08218654603481e-01 + 1.32000000000000e+02 -5.68769160282536e-01 7.22726946114877e-01 -3.01185530669448e-01 + 1.35000000000000e+02 -5.88252908821619e-01 6.51971519548278e-01 -2.94527284921154e-01 + 1.38000000000000e+02 -6.07728072005134e-01 5.81216719268109e-01 -2.87870702883092e-01 + 1.41000000000000e+02 -6.25312980734950e-01 5.11917113827908e-01 -2.82904694585223e-01 + 1.44000000000000e+02 -6.39116027015019e-01 4.45527909875772e-01 -2.81319615496767e-01 + 1.47000000000000e+02 -6.52900940317335e-01 3.79139090101126e-01 -2.79738043324018e-01 + 1.50000000000000e+02 -6.66670110194854e-01 3.12750462408366e-01 -2.78159839410523e-01 + 1.53000000000000e+02 -6.91423868529968e-01 2.58710851852227e-01 -2.92436611808699e-01 + 1.56000000000000e+02 -7.16139659509821e-01 2.04671414989218e-01 -3.06713727094434e-01 + 1.59000000000000e+02 -7.40824462046985e-01 1.50632267952715e-01 -3.20991093106481e-01 + 1.62000000000000e+02 -6.92523326346939e-01 1.14218878924218e-01 -3.60600316892406e-01 + 1.65000000000000e+02 -6.04090178045220e-01 8.66185179666223e-02 -4.12875574153840e-01 + 1.68000000000000e+02 -5.25703495579730e-01 5.90182887830723e-02 -4.65150066961505e-01 + 1.71000000000000e+02 -4.24060615670435e-01 3.72487259247374e-02 -4.50000513056908e-01 + 1.74000000000000e+02 -2.82706583196469e-01 2.71407679330614e-02 -2.99999717902353e-01 + 1.77000000000000e+02 -1.40374735896749e-01 2.36166297084173e-02 -1.48954519621935e-01 + 1.80000000000000e+02 0.00000000000000e+00 2.33914127688100e-02 0.00000000000000e+00 diff --git a/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_08.dat b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_08.dat new file mode 100644 index 00000000..d72fa625 --- /dev/null +++ b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_08.dat @@ -0,0 +1,254 @@ +! ------------ AirfoilInfo v1.01.x Input File ---------------------------------- +! AeroElasticSE FAST driver +! line +! line +! ------------------------------------------------------------------------------ +DEFAULT InterpOrd ! Interpolation order to use for quasi-steady table lookup {1=linear; 3=cubic spline; "default"} [default=3] +1 NonDimArea ! The non-dimensional area of the airfoil (area/chord^2) (set to 1.0 if unsure or unneeded) +@"NREL-2p8-127_AF08_Coords.txt" NumCoords ! The number of coordinates in the airfoil shape file. Set to zero if coordinates not included. +AF08_BL.txt BL_file ! The file name including the boundary layer characteristics of the profile. Ignored if the aeroacoustic module is not called. +1 NumTabs ! Number of airfoil tables in this file. Each table must have lines for Re and Ctrl. +! ------------------------------------------------------------------------------ +! data for table 1 +! ------------------------------------------------------------------------------ +6.000000 Re ! Reynolds number in millions +0 Ctrl ! Control setting (must be 0 for current AirfoilInfo) +True InclUAdata ! Is unsteady aerodynamics data included in this table? If TRUE, then include 30 UA coefficients below this line +!........................................ +-2.094045 alpha0 ! 0-lift angle of attack, depends on airfoil. +11.810318 alpha1 ! Angle of attack at f=0.7, (approximately the stall angle) for AOA>alpha0. (deg) +-5.789318 alpha2 ! Angle of attack at f=0.7, (approximately the stall angle) for AOA1] +0.000000 S2 ! Constant in the f curve best-fit for AOA> alpha1; by definition it depends on the airfoil. [ignored if UAMod<>1] +0.000000 S3 ! Constant in the f curve best-fit for alpha2<=AOA< alpha0; by definition it depends on the airfoil. [ignored if UAMod<>1] +0.000000 S4 ! Constant in the f curve best-fit for AOA< alpha2; by definition it depends on the airfoil. [ignored if UAMod<>1] +1.434702 Cn1 ! Critical value of C0n at leading edge separation. It should be extracted from airfoil data at a given Mach and Reynolds number. It can be calculated from the static value of Cn at either the break in the pitching moment or the loss of chord force at the onset of stall. It is close to the condition of maximum lift of the airfoil at low Mach numbers. +-0.791051 Cn2 ! As Cn1 for negative AOAs. +Default St_sh ! Strouhal's shedding frequency constant. [default = 0.19] +0.013400 Cd0 ! 2D drag coefficient value at 0-lift. +-0.038790 Cm0 ! 2D pitching moment coefficient about 1/4-chord location, at 0-lift, positive if nose up. [If the aerodynamics coefficients table does not include a column for Cm, this needs to be set to 0.0] +0.000000 k0 ! Constant in the \hat(x)_cp curve best-fit; = (\hat(x)_AC-0.25). [ignored if UAMod<>1] +0.000000 k1 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k2 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k3 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k1_hat ! Constant in the expression of Cc due to leading edge vortex effects. [ignored if UAMod<>1] +Default x_cp_bar ! Constant in the expression of \hat(x)_cp^v. [ignored if UAMod<>1, default = 0.2] +Default UACutout ! Angle of attack above which unsteady aerodynamics are disabled (deg). [Specifying the string "Default" sets UACutout to 45 degrees] +Default filtCutOff ! Cut-off frequency (-3 dB corner frequency) for low-pass filtering the AoA input to UA, as well as the 1st and 2nd derivatives (Hz) [default = 20] +!........................................ +! Table of aerodynamics coefficients +200 NumAlf ! Number of data lines in the following table +! Alpha Cl Cd Cm +! (deg) (-) (-) (-) +-1.80000000000000e+02 0.00000000000000e+00 4.36560269351644e-02 0.00000000000000e+00 +-1.77000000000000e+02 1.35439946882412e-01 4.36560269351644e-02 1.18726131869253e-01 +-1.74000000000000e+02 2.73681807554892e-01 5.19326935053434e-02 2.39999774321882e-01 +-1.71000000000000e+02 4.10523187830625e-01 7.67629649316860e-02 3.60000410445527e-01 +-1.68000000000000e+02 5.20540196449849e-01 1.06183060966195e-01 3.39345685302513e-01 +-1.65000000000000e+02 6.17416589309490e-01 1.37898015734769e-01 2.48364921181521e-01 +-1.62000000000000e+02 7.20366694799217e-01 1.69613333930037e-01 1.57382975358883e-01 +-1.59000000000000e+02 7.79902956443025e-01 2.09395231609251e-01 1.00198616429354e-01 +-1.56000000000000e+02 7.54094985201384e-01 2.65310015371530e-01 1.10341134086108e-01 +-1.53000000000000e+02 7.28273002358664e-01 3.21224917158275e-01 1.20030838658758e-01 +-1.50000000000000e+02 7.02433949228043e-01 3.77139907333099e-01 1.29188534097997e-01 +-1.47000000000000e+02 6.88056994571163e-01 4.45660752601736e-01 1.38937062638940e-01 +-1.44000000000000e+02 6.73672820323352e-01 5.14181705032495e-01 1.48679864311782e-01 +-1.41000000000000e+02 6.59280196399078e-01 5.82702871795152e-01 1.58415928945197e-01 +-1.38000000000000e+02 6.40870225785841e-01 6.54060157601795e-01 1.69647719764598e-01 +-1.35000000000000e+02 6.20451890084054e-01 7.26835497177056e-01 1.81625021280610e-01 +-1.32000000000000e+02 6.00029188829974e-01 7.99611206996042e-01 1.93595285306556e-01 +-1.29000000000000e+02 5.75956737945601e-01 8.70852261041323e-01 2.05770654480656e-01 +-1.26000000000000e+02 5.44590931294051e-01 9.39023996253647e-01 2.18364183904311e-01 +-1.23000000000000e+02 5.13223602126577e-01 1.00719521066899e+00 2.30949738818684e-01 +-1.20000000000000e+02 4.81854438801891e-01 1.07536616469559e+00 2.43526390646390e-01 +-1.17000000000000e+02 4.39681481271308e-01 1.13061446591332e+00 2.54956685887127e-01 +-1.14000000000000e+02 3.97508111898989e-01 1.18586253082399e+00 2.66377239042142e-01 +-1.11000000000000e+02 3.55334297402172e-01 1.24111017367587e+00 2.77786058750497e-01 +-1.08000000000000e+02 3.08037893527830e-01 1.28321205725494e+00 2.87281519675595e-01 +-1.05000000000000e+02 2.58180351390511e-01 1.31874096109859e+00 2.95813196403833e-01 +-1.02000000000000e+02 2.08323097887283e-01 1.35426945781572e+00 3.04327743613626e-01 +-9.90000000000000e+01 1.57576203402918e-01 1.38176151510008e+00 3.11395522027348e-01 +-9.60000000000000e+01 1.05050834785785e-01 1.39318034541842e+00 3.15588655906570e-01 +-9.30000000000000e+01 5.25255582791447e-02 1.40459908850334e+00 3.19756596609520e-01 +-9.00000000000000e+01 3.27826917023240e-07 1.41601778797233e+00 3.23659461316635e-01 +-8.70000000000000e+01 -5.25255045195490e-02 1.40459910019038e+00 3.22945034933183e-01 +-8.40000000000000e+01 -1.05050981658418e-01 1.39318031348883e+00 3.21791611743605e-01 +-8.10000000000000e+01 -1.57575748382869e-01 1.38176161401983e+00 3.20129918962609e-01 +-7.80000000000000e+01 -2.08322856414832e-01 1.35426962988931e+00 3.17048455458342e-01 +-7.50000000000000e+01 -2.58180681242367e-01 1.31874072604392e+00 3.12905041046394e-01 +-7.20000000000000e+01 -3.08037652060678e-01 1.28321222932679e+00 3.08761210418793e-01 +-6.90000000000000e+01 -3.55333932045767e-01 1.24111065228680e+00 3.03514635390291e-01 +-6.60000000000000e+01 -3.97508229824454e-01 1.18586237634021e+00 2.96062481257706e-01 +-6.30000000000000e+01 -4.39681760287162e-01 1.13061410039362e+00 2.88610017991116e-01 +-6.00000000000000e+01 -4.81854646345531e-01 1.07536571368012e+00 2.81157387364500e-01 +-5.70000000000000e+01 -5.13223809656928e-01 1.00719475965353e+00 2.72212286505312e-01 +-5.40000000000000e+01 -5.44591138813060e-01 9.39023545233018e-01 2.63266996912069e-01 +-5.10000000000000e+01 -5.75956945455947e-01 8.70851810020693e-01 2.54321329847841e-01 +-4.80000000000000e+01 -6.01326324662319e-01 7.99654560229442e-01 2.45618131252866e-01 +-4.50000000000000e+01 -6.23695970153485e-01 7.26944601773029e-01 2.37036162995707e-01 +-4.20000000000000e+01 -6.42168713793076e-01 6.54103510491734e-01 2.29439922053861e-01 +-3.90000000000000e+01 -6.59537045517161e-01 5.81899603350932e-01 2.22338894134465e-01 +-3.60000000000000e+01 -6.74166998306598e-01 5.11590826220192e-01 2.16852610379598e-01 +-3.30000000000000e+01 -6.88095062911521e-01 4.43295420850299e-01 2.13321658336198e-01 +-3.00000000000000e+01 -7.02434061164880e-01 3.77139487001304e-01 2.11949178572412e-01 +-2.93939393939394e+01 -7.06130482490463e-01 3.64852362744942e-01 2.12237605316701e-01 +-2.87878787878788e+01 -7.09824479328829e-01 3.52565238488579e-01 2.12555391583848e-01 +-2.81818181818182e+01 -7.13516027506550e-01 3.40278114232216e-01 2.12872847967098e-01 +-2.75757575757576e+01 -7.17530381434993e-01 3.28305985630029e-01 2.13597061869978e-01 +-2.69696969696970e+01 -7.21682227375692e-01 3.16468866746567e-01 2.14495479961637e-01 +-2.63636363636364e+01 -7.25832258736785e-01 3.04631747863105e-01 2.15393660836009e-01 +-2.57575757575758e+01 -7.30267770470675e-01 2.92993562362201e-01 2.16593296530334e-01 +-2.51515151515151e+01 -7.35132964149189e-01 2.81653730571187e-01 2.18245185960105e-01 +-2.45454545454545e+01 -7.39997274048644e-01 2.70313898780173e-01 2.19896919526772e-01 +-2.39393939393939e+01 -7.44966676859083e-01 2.59028163484346e-01 2.21648566366930e-01 +-2.33333333333333e+01 -7.50889197184390e-01 2.48229307118538e-01 2.24300599299510e-01 +-2.27272727272727e+01 -7.56811618414165e-01 2.37430450752730e-01 2.26952544318588e-01 +-2.21212121212121e+01 -7.62733947044537e-01 2.26631594386922e-01 2.29604411305050e-01 +-2.15151515151515e+01 -7.65543180919198e-01 2.16298421341179e-01 2.33347719604617e-01 +-2.09090909090909e+01 -7.67159390551658e-01 2.06081699080272e-01 2.37363936868452e-01 +-2.03030303030303e+01 -7.70989589899503e-01 1.95864976819365e-01 2.41380122381193e-01 +-1.96969696969697e+01 -7.66408855179284e-01 1.86713082311620e-01 2.37110565273848e-01 +-1.90909090909091e+01 -7.53224334899666e-01 1.78625955319317e-01 2.24555711213706e-01 +-1.84848484848485e+01 -7.40515247767467e-01 1.70539222184923e-01 2.12001402771163e-01 +-1.78787878787879e+01 -7.28073414237448e-01 1.62452465875814e-01 1.99446889701465e-01 +-1.72727272727273e+01 -7.15796412819352e-01 1.54365338883510e-01 1.86891340465851e-01 +-1.66666666666667e+01 -7.03628403601917e-01 1.45137051028637e-01 1.74335949867985e-01 +-1.60606060606061e+01 -6.91536071334431e-01 1.35827440633388e-01 1.61780655103707e-01 +-1.54545454545455e+01 -6.79841375439502e-01 1.27125362674088e-01 1.49225873196518e-01 +-1.48484848484848e+01 -6.68371976472640e-01 1.18756044019379e-01 1.36670824522160e-01 +-1.42424242424242e+01 -6.57525266337486e-01 1.11081575507249e-01 1.24115046890632e-01 +-1.36363636363636e+01 -6.46919349317121e-01 1.03510536591038e-01 1.11559472566631e-01 +-1.30303030303030e+01 -6.36590196575789e-01 9.60197655285123e-02 9.90027923089362e-02 +-1.24242424242424e+01 -6.26616545201912e-01 8.84489364835728e-02 8.64466304336154e-02 +-1.18181818181818e+01 -6.16997647064756e-01 8.07255969659771e-02 7.38892790664918e-02 +-1.12121212121212e+01 -6.07806438992942e-01 7.26223306995905e-02 6.13323781273887e-02 +-1.06060606060606e+01 -5.99288567453162e-01 6.43078358166966e-02 4.87732017593027e-02 +-1.00000000000000e+01 -5.91657873003445e-01 5.59263606591254e-02 3.62141784693746e-02 +-9.39393939393939e+00 -5.79058163807746e-01 4.91379422584400e-02 2.49867487590630e-02 +-8.78787878787879e+00 -5.66700483456983e-01 4.25327427253251e-02 1.37556766416755e-02 +-8.18181818181818e+00 -5.52767057263263e-01 3.51385027365045e-02 2.51431078401171e-03 +-7.57575757575758e+00 -5.16152487631087e-01 3.07167300167049e-02 -3.52520860243561e-03 +-6.96969696969697e+00 -4.69757056162087e-01 2.73460615848954e-02 -7.35433309173912e-03 +-6.36363636363636e+00 -4.23157901477119e-01 2.40466853818601e-02 -1.16480887450771e-02 +-5.75757575757576e+00 -3.74765829542321e-01 2.11022048511000e-02 -1.59084513723056e-02 +-5.15151515151515e+00 -3.23413692430681e-01 1.89550579096399e-02 -1.86750851344994e-02 +-4.54545454545454e+00 -2.68547626763533e-01 1.70622389773778e-02 -2.19719612773405e-02 +-3.93939393939394e+00 -2.11994257260558e-01 1.53692119559176e-02 -2.56157244462441e-02 +-3.33333333333333e+00 -1.48415934878880e-01 1.48139917958905e-02 -2.94968023177144e-02 +-2.72727272727273e+00 -7.89769276979072e-02 1.41624540467447e-02 -3.39437653144343e-02 +-2.12121212121212e+00 -3.46478095391404e-03 1.34145873263993e-02 -3.86035781138906e-02 +-1.51515151515152e+00 7.38291063274909e-02 1.30921930075161e-02 -4.27533487199522e-02 +-9.09090909090912e-01 1.51829760730163e-01 1.28923820998857e-02 -4.69054889010057e-02 +-3.03030303030302e-01 2.30822308320161e-01 1.28050693423605e-02 -5.10801102705995e-02 + 3.03030303030302e-01 3.10463730114934e-01 1.27477575306067e-02 -5.50677649278274e-02 + 9.09090909090912e-01 3.90790263359822e-01 1.27353987638778e-02 -5.88795212672597e-02 + 1.51515151515152e+00 4.71284233730724e-01 1.28776954822189e-02 -6.27273016180439e-02 + 2.12121212121212e+00 5.50963097343411e-01 1.30675735894997e-02 -6.64832475878559e-02 + 2.72727272727273e+00 6.30138935816981e-01 1.32424674678596e-02 -6.95217238202173e-02 + 3.33333333333333e+00 7.08536320290482e-01 1.34717732475649e-02 -7.23228820759458e-02 + 3.93939393939394e+00 7.86307858387585e-01 1.38172159080549e-02 -7.49142757271172e-02 + 4.54545454545455e+00 8.62388339964567e-01 1.42557288224049e-02 -7.75040470102574e-02 + 5.15151515151515e+00 9.37700928676955e-01 1.47059776016534e-02 -8.00049921252249e-02 + 5.75757575757576e+00 1.01125073389474e+00 1.51614417050010e-02 -8.21454604598515e-02 + 6.36363636363637e+00 1.08227624065879e+00 1.57108190803841e-02 -8.39835694506992e-02 + 6.96969696969697e+00 1.15161256120026e+00 1.63448211385627e-02 -8.56439571000181e-02 + 7.57575757575757e+00 1.21596411426272e+00 1.71676404929355e-02 -8.74082304182359e-02 + 8.18181818181818e+00 1.27673300509297e+00 1.80775111046661e-02 -8.94455339298536e-02 + 8.78787878787879e+00 1.33119115050654e+00 1.91750329509376e-02 -9.16003178554933e-02 + 9.39393939393939e+00 1.37956425338417e+00 2.13859354652657e-02 -9.38392678971121e-02 + 1.00000000000000e+01 1.42465603147829e+00 2.40167211153884e-02 -9.61318882807184e-02 + 1.06060606060606e+01 1.44856679840724e+00 2.73518951987084e-02 -9.83269145446295e-02 + 1.12121212121212e+01 1.45643493495683e+00 3.11907783963854e-02 -1.01693563008612e-01 + 1.18181818181818e+01 1.44145511321968e+00 3.67776864017581e-02 -1.04240570768266e-01 + 1.24242424242424e+01 1.25811612577190e+00 4.49502463857501e-02 -9.87981028722830e-02 + 1.30303030303030e+01 1.21783548130362e+00 5.37917825568218e-02 -9.72024540714103e-02 + 1.36363636363636e+01 1.20160458150153e+00 6.40421590933513e-02 -9.82023678961166e-02 + 1.42424242424242e+01 1.18813191525126e+00 7.46618265741957e-02 -9.95181720845514e-02 + 1.48484848484848e+01 1.18027423785320e+00 8.60251229889524e-02 -1.01193555150372e-01 + 1.54545454545455e+01 1.17877779387270e+00 9.81117465457450e-02 -1.05541629489454e-01 + 1.60606060606061e+01 1.17689322444726e+00 1.10556666678342e-01 -1.10785671275185e-01 + 1.66666666666667e+01 1.16581038309829e+00 1.24057053255380e-01 -1.18134261648867e-01 + 1.72727272727273e+01 1.15665660147017e+00 1.37525823660165e-01 -1.25046831531383e-01 + 1.78787878787879e+01 1.14984732933414e+00 1.50955951675739e-01 -1.31427188552528e-01 + 1.84848484848485e+01 1.14985357005765e+00 1.64278673861716e-01 -1.35546000357850e-01 + 1.90909090909091e+01 1.14897293619198e+00 1.76960001690690e-01 -1.39369242924789e-01 + 1.96969696969697e+01 1.13396288213762e+00 1.86157753963698e-01 -1.44719855669495e-01 + 2.03030303030303e+01 1.12113454332556e+00 1.95864976819365e-01 -1.49461918843513e-01 + 2.09090909090909e+01 1.11049287841322e+00 2.06081699080272e-01 -1.53594296036503e-01 + 2.15151515151515e+01 1.09985087842677e+00 2.16298421341179e-01 -1.57724684571442e-01 + 2.21212121212121e+01 1.08964494555376e+00 2.26631594386922e-01 -1.61741842424593e-01 + 2.27272727272727e+01 1.08118409226682e+00 2.37430450752730e-01 -1.65312206684248e-01 + 2.33333333333333e+01 1.07272310525245e+00 2.48229307118538e-01 -1.68881329238900e-01 + 2.39393939393939e+01 1.06426197511829e+00 2.59028163484346e-01 -1.72449237026485e-01 + 2.45454545454545e+01 1.05716247952044e+00 2.70313898780173e-01 -1.75700716715067e-01 + 2.51515151515151e+01 1.05021311424356e+00 2.81653730571187e-01 -1.78916186478768e-01 + 2.57575757575758e+01 1.04326247901123e+00 2.92993562362201e-01 -1.82130682130006e-01 + 2.63636363636364e+01 1.03692547814336e+00 3.04631747863105e-01 -1.85209085023971e-01 + 2.69696969696970e+01 1.03099616857058e+00 3.16468866746567e-01 -1.88196490642796e-01 + 2.75757575757576e+01 1.02506425393147e+00 3.28305985630029e-01 -1.91182998125262e-01 + 2.81818181818182e+01 1.01932894884137e+00 3.40278114232216e-01 -1.94124420358041e-01 + 2.87878787878788e+01 1.01405525818665e+00 3.52565238488579e-01 -1.96961880499345e-01 + 2.93939393939394e+01 1.00877805189828e+00 3.64852362744942e-01 -1.99798436276836e-01 + 3.00000000000000e+01 1.00349736452608e+00 3.77139487001304e-01 -2.02634065252844e-01 + 3.30000000000000e+01 9.82998715735978e-01 4.43295420850300e-01 -2.15352590816283e-01 + 3.60000000000000e+01 9.63089651383735e-01 5.11590826220192e-01 -2.27863925187279e-01 + 3.90000000000000e+01 9.42175986921238e-01 5.81899603350932e-01 -2.39321618575565e-01 + 4.20000000000000e+01 9.17369367761984e-01 6.54103510491734e-01 -2.50662792778012e-01 + 4.50000000000000e+01 8.90994844258789e-01 7.26944601773029e-01 -2.61985791102602e-01 + 4.80000000000000e+01 8.59052634531658e-01 7.99654560229442e-01 -2.73143035398585e-01 + 5.10000000000000e+01 8.22819956247608e-01 8.70851810020694e-01 -2.84140610804423e-01 + 5.40000000000000e+01 7.78010344233567e-01 9.39023545233018e-01 -2.94794033259472e-01 + 5.70000000000000e+01 7.33199012906027e-01 1.00719475965353e+00 -3.05462909314392e-01 + 6.00000000000000e+01 6.88385299195316e-01 1.07536571368012e+00 -3.16145847013128e-01 + 6.30000000000000e+01 6.28130235918108e-01 1.13061410039362e+00 -3.25620798502509e-01 + 6.60000000000000e+01 5.67874167049533e-01 1.18586237634021e+00 -3.35110403637996e-01 + 6.90000000000000e+01 5.07616883385694e-01 1.24111065228680e+00 -3.44613531015476e-01 + 7.20000000000000e+01 4.40053035872077e-01 1.28321222932679e+00 -3.52880607742317e-01 + 7.50000000000000e+01 3.68836397224492e-01 1.31874072604392e+00 -3.60538886626655e-01 + 7.80000000000000e+01 2.97618557438900e-01 1.35426962988931e+00 -3.68212529205940e-01 + 8.10000000000000e+01 2.25125798524460e-01 1.38176161401983e+00 -3.75046689565342e-01 + 8.40000000000000e+01 1.50084444920197e-01 1.39318031348883e+00 -3.80189854624853e-01 + 8.70000000000000e+01 7.50422088870966e-02 1.40459910019038e+00 -3.85401065327424e-01 + 9.00000000000000e+01 -3.27826917250672e-07 1.41601778797233e+00 -3.90743940003956e-01 + 9.30000000000000e+01 -5.25255582791447e-02 1.40459908850334e+00 -3.92409982314967e-01 + 9.60000000000000e+01 -1.05050834785786e-01 1.39318034541842e+00 -3.94293016797664e-01 + 9.90000000000000e+01 -1.57576203402918e-01 1.38176151510008e+00 -3.96176174609728e-01 + 1.02000000000000e+02 -2.08323097887283e-01 1.35426945781572e+00 -3.94964753048719e-01 + 1.05000000000000e+02 -2.58180351390512e-01 1.31874096109859e+00 -3.92206337784692e-01 + 1.08000000000000e+02 -3.08037893527830e-01 1.28321205725494e+00 -3.89447790562342e-01 + 1.11000000000000e+02 -3.55334297402172e-01 1.24111017367587e+00 -3.85534983800253e-01 + 1.14000000000000e+02 -3.97508111898989e-01 1.18586253082399e+00 -3.79313668806810e-01 + 1.17000000000000e+02 -4.39681481271308e-01 1.13061446591332e+00 -3.73092768861011e-01 + 1.20000000000000e+02 -4.81854438801891e-01 1.07536616469558e+00 -3.66872427068639e-01 + 1.23000000000000e+02 -5.13223602126577e-01 1.00719521066899e+00 -3.59027141872641e-01 + 1.26000000000000e+02 -5.44590931294051e-01 9.39023996253647e-01 -3.51183092578474e-01 + 1.29000000000000e+02 -5.75956737945602e-01 8.70852261041322e-01 -3.43340078183588e-01 + 1.32000000000000e+02 -6.00029188829974e-01 7.99611206996042e-01 -3.36135466500916e-01 + 1.35000000000000e+02 -6.20451890084054e-01 7.26835497177056e-01 -3.29251904114765e-01 + 1.38000000000000e+02 -6.40870225785841e-01 6.54060157601795e-01 -3.22371150094234e-01 + 1.41000000000000e+02 -6.59280196399078e-01 5.82702871795151e-01 -3.17195017404215e-01 + 1.44000000000000e+02 -6.73672820323352e-01 5.14181705032495e-01 -3.15427742312397e-01 + 1.47000000000000e+02 -6.88056994571163e-01 4.45660752601736e-01 -3.13666489886140e-01 + 1.50000000000000e+02 -7.02433949228043e-01 3.77139907333099e-01 -3.11911025372031e-01 + 1.53000000000000e+02 -7.28273002358664e-01 3.21224917158276e-01 -3.26779546578991e-01 + 1.56000000000000e+02 -7.54094985201384e-01 2.65310015371530e-01 -3.41648669551904e-01 + 1.59000000000000e+02 -7.79902956443025e-01 2.09395231609251e-01 -3.56518297584456e-01 + 1.62000000000000e+02 -7.15623711897387e-01 1.69995730690300e-01 -3.89180151768352e-01 + 1.65000000000000e+02 -6.04668180255573e-01 1.38854010867083e-01 -4.30738080965074e-01 + 1.68000000000000e+02 -5.04633128784701e-01 1.07712184204155e-01 -4.72295103043239e-01 + 1.71000000000000e+02 -3.90299886270968e-01 7.84829800637506e-02 -4.50000513056908e-01 + 1.74000000000000e+02 -2.60199626255756e-01 5.30791102629704e-02 -2.99999717902353e-01 + 1.77000000000000e+02 -1.28700931105444e-01 4.42220543974298e-02 -1.48407664836567e-01 + 1.80000000000000e+02 0.00000000000000e+00 4.36560269351644e-02 0.00000000000000e+00 diff --git a/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_09.dat b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_09.dat new file mode 100644 index 00000000..709a0e40 --- /dev/null +++ b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_09.dat @@ -0,0 +1,254 @@ +! ------------ AirfoilInfo v1.01.x Input File ---------------------------------- +! AeroElasticSE FAST driver +! line +! line +! ------------------------------------------------------------------------------ +DEFAULT InterpOrd ! Interpolation order to use for quasi-steady table lookup {1=linear; 3=cubic spline; "default"} [default=3] +1 NonDimArea ! The non-dimensional area of the airfoil (area/chord^2) (set to 1.0 if unsure or unneeded) +@"NREL-2p8-127_AF09_Coords.txt" NumCoords ! The number of coordinates in the airfoil shape file. Set to zero if coordinates not included. +AF09_BL.txt BL_file ! The file name including the boundary layer characteristics of the profile. Ignored if the aeroacoustic module is not called. +1 NumTabs ! Number of airfoil tables in this file. Each table must have lines for Re and Ctrl. +! ------------------------------------------------------------------------------ +! data for table 1 +! ------------------------------------------------------------------------------ +6.000000 Re ! Reynolds number in millions +0 Ctrl ! Control setting (must be 0 for current AirfoilInfo) +True InclUAdata ! Is unsteady aerodynamics data included in this table? If TRUE, then include 30 UA coefficients below this line +!........................................ +-2.060385 alpha0 ! 0-lift angle of attack, depends on airfoil. +11.208140 alpha1 ! Angle of attack at f=0.7, (approximately the stall angle) for AOA>alpha0. (deg) +-7.861323 alpha2 ! Angle of attack at f=0.7, (approximately the stall angle) for AOA1] +0.000000 S2 ! Constant in the f curve best-fit for AOA> alpha1; by definition it depends on the airfoil. [ignored if UAMod<>1] +0.000000 S3 ! Constant in the f curve best-fit for alpha2<=AOA< alpha0; by definition it depends on the airfoil. [ignored if UAMod<>1] +0.000000 S4 ! Constant in the f curve best-fit for AOA< alpha2; by definition it depends on the airfoil. [ignored if UAMod<>1] +1.367424 Cn1 ! Critical value of C0n at leading edge separation. It should be extracted from airfoil data at a given Mach and Reynolds number. It can be calculated from the static value of Cn at either the break in the pitching moment or the loss of chord force at the onset of stall. It is close to the condition of maximum lift of the airfoil at low Mach numbers. +-0.824883 Cn2 ! As Cn1 for negative AOAs. +Default St_sh ! Strouhal's shedding frequency constant. [default = 0.19] +0.010934 Cd0 ! 2D drag coefficient value at 0-lift. +-0.049324 Cm0 ! 2D pitching moment coefficient about 1/4-chord location, at 0-lift, positive if nose up. [If the aerodynamics coefficients table does not include a column for Cm, this needs to be set to 0.0] +0.000000 k0 ! Constant in the \hat(x)_cp curve best-fit; = (\hat(x)_AC-0.25). [ignored if UAMod<>1] +0.000000 k1 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k2 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k3 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k1_hat ! Constant in the expression of Cc due to leading edge vortex effects. [ignored if UAMod<>1] +Default x_cp_bar ! Constant in the expression of \hat(x)_cp^v. [ignored if UAMod<>1, default = 0.2] +Default UACutout ! Angle of attack above which unsteady aerodynamics are disabled (deg). [Specifying the string "Default" sets UACutout to 45 degrees] +Default filtCutOff ! Cut-off frequency (-3 dB corner frequency) for low-pass filtering the AoA input to UA, as well as the 1st and 2nd derivatives (Hz) [default = 20] +!........................................ +! Table of aerodynamics coefficients +200 NumAlf ! Number of data lines in the following table +! Alpha Cl Cd Cm +! (deg) (-) (-) (-) +-1.80000000000000e+02 0.00000000000000e+00 5.31472191671717e-02 0.00000000000000e+00 +-1.77000000000000e+02 1.29495037060763e-01 5.31472191671717e-02 1.18521230701205e-01 +-1.74000000000000e+02 2.62196549024508e-01 6.37579530831230e-02 2.39999774321882e-01 +-1.71000000000000e+02 3.93295149394492e-01 9.55905031721947e-02 3.60000410445527e-01 +-1.68000000000000e+02 5.10233340661308e-01 1.28558250585849e-01 3.26000611777352e-01 +-1.65000000000000e+02 6.19785379304123e-01 1.62093583412369e-01 2.15002393125294e-01 +-1.62000000000000e+02 7.31395834011373e-01 1.95629300525583e-01 1.04002855069395e-01 +-1.59000000000000e+02 7.97042839057236e-01 2.36917620123939e-01 3.50287462844128e-02 +-1.56000000000000e+02 7.70832295867696e-01 2.93710882428943e-01 5.00110113837699e-02 +-1.53000000000000e+02 7.44620920477827e-01 3.50504182292723e-01 6.48349471240901e-02 +-1.50000000000000e+02 7.18408694438638e-01 4.07297530590864e-01 7.94722317169135e-02 +-1.47000000000000e+02 7.03823896258865e-01 4.76817027337738e-01 9.22485232622368e-02 +-1.44000000000000e+02 6.89238523528509e-01 5.46336591473471e-01 1.05021570591302e-01 +-1.41000000000000e+02 6.74652275680612e-01 6.15856290391738e-01 1.17790814864596e-01 +-1.38000000000000e+02 6.55921766878216e-01 6.88177317217559e-01 1.31322598661476e-01 +-1.35000000000000e+02 6.35119149734577e-01 7.61899002314359e-01 1.45235182430339e-01 +-1.32000000000000e+02 6.14315531955484e-01 8.35620937733996e-01 1.59144670993128e-01 +-1.29000000000000e+02 5.89758365423619e-01 9.07722303996263e-01 1.73171416661612e-01 +-1.26000000000000e+02 5.57694365436177e-01 9.76582524253020e-01 1.87436089134836e-01 +-1.23000000000000e+02 5.25630147618883e-01 1.04544221845313e+00 2.01697660743594e-01 +-1.20000000000000e+02 4.93565771807661e-01 1.11430164963474e+00 2.15955995381730e-01 +-1.17000000000000e+02 4.50397682635010e-01 1.16980036934638e+00 2.29069583999682e-01 +-1.14000000000000e+02 4.07229711397332e-01 1.22529885093775e+00 2.42179581353683e-01 +-1.11000000000000e+02 3.64062034832866e-01 1.28079690855731e+00 2.55285105310821e-01 +-1.08000000000000e+02 3.15627063533621e-01 1.32277521883958e+00 2.66511224315401e-01 +-1.05000000000000e+02 2.64558413703211e-01 1.35799355250651e+00 2.76794753835721e-01 +-1.02000000000000e+02 2.13490336137694e-01 1.39321148260576e+00 2.87071098135651e-01 +-9.90000000000000e+01 1.61500486209697e-01 1.42017677477570e+00 2.95908817817940e-01 +-9.60000000000000e+01 1.07667090348450e-01 1.43063643362188e+00 3.01875969512173e-01 +-9.30000000000000e+01 5.38337094334587e-02 1.44109601256217e+00 3.07830613812683e-01 +-9.00000000000000e+01 3.35991459655313e-07 1.45155555155023e+00 3.13757307492905e-01 +-8.70000000000000e+01 -5.38336543349781e-02 1.44109602326751e+00 3.15792074690342e-01 +-8.40000000000000e+01 -1.07667240878618e-01 1.43063640437435e+00 3.17709664434913e-01 +-8.10000000000000e+01 -1.61500019858388e-01 1.42017686538628e+00 3.19427985605789e-01 +-7.80000000000000e+01 -2.13490088801890e-01 1.39321165317520e+00 3.18443936149184e-01 +-7.50000000000000e+01 -2.64558751566886e-01 1.35799331950653e+00 3.16050829869962e-01 +-7.20000000000000e+01 -3.15626816200455e-01 1.32277538940729e+00 3.13657156553441e-01 +-6.90000000000000e+01 -3.64061660870620e-01 1.28079738933759e+00 3.10049989411700e-01 +-6.60000000000000e+01 -4.07229832102981e-01 1.22529869575376e+00 3.04015735248115e-01 +-6.30000000000000e+01 -4.50397968233045e-01 1.16980000216993e+00 2.97981084772964e-01 +-6.00000000000000e+01 -4.93565983944208e-01 1.11430119406435e+00 2.91946220973731e-01 +-5.70000000000000e+01 -5.25630359754821e-01 1.04544176288274e+00 2.84141782265212e-01 +-5.40000000000000e+01 -5.57694577570126e-01 9.76582068677410e-01 2.76337115591071e-01 +-5.10000000000000e+01 -5.89758577557172e-01 9.07721848420653e-01 2.68531992982216e-01 +-4.80000000000000e+01 -6.15975377464480e-01 8.35676496789876e-01 2.60891044708829e-01 +-4.50000000000000e+01 -6.39268597360940e-01 7.62038630661659e-01 2.53332180964662e-01 +-4.20000000000000e+01 -6.57581661720133e-01 6.88232875834521e-01 2.47037064737753e-01 +-3.90000000000000e+01 -6.74980379108277e-01 6.14826511890619e-01 2.41247071396765e-01 +-3.60000000000000e+01 -6.89869193378202e-01 5.43015121244335e-01 2.37267768231330e-01 +-3.30000000000000e+01 -7.03872456392545e-01 4.73784534746912e-01 2.35795153182948e-01 +-3.00000000000000e+01 -7.18408799575845e-01 4.07297098236698e-01 2.37089771150360e-01 +-2.93939393939394e+01 -7.21762686347836e-01 3.94552959906465e-01 2.38090915530434e-01 +-2.87878787878788e+01 -7.25116462207148e-01 3.81808821576231e-01 2.39093403016499e-01 +-2.81818181818182e+01 -7.28470126047924e-01 3.69064683245998e-01 2.40095875411411e-01 +-2.75757575757576e+01 -7.32236853727248e-01 3.56724431468315e-01 2.41620187509530e-01 +-2.69696969696970e+01 -7.36180584373604e-01 3.44557288776848e-01 2.43368158185924e-01 +-2.63636363636364e+01 -7.40124232008641e-01 3.32390146085381e-01 2.45116118010372e-01 +-2.57575757575758e+01 -7.44432056142082e-01 3.20478002655761e-01 2.47250782325627e-01 +-2.51515151515151e+01 -7.49286130044737e-01 3.08948298688103e-01 2.49965419735941e-01 +-2.45454545454545e+01 -7.54140163517274e-01 2.97418594720445e-01 2.52680050016007e-01 +-2.39393939393939e+01 -7.59128300719057e-01 2.85958242769248e-01 2.55522930540395e-01 +-2.33333333333333e+01 -7.65323729613723e-01 2.75122072393073e-01 2.59520140578325e-01 +-2.27272727272727e+01 -7.71519153975079e-01 2.64285902016898e-01 2.63517346594489e-01 +-2.21212121212121e+01 -7.77714574100304e-01 2.53449731640723e-01 2.67514549040905e-01 +-2.15151515151515e+01 -7.83978195814861e-01 2.43210638882764e-01 2.72910891584855e-01 +-2.09090909090909e+01 -7.90117542155355e-01 2.33120853936042e-01 2.78657108165319e-01 +-2.03030303030303e+01 -7.97012109620063e-01 2.23031068989321e-01 2.84403323293269e-01 +-1.96969696969697e+01 -7.95415736248302e-01 2.13313352612748e-01 2.80089060137697e-01 +-1.90909090909091e+01 -7.85263277790639e-01 2.03967683758259e-01 2.65714886768838e-01 +-1.84848484848485e+01 -7.75273314466664e-01 1.94622470054976e-01 2.51341410437202e-01 +-1.78787878787879e+01 -7.65374889035412e-01 1.85277229570461e-01 2.36967769403479e-01 +-1.72727272727273e+01 -7.55533108229545e-01 1.75931560715972e-01 2.22592985180729e-01 +-1.66666666666667e+01 -7.45728795354525e-01 1.66196420256137e-01 2.08218526695132e-01 +-1.60606060606061e+01 -7.35950554364156e-01 1.56433343834581e-01 1.93844333165442e-01 +-1.54545454545455e+01 -7.26308463193755e-01 1.46878222014310e-01 1.79470874697127e-01 +-1.48484848484848e+01 -7.16743375686355e-01 1.37436585788465e-01 1.65097285434163e-01 +-1.42424242424242e+01 -7.07390619723189e-01 1.28231667233805e-01 1.50723069814813e-01 +-1.36363636363636e+01 -6.98120667001908e-01 1.19062253074563e-01 1.36349337872941e-01 +-1.30303030303030e+01 -6.88944298853437e-01 1.09919099684084e-01 1.21974646106258e-01 +-1.24242424242424e+01 -6.79890334514997e-01 1.00749731941577e-01 1.07600926861901e-01 +-1.18181818181818e+01 -6.70956348082078e-01 9.15279934171627e-02 9.32263230029353e-02 +-1.12121212121212e+01 -6.62168843237812e-01 8.21771971589323e-02 7.88528466356555e-02 +-1.06060606060606e+01 -6.53611277615254e-01 7.27538640183303e-02 6.44774855298434e-02 +-1.00000000000000e+01 -6.45356230550116e-01 6.33080422182624e-02 5.01034327127313e-02 +-9.39393939393939e+00 -6.36593332900123e-01 5.41963669816850e-02 3.57833738354860e-02 +-8.78787878787879e+00 -6.27918256833836e-01 4.51475416350120e-02 2.14623968040231e-02 +-8.18181818181818e+00 -6.18711373162793e-01 3.58305294547305e-02 7.14198465445491e-03 +-7.57575757575758e+00 -5.80216174573165e-01 3.01489440959233e-02 -5.19349418320715e-04 +-6.96969696969697e+00 -5.28953354241068e-01 2.59835542019697e-02 -5.35572587261972e-03 +-6.36363636363636e+00 -4.73862537653747e-01 2.22211779699908e-02 -1.07634960479835e-02 +-5.75757575757576e+00 -4.16582198644429e-01 1.90003840623066e-02 -1.61245333665883e-02 +-5.15151515151515e+00 -3.55933513528219e-01 1.66928246089848e-02 -2.10369141861243e-02 +-4.54545454545454e+00 -2.91472100196896e-01 1.47078923324148e-02 -2.64604110668977e-02 +-3.93939393939394e+00 -2.25304889231469e-01 1.29545096367512e-02 -3.21126856296872e-02 +-3.33333333333333e+00 -1.54104000261012e-01 1.23887165275606e-02 -3.78462438825610e-02 +-2.72727272727273e+00 -8.16248041858842e-02 1.17323458130580e-02 -4.34613224548195e-02 +-2.12121212121212e+00 -7.62116470645060e-03 1.09678271146517e-02 -4.88326464973399e-02 +-1.51515151515152e+00 6.83134982557210e-02 1.06280353358650e-02 -5.37247752016293e-02 +-9.09090909090912e-01 1.44916946777653e-01 1.04099760350921e-02 -5.85191375679298e-02 +-3.03030303030302e-01 2.22554588237817e-01 1.02931716210053e-02 -6.33281972284231e-02 + 3.03030303030302e-01 3.00795206874542e-01 1.02297528304907e-02 -6.78528768736416e-02 + 9.09090909090912e-01 3.79652000805070e-01 1.02202988420258e-02 -7.20918564811688e-02 + 1.51515151515152e+00 4.59004148697031e-01 1.03956813611896e-02 -7.63468764323537e-02 + 2.12121212121212e+00 5.38292042421047e-01 1.06036731488726e-02 -8.03761253262362e-02 + 2.72727272727273e+00 6.17098027022441e-01 1.08115944967115e-02 -8.34392709248819e-02 + 3.33333333333333e+00 6.94907654704091e-01 1.10839446374173e-02 -8.61737788284095e-02 + 3.93939393939394e+00 7.71913058145968e-01 1.14291538648689e-02 -8.86385535504365e-02 + 4.54545454545455e+00 8.46751947966220e-01 1.18860333393268e-02 -9.11095009974341e-02 + 5.15151515151515e+00 9.20604899194484e-01 1.23569858194089e-02 -9.34332370032627e-02 + 5.75757575757576e+00 9.92199902524323e-01 1.28374739059253e-02 -9.53033834851092e-02 + 6.36363636363637e+00 1.06055718025240e+00 1.34310891694729e-02 -9.68110066273987e-02 + 6.96969696969697e+00 1.12674988698576e+00 1.40997355822941e-02 -9.80785912470612e-02 + 7.57575757575757e+00 1.18666342902678e+00 1.49845781349695e-02 -9.93714676847982e-02 + 8.18181818181818e+00 1.24314989353240e+00 1.59667211082838e-02 -1.00692149985168e-01 + 8.78787878787879e+00 1.29245687180882e+00 1.71544710253729e-02 -1.02035478870500e-01 + 9.39393939393939e+00 1.33396126311506e+00 1.95659937586037e-02 -1.03407560601880e-01 + 1.00000000000000e+01 1.37126009363817e+00 2.25665763961257e-02 -1.04797915194330e-01 + 1.06060606060606e+01 1.38618576553784e+00 2.67311075620441e-02 -1.05641194801641e-01 + 1.12121212121212e+01 1.38519725174546e+00 3.17846622479086e-02 -1.06586637285388e-01 + 1.18181818181818e+01 1.35493629423442e+00 3.87531354728749e-02 -1.07628263634721e-01 + 1.24242424242424e+01 1.31246186473740e+00 4.83484785906573e-02 -1.07847108308056e-01 + 1.30303030303030e+01 1.28680791441048e+00 5.91170543627865e-02 -1.08015031049527e-01 + 1.36363636363636e+01 1.26172678770879e+00 7.17168991472314e-02 -1.08181203384768e-01 + 1.42424242424242e+01 1.23769104210515e+00 8.49758848909100e-02 -1.08605313713084e-01 + 1.48484848484848e+01 1.21528767185958e+00 9.92702312554880e-02 -1.09411818544650e-01 + 1.54545454545455e+01 1.19968194488222e+00 1.14607265848385e-01 -1.13749735842298e-01 + 1.60606060606061e+01 1.18663909270316e+00 1.30222530116573e-01 -1.19428362054540e-01 + 1.66666666666667e+01 1.17688627348101e+00 1.45214198979932e-01 -1.27285721302187e-01 + 1.72727272727273e+01 1.16956684907482e+00 1.60165335729503e-01 -1.34601993519905e-01 + 1.78787878787879e+01 1.16522099838670e+00 1.75066932714929e-01 -1.41256962609131e-01 + 1.84848484848485e+01 1.16952525051625e+00 1.89830940964302e-01 -1.45028799262795e-01 + 1.90909090909091e+01 1.17284535113364e+00 2.03772684613384e-01 -1.48423774647318e-01 + 1.96969696969697e+01 1.15835573662925e+00 2.13248351672080e-01 -1.53767566099225e-01 + 2.03030303030303e+01 1.14530509433480e+00 2.23031068989321e-01 -1.58704075145085e-01 + 2.09090909090909e+01 1.13369372685470e+00 2.33120853936042e-01 -1.63233228331231e-01 + 2.15151515151515e+01 1.12208234404602e+00 2.43210638882764e-01 -1.67762290542514e-01 + 2.21212121212121e+01 1.11102321657310e+00 2.53449731640723e-01 -1.72148946259134e-01 + 2.27272727272727e+01 1.10217259984565e+00 2.64285902016898e-01 -1.75966397581727e-01 + 2.33333333333333e+01 1.09332197700060e+00 2.75122072393073e-01 -1.79783792100215e-01 + 2.39393939393939e+01 1.08447134760827e+00 2.85958242769248e-01 -1.83601131046924e-01 + 2.45454545454545e+01 1.07734542237668e+00 2.97418594720445e-01 -1.87014968760816e-01 + 2.51515151515151e+01 1.07041107379095e+00 3.08948298688103e-01 -1.90383934992330e-01 + 2.57575757575758e+01 1.06347666710874e+00 3.20478002655761e-01 -1.93752856661258e-01 + 2.63636363636364e+01 1.05732236007864e+00 3.32390146085381e-01 -1.96948677634826e-01 + 2.69696969696970e+01 1.05168813342601e+00 3.44557288776848e-01 -2.00029068561270e-01 + 2.75757575757576e+01 1.04605378759977e+00 3.56724431468315e-01 -2.03109418400795e-01 + 2.81818181818182e+01 1.04067256013258e+00 3.69064683245998e-01 -2.06133132039065e-01 + 2.87878787878788e+01 1.03588202408929e+00 3.81808821576232e-01 -2.09024762045095e-01 + 2.93939393939394e+01 1.03109132721680e+00 3.94552959906465e-01 -2.11916350679321e-01 + 3.00000000000000e+01 1.02630047109565e+00 4.07297098236698e-01 -2.14807896915288e-01 + 3.30000000000000e+01 1.00553169528085e+00 4.73784534746913e-01 -2.28328930073073e-01 + 3.60000000000000e+01 9.85527854289020e-01 5.43015121244335e-01 -2.41378773612232e-01 + 3.90000000000000e+01 9.64256669240620e-01 6.14826511890619e-01 -2.53786845019076e-01 + 4.20000000000000e+01 9.39401732187148e-01 6.88232875834521e-01 -2.65971257965397e-01 + 4.50000000000000e+01 9.13241579977801e-01 7.62038630661659e-01 -2.78098314901201e-01 + 4.80000000000000e+01 8.79965823978363e-01 8.35676496789876e-01 -2.89925721686919e-01 + 5.10000000000000e+01 8.42513311869095e-01 9.07721848420653e-01 -3.01541565653910e-01 + 5.40000000000000e+01 7.96707214786344e-01 9.76582068677410e-01 -3.12725809880497e-01 + 5.70000000000000e+01 7.50901373321919e-01 1.04544176288274e+00 -3.23914976497956e-01 + 6.00000000000000e+01 7.05095590005431e-01 1.11430119406435e+00 -3.35108765012171e-01 + 6.30000000000000e+01 6.43426651348128e-01 1.16980000216993e+00 -3.44954018840384e-01 + 6.60000000000000e+01 5.81757536770671e-01 1.22529869575376e+00 -3.54804262733281e-01 + 6.90000000000000e+01 5.20088366620145e-01 1.28079738933759e+00 -3.64659118816904e-01 + 7.20000000000000e+01 4.50895765482209e-01 1.32277538940729e+00 -3.73183031740474e-01 + 7.50000000000000e+01 3.77941618474775e-01 1.35799331950653e+00 -3.81044639026107e-01 + 7.80000000000000e+01 3.04986617856015e-01 1.39321165317520e+00 -3.88911546743740e-01 + 8.10000000000000e+01 2.30715110532685e-01 1.42017686538628e+00 -3.95889296470916e-01 + 8.40000000000000e+01 1.53810733540745e-01 1.43063640437435e+00 -4.01084668321152e-01 + 8.70000000000000e+01 7.69053727306556e-02 1.44109602326751e+00 -4.06287962899012e-01 + 9.00000000000000e+01 -3.35991459889849e-07 1.45155555155023e+00 -4.11502017960891e-01 + 9.30000000000000e+01 -5.38337094334587e-02 1.44109601256217e+00 -4.13894658825039e-01 + 9.60000000000000e+01 -1.07667090348450e-01 1.43063643362188e+00 -4.16297269931508e-01 + 9.90000000000000e+01 -1.61500486209697e-01 1.42017677477570e+00 -4.18699936551505e-01 + 1.02000000000000e+02 -2.13490336137694e-01 1.39321148260576e+00 -4.17907661987286e-01 + 1.05000000000000e+02 -2.64558413703211e-01 1.35799355250651e+00 -4.15518040952612e-01 + 1.08000000000000e+02 -3.15627063533621e-01 1.32277521883958e+00 -4.13127922002446e-01 + 1.11000000000000e+02 -3.64062034832866e-01 1.28079690855731e+00 -4.09526520529020e-01 + 1.14000000000000e+02 -4.07229711397332e-01 1.22529885093775e+00 -4.03502582615359e-01 + 1.17000000000000e+02 -4.50397682635010e-01 1.16980036934638e+00 -3.97478465589571e-01 + 1.20000000000000e+02 -4.93565771807662e-01 1.11430164963474e+00 -3.91454376227199e-01 + 1.23000000000000e+02 -5.25630147618883e-01 1.04544221845313e+00 -3.83664668897240e-01 + 1.26000000000000e+02 -5.57694365436177e-01 9.76582524253020e-01 -3.75875218145706e-01 + 1.29000000000000e+02 -5.89758365423620e-01 9.07722303996263e-01 -3.68085790436742e-01 + 1.32000000000000e+02 -6.14315531955485e-01 8.35620937733996e-01 -3.60884266412265e-01 + 1.35000000000000e+02 -6.35119149734577e-01 7.61899002314359e-01 -3.53977324090480e-01 + 1.38000000000000e+02 -6.55921766878216e-01 6.88177317217558e-01 -3.47071391893562e-01 + 1.41000000000000e+02 -6.74652275680612e-01 6.15856290391737e-01 -3.41901008734909e-01 + 1.44000000000000e+02 -6.89238523528509e-01 5.46336591473471e-01 -3.40201601680046e-01 + 1.47000000000000e+02 -7.03823896258865e-01 4.76817027337738e-01 -3.38504257224453e-01 + 1.50000000000000e+02 -7.18408694438638e-01 4.07297530590864e-01 -3.36808891109050e-01 + 1.53000000000000e+02 -7.44620920477827e-01 3.50504182292723e-01 -3.52050708459141e-01 + 1.56000000000000e+02 -7.70832295867696e-01 2.93710882428943e-01 -3.67292718466256e-01 + 1.59000000000000e+02 -7.97042839057236e-01 2.36917620123939e-01 -3.82534823044658e-01 + 1.62000000000000e+02 -7.25443285329967e-01 1.96119535360957e-01 -4.10092686634208e-01 + 1.65000000000000e+02 -6.04863200846212e-01 1.63319174643805e-01 -4.43808469577462e-01 + 1.68000000000000e+02 -4.87346219362824e-01 1.30518595329125e-01 -4.77523282896420e-01 + 1.71000000000000e+02 -3.66753120134991e-01 9.77955724163158e-02 -4.50000513056908e-01 + 1.74000000000000e+02 -2.44501896830564e-01 6.52276659281221e-02 -2.99999717902353e-01 + 1.77000000000000e+02 -1.20729578177091e-01 5.38728696135554e-02 -1.48151538376506e-01 + 1.80000000000000e+02 0.00000000000000e+00 5.31472191671717e-02 0.00000000000000e+00 diff --git a/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_10.dat b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_10.dat new file mode 100644 index 00000000..3d0828bf --- /dev/null +++ b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_10.dat @@ -0,0 +1,254 @@ +! ------------ AirfoilInfo v1.01.x Input File ---------------------------------- +! AeroElasticSE FAST driver +! line +! line +! ------------------------------------------------------------------------------ +DEFAULT InterpOrd ! Interpolation order to use for quasi-steady table lookup {1=linear; 3=cubic spline; "default"} [default=3] +1 NonDimArea ! The non-dimensional area of the airfoil (area/chord^2) (set to 1.0 if unsure or unneeded) +@"NREL-2p8-127_AF10_Coords.txt" NumCoords ! The number of coordinates in the airfoil shape file. Set to zero if coordinates not included. +AF10_BL.txt BL_file ! The file name including the boundary layer characteristics of the profile. Ignored if the aeroacoustic module is not called. +1 NumTabs ! Number of airfoil tables in this file. Each table must have lines for Re and Ctrl. +! ------------------------------------------------------------------------------ +! data for table 1 +! ------------------------------------------------------------------------------ +6.000000 Re ! Reynolds number in millions +0 Ctrl ! Control setting (must be 0 for current AirfoilInfo) +True InclUAdata ! Is unsteady aerodynamics data included in this table? If TRUE, then include 30 UA coefficients below this line +!........................................ +-2.064146 alpha0 ! 0-lift angle of attack, depends on airfoil. +11.141003 alpha1 ! Angle of attack at f=0.7, (approximately the stall angle) for AOA>alpha0. (deg) +-8.373634 alpha2 ! Angle of attack at f=0.7, (approximately the stall angle) for AOA1] +0.000000 S2 ! Constant in the f curve best-fit for AOA> alpha1; by definition it depends on the airfoil. [ignored if UAMod<>1] +0.000000 S3 ! Constant in the f curve best-fit for alpha2<=AOA< alpha0; by definition it depends on the airfoil. [ignored if UAMod<>1] +0.000000 S4 ! Constant in the f curve best-fit for AOA< alpha2; by definition it depends on the airfoil. [ignored if UAMod<>1] +1.372191 Cn1 ! Critical value of C0n at leading edge separation. It should be extracted from airfoil data at a given Mach and Reynolds number. It can be calculated from the static value of Cn at either the break in the pitching moment or the loss of chord force at the onset of stall. It is close to the condition of maximum lift of the airfoil at low Mach numbers. +-0.848243 Cn2 ! As Cn1 for negative AOAs. +Default St_sh ! Strouhal's shedding frequency constant. [default = 0.19] +0.010759 Cd0 ! 2D drag coefficient value at 0-lift. +-0.057548 Cm0 ! 2D pitching moment coefficient about 1/4-chord location, at 0-lift, positive if nose up. [If the aerodynamics coefficients table does not include a column for Cm, this needs to be set to 0.0] +0.000000 k0 ! Constant in the \hat(x)_cp curve best-fit; = (\hat(x)_AC-0.25). [ignored if UAMod<>1] +0.000000 k1 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k2 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k3 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k1_hat ! Constant in the expression of Cc due to leading edge vortex effects. [ignored if UAMod<>1] +Default x_cp_bar ! Constant in the expression of \hat(x)_cp^v. [ignored if UAMod<>1, default = 0.2] +Default UACutout ! Angle of attack above which unsteady aerodynamics are disabled (deg). [Specifying the string "Default" sets UACutout to 45 degrees] +Default filtCutOff ! Cut-off frequency (-3 dB corner frequency) for low-pass filtering the AoA input to UA, as well as the 1st and 2nd derivatives (Hz) [default = 20] +!........................................ +! Table of aerodynamics coefficients +200 NumAlf ! Number of data lines in the following table +! Alpha Cl Cd Cm +! (deg) (-) (-) (-) +-1.80000000000000e+02 0.00000000000000e+00 5.30837886627506e-02 0.00000000000000e+00 +-1.77000000000000e+02 1.24966191469559e-01 5.30837886627506e-02 1.18576829157013e-01 +-1.74000000000000e+02 2.52998633091314e-01 6.37003001697374e-02 2.39999774321882e-01 +-1.71000000000000e+02 3.79498286143344e-01 9.55501832215890e-02 3.60000410445527e-01 +-1.68000000000000e+02 4.98757573511548e-01 1.28321372265423e-01 3.22914823147173e-01 +-1.65000000000000e+02 6.15220538714466e-01 1.61553203552249e-01 2.07287957565546e-01 +-1.62000000000000e+02 7.27077094368088e-01 1.94785456665805e-01 9.16599143637722e-02 +-1.59000000000000e+02 7.93230980672808e-01 2.35846387240917e-01 1.84100886242669e-02 +-1.56000000000000e+02 7.68234137241237e-01 2.92564407901613e-01 3.03932586734567e-02 +-1.53000000000000e+02 7.43356372402597e-01 3.49282461855920e-01 4.28162358403718e-02 +-1.50000000000000e+02 7.18478522993120e-01 4.06000562593489e-01 5.56156944862064e-02 +-1.47000000000000e+02 7.03955906925430e-01 4.75651465566945e-01 6.92790833714106e-02 +-1.44000000000000e+02 6.89433035390160e-01 5.45302448258410e-01 8.29503219976363e-02 +-1.41000000000000e+02 6.74909652901486e-01 6.14953590391589e-01 9.66309029164283e-02 +-1.38000000000000e+02 6.56219474668182e-01 6.87418368921680e-01 1.10881678895009e-01 +-1.35000000000000e+02 6.35445907015363e-01 7.61289959942459e-01 1.25418499888186e-01 +-1.32000000000000e+02 6.14671501318397e-01 8.35161838486049e-01 1.39961030153749e-01 +-1.29000000000000e+02 5.90134200485388e-01 9.07415349226177e-01 1.54621277427466e-01 +-1.26000000000000e+02 5.58071091549210e-01 9.76432116678355e-01 1.69509055919750e-01 +-1.23000000000000e+02 5.26007827556163e-01 1.04544835687794e+00 1.84402154814945e-01 +-1.20000000000000e+02 4.93944486037582e-01 1.11446433346109e+00 1.99301684126228e-01 +-1.17000000000000e+02 4.50754244383126e-01 1.17011434599327e+00 2.13130402729061e-01 +-1.14000000000000e+02 4.07564132273452e-01 1.22576411981700e+00 2.26966296053101e-01 +-1.11000000000000e+02 3.64374322762834e-01 1.28141346851316e+00 2.40810540320626e-01 +-1.08000000000000e+02 3.15905431030774e-01 1.32353352870914e+00 2.52837246360334e-01 +-1.05000000000000e+02 2.64796957994024e-01 1.35888884163568e+00 2.63961625640692e-01 +-1.02000000000000e+02 2.13689029593013e-01 1.39424374942488e+00 2.75099894116298e-01 +-9.90000000000000e+01 1.61655412340594e-01 1.42133844008909e+00 2.84836104947235e-01 +-9.60000000000000e+01 1.07770377288908e-01 1.43191233870989e+00 2.91753073560900e-01 +-9.30000000000000e+01 5.38853538885643e-02 1.44248615655205e+00 2.98698830338381e-01 +-9.00000000000000e+01 3.36313787357514e-07 1.45305993400564e+00 3.05684965975821e-01 +-8.70000000000000e+01 -5.38852987372259e-02 1.44248616737432e+00 3.09060154363404e-01 +-8.40000000000000e+01 -1.07770527963470e-01 1.43191230914291e+00 3.12686281197342e-01 +-8.10000000000000e+01 -1.61654945541942e-01 1.42133853168932e+00 3.16767616953733e-01 +-7.80000000000000e+01 -2.13688782064248e-01 1.39424392065773e+00 3.16540498625861e-01 +-7.50000000000000e+01 -2.64797296121353e-01 1.35888860772946e+00 3.14266811229411e-01 +-7.20000000000000e+01 -3.15905183504718e-01 1.32353369994026e+00 3.11992145479124e-01 +-6.90000000000000e+01 -3.64373948609042e-01 1.28141395060407e+00 3.08496020987835e-01 +-6.60000000000000e+01 -4.07564253041044e-01 1.22576396420997e+00 3.02557290547327e-01 +-6.30000000000000e+01 -4.50754530127646e-01 1.17011397781587e+00 2.96617404810894e-01 +-6.00000000000000e+01 -4.93944698166970e-01 1.11446387685501e+00 2.90676423054807e-01 +-5.70000000000000e+01 -5.26008039685552e-01 1.04544790027186e+00 2.82948402317780e-01 +-5.40000000000000e+01 -5.58071303677059e-01 9.76431660067037e-01 2.75218817710457e-01 +-5.10000000000000e+01 -5.90134412613238e-01 9.07414892614858e-01 2.67487195859118e-01 +-4.80000000000000e+01 -6.16349723026200e-01 8.35214742285566e-01 2.59915443758204e-01 +-4.50000000000000e+01 -6.39641228159956e-01 7.61422951679187e-01 2.52421684677788e-01 +-4.20000000000000e+01 -6.57897683242975e-01 6.87471272303016e-01 2.46204422934917e-01 +-3.90000000000000e+01 -6.75245094925222e-01 6.13911269891018e-01 2.40506244340753e-01 +-3.60000000000000e+01 -6.90083088589439e-01 5.41941245231535e-01 2.36695331229210e-01 +-3.30000000000000e+01 -7.04017120189319e-01 4.72583293422338e-01 2.35442916975004e-01 +-3.00000000000000e+01 -7.18478627259844e-01 4.06000129199683e-01 2.37016869904415e-01 +-2.93939393939394e+01 -7.21798350573784e-01 3.93221418404654e-01 2.38091117333048e-01 +-2.87878787878788e+01 -7.25118073887724e-01 3.80442707609625e-01 2.39165364761681e-01 +-2.81818181818182e+01 -7.28437797201663e-01 3.67663996814596e-01 2.40239612190314e-01 +-2.75757575757576e+01 -7.32172588884317e-01 3.55293602246098e-01 2.41847562956378e-01 +-2.69696969696970e+01 -7.36085282271228e-01 3.43098215358386e-01 2.43684263346490e-01 +-2.63636363636364e+01 -7.39997975658139e-01 3.30902828470674e-01 2.45520963736601e-01 +-2.57575757575758e+01 -7.44276884748962e-01 3.18965212168995e-01 2.47753414207092e-01 +-2.51515151515151e+01 -7.49105032044442e-01 3.07414191669665e-01 2.50579397563581e-01 +-2.45454545454545e+01 -7.53933179339923e-01 2.95863171170336e-01 2.53405380920070e-01 +-2.39393939393939e+01 -7.58896243502194e-01 2.84382247917907e-01 2.56362693669404e-01 +-2.33333333333333e+01 -7.65073585586137e-01 2.73532213458751e-01 2.60501996380347e-01 +-2.27272727272727e+01 -7.71250927670079e-01 2.62682178999596e-01 2.64779889466675e-01 +-2.21212121212121e+01 -7.77428269754022e-01 2.51832144540440e-01 2.68945623496597e-01 +-2.15151515151515e+01 -7.90262923140693e-01 2.41893541513143e-01 2.73249028596959e-01 +-2.09090909090909e+01 -8.05906043706644e-01 2.32182854971129e-01 2.77270518618669e-01 +-2.03030303030303e+01 -8.19489198628311e-01 2.22472168429115e-01 2.81192694187527e-01 +-1.96969696969697e+01 -8.24678039235549e-01 2.13080793622121e-01 2.75632215545996e-01 +-1.90909090909091e+01 -8.21619989791241e-01 2.04008712486556e-01 2.60613787847909e-01 +-1.84848484848485e+01 -8.18197356256183e-01 1.95010678250887e-01 2.45586809616841e-01 +-1.78787878787879e+01 -8.14569480885818e-01 1.86007505483073e-01 2.30648571774812e-01 +-1.72727272727273e+01 -8.10814834138077e-01 1.76823863436936e-01 2.15753896541975e-01 +-1.66666666666667e+01 -8.06976123403415e-01 1.68593035533169e-01 2.00859509073193e-01 +-1.60606060606061e+01 -8.03078897629092e-01 1.60454418431078e-01 1.85965357045289e-01 +-1.54545454545455e+01 -7.97000707157957e-01 1.51710915395437e-01 1.71396869835783e-01 +-1.48484848484848e+01 -7.89576615706775e-01 1.42625264033402e-01 1.57006741726859e-01 +-1.42424242424242e+01 -7.78781317063958e-01 1.32791872599405e-01 1.43201565946783e-01 +-1.36363636363636e+01 -7.67357420824222e-01 1.22849813294929e-01 1.29490112449071e-01 +-1.30303030303030e+01 -7.55422617396779e-01 1.12823830974163e-01 1.15644996580170e-01 +-1.24242424242424e+01 -7.42969206287619e-01 1.02890282642851e-01 1.01449124172212e-01 +-1.18181818181818e+01 -7.30244644590558e-01 9.31176217950954e-02 8.72464359531469e-02 +-1.12121212121212e+01 -7.17231543580288e-01 8.37383245063512e-02 7.30648930269649e-02 +-1.06060606060606e+01 -7.03577356362280e-01 7.45798495908964e-02 5.90622202437287e-02 +-1.00000000000000e+01 -6.89105145844174e-01 6.55059849764586e-02 4.51630398367081e-02 +-9.39393939393939e+00 -6.76227800071737e-01 5.54692165142735e-02 3.11059783824235e-02 +-8.78787878787879e+00 -6.64141630347962e-01 4.52369131161758e-02 1.71623095710831e-02 +-8.18181818181818e+00 -6.54216850502614e-01 3.55800439872753e-02 3.42154297533580e-03 +-7.57575757575758e+00 -6.14625042059806e-01 2.91666756670593e-02 -3.86341370860449e-03 +-6.96969696969697e+00 -5.61841937827523e-01 2.43864881766210e-02 -8.43665697005592e-03 +-6.36363636363636e+00 -4.99189572128014e-01 2.06688208542298e-02 -1.37959149818896e-02 +-5.75757575757576e+00 -4.34608760745885e-01 1.76932591752901e-02 -1.92729400057168e-02 +-5.15151515151515e+00 -3.67348413458166e-01 1.56052490200204e-02 -2.57288663338659e-02 +-4.54545454545454e+00 -2.97220789753124e-01 1.38965283846311e-02 -3.24773660126783e-02 +-3.93939393939394e+00 -2.25827092845188e-01 1.24332806711584e-02 -3.91885815676604e-02 +-3.33333333333333e+00 -1.54050456378233e-01 1.19149897769548e-02 -4.56999911417254e-02 +-2.72727272727273e+00 -8.12318984160244e-02 1.13706359706548e-02 -5.16384940099625e-02 +-2.12121212121212e+00 -7.14979346296234e-03 1.07859435280497e-02 -5.70801147069148e-02 +-1.51515151515152e+00 6.87826749054011e-02 1.05033451229781e-02 -6.20466375298444e-02 +-9.09090909090912e-01 1.45369872154627e-01 1.03139004235661e-02 -6.68516603553039e-02 +-3.03030303030302e-01 2.23028758160340e-01 1.02094317053058e-02 -7.16176330178895e-02 + 3.03030303030302e-01 3.01237277028695e-01 1.01564455703337e-02 -7.60536458286783e-02 + 9.09090909090912e-01 3.80006385780218e-01 1.01544863426098e-02 -8.01685273418174e-02 + 1.51515151515152e+00 4.59246642973497e-01 1.03195069670379e-02 -8.42292432054636e-02 + 2.12121212121212e+00 5.38436193741909e-01 1.05158173919170e-02 -8.80305585640893e-02 + 2.72727272727273e+00 6.17086435268518e-01 1.07234607719624e-02 -9.09221588982618e-02 + 3.33333333333333e+00 6.94766649922142e-01 1.09892374201398e-02 -9.34851438113357e-02 + 3.93939393939394e+00 7.71665263445708e-01 1.12674755215391e-02 -9.57801882660128e-02 + 4.54545454545455e+00 8.46424118402375e-01 1.16353662750350e-02 -9.80494154414620e-02 + 5.15151515151515e+00 9.20198652009909e-01 1.20213692284540e-02 -1.00166544091476e-01 + 5.75757575757576e+00 9.91711074228843e-01 1.24325530524450e-02 -1.01849307770008e-01 + 6.36363636363637e+00 1.06002251469050e+00 1.29373530659327e-02 -1.03182589271796e-01 + 6.96969696969697e+00 1.12620049862159e+00 1.35051858034989e-02 -1.04281097204592e-01 + 7.57575757575757e+00 1.18623076703795e+00 1.42446030038888e-02 -1.05323489221343e-01 + 8.18181818181818e+00 1.24304860221996e+00 1.50702587438949e-02 -1.06330821016929e-01 + 8.78787878787879e+00 1.29339454484370e+00 1.60680959350975e-02 -1.07320656167730e-01 + 9.39393939393939e+00 1.33640612125946e+00 1.81467491655883e-02 -1.08107944391156e-01 + 1.00000000000000e+01 1.37469506451432e+00 2.09438769808961e-02 -1.08769953707875e-01 + 1.06060606060606e+01 1.39128542708790e+00 2.53973640660572e-02 -1.08704427997839e-01 + 1.12121212121212e+01 1.39247645190556e+00 3.08345002992362e-02 -1.08511132324392e-01 + 1.18181818181818e+01 1.36506866603177e+00 3.75119498467862e-02 -1.07969033181396e-01 + 1.24242424242424e+01 1.33988550587683e+00 4.76821530474488e-02 -1.09070781012852e-01 + 1.30303030303030e+01 1.28517385394240e+00 5.94392540313143e-02 -1.10747213245403e-01 + 1.36363636363636e+01 1.25643020037597e+00 7.18386529645335e-02 -1.10309370469218e-01 + 1.42424242424242e+01 1.22941101634947e+00 8.49147013682724e-02 -1.10076808850556e-01 + 1.48484848484848e+01 1.20587360276360e+00 9.89301897374668e-02 -1.10132396182924e-01 + 1.54545454545455e+01 1.18936767768177e+00 1.13924838258266e-01 -1.13810701314704e-01 + 1.60606060606061e+01 1.17565898671524e+00 1.29176297116898e-01 -1.19071521356745e-01 + 1.66666666666667e+01 1.16603643374085e+00 1.43801932752626e-01 -1.26420182833845e-01 + 1.72727272727273e+01 1.15901294982273e+00 1.58412873301332e-01 -1.33298298163097e-01 + 1.78787878787879e+01 1.15516613881923e+00 1.73005853001785e-01 -1.39601295567204e-01 + 1.84848484848485e+01 1.16035329239803e+00 1.87605989072833e-01 -1.43318174504004e-01 + 1.90909090909091e+01 1.16482121671689e+00 2.01471765042406e-01 -1.46723090792030e-01 + 1.96969696969697e+01 1.15241186617039e+00 2.11164662608912e-01 -1.52023933649729e-01 + 2.03030303030303e+01 1.14108152143087e+00 2.21109741610071e-01 -1.56986307485845e-01 + 2.09090909090909e+01 1.13083024354155e+00 2.31307016312692e-01 -1.61635219687799e-01 + 2.15151515151515e+01 1.12057896565223e+00 2.41504291015314e-01 -1.66292754579922e-01 + 2.21212121212121e+01 1.11061305902249e+00 2.51832144540440e-01 -1.70802437318188e-01 + 2.27272727272727e+01 1.10178834380504e+00 2.62682178999596e-01 -1.74726995984381e-01 + 2.33333333333333e+01 1.09296362858759e+00 2.73532213458751e-01 -1.78657586333139e-01 + 2.39393939393939e+01 1.08413891337014e+00 2.84382247917907e-01 -1.82623234550793e-01 + 2.45454545454545e+01 1.07704877435898e+00 2.95863171170336e-01 -1.86155882534370e-01 + 2.51515151515151e+01 1.07015136189154e+00 3.07414191669665e-01 -1.89640420415756e-01 + 2.57575757575758e+01 1.06325394942410e+00 3.18965212168995e-01 -1.93124958297141e-01 + 2.63636363636364e+01 1.05714092098968e+00 3.30902828470674e-01 -1.96422469773296e-01 + 2.69696969696970e+01 1.05155089650575e+00 3.43098215358386e-01 -1.99595277603454e-01 + 2.75757575757576e+01 1.04596087202182e+00 3.55293602246098e-01 -2.02768085433612e-01 + 2.81818181818182e+01 1.04062530585900e+00 3.67663996814596e-01 -2.05879229073642e-01 + 2.87878787878788e+01 1.03588342484769e+00 3.80442707609625e-01 -2.08846501945758e-01 + 2.93939393939394e+01 1.03114154383638e+00 3.93221418404654e-01 -2.11813774817874e-01 + 3.00000000000000e+01 1.02639966282507e+00 4.06000129199683e-01 -2.14781047689990e-01 + 3.30000000000000e+01 1.00573804168069e+00 4.72583293422338e-01 -2.28629026765098e-01 + 3.60000000000000e+01 9.85833707743003e-01 5.41941245231535e-01 -2.41944387146083e-01 + 3.90000000000000e+01 9.64635684439964e-01 6.13911269891018e-01 -2.55359517097689e-01 + 4.20000000000000e+01 9.39853820984217e-01 6.87471272303016e-01 -2.68402760096020e-01 + 4.50000000000000e+01 9.13773877837909e-01 7.61422951679187e-01 -2.81321973111748e-01 + 4.80000000000000e+01 8.80499938641377e-01 8.35214742285566e-01 -2.93829895857158e-01 + 5.10000000000000e+01 8.43049140618493e-01 9.07414892614859e-01 -3.06092438249886e-01 + 5.40000000000000e+01 7.97244356422135e-01 9.76431660067036e-01 -3.17878305263492e-01 + 5.70000000000000e+01 7.51439922147286e-01 1.04544790027186e+00 -3.29653788801724e-01 + 6.00000000000000e+01 7.05635662831859e-01 1.11446387685501e+00 -3.41419875328892e-01 + 6.30000000000000e+01 6.43935405201049e-01 1.17011397781587e+00 -3.51824168446815e-01 + 6.60000000000000e+01 5.82235011316305e-01 1.22576396420997e+00 -3.62218653318893e-01 + 6.90000000000000e+01 5.20534617431561e-01 1.28141395060407e+00 -3.72603978485147e-01 + 7.20000000000000e+01 4.51293480954431e-01 1.32353369994026e+00 -3.81654848148536e-01 + 7.50000000000000e+01 3.78282127550152e-01 1.35888860772946e+00 -3.90032025372884e-01 + 7.80000000000000e+01 3.05269896475863e-01 1.39424392065773e+00 -3.98398550132911e-01 + 8.10000000000000e+01 2.30935739780878e-01 1.42133853168932e+00 -4.05862264958857e-01 + 8.40000000000000e+01 1.53957823095881e-01 1.43191230914291e+00 -4.11528875629133e-01 + 8.70000000000000e+01 7.69789183415259e-02 1.44248616737432e+00 -4.17182529414559e-01 + 9.00000000000000e+01 -3.36313787592115e-07 1.45305993400564e+00 -4.22823883213375e-01 + 9.30000000000000e+01 -5.38853538885643e-02 1.44248615655205e+00 -4.25531830444160e-01 + 9.60000000000000e+01 -1.07770377288908e-01 1.43191233870989e+00 -4.28239883474790e-01 + 9.90000000000000e+01 -1.61655412340595e-01 1.42133844008909e+00 -4.30948043344561e-01 + 1.02000000000000e+02 -2.13689029593013e-01 1.39424374942488e+00 -4.30426032722678e-01 + 1.05000000000000e+02 -2.64796957994024e-01 1.35888884163568e+00 -4.28288858720630e-01 + 1.08000000000000e+02 -3.15905431030774e-01 1.32353352870914e+00 -4.26150923676660e-01 + 1.11000000000000e+02 -3.64374322762835e-01 1.28141346851316e+00 -4.22781294573843e-01 + 1.14000000000000e+02 -4.07564132273452e-01 1.22576411981700e+00 -4.16948201170771e-01 + 1.17000000000000e+02 -4.50754244383126e-01 1.17011434599327e+00 -4.11114214652485e-01 + 1.20000000000000e+02 -4.93944486037582e-01 1.11446433346109e+00 -4.05279567496773e-01 + 1.23000000000000e+02 -5.26007827556164e-01 1.04544835687794e+00 -3.97635867656992e-01 + 1.26000000000000e+02 -5.58071091549210e-01 9.76432116678355e-01 -3.89990992242211e-01 + 1.29000000000000e+02 -5.90134200485389e-01 9.07415349226176e-01 -3.82344714919725e-01 + 1.32000000000000e+02 -6.14671501318397e-01 8.35161838486048e-01 -3.75290062239593e-01 + 1.35000000000000e+02 -6.35445907015363e-01 7.61289959942459e-01 -3.68529899569896e-01 + 1.38000000000000e+02 -6.56219474668182e-01 6.87418368921679e-01 -3.61767875968571e-01 + 1.41000000000000e+02 -6.74909652901486e-01 6.14953590391588e-01 -3.56786256817077e-01 + 1.44000000000000e+02 -6.89433035390160e-01 5.45302448258410e-01 -3.55365699643800e-01 + 1.47000000000000e+02 -7.03955906925430e-01 4.75651465566945e-01 -3.53940753692651e-01 + 1.50000000000000e+02 -7.18478522993120e-01 4.06000562593488e-01 -3.52511578047886e-01 + 1.53000000000000e+02 -7.42629245947763e-01 3.49402521602820e-01 -3.67942713897313e-01 + 1.56000000000000e+02 -7.66779899087500e-01 2.92804540889390e-01 -3.83374818114856e-01 + 1.59000000000000e+02 -7.91051572510474e-01 2.36206619897226e-01 -3.98807852435555e-01 + 1.62000000000000e+02 -7.19307409708115e-01 1.95606690636341e-01 -4.23162217489700e-01 + 1.65000000000000e+02 -5.99422550148399e-01 1.63005892539676e-01 -4.51976932817733e-01 + 1.68000000000000e+02 -4.72905933087606e-01 1.30404868023183e-01 -4.80790683446680e-01 + 1.71000000000000e+02 -3.52738917050312e-01 9.78037326537191e-02 -4.50000513056908e-01 + 1.74000000000000e+02 -2.35159145800089e-01 6.52023755731394e-02 -2.99999717902353e-01 + 1.77000000000000e+02 -1.16216409329782e-01 5.38259028959444e-02 -1.48221036446267e-01 + 1.80000000000000e+02 0.00000000000000e+00 5.30837886627506e-02 0.00000000000000e+00 diff --git a/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_11.dat b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_11.dat new file mode 100644 index 00000000..742ec4f5 --- /dev/null +++ b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_11.dat @@ -0,0 +1,254 @@ +! ------------ AirfoilInfo v1.01.x Input File ---------------------------------- +! AeroElasticSE FAST driver +! line +! line +! ------------------------------------------------------------------------------ +DEFAULT InterpOrd ! Interpolation order to use for quasi-steady table lookup {1=linear; 3=cubic spline; "default"} [default=3] +1 NonDimArea ! The non-dimensional area of the airfoil (area/chord^2) (set to 1.0 if unsure or unneeded) +@"NREL-2p8-127_AF11_Coords.txt" NumCoords ! The number of coordinates in the airfoil shape file. Set to zero if coordinates not included. +AF11_BL.txt BL_file ! The file name including the boundary layer characteristics of the profile. Ignored if the aeroacoustic module is not called. +1 NumTabs ! Number of airfoil tables in this file. Each table must have lines for Re and Ctrl. +! ------------------------------------------------------------------------------ +! data for table 1 +! ------------------------------------------------------------------------------ +6.000000 Re ! Reynolds number in millions +0 Ctrl ! Control setting (must be 0 for current AirfoilInfo) +True InclUAdata ! Is unsteady aerodynamics data included in this table? If TRUE, then include 30 UA coefficients below this line +!........................................ +-2.081115 alpha0 ! 0-lift angle of attack, depends on airfoil. +11.269045 alpha1 ! Angle of attack at f=0.7, (approximately the stall angle) for AOA>alpha0. (deg) +-8.662155 alpha2 ! Angle of attack at f=0.7, (approximately the stall angle) for AOA1] +0.000000 S2 ! Constant in the f curve best-fit for AOA> alpha1; by definition it depends on the airfoil. [ignored if UAMod<>1] +0.000000 S3 ! Constant in the f curve best-fit for alpha2<=AOA< alpha0; by definition it depends on the airfoil. [ignored if UAMod<>1] +0.000000 S4 ! Constant in the f curve best-fit for AOA< alpha2; by definition it depends on the airfoil. [ignored if UAMod<>1] +1.400649 Cn1 ! Critical value of C0n at leading edge separation. It should be extracted from airfoil data at a given Mach and Reynolds number. It can be calculated from the static value of Cn at either the break in the pitching moment or the loss of chord force at the onset of stall. It is close to the condition of maximum lift of the airfoil at low Mach numbers. +-0.915233 Cn2 ! As Cn1 for negative AOAs. +Default St_sh ! Strouhal's shedding frequency constant. [default = 0.19] +0.010727 Cd0 ! 2D drag coefficient value at 0-lift. +-0.065156 Cm0 ! 2D pitching moment coefficient about 1/4-chord location, at 0-lift, positive if nose up. [If the aerodynamics coefficients table does not include a column for Cm, this needs to be set to 0.0] +0.000000 k0 ! Constant in the \hat(x)_cp curve best-fit; = (\hat(x)_AC-0.25). [ignored if UAMod<>1] +0.000000 k1 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k2 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k3 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k1_hat ! Constant in the expression of Cc due to leading edge vortex effects. [ignored if UAMod<>1] +Default x_cp_bar ! Constant in the expression of \hat(x)_cp^v. [ignored if UAMod<>1, default = 0.2] +Default UACutout ! Angle of attack above which unsteady aerodynamics are disabled (deg). [Specifying the string "Default" sets UACutout to 45 degrees] +Default filtCutOff ! Cut-off frequency (-3 dB corner frequency) for low-pass filtering the AoA input to UA, as well as the 1st and 2nd derivatives (Hz) [default = 20] +!........................................ +! Table of aerodynamics coefficients +200 NumAlf ! Number of data lines in the following table +! Alpha Cl Cd Cm +! (deg) (-) (-) (-) +-1.80000000000000e+02 0.00000000000000e+00 5.17338093025581e-02 0.00000000000000e+00 +-1.77000000000000e+02 1.20610218452195e-01 5.17338093025581e-02 1.18763338610947e-01 +-1.74000000000000e+02 2.43846180796722e-01 6.20803661366883e-02 2.39999774321882e-01 +-1.71000000000000e+02 3.65769725958049e-01 9.31203763075915e-02 3.60000410445527e-01 +-1.68000000000000e+02 4.84069232089561e-01 1.24885380987671e-01 3.21035049116140e-01 +-1.65000000000000e+02 6.01637542467089e-01 1.57012874460584e-01 2.02588544427697e-01 +-1.62000000000000e+02 7.13153594297870e-01 1.89140896133777e-01 8.41409821795466e-02 +-1.59000000000000e+02 7.80068980000668e-01 2.29356923814875e-01 7.97341748695581e-03 +-1.56000000000000e+02 7.58681265140819e-01 2.85748689900454e-01 1.75916291927228e-02 +-1.53000000000000e+02 7.37716006162308e-01 3.42140486787254e-01 2.79764209288751e-02 +-1.50000000000000e+02 7.16750629236893e-01 3.98532330574024e-01 3.87597184159220e-02 +-1.47000000000000e+02 7.02430836152056e-01 4.68441880461646e-01 5.28948486721724e-02 +-1.44000000000000e+02 6.88110788374351e-01 5.38351550730586e-01 6.70401805724200e-02 +-1.41000000000000e+02 6.73790231192722e-01 6.08261461770758e-01 8.11976416970075e-02 +-1.38000000000000e+02 6.55253757939153e-01 6.81025000549314e-01 9.58313303466701e-02 +-1.35000000000000e+02 6.34609335202059e-01 7.55215347408169e-01 1.10704411230940e-01 +-1.32000000000000e+02 6.13964075900703e-01 8.29406104470313e-01 1.25585263221553e-01 +-1.29000000000000e+02 5.89541757042321e-01 9.01995435488593e-01 1.40592248603482e-01 +-1.26000000000000e+02 5.57565301171594e-01 9.71381906816171e-01 1.55841088781127e-01 +-1.23000000000000e+02 5.25588689582014e-01 1.04076784806681e+00 1.71097114222845e-01 +-1.20000000000000e+02 4.93612000135919e-01 1.11015352428889e+00 1.86361656418168e-01 +-1.17000000000000e+02 4.50478535342387e-01 1.16621180599633e+00 2.00629220653074e-01 +-1.14000000000000e+02 4.07345160141662e-01 1.22226984751125e+00 2.14906094089605e-01 +-1.11000000000000e+02 3.64212007755362e-01 1.27832746077970e+00 2.29193883251082e-01 +-1.08000000000000e+02 3.15783665079539e-01 1.32087403967776e+00 2.41716558401183e-01 +-1.05000000000000e+02 2.64707686941683e-01 1.35666499851025e+00 2.53364833576556e-01 +-1.02000000000000e+02 2.13632134040282e-01 1.39245554721333e+00 2.65031201575310e-01 +-9.90000000000000e+01 1.61623631750871e-01 1.41999044316543e+00 2.75316312995168e-01 +-9.60000000000000e+01 1.07749190274494e-01 1.43101367601985e+00 2.82819378442760e-01 +-9.30000000000000e+01 5.38747603685306e-02 1.44203682466298e+00 2.90359307559513e-01 +-9.00000000000000e+01 3.36247670192969e-07 1.45305993120123e+00 2.97951186065388e-01 +-8.70000000000000e+01 -5.38747052280345e-02 1.44203683594514e+00 3.01753424548436e-01 +-8.40000000000000e+01 -1.07749340919434e-01 1.43101364519643e+00 3.05884772088962e-01 +-8.10000000000000e+01 -1.61623165043989e-01 1.41999053865818e+00 3.10613470732064e-01 +-7.80000000000000e+01 -2.13631886668320e-01 1.39245572055610e+00 3.10674655777832e-01 +-7.50000000000000e+01 -2.64708024854679e-01 1.35666476172186e+00 3.08542976324719e-01 +-7.20000000000000e+01 -3.15783417710861e-01 1.32087421301878e+00 3.06409302975954e-01 +-6.90000000000000e+01 -3.64211634092392e-01 1.27832794640741e+00 3.03044729448568e-01 +-6.60000000000000e+01 -4.07345280750829e-01 1.22226969076263e+00 2.97219713108405e-01 +-6.30000000000000e+01 -4.50478820711274e-01 1.16621143511785e+00 2.91391620398543e-01 +-6.00000000000000e+01 -4.93612211692021e-01 1.11015306523689e+00 2.85560191488404e-01 +-5.70000000000000e+01 -5.25588901138117e-01 1.04076738901481e+00 2.77925669828566e-01 +-5.40000000000000e+01 -5.57565512726151e-01 9.71381447758911e-01 2.70286195661910e-01 +-5.10000000000000e+01 -5.89541968596878e-01 9.01994976431333e-01 2.62640680641497e-01 +-4.80000000000000e+01 -6.15651105875399e-01 8.29449803698678e-01 2.55153878770895e-01 +-4.50000000000000e+01 -6.38826678153933e-01 7.55325331028288e-01 2.47739559108878e-01 +-4.20000000000000e+01 -6.56940774711891e-01 6.81068699431397e-01 2.41608950158798e-01 +-3.90000000000000e+01 -6.74138230588866e-01 6.07210570957826e-01 2.36033756265024e-01 +-3.60000000000000e+01 -6.88800358432074e-01 5.34964795566947e-01 2.32526368115935e-01 +-3.30000000000000e+01 -7.02527481598747e-01 4.65352126226771e-01 2.31660096996564e-01 +-3.00000000000000e+01 -7.16750731841146e-01 3.98531895640176e-01 2.33717011176468e-01 +-2.93939393939394e+01 -7.20014368241707e-01 3.85709000620782e-01 2.34916176725143e-01 +-2.87878787878788e+01 -7.23278004642269e-01 3.72886105601387e-01 2.36115342273819e-01 +-2.81818181818182e+01 -7.26541641042830e-01 3.60063210581993e-01 2.37314507822494e-01 +-2.75757575757576e+01 -7.30215084645349e-01 3.47650566598554e-01 2.39067661935682e-01 +-2.69696969696970e+01 -7.34064174972939e-01 3.35413759571076e-01 2.41058260087479e-01 +-2.63636363636364e+01 -7.37913265300529e-01 3.23176952543597e-01 2.43048858239275e-01 +-2.57575757575758e+01 -7.42124844608794e-01 3.11199070884588e-01 2.45450980247116e-01 +-2.51515151515151e+01 -7.46880072905424e-01 2.99609516932444e-01 2.48470292128175e-01 +-2.45454545454545e+01 -7.51635301202054e-01 2.88019962980301e-01 2.51489604009234e-01 +-2.39393939393939e+01 -7.56524250108274e-01 2.76500794819509e-01 2.54645697570981e-01 +-2.33333333333333e+01 -7.62616710389763e-01 2.65615112407906e-01 2.59032852740507e-01 +-2.27272727272727e+01 -7.68709170671251e-01 2.54729429996303e-01 2.63911099891641e-01 +-2.21212121212121e+01 -7.74801630952739e-01 2.43843747584701e-01 2.68391913865235e-01 +-2.15151515151515e+01 -7.93896255075763e-01 2.34765567487007e-01 2.69219982182975e-01 +-2.09090909090909e+01 -8.19588776751072e-01 2.26139379234369e-01 2.68013679183985e-01 +-2.03030303030303e+01 -8.41755850773015e-01 2.17513190981731e-01 2.66455457580854e-01 +-1.96969696969697e+01 -8.57132969513166e-01 2.09138320990721e-01 2.57323288186467e-01 +-1.90909090909091e+01 -8.65913538616401e-01 2.01014755044168e-01 2.40703240782996e-01 +-1.84848484848485e+01 -8.74215029540216e-01 1.93152415327005e-01 2.24051125011634e-01 +-1.78787878787879e+01 -8.82246941494251e-01 1.85271935431753e-01 2.07713877216966e-01 +-1.72727272727273e+01 -8.90112513417619e-01 1.76753055824415e-01 1.91533915208804e-01 +-1.66666666666667e+01 -8.97867665288278e-01 1.69666716562767e-01 1.75354108708192e-01 +-1.60606060606061e+01 -9.05545956258092e-01 1.62769575158031e-01 1.59174429439710e-01 +-1.54545454545455e+01 -9.05500228357417e-01 1.54709519958352e-01 1.44263287105186e-01 +-1.48484848484848e+01 -9.00650490354814e-01 1.45972869299812e-01 1.30048437843628e-01 +-1.42424242424242e+01 -8.83881928212747e-01 1.35695161200991e-01 1.18061058367204e-01 +-1.36363636363636e+01 -8.65135255067798e-01 1.25196579166224e-01 1.06372832901923e-01 +-1.30303030303030e+01 -8.44949235869776e-01 1.14536353092698e-01 9.41922629526705e-02 +-1.24242424242424e+01 -8.23438097507769e-01 1.04071539255474e-01 8.07476005612591e-02 +-1.18181818181818e+01 -8.01578346336287e-01 9.39351009261381e-02 6.72989309058954e-02 +-1.12121212121212e+01 -7.79436133521223e-01 8.45784112226453e-02 5.39664027575017e-02 +-1.06060606060606e+01 -7.56125420814654e-01 7.56686775243057e-02 4.13015037835521e-02 +-1.00000000000000e+01 -7.31404178229205e-01 6.69542054267392e-02 2.90154450614047e-02 +-9.39393939393939e+00 -7.10908164656284e-01 5.62659422161747e-02 1.61336287291465e-02 +-8.78787878787879e+00 -6.93895499794178e-01 4.51632034246090e-02 3.66630892977488e-03 +-8.18181818181818e+00 -6.82305849045296e-01 3.46949966165822e-02 -8.06490144015382e-03 +-7.57575757575758e+00 -6.41809741158512e-01 2.77831234233813e-02 -1.41096615374045e-02 +-6.96969696969697e+00 -5.88143925838256e-01 2.28417438781606e-02 -1.78405462944423e-02 +-6.36363636363636e+00 -5.18595414594118e-01 1.94965813878357e-02 -2.29439868991729e-02 +-5.75757575757576e+00 -4.47723085873360e-01 1.68485236815072e-02 -2.81966573016451e-02 +-5.15151515151515e+00 -3.75142989396497e-01 1.49610810018752e-02 -3.47182225820690e-02 +-4.54545454545454e+00 -3.00787223897522e-01 1.34635952053030e-02 -4.14011501128667e-02 +-3.93939393939394e+00 -2.25750200730196e-01 1.21953572497309e-02 -4.79556483496797e-02 +-3.33333333333333e+00 -1.53097407752943e-01 1.17061671579090e-02 -5.41961908245246e-02 +-2.72727272727273e+00 -7.95718917516246e-02 1.12293922425528e-02 -5.97874291038278e-02 +-2.12121212121212e+00 -5.03539621814182e-03 1.07440480589344e-02 -6.48477030716386e-02 +-1.51515151515152e+00 7.10741171824617e-02 1.04901796827387e-02 -6.95072912947862e-02 +-9.09090909090912e-01 1.47800523968434e-01 1.03183543231236e-02 -7.40089097305715e-02 +-3.03030303030302e-01 2.25712116064930e-01 1.02530762212861e-02 -7.84452609734865e-02 + 3.03030303030302e-01 3.04012747719234e-01 1.02309881009218e-02 -8.25691600591865e-02 + 9.09090909090912e-01 3.82711307380014e-01 1.02503405435553e-02 -8.63962105538320e-02 + 1.51515151515152e+00 4.61756851424667e-01 1.03813057971860e-02 -9.01104450324160e-02 + 2.12121212121212e+00 5.40685036400329e-01 1.05415949817604e-02 -9.35850435449342e-02 + 2.72727272727273e+00 6.18886227271413e-01 1.07445792627915e-02 -9.62817005798321e-02 + 3.33333333333333e+00 6.96227792951118e-01 1.09887579176491e-02 -9.86711658811812e-02 + 3.93939393939394e+00 7.72883389885004e-01 1.12344879960209e-02 -1.00807961075492e-01 + 4.54545454545455e+00 8.47551890939517e-01 1.15551058195410e-02 -1.02885524901180e-01 + 5.15151515151515e+00 9.21271553826334e-01 1.18923634479442e-02 -1.04819428291073e-01 + 5.75757575757576e+00 9.92784335144794e-01 1.22610882531594e-02 -1.06359973327630e-01 + 6.36363636363637e+00 1.06131473281146e+00 1.27079774642478e-02 -1.07580975239224e-01 + 6.96969696969697e+00 1.12787422242318e+00 1.32063108971969e-02 -1.08587510060800e-01 + 7.57575757575757e+00 1.18885675085141e+00 1.38302419296642e-02 -1.09502885178324e-01 + 8.18181818181818e+00 1.24720837846946e+00 1.45051079826196e-02 -1.10383577044148e-01 + 8.78787878787879e+00 1.30109155320978e+00 1.52650096833159e-02 -1.11295079946526e-01 + 9.39393939393939e+00 1.34910270552171e+00 1.69597298070715e-02 -1.11617299458299e-01 + 1.00000000000000e+01 1.39122211758901e+00 1.92951287014474e-02 -1.11579588588804e-01 + 1.06060606060606e+01 1.41374692668675e+00 2.32087315726581e-02 -1.10700973175584e-01 + 1.12121212121212e+01 1.42235063763216e+00 2.80043073060677e-02 -1.09633362298298e-01 + 1.18181818181818e+01 1.40509952208549e+00 3.36675325297581e-02 -1.08071370626820e-01 + 1.24242424242424e+01 1.36098461886640e+00 4.53311237959958e-02 -1.09677679611616e-01 + 1.30303030303030e+01 1.27121985294027e+00 5.94850170456720e-02 -1.12451230995673e-01 + 1.36363636363636e+01 1.23331688079203e+00 7.12491888525373e-02 -1.11569128322250e-01 + 1.42424242424242e+01 1.19929983782480e+00 8.34701602960147e-02 -1.10866527861742e-01 + 1.48484848484848e+01 1.17429197921907e+00 9.63163863742802e-02 -1.10364535193828e-01 + 1.54545454545455e+01 1.15693155875190e+00 1.09918192046590e-01 -1.12997477778780e-01 + 1.60606060606061e+01 1.14266018641121e+00 1.23724487625457e-01 -1.16993403213071e-01 + 1.66666666666667e+01 1.13325405216419e+00 1.37104753717798e-01 -1.22803327538571e-01 + 1.72727272727273e+01 1.12686629586509e+00 1.50546395471717e-01 -1.28360097087402e-01 + 1.78787878787879e+01 1.12416770644291e+00 1.64063052701384e-01 -1.33607452032450e-01 + 1.84848484848485e+01 1.13139272733087e+00 1.78010604421774e-01 -1.37206719425119e-01 + 1.90909090909091e+01 1.13867731668370e+00 1.91501101195136e-01 -1.40692310188144e-01 + 1.96969696969697e+01 1.13223871836009e+00 2.01790232355546e-01 -1.45868712277606e-01 + 2.03030303030303e+01 1.12592570808589e+00 2.12197188791206e-01 -1.50881669040385e-01 + 2.09090909090909e+01 1.11973829296607e+00 2.22721977167913e-01 -1.55819852215318e-01 + 2.15151515151515e+01 1.11355087784625e+00 2.33246765544621e-01 -1.60788589705368e-01 + 2.21212121212121e+01 1.10686018543461e+00 2.43843747584701e-01 -1.65603019715883e-01 + 2.27272727272727e+01 1.09815690169093e+00 2.54729429996303e-01 -1.69822108656288e-01 + 2.33333333333333e+01 1.08945361794725e+00 2.65615112407906e-01 -1.74062570732705e-01 + 2.39393939393939e+01 1.08075033420357e+00 2.76500794819509e-01 -1.78427259605238e-01 + 2.45454545454545e+01 1.07376593672417e+00 2.88019962980301e-01 -1.82284015244859e-01 + 2.51515151515151e+01 1.06697252249912e+00 2.99609516932444e-01 -1.86084335072627e-01 + 2.57575757575758e+01 1.06017910827406e+00 3.11199070884588e-01 -1.89884654900395e-01 + 2.63636363636364e+01 1.05416214500944e+00 3.23176952543597e-01 -1.93462066542360e-01 + 2.69696969696970e+01 1.04866289615838e+00 3.35413759571076e-01 -1.96890849633946e-01 + 2.75757575757576e+01 1.04316364730731e+00 3.47650566598554e-01 -2.00319632725532e-01 + 2.81818181818182e+01 1.03791578996892e+00 3.60063210581993e-01 -2.03673565505490e-01 + 2.87878787878788e+01 1.03325446250951e+00 3.72886105601387e-01 -2.06852862539969e-01 + 2.93939393939394e+01 1.02859313505011e+00 3.85709000620782e-01 -2.10032159574448e-01 + 3.00000000000000e+01 1.02393180759070e+00 3.98531895640176e-01 -2.13211456608927e-01 + 3.30000000000000e+01 1.00360981651186e+00 4.65352126226771e-01 -2.27906428002545e-01 + 3.60000000000000e+01 9.84001264428555e-01 5.34964795566947e-01 -2.41925534967727e-01 + 3.90000000000000e+01 9.63054591373508e-01 6.07210570957826e-01 -2.55861101384382e-01 + 4.20000000000000e+01 9.38486939161695e-01 6.81068699431397e-01 -2.69396898615722e-01 + 4.50000000000000e+01 9.12610178291857e-01 7.55325331028288e-01 -2.82806077238433e-01 + 4.80000000000000e+01 8.79501806448111e-01 8.29449803698678e-01 -2.95759616602379e-01 + 5.10000000000000e+01 8.42202650323331e-01 9.01994976431333e-01 -3.08464526695633e-01 + 5.40000000000000e+01 7.96521656220475e-01 9.71381447758911e-01 -3.20679850937119e-01 + 5.70000000000000e+01 7.50841011093444e-01 1.04076738901481e+00 -3.32886639691835e-01 + 6.00000000000000e+01 7.05160540452998e-01 1.11015306523690e+00 -3.45085056710935e-01 + 6.30000000000000e+01 6.43541341893905e-01 1.16621143511785e+00 -3.55934491344085e-01 + 6.60000000000000e+01 5.81922006714618e-01 1.22226969076263e+00 -3.66774194260320e-01 + 6.90000000000000e+01 5.20302671535330e-01 1.27832794640741e+00 -3.77604487698421e-01 + 7.20000000000000e+01 4.51119501480277e-01 1.32087421301878e+00 -3.87119214978594e-01 + 7.50000000000000e+01 3.78154568829116e-01 1.35666476172186e+00 -3.95968866317771e-01 + 7.80000000000000e+01 3.05188640011092e-01 1.39245572055610e+00 -4.04806568926510e-01 + 8.10000000000000e+01 2.30890390081552e-01 1.41999053865818e+00 -4.12748066743701e-01 + 8.40000000000000e+01 1.53927589898212e-01 1.43101364519643e+00 -4.18906566709380e-01 + 8.70000000000000e+01 7.69638017609944e-02 1.44203683594514e+00 -4.25049810698846e-01 + 9.00000000000000e+01 -3.36247670426886e-07 1.45305993120123e+00 -4.31178399042578e-01 + 9.30000000000000e+01 -5.38747603685306e-02 1.44203682466298e+00 -4.34104668279932e-01 + 9.60000000000000e+01 -1.07749190274494e-01 1.43101367601985e+00 -4.37031487108267e-01 + 9.90000000000000e+01 -1.61623631750871e-01 1.41999044316543e+00 -4.39958819257674e-01 + 1.02000000000000e+02 -2.13632134040282e-01 1.39245554721333e+00 -4.39636233003905e-01 + 1.05000000000000e+02 -2.64707686941683e-01 1.35666499851025e+00 -4.37688769297266e-01 + 1.08000000000000e+02 -3.15783665079539e-01 1.32087403967776e+00 -4.35740818710456e-01 + 1.11000000000000e+02 -3.64212007755363e-01 1.27832746077970e+00 -4.32550227083959e-01 + 1.14000000000000e+02 -4.07345160141662e-01 1.22226984751125e+00 -4.26873946888224e-01 + 1.17000000000000e+02 -4.50478535342387e-01 1.16621180599633e+00 -4.21196949202848e-01 + 1.20000000000000e+02 -4.93612000135919e-01 1.11015352428889e+00 -4.15519446213869e-01 + 1.23000000000000e+02 -5.25588689582014e-01 1.04076784806681e+00 -4.08013919223535e-01 + 1.26000000000000e+02 -5.57565301171594e-01 9.71381906816171e-01 -4.00507231110389e-01 + 1.29000000000000e+02 -5.89541757042322e-01 9.01995435488592e-01 -3.92999135332578e-01 + 1.32000000000000e+02 -6.13964075900704e-01 8.29406104470312e-01 -3.86098598415459e-01 + 1.35000000000000e+02 -6.34609335202059e-01 7.55215347408169e-01 -3.79500308090265e-01 + 1.38000000000000e+02 -6.55253757939153e-01 6.81025000549314e-01 -3.72899876934706e-01 + 1.41000000000000e+02 -6.73790231192722e-01 6.08261461770757e-01 -3.68126222376485e-01 + 1.44000000000000e+02 -6.88110788374351e-01 5.38351550730586e-01 -3.67006301532646e-01 + 1.47000000000000e+02 -7.02430836152056e-01 4.68441880461646e-01 -3.65881031661847e-01 + 1.50000000000000e+02 -7.16750629236893e-01 3.98532330574024e-01 -3.64750607711192e-01 + 1.53000000000000e+02 -7.34878858674711e-01 3.42608943418167e-01 -3.80350965963448e-01 + 1.56000000000000e+02 -7.53007027741238e-01 2.86685655813922e-01 -3.95955856199125e-01 + 1.59000000000000e+02 -7.71564544817183e-01 2.30762502127974e-01 -4.11565385415533e-01 + 1.62000000000000e+02 -7.00256219005735e-01 1.90909397104532e-01 -4.33416022361716e-01 + 1.65000000000000e+02 -5.83546590903823e-01 1.59091452320285e-01 -4.58385560746469e-01 + 1.68000000000000e+02 -4.58125712100344e-01 1.27273272145471e-01 -4.83354146585932e-01 + 1.71000000000000e+02 -3.41045278744180e-01 9.54550237835969e-02 -4.50000513056908e-01 + 1.74000000000000e+02 -2.27363439140247e-01 6.36366390444162e-02 -2.99999717902353e-01 + 1.77000000000000e+02 -1.12541609339478e-01 5.25040908476199e-02 -1.48454173263684e-01 + 1.80000000000000e+02 0.00000000000000e+00 5.17338093025581e-02 0.00000000000000e+00 diff --git a/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_12.dat b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_12.dat new file mode 100644 index 00000000..43ee56ca --- /dev/null +++ b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_12.dat @@ -0,0 +1,254 @@ +! ------------ AirfoilInfo v1.01.x Input File ---------------------------------- +! AeroElasticSE FAST driver +! line +! line +! ------------------------------------------------------------------------------ +DEFAULT InterpOrd ! Interpolation order to use for quasi-steady table lookup {1=linear; 3=cubic spline; "default"} [default=3] +1 NonDimArea ! The non-dimensional area of the airfoil (area/chord^2) (set to 1.0 if unsure or unneeded) +@"NREL-2p8-127_AF12_Coords.txt" NumCoords ! The number of coordinates in the airfoil shape file. Set to zero if coordinates not included. +AF12_BL.txt BL_file ! The file name including the boundary layer characteristics of the profile. Ignored if the aeroacoustic module is not called. +1 NumTabs ! Number of airfoil tables in this file. Each table must have lines for Re and Ctrl. +! ------------------------------------------------------------------------------ +! data for table 1 +! ------------------------------------------------------------------------------ +6.000000 Re ! Reynolds number in millions +0 Ctrl ! Control setting (must be 0 for current AirfoilInfo) +True InclUAdata ! Is unsteady aerodynamics data included in this table? If TRUE, then include 30 UA coefficients below this line +!........................................ +-2.104210 alpha0 ! 0-lift angle of attack, depends on airfoil. +11.449404 alpha1 ! Angle of attack at f=0.7, (approximately the stall angle) for AOA>alpha0. (deg) +-8.941354 alpha2 ! Angle of attack at f=0.7, (approximately the stall angle) for AOA1] +0.000000 S2 ! Constant in the f curve best-fit for AOA> alpha1; by definition it depends on the airfoil. [ignored if UAMod<>1] +0.000000 S3 ! Constant in the f curve best-fit for alpha2<=AOA< alpha0; by definition it depends on the airfoil. [ignored if UAMod<>1] +0.000000 S4 ! Constant in the f curve best-fit for AOA< alpha2; by definition it depends on the airfoil. [ignored if UAMod<>1] +1.433280 Cn1 ! Critical value of C0n at leading edge separation. It should be extracted from airfoil data at a given Mach and Reynolds number. It can be calculated from the static value of Cn at either the break in the pitching moment or the loss of chord force at the onset of stall. It is close to the condition of maximum lift of the airfoil at low Mach numbers. +-1.020492 Cn2 ! As Cn1 for negative AOAs. +Default St_sh ! Strouhal's shedding frequency constant. [default = 0.19] +0.010714 Cd0 ! 2D drag coefficient value at 0-lift. +-0.072028 Cm0 ! 2D pitching moment coefficient about 1/4-chord location, at 0-lift, positive if nose up. [If the aerodynamics coefficients table does not include a column for Cm, this needs to be set to 0.0] +0.000000 k0 ! Constant in the \hat(x)_cp curve best-fit; = (\hat(x)_AC-0.25). [ignored if UAMod<>1] +0.000000 k1 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k2 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k3 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k1_hat ! Constant in the expression of Cc due to leading edge vortex effects. [ignored if UAMod<>1] +Default x_cp_bar ! Constant in the expression of \hat(x)_cp^v. [ignored if UAMod<>1, default = 0.2] +Default UACutout ! Angle of attack above which unsteady aerodynamics are disabled (deg). [Specifying the string "Default" sets UACutout to 45 degrees] +Default filtCutOff ! Cut-off frequency (-3 dB corner frequency) for low-pass filtering the AoA input to UA, as well as the 1st and 2nd derivatives (Hz) [default = 20] +!........................................ +! Table of aerodynamics coefficients +200 NumAlf ! Number of data lines in the following table +! Alpha Cl Cd Cm +! (deg) (-) (-) (-) +-1.80000000000000e+02 0.00000000000000e+00 5.02017886725028e-02 0.00000000000000e+00 +-1.77000000000000e+02 1.16814702114733e-01 5.02017886725028e-02 1.18974998388536e-01 +-1.74000000000000e+02 2.35757260050863e-01 6.02419881354083e-02 2.39999774321882e-01 +-1.71000000000000e+02 3.53636476996742e-01 9.03629161351898e-02 3.60000410445527e-01 +-1.68000000000000e+02 4.69829759859863e-01 1.20986055059121e-01 3.19692038335689e-01 +-1.65000000000000e+02 5.86100406969184e-01 1.51860293583585e-01 1.99231033151485e-01 +-1.62000000000000e+02 6.97207018087719e-01 1.82735181026080e-01 7.87690618632042e-02 +-1.59000000000000e+02 7.65053274169454e-01 2.21992372815171e-01 4.59488938113571e-04 +-1.56000000000000e+02 7.47840212628704e-01 2.78013889729193e-01 8.23826475941633e-03 +-1.53000000000000e+02 7.31315050935883e-01 3.34035434615955e-01 1.69033914984109e-02 +-1.50000000000000e+02 7.14789733419415e-01 3.90057026535133e-01 2.57900977189505e-02 +-1.47000000000000e+02 7.00700113478808e-01 4.60260101212902e-01 4.02282514210461e-02 +-1.44000000000000e+02 6.86610239724511e-01 5.30463342418639e-01 5.46749993729137e-02 +-1.41000000000000e+02 6.72519858324716e-01 6.00666916692206e-01 6.91319722248670e-02 +-1.38000000000000e+02 6.54157816774948e-01 6.73769502775919e-01 8.40066813863651e-02 +-1.35000000000000e+02 6.33659953815723e-01 7.48321588883743e-01 9.90913902837609e-02 +-1.32000000000000e+02 6.13161255971681e-01 8.22874224418487e-01 1.14182857514007e-01 +-1.29000000000000e+02 5.88869424113624e-01 8.95844660221988e-01 1.29408668138862e-01 +-1.26000000000000e+02 5.56991306252975e-01 9.65650689048611e-01 1.44894245978222e-01 +-1.23000000000000e+02 5.25113031922222e-01 1.03545618459309e+00 1.60385940835181e-01 +-1.20000000000000e+02 4.93234679359342e-01 1.10526141350648e+00 1.75884859665492e-01 +-1.17000000000000e+02 4.50165647641462e-01 1.16178301844503e+00 1.90450025251094e-01 +-1.14000000000000e+02 4.07096660176995e-01 1.21830438150688e+00 2.05022854430753e-01 +-1.11000000000000e+02 3.64027804983567e-01 1.27482531278278e+00 2.19604660336798e-01 +-1.08000000000000e+02 3.15645479300682e-01 1.31785592534089e+00 2.32463316412531e-01 +-1.05000000000000e+02 2.64606377915867e-01 1.35414127581743e+00 2.44466971927803e-01 +-1.02000000000000e+02 2.13567566267535e-01 1.39042621049931e+00 2.56485516539190e-01 +-9.90000000000000e+01 1.61587565629768e-01 1.41846067229841e+00 2.67134366691667e-01 +-9.60000000000000e+01 1.07725146245282e-01 1.42999383096059e+00 2.75027548957952e-01 +-9.30000000000000e+01 5.38627383393683e-02 1.44152690151593e+00 2.82950978094881e-01 +-9.00000000000000e+01 3.36172637297600e-07 1.45305992801866e+00 2.90917363787953e-01 +-8.70000000000000e+01 -5.38626832111768e-02 1.44152691331999e+00 2.94767512788956e-01 +-8.40000000000000e+01 -1.07725296856606e-01 1.42999379871131e+00 2.98897742164918e-01 +-8.10000000000000e+01 -1.61587099027032e-01 1.41846077220858e+00 3.03536772948404e-01 +-7.80000000000000e+01 -2.13567319073521e-01 1.39042638623652e+00 3.03702648984174e-01 +-7.50000000000000e+01 -2.64606715585627e-01 1.35414103575821e+00 3.01751455652536e-01 +-7.20000000000000e+01 -3.15645232110603e-01 1.31785610107633e+00 2.99797410104482e-01 +-6.90000000000000e+01 -3.64027431877603e-01 1.27482580242423e+00 2.96601873383554e-01 +-6.60000000000000e+01 -4.07096780606374e-01 1.21830422346273e+00 2.90925626936627e-01 +-6.30000000000000e+01 -4.50165932584065e-01 1.16178264450123e+00 2.85244623169737e-01 +-6.00000000000000e+01 -4.93234890264853e-01 1.10526095167874e+00 2.79558323005520e-01 +-5.70000000000000e+01 -5.25113242827733e-01 1.03545572276536e+00 2.72051789581655e-01 +-5.40000000000000e+01 -5.56991517156933e-01 9.65650227215581e-01 2.64537349061016e-01 +-5.10000000000000e+01 -5.88869635017581e-01 8.95844198388958e-01 2.57013385477719e-01 +-4.80000000000000e+01 -6.14858281985569e-01 8.22907477862781e-01 2.49649988716779e-01 +-4.50000000000000e+01 -6.37902288159362e-01 7.48405461801475e-01 2.42355684979480e-01 +-4.20000000000000e+01 -6.55854829508633e-01 6.73802755955525e-01 2.36361332357867e-01 +-3.90000000000000e+01 -6.72882108422873e-01 5.99606299882174e-01 2.30958164591745e-01 +-3.60000000000000e+01 -6.87344655388143e-01 5.27047589477837e-01 2.27795230971316e-01 +-3.30000000000000e+01 -7.00836969047683e-01 4.57145854597990e-01 2.27367173402586e-01 +-3.00000000000000e+01 -7.14789834137016e-01 3.90056589853572e-01 2.29972174924480e-01 +-2.93939393939394e+01 -7.17989820447135e-01 3.77183552479970e-01 2.31313103482737e-01 +-2.87878787878788e+01 -7.21189806757255e-01 3.64310515106369e-01 2.32654032040993e-01 +-2.81818181818182e+01 -7.24389793067374e-01 3.51437477732768e-01 2.33994960599249e-01 +-2.75757575757576e+01 -7.27993615957789e-01 3.38976887108657e-01 2.35912898360177e-01 +-2.69696969696970e+01 -7.31770526515904e-01 3.26693074541322e-01 2.38078146993880e-01 +-2.63636363636364e+01 -7.35547437074019e-01 3.14409261973987e-01 2.40243395627583e-01 +-2.57575757575758e+01 -7.39682607350460e-01 3.02385685277020e-01 2.42838068946369e-01 +-2.51515151515151e+01 -7.44355083707426e-01 2.90752401734336e-01 2.46076779209917e-01 +-2.45454545454545e+01 -7.49027560064392e-01 2.79119118191653e-01 2.49315489473464e-01 +-2.39393939393939e+01 -7.53832399461519e-01 2.67556547894255e-01 2.52697168932637e-01 +-2.33333333333333e+01 -7.59828531846218e-01 2.56630410494836e-01 2.57365598831951e-01 +-2.27272727272727e+01 -7.65824664230917e-01 2.45704273095417e-01 2.62833561583836e-01 +-2.21212121212121e+01 -7.71820796615617e-01 2.34778135695999e-01 2.67654474711527e-01 +-2.15151515151515e+01 -7.96443477215383e-01 2.26676404363075e-01 2.64351420041365e-01 +-2.09090909090909e+01 -8.30849944454416e-01 2.19280956225120e-01 2.57191864213633e-01 +-2.03030303030303e+01 -8.61239798275855e-01 2.11885508087165e-01 2.49459359740882e-01 +-1.96969696969697e+01 -8.86851353917406e-01 2.04664215991167e-01 2.36345486505374e-01 +-1.90909090909091e+01 -9.07849523166766e-01 1.97617070085050e-01 2.17989979126022e-01 +-1.84848484848485e+01 -9.28438728259752e-01 1.90994947917113e-01 1.99581867965191e-01 +-1.78787878787879e+01 -9.48798009848073e-01 1.84343308202159e-01 1.81686497656418e-01 +-1.72727272727273e+01 -9.69015714430469e-01 1.76652563396641e-01 1.64047931232961e-01 +-1.66666666666667e+01 -9.89139234078135e-01 1.70406496274106e-01 1.46409370226095e-01 +-1.60606060606061e+01 -1.00919719372332e+00 1.64405524173896e-01 1.28770813650940e-01 +-1.54545454545455e+01 -1.01540755504446e+00 1.56862910031355e-01 1.13470810022679e-01 +-1.48484848484848e+01 -1.01298433891169e+00 1.48403778032376e-01 9.94548755135208e-02 +-1.42424242424242e+01 -9.89203767259323e-01 1.37794975860024e-01 8.94257900471029e-02 +-1.36363636363636e+01 -9.62014659606293e-01 1.26881241910317e-01 7.98089478777152e-02 +-1.30303030303030e+01 -9.32449292572719e-01 1.15751868266820e-01 6.93414419906876e-02 +-1.24242424242424e+01 -9.00792491049511e-01 1.04900663581092e-01 5.67713948672409e-02 +-1.18181818181818e+01 -8.68848659795491e-01 9.45041039998393e-02 4.42375285802314e-02 +-1.12121212121212e+01 -8.36808576348847e-01 8.51661045609216e-02 3.19958406592258e-02 +-1.06060606060606e+01 -8.03284211237670e-01 7.64433166380479e-02 2.09106002122012e-02 +-1.00000000000000e+01 -7.68096954585546e-01 6.80130732444816e-02 1.04779161942864e-02 +-9.39393939393939e+00 -7.39737601227035e-01 5.68394250941624e-02 -1.00892879318824e-03 +-8.78787878787879e+00 -7.17791627668883e-01 4.50577060106998e-02 -1.17953152141081e-02 +-8.18181818181818e+00 -7.04457618185764e-01 3.35556812007792e-02 -2.13372325268140e-02 +-7.57575757575758e+00 -6.63232806034972e-01 2.62982027978296e-02 -2.60669251138793e-02 +-6.96969696969697e+00 -6.08991380617151e-01 2.14176171488251e-02 -2.89228360247444e-02 +-6.36363636363636e+00 -5.33652028186316e-01 1.85402907866192e-02 -3.37736937247221e-02 +-5.75757575757576e+00 -4.57645786576647e-01 1.62204582639942e-02 -3.87352025598183e-02 +-5.15151515151515e+00 -3.80878183776993e-01 1.45075217386201e-02 -4.47429870829259e-02 +-4.54545454545454e+00 -3.03328576206396e-01 1.31751950655347e-02 -5.08206305818731e-02 +-3.93939393939394e+00 -2.25638938079791e-01 1.20463073814285e-02 -5.67577483907786e-02 +-3.33333333333333e+00 -1.51759128742261e-01 1.15765523813214e-02 -6.23461963393866e-02 +-2.72727272727273e+00 -7.72803618184935e-02 1.11443927588391e-02 -6.73647853995964e-02 +-2.12121212121212e+00 -2.14165309152243e-03 1.07204811423473e-02 -7.19089758691984e-02 +-1.51515151515152e+00 7.42011233954975e-02 1.04829792545349e-02 -7.61446613489007e-02 +-9.09090909090912e-01 1.51109201168349e-01 1.03234088196644e-02 -8.02509486552512e-02 +-3.03030303030302e-01 2.29344027261245e-01 1.03026060888101e-02 -8.42792874035115e-02 + 3.03030303030302e-01 3.07759215649705e-01 1.03155825014327e-02 -8.80359990719921e-02 + 9.09090909090912e-01 3.86363579252603e-01 1.03591204387569e-02 -9.15396518680686e-02 + 1.51515151515152e+00 4.65155136112344e-01 1.04514380417906e-02 -9.48849911388328e-02 + 2.12121212121212e+00 5.43742423609011e-01 1.05708486137771e-02 -9.80280317259123e-02 + 2.72727272727273e+00 6.21355563499191e-01 1.07685455281878e-02 -1.00538334680120e-01 + 3.33333333333333e+00 6.98247696483015e-01 1.09884995827544e-02 -1.02768385980751e-01 + 3.93939393939394e+00 7.74577272776593e-01 1.12160604908465e-02 -1.04764162336771e-01 + 4.54545454545455e+00 8.49123646294387e-01 1.15084433622475e-02 -1.06669894654905e-01 + 5.15151515151515e+00 9.22768835492197e-01 1.18149173971583e-02 -1.08443519681338e-01 + 5.75757575757576e+00 9.94281779511649e-01 1.21556943938836e-02 -1.09866171766382e-01 + 6.36363636363637e+00 1.06310529013751e+00 1.25630225021709e-02 -1.10999261303783e-01 + 6.96969696969697e+00 1.13016792278117e+00 1.30120459327629e-02 -1.11939153730602e-01 + 7.57575757575757e+00 1.19235719212211e+00 1.35489371100261e-02 -1.12757130291620e-01 + 8.18181818181818e+00 1.25253452840185e+00 1.41028478529467e-02 -1.13550777719788e-01 + 8.78787878787879e+00 1.31022818965375e+00 1.46613278249224e-02 -1.14419167648035e-01 + 9.39393939393939e+00 1.36351139175394e+00 1.60081512284208e-02 -1.14359279394763e-01 + 1.00000000000000e+01 1.40997780157282e+00 1.78443424094440e-02 -1.13736890758993e-01 + 1.06060606060606e+01 1.43923730215627e+00 2.09588631373841e-02 -1.12187901895665e-01 + 1.12121212121212e+01 1.45625328102718e+00 2.47924700140119e-02 -1.10420788252029e-01 + 1.18181818181818e+01 1.45052843686856e+00 2.93047053533567e-02 -1.08130034479078e-01 + 1.24242424242424e+01 1.37738927101704e+00 4.26630642527924e-02 -1.10097235207091e-01 + 1.30303030303030e+01 1.25402046394694e+00 5.95100927900937e-02 -1.13671143573967e-01 + 1.36363636363636e+01 1.20642687925599e+00 7.05802370100983e-02 -1.12460113720568e-01 + 1.42424242424242e+01 1.16512824375798e+00 8.18308265484637e-02 -1.11416728271022e-01 + 1.48484848484848e+01 1.13845165437591e+00 9.33501183013086e-02 -1.10513745021243e-01 + 1.54545454545455e+01 1.12012151200243e+00 1.05371259823310e-01 -1.12074593125414e-01 + 1.60606060606061e+01 1.10521158214097e+00 1.17537515544027e-01 -1.14635056143715e-01 + 1.66666666666667e+01 1.09605105013413e+00 1.29504477189816e-01 -1.18698748541531e-01 + 1.72727272727273e+01 1.09038474770029e+00 1.41619143192006e-01 -1.22755992205202e-01 + 1.78787878787879e+01 1.08898921460796e+00 1.53914338613840e-01 -1.26805354000924e-01 + 1.84848484848485e+01 1.09852690400848e+00 1.67121306650109e-01 -1.30271150233030e-01 + 1.90909090909091e+01 1.10900797848342e+00 1.80185918785840e-01 -1.33848294218024e-01 + 1.96969696969697e+01 1.10934527307501e+00 1.91151684117947e-01 -1.38883475019382e-01 + 2.03030303030303e+01 1.10872617200819e+00 2.02082800980853e-01 -1.43953835687333e-01 + 2.09090909090909e+01 1.10715062117621e+00 2.12979267414367e-01 -1.49203757196069e-01 + 2.15151515151515e+01 1.10557507034423e+00 2.23875733847882e-01 -1.54503423314042e-01 + 2.21212121212121e+01 1.10260124642550e+00 2.34778135695999e-01 -1.59652147931712e-01 + 2.27272727272727e+01 1.09403576887978e+00 2.45704273095417e-01 -1.64232639974624e-01 + 2.33333333333333e+01 1.08547029133405e+00 2.56630410494836e-01 -1.68847929010858e-01 + 2.39393939393939e+01 1.07690481378832e+00 2.67556547894255e-01 -1.73665468151725e-01 + 2.45454545454545e+01 1.07004041681628e+00 2.79119118191653e-01 -1.77890036537271e-01 + 2.51515151515151e+01 1.06336502473105e+00 2.90752401734336e-01 -1.82048720700615e-01 + 2.57575757575758e+01 1.05668963264583e+00 3.02385685277020e-01 -1.86207404863960e-01 + 2.63636363636364e+01 1.05078168869387e+00 3.14409261973987e-01 -1.90102460494435e-01 + 2.69696969696970e+01 1.04538545633799e+00 3.26693074541322e-01 -1.93821736457880e-01 + 2.75757575757576e+01 1.03998922398212e+00 3.38976887108657e-01 -1.97541012421324e-01 + 2.81818181818182e+01 1.03484090277918e+00 3.51437477732768e-01 -2.01170473836824e-01 + 2.87878787878788e+01 1.03027099131248e+00 3.64310515106369e-01 -2.04590385950606e-01 + 2.93939393939394e+01 1.02570107984578e+00 3.77183552479970e-01 -2.08010298064387e-01 + 3.00000000000000e+01 1.02113116837907e+00 3.90056589853572e-01 -2.11430210178169e-01 + 3.30000000000000e+01 1.00119460561295e+00 4.57145854597991e-01 -2.27086388641851e-01 + 3.60000000000000e+01 9.81921720811872e-01 5.27047589477837e-01 -2.41904140621254e-01 + 3.90000000000000e+01 9.61260291943995e-01 5.99606299882174e-01 -2.56159440416738e-01 + 4.20000000000000e+01 9.36935736815422e-01 6.73802755955525e-01 -2.70019544874094e-01 + 4.50000000000000e+01 9.11289556833257e-01 7.48405461801475e-01 -2.83768812367968e-01 + 4.80000000000000e+01 8.78369078677083e-01 8.22907477862781e-01 -2.97042946965006e-01 + 5.10000000000000e+01 8.41242012973183e-01 8.95844198388958e-01 -3.10074656049880e-01 + 5.40000000000000e+01 7.95701501741868e-01 9.65650227215581e-01 -3.22614713534726e-01 + 5.70000000000000e+01 7.50161338413173e-01 1.03545572276536e+00 -3.35153534620333e-01 + 6.00000000000000e+01 7.04621349034462e-01 1.10526095167874e+00 -3.47689985564868e-01 + 6.30000000000000e+01 6.43094140155942e-01 1.16178264450123e+00 -3.58895514925207e-01 + 6.60000000000000e+01 5.81566794241577e-01 1.21830422346273e+00 -3.70096619015063e-01 + 6.90000000000000e+01 5.20039448327212e-01 1.27482580242423e+00 -3.81292926550571e-01 + 7.20000000000000e+01 4.50922061318250e-01 1.31785610107633e+00 -3.91197073364813e-01 + 7.50000000000000e+01 3.78009809140240e-01 1.35414103575821e+00 -4.00450410082631e-01 + 7.80000000000000e+01 3.05096426319516e-01 1.39042638623652e+00 -4.09696121786907e-01 + 8.10000000000000e+01 2.30838925091062e-01 1.41846077220858e+00 -4.18058441063076e-01 + 8.40000000000000e+01 1.53893279831030e-01 1.42999379871131e+00 -4.24659851438870e-01 + 8.70000000000000e+01 7.69466467481749e-02 1.44152691331999e+00 -4.31250229720335e-01 + 9.00000000000000e+01 -3.36172637530740e-07 1.45305992801866e+00 -4.37829850424638e-01 + 9.30000000000000e+01 -5.38627383393683e-02 1.44152690151593e+00 -4.40933372026436e-01 + 9.60000000000000e+01 -1.07725146245282e-01 1.42999383096059e+00 -4.44037873446937e-01 + 9.90000000000000e+01 -1.61587565629768e-01 1.41846067229841e+00 -4.47143282683005e-01 + 1.02000000000000e+02 -2.13567566267535e-01 1.39042621049931e+00 -4.46986201155388e-01 + 1.05000000000000e+02 -2.64606377915867e-01 1.35414127581743e+00 -4.45198189623654e-01 + 1.08000000000000e+02 -3.15645479300682e-01 1.31785592534089e+00 -4.43410060853994e-01 + 1.11000000000000e+02 -3.64027804983567e-01 1.27482531278278e+00 -4.40372525830713e-01 + 1.14000000000000e+02 -4.07096660176995e-01 1.21830438150688e+00 -4.34835474017044e-01 + 1.17000000000000e+02 -4.50165647641462e-01 1.16178301844503e+00 -4.29298134131730e-01 + 1.20000000000000e+02 -4.93234679359343e-01 1.10526141350648e+00 -4.23760689165608e-01 + 1.23000000000000e+02 -5.25113031922223e-01 1.03545618459309e+00 -4.16386674177567e-01 + 1.26000000000000e+02 -5.56991306252975e-01 9.65650689048611e-01 -4.09012018270847e-01 + 1.29000000000000e+02 -5.88869424113624e-01 8.95844660221987e-01 -4.01636451380112e-01 + 1.32000000000000e+02 -6.13161255971681e-01 8.22874224418486e-01 -3.94888279932588e-01 + 1.35000000000000e+02 -6.33659953815723e-01 7.48321588883743e-01 -3.88452749684788e-01 + 1.38000000000000e+02 -6.54157816774948e-01 6.73769502775918e-01 -3.82015808693097e-01 + 1.41000000000000e+02 -6.72519858324716e-01 6.00666916692205e-01 -3.77450446527224e-01 + 1.44000000000000e+02 -6.86610239724511e-01 5.30463342418639e-01 -3.76628216553060e-01 + 1.47000000000000e+02 -7.00700113478808e-01 4.60260101212902e-01 -3.75801923510001e-01 + 1.50000000000000e+02 -7.14789733419415e-01 3.90057026535133e-01 -3.74971722702591e-01 + 1.53000000000000e+02 -7.26083351466705e-01 3.34899268561139e-01 -3.90699237662118e-01 + 1.56000000000000e+02 -7.37376919859767e-01 2.79741654709182e-01 -4.06434613881277e-01 + 1.59000000000000e+02 -7.49369636696621e-01 2.24584258977831e-01 -4.22178074951782e-01 + 1.62000000000000e+02 -6.78487565748514e-01 1.85578685533409e-01 -4.41942545112509e-01 + 1.65000000000000e+02 -5.65406079877361e-01 1.54649159831924e-01 -4.63714630913619e-01 + 1.68000000000000e+02 -4.44894229884888e-01 1.23719388559455e-01 -4.85485784604534e-01 + 1.71000000000000e+02 -3.31496503011607e-01 9.27895975192221e-02 -4.50000513056908e-01 + 1.74000000000000e+02 -2.20997628314192e-01 6.18597669425397e-02 -2.99999717902353e-01 + 1.77000000000000e+02 -1.09575522573893e-01 5.10040358195194e-02 -1.48718747985670e-01 + 1.80000000000000e+02 0.00000000000000e+00 5.02017886725028e-02 0.00000000000000e+00 diff --git a/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_13.dat b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_13.dat new file mode 100644 index 00000000..92b13a2b --- /dev/null +++ b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_13.dat @@ -0,0 +1,254 @@ +! ------------ AirfoilInfo v1.01.x Input File ---------------------------------- +! AeroElasticSE FAST driver +! line +! line +! ------------------------------------------------------------------------------ +DEFAULT InterpOrd ! Interpolation order to use for quasi-steady table lookup {1=linear; 3=cubic spline; "default"} [default=3] +1 NonDimArea ! The non-dimensional area of the airfoil (area/chord^2) (set to 1.0 if unsure or unneeded) +@"NREL-2p8-127_AF13_Coords.txt" NumCoords ! The number of coordinates in the airfoil shape file. Set to zero if coordinates not included. +AF13_BL.txt BL_file ! The file name including the boundary layer characteristics of the profile. Ignored if the aeroacoustic module is not called. +1 NumTabs ! Number of airfoil tables in this file. Each table must have lines for Re and Ctrl. +! ------------------------------------------------------------------------------ +! data for table 1 +! ------------------------------------------------------------------------------ +6.000000 Re ! Reynolds number in millions +0 Ctrl ! Control setting (must be 0 for current AirfoilInfo) +True InclUAdata ! Is unsteady aerodynamics data included in this table? If TRUE, then include 30 UA coefficients below this line +!........................................ +-2.132099 alpha0 ! 0-lift angle of attack, depends on airfoil. +11.682019 alpha1 ! Angle of attack at f=0.7, (approximately the stall angle) for AOA>alpha0. (deg) +-9.246885 alpha2 ! Angle of attack at f=0.7, (approximately the stall angle) for AOA1] +0.000000 S2 ! Constant in the f curve best-fit for AOA> alpha1; by definition it depends on the airfoil. [ignored if UAMod<>1] +0.000000 S3 ! Constant in the f curve best-fit for alpha2<=AOA< alpha0; by definition it depends on the airfoil. [ignored if UAMod<>1] +0.000000 S4 ! Constant in the f curve best-fit for AOA< alpha2; by definition it depends on the airfoil. [ignored if UAMod<>1] +1.467246 Cn1 ! Critical value of C0n at leading edge separation. It should be extracted from airfoil data at a given Mach and Reynolds number. It can be calculated from the static value of Cn at either the break in the pitching moment or the loss of chord force at the onset of stall. It is close to the condition of maximum lift of the airfoil at low Mach numbers. +-1.116975 Cn2 ! As Cn1 for negative AOAs. +Default St_sh ! Strouhal's shedding frequency constant. [default = 0.19] +0.010706 Cd0 ! 2D drag coefficient value at 0-lift. +-0.078417 Cm0 ! 2D pitching moment coefficient about 1/4-chord location, at 0-lift, positive if nose up. [If the aerodynamics coefficients table does not include a column for Cm, this needs to be set to 0.0] +0.000000 k0 ! Constant in the \hat(x)_cp curve best-fit; = (\hat(x)_AC-0.25). [ignored if UAMod<>1] +0.000000 k1 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k2 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k3 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k1_hat ! Constant in the expression of Cc due to leading edge vortex effects. [ignored if UAMod<>1] +Default x_cp_bar ! Constant in the expression of \hat(x)_cp^v. [ignored if UAMod<>1, default = 0.2] +Default UACutout ! Angle of attack above which unsteady aerodynamics are disabled (deg). [Specifying the string "Default" sets UACutout to 45 degrees] +Default filtCutOff ! Cut-off frequency (-3 dB corner frequency) for low-pass filtering the AoA input to UA, as well as the 1st and 2nd derivatives (Hz) [default = 20] +!........................................ +! Table of aerodynamics coefficients +200 NumAlf ! Number of data lines in the following table +! Alpha Cl Cd Cm +! (deg) (-) (-) (-) +-1.80000000000000e+02 0.00000000000000e+00 4.87439042124992e-02 0.00000000000000e+00 +-1.77000000000000e+02 1.13601999469549e-01 4.87439042124992e-02 1.19176415715757e-01 +-1.74000000000000e+02 2.28858413112315e-01 5.84925712756744e-02 2.39999774321882e-01 +-1.71000000000000e+02 3.43288316600078e-01 8.77388925055090e-02 3.60000410445527e-01 +-1.68000000000000e+02 4.57070767928178e-01 1.17275421818159e-01 3.18708357160145e-01 +-1.65000000000000e+02 5.71129134749526e-01 1.46957051785061e-01 1.96771841693633e-01 +-1.62000000000000e+02 6.81811167127312e-01 1.76639445546079e-01 7.48344304685462e-02 +-1.59000000000000e+02 7.50644491717964e-01 2.14984200570790e-01 -5.07801650458084e-03 +-1.56000000000000e+02 7.37523770619090e-01 2.70653385079522e-01 1.06132839067504e-03 +-1.53000000000000e+02 7.25223845001242e-01 3.26322594869384e-01 8.04336961373999e-03 +-1.50000000000000e+02 7.12923727515902e-01 3.81991851817702e-01 1.50360358377684e-02 +-1.47000000000000e+02 6.99053142386901e-01 4.52474247296891e-01 2.96995895978959e-02 +-1.44000000000000e+02 6.85182304280847e-01 5.22956853217613e-01 4.43686473866053e-02 +-1.41000000000000e+02 6.71310960202625e-01 5.93439880036427e-01 5.90442691380621e-02 +-1.38000000000000e+02 6.53114909413893e-01 6.66865106551800e-01 7.40923427363092e-02 +-1.35000000000000e+02 6.32756514043044e-01 7.41761426946880e-01 8.93274281204840e-02 +-1.32000000000000e+02 6.12397285385553e-01 8.16658429255323e-01 1.04567050663022e-01 +-1.29000000000000e+02 5.88229626117782e-01 8.89991527762646e-01 1.19947402883451e-01 +-1.26000000000000e+02 5.56445087582313e-01 9.60196811237631e-01 1.35603342201244e-01 +-1.23000000000000e+02 5.24660391861842e-01 1.03040155838038e+00 1.51263206732352e-01 +-1.20000000000000e+02 4.92875617551808e-01 1.10060603736703e+00 1.66927716624602e-01 +-1.17000000000000e+02 4.49867900921898e-01 1.15756854481392e+00 1.81710954488631e-01 +-1.14000000000000e+02 4.06860185400029e-01 1.21453080878140e+00 1.96498840434726e-01 +-1.11000000000000e+02 3.63852515987308e-01 1.27149263759476e+00 2.11292122383483e-01 +-1.08000000000000e+02 3.15513980484258e-01 1.31498386088960e+00 2.24396145865201e-01 +-1.05000000000000e+02 2.64509971345682e-01 1.35173967885259e+00 2.36659399343987e-01 +-1.02000000000000e+02 2.13506123000612e-01 1.38849507562982e+00 2.48931685712608e-01 +-9.90000000000000e+01 1.61553244788091e-01 1.41700492873292e+00 2.59841073682875e-01 +-9.60000000000000e+01 1.07702265733195e-01 1.42902333732993e+00 2.68014448982559e-01 +-9.30000000000000e+01 5.38512980694728e-02 1.44104165411306e+00 2.76206223274710e-01 +-9.00000000000000e+01 3.36101235326894e-07 1.45305992499009e+00 2.84424528048508e-01 +-8.70000000000000e+01 -5.38512429529903e-02 1.44104166641377e+00 2.88179235636605e-01 +-8.40000000000000e+01 -1.07702416312529e-01 1.42902330372378e+00 2.92116238002531e-01 +-8.10000000000000e+01 -1.61552778284462e-01 1.41700503284675e+00 2.96384910251329e-01 +-7.80000000000000e+01 -2.13505875975934e-01 1.38849525364560e+00 2.96589518980285e-01 +-7.50000000000000e+01 -2.64510308783977e-01 1.35173943568081e+00 2.94839423717641e-01 +-7.20000000000000e+01 -3.15513733464136e-01 1.31498403890358e+00 2.93086106067290e-01 +-6.90000000000000e+01 -3.63852143411397e-01 1.27149313105570e+00 2.90081406410839e-01 +-6.60000000000000e+01 -4.06860305658320e-01 1.21453064950441e+00 2.84576673209790e-01 +-6.30000000000000e+01 -4.49868185458844e-01 1.15756816795312e+00 2.79066340953731e-01 +-6.00000000000000e+01 -4.92875827838210e-01 1.10060557289787e+00 2.73549730680385e-01 +-5.70000000000000e+01 -5.24660602148244e-01 1.03040109391122e+00 2.66198212861305e-01 +-5.40000000000000e+01 -5.56445297867155e-01 9.60196346763153e-01 2.58837329083779e-01 +-5.10000000000000e+01 -5.88229836402624e-01 8.89991063288168e-01 2.51465219825159e-01 +-4.80000000000000e+01 -6.14103823719259e-01 8.16681742398572e-01 2.44260248495120e-01 +-4.50000000000000e+01 -6.37022630417404e-01 7.41820452687947e-01 2.37125494405563e-01 +-4.20000000000000e+01 -6.54821434392937e-01 6.66888419508008e-01 2.31318374407913e-01 +-3.90000000000000e+01 -6.71686771395590e-01 5.92370007881034e-01 2.26128186404354e-01 +-3.60000000000000e+01 -6.85959395421995e-01 5.19513505734105e-01 2.23293038777573e-01 +-3.30000000000000e+01 -6.99228262265746e-01 4.49336693515259e-01 2.23281989121863e-01 +-3.00000000000000e+01 -7.12923826438148e-01 3.81991413473000e-01 2.26408555434034e-01 +-2.93939393939394e+01 -7.16063242755988e-01 3.69070660189083e-01 2.27884386933293e-01 +-2.87878787878788e+01 -7.19202659073829e-01 3.56149906905165e-01 2.29360218432552e-01 +-2.81818181818182e+01 -7.22342075391669e-01 3.43229153621248e-01 2.30836049931811e-01 +-2.75757575757576e+01 -7.25879646593120e-01 3.30722936547354e-01 2.32910797277799e-01 +-2.69696969696970e+01 -7.29587870240511e-01 3.18394393090142e-01 2.35242244863728e-01 +-2.63636363636364e+01 -7.33296093887901e-01 3.06065849632931e-01 2.37573692449656e-01 +-2.57575757575758e+01 -7.37358552649944e-01 2.93998789131352e-01 2.40351599308823e-01 +-2.51515151515151e+01 -7.41952281524987e-01 2.82323892121304e-01 2.43799091024856e-01 +-2.45454545454545e+01 -7.46546010400030e-01 2.70648995111257e-01 2.47246582740888e-01 +-2.39393939393939e+01 -7.51270810440089e-01 2.59045122954569e-01 2.50842931746802e-01 +-2.33333333333333e+01 -7.57175276341296e-01 2.48080488228869e-01 2.55779025181128e-01 +-2.27272727272727e+01 -7.63079742242504e-01 2.37115853503168e-01 2.61669103088351e-01 +-2.21212121212121e+01 -7.68984208143711e-01 2.26151218777467e-01 2.66787136053718e-01 +-2.15151515151515e+01 -7.98558741205574e-01 2.18978684775324e-01 2.59268734046189e-01 +-2.09090909090909e+01 -8.39976990506764e-01 2.12754419878834e-01 2.46412877782449e-01 +-2.03030303030303e+01 -8.77626065799621e-01 2.06530154982344e-01 2.32873392185209e-01 +-1.96969696969697e+01 -9.12482277726115e-01 2.00406617873157e-01 2.16079231533506e-01 +-1.90909090909091e+01 -9.44653374099275e-01 1.94383802853063e-01 1.96196944890485e-01 +-1.84848484848485e+01 -9.76556738297402e-01 1.88868061750279e-01 1.76251855690617e-01 +-1.78787878787879e+01 -1.00830988060465e+00 1.83317104202353e-01 1.56918611734039e-01 +-1.72727272727273e+01 -1.03997095936839e+00 1.76526361566991e-01 1.37892024373634e-01 +-1.66666666666667e+01 -1.07157049021422e+00 1.70932183497624e-01 1.18865299601930e-01 +-1.60606060606061e+01 -1.10312717894668e+00 1.65593044673498e-01 9.98384624039651e-02 +-1.54545454545455e+01 -1.11507119669234e+00 1.58446673227857e-01 8.41684149093784e-02 +-1.48484848484848e+01 -1.11477271836942e+00 1.50207476871942e-01 7.03417694480957e-02 +-1.42424242424242e+01 -1.08423257216199e+00 1.39348090503607e-01 6.20173634895011e-02 +-1.36363636363636e+01 -1.04896032877406e+00 1.28119902100447e-01 5.40305604199166e-02 +-1.30303030303030e+01 -1.01046372636334e+00 1.16637431776633e-01 4.49260984726437e-02 +-1.24242424242424e+01 -9.69201936614847e-01 1.05499178414566e-01 3.32219061711730e-02 +-1.18181818181818e+01 -9.27767400425763e-01 9.49119646912448e-02 2.16483145014490e-02 +-1.12121212121212e+01 -8.86480598336731e-01 8.55891565143775e-02 1.06380104995937e-02 +-1.06060606060606e+01 -8.43514329482308e-01 7.70087578463476e-02 1.14934323347435e-03 +-1.00000000000000e+01 -7.98856262424989e-01 6.88029421594717e-02 -7.48514667045178e-03 +-9.39393939393939e+00 -7.63413220908471e-01 5.72619896948118e-02 -1.75515357315967e-02 +-8.78787878787879e+00 -7.36855164567028e-01 4.49241428048966e-02 -2.67299768784618e-02 +-8.18181818181818e+00 -7.21915221248136e-01 3.22666539335863e-02 -3.43270785756021e-02 +-7.57575757575758e+00 -6.80107790322963e-01 2.47696277944221e-02 -3.79455763749705e-02 +-6.96969696969697e+00 -6.25477329057538e-01 2.00640152396707e-02 -4.00917938604969e-02 +-6.36363636363636e+00 -5.45385415536934e-01 1.76703500104717e-02 -4.47595761821227e-02 +-5.75757575757576e+00 -4.65240863542729e-01 1.56676325439870e-02 -4.94624634693340e-02 +-5.15151515151515e+00 -3.85177304810552e-01 1.41170830647471e-02 -5.47806233959061e-02 +-4.54545454545454e+00 -3.05186013364708e-01 1.29299720858053e-02 -6.00838561640560e-02 +-3.93939393939394e+00 -2.25496618815856e-01 1.19194070246950e-02 -6.52622261528225e-02 +-3.33333333333333e+00 -1.50095854632385e-01 1.14661881877472e-02 -7.00888229733615e-02 +-2.72727272727273e+00 -7.44807687769198e-02 1.10712748312864e-02 -7.44803490024561e-02 +-2.12121212121212e+00 1.36241455738510e-03 1.06994983826237e-02 -7.84888091237353e-02 +-1.51515151515152e+00 7.79762724684800e-02 1.04764559842521e-02 -8.22769309796209e-02 +-9.09090909090912e-01 1.55093196357546e-01 1.03282187235360e-02 -8.59707384355398e-02 +-3.03030303030302e-01 2.33690956667381e-01 1.03497391513504e-02 -8.95788413712978e-02 + 3.03030303030302e-01 3.12230375322369e-01 1.03960832854878e-02 -9.29631294177707e-02 + 9.09090909090912e-01 3.90723642801794e-01 1.04626363547074e-02 -9.61417302922719e-02 + 1.51515151515152e+00 4.69223374488536e-01 1.05181765096339e-02 -9.91269841658500e-02 + 2.12121212121212e+00 5.47419021984281e-01 1.05986866302366e-02 -1.01951326898863e-01 + 2.72727272727273e+00 6.24353465324347e-01 1.07913520395363e-02 -1.04285374966365e-01 + 3.33333333333333e+00 7.00719049213690e-01 1.09882631518878e-02 -1.06367221462522e-01 + 3.93939393939394e+00 7.76662113860127e-01 1.11995924883540e-02 -1.08233532083904e-01 + 4.54545454545455e+00 8.51062527788879e-01 1.14677130840408e-02 -1.09981051673887e-01 + 5.15151515151515e+00 9.24618318776539e-01 1.17484143214346e-02 -1.11607861589439e-01 + 5.75757575757576e+00 9.96131045922850e-01 1.20661413484365e-02 -1.12922063002211e-01 + 6.36363636363637e+00 1.06530124476682e+00 1.24411013682114e-02 -1.13971538180268e-01 + 6.96969696969697e+00 1.13294924210721e+00 1.28499924886479e-02 -1.14845663241843e-01 + 7.57575757575757e+00 1.19647826401428e+00 1.33185723521347e-02 -1.15548552499834e-01 + 8.18181818181818e+00 1.25852214595514e+00 1.37822042010170e-02 -1.16225412192196e-01 + 8.78787878787879e+00 1.31953258382690e+00 1.42014660644829e-02 -1.16973536925898e-01 + 9.39393939393939e+00 1.37722282574832e+00 1.52499336492677e-02 -1.16582058795787e-01 + 1.00000000000000e+01 1.42782587729733e+00 1.66203055937069e-02 -1.15506211836930e-01 + 1.06060606060606e+01 1.46349417020859e+00 1.89049864855517e-02 -1.13428166197566e-01 + 1.12121212121212e+01 1.48851533807067e+00 2.17360570752516e-02 -1.11086533657004e-01 + 1.18181818181818e+01 1.49375899629952e+00 2.51530002017571e-02 -1.08182154414350e-01 + 1.24242424242424e+01 1.39019183027460e+00 4.01241150571406e-02 -1.10396226977541e-01 + 1.30303030303030e+01 1.23558289690220e+00 5.95330302498055e-02 -1.14566124306707e-01 + 1.36363636363636e+01 1.17983620766855e+00 6.99436564860179e-02 -1.13107355391663e-01 + 1.42424242424242e+01 1.13261025086269e+00 8.02708219712224e-02 -1.11811426810697e-01 + 1.48484848484848e+01 1.10434568242928e+00 9.05273912159466e-02 -1.10627750277284e-01 + 1.54545454545455e+01 1.08509274406338e+00 1.01044358671353e-01 -1.11196367879537e-01 + 1.60606060606061e+01 1.06957515718470e+00 1.11649937873699e-01 -1.12390832093296e-01 + 1.66666666666667e+01 1.06064834245443e+00 1.22271986435775e-01 -1.14792794654718e-01 + 1.72727272727273e+01 1.05566858193663e+00 1.33123890508199e-01 -1.17423076146692e-01 + 1.78787878787879e+01 1.05551304883942e+00 1.44256732007905e-01 -1.20332417004491e-01 + 1.84848484848485e+01 1.06725149416938e+00 1.56758954022331e-01 -1.23671200892881e-01 + 1.90909090909091e+01 1.08077437232159e+00 1.69418290548337e-01 -1.27335467738334e-01 + 1.96969696969697e+01 1.08755966688782e+00 1.81027946977387e-01 -1.32236261105666e-01 + 2.03030303030303e+01 1.09235894047421e+00 1.92457859565650e-01 -1.37361247840428e-01 + 2.09090909090909e+01 1.09517208072444e+00 2.03708018144370e-01 -1.42882710356362e-01 + 2.15151515151515e+01 1.09798522097467e+00 2.14958176723090e-01 -1.48463527012242e-01 + 2.21212121212121e+01 1.09854840217806e+00 2.26151218777467e-01 -1.53912838053508e-01 + 2.27272727272727e+01 1.09011406223620e+00 2.37115853503168e-01 -1.58878474315141e-01 + 2.33333333333333e+01 1.08167972229433e+00 2.48080488228869e-01 -1.63885629560299e-01 + 2.39393939393939e+01 1.07324538235247e+00 2.59045122954570e-01 -1.69134105044946e-01 + 2.45454545454545e+01 1.06649517893070e+00 2.70648995111257e-01 -1.73708687311479e-01 + 2.51515151515151e+01 1.05993209776363e+00 2.82323892121304e-01 -1.78208394164471e-01 + 2.57575757575758e+01 1.05336901659657e+00 2.93998789131352e-01 -1.82708101017462e-01 + 2.63636363636364e+01 1.04756481639234e+00 3.06065849632931e-01 -1.86905429493079e-01 + 2.69696969696970e+01 1.04226661544969e+00 3.18394393090142e-01 -1.90901141057530e-01 + 2.75757575757576e+01 1.03696841450705e+00 3.30722936547354e-01 -1.94896852621981e-01 + 2.81818181818182e+01 1.03191481277606e+00 3.43229153621248e-01 -1.98788509538092e-01 + 2.87878787878788e+01 1.02743189358122e+00 3.56149906905165e-01 -2.02437393101785e-01 + 2.93939393939394e+01 1.02294897438639e+00 3.69070660189083e-01 -2.06086276665478e-01 + 3.00000000000000e+01 1.01846605519156e+00 3.81991413473000e-01 -2.09735160229171e-01 + 3.30000000000000e+01 9.98896269436472e-01 4.49336693515259e-01 -2.26306031891365e-01 + 3.60000000000000e+01 9.79942808607176e-01 5.19513505734105e-01 -2.41883781570832e-01 + 3.90000000000000e+01 9.59552820645265e-01 5.92370007881034e-01 -2.56418564967551e-01 + 4.20000000000000e+01 9.35459598863631e-01 6.66888419508008e-01 -2.70550711580551e-01 + 4.50000000000000e+01 9.10032841705360e-01 7.41820452687947e-01 -2.84583661386136e-01 + 4.80000000000000e+01 8.77291164853731e-01 8.16681742398572e-01 -2.98125199456282e-01 + 5.10000000000000e+01 8.40327861925211e-01 8.89991063288168e-01 -3.11430203584398e-01 + 5.40000000000000e+01 7.94921035444153e-01 9.60196346763153e-01 -3.24242564733735e-01 + 5.70000000000000e+01 7.49514555844441e-01 1.03040109391122e+00 -3.37060914767786e-01 + 6.00000000000000e+01 7.04108249684082e-01 1.10060557289787e+00 -3.49883096668555e-01 + 6.30000000000000e+01 6.42668579003910e-01 1.15756816795312e+00 -3.61391087463078e-01 + 6.60000000000000e+01 5.81228770892357e-01 1.21453064950441e+00 -3.72900577797390e-01 + 6.90000000000000e+01 5.19788962780805e-01 1.27149313105570e+00 -3.84410594625320e-01 + 7.20000000000000e+01 4.50734175503690e-01 1.31498403890358e+00 -3.94650756300015e-01 + 7.50000000000000e+01 3.77872054532562e-01 1.35173943568081e+00 -4.04254594429255e-01 + 7.80000000000000e+01 3.05008674950305e-01 1.38849525364560e+00 -4.13856378244412e-01 + 8.10000000000000e+01 2.30789950548293e-01 1.41700503284675e+00 -4.22588303462247e-01 + 8.40000000000000e+01 1.53860630065887e-01 1.42902330372378e+00 -4.29581922692123e-01 + 8.70000000000000e+01 7.69303218853695e-02 1.44104166641377e+00 -4.36570514980957e-01 + 9.00000000000000e+01 -3.36101235559296e-07 1.45305992499009e+00 -4.43554018258070e-01 + 9.30000000000000e+01 -5.38512980694728e-02 1.44104165411306e+00 -4.46821429870465e-01 + 9.60000000000000e+01 -1.07702265733195e-01 1.42902333732993e+00 -4.50090063193436e-01 + 9.90000000000000e+01 -1.61553244788092e-01 1.41700492873292e+00 -4.53359826724784e-01 + 1.02000000000000e+02 -2.13506123000612e-01 1.38849507562982e+00 -4.53358356880233e-01 + 1.05000000000000e+02 -2.64509971345682e-01 1.35173967885259e+00 -4.51721761227933e-01 + 1.08000000000000e+02 -3.15513980484258e-01 1.31498386088960e+00 -4.50085315220303e-01 + 1.11000000000000e+02 -3.63852515987308e-01 1.27149263759476e+00 -4.47194708590916e-01 + 1.14000000000000e+02 -4.06860185400029e-01 1.21453080878140e+00 -4.41794921939120e-01 + 1.17000000000000e+02 -4.49867900921898e-01 1.15756854481392e+00 -4.36395234719870e-01 + 1.20000000000000e+02 -4.92875617551808e-01 1.10060603736703e+00 -4.30995807908883e-01 + 1.23000000000000e+02 -5.24660391861842e-01 1.03040155838038e+00 -4.23756434063717e-01 + 1.26000000000000e+02 -5.56445087582313e-01 9.60196811237631e-01 -4.16516996565852e-01 + 1.29000000000000e+02 -5.88229626117782e-01 8.89991527762645e-01 -4.09277210165741e-01 + 1.32000000000000e+02 -6.12397285385553e-01 8.16658429255322e-01 -4.02686723110960e-01 + 1.35000000000000e+02 -6.32756514043044e-01 7.41761426946880e-01 -3.96420479648652e-01 + 1.38000000000000e+02 -6.53114909413893e-01 6.66865106551800e-01 -3.90153798231996e-01 + 1.41000000000000e+02 -6.71310960202625e-01 5.93439880036427e-01 -3.85803144277468e-01 + 1.44000000000000e+02 -6.85182304280847e-01 5.22956853217613e-01 -3.85284327936909e-01 + 1.47000000000000e+02 -6.99053142386901e-01 4.52474247296891e-01 -3.84763389697547e-01 + 1.50000000000000e+02 -7.12923727515902e-01 3.81991851817701e-01 -3.84240435098614e-01 + 1.53000000000000e+02 -7.17713468565102e-01 3.27562673383999e-01 -4.00044506289342e-01 + 1.56000000000000e+02 -7.22503170158526e-01 2.73133681485946e-01 -4.15858223301289e-01 + 1.59000000000000e+02 -7.28127146175927e-01 2.18704987836167e-01 -4.31681847835051e-01 + 1.62000000000000e+02 -6.57546925365099e-01 1.80505932981753e-01 -4.49567289106761e-01 + 1.65000000000000e+02 -5.47955571734396e-01 1.50421834782562e-01 -4.68480081499263e-01 + 1.68000000000000e+02 -4.33508829076636e-01 1.20337481324609e-01 -4.87391973738006e-01 + 1.71000000000000e+02 -3.23710952534405e-01 9.02531541751285e-02 -4.50000513056908e-01 + 1.74000000000000e+02 -2.15807282191796e-01 6.01688796438182e-02 -2.99999717902353e-01 + 1.77000000000000e+02 -1.07173368611120e-01 4.95765701106933e-02 -1.48970519644697e-01 + 1.80000000000000e+02 0.00000000000000e+00 4.87439042124992e-02 0.00000000000000e+00 diff --git a/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_14.dat b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_14.dat new file mode 100644 index 00000000..229833e5 --- /dev/null +++ b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_14.dat @@ -0,0 +1,254 @@ +! ------------ AirfoilInfo v1.01.x Input File ---------------------------------- +! AeroElasticSE FAST driver +! line +! line +! ------------------------------------------------------------------------------ +DEFAULT InterpOrd ! Interpolation order to use for quasi-steady table lookup {1=linear; 3=cubic spline; "default"} [default=3] +1 NonDimArea ! The non-dimensional area of the airfoil (area/chord^2) (set to 1.0 if unsure or unneeded) +@"NREL-2p8-127_AF14_Coords.txt" NumCoords ! The number of coordinates in the airfoil shape file. Set to zero if coordinates not included. +AF14_BL.txt BL_file ! The file name including the boundary layer characteristics of the profile. Ignored if the aeroacoustic module is not called. +1 NumTabs ! Number of airfoil tables in this file. Each table must have lines for Re and Ctrl. +! ------------------------------------------------------------------------------ +! data for table 1 +! ------------------------------------------------------------------------------ +6.000000 Re ! Reynolds number in millions +0 Ctrl ! Control setting (must be 0 for current AirfoilInfo) +True InclUAdata ! Is unsteady aerodynamics data included in this table? If TRUE, then include 30 UA coefficients below this line +!........................................ +-2.166094 alpha0 ! 0-lift angle of attack, depends on airfoil. +11.851014 alpha1 ! Angle of attack at f=0.7, (approximately the stall angle) for AOA>alpha0. (deg) +-9.637248 alpha2 ! Angle of attack at f=0.7, (approximately the stall angle) for AOA1] +0.000000 S2 ! Constant in the f curve best-fit for AOA> alpha1; by definition it depends on the airfoil. [ignored if UAMod<>1] +0.000000 S3 ! Constant in the f curve best-fit for alpha2<=AOA< alpha0; by definition it depends on the airfoil. [ignored if UAMod<>1] +0.000000 S4 ! Constant in the f curve best-fit for AOA< alpha2; by definition it depends on the airfoil. [ignored if UAMod<>1] +1.502705 Cn1 ! Critical value of C0n at leading edge separation. It should be extracted from airfoil data at a given Mach and Reynolds number. It can be calculated from the static value of Cn at either the break in the pitching moment or the loss of chord force at the onset of stall. It is close to the condition of maximum lift of the airfoil at low Mach numbers. +-1.198117 Cn2 ! As Cn1 for negative AOAs. +Default St_sh ! Strouhal's shedding frequency constant. [default = 0.19] +0.010692 Cd0 ! 2D drag coefficient value at 0-lift. +-0.084655 Cm0 ! 2D pitching moment coefficient about 1/4-chord location, at 0-lift, positive if nose up. [If the aerodynamics coefficients table does not include a column for Cm, this needs to be set to 0.0] +0.000000 k0 ! Constant in the \hat(x)_cp curve best-fit; = (\hat(x)_AC-0.25). [ignored if UAMod<>1] +0.000000 k1 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k2 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k3 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k1_hat ! Constant in the expression of Cc due to leading edge vortex effects. [ignored if UAMod<>1] +Default x_cp_bar ! Constant in the expression of \hat(x)_cp^v. [ignored if UAMod<>1, default = 0.2] +Default UACutout ! Angle of attack above which unsteady aerodynamics are disabled (deg). [Specifying the string "Default" sets UACutout to 45 degrees] +Default filtCutOff ! Cut-off frequency (-3 dB corner frequency) for low-pass filtering the AoA input to UA, as well as the 1st and 2nd derivatives (Hz) [default = 20] +!........................................ +! Table of aerodynamics coefficients +200 NumAlf ! Number of data lines in the following table +! Alpha Cl Cd Cm +! (deg) (-) (-) (-) +-1.80000000000000e+02 0.00000000000000e+00 4.74971586892991e-02 0.00000000000000e+00 +-1.77000000000000e+02 1.11000230721027e-01 4.74971586892991e-02 1.19348662665291e-01 +-1.74000000000000e+02 2.23249498352695e-01 5.69965146964868e-02 2.39999774321882e-01 +-1.71000000000000e+02 3.34875005612777e-01 8.54948945736924e-02 3.60000410445527e-01 +-1.68000000000000e+02 4.46351865610983e-01 1.14102183123101e-01 3.18009867522619e-01 +-1.65000000000000e+02 5.57999076618718e-01 1.42763924737488e-01 1.95025625752222e-01 +-1.62000000000000e+02 6.68256570415867e-01 1.71426528385083e-01 7.20405402903902e-02 +-1.59000000000000e+02 7.38112012967269e-01 2.08990990812950e-01 -9.03147344265643e-03 +-1.56000000000000e+02 7.28701413125268e-01 2.64358869655133e-01 -4.58368783527860e-03 +-1.53000000000000e+02 7.20014801391652e-01 3.19726771476650e-01 4.84852864421045e-04 +-1.50000000000000e+02 7.11327966966767e-01 3.75094720564407e-01 5.41799540089436e-03 +-1.47000000000000e+02 6.97644694809602e-01 4.45815984052867e-01 2.02835508949186e-02 +-1.44000000000000e+02 6.83961170390853e-01 5.16537495536617e-01 3.51512653382985e-02 +-1.41000000000000e+02 6.70277141430926e-01 5.87259503028655e-01 5.00215815438595e-02 +-1.38000000000000e+02 6.52223041697912e-01 6.60960643393727e-01 6.52179053138514e-02 +-1.35000000000000e+02 6.31983915443519e-01 7.36151344151820e-01 8.05776041224766e-02 +-1.32000000000000e+02 6.11743957269201e-01 8.11342840122296e-01 9.59393162430393e-02 +-1.29000000000000e+02 5.87682487226497e-01 8.84986078503406e-01 1.11444964032245e-01 +-1.26000000000000e+02 5.55977975337812e-01 9.55532794347773e-01 1.27236023845822e-01 +-1.23000000000000e+02 5.24273305652762e-01 1.02607897125153e+00 1.43028582986147e-01 +-1.20000000000000e+02 4.92568557072479e-01 1.09662487869506e+00 1.58822953785748e-01 +-1.17000000000000e+02 4.49613275538441e-01 1.15396443469656e+00 1.73777165711677e-01 +-1.14000000000000e+02 4.06657958215625e-01 1.21130374584807e+00 1.88732854747424e-01 +-1.11000000000000e+02 3.63702613318511e-01 1.26864261896506e+00 2.03690155444885e-01 +-1.08000000000000e+02 3.15401526057875e-01 1.31252774478765e+00 2.16985072342206e-01 +-1.05000000000000e+02 2.64427526911241e-01 1.34968589451878e+00 2.29449925939083e-01 +-1.02000000000000e+02 2.13453578289375e-01 1.38684361845383e+00 2.41917717292569e-01 +-9.90000000000000e+01 1.61523894481612e-01 1.41576001404799e+00 2.53026853626378e-01 +-9.60000000000000e+01 1.07682698904138e-01 1.42819339598511e+00 2.61414906151363e-01 +-9.30000000000000e+01 5.38415146430987e-02 1.44062668293820e+00 2.69809084986757e-01 +-9.00000000000000e+01 3.36040174186750e-07 1.45305992240014e+00 2.78212559061635e-01 +-8.70000000000000e+01 -5.38414595366295e-02 1.44062669566363e+00 2.81853755036713e-01 +-8.40000000000000e+01 -1.07682849456116e-01 1.42819336121861e+00 2.85569122512613e-01 +-8.10000000000000e+01 -1.61523428062735e-01 1.41576012175667e+00 2.89419982005163e-01 +-7.80000000000000e+01 -2.13453331409509e-01 1.38684379841819e+00 2.89665265635515e-01 +-7.50000000000000e+01 -2.64427864151593e-01 1.34968564868523e+00 2.88138738774038e-01 +-7.20000000000000e+01 -3.15401279183096e-01 1.31252792475019e+00 2.86609458179388e-01 +-6.90000000000000e+01 -3.63702241195888e-01 1.26864311569235e+00 2.83820667109906e-01 +-6.60000000000000e+01 -4.06658078327606e-01 1.21130358551679e+00 2.78515251076842e-01 +-6.30000000000000e+01 -4.49613559728479e-01 1.15396405534123e+00 2.73204848612241e-01 +-6.00000000000000e+01 -4.92568766829435e-01 1.09662441196703e+00 2.67888882389067e-01 +-5.70000000000000e+01 -5.24273515409718e-01 1.02607850452350e+00 2.60728337244673e-01 +-5.40000000000000e+01 -5.55978185093202e-01 9.55532327614396e-01 2.53559556903730e-01 +-5.10000000000000e+01 -5.87682696981887e-01 8.84985611770030e-01 2.46380928095060e-01 +-4.80000000000000e+01 -6.13458630295659e-01 8.11357652574190e-01 2.39383508326475e-01 +-4.50000000000000e+01 -6.36270369602626e-01 7.36189121222556e-01 2.32464914094013e-01 +-4.20000000000000e+01 -6.53937701306032e-01 6.60975455724981e-01 2.26919127213316e-01 +-3.90000000000000e+01 -6.70664549725515e-01 5.86181715938499e-01 2.21997712524231e-01 +-3.60000000000000e+01 -6.84774756509486e-01 5.13070549905569e-01 2.19442879100228e-01 +-3.30000000000000e+01 -6.97852537348206e-01 4.42658498578043e-01 2.19788443952018e-01 +-3.00000000000000e+01 -7.11328064353672e-01 3.75094280797430e-01 2.23361039140397e-01 +-2.93939393939394e+01 -7.14415682762428e-01 3.62132722086743e-01 2.24952236186361e-01 +-2.87878787878788e+01 -7.17503301171185e-01 3.49171163376055e-01 2.26543433232325e-01 +-2.81818181818182e+01 -7.20590919579942e-01 3.36209604665368e-01 2.28134630278289e-01 +-2.75757575757576e+01 -7.24071834030542e-01 3.23664369017940e-01 2.30343477172995e-01 +-2.69696969696970e+01 -7.27721318387681e-01 3.11297572847134e-01 2.32817053854427e-01 +-2.63636363636364e+01 -7.31370802744820e-01 2.98930776676328e-01 2.35290630535858e-01 +-2.57575757575758e+01 -7.35371080478430e-01 2.86826529936594e-01 2.38225234034872e-01 +-2.51515151515151e+01 -7.39897466519906e-01 2.75116046152996e-01 2.41851270312120e-01 +-2.45454545454545e+01 -7.44423852561381e-01 2.63405562369399e-01 2.45477306589367e-01 +-2.39393939393939e+01 -7.49080204989271e-01 2.51766369918421e-01 2.49257235504190e-01 +-2.33333333333333e+01 -7.54906280057009e-01 2.40768813263367e-01 2.54422227951541e-01 +-2.27272727272727e+01 -7.60732355124748e-01 2.29771256608312e-01 2.60428793385145e-01 +-2.21212121212121e+01 -7.66558430192487e-01 2.18773699953258e-01 2.65754286761814e-01 +-2.15151515151515e+01 -8.00687554276612e-01 2.12395791755905e-01 2.54131477053226e-01 +-2.09090909090909e+01 -8.47011591503202e-01 2.07173092829286e-01 2.36349555357985e-01 +-2.03030303030303e+01 -8.90594276628836e-01 2.01950393902668e-01 2.17964558879003e-01 +-1.96969696969697e+01 -9.33116480486079e-01 1.96765628796972e-01 1.98214287245217e-01 +-1.90909090909091e+01 -9.74622494568323e-01 1.91618795366269e-01 1.77245579244523e-01 +-1.84848484848485e+01 -1.01601768577475e+00 1.86919414620951e-01 1.56221773196698e-01 +-1.78787878787879e+01 -1.05735116332665e+00 1.82188959514290e-01 1.35737748819307e-01 +-1.72727272727273e+01 -1.09864750288064e+00 1.76364686193561e-01 1.15524161434742e-01 +-1.66666666666667e+01 -1.13991853932663e+00 1.71295280735592e-01 9.53103144961163e-02 +-1.60606060606061e+01 -1.18117196285153e+00 1.66429521167139e-01 7.50962551972795e-02 +-1.54545454545455e+01 -1.19791272454831e+00 1.59575377638483e-01 5.91097556474128e-02 +-1.48484848484848e+01 -1.19934186806973e+00 1.51502853954205e-01 4.54449853411950e-02 +-1.42424242424242e+01 -1.16297897530355e+00 1.40460445425891e-01 3.82990945588821e-02 +-1.36363636363636e+01 -1.12077036373998e+00 1.29002431424042e-01 3.11065404436185e-02 +-1.30303030303030e+01 -1.07463320183473e+00 1.17263267706531e-01 2.26980761363050e-02 +-1.24242424242424e+01 -1.02518157920182e+00 1.05918643160515e-01 1.17933498379386e-02 +-1.18181818181818e+01 -9.75681942398755e-01 9.51959685529269e-02 1.19873623725293e-03 +-1.12121212121212e+01 -9.26571076805030e-01 8.58848934178665e-02 -8.41861521656647e-03 +-1.06060606060606e+01 -8.75664896114804e-01 7.74090431182947e-02 -1.63777998285526e-02 +-1.00000000000000e+01 -8.23237071758609e-01 6.93728235267388e-02 -2.34138528773980e-02 +-9.39393939393939e+00 -7.82111343672048e-01 5.75636308912248e-02 -3.21020160083091e-02 +-8.78787878787879e+00 -7.51375159974407e-01 4.47516034625548e-02 -3.98906956582438e-02 +-8.18181818181818e+00 -7.35088054943470e-01 3.08041630438302e-02 -4.60682064471990e-02 +-7.57575757575758e+00 -6.92836122752420e-01 2.31579933295670e-02 -4.89829934537834e-02 +-6.96969696969697e+00 -6.37949933369482e-01 1.87032507714761e-02 -5.07384454242695e-02 +-6.36363636363636e+00 -5.54161342148495e-01 1.67784052774049e-02 -5.53503816254145e-02 +-5.75757575757576e+00 -4.70840124165288e-01 1.50845427200835e-02 -5.98951476736281e-02 +-5.15151515151515e+00 -3.88292011066822e-01 1.36982538638481e-02 -6.45572843794330e-02 +-4.54545454545454e+00 -3.06502440552051e-01 1.26562227449715e-02 -6.91008881961310e-02 +-3.93939393939394e+00 -2.25310842700356e-01 1.17673191515673e-02 -7.35346491057446e-02 +-3.33333333333333e+00 -1.47988215381915e-01 1.13325276777439e-02 -7.76194041395815e-02 +-2.72727272727273e+00 -7.09984158942061e-02 1.09783067702849e-02 -8.14085077704442e-02 +-2.12121212121212e+00 5.67824274921396e-03 1.06696224794102e-02 -8.49142606714796e-02 +-1.51515151515152e+00 8.26102586756291e-02 1.04667274124626e-02 -8.82711832196438e-02 +-9.09090909090912e-01 1.59969016769918e-01 1.03323320303745e-02 -9.15655050496302e-02 +-3.03030303030302e-01 2.38974448513455e-01 1.03900461416016e-02 -9.47661275562079e-02 + 3.03030303030302e-01 3.17646859605712e-01 1.04649254982203e-02 -9.77901212356652e-02 + 9.09090909090912e-01 3.96007393557534e-01 1.05511605199152e-02 -1.00651121145792e-01 + 1.51515151515152e+00 4.74169429973799e-01 1.05752495413395e-02 -1.03293525376690e-01 + 2.12121212121212e+00 5.51911940760023e-01 1.06224929903068e-02 -1.05813765929291e-01 + 2.72727272727273e+00 6.28056580841275e-01 1.08108555850528e-02 -1.07977517357485e-01 + 3.33333333333333e+00 7.03798053899655e-01 1.09879017716880e-02 -1.09916646422344e-01 + 3.93939393939394e+00 7.79276493869128e-01 1.11758838962833e-02 -1.11658275595353e-01 + 4.54545454545455e+00 8.53499796067138e-01 1.14129478363666e-02 -1.13253311951308e-01 + 5.15151515151515e+00 9.26946560290491e-01 1.16638391697767e-02 -1.14737019623995e-01 + 5.75757575757576e+00 9.98458448466187e-01 1.19568385022413e-02 -1.15939256762654e-01 + 6.36363636363637e+00 1.06804425733062e+00 1.22991453288649e-02 -1.16892495532205e-01 + 6.96969696969697e+00 1.13638020854557e+00 1.26698916273089e-02 -1.17681562497719e-01 + 7.57575757575757e+00 1.20139147533564e+00 1.30839223585554e-02 -1.18207998448365e-01 + 8.18181818181818e+00 1.26525870625966e+00 1.34927417386065e-02 -1.18675618171796e-01 + 8.78787878787879e+00 1.32856174203142e+00 1.38637786532075e-02 -1.19120015634172e-01 + 9.39393939393939e+00 1.38894849360344e+00 1.46729594502212e-02 -1.18422993276735e-01 + 1.00000000000000e+01 1.44308909541765e+00 1.56494510556849e-02 -1.17051335409731e-01 + 1.06060606060606e+01 1.48423802370368e+00 1.71908084497653e-02 -1.14598756389549e-01 + 1.12121212121212e+01 1.51610502455934e+00 1.91222908592098e-02 -1.11779817617528e-01 + 1.18181818181818e+01 1.53072866564893e+00 2.16025680835697e-02 -1.08254794802547e-01 + 1.24242424242424e+01 1.39977849156389e+00 3.79528706066007e-02 -1.10603299151591e-01 + 1.30303030303030e+01 1.21617535220138e+00 5.95675147584135e-02 -1.15202550970118e-01 + 1.36363636363636e+01 1.15533504132719e+00 6.93992690943369e-02 -1.13563572716609e-01 + 1.42424242424242e+01 1.10480169457590e+00 7.89367459341939e-02 -1.12086468683529e-01 + 1.48484848484848e+01 1.07517912705030e+00 8.81134671681645e-02 -1.10736245553130e-01 + 1.54545454545455e+01 1.05513703714054e+00 9.73441034120854e-02 -1.10445332098790e-01 + 1.60606060606061e+01 1.03909979751391e+00 1.06615031950527e-01 -1.10471629053083e-01 + 1.66666666666667e+01 1.03037285182419e+00 1.16086945222589e-01 -1.11452522736188e-01 + 1.72727272727273e+01 1.02598020440334e+00 1.25858967571876e-01 -1.12862502655475e-01 + 1.78787878787879e+01 1.02688508760461e+00 1.35997793709910e-01 -1.14796926748810e-01 + 1.84848484848485e+01 1.04050556314885e+00 1.47897334941441e-01 -1.18027092927592e-01 + 1.90909090909091e+01 1.05662971405014e+00 1.60210090125818e-01 -1.21765865016242e-01 + 1.96969696969697e+01 1.06892917336845e+00 1.72370385761586e-01 -1.26551733685257e-01 + 2.03030303030303e+01 1.07836210245173e+00 1.84226855703769e-01 -1.31723435235985e-01 + 2.09090909090909e+01 1.08492833913008e+00 1.95779482763855e-01 -1.37432962053028e-01 + 2.15151515151515e+01 1.09149457580843e+00 2.07332109823942e-01 -1.43194849094184e-01 + 2.21212121212121e+01 1.09508251337799e+00 2.18773699953258e-01 -1.48870391290255e-01 + 2.27272727272727e+01 1.08676031896276e+00 2.29771256608312e-01 -1.54237881279540e-01 + 2.33333333333333e+01 1.07843812454753e+00 2.40768813263367e-01 -1.59641997918361e-01 + 2.39393939393939e+01 1.07011593013229e+00 2.51766369918421e-01 -1.65258999148450e-01 + 2.45454545454545e+01 1.06346338211567e+00 2.63405562369399e-01 -1.70132904338816e-01 + 2.51515151515151e+01 1.05699634637488e+00 2.75116046152996e-01 -1.74924245078642e-01 + 2.57575757575758e+01 1.05052931063409e+00 2.86826529936594e-01 -1.79715585818468e-01 + 2.63636363636364e+01 1.04481382943098e+00 2.98930776676328e-01 -1.84171410304438e-01 + 2.69696969696970e+01 1.03959946244701e+00 3.11297572847134e-01 -1.88403522528518e-01 + 2.75757575757576e+01 1.03438509546304e+00 3.23664369017940e-01 -1.92635634752598e-01 + 2.81818181818182e+01 1.02941249540321e+00 3.36209604665368e-01 -1.96751514558490e-01 + 2.87878787878788e+01 1.02500396977555e+00 3.49171163376055e-01 -2.00596208653092e-01 + 2.93939393939394e+01 1.02059544414789e+00 3.62132722086743e-01 -2.04440902747695e-01 + 3.00000000000000e+01 1.01618691852022e+00 3.75094280797430e-01 -2.08285596842297e-01 + 3.30000000000000e+01 9.96930791089291e-01 4.42658498578043e-01 -2.25638690746125e-01 + 3.60000000000000e+01 9.78250493475424e-01 5.13070549905569e-01 -2.41866371031337e-01 + 3.90000000000000e+01 9.58092634837620e-01 5.86181715938499e-01 -2.56756566563372e-01 + 4.20000000000000e+01 9.34197243420856e-01 6.60975455724981e-01 -2.71189386382951e-01 + 4.50000000000000e+01 9.08958131052610e-01 7.36189121222556e-01 -2.85513863759938e-01 + 4.80000000000000e+01 8.76369360506042e-01 8.11357652574190e-01 -2.99318564738472e-01 + 5.10000000000000e+01 8.39546103316861e-01 8.84985611770030e-01 -3.12885528690573e-01 + 5.40000000000000e+01 7.94253600616922e-01 9.55532327614396e-01 -3.25953209472103e-01 + 5.70000000000000e+01 7.48961443924963e-01 1.02607850452350e+00 -3.39030396022098e-01 + 6.00000000000000e+01 7.03669460235677e-01 1.09662441196703e+00 -3.52114744115643e-01 + 6.30000000000000e+01 6.42304649985047e-01 1.15396405534123e+00 -3.63896004000846e-01 + 6.60000000000000e+01 5.80939701964786e-01 1.21130358551679e+00 -3.75682451037757e-01 + 6.90000000000000e+01 5.19574753944523e-01 1.26864311569235e+00 -3.87472927093907e-01 + 7.20000000000000e+01 4.50573500357888e-01 1.31252792475019e+00 -3.98011457008727e-01 + 7.50000000000000e+01 3.77754250313412e-01 1.34968564868523e+00 -4.07925210836086e-01 + 7.80000000000000e+01 3.04933632222489e-01 1.38684379841819e+00 -4.17841195787456e-01 + 8.10000000000000e+01 2.30748068771223e-01 1.41576012175667e+00 -4.26898468755288e-01 + 8.40000000000000e+01 1.53832708821342e-01 1.42819336121861e+00 -4.34236382280660e-01 + 8.70000000000000e+01 7.69163612800006e-02 1.44062669566363e+00 -4.41574423427714e-01 + 9.00000000000000e+01 -3.36040174418520e-07 1.45305992240014e+00 -4.48912349036806e-01 + 9.30000000000000e+01 -5.38415146430987e-02 1.44062668293820e+00 -4.52353830558963e-01 + 9.60000000000000e+01 -1.07682698904138e-01 1.42819339598511e+00 -4.55796422926281e-01 + 9.90000000000000e+01 -1.61523894481612e-01 1.41576001404799e+00 -4.59240045315168e-01 + 1.02000000000000e+02 -2.13453578289375e-01 1.38684361845383e+00 -4.59405772291525e-01 + 1.05000000000000e+02 -2.64427526911242e-01 1.34968589451878e+00 -4.57933058035756e-01 + 1.08000000000000e+02 -3.15401526057875e-01 1.31252774478765e+00 -4.56460500541016e-01 + 1.11000000000000e+02 -3.63702613318511e-01 1.26864261896506e+00 -4.53729817735206e-01 + 1.14000000000000e+02 -4.06657958215626e-01 1.21130374584807e+00 -4.48482124934980e-01 + 1.17000000000000e+02 -4.49613275538441e-01 1.15396443469656e+00 -4.43234672446104e-01 + 1.20000000000000e+02 -4.92568557072479e-01 1.09662487869506e+00 -4.37987618819821e-01 + 1.23000000000000e+02 -5.24273305652762e-01 1.02607897125153e+00 -4.30899900449802e-01 + 1.26000000000000e+02 -5.55977975337812e-01 9.55532794347773e-01 -4.23812474118514e-01 + 1.29000000000000e+02 -5.87682487226498e-01 8.84986078503406e-01 -4.16725057602321e-01 + 1.32000000000000e+02 -6.11743957269202e-01 8.11342840122296e-01 -4.10311145379585e-01 + 1.35000000000000e+02 -6.31983915443519e-01 7.36151344151820e-01 -4.04234114284225e-01 + 1.38000000000000e+02 -6.52223041697912e-01 6.60960643393727e-01 -3.98157422646348e-01 + 1.41000000000000e+02 -6.70277141430926e-01 5.87259503028655e-01 -3.94043626890889e-01 + 1.44000000000000e+02 -6.83961170390853e-01 5.16537495536617e-01 -3.93855328257089e-01 + 1.47000000000000e+02 -6.97644694809602e-01 4.45815984052867e-01 -3.93666633192198e-01 + 1.50000000000000e+02 -7.11327966966768e-01 3.75094720564406e-01 -3.93477629010198e-01 + 1.53000000000000e+02 -7.10555758661770e-01 3.21288604729336e-01 -4.09291401293984e-01 + 1.56000000000000e+02 -7.09783519622452e-01 2.67482711700951e-01 -4.25113789480059e-01 + 1.59000000000000e+02 -7.09747287572277e-01 2.13677185443974e-01 -4.40944959963481e-01 + 1.62000000000000e+02 -6.39242744263654e-01 1.76167844671200e-01 -4.56979587409322e-01 + 1.65000000000000e+02 -5.32702098344237e-01 1.46806734460832e-01 -4.73112741890976e-01 + 1.68000000000000e+02 -4.24165693368368e-01 1.17445360706964e-01 -4.89245046545928e-01 + 1.71000000000000e+02 -3.17540377497210e-01 8.80840526647858e-02 -4.50000513056908e-01 + 1.74000000000000e+02 -2.11693558985589e-01 5.87228760490535e-02 -2.99999717902353e-01 + 1.77000000000000e+02 -1.05275486594639e-01 4.83558379259246e-02 -1.49185828331614e-01 + 1.80000000000000e+02 0.00000000000000e+00 4.74971586892991e-02 0.00000000000000e+00 diff --git a/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_15.dat b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_15.dat new file mode 100644 index 00000000..8a6d71ed --- /dev/null +++ b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_15.dat @@ -0,0 +1,254 @@ +! ------------ AirfoilInfo v1.01.x Input File ---------------------------------- +! AeroElasticSE FAST driver +! line +! line +! ------------------------------------------------------------------------------ +DEFAULT InterpOrd ! Interpolation order to use for quasi-steady table lookup {1=linear; 3=cubic spline; "default"} [default=3] +1 NonDimArea ! The non-dimensional area of the airfoil (area/chord^2) (set to 1.0 if unsure or unneeded) +@"NREL-2p8-127_AF15_Coords.txt" NumCoords ! The number of coordinates in the airfoil shape file. Set to zero if coordinates not included. +AF15_BL.txt BL_file ! The file name including the boundary layer characteristics of the profile. Ignored if the aeroacoustic module is not called. +1 NumTabs ! Number of airfoil tables in this file. Each table must have lines for Re and Ctrl. +! ------------------------------------------------------------------------------ +! data for table 1 +! ------------------------------------------------------------------------------ +6.000000 Re ! Reynolds number in millions +0 Ctrl ! Control setting (must be 0 for current AirfoilInfo) +True InclUAdata ! Is unsteady aerodynamics data included in this table? If TRUE, then include 30 UA coefficients below this line +!........................................ +-2.208961 alpha0 ! 0-lift angle of attack, depends on airfoil. +11.877956 alpha1 ! Angle of attack at f=0.7, (approximately the stall angle) for AOA>alpha0. (deg) +-10.077196 alpha2 ! Angle of attack at f=0.7, (approximately the stall angle) for AOA1] +0.000000 S2 ! Constant in the f curve best-fit for AOA> alpha1; by definition it depends on the airfoil. [ignored if UAMod<>1] +0.000000 S3 ! Constant in the f curve best-fit for alpha2<=AOA< alpha0; by definition it depends on the airfoil. [ignored if UAMod<>1] +0.000000 S4 ! Constant in the f curve best-fit for AOA< alpha2; by definition it depends on the airfoil. [ignored if UAMod<>1] +1.523431 Cn1 ! Critical value of C0n at leading edge separation. It should be extracted from airfoil data at a given Mach and Reynolds number. It can be calculated from the static value of Cn at either the break in the pitching moment or the loss of chord force at the onset of stall. It is close to the condition of maximum lift of the airfoil at low Mach numbers. +-1.245136 Cn2 ! As Cn1 for negative AOAs. +Default St_sh ! Strouhal's shedding frequency constant. [default = 0.19] +0.010644 Cd0 ! 2D drag coefficient value at 0-lift. +-0.090826 Cm0 ! 2D pitching moment coefficient about 1/4-chord location, at 0-lift, positive if nose up. [If the aerodynamics coefficients table does not include a column for Cm, this needs to be set to 0.0] +0.000000 k0 ! Constant in the \hat(x)_cp curve best-fit; = (\hat(x)_AC-0.25). [ignored if UAMod<>1] +0.000000 k1 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k2 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k3 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k1_hat ! Constant in the expression of Cc due to leading edge vortex effects. [ignored if UAMod<>1] +Default x_cp_bar ! Constant in the expression of \hat(x)_cp^v. [ignored if UAMod<>1, default = 0.2] +Default UACutout ! Angle of attack above which unsteady aerodynamics are disabled (deg). [Specifying the string "Default" sets UACutout to 45 degrees] +Default filtCutOff ! Cut-off frequency (-3 dB corner frequency) for low-pass filtering the AoA input to UA, as well as the 1st and 2nd derivatives (Hz) [default = 20] +!........................................ +! Table of aerodynamics coefficients +200 NumAlf ! Number of data lines in the following table +! Alpha Cl Cd Cm +! (deg) (-) (-) (-) +-1.80000000000000e+02 0.00000000000000e+00 4.67684423893836e-02 0.00000000000000e+00 +-1.77000000000000e+02 1.09408903050313e-01 4.67684423893836e-02 1.19449340115019e-01 +-1.74000000000000e+02 2.19827919665962e-01 5.61220773758285e-02 2.39999774321882e-01 +-1.71000000000000e+02 3.29742593401240e-01 8.41832894069106e-02 3.60000410445527e-01 +-1.68000000000000e+02 4.39652946023446e-01 1.12247441543861e-01 3.17657026395814e-01 +-1.65000000000000e+02 5.49568920893405e-01 1.40313063699431e-01 1.94143527053385e-01 +-1.62000000000000e+02 6.59436266220261e-01 1.68379605308450e-01 7.06292113109056e-02 +-1.59000000000000e+02 7.30300487636504e-01 2.05487990755536e-01 -1.10385648721879e-02 +-1.56000000000000e+02 7.23544790871733e-01 2.60679757996445e-01 -8.60356910819995e-03 +-1.53000000000000e+02 7.16970142385750e-01 3.15871546871301e-01 -6.03641287104454e-03 +-1.50000000000000e+02 7.10395253192162e-01 3.71063383075396e-01 -3.53054989193793e-03 +-1.47000000000000e+02 6.96821464496714e-01 4.41924263677891e-01 1.15622643794935e-02 +-1.44000000000000e+02 6.83247423957872e-01 5.12785414225651e-01 2.66551539940038e-02 +-1.41000000000000e+02 6.69672879714259e-01 5.83647104683221e-01 4.17481792755350e-02 +-1.38000000000000e+02 6.51701749637977e-01 6.57509515264151e-01 5.71032192754300e-02 +-1.35000000000000e+02 6.31532335564314e-01 7.32872279819475e-01 7.25892986682547e-02 +-1.32000000000000e+02 6.11362090369567e-01 8.08235905809873e-01 8.80756349445296e-02 +-1.29000000000000e+02 5.87362687378832e-01 8.82060419340625e-01 1.03702753521495e-01 +-1.26000000000000e+02 5.55704950650637e-01 9.52806700636205e-01 1.19611333221862e-01 +-1.23000000000000e+02 5.24047055768739e-01 1.02355244146660e+00 1.35519828983413e-01 +-1.20000000000000e+02 4.92389081812946e-01 1.09429791207450e+00 1.51428303263083e-01 +-1.17000000000000e+02 4.49464448320822e-01 1.15185785100299e+00 1.66519076342545e-01 +-1.14000000000000e+02 4.06539757473919e-01 1.20941754428038e+00 1.81609537109452e-01 +-1.11000000000000e+02 3.63614995985125e-01 1.26697679783968e+00 1.96699434164473e-01 +-1.08000000000000e+02 3.15335797028190e-01 1.31109215764924e+00 2.10144017964703e-01 +-1.05000000000000e+02 2.64379338566390e-01 1.34848546821470e+00 2.22765790368656e-01 +-1.02000000000000e+02 2.13422866177849e-01 1.38587835028935e+00 2.35387244205176e-01 +-9.90000000000000e+01 1.61506739379516e-01 1.41503236786356e+00 2.46653165683191e-01 +-9.60000000000000e+01 1.07671262193915e-01 1.42770829956833e+00 2.55208020338782e-01 +-9.30000000000000e+01 5.38357962810632e-02 1.44038413443613e+00 2.63762460154027e-01 +-9.00000000000000e+01 3.36004484266645e-07 1.45305992088633e+00 2.72316549083834e-01 +-8.70000000000000e+01 -5.38357411804466e-02 1.44038414740981e+00 2.75975908689839e-01 +-8.40000000000000e+01 -1.07671412729903e-01 1.42770826412360e+00 2.79637509125723e-01 +-8.10000000000000e+01 -1.61506273010176e-01 1.41503247767341e+00 2.83303463358523e-01 +-7.80000000000000e+01 -2.13422619382625e-01 1.38587853139263e+00 2.83673895090911e-01 +-7.50000000000000e+01 -2.64379675691045e-01 1.34848522082535e+00 2.82397275634580e-01 +-7.20000000000000e+01 -3.15335550238364e-01 1.31109233875070e+00 2.81119990974020e-01 +-6.90000000000000e+01 -3.63614624127447e-01 1.26697729647612e+00 2.78579207220845e-01 +-6.60000000000000e+01 -4.06539877500383e-01 1.20941738333287e+00 2.73511947958626e-01 +-6.30000000000000e+01 -4.49464732308094e-01 1.15185747018962e+00 2.68443139589274e-01 +-6.00000000000000e+01 -4.92389291260444e-01 1.09429744402618e+00 2.63372775517188e-01 +-5.70000000000000e+01 -5.24047265216237e-01 1.02355197341827e+00 2.56458829905844e-01 +-5.40000000000000e+01 -5.55705160096565e-01 9.52806232582514e-01 2.49542806281396e-01 +-5.10000000000000e+01 -5.87362896824760e-01 8.82059951286934e-01 2.42624285718169e-01 +-4.80000000000000e+01 -6.13081518081798e-01 8.08245749651705e-01 2.35914730168143e-01 +-4.50000000000000e+01 -6.35830677053252e-01 7.32897637152475e-01 2.29306703335177e-01 +-4.20000000000000e+01 -6.53421163894653e-01 6.57519359024154e-01 2.24147571871917e-01 +-3.90000000000000e+01 -6.70067066454672e-01 5.82564691354695e-01 2.19583471937992e-01 +-3.60000000000000e+01 -6.84082341201795e-01 5.09304675599610e-01 2.17192480713428e-01 +-3.30000000000000e+01 -6.97048433260438e-01 4.38755128231645e-01 2.17746484897517e-01 +-3.00000000000000e+01 -7.10395349681667e-01 3.71062942477108e-01 2.21579781653519e-01 +-2.93939393939394e+01 -7.13452692480888e-01 3.58077533205854e-01 2.23238409263915e-01 +-2.87878787878788e+01 -7.16510035280109e-01 3.45092123934599e-01 2.24897036874312e-01 +-2.81818181818182e+01 -7.19567378079330e-01 3.32106714663345e-01 2.26555664484708e-01 +-2.75757575757576e+01 -7.23015176952550e-01 3.19538672861810e-01 2.28842891870977e-01 +-2.69696969696970e+01 -7.26630328498820e-01 3.07149518178065e-01 2.31399542272472e-01 +-2.63636363636364e+01 -7.30245480045089e-01 2.94760363494321e-01 2.33956192673967e-01 +-2.57575757575758e+01 -7.34209413289690e-01 2.82634381591017e-01 2.36982384547252e-01 +-2.51515151515151e+01 -7.38696437793794e-01 2.70903097522626e-01 2.40712779195633e-01 +-2.45454545454545e+01 -7.43183462297898e-01 2.59171813454235e-01 2.44443173844013e-01 +-2.39393939393939e+01 -7.47799807451049e-01 2.47511976474211e-01 2.48330404264612e-01 +-2.33333333333333e+01 -7.53580063482705e-01 2.36495177121992e-01 2.53629186999333e-01 +-2.27272727272727e+01 -7.59360319514362e-01 2.25478377769773e-01 2.59138821302601e-01 +-2.21212121212121e+01 -7.65140575546019e-01 2.14461578417554e-01 2.64477816678713e-01 +-2.15151515151515e+01 -8.03302749793657e-01 2.08548124886777e-01 2.49301560239203e-01 +-2.09090909090909e+01 -8.50824045909576e-01 2.03910836081233e-01 2.28513888557106e-01 +-2.03030303030303e+01 -8.97768386898726e-01 1.99273547275689e-01 2.07575119743590e-01 +-1.96969696969697e+01 -9.44678207213724e-01 1.94637489543005e-01 1.86538818608059e-01 +-1.90909090909091e+01 -9.91555050415259e-01 1.90002662813539e-01 1.65441760982968e-01 +-1.84848484848485e+01 -1.03842681336623e+00 1.85480504382984e-01 1.44332068966338e-01 +-1.78787878787879e+01 -1.08529649705215e+00 1.80950527403410e-01 1.23357644166816e-01 +-1.72727272727273e+01 -1.13216603243267e+00 1.76145971766597e-01 1.02450261417032e-01 +-1.66666666666667e+01 -1.17903468591979e+00 1.71473937535991e-01 8.15425477213738e-02 +-1.60606060606061e+01 -1.22590272554085e+00 1.66848907281323e-01 6.06345632546291e-02 +-1.54545454545455e+01 -1.24540579219954e+00 1.60147463320380e-01 4.44630991177370e-02 +-1.48484848484848e+01 -1.24781000746850e+00 1.52164045091083e-01 3.08929440011085e-02 +-1.42424242424242e+01 -1.20802738977228e+00 1.41026803742556e-01 2.37904766410137e-02 +-1.36363636363636e+01 -1.16175523534967e+00 1.29449635840845e-01 1.56762299252564e-02 +-1.30303030303030e+01 -1.11115112057063e+00 1.17578013100753e-01 6.58924652136504e-03 +-1.24242424242424e+01 -1.05692194409935e+00 1.06127950509725e-01 -3.71182830764803e-03 +-1.18181818181818e+01 -1.00272814309195e+00 9.53368098006124e-02 -1.33696206088078e-02 +-1.12121212121212e+01 -9.49076573968545e-01 8.60321040274192e-02 -2.13872923605838e-02 +-1.06060606060606e+01 -8.93581807311589e-01 7.76106753832643e-02 -2.80731947658556e-02 +-1.00000000000000e+01 -8.36985941927378e-01 6.96649134803325e-02 -3.40347701647619e-02 +-9.39393939393939e+00 -7.93166380537571e-01 5.77167470270437e-02 -4.15395521632745e-02 +-8.78787878787879e+00 -7.59169809540880e-01 4.45159809940110e-02 -4.84819804761218e-02 +-8.18181818181818e+00 -7.42105465881365e-01 2.91170572332394e-02 -5.43926186316557e-02 +-7.57575757575758e+00 -6.99614592258827e-01 2.14382481096017e-02 -5.74658684394408e-02 +-6.96969696969697e+00 -6.44608817122756e-01 1.72874428994890e-02 -5.94924254124929e-02 +-6.36363636363636e+00 -5.58802274186132e-01 1.57551020164310e-02 -6.43044689253696e-02 +-5.75757575757576e+00 -4.73764998472755e-01 1.43502448275924e-02 -6.89249208066366e-02 +-5.15151515151515e+00 -3.89894394333158e-01 1.31419672724884e-02 -7.32603190020164e-02 +-4.54545454545454e+00 -3.07166264437107e-01 1.22637086666309e-02 -7.73190401255010e-02 +-3.93939393939394e+00 -2.25054198114775e-01 1.15266148059250e-02 -8.12466599743608e-02 +-3.33333333333333e+00 -1.45172725478899e-01 1.11181586895799e-02 -8.48048561058059e-02 +-2.72727272727273e+00 -6.64481817059381e-02 1.08213328544847e-02 -8.81461929096935e-02 +-2.12121212121212e+00 1.12495325557481e-02 1.06139900247299e-02 -9.12799422030186e-02 +-1.51515151515152e+00 8.85670296087496e-02 1.04479884948180e-02 -9.42942439451978e-02 +-9.09090909090912e-01 1.66213270670549e-01 1.03347362369138e-02 -9.72595244702951e-02 +-3.03030303030302e-01 2.45681839335204e-01 1.04136053686051e-02 -1.00116736668253e-01 + 3.03030303030302e-01 3.24493811021227e-01 1.05051634149457e-02 -1.02832528533338e-01 + 9.09090909090912e-01 4.02689577361445e-01 1.06029024359060e-02 -1.05409582524880e-01 + 1.51515151515152e+00 4.80450558739067e-01 1.06086084327215e-02 -1.07756982884227e-01 + 2.12121212121212e+00 5.57655020416299e-01 1.06364076844461e-02 -1.10007533488911e-01 + 2.72727272727273e+00 6.32854110854688e-01 1.08222553063749e-02 -1.12010805967812e-01 + 3.33333333333333e+00 7.07829104208440e-01 1.09871939917408e-02 -1.13813398304224e-01 + 3.93939393939394e+00 7.82726097125106e-01 1.11313590740197e-02 -1.15433563257352e-01 + 4.54545454545455e+00 8.56725036367504e-01 1.13155452275198e-02 -1.16880352315399e-01 + 5.15151515151515e+00 9.30032793828029e-01 1.15208350124478e-02 -1.18219662619805e-01 + 5.75757575757576e+00 1.00154268140207e+00 1.17795522060827e-02 -1.19293155287934e-01 + 6.36363636363637e+00 1.07164671957996e+00 1.20808443869704e-02 -1.20114824732784e-01 + 6.96969696969697e+00 1.14081776942528e+00 1.24089124959070e-02 -1.20769509296104e-01 + 7.57575757575757e+00 1.20747309170393e+00 1.27841449542467e-02 -1.20984177116947e-01 + 8.18181818181818e+00 1.27293094202657e+00 1.31971119963991e-02 -1.21040387776290e-01 + 8.78787878787879e+00 1.33631723158136e+00 1.36879819805424e-02 -1.20797951715922e-01 + 9.39393939393939e+00 1.39580208572342e+00 1.43634591973061e-02 -1.19814227819290e-01 + 1.00000000000000e+01 1.45201036734241e+00 1.51114679774447e-02 -1.18417062091605e-01 + 1.06060606060606e+01 1.49636269861419e+00 1.62052841025846e-02 -1.15842476045504e-01 + 1.12121212121212e+01 1.53223105339179e+00 1.75945580457730e-02 -1.12669856479682e-01 + 1.18181818181818e+01 1.55233724587327e+00 1.95273589024484e-02 -1.08387441695462e-01 + 1.24242424242424e+01 1.40485306788269e+00 3.66837894727473e-02 -1.10705453199216e-01 + 1.30303030303030e+01 1.19641936134212e+00 5.96341107919704e-02 -1.15524471863464e-01 + 1.36363636363636e+01 1.13694346952033e+00 6.90810774839366e-02 -1.13792452322283e-01 + 1.42424242424242e+01 1.08854773748024e+00 7.81569854013355e-02 -1.12222962444976e-01 + 1.48484848484848e+01 1.05813142651997e+00 8.67025410668526e-02 -1.10869165205536e-01 + 1.54545454545455e+01 1.03762808162079e+00 9.51813233811173e-02 -1.10006355575461e-01 + 1.60606060606061e+01 1.02128710765488e+00 1.03672155520267e-01 -1.09349864817940e-01 + 1.66666666666667e+01 1.01267698438400e+00 1.12471820673251e-01 -1.09500151103095e-01 + 1.72727272727273e+01 1.00862750152695e+00 1.21612657749372e-01 -1.10196871074556e-01 + 1.78787878787879e+01 1.01015219256151e+00 1.31170487057709e-01 -1.11561461369328e-01 + 1.84848484848485e+01 1.02487270501671e+00 1.42717764493646e-01 -1.14728141059506e-01 + 1.90909090909091e+01 1.04251728636470e+00 1.54827944679204e-01 -1.18510461076852e-01 + 1.96969696969697e+01 1.05803974641611e+00 1.67310086078875e-01 -1.23229156855034e-01 + 2.03030303030303e+01 1.07018102313405e+00 1.79415876584770e-01 -1.28428162973701e-01 + 2.09090909090909e+01 1.07894092523283e+00 1.91145294905368e-01 -1.34145582008302e-01 + 2.15151515151515e+01 1.08770082733162e+00 2.02874713225965e-01 -1.39876119614393e-01 + 2.21212121212121e+01 1.09305671932835e+00 2.14461578417554e-01 -1.45612662747519e-01 + 2.27272727272727e+01 1.08480007339250e+00 2.25478377769773e-01 -1.51382551672362e-01 + 2.33333333333333e+01 1.07654342745665e+00 2.36495177121992e-01 -1.57161617206521e-01 + 2.39393939393939e+01 1.06828678152080e+00 2.47511976474211e-01 -1.62994019825784e-01 + 2.45454545454545e+01 1.06169131258261e+00 2.59171813454235e-01 -1.68042877714576e-01 + 2.51515151515151e+01 1.05528041489594e+00 2.70903097522626e-01 -1.73004676950534e-01 + 2.57575757575758e+01 1.04886951720927e+00 2.82634381591017e-01 -1.77966476186493e-01 + 2.63636363636364e+01 1.04320589180274e+00 2.94760363494321e-01 -1.82573390251451e-01 + 2.69696969696970e+01 1.03804052533334e+00 3.07149518178065e-01 -1.86943677436481e-01 + 2.75757575757576e+01 1.03287515886394e+00 3.19538672861810e-01 -1.91313964621511e-01 + 2.81818181818182e+01 1.02794990386129e+00 3.32106714663345e-01 -1.95560901544960e-01 + 2.87878787878788e+01 1.02358486088827e+00 3.45092123934599e-01 -1.99520045880541e-01 + 2.93939393939394e+01 1.01921981791524e+00 3.58077533205854e-01 -2.03479190216121e-01 + 3.00000000000000e+01 1.01485477494222e+00 3.71062942477108e-01 -2.07438334551702e-01 + 3.30000000000000e+01 9.95781979176941e-01 4.38755128231646e-01 -2.25248633303694e-01 + 3.60000000000000e+01 9.77261344047451e-01 5.09304675599610e-01 -2.41856194661193e-01 + 3.90000000000000e+01 9.57239163797111e-01 5.82564691354695e-01 -2.57340269463326e-01 + 4.20000000000000e+01 9.33459403203811e-01 6.57519359024154e-01 -2.72202941735538e-01 + 4.50000000000000e+01 9.08329968243298e-01 7.32897637152475e-01 -2.86898149313765e-01 + 4.80000000000000e+01 8.75830570639952e-01 8.08245749651705e-01 -3.01010122893952e-01 + 5.10000000000000e+01 8.39089169459949e-01 8.82059951286934e-01 -3.14864677792113e-01 + 5.40000000000000e+01 7.93863488417853e-01 9.52806232582514e-01 -3.28197186474091e-01 + 5.70000000000000e+01 7.48638152873260e-01 1.02355197341827e+00 -3.41532795817309e-01 + 6.00000000000000e+01 7.03412990076103e-01 1.09429744402618e+00 -3.54870873320022e-01 + 6.30000000000000e+01 6.42091935358749e-01 1.15185747018962e+00 -3.66903187497261e-01 + 6.60000000000000e+01 5.80770742674055e-01 1.20941738333287e+00 -3.78937520560764e-01 + 6.90000000000000e+01 5.19449549989362e-01 1.26697729647612e+00 -3.90973534083543e-01 + 7.20000000000000e+01 4.50479586567496e-01 1.31109233875070e+00 -4.01764478228043e-01 + 7.50000000000000e+01 3.77685394357568e-01 1.34848522082535e+00 -4.11933663285151e-01 + 7.80000000000000e+01 3.04889770136817e-01 1.38587853139263e+00 -4.22104253439653e-01 + 8.10000000000000e+01 2.30723589089482e-01 1.41503247767341e+00 -4.31419619766910e-01 + 8.40000000000000e+01 1.53816388998543e-01 1.42770826412360e+00 -4.39023497820268e-01 + 8.70000000000000e+01 7.69082013784813e-02 1.44038414740981e+00 -4.46628018116478e-01 + 9.00000000000000e+01 -3.36004484498046e-07 1.45305992088633e+00 -4.54233190688659e-01 + 9.30000000000000e+01 -5.38357962810632e-02 1.44038413443613e+00 -4.57885786719435e-01 + 9.60000000000000e+01 -1.07671262193915e-01 1.42770829956833e+00 -4.61538677552376e-01 + 9.90000000000000e+01 -1.61506739379516e-01 1.41503236786356e+00 -4.65191853174755e-01 + 1.02000000000000e+02 -2.13422866177849e-01 1.38587835028935e+00 -4.65561570743231e-01 + 1.05000000000000e+02 -2.64379338566390e-01 1.34848546821470e+00 -4.64289725865889e-01 + 1.08000000000000e+02 -3.15335797028190e-01 1.31109215764924e+00 -4.63017478275328e-01 + 1.11000000000000e+02 -3.63614995985125e-01 1.26697679783968e+00 -4.60482928481624e-01 + 1.14000000000000e+02 -4.06539757473920e-01 1.20941754428038e+00 -4.55423611669011e-01 + 1.17000000000000e+02 -4.49464448320822e-01 1.15185785100299e+00 -4.50364064972578e-01 + 1.20000000000000e+02 -4.92389081812947e-01 1.09429791207450e+00 -4.45304488017237e-01 + 1.23000000000000e+02 -5.24047055768740e-01 1.02355244146660e+00 -4.38404309098436e-01 + 1.26000000000000e+02 -5.55704950650637e-01 9.52806700636205e-01 -4.31504104372525e-01 + 1.29000000000000e+02 -5.87362687378832e-01 8.82060419340624e-01 -4.24603632838989e-01 + 1.32000000000000e+02 -6.11362090369567e-01 8.08235905809873e-01 -4.18403572366859e-01 + 1.35000000000000e+02 -6.31532335564314e-01 7.32872279819475e-01 -4.12553840848231e-01 + 1.38000000000000e+02 -6.51701749637977e-01 6.57509515264151e-01 -4.06704379408258e-01 + 1.41000000000000e+02 -6.69672879714259e-01 5.83647104683220e-01 -4.02869826230333e-01 + 1.44000000000000e+02 -6.83247423957872e-01 5.12785414225651e-01 -4.03065008320271e-01 + 1.47000000000000e+02 -6.96821464496714e-01 4.41924263677891e-01 -4.03260077987011e-01 + 1.50000000000000e+02 -7.10395253192162e-01 3.71063383075396e-01 -4.03455201443317e-01 + 1.53000000000000e+02 -7.06372114301663e-01 3.17621444101635e-01 -4.19162152168120e-01 + 1.56000000000000e+02 -7.02348949774489e-01 2.64179749134792e-01 -4.34871119537335e-01 + 1.59000000000000e+02 -6.98510217081455e-01 2.10738460990774e-01 -4.50581918807084e-01 + 1.62000000000000e+02 -6.27628255763012e-01 1.73632254525860e-01 -4.64655763669874e-01 + 1.65000000000000e+02 -5.23023338960169e-01 1.44693727049735e-01 -4.77910305590711e-01 + 1.68000000000000e+02 -4.18349440675210e-01 1.15754931187723e-01 -4.91164080985006e-01 + 1.71000000000000e+02 -3.13741957550692e-01 8.68162240683767e-02 -4.50000513056908e-01 + 1.74000000000000e+02 -2.09161222825938e-01 5.78776944385058e-02 -2.99999717902353e-01 + 1.77000000000000e+02 -1.04100854082611e-01 4.76423262875679e-02 -1.49311675143774e-01 + 1.80000000000000e+02 0.00000000000000e+00 4.67684423893836e-02 0.00000000000000e+00 diff --git a/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_16.dat b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_16.dat new file mode 100644 index 00000000..42e6caf1 --- /dev/null +++ b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_16.dat @@ -0,0 +1,254 @@ +! ------------ AirfoilInfo v1.01.x Input File ---------------------------------- +! AeroElasticSE FAST driver +! line +! line +! ------------------------------------------------------------------------------ +DEFAULT InterpOrd ! Interpolation order to use for quasi-steady table lookup {1=linear; 3=cubic spline; "default"} [default=3] +1 NonDimArea ! The non-dimensional area of the airfoil (area/chord^2) (set to 1.0 if unsure or unneeded) +@"NREL-2p8-127_AF16_Coords.txt" NumCoords ! The number of coordinates in the airfoil shape file. Set to zero if coordinates not included. +AF16_BL.txt BL_file ! The file name including the boundary layer characteristics of the profile. Ignored if the aeroacoustic module is not called. +1 NumTabs ! Number of airfoil tables in this file. Each table must have lines for Re and Ctrl. +! ------------------------------------------------------------------------------ +! data for table 1 +! ------------------------------------------------------------------------------ +6.000000 Re ! Reynolds number in millions +0 Ctrl ! Control setting (must be 0 for current AirfoilInfo) +True InclUAdata ! Is unsteady aerodynamics data included in this table? If TRUE, then include 30 UA coefficients below this line +!........................................ +-2.302844 alpha0 ! 0-lift angle of attack, depends on airfoil. +11.519512 alpha1 ! Angle of attack at f=0.7, (approximately the stall angle) for AOA>alpha0. (deg) +-10.603134 alpha2 ! Angle of attack at f=0.7, (approximately the stall angle) for AOA1] +0.000000 S2 ! Constant in the f curve best-fit for AOA> alpha1; by definition it depends on the airfoil. [ignored if UAMod<>1] +0.000000 S3 ! Constant in the f curve best-fit for alpha2<=AOA< alpha0; by definition it depends on the airfoil. [ignored if UAMod<>1] +0.000000 S4 ! Constant in the f curve best-fit for AOA< alpha2; by definition it depends on the airfoil. [ignored if UAMod<>1] +1.490978 Cn1 ! Critical value of C0n at leading edge separation. It should be extracted from airfoil data at a given Mach and Reynolds number. It can be calculated from the static value of Cn at either the break in the pitching moment or the loss of chord force at the onset of stall. It is close to the condition of maximum lift of the airfoil at low Mach numbers. +-1.228842 Cn2 ! As Cn1 for negative AOAs. +Default St_sh ! Strouhal's shedding frequency constant. [default = 0.19] +0.010387 Cd0 ! 2D drag coefficient value at 0-lift. +-0.097277 Cm0 ! 2D pitching moment coefficient about 1/4-chord location, at 0-lift, positive if nose up. [If the aerodynamics coefficients table does not include a column for Cm, this needs to be set to 0.0] +0.000000 k0 ! Constant in the \hat(x)_cp curve best-fit; = (\hat(x)_AC-0.25). [ignored if UAMod<>1] +0.000000 k1 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k2 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k3 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k1_hat ! Constant in the expression of Cc due to leading edge vortex effects. [ignored if UAMod<>1] +Default x_cp_bar ! Constant in the expression of \hat(x)_cp^v. [ignored if UAMod<>1, default = 0.2] +Default UACutout ! Angle of attack above which unsteady aerodynamics are disabled (deg). [Specifying the string "Default" sets UACutout to 45 degrees] +Default filtCutOff ! Cut-off frequency (-3 dB corner frequency) for low-pass filtering the AoA input to UA, as well as the 1st and 2nd derivatives (Hz) [default = 20] +!........................................ +! Table of aerodynamics coefficients +200 NumAlf ! Number of data lines in the following table +! Alpha Cl Cd Cm +! (deg) (-) (-) (-) +-1.80000000000000e+02 0.00000000000000e+00 4.74945271221455e-02 0.00000000000000e+00 +-1.77000000000000e+02 1.09026165719319e-01 4.74945271221455e-02 1.19452717008645e-01 +-1.74000000000000e+02 2.19050122417552e-01 5.69933789541972e-02 2.39999774321882e-01 +-1.71000000000000e+02 3.28575719604901e-01 8.54902462894429e-02 3.60000410445527e-01 +-1.68000000000000e+02 4.38106914174825e-01 1.13986527655115e-01 3.17778142294727e-01 +-1.65000000000000e+02 5.47644046044007e-01 1.42482516042840e-01 1.94446315387067e-01 +-1.62000000000000e+02 6.57185375418956e-01 1.70979335776501e-01 7.11135800063474e-02 +-1.59000000000000e+02 7.28986558567270e-01 2.08325862036029e-01 -1.07467958526159e-02 +-1.56000000000000e+02 7.23604309898402e-01 2.63371501965611e-01 -1.08174141591834e-02 +-1.53000000000000e+02 7.17767305056863e-01 3.18417162412815e-01 -1.14148679848354e-02 +-1.50000000000000e+02 7.12445310173410e-01 3.73462869777982e-01 -1.26457400718686e-02 +-1.47000000000000e+02 6.98630831673898e-01 4.44240664843570e-01 2.75536840347873e-03 +-1.44000000000000e+02 6.84816100411641e-01 5.15018714390009e-01 1.81567857412231e-02 +-1.41000000000000e+02 6.71000863605846e-01 5.85797272916321e-01 3.36066126261243e-02 +-1.38000000000000e+02 6.52847363996135e-01 6.59563695332857e-01 4.92127237288619e-02 +-1.35000000000000e+02 6.32524741785104e-01 7.34824043633297e-01 6.48870780422191e-02 +-1.32000000000000e+02 6.12201334294277e-01 8.10085206753381e-01 8.05597032537663e-02 +-1.29000000000000e+02 5.88065552379780e-01 8.83801868347751e-01 9.63550603105852e-02 +-1.26000000000000e+02 5.56305003551198e-01 9.54429519550126e-01 1.12398380329180e-01 +-1.23000000000000e+02 5.24544329085952e-01 1.02505663119359e+00 1.28440896746455e-01 +-1.20000000000000e+02 4.92783591804722e-01 1.09568347306768e+00 1.44482743848553e-01 +-1.17000000000000e+02 4.49791636415260e-01 1.15311205772626e+00 1.59698551465877e-01 +-1.14000000000000e+02 4.06799639145038e-01 1.21054039721062e+00 1.74914207352244e-01 +-1.11000000000000e+02 3.63807602041395e-01 1.26796829798034e+00 1.90129494093679e-01 +-1.08000000000000e+02 3.15480318387913e-01 1.31194660547628e+00 2.03701386725598e-01 +-1.05000000000000e+02 2.64485370834833e-01 1.34920001392269e+00 2.16452268723353e-01 +-1.02000000000000e+02 2.13490407640989e-01 1.38645299548144e+00 2.29203915346582e-01 +-9.90000000000000e+01 1.61544432084705e-01 1.41546560806078e+00 2.40600993496564e-01 +-9.60000000000000e+01 1.07696390610193e-01 1.42799712574756e+00 2.49288387037645e-01 +-9.30000000000000e+01 5.38483605044154e-02 1.44052854770060e+00 2.57977933040283e-01 +-9.00000000000000e+01 3.36082901150735e-07 1.45305992178765e+00 2.66670007912819e-01 +-8.70000000000000e+01 -5.38483053909395e-02 1.44052856052647e+00 2.70653828346413e-01 +-8.40000000000000e+01 -1.07696541181314e-01 1.42799709070664e+00 2.74632091077504e-01 +-8.10000000000000e+01 -1.61543965606523e-01 1.41546571661960e+00 2.78605161493305e-01 +-7.80000000000000e+01 -2.13490160659344e-01 1.38645317590716e+00 2.79287028552001e-01 +-7.50000000000000e+01 -2.64485708214139e-01 1.34919976745892e+00 2.78321604655193e-01 +-7.20000000000000e+01 -3.15480071411678e-01 1.31194678590016e+00 2.77352606273105e-01 +-6.90000000000000e+01 -3.63807229600907e-01 1.26796879547887e+00 2.75114638009095e-01 +-6.60000000000000e+01 -4.06799759359618e-01 1.21054023663040e+00 2.70342633491159e-01 +-6.30000000000000e+01 -4.49791920847929e-01 1.15311167778193e+00 2.65569198485011e-01 +-6.00000000000000e+01 -4.92783801932097e-01 1.09568300580419e+00 2.60795303619874e-01 +-5.70000000000000e+01 -5.24544539213326e-01 1.02505616393010e+00 2.54185204039382e-01 +-5.40000000000000e+01 -5.56305213677325e-01 9.54429052281285e-01 2.47577553322180e-01 +-5.10000000000000e+01 -5.88065762505907e-01 8.83801401078910e-01 2.40973778659848e-01 +-4.80000000000000e+01 -6.13910354720703e-01 8.10097993520892e-01 2.34611596779972e-01 +-4.50000000000000e+01 -6.36797063706404e-01 7.34856757216810e-01 2.28377676012707e-01 +-4.20000000000000e+01 -6.54556371048421e-01 6.59576481995557e-01 2.23680283338938e-01 +-3.90000000000000e+01 -6.71380181626923e-01 5.84717599999870e-01 2.19536883348591e-01 +-3.60000000000000e+01 -6.85604200137604e-01 5.11546160178582e-01 2.17305088035508e-01 +-3.30000000000000e+01 -6.98815713908257e-01 4.41078428348352e-01 2.18054288333084e-01 +-3.00000000000000e+01 -7.12445408634725e-01 3.73462429674547e-01 2.22124678427173e-01 +-2.93939393939394e+01 -7.15569260532856e-01 3.60491220538288e-01 2.23842948054128e-01 +-2.87878787878788e+01 -7.18693112430987e-01 3.47520011402029e-01 2.25561217681083e-01 +-2.81818181818182e+01 -7.21816964329118e-01 3.34548802265771e-01 2.27279487308038e-01 +-2.75757575757576e+01 -7.25337539045798e-01 3.21994339673895e-01 2.29635020906344e-01 +-2.69696969696970e+01 -7.29028152413596e-01 3.09618498066121e-01 2.32263691065060e-01 +-2.63636363636364e+01 -7.32718765781393e-01 2.97242656458348e-01 2.34892361223777e-01 +-2.57575757575758e+01 -7.36762602567382e-01 2.85129614107284e-01 2.37997233303781e-01 +-2.51515151515151e+01 -7.41336192157463e-01 2.73410709392586e-01 2.41816297280826e-01 +-2.45454545454545e+01 -7.45909781747544e-01 2.61691804677889e-01 2.45635361257870e-01 +-2.39393939393939e+01 -7.50627141320397e-01 2.50043674398799e-01 2.49515043488697e-01 +-2.33333333333333e+01 -7.56638458572749e-01 2.39032527742441e-01 2.53940301739542e-01 +-2.27272727272727e+01 -7.62649775825102e-01 2.28021381086083e-01 2.57853785491344e-01 +-2.21212121212121e+01 -7.68661093077454e-01 2.17010234429726e-01 2.62068606039781e-01 +-2.15151515151515e+01 -8.07233018911813e-01 2.10719432824284e-01 2.44666939257051e-01 +-2.09090909090909e+01 -8.50063944721421e-01 2.05609021115132e-01 2.23825168737330e-01 +-2.03030303030303e+01 -8.94818933511164e-01 2.00498609405980e-01 2.03531509688972e-01 +-1.96969696969697e+01 -9.39301590592824e-01 1.95388221736857e-01 1.83458906167973e-01 +-1.90909090909091e+01 -9.83659564135496e-01 1.90277858106401e-01 1.63473959738679e-01 +-1.84848484848485e+01 -1.02835646060585e+00 1.84862741269290e-01 1.43541881926139e-01 +-1.78787878787879e+01 -1.07312022949524e+00 1.79623630734647e-01 1.23006204069627e-01 +-1.72727272727273e+01 -1.11789561032257e+00 1.75305320947758e-01 1.02174031312229e-01 +-1.66666666666667e+01 -1.16291637243167e+00 1.70479646552578e-01 8.13469192385163e-02 +-1.60606060606061e+01 -1.20810673312181e+00 1.65435507128552e-01 6.05261011893848e-02 +-1.54545454545455e+01 -1.22780192188674e+00 1.58414016648205e-01 4.42999154215266e-02 +-1.48484848484848e+01 -1.23148075482471e+00 1.50176007301149e-01 3.06001307793610e-02 +-1.42424242424242e+01 -1.19557688058349e+00 1.38991906593942e-01 2.19117759370747e-02 +-1.36363636363636e+01 -1.15320275631460e+00 1.27391804267069e-01 1.07082871223446e-02 +-1.30303030303030e+01 -1.10624218648539e+00 1.15510306693132e-01 -8.83566244868970e-04 +-1.24242424242424e+01 -1.05404262149901e+00 1.03763709632377e-01 -1.08587103233837e-02 +-1.18181818181818e+01 -1.00136072816888e+00 9.26167355272088e-02 -1.96543223095588e-02 +-1.12121212121212e+01 -9.48585842590762e-01 8.31140514128371e-02 -2.58402153588698e-02 +-1.06060606060606e+01 -8.93667893889375e-01 7.46227143327008e-02 -3.16390840974881e-02 +-1.00000000000000e+01 -8.38065195025141e-01 6.66511845807474e-02 -3.72575661487416e-02 +-9.39393939393939e+00 -7.95410787978230e-01 5.51236226526759e-02 -4.38865668044484e-02 +-8.78787878787879e+00 -7.59114580119346e-01 4.22612717076337e-02 -5.05975414003474e-02 +-8.18181818181818e+00 -7.39908303358907e-01 2.65347518460736e-02 -5.75870121728342e-02 +-7.57575757575758e+00 -6.95515216031812e-01 1.93744036977655e-02 -6.18696615221871e-02 +-6.96969696969697e+00 -6.38970352980065e-01 1.56903682577269e-02 -6.50444957534814e-02 +-6.36363636363636e+00 -5.53050978116223e-01 1.44330515252630e-02 -7.04916309908320e-02 +-5.75757575757576e+00 -4.67855482297821e-01 1.32728500481496e-02 -7.56445389562658e-02 +-5.15151515151515e+00 -3.83761883334006e-01 1.22747621729221e-02 -8.03433974705679e-02 +-4.54545454545454e+00 -3.00853428667449e-01 1.15921315939537e-02 -8.44964464276008e-02 +-3.93939393939394e+00 -2.18316833870855e-01 1.10444241869388e-02 -8.84303296892449e-02 +-3.33333333333333e+00 -1.35802226396340e-01 1.06756393000342e-02 -9.19189227982073e-02 +-2.72727272727273e+00 -5.52401875853970e-02 1.04478510242675e-02 -9.51462086023917e-02 +-2.12121212121212e+00 2.36396912458736e-02 1.03604338233977e-02 -9.81888615779641e-02 +-1.51515151515152e+00 1.01484614889655e-01 1.02452048792184e-02 -1.01004246307992e-01 +-9.09090909090912e-01 1.79466580667274e-01 1.01619214134529e-02 -1.03750330378995e-01 +-3.03030303030302e-01 2.59087622411868e-01 1.02426571705537e-02 -1.06360316407136e-01 + 3.03030303030302e-01 3.37837592391149e-01 1.03303065575862e-02 -1.08843506321385e-01 + 9.09090909090912e-01 4.15789971549744e-01 1.04212147734708e-02 -1.11177829034995e-01 + 1.51515151515152e+00 4.93147895935465e-01 1.04236090925569e-02 -1.13298457665409e-01 + 2.12121212121212e+00 5.69859535842775e-01 1.04645134860512e-02 -1.15323446159398e-01 + 2.72727272727273e+00 6.44307642449725e-01 1.06495299479427e-02 -1.17170718042645e-01 + 3.33333333333333e+00 7.18600940028201e-01 1.08126791422125e-02 -1.18836030380812e-01 + 3.93939393939394e+00 7.92950170251859e-01 1.09043051654465e-02 -1.20329319459463e-01 + 4.54545454545455e+00 8.66750625755535e-01 1.10287283292864e-02 -1.21622097750385e-01 + 5.15151515151515e+00 9.39936884951220e-01 1.11859719302871e-02 -1.22800063053947e-01 + 5.75757575757576e+00 1.01143404956829e+00 1.14111475039848e-02 -1.23696733437718e-01 + 6.36363636363637e+00 1.08182810267221e+00 1.16720384522875e-02 -1.24300128967657e-01 + 6.96969696969697e+00 1.15154797840494e+00 1.19507072068761e-02 -1.24706383395138e-01 + 7.57575757575757e+00 1.21829984832910e+00 1.23111001660822e-02 -1.24318393141766e-01 + 8.18181818181818e+00 1.28284334003200e+00 1.28453551133823e-02 -1.23573477309161e-01 + 8.78787878787879e+00 1.34152950781049e+00 1.37024581751005e-02 -1.22008658301098e-01 + 9.39393939393939e+00 1.39175204718020e+00 1.50501911010927e-02 -1.20764566885121e-01 + 1.00000000000000e+01 1.44072055032551e+00 1.67619493434159e-02 -1.19700808310407e-01 + 1.06060606060606e+01 1.47445006881312e+00 1.86588668153617e-02 -1.17383563054315e-01 + 1.12121212121212e+01 1.50211111367966e+00 2.06442638039865e-02 -1.13986779446044e-01 + 1.18181818181818e+01 1.51849743382808e+00 2.27949008726186e-02 -1.08801154929910e-01 + 1.24242424242424e+01 1.38110104869832e+00 3.91932789258445e-02 -1.10609411291075e-01 + 1.30303030303030e+01 1.17394609485373e+00 6.11116586730917e-02 -1.14753045755195e-01 + 1.36363636363636e+01 1.12719502884985e+00 7.05126133472740e-02 -1.13285854419029e-01 + 1.42424242424242e+01 1.08888194901864e+00 7.96731387425781e-02 -1.11992721439345e-01 + 1.48484848484848e+01 1.06009153338648e+00 8.83736363016277e-02 -1.11029145646405e-01 + 1.54545454545455e+01 1.04088100180195e+00 9.68845274277538e-02 -1.10082901069663e-01 + 1.60606060606061e+01 1.02566184269085e+00 1.05353288508621e-01 -1.09447986832365e-01 + 1.66666666666667e+01 1.01747136523085e+00 1.14011650931451e-01 -1.09533721766659e-01 + 1.72727272727273e+01 1.01393796533581e+00 1.23111695493764e-01 -1.10194974676891e-01 + 1.78787878787879e+01 1.01620977550644e+00 1.32751579382771e-01 -1.11556728709361e-01 + 1.84848484848485e+01 1.03062727147662e+00 1.44357732350225e-01 -1.14737403733058e-01 + 1.90909090909091e+01 1.04771493788588e+00 1.56504624193137e-01 -1.18523866085458e-01 + 1.96969696969697e+01 1.06291878178938e+00 1.68930683382824e-01 -1.23167550096525e-01 + 2.03030303030303e+01 1.07502785257006e+00 1.81134979640342e-01 -1.28324656352032e-01 + 2.09090909090909e+01 1.08382115536938e+00 1.93117500419765e-01 -1.33815690623442e-01 + 2.15151515151515e+01 1.09214908926105e+00 2.05100021199187e-01 -1.39246581437727e-01 + 2.21212121212121e+01 1.09715356486127e+00 2.16895622980487e-01 -1.44828119061210e-01 + 2.27272727272727e+01 1.08886762688942e+00 2.27943741095172e-01 -1.50978244430421e-01 + 2.33333333333333e+01 1.08058168891757e+00 2.38991859209858e-01 -1.57084368281988e-01 + 2.39393939393939e+01 1.07229575094571e+00 2.50039977324543e-01 -1.62956004038701e-01 + 2.45454545454545e+01 1.06558611366856e+00 2.61691804677889e-01 -1.68040941931674e-01 + 2.51515151515151e+01 1.05905161714547e+00 2.73410709392586e-01 -1.73040662366437e-01 + 2.57575757575758e+01 1.05251712062237e+00 2.85129614107284e-01 -1.78042939631076e-01 + 2.63636363636364e+01 1.04673941380572e+00 2.97242656458348e-01 -1.82687214968074e-01 + 2.69696969696970e+01 1.04146631186305e+00 3.09618498066121e-01 -1.87092862759889e-01 + 2.75757575757576e+01 1.03619320992039e+00 3.21994339673895e-01 -1.91500121873642e-01 + 2.81818181818182e+01 1.03116398723408e+00 3.34548802265770e-01 -1.95783309953570e-01 + 2.87878787878788e+01 1.02670376733233e+00 3.47520011402030e-01 -1.99774488550039e-01 + 2.93939393939394e+01 1.02224354743058e+00 3.60491220538288e-01 -2.03766728259228e-01 + 3.00000000000000e+01 1.01778332752883e+00 3.73462429674547e-01 -2.07760038049125e-01 + 3.30000000000000e+01 9.98306668405358e-01 4.41078428348352e-01 -2.25710390737701e-01 + 3.60000000000000e+01 9.79435247436346e-01 5.11546160178582e-01 -2.42439672107783e-01 + 3.90000000000000e+01 9.59115016848787e-01 5.84717599999870e-01 -2.58725778460445e-01 + 4.20000000000000e+01 9.35081102871063e-01 6.59576481995558e-01 -2.74139975914325e-01 + 4.50000000000000e+01 9.09710553576705e-01 7.34856757216810e-01 -2.89288459990168e-01 + 4.80000000000000e+01 8.77014675428035e-01 8.10097993520892e-01 -3.03752712432158e-01 + 5.10000000000000e+01 8.40093342319397e-01 8.83801401078911e-01 -3.17922061767336e-01 + 5.40000000000000e+01 7.94720827645917e-01 9.54429052281285e-01 -3.31525536369943e-01 + 5.70000000000000e+01 7.49348627860369e-01 1.02505616393010e+00 -3.45117992160713e-01 + 6.00000000000000e+01 7.03976585517588e-01 1.09568300580419e+00 -3.58702045370939e-01 + 6.30000000000000e+01 6.42559375800653e-01 1.15311167778193e+00 -3.70952105943644e-01 + 6.60000000000000e+01 5.81142028551168e-01 1.21054023663040e+00 -3.83194946194241e-01 + 6.90000000000000e+01 5.19724681301684e-01 1.26796879547887e+00 -3.95431861953200e-01 + 7.20000000000000e+01 4.50686006342368e-01 1.31194678590016e+00 -4.06412636751425e-01 + 7.50000000000000e+01 3.77836823546866e-01 1.34919976745892e+00 -4.16762432040660e-01 + 7.80000000000000e+01 3.04986205955287e-01 1.38645317590716e+00 -4.27107489371432e-01 + 8.10000000000000e+01 2.30777377649507e-01 1.41546571661960e+00 -4.36589691718973e-01 + 8.40000000000000e+01 1.53852221672675e-01 1.42799709070664e+00 -4.44350170094074e-01 + 8.70000000000000e+01 7.69261097609987e-02 1.44052856052647e+00 -4.52106372914785e-01 + 9.00000000000000e+01 -3.36082901382020e-07 1.45305992178765e+00 -4.59858962710058e-01 + 9.30000000000000e+01 -5.38483605044154e-02 1.44052854770060e+00 -4.63848553313885e-01 + 9.60000000000000e+01 -1.07696390610194e-01 1.42799712574756e+00 -4.67844287195712e-01 + 9.90000000000000e+01 -1.61544432084705e-01 1.41546560806078e+00 -4.71846453257926e-01 + 1.02000000000000e+02 -2.13490407640989e-01 1.38645299548144e+00 -4.72567917825502e-01 + 1.05000000000000e+02 -2.64485370834833e-01 1.34920001392269e+00 -4.71652413145928e-01 + 1.08000000000000e+02 -3.15480318387913e-01 1.31194660547628e+00 -4.70694898637910e-01 + 1.11000000000000e+02 -3.63807602041395e-01 1.26796829798034e+00 -4.68443341138964e-01 + 1.14000000000000e+02 -4.06799639145038e-01 1.21054039721062e+00 -4.63658575489138e-01 + 1.17000000000000e+02 -4.49791636415260e-01 1.15311205772626e+00 -4.58872593540100e-01 + 1.20000000000000e+02 -4.92783591804723e-01 1.09568347306768e+00 -4.54085669273530e-01 + 1.23000000000000e+02 -5.24544329085952e-01 1.02505663119359e+00 -4.47459524176604e-01 + 1.26000000000000e+02 -5.56305003551198e-01 9.54429519550126e-01 -4.40832384971193e-01 + 1.29000000000000e+02 -5.88065552379780e-01 8.83801868347751e-01 -4.34204079889270e-01 + 1.32000000000000e+02 -6.12201334294277e-01 8.10085206753381e-01 -4.28311374168508e-01 + 1.35000000000000e+02 -6.32524741785104e-01 7.34824043633297e-01 -4.22785962751293e-01 + 1.38000000000000e+02 -6.52847363996135e-01 6.59563695332856e-01 -4.17259798695567e-01 + 1.41000000000000e+02 -6.71000863605846e-01 5.85797272916321e-01 -4.13816791549941e-01 + 1.44000000000000e+02 -6.84816100411641e-01 5.15018714390009e-01 -4.14540480801535e-01 + 1.47000000000000e+02 -6.98630831673898e-01 4.44240664843570e-01 -4.15262578060876e-01 + 1.50000000000000e+02 -7.12445310173410e-01 3.73462869777981e-01 -4.15983399559589e-01 + 1.53000000000000e+02 -7.07009533624438e-01 3.20145904015172e-01 -4.31332989170919e-01 + 1.56000000000000e+02 -7.02319196022267e-01 2.66829166731978e-01 -4.46674211305675e-01 + 1.59000000000000e+02 -6.97067607564390e-01 2.13512805022704e-01 -4.61700248148900e-01 + 1.62000000000000e+02 -6.25252484559990e-01 1.76166650176245e-01 -4.73355693794957e-01 + 1.65000000000000e+02 -5.21043473383171e-01 1.46805733824602e-01 -4.83347659534527e-01 + 1.68000000000000e+02 -4.16835056347187e-01 1.17444553927237e-01 -4.93339032716489e-01 + 1.71000000000000e+02 -3.12626441266809e-01 8.80834460119835e-02 -4.50000513056908e-01 + 1.74000000000000e+02 -2.08417430088600e-01 5.87224820643139e-02 -2.99999717902353e-01 + 1.77000000000000e+02 -1.03734285731640e-01 4.83552281802738e-02 -1.49315896260807e-01 + 1.80000000000000e+02 0.00000000000000e+00 4.74945271221455e-02 0.00000000000000e+00 diff --git a/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_17.dat b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_17.dat new file mode 100644 index 00000000..217af07d --- /dev/null +++ b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_17.dat @@ -0,0 +1,254 @@ +! ------------ AirfoilInfo v1.01.x Input File ---------------------------------- +! AeroElasticSE FAST driver +! line +! line +! ------------------------------------------------------------------------------ +DEFAULT InterpOrd ! Interpolation order to use for quasi-steady table lookup {1=linear; 3=cubic spline; "default"} [default=3] +1 NonDimArea ! The non-dimensional area of the airfoil (area/chord^2) (set to 1.0 if unsure or unneeded) +@"NREL-2p8-127_AF17_Coords.txt" NumCoords ! The number of coordinates in the airfoil shape file. Set to zero if coordinates not included. +AF17_BL.txt BL_file ! The file name including the boundary layer characteristics of the profile. Ignored if the aeroacoustic module is not called. +1 NumTabs ! Number of airfoil tables in this file. Each table must have lines for Re and Ctrl. +! ------------------------------------------------------------------------------ +! data for table 1 +! ------------------------------------------------------------------------------ +6.000000 Re ! Reynolds number in millions +0 Ctrl ! Control setting (must be 0 for current AirfoilInfo) +True InclUAdata ! Is unsteady aerodynamics data included in this table? If TRUE, then include 30 UA coefficients below this line +!........................................ +-2.516492 alpha0 ! 0-lift angle of attack, depends on airfoil. +10.239483 alpha1 ! Angle of attack at f=0.7, (approximately the stall angle) for AOA>alpha0. (deg) +-11.166956 alpha2 ! Angle of attack at f=0.7, (approximately the stall angle) for AOA1] +0.000000 S2 ! Constant in the f curve best-fit for AOA> alpha1; by definition it depends on the airfoil. [ignored if UAMod<>1] +0.000000 S3 ! Constant in the f curve best-fit for alpha2<=AOA< alpha0; by definition it depends on the airfoil. [ignored if UAMod<>1] +0.000000 S4 ! Constant in the f curve best-fit for AOA< alpha2; by definition it depends on the airfoil. [ignored if UAMod<>1] +1.381088 Cn1 ! Critical value of C0n at leading edge separation. It should be extracted from airfoil data at a given Mach and Reynolds number. It can be calculated from the static value of Cn at either the break in the pitching moment or the loss of chord force at the onset of stall. It is close to the condition of maximum lift of the airfoil at low Mach numbers. +-1.159496 Cn2 ! As Cn1 for negative AOAs. +Default St_sh ! Strouhal's shedding frequency constant. [default = 0.19] +0.009688 Cd0 ! 2D drag coefficient value at 0-lift. +-0.104313 Cm0 ! 2D pitching moment coefficient about 1/4-chord location, at 0-lift, positive if nose up. [If the aerodynamics coefficients table does not include a column for Cm, this needs to be set to 0.0] +0.000000 k0 ! Constant in the \hat(x)_cp curve best-fit; = (\hat(x)_AC-0.25). [ignored if UAMod<>1] +0.000000 k1 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k2 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k3 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k1_hat ! Constant in the expression of Cc due to leading edge vortex effects. [ignored if UAMod<>1] +Default x_cp_bar ! Constant in the expression of \hat(x)_cp^v. [ignored if UAMod<>1, default = 0.2] +Default UACutout ! Angle of attack above which unsteady aerodynamics are disabled (deg). [Specifying the string "Default" sets UACutout to 45 degrees] +Default filtCutOff ! Cut-off frequency (-3 dB corner frequency) for low-pass filtering the AoA input to UA, as well as the 1st and 2nd derivatives (Hz) [default = 20] +!........................................ +! Table of aerodynamics coefficients +200 NumAlf ! Number of data lines in the following table +! Alpha Cl Cd Cm +! (deg) (-) (-) (-) +-1.80000000000000e+02 0.00000000000000e+00 5.02376982549728e-02 0.00000000000000e+00 +-1.77000000000000e+02 1.08718036745927e-01 5.02376982549728e-02 1.19452717008645e-01 +-1.74000000000000e+02 2.18430776525163e-01 6.02851812182215e-02 2.39999774321882e-01 +-1.71000000000000e+02 3.27646531789012e-01 9.04279599581437e-02 3.60000410445527e-01 +-1.68000000000000e+02 4.36869311875493e-01 1.20570256132886e-01 3.18260147906390e-01 +-1.65000000000000e+02 5.46099384730567e-01 1.50712311030671e-01 1.95651323790509e-01 +-1.62000000000000e+02 6.55334540103918e-01 1.80854868202663e-01 7.30412515523047e-02 +-1.59000000000000e+02 7.28010405538067e-01 2.19127710006320e-01 -9.45584975904147e-03 +-1.56000000000000e+02 7.24644310916020e-01 2.73660846032009e-01 -1.21837323981812e-02 +-1.53000000000000e+02 7.21308604937496e-01 3.28193998660095e-01 -1.57136492042310e-02 +-1.50000000000000e+02 7.20052599183224e-01 3.82727196695211e-01 -2.24733180893469e-02 +-1.47000000000000e+02 7.05344979121394e-01 4.53184198414303e-01 -6.72063266750436e-03 +-1.44000000000000e+02 6.90637102885333e-01 5.23641395400969e-01 9.03246882847654e-03 +-1.41000000000000e+02 6.75928714282518e-01 5.94098982936728e-01 2.49798597818277e-02 +-1.38000000000000e+02 6.57098483724279e-01 6.67494798442362e-01 4.09475868870872e-02 +-1.35000000000000e+02 6.36207340549935e-01 7.42359721972419e-01 5.68857580517079e-02 +-1.32000000000000e+02 6.15315579547438e-01 8.17225281824516e-01 7.28165592297191e-02 +-1.29000000000000e+02 5.90673724574305e-01 8.90525522009492e-01 8.88369855206700e-02 +-1.26000000000000e+02 5.58531663885406e-01 9.60695115424263e-01 1.05046529374471e-01 +-1.23000000000000e+02 5.26389596453192e-01 1.03086417277945e+00 1.21252954182462e-01 +-1.20000000000000e+02 4.94247525649446e-01 1.10103296211486e+00 1.37456542318889e-01 +-1.17000000000000e+02 4.51005751931015e-01 1.15795443010112e+00 1.52804706847535e-01 +-1.14000000000000e+02 4.07763995533133e-01 1.21487565475428e+00 1.68151691714967e-01 +-1.11000000000000e+02 3.64522317186419e-01 1.27179644456681e+00 1.83497290780899e-01 +-1.08000000000000e+02 3.16016600929376e-01 1.31524560139462e+00 1.97190287375102e-01 +-1.05000000000000e+02 2.64878825634709e-01 1.35195883914965e+00 2.10057619315569e-01 +-1.02000000000000e+02 2.13741036335945e-01 1.38867165620685e+00 2.22925091726200e-01 +-9.90000000000000e+01 1.61684301770569e-01 1.41713830337121e+00 2.34432883783133e-01 +-9.60000000000000e+01 1.07789636867620e-01 1.42911225356491e+00 2.43221503139034e-01 +-9.30000000000000e+01 5.38949836895802e-02 1.44108611228438e+00 2.52012246779875e-01 +-9.00000000000000e+01 3.36373889682523e-07 1.45305992526757e+00 2.60805612076082e-01 +-8.70000000000000e+01 -5.38949285283857e-02 1.44108612453959e+00 2.65268702964392e-01 +-8.40000000000000e+01 -1.07789787569110e-01 1.42911222008308e+00 2.69705899355330e-01 +-8.10000000000000e+01 -1.61683834888495e-01 1.41713840709990e+00 2.74118148425682e-01 +-7.80000000000000e+01 -2.13740788662556e-01 1.38867183401641e+00 2.75218906403952e-01 +-7.50000000000000e+01 -2.64879163958945e-01 1.35195859625958e+00 2.74653513726577e-01 +-7.20000000000000e+01 -3.16016353261405e-01 1.31524577920238e+00 2.74066661635360e-01 +-6.90000000000000e+01 -3.64521942583287e-01 1.27179693767224e+00 2.72190520318518e-01 +-6.60000000000000e+01 -4.07764116445761e-01 1.21487549559204e+00 2.67758304954097e-01 +-6.30000000000000e+01 -4.51006038016469e-01 1.15795405351184e+00 2.63309723707785e-01 +-6.00000000000000e+01 -4.94247738299703e-01 1.10103249788183e+00 2.58846174876524e-01 +-5.70000000000000e+01 -5.26389809103449e-01 1.03086370854641e+00 2.52537766967854e-01 +-5.40000000000000e+01 -5.58531876535596e-01 9.60694651185909e-01 2.46218241369695e-01 +-5.10000000000000e+01 -5.90673937224495e-01 8.90525057771137e-01 2.39889401901766e-01 +-4.80000000000000e+01 -6.16985978521229e-01 8.17249434089066e-01 2.33807907536728e-01 +-4.50000000000000e+01 -6.40383103818546e-01 7.42420845191650e-01 2.27849917319468e-01 +-4.20000000000000e+01 -6.58768869626067e-01 6.67518950513351e-01 2.23456296897971e-01 +-3.90000000000000e+01 -6.76252856241839e-01 5.93029893358622e-01 2.19662575489263e-01 +-3.60000000000000e+01 -6.91251469843313e-01 5.20200446113040e-01 2.17992553881491e-01 +-3.30000000000000e+01 -7.05373690625492e-01 4.50048605759265e-01 2.19429640986969e-01 +-3.00000000000000e+01 -7.20052704961507e-01 3.82726758502379e-01 2.24334644865001e-01 +-2.93939393939394e+01 -7.23423358758069e-01 3.69810374707743e-01 2.26262638995891e-01 +-2.87878787878788e+01 -7.26794012554631e-01 3.56893990913108e-01 2.28190633126782e-01 +-2.81818181818182e+01 -7.30164666351193e-01 3.43977607118473e-01 2.30118627257672e-01 +-2.75757575757576e+01 -7.33955296036718e-01 3.31475572351972e-01 2.32714210527911e-01 +-2.69696969696970e+01 -7.37925930829896e-01 3.19151130974461e-01 2.35595927974075e-01 +-2.63636363636364e+01 -7.41896565623074e-01 3.06826689596951e-01 2.38477645420239e-01 +-2.57575757575758e+01 -7.46236904909058e-01 2.94763605830315e-01 2.41858864830355e-01 +-2.51515151515151e+01 -7.51131714769935e-01 2.83092497567289e-01 2.45989220771138e-01 +-2.45454545454545e+01 -7.56026524630811e-01 2.71421389304264e-01 2.50119576711921e-01 +-2.39393939393939e+01 -7.61117995847343e-01 2.59818577841106e-01 2.53958515768821e-01 +-2.33333333333333e+01 -7.67979457339360e-01 2.48830450799340e-01 2.55174646451070e-01 +-2.27272727272727e+01 -7.74840918831377e-01 2.37842323757575e-01 2.56491201944605e-01 +-2.21212121212121e+01 -7.81702380323394e-01 2.26854196715809e-01 2.57271002838526e-01 +-2.15151515151515e+01 -8.12448284285856e-01 2.19127250982838e-01 2.39096729103820e-01 +-2.09090909090909e+01 -8.46418529847557e-01 2.12215810350734e-01 2.19171773544913e-01 +-2.03030303030303e+01 -8.82410390516615e-01 2.05304369718630e-01 1.99907002060488e-01 +-1.96969696969697e+01 -9.17302460891263e-01 1.98393040992681e-01 1.80908557885250e-01 +-1.90909090909091e+01 -9.51690757109299e-01 1.91481824166556e-01 1.62015766540326e-01 +-1.84848484848485e+01 -9.87451060932182e-01 1.84488095751064e-01 1.43186155335470e-01 +-1.78787878787879e+01 -1.02348107734750e+00 1.78125103821018e-01 1.23309320342863e-01 +-1.72727272727273e+01 -1.05955430524795e+00 1.72667345635547e-01 1.02937199694708e-01 +-1.66666666666667e+01 -1.09661808800758e+00 1.66429075696717e-01 8.25865362857696e-02 +-1.60606060606061e+01 -1.13436650818888e+00 1.59785188254103e-01 6.22621217533182e-02 +-1.54545454545455e+01 -1.15393444133063e+00 1.51574659183086e-01 4.58165236508863e-02 +-1.48484848484848e+01 -1.16179648627071e+00 1.42415253094923e-01 3.15133238851397e-02 +-1.42424242424242e+01 -1.14050675694352e+00 1.31113076076399e-01 2.06305497523611e-02 +-1.36363636363636e+01 -1.11318982416965e+00 1.19491463618837e-01 6.42328479698607e-03 +-1.30303030303030e+01 -1.08076735917766e+00 1.07643742796169e-01 -7.83926565619422e-03 +-1.24242424242424e+01 -1.03727303023693e+00 9.49346653316282e-02 -1.75014551808433e-02 +-1.18181818181818e+01 -9.91440219649850e-01 8.26304983608341e-02 -2.54111950263429e-02 +-1.12121212121212e+01 -9.43045452072816e-01 7.24323611406984e-02 -2.97310850160300e-02 +-1.06060606060606e+01 -8.91357118244056e-01 6.36793113860100e-02 -3.46811573258460e-02 +-1.00000000000000e+01 -8.38640919151541e-01 5.56031252905086e-02 -4.00042772613043e-02 +-9.39393939393939e+00 -7.97154810810589e-01 4.56286447472684e-02 -4.58057854493708e-02 +-8.78787878787879e+00 -7.57700218153473e-01 3.48441279722901e-02 -5.20559338844009e-02 +-8.18181818181818e+00 -7.29615756802838e-01 2.21903132460571e-02 -5.98183982708405e-02 +-7.57575757575758e+00 -6.77769009447363e-01 1.66725656645290e-02 -6.52314095706447e-02 +-6.96969696969697e+00 -6.15253643707113e-01 1.38193953292020e-02 -6.96903302338436e-02 +-6.36363636363636e+00 -5.29222888480069e-01 1.28208124258429e-02 -7.60443151485867e-02 +-5.75757575757576e+00 -4.43714189157886e-01 1.18605164320041e-02 -8.20746230823483e-02 +-5.15151515151515e+00 -3.59021198798114e-01 1.11014093554157e-02 -8.75040133661531e-02 +-4.54545454545454e+00 -2.75625966933364e-01 1.06136414059815e-02 -9.20337243383322e-02 +-3.93939393939394e+00 -1.92587400034749e-01 1.02273414896665e-02 -9.62397074831400e-02 +-3.33333333333333e+00 -1.09292475701538e-01 9.90518405717358e-03 -9.99005436593104e-02 +-2.72727272727273e+00 -2.77772625212584e-02 9.71093449432091e-03 -1.03217781859456e-01 +-2.12121212121212e+00 5.20911798292055e-02 9.64590630058275e-03 -1.06366269240076e-01 +-1.51515151515152e+00 1.30586446388122e-01 9.55659941113129e-03 -1.09005739501319e-01 +-9.09090909090912e-01 2.08840498658564e-01 9.49982823781086e-03 -1.11539847170668e-01 +-3.03030303030302e-01 2.87578475260949e-01 9.58414006664110e-03 -1.13902065395105e-01 + 3.03030303030302e-01 3.65664552744906e-01 9.65560539372337e-03 -1.16149780563894e-01 + 9.09090909090912e-01 4.43204973276288e-01 9.71978591639622e-03 -1.18219507269873e-01 + 1.51515151515152e+00 5.20281024804697e-01 9.71394548831763e-03 -1.20121864462230e-01 + 2.12121212121212e+00 5.96811467615798e-01 9.80332128304454e-03 -1.21920157367353e-01 + 2.72727272727273e+00 6.71434914937960e-01 9.98488831915120e-03 -1.23594864438980e-01 + 3.33333333333333e+00 7.45656831699806e-01 1.01455835290262e-02 -1.25107525282158e-01 + 3.93939393939394e+00 8.19857800959508e-01 1.02378295152185e-02 -1.26457757043226e-01 + 4.54545454545455e+00 8.93627925198807e-01 1.03669090136902e-02 -1.27577353045154e-01 + 5.15151515151515e+00 9.66788832639503e-01 1.05314448784099e-02 -1.28565417198802e-01 + 5.75757575757576e+00 1.03821639854981e+00 1.07650302198420e-02 -1.29227175957820e-01 + 6.36363636363637e+00 1.10795832677679e+00 1.10272583218359e-02 -1.29514536462203e-01 + 6.96969696969697e+00 1.17694418225097e+00 1.12742209874335e-02 -1.29549901025754e-01 + 7.57575757575757e+00 1.23921531344826e+00 1.16670639800197e-02 -1.28261266809327e-01 + 8.18181818181818e+00 1.29706014706839e+00 1.24490049337565e-02 -1.26386684375794e-01 + 8.78787878787879e+00 1.34554047570179e+00 1.37772189838099e-02 -1.23143424626972e-01 + 9.39393939393939e+00 1.37610897192605e+00 1.75961680761005e-02 -1.21674324726306e-01 + 1.00000000000000e+01 1.39836265121160e+00 2.28583111147752e-02 -1.21039639768622e-01 + 1.06060606060606e+01 1.39287314658036e+00 2.77463509449118e-02 -1.19204194226554e-01 + 1.12121212121212e+01 1.39004598907911e+00 3.19782079487326e-02 -1.15663804195089e-01 + 1.18181818181818e+01 1.39216407137552e+00 3.49921524756390e-02 -1.09850755288886e-01 + 1.24242424242424e+01 1.29370295829420e+00 4.85210271088614e-02 -1.10247193463411e-01 + 1.30303030303030e+01 1.14384582375774e+00 6.62157966012066e-02 -1.11897572147813e-01 + 1.36363636363636e+01 1.11782919778447e+00 7.57838750439830e-02 -1.11408861155646e-01 + 1.42424242424242e+01 1.09289947478728e+00 8.53102626033743e-02 -1.11136178965314e-01 + 1.48484848484848e+01 1.07102348419001e+00 9.46544491998690e-02 -1.11159785150535e-01 + 1.54545454545455e+01 1.05696164008760e+00 1.03374871102944e-01 -1.10493943921915e-01 + 1.60606060606061e+01 1.04604302431932e+00 1.11858598309336e-01 -1.10049366517221e-01 + 1.66666666666667e+01 1.03932307570257e+00 1.20082914343280e-01 -1.09980310610667e-01 + 1.72727272727273e+01 1.03747930790449e+00 1.29111242533919e-01 -1.10591886748552e-01 + 1.78787878787879e+01 1.04205220466167e+00 1.39122262444516e-01 -1.12023579838031e-01 + 1.84848484848485e+01 1.05490344379951e+00 1.50986790721675e-01 -1.15270449343547e-01 + 1.90909090909091e+01 1.06946548085938e+00 1.63292698023894e-01 -1.19065362073820e-01 + 1.96969696969697e+01 1.08276085154215e+00 1.75474320562998e-01 -1.23397138492291e-01 + 2.03030303030303e+01 1.09403365481318e+00 1.88008089241998e-01 -1.28358085737133e-01 + 2.09090909090909e+01 1.10239238595793e+00 2.00894023983065e-01 -1.33614744559156e-01 + 2.15151515151515e+01 1.10887254746938e+00 2.13779958724133e-01 -1.38763402571504e-01 + 2.21212121212121e+01 1.11237585687728e+00 2.26320681259285e-01 -1.44191042062497e-01 + 2.27272727272727e+01 1.10397482083247e+00 2.37480910168700e-01 -1.50693555732446e-01 + 2.33333333333333e+01 1.09557378478766e+00 2.48641139078116e-01 -1.57112728954266e-01 + 2.39393939393939e+01 1.08717274874285e+00 2.59801367987532e-01 -1.63133329944962e-01 + 2.45454545454545e+01 1.08003882943089e+00 2.71421389304264e-01 -1.68354300674623e-01 + 2.51515151515151e+01 1.07304569783844e+00 2.83092497567289e-01 -1.73495272149449e-01 + 2.57575757575758e+01 1.06605256624600e+00 2.94763605830315e-01 -1.78646564861648e-01 + 2.63636363636364e+01 1.05985153546545e+00 3.06826689596951e-01 -1.83426648708445e-01 + 2.69696969696970e+01 1.05417865395407e+00 3.19151130974461e-01 -1.87959534349431e-01 + 2.75757575757576e+01 1.04850577244270e+00 3.31475572351972e-01 -1.92498924465493e-01 + 2.81818181818182e+01 1.04309074438137e+00 3.43977607118473e-01 -1.96910710531247e-01 + 2.87878787878788e+01 1.03827732275955e+00 3.56893990913108e-01 -2.01014545276943e-01 + 2.93939393939394e+01 1.03346390113772e+00 3.69810374707743e-01 -2.05122663450476e-01 + 3.00000000000000e+01 1.02865047951590e+00 3.82726758502379e-01 -2.09235101253211e-01 + 3.30000000000000e+01 1.00767522728702e+00 4.50048605759265e-01 -2.27666231032229e-01 + 3.60000000000000e+01 9.87502112870606e-01 5.20200446113040e-01 -2.44805976520978e-01 + 3.90000000000000e+01 9.66075877033301e-01 5.93029893358622e-01 -2.61539856917676e-01 + 4.20000000000000e+01 9.41098858571731e-01 6.67518950513352e-01 -2.77304866762762e-01 + 4.50000000000000e+01 9.14833592285066e-01 7.42420845191650e-01 -2.92778427054725e-01 + 4.80000000000000e+01 8.81408622533811e-01 8.17249434089067e-01 -3.07497585034756e-01 + 5.10000000000000e+01 8.43819604431597e-01 8.90525057771138e-01 -3.21903684993278e-01 + 5.40000000000000e+01 7.97902221930250e-01 9.60694651185909e-01 -3.35704391970839e-01 + 5.70000000000000e+01 7.51985042501660e-01 1.03086370854641e+00 -3.49495136575764e-01 + 6.00000000000000e+01 7.06067964608676e-01 1.10103249788183e+00 -3.63279172814127e-01 + 6.30000000000000e+01 6.44293944876385e-01 1.15795405351184e+00 -3.75684064171539e-01 + 6.60000000000000e+01 5.82519789224936e-01 1.21487549559204e+00 -3.88081898949555e-01 + 6.90000000000000e+01 5.20745633573486e-01 1.27179693767224e+00 -4.00474177818223e-01 + 7.20000000000000e+01 4.51451982439921e-01 1.31524577920238e+00 -4.11592132530663e-01 + 7.50000000000000e+01 3.78398737499386e-01 1.35195859625958e+00 -4.22069569360111e-01 + 7.80000000000000e+01 3.05344055424385e-01 1.38867183401641e+00 -4.32541989601588e-01 + 8.10000000000000e+01 2.30976975521496e-01 1.41713840709990e+00 -4.42143819760501e-01 + 8.40000000000000e+01 1.53985190557838e-01 1.42911222008308e+00 -4.50008085895448e-01 + 8.70000000000000e+01 7.69925651285527e-02 1.44108612453959e+00 -4.57867677290619e-01 + 9.00000000000000e+01 -3.36373889913427e-07 1.45305992526757e+00 -4.65723360969959e-01 + 9.30000000000000e+01 -5.38949836895802e-02 1.44108611228438e+00 -4.70213156857291e-01 + 9.60000000000000e+01 -1.07789636867620e-01 1.42911225356491e+00 -4.74730592511974e-01 + 9.90000000000000e+01 -1.61684301770570e-01 1.41713830337121e+00 -4.79276533058230e-01 + 1.02000000000000e+02 -2.13741036335945e-01 1.38867165620685e+00 -4.80562246931058e-01 + 1.05000000000000e+02 -2.64878825634710e-01 1.35195883914965e+00 -4.80232757378909e-01 + 1.08000000000000e+02 -3.16016600929376e-01 1.31524560139462e+00 -4.79737782066907e-01 + 1.11000000000000e+02 -3.64522317186419e-01 1.27179644456681e+00 -4.77863421662414e-01 + 1.14000000000000e+02 -4.07763995533133e-01 1.21487565475428e+00 -4.73449633291489e-01 + 1.17000000000000e+02 -4.51005751931015e-01 1.15795443010112e+00 -4.69034472019867e-01 + 1.20000000000000e+02 -4.94247525649446e-01 1.10103296211486e+00 -4.64618222554077e-01 + 1.23000000000000e+02 -5.26389596453192e-01 1.03086417277945e+00 -4.58370282910620e-01 + 1.26000000000000e+02 -5.58531663885406e-01 9.60695115424263e-01 -4.52121193405810e-01 + 1.29000000000000e+02 -5.90673724574306e-01 8.90525522009491e-01 -4.45870794666629e-01 + 1.32000000000000e+02 -6.15315579547438e-01 8.17225281824516e-01 -4.40405924630618e-01 + 1.35000000000000e+02 -6.36207340549935e-01 7.42359721972419e-01 -4.35333210353452e-01 + 1.38000000000000e+02 -6.57098483724280e-01 6.67494798442361e-01 -4.30259571411825e-01 + 1.41000000000000e+02 -6.75928714282518e-01 5.94098982936727e-01 -4.27362077072584e-01 + 1.44000000000000e+02 -6.90637102885333e-01 5.23641395400969e-01 -4.28817330039073e-01 + 1.47000000000000e+02 -7.05344979121394e-01 4.53184198414303e-01 -4.30270852318803e-01 + 1.50000000000000e+02 -7.20052599183224e-01 3.82727196695211e-01 -4.31722931389651e-01 + 1.53000000000000e+02 -7.10181631872742e-01 3.29822360950801e-01 -4.46423672577750e-01 + 1.56000000000000e+02 -7.03319879618389e-01 2.76917694334790e-01 -4.61114380563247e-01 + 1.59000000000000e+02 -6.96086980977297e-01 2.24013284168088e-01 -4.74558545497368e-01 + 1.62000000000000e+02 -6.23394384096259e-01 1.85740697616627e-01 -4.83189489859145e-01 + 1.65000000000000e+02 -5.19495002406176e-01 1.54784146617186e-01 -4.89493605397558e-01 + 1.68000000000000e+02 -4.15596211308916e-01 1.23827350356444e-01 -4.95797422538914e-01 + 1.71000000000000e+02 -3.11697223350018e-01 9.28705619946343e-02 -4.50000513056908e-01 + 1.74000000000000e+02 -2.07797841658894e-01 6.19137894310576e-02 -2.99999717902353e-01 + 1.77000000000000e+02 -1.03426007186958e-01 5.10483521183991e-02 -1.49315896260807e-01 + 1.80000000000000e+02 0.00000000000000e+00 5.02376982549728e-02 0.00000000000000e+00 diff --git a/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_18.dat b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_18.dat new file mode 100644 index 00000000..2754301a --- /dev/null +++ b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_18.dat @@ -0,0 +1,254 @@ +! ------------ AirfoilInfo v1.01.x Input File ---------------------------------- +! AeroElasticSE FAST driver +! line +! line +! ------------------------------------------------------------------------------ +DEFAULT InterpOrd ! Interpolation order to use for quasi-steady table lookup {1=linear; 3=cubic spline; "default"} [default=3] +1 NonDimArea ! The non-dimensional area of the airfoil (area/chord^2) (set to 1.0 if unsure or unneeded) +@"NREL-2p8-127_AF18_Coords.txt" NumCoords ! The number of coordinates in the airfoil shape file. Set to zero if coordinates not included. +AF18_BL.txt BL_file ! The file name including the boundary layer characteristics of the profile. Ignored if the aeroacoustic module is not called. +1 NumTabs ! Number of airfoil tables in this file. Each table must have lines for Re and Ctrl. +! ------------------------------------------------------------------------------ +! data for table 1 +! ------------------------------------------------------------------------------ +6.000000 Re ! Reynolds number in millions +0 Ctrl ! Control setting (must be 0 for current AirfoilInfo) +True InclUAdata ! Is unsteady aerodynamics data included in this table? If TRUE, then include 30 UA coefficients below this line +!........................................ +-2.792370 alpha0 ! 0-lift angle of attack, depends on airfoil. +9.587807 alpha1 ! Angle of attack at f=0.7, (approximately the stall angle) for AOA>alpha0. (deg) +-11.610700 alpha2 ! Angle of attack at f=0.7, (approximately the stall angle) for AOA1] +0.000000 S2 ! Constant in the f curve best-fit for AOA> alpha1; by definition it depends on the airfoil. [ignored if UAMod<>1] +0.000000 S3 ! Constant in the f curve best-fit for alpha2<=AOA< alpha0; by definition it depends on the airfoil. [ignored if UAMod<>1] +0.000000 S4 ! Constant in the f curve best-fit for AOA< alpha2; by definition it depends on the airfoil. [ignored if UAMod<>1] +1.342044 Cn1 ! Critical value of C0n at leading edge separation. It should be extracted from airfoil data at a given Mach and Reynolds number. It can be calculated from the static value of Cn at either the break in the pitching moment or the loss of chord force at the onset of stall. It is close to the condition of maximum lift of the airfoil at low Mach numbers. +-1.062317 Cn2 ! As Cn1 for negative AOAs. +Default St_sh ! Strouhal's shedding frequency constant. [default = 0.19] +0.008843 Cd0 ! 2D drag coefficient value at 0-lift. +-0.109829 Cm0 ! 2D pitching moment coefficient about 1/4-chord location, at 0-lift, positive if nose up. [If the aerodynamics coefficients table does not include a column for Cm, this needs to be set to 0.0] +0.000000 k0 ! Constant in the \hat(x)_cp curve best-fit; = (\hat(x)_AC-0.25). [ignored if UAMod<>1] +0.000000 k1 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k2 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k3 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k1_hat ! Constant in the expression of Cc due to leading edge vortex effects. [ignored if UAMod<>1] +Default x_cp_bar ! Constant in the expression of \hat(x)_cp^v. [ignored if UAMod<>1, default = 0.2] +Default UACutout ! Angle of attack above which unsteady aerodynamics are disabled (deg). [Specifying the string "Default" sets UACutout to 45 degrees] +Default filtCutOff ! Cut-off frequency (-3 dB corner frequency) for low-pass filtering the AoA input to UA, as well as the 1st and 2nd derivatives (Hz) [default = 20] +!........................................ +! Table of aerodynamics coefficients +200 NumAlf ! Number of data lines in the following table +! Alpha Cl Cd Cm +! (deg) (-) (-) (-) +-1.80000000000000e+02 0.00000000000000e+00 5.36137248474854e-02 0.00000000000000e+00 +-1.77000000000000e+02 1.08504173136844e-01 5.36137248474854e-02 1.19452717008645e-01 +-1.74000000000000e+02 2.18001573212032e-01 6.43364093197600e-02 2.39999774321882e-01 +-1.71000000000000e+02 3.27002606158882e-01 9.65048147530414e-02 3.60000410445527e-01 +-1.68000000000000e+02 4.36007303027872e-01 1.28672864881152e-01 3.18853353245729e-01 +-1.65000000000000e+02 5.45015893840642e-01 1.60840737360825e-01 1.97134330215277e-01 +-1.62000000000000e+02 6.54027865395150e-01 1.93008707125421e-01 7.54136410554247e-02 +-1.59000000000000e+02 7.27335195948828e-01 2.32421567454577e-01 -7.86707963484010e-03 +-1.56000000000000e+02 7.26473886558584e-01 2.86323963827313e-01 -1.32688253981472e-02 +-1.53000000000000e+02 7.26401782562124e-01 3.40226371983972e-01 -1.93321617932501e-02 +-1.50000000000000e+02 7.29414906072036e-01 3.94128823688151e-01 -3.04550520731389e-02 +-1.47000000000000e+02 7.13608094775223e-01 4.64191024348164e-01 -1.44069907171891e-02 +-1.44000000000000e+02 6.97801023105656e-01 5.34253347401846e-01 1.64143099960009e-03 +-1.41000000000000e+02 6.81993430671987e-01 6.04315915251604e-01 1.79777655646737e-02 +-1.38000000000000e+02 6.62330345884982e-01 6.77255624037684e-01 3.42196692787287e-02 +-1.35000000000000e+02 6.40739522742596e-01 7.51633897455329e-01 5.03555236432470e-02 +-1.32000000000000e+02 6.19148287855155e-01 8.26012587517633e-01 6.64803246966578e-02 +-1.29000000000000e+02 5.93883607684111e-01 8.98800336981566e-01 8.26682061752675e-02 +-1.26000000000000e+02 5.61272019531039e-01 9.68406197695395e-01 9.89967979935854e-02 +-1.23000000000000e+02 5.28660570956951e-01 1.03801152665627e+00 1.15320660255902e-01 +-1.20000000000000e+02 4.96049192169745e-01 1.10761658975060e+00 1.31640184505148e-01 +-1.17000000000000e+02 4.52499966498427e-01 1.16391394816134e+00 1.47076828299769e-01 +-1.14000000000000e+02 4.08950831006833e-01 1.22021106550486e+00 1.62511306961593e-01 +-1.11000000000000e+02 3.65401918647224e-01 1.27650775277552e+00 1.77943395962959e-01 +-1.08000000000000e+02 3.16676605002551e-01 1.31930568274196e+00 1.91712305326037e-01 +-1.05000000000000e+02 2.65363051300195e-01 1.35535413126937e+00 2.04649708702310e-01 +-1.02000000000000e+02 2.14049485607990e-01 1.39140216671678e+00 2.17585944039292e-01 +-9.90000000000000e+01 1.61856439692740e-01 1.41919689307479e+00 2.29156194914714e-01 +-9.60000000000000e+01 1.07904395236486e-01 1.43048464375975e+00 2.37995669823376e-01 +-9.30000000000000e+01 5.39523629434884e-02 1.44177230821265e+00 2.46835565853370e-01 +-9.00000000000000e+01 3.36732009892260e-07 1.45305992955031e+00 2.55676268872361e-01 +-8.70000000000000e+01 -5.39523077235666e-02 1.44177231976554e+00 2.60546156064344e-01 +-8.40000000000000e+01 -1.07904546098422e-01 1.43048461219668e+00 2.65376218554658e-01 +-8.10000000000000e+01 -1.61855972313595e-01 1.41919699085902e+00 2.70167661087483e-01 +-7.80000000000000e+01 -2.14049237083272e-01 1.39140234130663e+00 2.71634637929492e-01 +-7.50000000000000e+01 -2.65363390787359e-01 1.35535389277745e+00 2.71422475089917e-01 +-7.20000000000000e+01 -3.16676356483258e-01 1.31930585733004e+00 2.71175587395195e-01 +-6.90000000000000e+01 -3.65401541382520e-01 1.27650824047434e+00 2.69624220790176e-01 +-6.60000000000000e+01 -4.08950952778550e-01 1.22021090808774e+00 2.65499895797782e-01 +-6.30000000000000e+01 -4.52500254617964e-01 1.16391357570114e+00 2.61346777314543e-01 +-6.00000000000000e+01 -4.96049407924919e-01 1.10761612924714e+00 2.57166068579216e-01 +-5.70000000000000e+01 -5.28660786712125e-01 1.03801106615281e+00 2.51133429071216e-01 +-5.40000000000000e+01 -5.61272235287598e-01 9.68405737186667e-01 2.45075869286174e-01 +-5.10000000000000e+01 -5.93883823440670e-01 8.98799876472838e-01 2.38994436395362e-01 +-4.80000000000000e+01 -6.20771155324413e-01 8.26050727323750e-01 2.33161030617360e-01 +-4.50000000000000e+01 -6.44796451070394e-01 7.51729984474128e-01 2.27439298824510e-01 +-4.20000000000000e+01 -6.63953200654077e-01 6.77293763541013e-01 2.23291102757799e-01 +-3.90000000000000e+01 -6.82249667333847e-01 6.03259850610683e-01 2.19817265076178e-01 +-3.60000000000000e+01 -6.98201576773723e-01 5.30851294361004e-01 2.18838619571564e-01 +-3.30000000000000e+01 -7.13444606626873e-01 4.61088222324340e-01 2.21122290445851e-01 +-3.00000000000000e+01 -7.29415020855328e-01 3.94128387846700e-01 2.27054455296579e-01 +-2.93939393939394e+01 -7.33089414277251e-01 3.81279477717506e-01 2.29240557823958e-01 +-2.87878787878788e+01 -7.36763807699173e-01 3.68430567588313e-01 2.31426660351336e-01 +-2.81818181818182e+01 -7.40438201121096e-01 3.55581657459119e-01 2.33612762878715e-01 +-2.75757575757576e+01 -7.44561188035578e-01 3.43144145729673e-01 2.36503775794692e-01 +-2.69696969696970e+01 -7.48876445797132e-01 3.30882962725711e-01 2.39696919079866e-01 +-2.63636363636364e+01 -7.53191703558686e-01 3.18621779721749e-01 2.42890062365039e-01 +-2.57575757575758e+01 -7.57896949106898e-01 3.06620180092045e-01 2.46611383026609e-01 +-2.51515151515151e+01 -7.63187085443502e-01 2.95007895024532e-01 2.51124846654346e-01 +-2.45454545454545e+01 -7.68477221780106e-01 2.83395609957020e-01 2.55638310282083e-01 +-2.39393939393939e+01 -7.74029112998335e-01 2.71848572457760e-01 2.59427106627508e-01 +-2.33333333333333e+01 -7.81936848828191e-01 2.60888775705009e-01 2.56693757133074e-01 +-2.27272727272727e+01 -7.89844584658047e-01 2.49928978952259e-01 2.54973507041906e-01 +-2.21212121212121e+01 -7.97752320487903e-01 2.38969182199509e-01 2.51757698493230e-01 +-2.15151515151515e+01 -8.17245649453576e-01 2.29474770810752e-01 2.34218156316905e-01 +-2.09090909090909e+01 -8.40715821523898e-01 2.20346800023089e-01 2.15558365010287e-01 +-2.03030303030303e+01 -8.64893147204684e-01 2.11218829235425e-01 1.97258668465790e-01 +-1.96969696969697e+01 -8.87438946084652e-01 2.02091078490948e-01 1.79104249713839e-01 +-1.90909090909091e+01 -9.09237361854086e-01 1.92963547777208e-01 1.61007469502170e-01 +-1.84848484848485e+01 -9.33071785400616e-01 1.84171846523930e-01 1.42945493987761e-01 +-1.78787878787879e+01 -9.57306241435504e-01 1.76283936647877e-01 1.23884251763747e-01 +-1.72727272727273e+01 -9.81604014520295e-01 1.68616795799771e-01 1.04367473421751e-01 +-1.66666666666667e+01 -1.00737125830751e+00 1.60297507335738e-01 8.48827458147722e-02 +-1.60606060606061e+01 -1.03415415721149e+00 1.51566539016137e-01 6.54371368564537e-02 +-1.54545454545455e+01 -1.05213926667993e+00 1.41887359500634e-01 4.85999555851204e-02 +-1.48484848484848e+01 -1.06411426754698e+00 1.31650218002569e-01 3.32132244253039e-02 +-1.42424242424242e+01 -1.06085920517278e+00 1.20325281854275e-01 1.97519541398105e-02 +-1.36363636363636e+01 -1.05297179510023e+00 1.08818108910721e-01 3.34724170517964e-03 +-1.30303030303030e+01 -1.04038617850512e+00 9.71704693558744e-02 -1.30280274230778e-02 +-1.24242424242424e+01 -1.00963309974379e+00 8.35931628390448e-02 -2.24525867458495e-02 +-1.18181818181818e+01 -9.74392976542105e-01 7.02569290424257e-02 -2.96665236814477e-02 +-1.12121212121212e+01 -9.33183989496999e-01 5.92863820290872e-02 -3.25396861725729e-02 +-1.06060606060606e+01 -8.87095198505282e-01 5.02112419249079e-02 -3.68554806252278e-02 +-1.00000000000000e+01 -8.39030346732209e-01 4.20062550430957e-02 -4.19667667411679e-02 +-9.39393939393939e+00 -7.98355307687373e-01 3.39431550888320e-02 -4.71586015184073e-02 +-8.78787878787879e+00 -7.55075718086549e-01 2.58616329336961e-02 -5.31128483759924e-02 +-8.18181818181818e+00 -7.12760376198709e-01 1.76807004789459e-02 -6.15557949547917e-02 +-7.57575757575758e+00 -6.50212657860430e-01 1.40779977251651e-02 -6.80037285779409e-02 +-6.96969696969697e+00 -5.79316182872428e-01 1.20930353131595e-02 -7.36947785344258e-02 +-6.36363636363636e+00 -4.93332487227875e-01 1.12571113999265e-02 -8.08636763018482e-02 +-5.75757575757576e+00 -4.07625165812638e-01 1.04386697349651e-02 -8.76670243494600e-02 +-5.15151515151515e+00 -3.22375665042248e-01 9.89046924180047e-03 -9.37249643058138e-02 +-4.54545454545454e+00 -2.38569752393226e-01 9.55568172944726e-03 -9.85721042394988e-02 +-3.93939393939394e+00 -1.55278792252772e-01 9.28231334429143e-03 -1.03000270064649e-01 +-3.33333333333333e+00 -7.27588785201134e-02 9.00905966504459e-03 -1.06804167238102e-01 +-2.72727272727273e+00 8.75545142458852e-03 8.82260921114890e-03 -1.10193484668354e-01 +-2.12121212121212e+00 8.90951677107422e-02 8.71711984822585e-03 -1.13439603715240e-01 +-1.51515151515152e+00 1.68020877233593e-01 8.63506810960759e-03 -1.15955900231793e-01 +-9.09090909090912e-01 2.46284645308487e-01 8.59786619783916e-03 -1.18329762049110e-01 +-3.03030303030302e-01 3.23526927130680e-01 8.68469307519355e-03 -1.20499605866875e-01 + 3.03030303030302e-01 4.00568746060339e-01 8.73666462420641e-03 -1.22563336532720e-01 + 9.09090909090912e-01 4.77532382355605e-01 8.76693795829447e-03 -1.24415248851028e-01 + 1.51515151515152e+00 5.54310964834009e-01 8.75563015487188e-03 -1.26154371277845e-01 + 2.12121212121212e+00 6.30748642497307e-01 8.89942708059405e-03 -1.27777288327563e-01 + 2.72727272727273e+00 7.05967166479233e-01 9.07466954914071e-03 -1.29308981144731e-01 + 3.33333333333333e+00 7.80411644410489e-01 9.23152948118853e-03 -1.30694777177827e-01 + 3.93939393939394e+00 8.54634907157449e-01 9.35773501083766e-03 -1.31925075915747e-01 + 4.54545454545455e+00 9.28368090200400e-01 9.52948973845109e-03 -1.32899735261145e-01 + 5.15151515151515e+00 1.00145694605734e+00 9.73306782417346e-03 -1.33724225695198e-01 + 5.75757575757576e+00 1.07270733762567e+00 1.00006966462114e-02 -1.34169484840169e-01 + 6.36363636363637e+00 1.14127724503204e+00 1.02973665103093e-02 -1.34153350705440e-01 + 6.96969696969697e+00 1.20864942903410e+00 1.05582170564899e-02 -1.33827802118801e-01 + 7.57575757575757e+00 1.26443440681650e+00 1.10668993698580e-02 -1.31662626204201e-01 + 8.18181818181818e+00 1.31327712628436e+00 1.21179224024120e-02 -1.28718467346890e-01 + 8.78787878787879e+00 1.34931677106702e+00 1.38745085223537e-02 -1.24009773357878e-01 + 9.39393939393939e+00 1.35685700568352e+00 2.07295073959453e-02 -1.22353831339396e-01 + 1.00000000000000e+01 1.34623269398792e+00 3.03611166129043e-02 -1.22101994507537e-01 + 1.06060606060606e+01 1.29247625354756e+00 3.89303371400334e-02 -1.20772828739056e-01 + 1.12121212121212e+01 1.25212720004798e+00 4.59269172993146e-02 -1.17349872385937e-01 + 1.18181818181818e+01 1.23668533143930e+00 5.00033361654154e-02 -1.11373005101486e-01 + 1.24242424242424e+01 1.18614194111661e+00 6.00007067895342e-02 -1.09801411206576e-01 + 1.30303030303030e+01 1.11590193321859e+00 7.24445919904755e-02 -1.08383334659172e-01 + 1.36363636363636e+01 1.11070643578549e+00 8.22712281118321e-02 -1.09098841523507e-01 + 1.42424242424242e+01 1.10016431536211e+00 9.22478830207050e-02 -1.10082030306725e-01 + 1.48484848484848e+01 1.08932388927719e+00 1.02384259095179e-01 -1.11305168394289e-01 + 1.54545454545455e+01 1.08265839747059e+00 1.11362550974526e-01 -1.11223542069270e-01 + 1.60606060606061e+01 1.07750353752455e+00 1.19864697023678e-01 -1.11093423299158e-01 + 1.66666666666667e+01 1.07245197326073e+00 1.27554831236544e-01 -1.10774119006494e-01 + 1.72727272727273e+01 1.07224113795030e+00 1.36494897934856e-01 -1.11302931932702e-01 + 1.78787878787879e+01 1.07862447668773e+00 1.46962675742666e-01 -1.12850875597998e-01 + 1.84848484848485e+01 1.08861259617754e+00 1.59145187067245e-01 -1.16200177309305e-01 + 1.90909090909091e+01 1.09918905179666e+00 1.71646795036045e-01 -1.20001587294594e-01 + 1.96969696969697e+01 1.10912810899916e+00 1.83527588865384e-01 -1.23816697554203e-01 + 2.03030303030303e+01 1.11825522290028e+00 1.96466839959649e-01 -1.28421649372128e-01 + 2.09090909090909e+01 1.12524803924632e+00 2.10464608199569e-01 -1.33477817053054e-01 + 2.15151515151515e+01 1.12945414332918e+00 2.24462376439488e-01 -1.38427537382908e-01 + 2.21212121212121e+01 1.13110996428679e+00 2.37920120683396e-01 -1.43742831263358e-01 + 2.27272727272727e+01 1.12256727679690e+00 2.49218324588170e-01 -1.50497808264014e-01 + 2.33333333333333e+01 1.11402458930701e+00 2.60516528492943e-01 -1.57166764414652e-01 + 2.39393939393939e+01 1.10548190181713e+00 2.71814732397717e-01 -1.63463059451524e-01 + 2.45454545454545e+01 1.09782581769558e+00 2.83395609957020e-01 -1.68925418413166e-01 + 2.51515151515151e+01 1.09026824294031e+00 2.95007895024532e-01 -1.74308243109077e-01 + 2.57575757575758e+01 1.08271066818504e+00 3.06620180092045e-01 -1.79706378559642e-01 + 2.63636363636364e+01 1.07598865169483e+00 3.18621779721749e-01 -1.84704949130393e-01 + 2.69696969696970e+01 1.06982376061140e+00 3.30882962725711e-01 -1.89437565776199e-01 + 2.75757575757576e+01 1.06365886952798e+00 3.43144145729673e-01 -1.94179831305997e-01 + 2.81818181818182e+01 1.05776902996474e+00 3.55581657459119e-01 -1.98785028498289e-01 + 2.87878787878788e+01 1.05252092222901e+00 3.68430567588313e-01 -2.03055245546250e-01 + 2.93939393939394e+01 1.04727281449329e+00 3.81279477717506e-01 -2.07331816726986e-01 + 3.00000000000000e+01 1.04202470675756e+00 3.94128387846700e-01 -2.11614795742417e-01 + 3.30000000000000e+01 1.01920513278199e+00 4.61088222324340e-01 -2.30709635446696e-01 + 3.60000000000000e+01 9.97430021449977e-01 5.30851294361004e-01 -2.48389635018723e-01 + 3.90000000000000e+01 9.74642622581348e-01 6.03259850610683e-01 -2.65244377392235e-01 + 4.20000000000000e+01 9.48504923410187e-01 6.77293763541014e-01 -2.81146520062724e-01 + 4.50000000000000e+01 9.21138527003474e-01 7.51729984474128e-01 -2.96778859241448e-01 + 4.80000000000000e+01 8.86816262654281e-01 8.26050727323750e-01 -3.11620664341732e-01 + 5.10000000000000e+01 8.48405523199447e-01 8.98799876472838e-01 -3.26146108681646e-01 + 5.40000000000000e+01 8.01817570694549e-01 9.68405737186667e-01 -3.40039290927774e-01 + 5.70000000000000e+01 7.55229683651232e-01 1.03801106615281e+00 -3.53931325023812e-01 + 6.00000000000000e+01 7.08641829338459e-01 1.10761612924715e+00 -3.67824192591327e-01 + 6.30000000000000e+01 6.46428682755529e-01 1.16391357570114e+00 -3.80297188353490e-01 + 6.60000000000000e+01 5.84215402239047e-01 1.22021090808774e+00 -3.92768487627463e-01 + 6.90000000000000e+01 5.22002121722564e-01 1.27650824047434e+00 -4.05238805155188e-01 + 7.20000000000000e+01 4.52394670864868e-01 1.31930585733004e+00 -4.16419077136110e-01 + 7.50000000000000e+01 3.79090286205083e-01 1.35535389277745e+00 -4.26952712546759e-01 + 7.80000000000000e+01 3.05784461532969e-01 1.39140234130664e+00 -4.37484524738100e-01 + 8.10000000000000e+01 2.31222621050345e-01 1.41919699085902e+00 -4.47140901263708e-01 + 8.40000000000000e+01 1.54148835649795e-01 1.43048461219668e+00 -4.55046838069807e-01 + 8.70000000000000e+01 7.70743518918329e-02 1.44177231976554e+00 -4.62950611733494e-01 + 9.00000000000000e+01 -3.36732010122695e-07 1.45305992955031e+00 -4.70852706467098e-01 + 9.30000000000000e+01 -5.39523629434884e-02 1.44177230821265e+00 -4.75763515343477e-01 + 9.60000000000000e+01 -1.07904395236486e-01 1.43048464375975e+00 -4.80716438183718e-01 + 9.90000000000000e+01 -1.61856439692741e-01 1.41919689307479e+00 -4.85712617490280e-01 + 1.02000000000000e+02 -2.14049485607990e-01 1.39140216671678e+00 -4.87463918618097e-01 + 1.05000000000000e+02 -2.65363051300195e-01 1.35535413126937e+00 -4.87615426725982e-01 + 1.08000000000000e+02 -3.16676605002551e-01 1.31930568274196e+00 -4.87522734138826e-01 + 1.11000000000000e+02 -3.65401918647224e-01 1.27650775277552e+00 -4.85996410622861e-01 + 1.14000000000000e+02 -4.08950831006833e-01 1.22021106550486e+00 -4.81927358927190e-01 + 1.17000000000000e+02 -4.52499966498427e-01 1.16391394816134e+00 -4.77857363874255e-01 + 1.20000000000000e+02 -4.96049192169745e-01 1.10761658975060e+00 -4.73786676400946e-01 + 1.23000000000000e+02 -5.28660570956951e-01 1.03801152665627e+00 -4.67894035404986e-01 + 1.26000000000000e+02 -5.61272019531039e-01 9.68406197695395e-01 -4.62000666821961e-01 + 1.29000000000000e+02 -5.93883607684111e-01 8.98800336981565e-01 -4.56106383315202e-01 + 1.32000000000000e+02 -6.19148287855155e-01 8.26012587517633e-01 -4.51045249617514e-01 + 1.35000000000000e+02 -6.40739522742596e-01 7.51633897455329e-01 -4.46400358390250e-01 + 1.38000000000000e+02 -6.62330345884983e-01 6.77255624037683e-01 -4.41754984328411e-01 + 1.41000000000000e+02 -6.81993430671987e-01 6.04315915251604e-01 -4.39372656415041e-01 + 1.44000000000000e+02 -6.97801023105656e-01 5.34253347401846e-01 -4.41516679399736e-01 + 1.47000000000000e+02 -7.13608094775223e-01 4.64191024348164e-01 -4.43659776127911e-01 + 1.50000000000000e+02 -7.29414906072037e-01 3.94128823688151e-01 -4.45802094533083e-01 + 1.53000000000000e+02 -7.15037146111127e-01 3.41731197240688e-01 -4.59822411066617e-01 + 1.56000000000000e+02 -7.05123336765058e-01 2.89333666877955e-01 -4.73837152031237e-01 + 1.59000000000000e+02 -6.95414684317536e-01 2.36936246357618e-01 -4.86012649076484e-01 + 1.62000000000000e+02 -6.22098323807239e-01 1.97523498321224e-01 -4.91995579783009e-01 + 1.65000000000000e+02 -5.18414913187139e-01 1.64603196340870e-01 -4.94997251401146e-01 + 1.68000000000000e+02 -4.14732090684931e-01 1.31682671601892e-01 -4.97998891218103e-01 + 1.71000000000000e+02 -3.11049072145794e-01 9.87620758945397e-02 -4.50000513056908e-01 + 1.74000000000000e+02 -2.07365661523777e-01 6.58413382471257e-02 -2.99999717902353e-01 + 1.77000000000000e+02 -1.03210513612473e-01 5.43627855211274e-02 -1.49315896260807e-01 + 1.80000000000000e+02 0.00000000000000e+00 5.36137248474854e-02 0.00000000000000e+00 diff --git a/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_19.dat b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_19.dat new file mode 100644 index 00000000..de96b588 --- /dev/null +++ b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_19.dat @@ -0,0 +1,254 @@ +! ------------ AirfoilInfo v1.01.x Input File ---------------------------------- +! AeroElasticSE FAST driver +! line +! line +! ------------------------------------------------------------------------------ +DEFAULT InterpOrd ! Interpolation order to use for quasi-steady table lookup {1=linear; 3=cubic spline; "default"} [default=3] +1 NonDimArea ! The non-dimensional area of the airfoil (area/chord^2) (set to 1.0 if unsure or unneeded) +@"NREL-2p8-127_AF19_Coords.txt" NumCoords ! The number of coordinates in the airfoil shape file. Set to zero if coordinates not included. +AF19_BL.txt BL_file ! The file name including the boundary layer characteristics of the profile. Ignored if the aeroacoustic module is not called. +1 NumTabs ! Number of airfoil tables in this file. Each table must have lines for Re and Ctrl. +! ------------------------------------------------------------------------------ +! data for table 1 +! ------------------------------------------------------------------------------ +6.000000 Re ! Reynolds number in millions +0 Ctrl ! Control setting (must be 0 for current AirfoilInfo) +True InclUAdata ! Is unsteady aerodynamics data included in this table? If TRUE, then include 30 UA coefficients below this line +!........................................ +-3.045221 alpha0 ! 0-lift angle of attack, depends on airfoil. +9.266236 alpha1 ! Angle of attack at f=0.7, (approximately the stall angle) for AOA>alpha0. (deg) +-11.753418 alpha2 ! Angle of attack at f=0.7, (approximately the stall angle) for AOA1] +0.000000 S2 ! Constant in the f curve best-fit for AOA> alpha1; by definition it depends on the airfoil. [ignored if UAMod<>1] +0.000000 S3 ! Constant in the f curve best-fit for alpha2<=AOA< alpha0; by definition it depends on the airfoil. [ignored if UAMod<>1] +0.000000 S4 ! Constant in the f curve best-fit for AOA< alpha2; by definition it depends on the airfoil. [ignored if UAMod<>1] +1.340318 Cn1 ! Critical value of C0n at leading edge separation. It should be extracted from airfoil data at a given Mach and Reynolds number. It can be calculated from the static value of Cn at either the break in the pitching moment or the loss of chord force at the onset of stall. It is close to the condition of maximum lift of the airfoil at low Mach numbers. +-0.990977 Cn2 ! As Cn1 for negative AOAs. +Default St_sh ! Strouhal's shedding frequency constant. [default = 0.19] +0.008173 Cd0 ! 2D drag coefficient value at 0-lift. +-0.112549 Cm0 ! 2D pitching moment coefficient about 1/4-chord location, at 0-lift, positive if nose up. [If the aerodynamics coefficients table does not include a column for Cm, this needs to be set to 0.0] +0.000000 k0 ! Constant in the \hat(x)_cp curve best-fit; = (\hat(x)_AC-0.25). [ignored if UAMod<>1] +0.000000 k1 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k2 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k3 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k1_hat ! Constant in the expression of Cc due to leading edge vortex effects. [ignored if UAMod<>1] +Default x_cp_bar ! Constant in the expression of \hat(x)_cp^v. [ignored if UAMod<>1, default = 0.2] +Default UACutout ! Angle of attack above which unsteady aerodynamics are disabled (deg). [Specifying the string "Default" sets UACutout to 45 degrees] +Default filtCutOff ! Cut-off frequency (-3 dB corner frequency) for low-pass filtering the AoA input to UA, as well as the 1st and 2nd derivatives (Hz) [default = 20] +!........................................ +! Table of aerodynamics coefficients +200 NumAlf ! Number of data lines in the following table +! Alpha Cl Cd Cm +! (deg) (-) (-) (-) +-1.80000000000000e+02 0.00000000000000e+00 5.58151028351338e-02 0.00000000000000e+00 +-1.77000000000000e+02 1.08403822920070e-01 5.58151028351338e-02 1.19452717008645e-01 +-1.74000000000000e+02 2.17800459908011e-01 6.69780604209238e-02 2.39999774321882e-01 +-1.71000000000000e+02 3.26700878169450e-01 1.00467299648537e-01 3.60000410445527e-01 +-1.68000000000000e+02 4.35601558622185e-01 1.33956266552371e-01 3.19240159788981e-01 +-1.65000000000000e+02 5.44502718536549e-01 1.67445097297493e-01 1.98101342058805e-01 +-1.62000000000000e+02 6.53405489525881e-01 2.00933761249497e-01 7.69605856327805e-02 +-1.59000000000000e+02 7.27019339407255e-01 2.41089984114099e-01 -6.83110332274381e-03 +-1.56000000000000e+02 7.28728560841196e-01 2.94581099251365e-01 -1.48336824338646e-02 +-1.53000000000000e+02 7.31142347309657e-01 3.48072223030611e-01 -2.31137907275188e-02 +-1.50000000000000e+02 7.35519708784298e-01 4.01563389144863e-01 -3.46869785111124e-02 +-1.47000000000000e+02 7.18996156868714e-01 4.71368155114379e-01 -1.84787848110211e-02 +-1.44000000000000e+02 7.02472341842677e-01 5.41172995959272e-01 -2.27031145595949e-03 +-1.41000000000000e+02 6.85948000576950e-01 6.10977986560267e-01 1.41215595154545e-02 +-1.38000000000000e+02 6.65741843359713e-01 6.83620285576331e-01 3.03710500677338e-02 +-1.35000000000000e+02 6.43694785635686e-01 7.57681233044139e-01 4.65119317299114e-02 +-1.32000000000000e+02 6.21647450545519e-01 8.31742453913374e-01 6.26455676270925e-02 +-1.29000000000000e+02 5.95976649852831e-01 9.04196027753608e-01 7.88432528643242e-02 +-1.26000000000000e+02 5.63058900774808e-01 9.73434299905923e-01 9.51782729473790e-02 +-1.23000000000000e+02 5.30141386686949e-01 1.04267204311347e+00 1.11510014334606e-01 +-1.20000000000000e+02 4.97223990089781e-01 1.11190952185851e+00 1.27838839143617e-01 +-1.17000000000000e+02 4.53474286743658e-01 1.16779992225404e+00 1.43283454610664e-01 +-1.14000000000000e+02 4.09724721085944e-01 1.22369008305982e+00 1.58726450315576e-01 +-1.11000000000000e+02 3.65975473161876e-01 1.27957981690164e+00 1.74167578217843e-01 +-1.08000000000000e+02 3.17106968448641e-01 1.32195310670654e+00 1.87944896444489e-01 +-1.05000000000000e+02 2.65678796360799e-01 1.35756807157142e+00 2.00890123017622e-01 +-1.02000000000000e+02 2.14250613596524e-01 1.39318262832361e+00 2.13833889964470e-01 +-9.90000000000000e+01 1.61968684256675e-01 1.42053922078900e+00 2.25410295218944e-01 +-9.60000000000000e+01 1.07979224785424e-01 1.43137952698492e+00 2.34252955588311e-01 +-9.30000000000000e+01 5.39897777632595e-02 1.44221975036700e+00 2.43094929221455e-01 +-9.00000000000000e+01 3.36965526401992e-07 1.45305993234293e+00 2.51936472308407e-01 +-8.70000000000000e+01 -5.39897225050438e-02 1.44221976146193e+00 2.56931622255970e-01 +-8.40000000000000e+01 -1.07979375751980e-01 1.43137949667301e+00 2.61901020827721e-01 +-8.10000000000000e+01 -1.61968216553408e-01 1.42053931469708e+00 2.66845383648936e-01 +-7.80000000000000e+01 -2.14250364516685e-01 1.39318280081402e+00 2.68479729146681e-01 +-7.50000000000000e+01 -2.65679136606263e-01 1.35756783594738e+00 2.68447877672478e-01 +-7.20000000000000e+01 -3.17106719374234e-01 1.32195327919519e+00 2.68392871736955e-01 +-6.90000000000000e+01 -3.65975094161662e-01 1.27958030107501e+00 2.67043843374306e-01 +-6.60000000000000e+01 -4.09724843417841e-01 1.22368992678063e+00 2.63130341234035e-01 +-6.30000000000000e+01 -4.53474576189544e-01 1.16779955248625e+00 2.59197088106754e-01 +-6.00000000000000e+01 -4.97224207869552e-01 1.11190906378698e+00 2.55244704276654e-01 +-5.70000000000000e+01 -5.30141604466721e-01 1.04267158504194e+00 2.49454887071623e-01 +-5.40000000000000e+01 -5.63059118556911e-01 9.73433841829142e-01 2.43646817884402e-01 +-5.10000000000000e+01 -5.95976867634935e-01 9.04195569676826e-01 2.37820619877023e-01 +-4.80000000000000e+01 -6.23239324536221e-01 8.31789714461067e-01 2.32266352846812e-01 +-4.50000000000000e+01 -6.47674226237690e-01 7.57800118621131e-01 2.26836908914070e-01 +-4.20000000000000e+01 -6.67333704892715e-01 6.83667545750015e-01 2.23029606785968e-01 +-3.90000000000000e+01 -6.86159958788100e-01 6.09930414983374e-01 2.19918132247163e-01 +-3.60000000000000e+01 -7.02733476031370e-01 5.37796305675443e-01 2.19390306691080e-01 +-3.30000000000000e+01 -7.18707342668409e-01 4.68286734608672e-01 2.22226002504236e-01 +-3.00000000000000e+01 -7.35519829439412e-01 4.01562954836658e-01 2.28827939791023e-01 +-2.93939393939394e+01 -7.39392279869158e-01 3.88758041707422e-01 2.31182344944843e-01 +-2.87878787878788e+01 -7.43264730298904e-01 3.75953128578187e-01 2.33536750098664e-01 +-2.81818181818182e+01 -7.47137180728651e-01 3.63148215448951e-01 2.35891155252484e-01 +-2.75757575757576e+01 -7.51476885097161e-01 3.50752776727396e-01 2.38974806555987e-01 +-2.69696969696970e+01 -7.56016858332907e-01 3.38532842092560e-01 2.42371018735316e-01 +-2.63636363636364e+01 -7.60556831568653e-01 3.26312907457723e-01 2.45767230914644e-01 +-2.57575757575758e+01 -7.65500018552221e-01 3.14351399285216e-01 2.49710318611517e-01 +-2.51515151515151e+01 -7.71047932183450e-01 3.02777470576641e-01 2.54473592128438e-01 +-2.45454545454545e+01 -7.76595845814680e-01 2.91203541868066e-01 2.59236865645359e-01 +-2.39393939393939e+01 -7.82447959329456e-01 2.79692872440278e-01 2.62992965843921e-01 +-2.33333333333333e+01 -7.91037930690711e-01 2.68751548786870e-01 2.57684311183680e-01 +-2.27272727272727e+01 -7.99627902051967e-01 2.57810225133461e-01 2.53255349257629e-01 +-2.21212121212121e+01 -8.08217873413222e-01 2.46868901480052e-01 2.47684440936497e-01 +-2.15151515151515e+01 -8.19990478826953e-01 2.36221993248645e-01 2.31504471971342e-01 +-2.09090909090909e+01 -8.34647953216695e-01 2.25648707810846e-01 2.13702005243607e-01 +-2.03030303030303e+01 -8.49132464561041e-01 2.15075422373046e-01 1.95960374750995e-01 +-1.96969696969697e+01 -8.62578663351143e-01 2.04502427490460e-01 1.78243288992263e-01 +-1.90909090909091e+01 -8.75549253302963e-01 1.93929723146649e-01 1.60535941747677e-01 +-1.84848484848485e+01 -8.89815545281606e-01 1.83695365421934e-01 1.42835185458870e-01 +-1.78787878787879e+01 -9.04336378911458e-01 1.74027498768236e-01 1.24649099331343e-01 +-1.72727272727273e+01 -9.18897356865547e-01 1.64194842338135e-01 1.06248581428441e-01 +-1.66666666666667e+01 -9.34393729163051e-01 1.54084754485664e-01 8.78685062390541e-02 +-1.60606060606061e+01 -9.50536639664486e-01 1.43764438001973e-01 6.95133639931887e-02 +-1.54545454545455e+01 -9.64734821551149e-01 1.33117373956884e-01 5.21860598369796e-02 +-1.48484848484848e+01 -9.77391904313972e-01 1.22286093821075e-01 3.54343122342188e-02 +-1.42424242424242e+01 -9.85991220935185e-01 1.11183046356548e-01 1.93441677911052e-02 +-1.36363636363636e+01 -9.92508781462450e-01 1.00022677031595e-01 1.86113773658177e-03 +-1.30303030303030e+01 -9.96614484588265e-01 8.88116806333893e-02 -1.56141016371839e-02 +-1.24242424242424e+01 -9.78086134430020e-01 7.52791871427589e-02 -2.49185975754885e-02 +-1.18181818181818e+01 -9.53932069219898e-01 6.20273381259160e-02 -3.17721050900264e-02 +-1.12121212121212e+01 -9.20876137842797e-01 5.07143911844155e-02 -3.39028634816218e-02 +-1.06060606060606e+01 -8.81577109301206e-01 4.14292282661460e-02 -3.79021056900473e-02 +-1.00000000000000e+01 -8.39208813140256e-01 3.31402553113552e-02 -4.29111295394993e-02 +-9.39393939393939e+00 -7.98914426405686e-01 2.63234936305883e-02 -4.78020739246981e-02 +-8.78787878787879e+00 -7.51657176842035e-01 2.00389695291873e-02 -5.40250476091291e-02 +-8.18181818181818e+00 -6.93679577084241e-01 1.48308481680817e-02 -6.34207316233908e-02 +-7.57575757575758e+00 -6.21203231263108e-01 1.23436646598620e-02 -7.09002799417693e-02 +-6.96969696969697e+00 -5.42846056045475e-01 1.08867824056562e-02 -7.76381592574485e-02 +-6.36363636363636e+00 -4.57248717599494e-01 1.00699499146877e-02 -8.51835466097516e-02 +-5.75757575757576e+00 -3.71772773815341e-01 9.34966265890492e-03 -9.22149694821789e-02 +-5.15151515151515e+00 -2.86510321252854e-01 8.93727471505472e-03 -9.83419419547575e-02 +-4.54545454545454e+00 -2.02800521849721e-01 8.69069179286290e-03 -1.03107031002192e-01 +-3.93939393939394e+00 -1.19779247070242e-01 8.48574750992013e-03 -1.07388031434577e-01 +-3.33333333333333e+00 -3.84842209773342e-02 8.25863893989330e-03 -1.11024512192661e-01 +-2.72727272727273e+00 4.24696095161102e-02 8.07912598948857e-03 -1.14232025558283e-01 +-2.12121212121212e+00 1.22655957049352e-01 7.94212397685742e-03 -1.17344637430821e-01 +-1.51515151515152e+00 2.01513656509836e-01 7.86589688092029e-03 -1.19802686323078e-01 +-9.09090909090912e-01 2.79423697181455e-01 7.84144762810594e-03 -1.22095855725919e-01 +-3.03030303030302e-01 3.55313195985403e-01 7.92627146648238e-03 -1.24166876151792e-01 + 3.03030303030302e-01 4.31348608046625e-01 7.96635081424009e-03 -1.26135660486964e-01 + 9.09090909090912e-01 5.07641470964623e-01 7.97255718827600e-03 -1.27871042553699e-01 + 1.51515151515152e+00 5.83948077422797e-01 7.96669925131739e-03 -1.29528648870106e-01 + 2.12121212121212e+00 6.60075851841618e-01 8.13587472418758e-03 -1.31061713680780e-01 + 2.72727272727273e+00 7.35527633751173e-01 8.30297676364884e-03 -1.32516554910940e-01 + 3.33333333333333e+00 8.09980208614822e-01 8.45480310834448e-03 -1.33834053323750e-01 + 3.93939393939394e+00 8.84045273581437e-01 8.60887609936009e-03 -1.34999421375079e-01 + 4.54545454545455e+00 9.57533521208408e-01 8.81210276724078e-03 -1.35895700708834e-01 + 5.15151515151515e+00 1.03035843997482e+00 9.04375918791339e-03 -1.36630117116849e-01 + 5.75757575757576e+00 1.10131375775296e+00 9.33994000860195e-03 -1.36951375051287e-01 + 6.36363636363637e+00 1.16891066608882e+00 9.67833808285477e-03 -1.36757550838472e-01 + 6.96969696969697e+00 1.23465262669807e+00 1.00087887591604e-02 -1.36219258169966e-01 + 7.57575757575757e+00 1.28575742789560e+00 1.07210657691971e-02 -1.33537358220650e-01 + 8.18181818181818e+00 1.32822847132065e+00 1.19390938706417e-02 -1.29971609720980e-01 + 8.78787878787879e+00 1.35408256195699e+00 1.39481484368526e-02 -1.24516098191203e-01 + 9.39393939393939e+00 1.34430353385980e+00 2.27726382829582e-02 -1.22692829271057e-01 + 1.00000000000000e+01 1.31224074007862e+00 3.52534094952587e-02 -1.22656293137505e-01 + 1.06060606060606e+01 1.22701127443843e+00 4.62229873456646e-02 -1.21636756952509e-01 + 1.12121212121212e+01 1.16219562577377e+00 5.50223378711124e-02 -1.18681954879612e-01 + 1.18181818181818e+01 1.13530358391339e+00 5.97915556707085e-02 -1.12985606092307e-01 + 1.24242424242424e+01 1.11600551029910e+00 6.74861674225558e-02 -1.09510733624339e-01 + 1.30303030303030e+01 1.09983288203511e+00 7.64936470016543e-02 -1.06091834625369e-01 + 1.36363636363636e+01 1.10710335628616e+00 8.65013832514091e-02 -1.07592565956690e-01 + 1.42424242424242e+01 1.10938358437695e+00 9.67716403001183e-02 -1.09394660231539e-01 + 1.48484848484848e+01 1.11061811797752e+00 1.07424572874100e-01 -1.11514011821931e-01 + 1.54545454545455e+01 1.11082268580784e+00 1.16571011915171e-01 -1.12131429881359e-01 + 1.60606060606061e+01 1.11033605299743e+00 1.25085168188146e-01 -1.12361290382414e-01 + 1.66666666666667e+01 1.10609925661839e+00 1.32426982839510e-01 -1.11763403041033e-01 + 1.72727272727273e+01 1.10609074419205e+00 1.41309497589980e-01 -1.12196477228094e-01 + 1.78787878787879e+01 1.11168148131629e+00 1.52075109775884e-01 -1.13878511431696e-01 + 1.84848484848485e+01 1.11799563681487e+00 1.64464965699760e-01 -1.17335103628994e-01 + 1.90909090909091e+01 1.12427870883996e+00 1.77094182598103e-01 -1.21133211985493e-01 + 1.96969696969697e+01 1.13008308302165e+00 1.88778817516490e-01 -1.24354909490447e-01 + 2.03030303030303e+01 1.13565448667379e+00 2.01982468205630e-01 -1.28506406560087e-01 + 2.09090909090909e+01 1.14015133774343e+00 2.16705220601696e-01 -1.33414633720588e-01 + 2.15151515151515e+01 1.14287461583876e+00 2.31427972997762e-01 -1.38269729436345e-01 + 2.21212121212121e+01 1.14332576014604e+00 2.45483672070678e-01 -1.43529989407809e-01 + 2.27272727272727e+01 1.13469070715944e+00 2.56871844199725e-01 -1.50406733035442e-01 + 2.33333333333333e+01 1.12605565417285e+00 2.68260016328771e-01 -1.57238953577331e-01 + 2.39393939393939e+01 1.11742060118626e+00 2.79648188457818e-01 -1.63893422540327e-01 + 2.45454545454545e+01 1.10942403333740e+00 2.91203541868066e-01 -1.69656064509149e-01 + 2.51515151515151e+01 1.10149840675555e+00 3.02777470576641e-01 -1.75327968907266e-01 + 2.57575757575758e+01 1.09357278017371e+00 3.14351399285216e-01 -1.81009617670108e-01 + 2.63636363636364e+01 1.08651104880220e+00 3.26312907457723e-01 -1.86249835379891e-01 + 2.69696969696970e+01 1.08002533707003e+00 3.38532842092560e-01 -1.91196015332576e-01 + 2.75757575757576e+01 1.07353962533786e+00 3.50752776727396e-01 -1.96148336213444e-01 + 2.81818181818182e+01 1.06734017933048e+00 3.63148215448951e-01 -2.00947535149472e-01 + 2.87878787878788e+01 1.06180862938348e+00 3.75953128578187e-01 -2.05379818120139e-01 + 2.93939393939394e+01 1.05627707943649e+00 3.88758041707422e-01 -2.09816145110101e-01 + 3.00000000000000e+01 1.05074552948950e+00 4.01562954836658e-01 -2.14256550297368e-01 + 3.30000000000000e+01 1.02672334375004e+00 4.68286734608673e-01 -2.33923275085492e-01 + 3.60000000000000e+01 1.00390363142049e+00 5.37796305675443e-01 -2.52023342292616e-01 + 3.90000000000000e+01 9.80228670131175e-01 6.09930414983374e-01 -2.68877380086188e-01 + 4.20000000000000e+01 9.53334135403550e-01 6.83667545750015e-01 -2.84801740802117e-01 + 4.50000000000000e+01 9.25249734105174e-01 7.57800118621131e-01 -3.00471220322711e-01 + 4.80000000000000e+01 8.90342378222425e-01 8.31789714461067e-01 -3.15332659299714e-01 + 5.10000000000000e+01 8.51395825660653e-01 9.04195569676826e-01 -3.29875873212572e-01 + 5.40000000000000e+01 8.04370620070051e-01 9.73433841829142e-01 -3.43774687106004e-01 + 5.70000000000000e+01 7.57345390210040e-01 1.04267158504194e+00 -3.57676244146600e-01 + 6.00000000000000e+01 7.10320148215417e-01 1.11190906378698e+00 -3.71581147754796e-01 + 6.30000000000000e+01 6.47820663786416e-01 1.16779955248625e+00 -3.84050834181803e-01 + 6.60000000000000e+01 5.85321046718599e-01 1.22368992678063e+00 -3.96521729786065e-01 + 6.90000000000000e+01 5.22821429650782e-01 1.27958030107501e+00 -4.08993794958095e-01 + 7.20000000000000e+01 4.53009361979119e-01 1.32195327919519e+00 -4.20171504341749e-01 + 7.50000000000000e+01 3.79541218701137e-01 1.35756783594738e+00 -4.30701936371378e-01 + 7.80000000000000e+01 3.06071633534284e-01 1.39318280081402e+00 -4.41232525983427e-01 + 8.10000000000000e+01 2.31382797116840e-01 1.42053931469708e+00 -4.50887242301039e-01 + 8.40000000000000e+01 1.54255542363546e-01 1.43137949667301e+00 -4.58789175569348e-01 + 8.70000000000000e+01 7.71276819161773e-02 1.44221976146193e+00 -4.66690861017101e-01 + 9.00000000000000e+01 -3.36965526632122e-07 1.45305993234293e+00 -4.74592503766813e-01 + 9.30000000000000e+01 -5.39897777632595e-02 1.44221975036700e+00 -4.79614013589955e-01 + 9.60000000000000e+01 -1.07979224785424e-01 1.43137952698492e+00 -4.84662548255213e-01 + 9.90000000000000e+01 -1.61968684256675e-01 1.42053922078900e+00 -4.89738716026789e-01 + 1.02000000000000e+02 -2.14250613596524e-01 1.39318262832361e+00 -4.91556612878414e-01 + 1.05000000000000e+02 -2.65678796360800e-01 1.35756807157142e+00 -4.91759948361478e-01 + 1.08000000000000e+02 -3.17106968448641e-01 1.32195310670654e+00 -4.91808185319412e-01 + 1.11000000000000e+02 -3.65975473161876e-01 1.27957981690164e+00 -4.90481329182113e-01 + 1.14000000000000e+02 -4.09724721085945e-01 1.22369008305982e+00 -4.86610622674850e-01 + 1.17000000000000e+02 -4.53474286743658e-01 1.16779992225404e+00 -4.82739400053527e-01 + 1.20000000000000e+02 -4.97223990089781e-01 1.11190952185851e+00 -4.78867879128044e-01 + 1.23000000000000e+02 -5.30141386686949e-01 1.04267204311347e+00 -4.73180864409918e-01 + 1.26000000000000e+02 -5.63058900774808e-01 9.73434299905923e-01 -4.67493542642030e-01 + 1.29000000000000e+02 -5.95976649852831e-01 9.04196027753607e-01 -4.61805698033490e-01 + 1.32000000000000e+02 -6.21647450545520e-01 8.31742453913373e-01 -4.56978785337660e-01 + 1.35000000000000e+02 -6.43694785635686e-01 7.57681233044139e-01 -4.52582281581552e-01 + 1.38000000000000e+02 -6.65741843359713e-01 6.83620285576330e-01 -4.48185737640142e-01 + 1.41000000000000e+02 -6.85948000576951e-01 6.10977986560267e-01 -4.46102392733155e-01 + 1.44000000000000e+02 -7.02472341842677e-01 5.41172995959272e-01 -4.48645505252371e-01 + 1.47000000000000e+02 -7.18996156868714e-01 4.71368155114379e-01 -4.51188446648819e-01 + 1.50000000000000e+02 -7.35519708784299e-01 4.01563389144863e-01 -4.53731249233545e-01 + 1.53000000000000e+02 -7.20041338298566e-01 3.49496494506179e-01 -4.67335818397252e-01 + 1.56000000000000e+02 -7.07403995417188e-01 2.97429648323240e-01 -4.80939257564229e-01 + 1.59000000000000e+02 -6.95102717992735e-01 2.45362816385929e-01 -4.93374572820376e-01 + 1.62000000000000e+02 -6.21487493690614e-01 2.05206612595701e-01 -4.97977180373460e-01 + 1.65000000000000e+02 -5.17905869149982e-01 1.71005823609649e-01 -4.98735700762325e-01 + 1.68000000000000e+02 -4.14324831560763e-01 1.36804826538108e-01 -4.99494277943921e-01 + 1.71000000000000e+02 -3.10743598323177e-01 1.02603707071835e-01 -4.50000513056908e-01 + 1.74000000000000e+02 -2.07161973779746e-01 6.84023428103841e-02 -2.99999717902353e-01 + 1.77000000000000e+02 -1.03108758635925e-01 5.65240009423786e-02 -1.49315896260807e-01 + 1.80000000000000e+02 0.00000000000000e+00 5.58151028351338e-02 0.00000000000000e+00 diff --git a/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_20.dat b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_20.dat new file mode 100644 index 00000000..b86dcd63 --- /dev/null +++ b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_20.dat @@ -0,0 +1,254 @@ +! ------------ AirfoilInfo v1.01.x Input File ---------------------------------- +! AeroElasticSE FAST driver +! line +! line +! ------------------------------------------------------------------------------ +DEFAULT InterpOrd ! Interpolation order to use for quasi-steady table lookup {1=linear; 3=cubic spline; "default"} [default=3] +1 NonDimArea ! The non-dimensional area of the airfoil (area/chord^2) (set to 1.0 if unsure or unneeded) +@"NREL-2p8-127_AF20_Coords.txt" NumCoords ! The number of coordinates in the airfoil shape file. Set to zero if coordinates not included. +AF20_BL.txt BL_file ! The file name including the boundary layer characteristics of the profile. Ignored if the aeroacoustic module is not called. +1 NumTabs ! Number of airfoil tables in this file. Each table must have lines for Re and Ctrl. +! ------------------------------------------------------------------------------ +! data for table 1 +! ------------------------------------------------------------------------------ +6.000000 Re ! Reynolds number in millions +0 Ctrl ! Control setting (must be 0 for current AirfoilInfo) +True InclUAdata ! Is unsteady aerodynamics data included in this table? If TRUE, then include 30 UA coefficients below this line +!........................................ +-3.223506 alpha0 ! 0-lift angle of attack, depends on airfoil. +9.164046 alpha1 ! Angle of attack at f=0.7, (approximately the stall angle) for AOA>alpha0. (deg) +-11.802083 alpha2 ! Angle of attack at f=0.7, (approximately the stall angle) for AOA1] +0.000000 S2 ! Constant in the f curve best-fit for AOA> alpha1; by definition it depends on the airfoil. [ignored if UAMod<>1] +0.000000 S3 ! Constant in the f curve best-fit for alpha2<=AOA< alpha0; by definition it depends on the airfoil. [ignored if UAMod<>1] +0.000000 S4 ! Constant in the f curve best-fit for AOA< alpha2; by definition it depends on the airfoil. [ignored if UAMod<>1] +1.346223 Cn1 ! Critical value of C0n at leading edge separation. It should be extracted from airfoil data at a given Mach and Reynolds number. It can be calculated from the static value of Cn at either the break in the pitching moment or the loss of chord force at the onset of stall. It is close to the condition of maximum lift of the airfoil at low Mach numbers. +-0.953798 Cn2 ! As Cn1 for negative AOAs. +Default St_sh ! Strouhal's shedding frequency constant. [default = 0.19] +0.007766 Cd0 ! 2D drag coefficient value at 0-lift. +-0.112979 Cm0 ! 2D pitching moment coefficient about 1/4-chord location, at 0-lift, positive if nose up. [If the aerodynamics coefficients table does not include a column for Cm, this needs to be set to 0.0] +0.000000 k0 ! Constant in the \hat(x)_cp curve best-fit; = (\hat(x)_AC-0.25). [ignored if UAMod<>1] +0.000000 k1 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k2 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k3 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k1_hat ! Constant in the expression of Cc due to leading edge vortex effects. [ignored if UAMod<>1] +Default x_cp_bar ! Constant in the expression of \hat(x)_cp^v. [ignored if UAMod<>1, default = 0.2] +Default UACutout ! Angle of attack above which unsteady aerodynamics are disabled (deg). [Specifying the string "Default" sets UACutout to 45 degrees] +Default filtCutOff ! Cut-off frequency (-3 dB corner frequency) for low-pass filtering the AoA input to UA, as well as the 1st and 2nd derivatives (Hz) [default = 20] +!........................................ +! Table of aerodynamics coefficients +200 NumAlf ! Number of data lines in the following table +! Alpha Cl Cd Cm +! (deg) (-) (-) (-) +-1.80000000000000e+02 0.00000000000000e+00 5.60839860376548e-02 1.47167178040004e-03 +-1.77000000000000e+02 1.08689836995157e-01 5.60839860376548e-02 1.20045412825477e-01 +-1.74000000000000e+02 2.18375213642741e-01 6.73007199605437e-02 2.39999774321882e-01 +-1.71000000000000e+02 3.27563004817197e-01 1.00951289964885e-01 3.60000410445527e-01 +-1.68000000000000e+02 4.36467171182598e-01 1.34633335777690e-01 3.19169994146170e-01 +-1.65000000000000e+02 5.45229528453792e-01 1.68331119127359e-01 1.97925928770713e-01 +-1.62000000000000e+02 6.53993133012884e-01 2.02028691114530e-01 7.66798765295578e-02 +-1.59000000000000e+02 7.27503940714938e-01 2.42310026594573e-01 -7.27450282376270e-03 +-1.56000000000000e+02 7.31110795820098e-01 2.95758666342963e-01 -1.72902036375927e-02 +-1.53000000000000e+02 7.34319596822270e-01 3.49207314408847e-01 -2.71905033085442e-02 +-1.50000000000000e+02 7.36523173539597e-01 4.02656004658303e-01 -3.53620431597287e-02 +-1.47000000000000e+02 7.19881808024148e-01 4.72422936035072e-01 -1.91283433052972e-02 +-1.44000000000000e+02 7.03240180419886e-01 5.42189935051373e-01 -2.89438151512004e-03 +-1.41000000000000e+02 6.86598028619283e-01 6.11957069351567e-01 1.32352052371265e-02 +-1.38000000000000e+02 6.66302604968628e-01 6.84555659899671e-01 2.92408808365066e-02 +-1.35000000000000e+02 6.44180552804007e-01 7.58569972827814e-01 4.52061276876922e-02 +-1.32000000000000e+02 6.22058248103176e-01 8.32584537348692e-01 6.11744715260335e-02 +-1.29000000000000e+02 5.96320693031764e-01 9.04989003183199e-01 7.72346550841547e-02 +-1.26000000000000e+02 5.63352620077395e-01 9.74173264003827e-01 9.34737950291405e-02 +-1.23000000000000e+02 5.30384796680654e-01 1.04335699334894e+00 1.09713844738546e-01 +-1.20000000000000e+02 4.97417098058063e-01 1.11254045696623e+00 1.25955007125395e-01 +-1.17000000000000e+02 4.53634438299479e-01 1.16837104972410e+00 1.41339031769430e-01 +-1.14000000000000e+02 4.09851924952369e-01 1.22420140310934e+00 1.56723518860802e-01 +-1.11000000000000e+02 3.66069746716654e-01 1.28003132998751e+00 1.72108208755073e-01 +-1.08000000000000e+02 3.17177705557324e-01 1.32234220591584e+00 1.85841350669341e-01 +-1.05000000000000e+02 2.65730694027691e-01 1.35789345342785e+00 1.98749244923706e-01 +-1.02000000000000e+02 2.14283672037506e-01 1.39344429355730e+00 2.11656834470358e-01 +-9.90000000000000e+01 1.61987132519313e-01 1.42073648944996e+00 2.23201790003783e-01 +-9.60000000000000e+01 1.07991521148030e-01 1.43151103914374e+00 2.32020842715942e-01 +-9.30000000000000e+01 5.39959252161754e-02 1.44228550652603e+00 2.40839683380319e-01 +-9.00000000000000e+01 3.37003894400466e-07 1.45305993275333e+00 2.49658549004585e-01 +-8.70000000000000e+01 -5.39958699516678e-02 1.44228551755366e+00 2.54494482776028e-01 +-8.40000000000000e+01 -1.07991672131789e-01 1.43151100901570e+00 2.59343605608854e-01 +-8.10000000000000e+01 -1.61986664762753e-01 1.42073658278841e+00 2.64205569719769e-01 +-7.80000000000000e+01 -2.14283422866425e-01 1.39344446573911e+00 2.65795815265371e-01 +-7.50000000000000e+01 -2.65731034397795e-01 1.35789321822535e+00 2.65755918593268e-01 +-7.20000000000000e+01 -3.17177456391675e-01 1.32234237809590e+00 2.65727119737369e-01 +-6.90000000000000e+01 -3.66069367431166e-01 1.28003181364278e+00 2.64438345067420e-01 +-6.60000000000000e+01 -4.09852047376346e-01 1.22420124699738e+00 2.60617266085316e-01 +-6.30000000000000e+01 -4.53634727963402e-01 1.16837068035199e+00 2.56805932797703e-01 +-6.00000000000000e+01 -4.97417316170630e-01 1.11253999925206e+00 2.53004344403069e-01 +-5.70000000000000e+01 -5.30385014793222e-01 1.04335653563477e+00 2.47400711870632e-01 +-5.40000000000000e+01 -5.63352838192439e-01 9.74172806284381e-01 2.41806514160262e-01 +-5.10000000000000e+01 -5.96320911146808e-01 9.04988545463753e-01 2.36221437763850e-01 +-4.80000000000000e+01 -6.23645028218618e-01 8.32633137744547e-01 2.30956513607567e-01 +-4.50000000000000e+01 -6.48147258055512e-01 7.58692207540872e-01 2.25857970172168e-01 +-4.20000000000000e+01 -6.67889372666217e-01 6.84604259911055e-01 2.22474982226598e-01 +-3.90000000000000e+01 -6.86802709568193e-01 6.10910749328229e-01 2.19736387390917e-01 +-3.60000000000000e+01 -7.03478405910380e-01 5.38816968440485e-01 2.19280528126823e-01 +-3.30000000000000e+01 -7.19572395319055e-01 4.69344655336830e-01 2.22204576432948e-01 +-3.00000000000000e+01 -7.36523295159899e-01 4.02655570575433e-01 2.28913832317185e-01 +-2.93939393939394e+01 -7.40428301639941e-01 3.89857123435579e-01 2.31295215800378e-01 +-2.87878787878788e+01 -7.44333308119982e-01 3.77058676295725e-01 2.33676599283572e-01 +-2.81818181818182e+01 -7.48238314600024e-01 3.64260229155871e-01 2.36057982766765e-01 +-2.75757575757576e+01 -7.52613641879506e-01 3.51870974153269e-01 2.39172506623836e-01 +-2.69696969696970e+01 -7.57190552507842e-01 3.39657102253967e-01 2.42601260453133e-01 +-2.63636363636364e+01 -7.61767463136177e-01 3.27443230354664e-01 2.46030014282430e-01 +-2.57575757575758e+01 -7.66749761722573e-01 3.15487613973748e-01 2.50008630333910e-01 +-2.51515151515151e+01 -7.72340047765258e-01 3.03919320680690e-01 2.54811911566304e-01 +-2.45454545454545e+01 -7.77930333807944e-01 2.92351027387632e-01 2.59615192798699e-01 +-2.39393939393939e+01 -7.83831337974498e-01 2.80845692169765e-01 2.63368296589326e-01 +-2.33333333333333e+01 -7.92528865412384e-01 2.69906991817601e-01 2.57669600084677e-01 +-2.27272727272727e+01 -8.01226392850269e-01 2.58968291465437e-01 2.51477123925418e-01 +-2.21212121212121e+01 -8.09923920288154e-01 2.48029591113273e-01 2.45907124300863e-01 +-2.15151515151515e+01 -8.20235783478513e-01 2.37173728120076e-01 2.31168860674295e-01 +-2.09090909090909e+01 -8.29622622700524e-01 2.26338579795089e-01 2.13713746850245e-01 +-2.03030303030303e+01 -8.39213259378848e-01 2.15503431470102e-01 1.96258633026194e-01 +-1.96969696969697e+01 -8.49342921178197e-01 2.04670828846016e-01 1.78811743339257e-01 +-1.90909090909091e+01 -8.59723555494070e-01 1.93840771778819e-01 1.61373077324190e-01 +-1.84848484848485e+01 -8.69355568885329e-01 1.82817117288920e-01 1.43848790063230e-01 +-1.78787878787879e+01 -8.78841519111643e-01 1.71507191312464e-01 1.26522966331281e-01 +-1.72727272727273e+01 -8.88304094365764e-01 1.60344653968440e-01 1.09264562513686e-01 +-1.66666666666667e+01 -8.97226846531499e-01 1.49299202250655e-01 9.19320215375475e-02 +-1.60606060606061e+01 -9.05768732409721e-01 1.38352219033920e-01 7.45346221583764e-02 +-1.54545454545455e+01 -9.14769264432095e-01 1.27532003288276e-01 5.67050762225817e-02 +-1.48484848484848e+01 -9.24224518221895e-01 1.16781059230677e-01 3.86315588318540e-02 +-1.42424242424242e+01 -9.34933174803990e-01 1.06107627638312e-01 2.02903974043766e-02 +-1.36363636363636e+01 -9.46580047643885e-01 9.54549647670512e-02 2.58155653624406e-03 +-1.30303030303030e+01 -9.59376519315215e-01 8.48210475936575e-02 -1.51277660357559e-02 +-1.24242424242424e+01 -9.49137204600254e-01 7.23014208476810e-02 -2.45207730999593e-02 +-1.18181818181818e+01 -9.33511315858133e-01 6.03072372984705e-02 -3.14401400294280e-02 +-1.12121212121212e+01 -9.07412559417457e-01 4.91969779770790e-02 -3.36076468476470e-02 +-1.06060606060606e+01 -8.74358654564795e-01 3.98750651939524e-02 -3.77019772884650e-02 +-1.00000000000000e+01 -8.37436227745362e-01 3.15713217351823e-02 -4.28344259088231e-02 +-9.39393939393939e+00 -7.97360016762257e-01 2.49748326421447e-02 -4.78167321636766e-02 +-8.78787878787879e+00 -7.46918091090845e-01 1.90106766562991e-02 -5.49142422548264e-02 +-8.18181818181818e+00 -6.76385235190348e-01 1.41430349552736e-02 -6.55740988464556e-02 +-7.57575757575758e+00 -5.97548773054335e-01 1.16500159105889e-02 -7.40578404001251e-02 +-6.96969696969697e+00 -5.14687150181851e-01 1.02794635432385e-02 -8.15694642369420e-02 +-6.36363636363636e+00 -4.29783331561822e-01 9.37100611916169e-03 -8.89972589526919e-02 +-5.75757575757576e+00 -3.44985681028980e-01 8.72254512466363e-03 -9.56743162334849e-02 +-5.15151515151515e+00 -2.60342088083212e-01 8.36628808560654e-03 -1.01294050980689e-01 +-4.54545454545454e+00 -1.77283987129221e-01 8.15049198443473e-03 -1.05574157964945e-01 +-3.93939393939394e+00 -9.49967516754283e-02 7.98399273984275e-03 -1.09327817332233e-01 +-3.33333333333333e+00 -1.45488178579448e-02 7.79517199106549e-03 -1.12477093218156e-01 +-2.72727272727273e+00 6.57363122021591e-02 7.63446498473685e-03 -1.15244192981836e-01 +-2.12121212121212e+00 1.45332789615814e-01 7.51105279420149e-03 -1.17982678474176e-01 +-1.51515151515152e+00 2.23672723468766e-01 7.44827862315605e-03 -1.20431702659156e-01 +-9.09090909090912e-01 3.00978847690010e-01 7.43157561421629e-03 -1.22712093550068e-01 +-3.03030303030302e-01 3.76098908531403e-01 7.51006367733051e-03 -1.24767379670863e-01 + 3.03030303030302e-01 4.51444826699281e-01 7.54938811200737e-03 -1.26721030186769e-01 + 9.09090909090912e-01 5.27096787476172e-01 7.54812362715996e-03 -1.28437544066459e-01 + 1.51515151515152e+00 6.02777798759360e-01 7.55798597733358e-03 -1.30082417308287e-01 + 2.12121212121212e+00 6.78328119290960e-01 7.71509624311103e-03 -1.31599798151816e-01 + 2.72727272727273e+00 7.53369580256120e-01 7.87416012848208e-03 -1.33039382183475e-01 + 3.33333333333333e+00 8.27436011075852e-01 8.02072404030208e-03 -1.34343039337526e-01 + 3.93939393939394e+00 9.01064324481151e-01 8.17634754573474e-03 -1.35496483033582e-01 + 4.54545454545455e+00 9.74097640300264e-01 8.37626659639857e-03 -1.36379157527485e-01 + 5.15151515151515e+00 1.04648944718360e+00 8.60497543451105e-03 -1.37098870871982e-01 + 5.75757575757576e+00 1.11709742972339e+00 8.90798254151872e-03 -1.37401161602970e-01 + 6.36363636363637e+00 1.18428988344244e+00 9.27589711393541e-03 -1.37179374672226e-01 + 6.96969696969697e+00 1.24896889274954e+00 9.70884746672005e-03 -1.36604163101376e-01 + 7.57575757575757e+00 1.29881944271375e+00 1.06632766664296e-02 -1.33835538319740e-01 + 8.18181818181818e+00 1.33958725078695e+00 1.19126582890210e-02 -1.30168176642310e-01 + 8.78787878787879e+00 1.36005346559897e+00 1.39779508814557e-02 -1.24720046583824e-01 + 9.39393939393939e+00 1.34301374720075e+00 2.30914396203260e-02 -1.22744826084420e-01 + 1.00000000000000e+01 1.30753093113672e+00 3.60092777128439e-02 -1.22742898670035e-01 + 1.06060606060606e+01 1.21740138674990e+00 4.73489216901772e-02 -1.21777727655646e-01 + 1.12121212121212e+01 1.14876626618267e+00 5.64290043026546e-02 -1.19509336453563e-01 + 1.18181818181818e+01 1.12008684609046e+00 6.13613926416215e-02 -1.14351014023090e-01 + 1.24242424242424e+01 1.10641679635825e+00 6.86990657706108e-02 -1.09572759572039e-01 + 1.30303030303030e+01 1.10001146588234e+00 7.71321227342433e-02 -1.05827721623316e-01 + 1.36363636363636e+01 1.10899885123525e+00 8.72204117979317e-02 -1.07475148520177e-01 + 1.42424242424242e+01 1.12008882355609e+00 9.75650647021123e-02 -1.09425019423431e-01 + 1.48484848484848e+01 1.13075597639677e+00 1.08294194106513e-01 -1.11906001460801e-01 + 1.54545454545455e+01 1.13516931068150e+00 1.17464255427677e-01 -1.13115892870182e-01 + 1.60606060606061e+01 1.13676837338324e+00 1.25978158509963e-01 -1.13656640925689e-01 + 1.66666666666667e+01 1.13211072570407e+00 1.33262514337462e-01 -1.12840862880448e-01 + 1.72727272727273e+01 1.13058655438625e+00 1.42129358900706e-01 -1.13195774561728e-01 + 1.78787878787879e+01 1.13267144501086e+00 1.52930376429612e-01 -1.14987235036101e-01 + 1.84848484848485e+01 1.13534488348534e+00 1.65326800303123e-01 -1.18507779175190e-01 + 1.90909090909091e+01 1.13808110384824e+00 1.77947867911582e-01 -1.22278286215279e-01 + 1.96969696969697e+01 1.13996942404966e+00 1.89581788465173e-01 -1.25014693335627e-01 + 2.03030303030303e+01 1.14136257005177e+00 2.02809939468738e-01 -1.28759059263829e-01 + 2.09090909090909e+01 1.14278916134738e+00 2.17632411113615e-01 -1.33592215797638e-01 + 2.15151515151515e+01 1.14520088380394e+00 2.32454882758493e-01 -1.38449866850649e-01 + 2.21212121212121e+01 1.14534623034980e+00 2.46593134049512e-01 -1.43713984431992e-01 + 2.27272727272727e+01 1.13669195126191e+00 2.57995207937436e-01 -1.50603549902548e-01 + 2.33333333333333e+01 1.12803767217403e+00 2.69397281825361e-01 -1.57514015684770e-01 + 2.39393939393939e+01 1.11938339308615e+00 2.80799355713285e-01 -1.64504480543572e-01 + 2.45454545454545e+01 1.11133045136127e+00 2.92351027387632e-01 -1.70538137552357e-01 + 2.51515151515151e+01 1.10334432346167e+00 3.03919320680690e-01 -1.76461209319149e-01 + 2.57575757575758e+01 1.09535819556207e+00 3.15487613973748e-01 -1.82379292873812e-01 + 2.63636363636364e+01 1.08824062881607e+00 3.27443230354664e-01 -1.87812657912168e-01 + 2.69696969696970e+01 1.08170219282164e+00 3.39657102253967e-01 -1.92922675867797e-01 + 2.75757575757576e+01 1.07516375682721e+00 3.51870974153269e-01 -1.98029550237023e-01 + 2.81818181818182e+01 1.06891342259585e+00 3.64260229155871e-01 -2.02965263331226e-01 + 2.87878787878788e+01 1.06333526814667e+00 3.77058676295725e-01 -2.07506580463469e-01 + 2.93939393939394e+01 1.05775711369748e+00 3.89857123435579e-01 -2.12045827432426e-01 + 3.00000000000000e+01 1.05217895924830e+00 4.02655570575433e-01 -2.16582986742122e-01 + 3.30000000000000e+01 1.02795917310136e+00 4.69344655336830e-01 -2.36555351110227e-01 + 3.60000000000000e+01 1.00496772750934e+00 5.38816968440485e-01 -2.54825361123685e-01 + 3.90000000000000e+01 9.81146869188920e-01 6.10910749328229e-01 -2.71702784264139e-01 + 4.20000000000000e+01 9.54127928885481e-01 6.84604259911056e-01 -2.87623690411183e-01 + 4.50000000000000e+01 9.25925507989752e-01 7.58692207540872e-01 -3.03272921560484e-01 + 4.80000000000000e+01 8.90921980696787e-01 8.32633137744547e-01 -3.18102995823141e-01 + 5.10000000000000e+01 8.51887356225999e-01 9.04988545463753e-01 -3.32607858873096e-01 + 5.40000000000000e+01 8.04790278249480e-01 9.74172806284381e-01 -3.46467861120541e-01 + 5.70000000000000e+01 7.57693159426409e-01 1.04335653563477e+00 -3.60325018324970e-01 + 6.00000000000000e+01 7.10596020180217e-01 1.11253999925206e+00 -3.74179542354393e-01 + 6.30000000000000e+01 6.48049471053151e-01 1.16837068035199e+00 -3.86611182558364e-01 + 6.60000000000000e+01 5.85502788028442e-01 1.22420124699738e+00 -3.99041445615547e-01 + 6.90000000000000e+01 5.22956102060375e-01 1.28003181364278e+00 -4.11470147230388e-01 + 7.20000000000000e+01 4.53110398690217e-01 1.32234237809590e+00 -4.22612100063294e-01 + 7.50000000000000e+01 3.79615336039622e-01 1.35789321822535e+00 -4.33110599511480e-01 + 7.80000000000000e+01 3.06118835606714e-01 1.39344446573911e+00 -4.43608014083683e-01 + 8.10000000000000e+01 2.31409126413095e-01 1.42073658278841e+00 -4.53232613764225e-01 + 8.40000000000000e+01 1.54273083446276e-01 1.43151100901570e+00 -4.61112452060330e-01 + 8.70000000000000e+01 7.71364489011903e-02 1.44228551755366e+00 -4.68991671868026e-01 + 9.00000000000000e+01 -3.37003894630567e-07 1.45305993275333e+00 -4.76870426093284e-01 + 9.30000000000000e+01 -5.39959252161754e-02 1.44228550652603e+00 -4.81692680238558e-01 + 9.60000000000000e+01 -1.07991521148031e-01 1.43151103914374e+00 -4.86490823116468e-01 + 9.90000000000000e+01 -1.61987132519313e-01 1.42073648944996e+00 -4.91273974428200e-01 + 1.02000000000000e+02 -2.14283672037506e-01 1.39344429355730e+00 -4.92759271498875e-01 + 1.05000000000000e+02 -2.65730694027692e-01 1.35789345342785e+00 -4.92588207197183e-01 + 1.08000000000000e+02 -3.17177705557324e-01 1.32234220591584e+00 -4.92507133962652e-01 + 1.11000000000000e+02 -3.66069746716655e-01 1.28003132998751e+00 -4.91213114955779e-01 + 1.14000000000000e+02 -4.09851924952369e-01 1.22420140310934e+00 -4.87375141860954e-01 + 1.17000000000000e+02 -4.53634438299479e-01 1.16837104972410e+00 -4.83536739448328e-01 + 1.20000000000000e+02 -4.97417098058063e-01 1.11254045696623e+00 -4.79698118822128e-01 + 1.23000000000000e+02 -5.30384796680655e-01 1.04335699334894e+00 -4.74045178392828e-01 + 1.26000000000000e+02 -5.63352620077395e-01 9.74173264003827e-01 -4.68392016442808e-01 + 1.29000000000000e+02 -5.96320693031764e-01 9.04989003183198e-01 -4.62734898551017e-01 + 1.32000000000000e+02 -6.22058248103176e-01 8.32584537348691e-01 -4.57940896727791e-01 + 1.35000000000000e+02 -6.44180552804007e-01 7.58569972827814e-01 -4.53579623270348e-01 + 1.38000000000000e+02 -6.66302604968628e-01 6.84555659899671e-01 -4.49218395373695e-01 + 1.41000000000000e+02 -6.86598028619283e-01 6.11957069351566e-01 -4.47177800534488e-01 + 1.44000000000000e+02 -7.03240180419886e-01 5.42189935051373e-01 -4.49778490640875e-01 + 1.47000000000000e+02 -7.19881808024148e-01 4.72422936035072e-01 -4.52379161521216e-01 + 1.50000000000000e+02 -7.36523173539597e-01 4.02656004658303e-01 -4.54979822788877e-01 + 1.53000000000000e+02 -7.23995989268374e-01 3.50606387738054e-01 -4.68570401665813e-01 + 1.56000000000000e+02 -7.10014434000594e-01 2.98556810596401e-01 -4.82106047676863e-01 + 1.59000000000000e+02 -6.95822993804938e-01 2.46507230442391e-01 -4.96319099842072e-01 + 1.62000000000000e+02 -6.22266685072149e-01 2.06230353085240e-01 -5.00873829028078e-01 + 1.65000000000000e+02 -5.18715046462665e-01 1.71839926690689e-01 -5.00546173646419e-01 + 1.68000000000000e+02 -4.15163994460962e-01 1.37449294383709e-01 -5.00218470478517e-01 + 1.71000000000000e+02 -3.11516836116274e-01 1.03069943092153e-01 -4.50000513056908e-01 + 1.74000000000000e+02 -2.07677460598702e-01 6.87131543581221e-02 -2.99999717902353e-01 + 1.77000000000000e+02 -1.03365251644600e-01 5.67869836313884e-02 -1.48723200443975e-01 + 1.80000000000000e+02 0.00000000000000e+00 5.60839860376548e-02 1.47167178040004e-03 diff --git a/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_21.dat b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_21.dat new file mode 100644 index 00000000..b3de07d8 --- /dev/null +++ b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_21.dat @@ -0,0 +1,254 @@ +! ------------ AirfoilInfo v1.01.x Input File ---------------------------------- +! AeroElasticSE FAST driver +! line +! line +! ------------------------------------------------------------------------------ +DEFAULT InterpOrd ! Interpolation order to use for quasi-steady table lookup {1=linear; 3=cubic spline; "default"} [default=3] +1 NonDimArea ! The non-dimensional area of the airfoil (area/chord^2) (set to 1.0 if unsure or unneeded) +@"NREL-2p8-127_AF21_Coords.txt" NumCoords ! The number of coordinates in the airfoil shape file. Set to zero if coordinates not included. +AF21_BL.txt BL_file ! The file name including the boundary layer characteristics of the profile. Ignored if the aeroacoustic module is not called. +1 NumTabs ! Number of airfoil tables in this file. Each table must have lines for Re and Ctrl. +! ------------------------------------------------------------------------------ +! data for table 1 +! ------------------------------------------------------------------------------ +6.000000 Re ! Reynolds number in millions +0 Ctrl ! Control setting (must be 0 for current AirfoilInfo) +True InclUAdata ! Is unsteady aerodynamics data included in this table? If TRUE, then include 30 UA coefficients below this line +!........................................ +-3.391748 alpha0 ! 0-lift angle of attack, depends on airfoil. +9.217593 alpha1 ! Angle of attack at f=0.7, (approximately the stall angle) for AOA>alpha0. (deg) +-11.634112 alpha2 ! Angle of attack at f=0.7, (approximately the stall angle) for AOA1] +0.000000 S2 ! Constant in the f curve best-fit for AOA> alpha1; by definition it depends on the airfoil. [ignored if UAMod<>1] +0.000000 S3 ! Constant in the f curve best-fit for alpha2<=AOA< alpha0; by definition it depends on the airfoil. [ignored if UAMod<>1] +0.000000 S4 ! Constant in the f curve best-fit for AOA< alpha2; by definition it depends on the airfoil. [ignored if UAMod<>1] +1.356958 Cn1 ! Critical value of C0n at leading edge separation. It should be extracted from airfoil data at a given Mach and Reynolds number. It can be calculated from the static value of Cn at either the break in the pitching moment or the loss of chord force at the onset of stall. It is close to the condition of maximum lift of the airfoil at low Mach numbers. +-0.907795 Cn2 ! As Cn1 for negative AOAs. +Default St_sh ! Strouhal's shedding frequency constant. [default = 0.19] +0.007422 Cd0 ! 2D drag coefficient value at 0-lift. +-0.113062 Cm0 ! 2D pitching moment coefficient about 1/4-chord location, at 0-lift, positive if nose up. [If the aerodynamics coefficients table does not include a column for Cm, this needs to be set to 0.0] +0.000000 k0 ! Constant in the \hat(x)_cp curve best-fit; = (\hat(x)_AC-0.25). [ignored if UAMod<>1] +0.000000 k1 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k2 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k3 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k1_hat ! Constant in the expression of Cc due to leading edge vortex effects. [ignored if UAMod<>1] +Default x_cp_bar ! Constant in the expression of \hat(x)_cp^v. [ignored if UAMod<>1, default = 0.2] +Default UACutout ! Angle of attack above which unsteady aerodynamics are disabled (deg). [Specifying the string "Default" sets UACutout to 45 degrees] +Default filtCutOff ! Cut-off frequency (-3 dB corner frequency) for low-pass filtering the AoA input to UA, as well as the 1st and 2nd derivatives (Hz) [default = 20] +!........................................ +! Table of aerodynamics coefficients +200 NumAlf ! Number of data lines in the following table +! Alpha Cl Cd Cm +! (deg) (-) (-) (-) +-1.80000000000000e+02 0.00000000000000e+00 5.43028798119170e-02 2.26615932282131e-02 +-1.77000000000000e+02 1.13025106629939e-01 5.43028798119170e-02 1.28579365822585e-01 +-1.74000000000000e+02 2.27085486936604e-01 6.51633944994418e-02 2.39999774321882e-01 +-1.71000000000000e+02 3.40628485406802e-01 9.77452951033210e-02 3.60000410445527e-01 +-1.68000000000000e+02 4.49810292581463e-01 1.30815585114068e-01 3.17166481479515e-01 +-1.65000000000000e+02 5.56811555009885e-01 1.64130064128025e-01 1.92917170488019e-01 +-1.62000000000000e+02 6.63814055955440e-01 1.97444368137118e-01 6.86658789432206e-02 +-1.59000000000000e+02 7.35163378078923e-01 2.37618358711485e-01 -1.63189555213320e-02 +-1.56000000000000e+02 7.36658480852925e-01 2.91511490364540e-01 -2.43269386035842e-02 +-1.53000000000000e+02 7.37191671747579e-01 3.45404633730741e-01 -3.20559725750530e-02 +-1.50000000000000e+02 7.35295872691298e-01 3.99297820213560e-01 -3.53001565756154e-02 +-1.47000000000000e+02 7.18798588287585e-01 4.69181021715765e-01 -1.90934045495720e-02 +-1.44000000000000e+02 7.02301063534926e-01 5.39064308687913e-01 -2.88639524111870e-03 +-1.41000000000000e+02 6.85803058067216e-01 6.08947766606052e-01 1.29498269612823e-02 +-1.38000000000000e+02 6.65616813110053e-01 6.81680698854136e-01 2.86882702662571e-02 +-1.35000000000000e+02 6.43586455890160e-01 7.55838362486724e-01 4.44546354620422e-02 +-1.32000000000000e+02 6.21555858594649e-01 8.29996331514374e-01 6.02291708250731e-02 +-1.29000000000000e+02 5.95899961956707e-01 9.02551799836887e-01 7.61226856194456e-02 +-1.26000000000000e+02 5.62993449444218e-01 9.71902259143020e-01 9.22427459258282e-02 +-1.23000000000000e+02 5.30087151245601e-01 1.04125214332386e+00 1.08365878635908e-01 +-1.20000000000000e+02 4.97180960199916e-01 1.11060173995280e+00 1.24492137036960e-01 +-1.17000000000000e+02 4.53438556744641e-01 1.16661616454686e+00 1.39794623246837e-01 +-1.14000000000000e+02 4.09696303308865e-01 1.22263034910072e+00 1.55098596191987e-01 +-1.11000000000000e+02 3.65954392283428e-01 1.27864410574316e+00 1.70403792833604e-01 +-1.08000000000000e+02 3.17091142370324e-01 1.32114669115373e+00 1.84082975431326e-01 +-1.05000000000000e+02 2.65667184017510e-01 1.35689358806697e+00 1.96954679095920e-01 +-1.02000000000000e+02 2.14243214939976e-01 1.39264007535569e+00 2.09826696172051e-01 +-9.90000000000000e+01 1.61964542361192e-01 1.42013008159586e+00 2.21340640675138e-01 +-9.60000000000000e+01 1.07976425758201e-01 1.43110676810732e+00 2.30136989903572e-01 +-9.30000000000000e+01 5.39883669172201e-02 1.44208337076307e+00 2.38933482205731e-01 +-9.00000000000000e+01 3.36956720911094e-07 1.45305993149174e+00 2.47730362549832e-01 +-8.70000000000000e+01 -5.39883116604485e-02 1.44208338199759e+00 2.52366652228794e-01 +-8.40000000000000e+01 -1.07976576721003e-01 1.43110673741406e+00 2.57034873165347e-01 +-8.10000000000000e+01 -1.61964074669558e-01 1.42013017668539e+00 2.61734177795205e-01 +-7.80000000000000e+01 -2.14242965880546e-01 1.39264024848507e+00 2.63181349488851e-01 +-7.50000000000000e+01 -2.65667524235096e-01 1.35689335157008e+00 2.63016349820918e-01 +-7.20000000000000e+01 -3.17090893316325e-01 1.32114686428136e+00 2.62879007650853e-01 +-6.90000000000000e+01 -3.65954013346774e-01 1.27864459099094e+00 2.61500645209288e-01 +-6.60000000000000e+01 -4.09696425620247e-01 1.22263019247474e+00 2.57610540723508e-01 +-6.30000000000000e+01 -4.53438846142231e-01 1.16661579395854e+00 2.53744590647427e-01 +-6.00000000000000e+01 -4.97181177905552e-01 1.11060128113950e+00 2.49902512739027e-01 +-5.70000000000000e+01 -5.30087368951238e-01 1.04125168451056e+00 2.44282377435672e-01 +-5.40000000000000e+01 -5.62993667151980e-01 9.71901800324015e-01 2.38685350754697e-01 +-5.10000000000000e+01 -5.95900179664471e-01 9.02551341017881e-01 2.33110985323929e-01 +-4.80000000000000e+01 -6.23148878462794e-01 8.30040803802850e-01 2.27879411582758e-01 +-4.50000000000000e+01 -6.47568761333111e-01 7.55950278420295e-01 2.22834475134647e-01 +-4.20000000000000e+01 -6.67209820511491e-01 6.81725170790388e-01 2.19541528712913e-01 +-3.90000000000000e+01 -6.86016653934843e-01 6.07897658893372e-01 2.16860523607545e-01 +-3.60000000000000e+01 -7.02567434351865e-01 5.35679831809432e-01 2.16283272016665e-01 +-3.30000000000000e+01 -7.18514395643352e-01 4.66093046844495e-01 2.19061994245276e-01 +-3.00000000000000e+01 -7.35295993131416e-01 3.99297385438155e-01 2.25596659795295e-01 +-2.93939393939394e+01 -7.39161194393161e-01 3.86479064937486e-01 2.27934329427074e-01 +-2.87878787878788e+01 -7.43026395654906e-01 3.73660744436817e-01 2.30271999058854e-01 +-2.81818181818182e+01 -7.46891596916650e-01 3.60842423936148e-01 2.32609668690633e-01 +-2.75757575757576e+01 -7.51223361563041e-01 3.48434171659383e-01 2.35674061206088e-01 +-2.69696969696970e+01 -7.55755099099513e-01 3.36201677983836e-01 2.39049933104880e-01 +-2.63636363636364e+01 -7.60286836635986e-01 3.23969184308288e-01 2.42425805003671e-01 +-2.57575757575758e+01 -7.65221306359447e-01 3.11995455491433e-01 2.46346530788199e-01 +-2.51515151515151e+01 -7.70759780501553e-01 3.00409813654186e-01 2.51084410416232e-01 +-2.45454545454545e+01 -7.76298254643659e-01 2.88824171816938e-01 2.55822290044264e-01 +-2.39393939393939e+01 -7.82132311059061e-01 2.77302256598583e-01 2.59616206109365e-01 +-2.33333333333333e+01 -7.90626665160274e-01 2.66353893288030e-01 2.54914267352217e-01 +-2.27272727272727e+01 -7.99121019261486e-01 2.55405529977478e-01 2.49019152637843e-01 +-2.21212121212121e+01 -8.07615373362699e-01 2.44457166666925e-01 2.44656741536136e-01 +-2.15151515151515e+01 -8.17117669056492e-01 2.33552006854907e-01 2.32819418554197e-01 +-2.09090909090909e+01 -8.23661297618886e-01 2.22657650696563e-01 2.18130675248769e-01 +-2.03030303030303e+01 -8.30697385161204e-01 2.11763294538219e-01 2.03441931943341e-01 +-1.96969696969697e+01 -8.39130226130645e-01 2.00903773822104e-01 1.88879827702874e-01 +-1.90909090909091e+01 -8.48263760915409e-01 1.90079086577562e-01 1.74444355363349e-01 +-1.84848484848485e+01 -8.54491663822831e-01 1.78820853261852e-01 1.58678068289752e-01 +-1.78787878787879e+01 -8.60163856305434e-01 1.66900896684023e-01 1.43105400370003e-01 +-1.72727272727273e+01 -8.65742368749698e-01 1.55433036053471e-01 1.27344882544298e-01 +-1.66666666666667e+01 -8.69217768752512e-01 1.44247604332767e-01 1.10578705840612e-01 +-1.60606060606061e+01 -8.71119382404463e-01 1.33299705468418e-01 9.29795736467647e-02 +-1.54545454545455e+01 -8.74590802382996e-01 1.22693011692481e-01 7.42553100122313e-02 +-1.48484848484848e+01 -8.79448011540517e-01 1.12275192353923e-01 5.48980138044471e-02 +-1.42424242424242e+01 -8.88041287646387e-01 1.02097518094139e-01 3.47904219734257e-02 +-1.36363636363636e+01 -8.99011386472906e-01 9.19774216439529e-02 1.62310520565996e-02 +-1.30303030303030e+01 -9.12832326690409e-01 8.19089384860160e-02 -2.31248158698626e-03 +-1.24242424242424e+01 -9.05837733998151e-01 7.05955147275284e-02 -1.32519999298020e-02 +-1.18181818181818e+01 -8.94149738372733e-01 6.00304976315857e-02 -2.19483169052786e-02 +-1.12121212121212e+01 -8.72289143999857e-01 4.92518839816106e-02 -2.63426664394142e-02 +-1.06060606060606e+01 -8.43836935503105e-01 3.99601622843484e-02 -3.25182305032108e-02 +-1.00000000000000e+01 -8.11533667684698e-01 3.16634689071838e-02 -3.96531690559947e-02 +-9.39393939393939e+00 -7.73775299793918e-01 2.50351497976403e-02 -4.66232350387770e-02 +-8.78787878787879e+00 -7.24386153510650e-01 1.90363399048990e-02 -5.58158243641951e-02 +-8.18181818181818e+00 -6.51350581746786e-01 1.39307768873385e-02 -6.82565719779272e-02 +-7.57575757575758e+00 -5.70259292800422e-01 1.11966451026731e-02 -7.78318201646995e-02 +-6.96969696969697e+00 -4.84863483201162e-01 9.80210985000549e-03 -8.59002125918137e-02 +-6.36363636363636e+00 -4.01260274507495e-01 8.79364513160939e-03 -9.27920938216900e-02 +-5.75757575757576e+00 -3.17829037962407e-01 8.21072836680058e-03 -9.88413955927494e-02 +-5.15151515151515e+00 -2.34560631356565e-01 7.89417831655769e-03 -1.03830189790787e-01 +-4.54545454545454e+00 -1.52768219821946e-01 7.69629272463115e-03 -1.07609067491263e-01 +-3.93939393939394e+00 -7.17446885276158e-02 7.55980850277901e-03 -1.10714124632562e-01 +-3.33333333333333e+00 7.65266106535894e-03 7.40740590680152e-03 -1.13312526310592e-01 +-2.72727272727273e+00 8.69540435134952e-02 7.26852935125166e-03 -1.15619076304701e-01 +-2.12121212121212e+00 1.65602650506344e-01 7.16999070079818e-03 -1.17974728073125e-01 +-1.51515151515152e+00 2.43153008832856e-01 7.12240036540634e-03 -1.20398358450422e-01 +-9.09090909090912e-01 3.19690083645440e-01 7.11221121992558e-03 -1.22659469489510e-01 +-3.03030303030302e-01 3.94185583692908e-01 7.18341302084739e-03 -1.24698324985504e-01 + 3.03030303030302e-01 4.68902411410735e-01 7.22469085552886e-03 -1.26637855769298e-01 + 9.09090909090912e-01 5.43881635947123e-01 7.21999237311871e-03 -1.28343787287290e-01 + 1.51515151515152e+00 6.18852988644897e-01 7.24722163406657e-03 -1.29976534377553e-01 + 2.12121212121212e+00 6.93718405482782e-01 7.38406188230317e-03 -1.31468930098195e-01 + 2.72727272727273e+00 7.68149611769229e-01 7.53516389223080e-03 -1.32869142821252e-01 + 3.33333333333333e+00 8.41715172859199e-01 7.67641621971856e-03 -1.34133903242727e-01 + 3.93939393939394e+00 9.14829634658937e-01 7.82676312299375e-03 -1.35268602227928e-01 + 4.54545454545455e+00 9.87354918951398e-01 8.01392970071129e-03 -1.36139906970678e-01 + 5.15151515151515e+00 1.05927746446687e+00 8.23073134973320e-03 -1.36861989320736e-01 + 5.75757575757576e+00 1.12953343156332e+00 8.53450625263956e-03 -1.37191762867414e-01 + 6.36363636363637e+00 1.19646607280768e+00 8.93008691845142e-03 -1.37002644214539e-01 + 6.96969696969697e+00 1.26024731016983e+00 9.47027625942907e-03 -1.36418678279720e-01 + 7.57575757575757e+00 1.30971003050197e+00 1.06647324108263e-02 -1.33671247589578e-01 + 8.18181818181818e+00 1.35040217332210e+00 1.19527461931973e-02 -1.30058175517731e-01 + 8.78787878787879e+00 1.37091316495312e+00 1.39974785904022e-02 -1.24857926363025e-01 + 9.39393939393939e+00 1.35667712683307e+00 2.24354236046123e-02 -1.22733114545900e-01 + 1.00000000000000e+01 1.32700007053080e+00 3.43303944973221e-02 -1.22710273741457e-01 + 1.06060606060606e+01 1.24713203043916e+00 4.48348853319247e-02 -1.21775958563809e-01 + 1.12121212121212e+01 1.18632667549810e+00 5.33280007969130e-02 -1.20204637608153e-01 + 1.18181818181818e+01 1.16131302771668e+00 5.88308583503445e-02 -1.15957794313766e-01 + 1.24242424242424e+01 1.14844752198994e+00 6.69420911628980e-02 -1.11212235524214e-01 + 1.30303030303030e+01 1.14161039119524e+00 7.59411805359307e-02 -1.07908924395850e-01 + 1.36363636363636e+01 1.14446202808895e+00 8.67113082553106e-02 -1.09652277516758e-01 + 1.42424242424242e+01 1.15360925201834e+00 9.73732500785179e-02 -1.11627155262551e-01 + 1.48484848484848e+01 1.16355448827020e+00 1.07873104416001e-01 -1.14134059252607e-01 + 1.54545454545455e+01 1.16664773714290e+00 1.16951528881583e-01 -1.15612411766512e-01 + 1.60606060606061e+01 1.16661013255713e+00 1.25430946902501e-01 -1.16354027535650e-01 + 1.66666666666667e+01 1.15970818612903e+00 1.32782384020419e-01 -1.15612441871561e-01 + 1.72727272727273e+01 1.15449556243335e+00 1.41571380936791e-01 -1.15991269265136e-01 + 1.78787878787879e+01 1.15081418671560e+00 1.52117413613284e-01 -1.17753256291338e-01 + 1.84848484848485e+01 1.14958568526759e+00 1.64075993230739e-01 -1.21043159594879e-01 + 1.90909090909091e+01 1.14892881211198e+00 1.76252052672837e-01 -1.24587774021336e-01 + 1.96969696969697e+01 1.14714298858187e+00 1.87659451395701e-01 -1.27408729102206e-01 + 2.03030303030303e+01 1.14429050732898e+00 2.00561453897594e-01 -1.31242484394764e-01 + 2.09090909090909e+01 1.14266964540886e+00 2.14958144733618e-01 -1.36284282472763e-01 + 2.15151515151515e+01 1.14423506135131e+00 2.29354835569642e-01 -1.41385269444278e-01 + 2.21212121212121e+01 1.14307069922354e+00 2.43146307939168e-01 -1.46827329115247e-01 + 2.27272727272727e+01 1.13437676569340e+00 2.54517529167918e-01 -1.53633328645347e-01 + 2.33333333333333e+01 1.12568283216327e+00 2.65888750396669e-01 -1.60489831976375e-01 + 2.39393939393939e+01 1.11698889863313e+00 2.77259971625421e-01 -1.67539646177715e-01 + 2.45454545454545e+01 1.10899853924541e+00 2.88824171816938e-01 -1.73613983027854e-01 + 2.51515151515151e+01 1.10108635308077e+00 3.00409813654186e-01 -1.79569604350001e-01 + 2.57575757575758e+01 1.09317416691613e+00 3.11995455491433e-01 -1.85513172087669e-01 + 2.63636363636364e+01 1.08612496192253e+00 3.23969184308288e-01 -1.90961864811472e-01 + 2.69696969696970e+01 1.07965116711405e+00 3.36201677983836e-01 -1.96080224256372e-01 + 2.75757575757576e+01 1.07317737230558e+00 3.48434171659383e-01 -2.01190987495797e-01 + 2.81818181818182e+01 1.06698932003423e+00 3.60842423936148e-01 -2.06125820524907e-01 + 2.87878787878788e+01 1.06146794315678e+00 3.73660744436817e-01 -2.10662136737585e-01 + 2.93939393939394e+01 1.05594656627932e+00 3.86479064937486e-01 -2.15193450579188e-01 + 3.00000000000000e+01 1.05042518940186e+00 3.99297385438155e-01 -2.19719719772206e-01 + 3.30000000000000e+01 1.02644827609649e+00 4.66093046844495e-01 -2.39615606337711e-01 + 3.60000000000000e+01 1.00366641718899e+00 5.35679831809432e-01 -2.57787676201759e-01 + 3.90000000000000e+01 9.80023910642716e-01 6.07897658893372e-01 -2.74564735422046e-01 + 4.20000000000000e+01 9.53157091193240e-01 6.81725170790389e-01 -2.90390686664731e-01 + 4.50000000000000e+01 9.25099031707945e-01 7.55950278420295e-01 -3.05940905817259e-01 + 4.80000000000000e+01 8.90213156909925e-01 8.30040803802850e-01 -3.20687232891725e-01 + 5.10000000000000e+01 8.51286270268613e-01 9.02551341017882e-01 -3.35111108629908e-01 + 5.40000000000000e+01 8.04277100153241e-01 9.71901800324015e-01 -3.48903550668194e-01 + 5.70000000000000e+01 7.57267880913182e-01 1.04125168451056e+00 -3.62689866471288e-01 + 6.00000000000000e+01 7.10258637110966e-01 1.11060128113950e+00 -3.76470193714150e-01 + 6.30000000000000e+01 6.47769674730578e-01 1.16661579395854e+00 -3.88852281816777e-01 + 6.60000000000000e+01 5.85280557002702e-01 1.22263019247474e+00 -4.01231358690575e-01 + 6.90000000000000e+01 5.22791393951418e-01 1.27864459099094e+00 -4.13607260555449e-01 + 7.20000000000000e+01 4.52986794514127e-01 1.32114686428136e+00 -4.24708378476078e-01 + 7.50000000000000e+01 3.79524626640559e-01 1.35689335157008e+00 -4.35171875987646e-01 + 7.80000000000000e+01 3.06061084931655e-01 1.39264024848507e+00 -4.45633420993565e-01 + 8.10000000000000e+01 2.31376934566227e-01 1.42013017668539e+00 -4.55226551749704e-01 + 8.40000000000000e+01 1.54251651146622e-01 1.43110673741406e+00 -4.63084866775445e-01 + 8.70000000000000e+01 7.71257414576533e-02 1.44208338199759e+00 -4.70942168414430e-01 + 9.00000000000000e+01 -3.36956721141558e-07 1.45305993149174e+00 -4.78798611378502e-01 + 9.30000000000000e+01 -5.39883669172201e-02 1.44208337076307e+00 -4.83401960300538e-01 + 9.60000000000000e+01 -1.07976425758202e-01 1.43110676810732e+00 -4.87843492281115e-01 + 9.90000000000000e+01 -1.61964542361192e-01 1.42013008159586e+00 -4.92246671349029e-01 + 1.02000000000000e+02 -2.14243214939976e-01 1.39264007535569e+00 -4.93334961576679e-01 + 1.05000000000000e+02 -2.65667184017510e-01 1.35689358806697e+00 -4.92747792758473e-01 + 1.08000000000000e+02 -3.17091142370324e-01 1.32114669115373e+00 -4.92489218692733e-01 + 1.11000000000000e+02 -3.65954392283428e-01 1.27864410574316e+00 -4.91167327902475e-01 + 1.14000000000000e+02 -4.09696303308866e-01 1.22263034910072e+00 -4.87302639052758e-01 + 1.17000000000000e+02 -4.53438556744641e-01 1.16661616454686e+00 -4.83437520681149e-01 + 1.20000000000000e+02 -4.97180960199916e-01 1.11060173995280e+00 -4.79572183996746e-01 + 1.23000000000000e+02 -5.30087151245601e-01 1.04125214332386e+00 -4.73893974859065e-01 + 1.26000000000000e+02 -5.62993449444218e-01 9.71902259143020e-01 -4.68215548654545e-01 + 1.29000000000000e+02 -5.95899961956708e-01 9.02551799836887e-01 -4.62491545543420e-01 + 1.32000000000000e+02 -6.21555858594649e-01 8.29996331514373e-01 -4.57600132450428e-01 + 1.35000000000000e+02 -6.43586455890160e-01 7.55838362486724e-01 -4.53140066017817e-01 + 1.38000000000000e+02 -6.65616813110053e-01 6.81680698854136e-01 -4.48679982709285e-01 + 1.41000000000000e+02 -6.85803058067216e-01 6.08947766606052e-01 -4.46525550737110e-01 + 1.44000000000000e+02 -7.02301063534926e-01 5.39064308687913e-01 -4.48982440146784e-01 + 1.47000000000000e+02 -7.18798588287585e-01 4.69181021715765e-01 -4.51439319035616e-01 + 1.50000000000000e+02 -7.35295872691298e-01 3.99297820213560e-01 -4.53896192664215e-01 + 1.53000000000000e+02 -7.28330506319376e-01 3.46647734139971e-01 -4.68325381164791e-01 + 1.56000000000000e+02 -7.17850798388541e-01 2.93997685207009e-01 -4.82051328896962e-01 + 1.59000000000000e+02 -7.06863743588803e-01 2.41347630242394e-01 -4.98256732246163e-01 + 1.62000000000000e+02 -6.34811170157550e-01 2.01242252961188e-01 -5.03086039127970e-01 + 1.65000000000000e+02 -5.31470448900505e-01 1.67409320614642e-01 -5.01928907588892e-01 + 1.68000000000000e+02 -4.28130311834334e-01 1.33576175967328e-01 -5.00771566637685e-01 + 1.71000000000000e+02 -3.23313093840734e-01 9.99186368162403e-02 -4.50000513056908e-01 + 1.74000000000000e+02 -2.15541645031820e-01 6.66123168560943e-02 -2.99999717902353e-01 + 1.77000000000000e+02 -1.07279423135448e-01 5.50240468507236e-02 -1.40189247446868e-01 + 1.80000000000000e+02 0.00000000000000e+00 5.43028798119170e-02 2.26615932282131e-02 diff --git a/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_22.dat b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_22.dat new file mode 100644 index 00000000..c2189748 --- /dev/null +++ b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_22.dat @@ -0,0 +1,254 @@ +! ------------ AirfoilInfo v1.01.x Input File ---------------------------------- +! AeroElasticSE FAST driver +! line +! line +! ------------------------------------------------------------------------------ +DEFAULT InterpOrd ! Interpolation order to use for quasi-steady table lookup {1=linear; 3=cubic spline; "default"} [default=3] +1 NonDimArea ! The non-dimensional area of the airfoil (area/chord^2) (set to 1.0 if unsure or unneeded) +@"NREL-2p8-127_AF22_Coords.txt" NumCoords ! The number of coordinates in the airfoil shape file. Set to zero if coordinates not included. +AF22_BL.txt BL_file ! The file name including the boundary layer characteristics of the profile. Ignored if the aeroacoustic module is not called. +1 NumTabs ! Number of airfoil tables in this file. Each table must have lines for Re and Ctrl. +! ------------------------------------------------------------------------------ +! data for table 1 +! ------------------------------------------------------------------------------ +6.000000 Re ! Reynolds number in millions +0 Ctrl ! Control setting (must be 0 for current AirfoilInfo) +True InclUAdata ! Is unsteady aerodynamics data included in this table? If TRUE, then include 30 UA coefficients below this line +!........................................ +-3.566308 alpha0 ! 0-lift angle of attack, depends on airfoil. +9.412539 alpha1 ! Angle of attack at f=0.7, (approximately the stall angle) for AOA>alpha0. (deg) +-11.254245 alpha2 ! Angle of attack at f=0.7, (approximately the stall angle) for AOA1] +0.000000 S2 ! Constant in the f curve best-fit for AOA> alpha1; by definition it depends on the airfoil. [ignored if UAMod<>1] +0.000000 S3 ! Constant in the f curve best-fit for alpha2<=AOA< alpha0; by definition it depends on the airfoil. [ignored if UAMod<>1] +0.000000 S4 ! Constant in the f curve best-fit for AOA< alpha2; by definition it depends on the airfoil. [ignored if UAMod<>1] +1.372317 Cn1 ! Critical value of C0n at leading edge separation. It should be extracted from airfoil data at a given Mach and Reynolds number. It can be calculated from the static value of Cn at either the break in the pitching moment or the loss of chord force at the onset of stall. It is close to the condition of maximum lift of the airfoil at low Mach numbers. +-0.851187 Cn2 ! As Cn1 for negative AOAs. +Default St_sh ! Strouhal's shedding frequency constant. [default = 0.19] +0.007099 Cd0 ! 2D drag coefficient value at 0-lift. +-0.113167 Cm0 ! 2D pitching moment coefficient about 1/4-chord location, at 0-lift, positive if nose up. [If the aerodynamics coefficients table does not include a column for Cm, this needs to be set to 0.0] +0.000000 k0 ! Constant in the \hat(x)_cp curve best-fit; = (\hat(x)_AC-0.25). [ignored if UAMod<>1] +0.000000 k1 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k2 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k3 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k1_hat ! Constant in the expression of Cc due to leading edge vortex effects. [ignored if UAMod<>1] +Default x_cp_bar ! Constant in the expression of \hat(x)_cp^v. [ignored if UAMod<>1, default = 0.2] +Default UACutout ! Angle of attack above which unsteady aerodynamics are disabled (deg). [Specifying the string "Default" sets UACutout to 45 degrees] +Default filtCutOff ! Cut-off frequency (-3 dB corner frequency) for low-pass filtering the AoA input to UA, as well as the 1st and 2nd derivatives (Hz) [default = 20] +!........................................ +! Table of aerodynamics coefficients +200 NumAlf ! Number of data lines in the following table +! Alpha Cl Cd Cm +! (deg) (-) (-) (-) +-1.80000000000000e+02 0.00000000000000e+00 5.07556742159798e-02 6.34072788301272e-02 +-1.77000000000000e+02 1.21373168046836e-01 5.07556742159798e-02 1.44989137166855e-01 +-1.74000000000000e+02 2.43858124753276e-01 6.09067517869507e-02 2.39999774321882e-01 +-1.71000000000000e+02 3.65787584521499e-01 9.13603177509608e-02 3.60000410445527e-01 +-1.68000000000000e+02 4.75515174866590e-01 1.23180858733612e-01 3.13292467675056e-01 +-1.65000000000000e+02 5.79141972913914e-01 1.55684871270972e-01 1.83232181192322e-01 +-1.62000000000000e+02 6.82769984990416e-01 1.88188793392151e-01 5.31699414433441e-02 +-1.59000000000000e+02 7.49929094529181e-01 2.28115056904519e-01 -3.37679356965932e-02 +-1.56000000000000e+02 7.45401898546715e-01 2.82885752112716e-01 -3.57982585441417e-02 +-1.53000000000000e+02 7.40045790863415e-01 3.37656465738121e-01 -3.75882513662505e-02 +-1.50000000000000e+02 7.32596618631745e-01 3.92427224341668e-01 -3.50272634037363e-02 +-1.47000000000000e+02 7.16416220992227e-01 4.62548307459531e-01 -1.89393396903141e-02 +-1.44000000000000e+02 7.00235624959091e-01 5.32669512974126e-01 -2.85117921368804e-03 +-1.41000000000000e+02 6.84054632124555e-01 6.02790963290924e-01 1.27311247792732e-02 +-1.38000000000000e+02 6.64108508380734e-01 6.75798748422820e-01 2.82558445968883e-02 +-1.35000000000000e+02 6.42279826820249e-01 7.50249695107020e-01 4.38571814291932e-02 +-1.32000000000000e+02 6.20450921675678e-01 8.24701058603098e-01 5.94656947948800e-02 +-1.29000000000000e+02 5.94974616376641e-01 8.97565459936934e-01 7.52120953201059e-02 +-1.26000000000000e+02 5.62203493473854e-01 9.67255929411789e-01 9.12244354642672e-02 +-1.23000000000000e+02 5.29432511812518e-01 1.03694573967196e+00 1.07239613164941e-01 +-1.20000000000000e+02 4.96661600769268e-01 1.10663522033711e+00 1.23257579300455e-01 +-1.17000000000000e+02 4.53007747800845e-01 1.16302575005567e+00 1.38481557370608e-01 +-1.14000000000000e+02 4.09354049149219e-01 1.21941603836822e+00 1.53706780948661e-01 +-1.11000000000000e+02 3.65700701685022e-01 1.27580589589615e+00 1.68932988096397e-01 +-1.08000000000000e+02 3.16900772369631e-01 1.31870071696580e+00 1.82560097851392e-01 +-1.05000000000000e+02 2.65527512940554e-01 1.35484791704772e+00 1.95399125304991e-01 +-1.02000000000000e+02 2.14154242205798e-01 1.39099470291805e+00 2.08238303928547e-01 +-9.90000000000000e+01 1.61914865702625e-01 1.41888942602526e+00 2.19722912577175e-01 +-9.60000000000000e+01 1.07943240147024e-01 1.43027966616597e+00 2.28497123718656e-01 +-9.30000000000000e+01 5.39717537188113e-02 1.44166981929167e+00 2.37271383106753e-01 +-9.00000000000000e+01 3.36853033223878e-07 1.45305992891065e+00 2.46045939350736e-01 +-8.70000000000000e+01 -5.39716984790431e-02 1.44166983094945e+00 2.50473302115734e-01 +-8.40000000000000e+01 -1.07943391063713e-01 1.43027963431632e+00 2.54928173585132e-01 +-8.10000000000000e+01 -1.61914398153851e-01 1.41888952469734e+00 2.59409826519098e-01 +-7.80000000000000e+01 -2.14153993391912e-01 1.39099487798618e+00 2.60637456906859e-01 +-7.50000000000000e+01 -2.65527852822723e-01 1.35484767790248e+00 2.60250041617006e-01 +-7.20000000000000e+01 -3.16900523561175e-01 1.31870089203215e+00 2.59886362685276e-01 +-6.90000000000000e+01 -3.65700323515595e-01 1.27580638440210e+00 2.58282671903770e-01 +-6.60000000000000e+01 -4.09354171212959e-01 1.21941588069058e+00 2.54173349716066e-01 +-6.30000000000000e+01 -4.53008036612590e-01 1.16302537697905e+00 2.50084873782204e-01 +-6.00000000000000e+01 -4.96661817579899e-01 1.10663475927516e+00 2.46016982651216e-01 +-5.70000000000000e+01 -5.29432728623149e-01 1.03694527861001e+00 2.40180820587871e-01 +-5.40000000000000e+01 -5.62203710285886e-01 9.67255468343294e-01 2.34364534434322e-01 +-5.10000000000000e+01 -5.94974833188673e-01 8.97564998868439e-01 2.28567701938433e-01 +-4.80000000000000e+01 -6.22057662441151e-01 8.24737086109294e-01 2.23106850479156e-01 +-4.50000000000000e+01 -6.46296436287407e-01 7.50340502131161e-01 2.17827122416360e-01 +-4.20000000000000e+01 -6.65715236572083e-01 6.75834775642757e-01 2.14270938724142e-01 +-3.90000000000000e+01 -6.84287831284676e-01 6.01733100265088e-01 2.11324975236861e-01 +-3.60000000000000e+01 -7.00563864724568e-01 5.29261493580405e-01 2.10489244413362e-01 +-3.30000000000000e+01 -7.16187489056336e-01 4.59440503480610e-01 2.12957840755690e-01 +-3.00000000000000e+01 -7.32596736476158e-01 3.92426788149384e-01 2.19119564417483e-01 +-2.93939393939394e+01 -7.36374389172812e-01 3.79567808225057e-01 2.21363823380573e-01 +-2.87878787878788e+01 -7.40152041869467e-01 3.66708828300729e-01 2.23608082343664e-01 +-2.81818181818182e+01 -7.43929694566121e-01 3.53849848376402e-01 2.25852341306755e-01 +-2.75757575757576e+01 -7.48165648451628e-01 3.41402728220191e-01 2.28809630520161e-01 +-2.69696969696970e+01 -7.52598033982392e-01 3.29132134535727e-01 2.32072530342035e-01 +-2.63636363636364e+01 -7.57030419513156e-01 3.16861540851264e-01 2.35335430163909e-01 +-2.57575757575758e+01 -7.61859695409693e-01 3.04850755726473e-01 2.39132514207883e-01 +-2.51515151515151e+01 -7.67284214354563e-01 2.93229622889516e-01 2.43730750086607e-01 +-2.45454545454545e+01 -7.72708733299433e-01 2.81608490052560e-01 2.48328985965330e-01 +-2.39393939393939e+01 -7.78397371018865e-01 2.70052672159968e-01 2.52203196387113e-01 +-2.33333333333333e+01 -7.86463128844015e-01 2.59084701411948e-01 2.49561037521642e-01 +-2.27272727272727e+01 -7.94528886669166e-01 2.48116730663927e-01 2.45890720916381e-01 +-2.21212121212121e+01 -8.02594644494317e-01 2.37148759915907e-01 2.43586283408853e-01 +-2.15151515151515e+01 -8.10907795657620e-01 2.26212863295167e-01 2.36219129070528e-01 +-2.09090909090909e+01 -8.16516141250483e-01 2.15284987269397e-01 2.26807332042050e-01 +-2.03030303030303e+01 -8.22548837928087e-01 2.04357111243626e-01 2.17395535013573e-01 +-1.96969696969697e+01 -8.30002084619816e-01 1.93526156053271e-01 2.08338072839810e-01 +-1.90909090909091e+01 -8.38276075640665e-01 1.82792116215481e-01 1.99634925475900e-01 +-1.84848484848485e+01 -8.41525789425216e-01 1.71763238665119e-01 1.87206613897995e-01 +-1.78787878787879e+01 -8.43830658066113e-01 1.60232706599968e-01 1.74288223907780e-01 +-1.72727272727273e+01 -8.45969420405482e-01 1.49310415673877e-01 1.60399611180235e-01 +-1.66666666666667e+01 -8.44462724081164e-01 1.38631475065992e-01 1.43746150937375e-01 +-1.60606060606061e+01 -8.40100015006392e-01 1.28157201231612e-01 1.24821818047702e-01 +-1.54545454545455e+01 -8.37817603025782e-01 1.18032218056081e-01 1.04802159358542e-01 +-1.48484848484848e+01 -8.37183712471984e-01 1.08103958885772e-01 8.41678532118364e-02 +-1.42424242424242e+01 -8.40890120256044e-01 9.84661435612030e-02 6.27214130589554e-02 +-1.36363636363636e+01 -8.46817406852861e-01 8.88896748069138e-02 4.26434421043484e-02 +-1.30303030303030e+01 -8.55315988459211e-01 7.93654273525520e-02 2.26015400198430e-02 +-1.24242424242424e+01 -8.47245180473497e-01 6.91820678235402e-02 8.67599048926910e-03 +-1.18181818181818e+01 -8.35432683112564e-01 5.98195535661050e-02 -3.47219937244458e-03 +-1.12121212121212e+01 -8.15393459831635e-01 4.94939958051427e-02 -1.22220313441137e-02 +-1.06060606060606e+01 -7.90094798205374e-01 4.03354037886031e-02 -2.24327341739879e-02 +-1.00000000000000e+01 -7.61704104709643e-01 3.20697982337656e-02 -3.34296643848299e-02 +-9.39393939393939e+00 -7.28357715972300e-01 2.53011224655095e-02 -4.42541982301917e-02 +-8.78787878787879e+00 -6.84142454187570e-01 1.91495037741205e-02 -5.66943316671589e-02 +-8.18181818181818e+00 -6.17979429458198e-01 1.37667951514698e-02 -7.13770363239650e-02 +-7.57575757575758e+00 -5.38103979710377e-01 1.08227708003567e-02 -8.21189162256499e-02 +-6.96969696969697e+00 -4.51631211888217e-01 9.39164055487013e-03 -9.05502975056676e-02 +-6.36363636363636e+00 -3.69904831929908e-01 8.28680451711851e-03 -9.65427316699646e-02 +-5.75757575757576e+00 -2.88476726756192e-01 7.76135087915599e-03 -1.01757959286034e-01 +-5.15151515151515e+00 -2.07260475931238e-01 7.47535721667608e-03 -1.06060127684791e-01 +-4.54545454545454e+00 -1.27279930853378e-01 7.28615916745306e-03 -1.09371226057769e-01 +-3.93939393939394e+00 -4.80058499406509e-02 7.17092890724474e-03 -1.11865483581015e-01 +-3.33333333333333e+00 2.99773467049867e-02 7.05390574872594e-03 -1.13980246411455e-01 +-2.72727272727273e+00 1.07925041765181e-01 6.93627094208034e-03 -1.15908672907983e-01 +-2.12121212121212e+00 1.85286698580458e-01 6.86333451961630e-03 -1.17939670229949e-01 +-1.51515151515152e+00 2.61818679801486e-01 6.83016135377631e-03 -1.20251324856380e-01 +-9.09090909090912e-01 3.37437336745196e-01 6.82527631097856e-03 -1.22427420055716e-01 +-3.03030303030302e-01 4.11339964275432e-01 6.88875118426107e-03 -1.24393823575531e-01 + 3.03030303030302e-01 4.85425194785723e-01 6.93305859100922e-03 -1.26271092424251e-01 + 9.09090909090912e-01 5.59688748393245e-01 6.92641095940415e-03 -1.27930360286602e-01 + 1.51515151515152e+00 6.33889422008781e-01 6.97145778583218e-03 -1.29509636273062e-01 + 2.12121212121212e+00 7.08007295477312e-01 7.08503567582370e-03 -1.30948866987131e-01 + 2.72727272727273e+00 7.81743944095907e-01 7.22808542364998e-03 -1.32280278589569e-01 + 3.33333333333333e+00 8.54768718499635e-01 7.36394317569994e-03 -1.33476357648126e-01 + 3.93939393939394e+00 9.27343605653137e-01 7.50800878324420e-03 -1.34580752920963e-01 + 4.54545454545455e+00 9.99337144270299e-01 7.68025178023798e-03 -1.35437140997352e-01 + 5.15151515151515e+00 1.07077533588784e+00 7.88250770331053e-03 -1.36171448237875e-01 + 5.75757575757576e+00 1.14067573993544e+00 8.18560595986809e-03 -1.36563716920552e-01 + 6.36363636363637e+00 1.20738594989603e+00 8.61082274432950e-03 -1.36450536130407e-01 + 6.96969696969697e+00 1.27030534457503e+00 9.26154940433015e-03 -1.35865188748459e-01 + 7.57575757575757e+00 1.31967720204744e+00 1.06711516164033e-02 -1.33196036139163e-01 + 8.18181818181818e+00 1.36117901696138e+00 1.20457201580521e-02 -1.29734082098160e-01 + 8.78787878787879e+00 1.38645164475349e+00 1.40141299367242e-02 -1.24969368476653e-01 + 9.39393939393939e+00 1.38364788675440e+00 2.10604272519143e-02 -1.22681471706985e-01 + 1.00000000000000e+01 1.36632615029107e+00 3.08301921000425e-02 -1.22594505197778e-01 + 1.06060606060606e+01 1.30793900793488e+00 3.95953728731437e-02 -1.21768157631026e-01 + 1.12121212121212e+01 1.26354919483254e+00 4.68596237969062e-02 -1.20824315241689e-01 + 1.18181818181818e+01 1.24622078267823e+00 5.34209201004403e-02 -1.17862121865541e-01 + 1.24242424242424e+01 1.23316572300737e+00 6.31476016531568e-02 -1.14380907459069e-01 + 1.30303030303030e+01 1.22283883104523e+00 7.34240891191203e-02 -1.12038188702533e-01 + 1.36363636363636e+01 1.21302095714098e+00 8.54972535339130e-02 -1.13922354181064e-01 + 1.42424242424242e+01 1.20995851746224e+00 9.67529857851515e-02 -1.15899802821485e-01 + 1.48484848484848e+01 1.20957781975123e+00 1.06783261680667e-01 -1.18176308348192e-01 + 1.54545454545455e+01 1.20628232400092e+00 1.15676133910572e-01 -1.19630275206793e-01 + 1.60606060606061e+01 1.20129649682940e+00 1.24088573760305e-01 -1.20475625038284e-01 + 1.66666666666667e+01 1.19049649901642e+00 1.31588359571251e-01 -1.20087718033958e-01 + 1.72727272727273e+01 1.17964142895866e+00 1.40230863472286e-01 -1.20588628022729e-01 + 1.78787878787879e+01 1.16825933056011e+00 1.50270037306760e-01 -1.22187730969383e-01 + 1.84848484848485e+01 1.16279372315999e+00 1.61375170677979e-01 -1.24959559895277e-01 + 1.90909090909091e+01 1.15872202145603e+00 1.72688440191291e-01 -1.28082765397647e-01 + 1.96969696969697e+01 1.15339844517572e+00 1.83671166909384e-01 -1.31533890864235e-01 + 2.03030303030303e+01 1.14667353640152e+00 1.95931329664752e-01 -1.35939723395958e-01 + 2.09090909090909e+01 1.14214263161388e+00 2.09469000726538e-01 -1.41468507832042e-01 + 2.15151515151515e+01 1.14163199846552e+00 2.23006671788323e-01 -1.47048295239323e-01 + 2.21212121212121e+01 1.13801617834194e+00 2.36098095781483e-01 -1.52838501078495e-01 + 2.27272727272727e+01 1.12925112767887e+00 2.47404990655498e-01 -1.59470164140170e-01 + 2.33333333333333e+01 1.12048607701580e+00 2.58711885529513e-01 -1.66145346243189e-01 + 2.39393939393939e+01 1.11172102635272e+00 2.70018780403529e-01 -1.72987104001955e-01 + 2.45454545454545e+01 1.10386992919784e+00 2.81608490052560e-01 -1.78880886757862e-01 + 2.51515151515151e+01 1.09612038024829e+00 2.93229622889516e-01 -1.84660438598366e-01 + 2.57575757575758e+01 1.08837083129873e+00 3.04850755726473e-01 -1.90429603885151e-01 + 2.63636363636364e+01 1.08147195893053e+00 3.16861540851264e-01 -1.95726297856203e-01 + 2.69696969696970e+01 1.07514029241291e+00 3.29132134535727e-01 -2.00707647194441e-01 + 2.75757575757576e+01 1.06880862589528e+00 3.41402728220191e-01 -2.05682450895045e-01 + 2.81818181818182e+01 1.06275754212664e+00 3.53849848376402e-01 -2.10489790164498e-01 + 2.87878787878788e+01 1.05736109527898e+00 3.66708828300730e-01 -2.14916711454757e-01 + 2.93939393939394e+01 1.05196464843131e+00 3.79567808225057e-01 -2.19339322210173e-01 + 3.00000000000000e+01 1.04656820158365e+00 3.92426788149384e-01 -2.23757586000285e-01 + 3.30000000000000e+01 1.02312514415356e+00 4.59440503480610e-01 -2.43238943532748e-01 + 3.60000000000000e+01 1.00080435367758e+00 5.29261493580405e-01 -2.61084484698553e-01 + 3.90000000000000e+01 9.77554126454961e-01 6.01733100265088e-01 -2.77608856801414e-01 + 4.20000000000000e+01 9.51021881685284e-01 6.75834775642758e-01 -2.93234977723852e-01 + 4.50000000000000e+01 9.23281318212600e-01 7.50340502131161e-01 -3.08601809213403e-01 + 4.80000000000000e+01 8.88654194131487e-01 8.24737086109295e-01 -3.23208356054975e-01 + 5.10000000000000e+01 8.49964254625460e-01 8.97564998868439e-01 -3.37506814180089e-01 + 5.40000000000000e+01 8.03148423080423e-01 9.67255468343294e-01 -3.51200699120049e-01 + 5.70000000000000e+01 7.56332531480030e-01 1.03694527861001e+00 -3.64889313118346e-01 + 6.00000000000000e+01 7.09516609852189e-01 1.10663475927516e+00 -3.78572770796720e-01 + 6.30000000000000e+01 6.47154294385920e-01 1.16302537697905e+00 -3.90891753454121e-01 + 6.60000000000000e+01 5.84791782254718e-01 1.21941588069058e+00 -4.03208150894803e-01 + 6.90000000000000e+01 5.22429143308335e-01 1.27580638440210e+00 -4.15521834280170e-01 + 7.20000000000000e+01 4.52714954299060e-01 1.31870089203215e+00 -4.26575704118960e-01 + 7.50000000000000e+01 3.79325140754361e-01 1.35484767790248e+00 -4.36999473643461e-01 + 7.80000000000000e+01 3.05934076441010e-01 1.39099487798618e+00 -4.47421477951532e-01 + 8.10000000000000e+01 2.31306131004083e-01 1.41888952469734e+00 -4.56980574222415e-01 + 8.40000000000000e+01 1.54204508701838e-01 1.43027963431632e+00 -4.64815596729305e-01 + 8.70000000000000e+01 7.71021882732242e-02 1.44166983094945e+00 -4.72649698806517e-01 + 9.00000000000000e+01 -3.36853033455059e-07 1.45305992891065e+00 -4.80483033427282e-01 + 9.30000000000000e+01 -5.39717537188113e-02 1.44166981929167e+00 -4.84882001487256e-01 + 9.60000000000000e+01 -1.07943240147024e-01 1.43027966616597e+00 -4.88977291312720e-01 + 9.90000000000000e+01 -1.61914865702625e-01 1.41888942602526e+00 -4.93035304646623e-01 + 1.02000000000000e+02 -2.14154242205798e-01 1.39099470291805e+00 -4.93786567296916e-01 + 1.05000000000000e+02 -2.65527512940555e-01 1.35484791704772e+00 -4.92868936308638e-01 + 1.08000000000000e+02 -3.16900772369631e-01 1.31870071696580e+00 -4.92410220071252e-01 + 1.11000000000000e+02 -3.65700701685022e-01 1.27580589589615e+00 -4.90965426724924e-01 + 1.14000000000000e+02 -4.09354049149220e-01 1.21941603836822e+00 -4.86982932906717e-01 + 1.17000000000000e+02 -4.53007747800845e-01 1.16302575005567e+00 -4.83000008666658e-01 + 1.20000000000000e+02 -4.96661600769268e-01 1.10663522033711e+00 -4.79016865676293e-01 + 1.23000000000000e+02 -5.29432511812518e-01 1.03694573967196e+00 -4.73227232421762e-01 + 1.26000000000000e+02 -5.62203493473854e-01 9.67255929411789e-01 -4.67437401740092e-01 + 1.29000000000000e+02 -5.94974616376641e-01 8.97565459936934e-01 -4.61550294565979e-01 + 1.32000000000000e+02 -6.20450921675679e-01 8.24701058603098e-01 -4.56453890288661e-01 + 1.35000000000000e+02 -6.42279826820249e-01 7.50249695107020e-01 -4.51785141239963e-01 + 1.38000000000000e+02 -6.64108508380734e-01 6.75798748422819e-01 -4.47116255471473e-01 + 1.41000000000000e+02 -6.84054632124555e-01 6.02790963290923e-01 -4.44720379804122e-01 + 1.44000000000000e+02 -7.00235624959091e-01 5.32669512974126e-01 -4.46870542783319e-01 + 1.47000000000000e+02 -7.16416220992227e-01 4.62548307459531e-01 -4.49020707038669e-01 + 1.50000000000000e+02 -7.32596618631745e-01 3.92427224341668e-01 -4.51170871932074e-01 + 1.53000000000000e+02 -7.33272841626932e-01 3.38604126000068e-01 -4.67244946323259e-01 + 1.56000000000000e+02 -7.30920747814166e-01 2.84781062373784e-01 -4.81810042653382e-01 + 1.59000000000000e+02 -7.28131423029985e-01 2.30957992223316e-01 -4.99843304573404e-01 + 1.62000000000000e+02 -6.59004284451097e-01 1.91223709907543e-01 -5.04964107373118e-01 + 1.65000000000000e+02 -5.56057205936165e-01 1.58533940661002e-01 -5.03102799944957e-01 + 1.68000000000000e+02 -4.53110707101343e-01 1.25843946014156e-01 -5.01241125772289e-01 + 1.71000000000000e+02 -3.46031678268841e-01 9.36455360526948e-02 -4.50000513056908e-01 + 1.74000000000000e+02 -2.30687396505613e-01 6.24303184126113e-02 -2.99999717902353e-01 + 1.77000000000000e+02 -1.14817786337317e-01 5.15140111366759e-02 -1.23779476102597e-01 + 1.80000000000000e+02 0.00000000000000e+00 5.07556742159798e-02 6.34072788301272e-02 diff --git a/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_23.dat b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_23.dat new file mode 100644 index 00000000..1d9534a4 --- /dev/null +++ b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_23.dat @@ -0,0 +1,254 @@ +! ------------ AirfoilInfo v1.01.x Input File ---------------------------------- +! AeroElasticSE FAST driver +! line +! line +! ------------------------------------------------------------------------------ +DEFAULT InterpOrd ! Interpolation order to use for quasi-steady table lookup {1=linear; 3=cubic spline; "default"} [default=3] +1 NonDimArea ! The non-dimensional area of the airfoil (area/chord^2) (set to 1.0 if unsure or unneeded) +@"NREL-2p8-127_AF23_Coords.txt" NumCoords ! The number of coordinates in the airfoil shape file. Set to zero if coordinates not included. +AF23_BL.txt BL_file ! The file name including the boundary layer characteristics of the profile. Ignored if the aeroacoustic module is not called. +1 NumTabs ! Number of airfoil tables in this file. Each table must have lines for Re and Ctrl. +! ------------------------------------------------------------------------------ +! data for table 1 +! ------------------------------------------------------------------------------ +6.000000 Re ! Reynolds number in millions +0 Ctrl ! Control setting (must be 0 for current AirfoilInfo) +True InclUAdata ! Is unsteady aerodynamics data included in this table? If TRUE, then include 30 UA coefficients below this line +!........................................ +-3.734961 alpha0 ! 0-lift angle of attack, depends on airfoil. +9.697795 alpha1 ! Angle of attack at f=0.7, (approximately the stall angle) for AOA>alpha0. (deg) +-10.684389 alpha2 ! Angle of attack at f=0.7, (approximately the stall angle) for AOA1] +0.000000 S2 ! Constant in the f curve best-fit for AOA> alpha1; by definition it depends on the airfoil. [ignored if UAMod<>1] +0.000000 S3 ! Constant in the f curve best-fit for alpha2<=AOA< alpha0; by definition it depends on the airfoil. [ignored if UAMod<>1] +0.000000 S4 ! Constant in the f curve best-fit for AOA< alpha2; by definition it depends on the airfoil. [ignored if UAMod<>1] +1.401232 Cn1 ! Critical value of C0n at leading edge separation. It should be extracted from airfoil data at a given Mach and Reynolds number. It can be calculated from the static value of Cn at either the break in the pitching moment or the loss of chord force at the onset of stall. It is close to the condition of maximum lift of the airfoil at low Mach numbers. +-0.842106 Cn2 ! As Cn1 for negative AOAs. +Default St_sh ! Strouhal's shedding frequency constant. [default = 0.19] +0.006818 Cd0 ! 2D drag coefficient value at 0-lift. +-0.113242 Cm0 ! 2D pitching moment coefficient about 1/4-chord location, at 0-lift, positive if nose up. [If the aerodynamics coefficients table does not include a column for Cm, this needs to be set to 0.0] +0.000000 k0 ! Constant in the \hat(x)_cp curve best-fit; = (\hat(x)_AC-0.25). [ignored if UAMod<>1] +0.000000 k1 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k2 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k3 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k1_hat ! Constant in the expression of Cc due to leading edge vortex effects. [ignored if UAMod<>1] +Default x_cp_bar ! Constant in the expression of \hat(x)_cp^v. [ignored if UAMod<>1, default = 0.2] +Default UACutout ! Angle of attack above which unsteady aerodynamics are disabled (deg). [Specifying the string "Default" sets UACutout to 45 degrees] +Default filtCutOff ! Cut-off frequency (-3 dB corner frequency) for low-pass filtering the AoA input to UA, as well as the 1st and 2nd derivatives (Hz) [default = 20] +!........................................ +! Table of aerodynamics coefficients +200 NumAlf ! Number of data lines in the following table +! Alpha Cl Cd Cm +! (deg) (-) (-) (-) +-1.80000000000000e+02 0.00000000000000e+00 4.63087218239101e-02 1.12294918356446e-01 +-1.77000000000000e+02 1.31407871834538e-01 4.63087218239101e-02 1.64677969845384e-01 +-1.74000000000000e+02 2.64019510355404e-01 5.55704139343663e-02 2.39999774321882e-01 +-1.71000000000000e+02 3.96029843973720e-01 8.33557943190768e-02 3.60000410445527e-01 +-1.68000000000000e+02 5.06430868461261e-01 1.13562290370517e-01 3.08610785372619e-01 +-1.65000000000000e+02 6.06027490595898e-01 1.44979315997335e-01 1.71528030078362e-01 +-1.62000000000000e+02 7.05625285482958e-01 1.76396375603631e-01 3.44433778978911e-02 +-1.59000000000000e+02 7.67703923736826e-01 2.15960936619897e-01 -5.47934885866511e-02 +-1.56000000000000e+02 7.55397723550236e-01 2.71820224837142e-01 -4.90352678454869e-02 +-1.53000000000000e+02 7.42659054409641e-01 3.27679539787795e-01 -4.31517727134676e-02 +-1.50000000000000e+02 7.28828504793094e-01 3.83538902055256e-01 -3.44596878302946e-02 +-1.47000000000000e+02 7.13090480114408e-01 4.53967729130364e-01 -1.86189086211220e-02 +-1.44000000000000e+02 6.97352307618548e-01 5.24396727029221e-01 -2.77793532551869e-03 +-1.41000000000000e+02 6.81613839477788e-01 5.94826066587771e-01 1.25927965767874e-02 +-1.38000000000000e+02 6.62002920890116e-01 6.68189421819665e-01 2.79774029417006e-02 +-1.35000000000000e+02 6.40455784934676e-01 7.43019778936259e-01 4.34673885521046e-02 +-1.32000000000000e+02 6.18908433527060e-01 8.17850698969113e-01 5.89612242447798e-02 +-1.29000000000000e+02 5.93682830023854e-01 8.91114749342423e-01 7.46038609930899e-02 +-1.26000000000000e+02 5.61100704888174e-01 9.61245052954708e-01 9.05389699091404e-02 +-1.23000000000000e+02 5.28518625044670e-01 1.03137459621631e+00 1.06475722031366e-01 +-1.20000000000000e+02 4.95936567846408e-01 1.10150375931678e+00 1.22414010239834e-01 +-1.17000000000000e+02 4.52406347782145e-01 1.15838084536770e+00 1.37579477845402e-01 +-1.14000000000000e+02 4.08876283070132e-01 1.21525768824574e+00 1.52745471209185e-01 +-1.11000000000000e+02 3.65346571871469e-01 1.27213409662221e+00 1.67911731135092e-01 +-1.08000000000000e+02 3.16635035430310e-01 1.31553636143885e+00 1.81492961378994e-01 +-1.05000000000000e+02 2.65332546911451e-01 1.35220145187604e+00 1.94295080678717e-01 +-1.02000000000000e+02 2.14030046275947e-01 1.38886612216712e+00 2.07096904272415e-01 +-9.90000000000000e+01 1.61845527217881e-01 1.41728443461560e+00 2.18547504691698e-01 +-9.60000000000000e+01 1.07896933109836e-01 1.42920967418575e+00 2.27294974831625e-01 +-9.30000000000000e+01 5.39485757284989e-02 1.44113482265378e+00 2.36042235203500e-01 +-9.00000000000000e+01 3.36708372806976e-07 1.45305992557158e+00 2.44789532965389e-01 +-8.70000000000000e+01 -5.39485205124533e-02 1.44113483485913e+00 2.48978944307922e-01 +-8.40000000000000e+01 -1.07897083962124e-01 1.42920964084012e+00 2.53182684189232e-01 +-8.10000000000000e+01 -1.61845059868626e-01 1.41728453792232e+00 2.57400380355460e-01 +-7.80000000000000e+01 -2.14029797804819e-01 1.38886629974350e+00 2.58354097127670e-01 +-7.50000000000000e+01 -2.65332886325409e-01 1.35220120930450e+00 2.57682039063764e-01 +-7.20000000000000e+01 -3.16634786964608e-01 1.31553653901342e+00 2.57022063927401e-01 +-6.90000000000000e+01 -3.65346194773105e-01 1.27213458934316e+00 2.55116538347366e-01 +-6.60000000000000e+01 -4.08876404788159e-01 1.21525752920760e+00 2.50706504502961e-01 +-6.30000000000000e+01 -4.52406635775942e-01 1.15838046907205e+00 2.46307312278457e-01 +-6.00000000000000e+01 -4.95936783407592e-01 1.10150329534591e+00 2.41918834523807e-01 +-5.70000000000000e+01 -5.28518840605854e-01 1.03137413224544e+00 2.35766279929407e-01 +-5.40000000000000e+01 -5.61100920449807e-01 9.61244588976293e-01 2.29623980263181e-01 +-5.10000000000000e+01 -5.93683045585487e-01 8.91114285364008e-01 2.23491601843586e-01 +-4.80000000000000e+01 -6.20534325092436e-01 8.17875803160575e-01 2.17675688732665e-01 +-4.50000000000000e+01 -6.44520273887822e-01 7.43083281614397e-01 2.12024856819171e-01 +-4.20000000000000e+01 -6.63628799731457e-01 6.68214525810191e-01 2.08040444001537e-01 +-3.90000000000000e+01 -6.81874399513891e-01 5.93758161928647e-01 2.04674544610408e-01 +-3.60000000000000e+01 -6.97766871415788e-01 5.20958260992169e-01 2.03489583532797e-01 +-3.30000000000000e+01 -7.12939161093519e-01 4.50834279245390e-01 2.05538204979316e-01 +-3.00000000000000e+01 -7.28828619013840e-01 3.83538464029985e-01 2.11194373081700e-01 +-2.93939393939394e+01 -7.32484050886326e-01 3.70626883995265e-01 2.13311958401767e-01 +-2.87878787878788e+01 -7.36139482758811e-01 3.57715303960545e-01 2.15429543721834e-01 +-2.81818181818182e+01 -7.39794914631297e-01 3.44803723925826e-01 2.17547129041902e-01 +-2.75757575757576e+01 -7.43897116047021e-01 3.32306320069088e-01 2.20359205164668e-01 +-2.69696969696970e+01 -7.48190806550193e-01 3.19986435516351e-01 2.23468945736725e-01 +-2.63636363636364e+01 -7.52484497053364e-01 3.07666550963613e-01 2.26578686308783e-01 +-2.57575757575758e+01 -7.57166921645990e-01 2.95607827569598e-01 2.30208187650959e-01 +-2.51515151515151e+01 -7.62432356773396e-01 2.83940785046750e-01 2.34617209011481e-01 +-2.45454545454545e+01 -7.67697791900801e-01 2.72273742523902e-01 2.39026230372002e-01 +-2.39393939393939e+01 -7.73185913789781e-01 2.60674093105127e-01 2.42999615685138e-01 +-2.33333333333333e+01 -7.80678259646152e-01 2.49680994670638e-01 2.43052192230589e-01 +-2.27272727272727e+01 -7.88170605502522e-01 2.38687896236150e-01 2.42568426653275e-01 +-2.21212121212121e+01 -7.95662951358893e-01 2.27694797801661e-01 2.42847201975787e-01 +-2.15151515151515e+01 -8.03122917039084e-01 2.16821981366589e-01 2.40650679427694e-01 +-2.09090909090909e+01 -8.09131542492648e-01 2.05979243168443e-01 2.37504038302243e-01 +-2.03030303030303e+01 -8.15361532190997e-01 1.95136504970297e-01 2.34357397176791e-01 +-1.96969696969697e+01 -8.22724297362875e-01 1.84465173018459e-01 2.31838282654647e-01 +-1.90909090909091e+01 -8.30906925089566e-01 1.73965237616411e-01 2.29946659236386e-01 +-1.84848484848485e+01 -8.31918112583414e-01 1.63453683142057e-01 2.21457087959307e-01 +-1.78787878787879e+01 -8.31595126485506e-01 1.52804171278659e-01 2.11525887706305e-01 +-1.72727272727273e+01 -8.31031369674327e-01 1.42866609967544e-01 1.99629022620351e-01 +-1.66666666666667e+01 -8.25256436764452e-01 1.33056030411927e-01 1.82862818294272e-01 +-1.60606060606061e+01 -8.15283902136340e-01 1.23352246439714e-01 1.62108086965354e-01 +-1.54545454545455e+01 -8.07202667770935e-01 1.13892061964644e-01 1.40642855087825e-01 +-1.48484848484848e+01 -8.00484816929381e-01 1.04572113067813e-01 1.18780315352772e-01 +-1.42424242424242e+01 -7.97273008609856e-01 9.54960779870226e-02 9.63104203643558e-02 +-1.36363636363636e+01 -7.95411303466245e-01 8.64650864864851e-02 7.45927649489055e-02 +-1.30303030303030e+01 -7.95017738651442e-01 7.74696737429739e-02 5.29180621304360e-02 +-1.24242424242424e+01 -7.83491668219477e-01 6.82294219737490e-02 3.53906464364337e-02 +-1.18181818181818e+01 -7.69390633326341e-01 5.96867612177415e-02 1.90461834027338e-02 +-1.12121212121212e+01 -7.49852461255598e-01 4.99975509367422e-02 4.95579546151236e-03 +-1.06060606060606e+01 -7.26864172133525e-01 4.11158480572885e-02 -1.01481331303818e-02 +-1.00000000000000e+01 -7.01883025098080e-01 3.29149003627515e-02 -2.57966293458753e-02 +-9.39393939393939e+00 -6.73760079004400e-01 2.58543044614024e-02 -4.12961616654669e-02 +-8.78787878787879e+00 -6.36634699427489e-01 1.93848671125434e-02 -5.74839914192587e-02 +-8.18181818181818e+00 -5.81874634591272e-01 1.36623501221776e-02 -7.45539130446945e-02 +-7.57575757575758e+00 -5.05150686435173e-01 1.05716894357738e-02 -8.64279283248293e-02 +-6.96969696969697e+00 -4.18595232643061e-01 9.10734541656171e-03 -9.50674159963851e-02 +-6.36363636363636e+00 -3.38986978205484e-01 7.90162668231047e-03 -9.99599652998083e-02 +-5.75757575757576e+00 -2.59840510197803e-01 7.41964713494604e-03 -1.04208933106189e-01 +-5.15151515151515e+00 -1.80988998184422e-01 7.14720887337387e-03 -1.07763832355698e-01 +-4.54545454545454e+00 -1.03071489415176e-01 6.95243839815077e-03 -1.10602747534693e-01 +-3.93939393939394e+00 -2.57708400834061e-02 6.84633480589618e-03 -1.12642875373749e-01 +-3.33333333333333e+00 5.06291120206322e-02 6.76146535162503e-03 -1.14417763754454e-01 +-2.72727272727273e+00 1.27032191349935e-01 6.66325312920406e-03 -1.16093113518882e-01 +-2.12121212121212e+00 2.02920139434825e-01 6.61583701230752e-03 -1.17866755340555e-01 +-1.51515151515152e+00 2.78307232368702e-01 6.59553135545088e-03 -1.19945517730907e-01 +-9.09090909090912e-01 3.52936192696077e-01 6.59403346409144e-03 -1.21944793137844e-01 +-3.03030303030302e-01 4.26320562661541e-01 6.64943771563519e-03 -1.23760507757517e-01 + 3.03030303030302e-01 4.99818577478435e-01 6.69818073560818e-03 -1.25508281414915e-01 + 9.09090909090912e-01 5.73376543665411e-01 6.69183344611623e-03 -1.27070496093681e-01 + 1.51515151515152e+00 6.46799556143286e-01 6.75524511750563e-03 -1.28538560457679e-01 + 2.12121212121212e+00 7.20154880913483e-01 6.84155940142869e-03 -1.29906010197320e-01 + 2.72727272727273e+00 7.93147472633957e-01 6.97678572298154e-03 -1.31165648253112e-01 + 3.33333333333333e+00 8.65616018748002e-01 7.10739240893340e-03 -1.32288860283965e-01 + 3.93939393939394e+00 9.37648112828365e-01 7.24422887006074e-03 -1.33365853998558e-01 + 4.54545454545455e+00 1.00910358732349e+00 7.39983874217581e-03 -1.34215184053867e-01 + 5.15151515151515e+00 1.08005492256340e+00 7.58558750578516e-03 -1.34976127499023e-01 + 5.75757575757576e+00 1.14960510771521e+00 7.88653428093343e-03 -1.35458436688932e-01 + 6.36363636363637e+00 1.21615416551218e+00 8.34153340579227e-03 -1.35456842953982e-01 + 6.96969696969697e+00 1.27828480587284e+00 9.10488091440775e-03 -1.34893951393780e-01 + 7.57575757575757e+00 1.32797468584652e+00 1.06845025707761e-02 -1.32377276048360e-01 + 8.18181818181818e+00 1.37107050025369e+00 1.21820686740787e-02 -1.29169553035756e-01 + 8.78787878787879e+00 1.40369513738070e+00 1.40255937471439e-02 -1.25043047898281e-01 + 9.39393939393939e+00 1.41709683794245e+00 1.92334681728973e-02 -1.22574062592608e-01 + 1.00000000000000e+01 1.41645872036543e+00 2.62062454721527e-02 -1.22372841879845e-01 + 1.06060606060606e+01 1.38657460264657e+00 3.26763717983368e-02 -1.21751932897855e-01 + 1.12121212121212e+01 1.36400259487080e+00 3.83098431246971e-02 -1.21315233753301e-01 + 1.18181818181818e+01 1.35688821281416e+00 4.60809911460502e-02 -1.19819418114883e-01 + 1.24242424242424e+01 1.34089573725963e+00 5.79456504379348e-02 -1.18207966359576e-01 + 1.30303030303030e+01 1.32223161769021e+00 7.00497051047743e-02 -1.17191325445144e-01 + 1.36363636363636e+01 1.29585304328532e+00 8.36737099489719e-02 -1.19176336444020e-01 + 1.42424242424242e+01 1.27550502164861e+00 9.56164211836313e-02 -1.21085843980632e-01 + 1.48484848484848e+01 1.26031280258829e+00 1.05038483493522e-01 -1.22965364533929e-01 + 1.54545454545455e+01 1.24817918569169e+00 1.13694141927813e-01 -1.24250481062770e-01 + 1.60606060606061e+01 1.23659506592632e+00 1.22025178103146e-01 -1.25145411447740e-01 + 1.66666666666667e+01 1.22112439263804e+00 1.29733166820717e-01 -1.25238540045732e-01 + 1.72727272727273e+01 1.20372487247866e+00 1.38204896553668e-01 -1.25906002656970e-01 + 1.78787878787879e+01 1.18372803528903e+00 1.47610097212096e-01 -1.27281617838633e-01 + 1.84848484848485e+01 1.17400652248468e+00 1.57673262028419e-01 -1.29411130817857e-01 + 1.90909090909091e+01 1.16668752601417e+00 1.67940267889330e-01 -1.32031130540839e-01 + 1.96969696969697e+01 1.15802631000889e+00 1.78430476422176e-01 -1.36362103439965e-01 + 2.03030303030303e+01 1.14825771518914e+00 1.89897612594817e-01 -1.41556026190695e-01 + 2.09090909090909e+01 1.14104652446381e+00 2.02341731675555e-01 -1.47700684953726e-01 + 2.15151515151515e+01 1.13734479071489e+00 2.14785850756294e-01 -1.53871949597139e-01 + 2.21212121212121e+01 1.13089213779505e+00 2.26985477991913e-01 -1.60089208840245e-01 + 2.27272727272727e+01 1.12204977020079e+00 2.38207389411154e-01 -1.66490399157068e-01 + 2.33333333333333e+01 1.11320740260652e+00 2.49429300830395e-01 -1.72914291335786e-01 + 2.39393939393939e+01 1.10436503501225e+00 2.60651212249636e-01 -1.79425078294699e-01 + 2.45454545454545e+01 1.09671055899213e+00 2.72273742523902e-01 -1.85035919192311e-01 + 2.51515151515151e+01 1.08918806808547e+00 2.83940785046750e-01 -1.90542124148107e-01 + 2.57575757575758e+01 1.08166557717880e+00 2.95607827569598e-01 -1.96042910921405e-01 + 2.63636363636364e+01 1.07497654178085e+00 3.07666550963613e-01 -2.01108325476125e-01 + 2.69696969696970e+01 1.06884322973428e+00 3.19986435516351e-01 -2.05883282560142e-01 + 2.75757575757576e+01 1.06270991768772e+00 3.32306320069088e-01 -2.10654825089128e-01 + 2.81818181818182e+01 1.05685002491795e+00 3.44803723925826e-01 -2.15273237837376e-01 + 2.87878787878788e+01 1.05162805573452e+00 3.57715303960546e-01 -2.19539750840593e-01 + 2.93939393939394e+01 1.04640608655109e+00 3.70626883995265e-01 -2.23804015238057e-01 + 3.00000000000000e+01 1.04118411736767e+00 3.83538464029985e-01 -2.28066012025690e-01 + 3.30000000000000e+01 1.01848589840269e+00 4.50834279245390e-01 -2.46961206869889e-01 + 3.60000000000000e+01 9.96808909621796e-01 5.20958260992169e-01 -2.64359434793424e-01 + 3.90000000000000e+01 9.74106328942832e-01 5.93758161928647e-01 -2.80547282143363e-01 + 4.20000000000000e+01 9.48041157048807e-01 6.68214525810192e-01 -2.95913378121082e-01 + 4.50000000000000e+01 9.20743807181201e-01 7.43083281614397e-01 -3.11045980331182e-01 + 4.80000000000000e+01 8.86477884798320e-01 8.17875803160575e-01 -3.25477187585035e-01 + 5.10000000000000e+01 8.48118712495052e-01 8.91114285364008e-01 -3.39620328980538e-01 + 5.40000000000000e+01 8.01572777205266e-01 9.61244588976293e-01 -3.53193383869185e-01 + 5.70000000000000e+01 7.55026776527843e-01 1.03137413224544e+00 -3.66763595394112e-01 + 6.00000000000000e+01 7.08480743156850e-01 1.10150329534591e+00 -3.80331070227688e-01 + 6.30000000000000e+01 6.46295216458993e-01 1.15838046907205e+00 -3.92574049260776e-01 + 6.60000000000000e+01 5.84109443410254e-01 1.21525752920760e+00 -4.04815652134246e-01 + 6.90000000000000e+01 5.21923445770576e-01 1.27213458934316e+00 -4.17055794570706e-01 + 7.20000000000000e+01 4.52335480264868e-01 1.31553653901342e+00 -4.28053298659701e-01 + 7.50000000000000e+01 3.79046682354287e-01 1.35220120930450e+00 -4.38429394598601e-01 + 7.80000000000000e+01 3.05756781496138e-01 1.38886629974350e+00 -4.48804321680909e-01 + 8.10000000000000e+01 2.31207286740326e-01 1.41728453792232e+00 -4.58322686478495e-01 + 8.40000000000000e+01 1.54138691138483e-01 1.42920964084012e+00 -4.66128863644011e-01 + 8.70000000000000e+01 7.70693031576111e-02 1.44113483485913e+00 -4.73934397736458e-01 + 9.00000000000000e+01 -3.36708373039042e-07 1.45305992557158e+00 -4.81739438540332e-01 + 9.30000000000000e+01 -5.39485757284989e-02 1.44113482265378e+00 -4.85914001849487e-01 + 9.60000000000000e+01 -1.07896933109837e-01 1.42920967418575e+00 -4.89748119107250e-01 + 9.90000000000000e+01 -1.61845527217882e-01 1.41728443461560e+00 -4.93557987335880e-01 + 1.02000000000000e+02 -2.14030046275947e-01 1.38886612216712e+00 -4.94077965350438e-01 + 1.05000000000000e+02 -2.65332546911451e-01 1.35220145187604e+00 -4.92944920029321e-01 + 1.08000000000000e+02 -3.16635035430310e-01 1.31553636143885e+00 -4.92245915161826e-01 + 1.11000000000000e+02 -3.65346571871470e-01 1.27213409662221e+00 -4.90545503515274e-01 + 1.14000000000000e+02 -4.08876283070132e-01 1.21525768824574e+00 -4.86317993590270e-01 + 1.17000000000000e+02 -4.52406347782145e-01 1.15838084536770e+00 -4.82090051371639e-01 + 1.20000000000000e+02 -4.95936567846409e-01 1.10150375931678e+00 -4.77861889492743e-01 + 1.23000000000000e+02 -5.28518625044671e-01 1.03137459621631e+00 -4.71840511315534e-01 + 1.26000000000000e+02 -5.61100704888174e-01 9.61245052954708e-01 -4.65818976558725e-01 + 1.29000000000000e+02 -5.93682830023854e-01 8.91114749342422e-01 -4.59682348306178e-01 + 1.32000000000000e+02 -6.18908433527060e-01 8.17850698969113e-01 -4.54312399338742e-01 + 1.35000000000000e+02 -6.40455784934676e-01 7.43019778936259e-01 -4.49364062058548e-01 + 1.38000000000000e+02 -6.62002920890116e-01 6.68189421819664e-01 -4.44415444601716e-01 + 1.41000000000000e+02 -6.81613839477788e-01 5.94826066587770e-01 -4.41694691787043e-01 + 1.44000000000000e+02 -6.97352307618548e-01 5.24396727029221e-01 -4.43429686334623e-01 + 1.47000000000000e+02 -7.13090480114408e-01 4.53967729130364e-01 -4.45164688600493e-01 + 1.50000000000000e+02 -7.28828504793094e-01 3.83538902055256e-01 -4.46899694725369e-01 + 1.53000000000000e+02 -7.38250770119389e-01 3.28279710588330e-01 -4.64997809025810e-01 + 1.56000000000000e+02 -7.46093272753856e-01 2.73020555057756e-01 -4.81308204600343e-01 + 1.59000000000000e+02 -7.53707623020192e-01 2.17761400703393e-01 -5.00902986460923e-01 + 1.62000000000000e+02 -6.88143441383303e-01 1.78536848703957e-01 -5.06252966573203e-01 + 1.65000000000000e+02 -5.85650053883360e-01 1.47329733490110e-01 -5.03908411641623e-01 + 1.68000000000000e+02 -4.83157240864670e-01 1.16122375886185e-01 -5.01563371955391e-01 + 1.71000000000000e+02 -3.73345827031091e-01 8.57857267499245e-02 -4.50000513056908e-01 + 1.74000000000000e+02 -2.48896869884329e-01 5.71905351997449e-02 -2.99999717902353e-01 + 1.77000000000000e+02 -1.23881031171309e-01 4.71151394500337e-02 -1.04090643424068e-01 + 1.80000000000000e+02 0.00000000000000e+00 4.63087218239101e-02 1.12294918356446e-01 diff --git a/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_24.dat b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_24.dat new file mode 100644 index 00000000..59306058 --- /dev/null +++ b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_24.dat @@ -0,0 +1,254 @@ +! ------------ AirfoilInfo v1.01.x Input File ---------------------------------- +! AeroElasticSE FAST driver +! line +! line +! ------------------------------------------------------------------------------ +DEFAULT InterpOrd ! Interpolation order to use for quasi-steady table lookup {1=linear; 3=cubic spline; "default"} [default=3] +1 NonDimArea ! The non-dimensional area of the airfoil (area/chord^2) (set to 1.0 if unsure or unneeded) +@"NREL-2p8-127_AF24_Coords.txt" NumCoords ! The number of coordinates in the airfoil shape file. Set to zero if coordinates not included. +AF24_BL.txt BL_file ! The file name including the boundary layer characteristics of the profile. Ignored if the aeroacoustic module is not called. +1 NumTabs ! Number of airfoil tables in this file. Each table must have lines for Re and Ctrl. +! ------------------------------------------------------------------------------ +! data for table 1 +! ------------------------------------------------------------------------------ +6.000000 Re ! Reynolds number in millions +0 Ctrl ! Control setting (must be 0 for current AirfoilInfo) +True InclUAdata ! Is unsteady aerodynamics data included in this table? If TRUE, then include 30 UA coefficients below this line +!........................................ +-3.881348 alpha0 ! 0-lift angle of attack, depends on airfoil. +10.220205 alpha1 ! Angle of attack at f=0.7, (approximately the stall angle) for AOA>alpha0. (deg) +-10.228661 alpha2 ! Angle of attack at f=0.7, (approximately the stall angle) for AOA1] +0.000000 S2 ! Constant in the f curve best-fit for AOA> alpha1; by definition it depends on the airfoil. [ignored if UAMod<>1] +0.000000 S3 ! Constant in the f curve best-fit for alpha2<=AOA< alpha0; by definition it depends on the airfoil. [ignored if UAMod<>1] +0.000000 S4 ! Constant in the f curve best-fit for AOA< alpha2; by definition it depends on the airfoil. [ignored if UAMod<>1] +1.447089 Cn1 ! Critical value of C0n at leading edge separation. It should be extracted from airfoil data at a given Mach and Reynolds number. It can be calculated from the static value of Cn at either the break in the pitching moment or the loss of chord force at the onset of stall. It is close to the condition of maximum lift of the airfoil at low Mach numbers. +-0.835242 Cn2 ! As Cn1 for negative AOAs. +Default St_sh ! Strouhal's shedding frequency constant. [default = 0.19] +0.006598 Cd0 ! 2D drag coefficient value at 0-lift. +-0.113186 Cm0 ! 2D pitching moment coefficient about 1/4-chord location, at 0-lift, positive if nose up. [If the aerodynamics coefficients table does not include a column for Cm, this needs to be set to 0.0] +0.000000 k0 ! Constant in the \hat(x)_cp curve best-fit; = (\hat(x)_AC-0.25). [ignored if UAMod<>1] +0.000000 k1 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k2 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k3 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k1_hat ! Constant in the expression of Cc due to leading edge vortex effects. [ignored if UAMod<>1] +Default x_cp_bar ! Constant in the expression of \hat(x)_cp^v. [ignored if UAMod<>1, default = 0.2] +Default UACutout ! Angle of attack above which unsteady aerodynamics are disabled (deg). [Specifying the string "Default" sets UACutout to 45 degrees] +Default filtCutOff ! Cut-off frequency (-3 dB corner frequency) for low-pass filtering the AoA input to UA, as well as the 1st and 2nd derivatives (Hz) [default = 20] +!........................................ +! Table of aerodynamics coefficients +200 NumAlf ! Number of data lines in the following table +! Alpha Cl Cd Cm +! (deg) (-) (-) (-) +-1.80000000000000e+02 0.00000000000000e+00 4.20239297897650e-02 1.57138208863316e-01 +-1.77000000000000e+02 1.40632365655801e-01 4.20239297897650e-02 1.82737995898986e-01 +-1.74000000000000e+02 2.82553053900608e-01 5.04286683283111e-02 2.39999774321882e-01 +-1.71000000000000e+02 4.23830336360153e-01 7.56431598642469e-02 3.60000410445527e-01 +-1.68000000000000e+02 5.34869114486967e-01 1.04245693608263e-01 3.04280258541825e-01 +-1.65000000000000e+02 6.30788993375323e-01 1.34542208912873e-01 1.60701763545007e-01 +-1.62000000000000e+02 7.26709994336859e-01 1.64838896980479e-01 1.71214488498863e-02 +-1.59000000000000e+02 7.84071397760670e-01 2.04002209021424e-01 -7.41764661492530e-02 +-1.56000000000000e+02 7.64500626823811e-01 2.60898469061760e-01 -6.11103531608993e-02 +-1.53000000000000e+02 7.44806596412559e-01 3.17794763757350e-01 -4.80087218730144e-02 +-1.50000000000000e+02 7.24801607355001e-01 3.74691108028256e-01 -3.36803071761103e-02 +-1.47000000000000e+02 7.09536340567078e-01 4.45426278146463e-01 -1.81789006503532e-02 +-1.44000000000000e+02 6.94270972610212e-01 5.16161667949901e-01 -2.67735864084869e-03 +-1.41000000000000e+02 6.79005402308234e-01 5.86897497139490e-01 1.25267866649444e-02 +-1.38000000000000e+02 6.59752709771772e-01 6.60614800800240e-01 2.78426345762092e-02 +-1.35000000000000e+02 6.38506464206380e-01 7.35822835648326e-01 4.32768039375504e-02 +-1.32000000000000e+02 6.17259998089925e-01 8.11031580816670e-01 5.87121989579576e-02 +-1.29000000000000e+02 5.92302309505059e-01 8.84693447887175e-01 7.43012013825991e-02 +-1.26000000000000e+02 5.59922158385802e-01 9.55261551412121e-01 9.01959583834699e-02 +-1.23000000000000e+02 5.27541955630656e-01 1.02582880155467e+00 1.06091386661389e-01 +-1.20000000000000e+02 4.95161727058530e-01 1.09639562502197e+00 1.21987354023941e-01 +-1.17000000000000e+02 4.51763647235390e-01 1.15375704715292e+00 1.37121497118599e-01 +-1.14000000000000e+02 4.08365719274480e-01 1.21111822435222e+00 1.52255604498479e-01 +-1.11000000000000e+02 3.64968138119650e-01 1.26847896334996e+00 1.67389419062474e-01 +-1.08000000000000e+02 3.16351063621799e-01 1.31238637614246e+00 1.80934520183943e-01 +-1.05000000000000e+02 2.65124202709162e-01 1.34956702339128e+00 1.93694959616565e-01 +-1.02000000000000e+02 2.13897328813262e-01 1.38674724458622e+00 2.06454767299050e-01 +-9.90000000000000e+01 1.61771435376163e-01 1.41568677594618e+00 2.17866871578471e-01 +-9.60000000000000e+01 1.07847463915400e-01 1.42814457068853e+00 2.26583332591711e-01 +-9.30000000000000e+01 5.39238186798111e-02 1.44060227026035e+00 2.35299390910874e-01 +-9.00000000000000e+01 3.36553857038623e-07 1.45305992224777e+00 2.44015288398801e-01 +-8.70000000000000e+01 -5.39237634891041e-02 1.44060228301076e+00 2.47951662237116e-01 +-8.40000000000000e+01 -1.07847614698837e-01 1.42814453585376e+00 2.51892083934148e-01 +-8.10000000000000e+01 -1.61770968240210e-01 1.41568688386634e+00 2.55836458741642e-01 +-7.80000000000000e+01 -2.13897080708414e-01 1.38674742465954e+00 2.56509498151152e-01 +-7.50000000000000e+01 -2.65124541622777e-01 1.34956677740889e+00 2.55548599134485e-01 +-7.20000000000000e+01 -3.16350815522372e-01 1.31238655621395e+00 2.54590706463430e-01 +-6.90000000000000e+01 -3.64967762165930e-01 1.26847946026667e+00 2.52383955015723e-01 +-6.60000000000000e+01 -4.08365840623045e-01 1.21111806395980e+00 2.47675595024712e-01 +-6.30000000000000e+01 -4.51763934354955e-01 1.15375666765293e+00 2.42970286422080e-01 +-6.00000000000000e+01 -4.95161941284426e-01 1.09639515815556e+00 2.38268000115941e-01 +-5.70000000000000e+01 -5.27542169856552e-01 1.02582833468826e+00 2.31806506435537e-01 +-5.40000000000000e+01 -5.59922372611185e-01 9.55261084537245e-01 2.25347767167551e-01 +-5.10000000000000e+01 -5.92302523730443e-01 8.84692981012299e-01 2.18891521602934e-01 +-4.80000000000000e+01 -6.18906352581358e-01 8.11045812993734e-01 2.12734135842278e-01 +-4.50000000000000e+01 -6.42622113131780e-01 7.35859162213287e-01 2.06728126759377e-01 +-4.20000000000000e+01 -6.61399051379004e-01 6.60629032861292e-01 2.02335706314512e-01 +-3.90000000000000e+01 -6.79295197663792e-01 5.85819587866301e-01 1.98564860746646e-01 +-3.60000000000000e+01 -6.94777748193317e-01 5.12692903825368e-01 1.97017430019138e-01 +-3.30000000000000e+01 -7.09467742340985e-01 4.42267305815927e-01 1.98629231822253e-01 +-3.00000000000000e+01 -7.24801717703120e-01 3.74690668178350e-01 2.03759075670758e-01 +-2.93939393939394e+01 -7.28326530814462e-01 3.61726727869206e-01 2.05744738406902e-01 +-2.87878787878788e+01 -7.31851343925804e-01 3.48762787560061e-01 2.07730401143047e-01 +-2.81818181818182e+01 -7.35376157037146e-01 3.35798847250917e-01 2.09716063879191e-01 +-2.75757575757576e+01 -7.39335418161425e-01 3.23251387701133e-01 2.12376937449998e-01 +-2.69696969696970e+01 -7.43480887264291e-01 3.10882435217812e-01 2.15327211917801e-01 +-2.63636363636364e+01 -7.47626356367156e-01 2.98513482734492e-01 2.18277486385603e-01 +-2.57575757575758e+01 -7.52151842029857e-01 2.86407040228379e-01 2.21732543995886e-01 +-2.51515151515151e+01 -7.57247263964635e-01 2.74694301506801e-01 2.25944658673781e-01 +-2.45454545454545e+01 -7.62342685899414e-01 2.62981562785224e-01 2.30156773351676e-01 +-2.39393939393939e+01 -7.67618823549025e-01 2.51338309217338e-01 2.34224184613365e-01 +-2.33333333333333e+01 -7.74521437619550e-01 2.40320435485340e-01 2.36989237113918e-01 +-2.27272727272727e+01 -7.81424051690076e-01 2.29302561753342e-01 2.39601565570627e-01 +-2.21212121212121e+01 -7.88326665760601e-01 2.18284688021344e-01 2.42470674291164e-01 +-2.15151515151515e+01 -7.95622047703425e-01 2.07577437194191e-01 2.45095428001552e-01 +-2.09090909090909e+01 -8.02604681726082e-01 1.96947862073894e-01 2.47624260079401e-01 +-2.03030303030303e+01 -8.09650349475145e-01 1.86318286953598e-01 2.50153092157250e-01 +-1.96969696969697e+01 -8.17637506447164e-01 1.75928434913981e-01 2.53560038839616e-01 +-1.90909090909091e+01 -8.26477015311138e-01 1.65778292393816e-01 2.57845050451215e-01 +-1.84848484848485e+01 -8.26084809962742e-01 1.55849503459699e-01 2.52897003259897e-01 +-1.78787878787879e+01 -8.23983493243247e-01 1.46076930679257e-01 2.45664651306383e-01 +-1.72727272727273e+01 -8.21570138202451e-01 1.37130650088349e-01 2.35566574130545e-01 +-1.66666666666667e+01 -8.12443964880370e-01 1.28220565266013e-01 2.18667326209765e-01 +-1.60606060606061e+01 -7.97844348659724e-01 1.19340921345769e-01 1.96202242311259e-01 +-1.54545454545455e+01 -7.84422413764076e-01 1.10579594948523e-01 1.73424826407758e-01 +-1.48484848484848e+01 -7.71787584327422e-01 1.01887960544163e-01 1.50473470711618e-01 +-1.42424242424242e+01 -7.61134965931686e-01 9.33387624500803e-02 1.27203383377638e-01 +-1.36363636363636e+01 -7.51019037969479e-01 8.48128124492238e-02 1.04178189645314e-01 +-1.30303030303030e+01 -7.41421130409000e-01 7.63034135314191e-02 8.11835234005733e-02 +-1.24242424242424e+01 -7.26117069582958e-01 6.77522789215004e-02 6.03315753701249e-02 +-1.18181818181818e+01 -7.09450417189115e-01 5.96236347309660e-02 4.00791186975229e-02 +-1.12121212121212e+01 -6.90082557893989e-01 5.06890203132416e-02 2.09663498148639e-02 +-1.06060606060606e+01 -6.69006785525034e-01 4.21875347068638e-02 1.31821761243166e-03 +-1.00000000000000e+01 -6.46973736816406e-01 3.40753735771777e-02 -1.86162729145852e-02 +-9.39393939393939e+00 -6.23566521153584e-01 2.66139202130595e-02 -3.84582682239768e-02 +-8.78787878787879e+00 -5.93143909692991e-01 1.97080621922025e-02 -5.81227331911647e-02 +-8.18181818181818e+00 -5.49437129950642e-01 1.36122296354314e-02 -7.73434792653389e-02 +-7.57575757575758e+00 -4.76129595933123e-01 1.04462591632936e-02 -9.01887084685705e-02 +-6.96969696969697e+00 -3.89923494054396e-01 8.96219583042148e-03 -9.89373513292037e-02 +-6.36363636363636e+00 -3.12270511910677e-01 7.65469409261513e-03 -1.02756750711562e-01 +-5.75757575757576e+00 -2.35244495718475e-01 7.20033215041447e-03 -1.06054556847806e-01 +-5.15151515151515e+00 -1.58611001142337e-01 6.92443690785538e-03 -1.08867710719892e-01 +-4.54545454545454e+00 -8.26264788487249e-02 6.71182503055839e-03 -1.11241902473054e-01 +-3.93939393939394e+00 -7.17505732470964e-03 6.60399736858371e-03 -1.13032741919541e-01 +-3.33333333333333e+00 6.77399244143484e-02 6.54568110870987e-03 -1.14632383709498e-01 +-2.72727272727273e+00 1.42670380661859e-01 6.46364824529083e-03 -1.16181617095474e-01 +-2.12121212121212e+00 2.17139817585866e-01 6.43953237954945e-03 -1.17766630428816e-01 +-1.51515151515152e+00 2.91428740135327e-01 6.42972618595009e-03 -1.19525590995757e-01 +-9.09090909090912e-01 3.65128859297927e-01 6.42967209033216e-03 -1.21282061863669e-01 +-3.03030303030302e-01 4.38105121735726e-01 6.47736400956553e-03 -1.22890854235333e-01 + 3.03030303030302e-01 5.11112071056141e-01 6.53139868052610e-03 -1.24460808318302e-01 + 9.09090909090912e-01 5.84048322897008e-01 6.52730920651946e-03 -1.25889751980391e-01 + 1.51515151515152e+00 6.56771187401434e-01 6.60828592671719e-03 -1.27205103311759e-01 + 2.12121212121212e+00 7.29431355319300e-01 6.66584266708599e-03 -1.28498098736987e-01 + 2.72727272727273e+00 8.01715099938977e-01 6.79410605892685e-03 -1.29703511469116e-01 + 3.33333333333333e+00 8.73667737101458e-01 6.92003913189438e-03 -1.30770162129486e-01 + 3.93939393939394e+00 9.45203779381055e-01 7.04950954145510e-03 -1.31831672743512e-01 + 4.54545454545455e+00 1.01616262246952e+00 7.18868096099871e-03 -1.32686207865223e-01 + 5.15151515151515e+00 1.08666504585964e+00 7.35805565558534e-03 -1.33484479795433e-01 + 5.75757575757576e+00 1.15589713891403e+00 7.65596176371924e-03 -1.34065604697579e-01 + 6.36363636363637e+00 1.22235143346160e+00 8.13782849850763e-03 -1.34188428144082e-01 + 6.96969696969697e+00 1.28381732514628e+00 9.00700508163636e-03 -1.33672116338428e-01 + 7.57575757575757e+00 1.33414824858160e+00 1.07028357691023e-02 -1.31358398670661e-01 + 8.18181818181818e+00 1.37921530349790e+00 1.23338548134546e-02 -1.28462440465876e-01 + 8.78787878787879e+00 1.41929596248767e+00 1.40314224567824e-02 -1.25079434784614e-01 + 9.39393939393939e+00 1.44895179840671e+00 1.73667127363230e-02 -1.22426571069460e-01 + 1.00000000000000e+01 1.46562058968523e+00 2.15076283531428e-02 -1.22080342259589e-01 + 1.06060606060606e+01 1.46482275209920e+00 2.56482444467929e-02 -1.21729653497994e-01 + 1.12121212121212e+01 1.46455008673655e+00 2.96173727205461e-02 -1.21654814919871e-01 + 1.18181818181818e+01 1.46787480330173e+00 3.84335406340759e-02 -1.21545340375698e-01 + 1.24242424242424e+01 1.44626795909455e+00 5.24745071699755e-02 -1.21745587084181e-01 + 1.30303030303030e+01 1.41548464258938e+00 6.65727041455837e-02 -1.22132303153946e-01 + 1.36363636363636e+01 1.37245053342376e+00 8.16057042391146e-02 -1.24136435674557e-01 + 1.42424242424242e+01 1.33537840735922e+00 9.41511245499718e-02 -1.25907093812210e-01 + 1.48484848484848e+01 1.30613659580939e+00 1.02967015650268e-01 -1.27351580700688e-01 + 1.54545454545455e+01 1.28553302955425e+00 1.11389370579920e-01 -1.28462528314075e-01 + 1.60606060606061e+01 1.26758424346921e+00 1.19644615010785e-01 -1.29390414755028e-01 + 1.66666666666667e+01 1.24771591748635e+00 1.27576133928679e-01 -1.29935088016977e-01 + 1.72727272727273e+01 1.22417688851766e+00 1.35896595584476e-01 -1.30758578064231e-01 + 1.78787878787879e+01 1.19608311119412e+00 1.44692436629616e-01 -1.31924607905431e-01 + 1.84848484848485e+01 1.18255480628068e+00 1.53780455374608e-01 -1.33460435656660e-01 + 1.90909090909091e+01 1.17242740863741e+00 1.63075826898732e-01 -1.35618139566060e-01 + 1.96969696969697e+01 1.16082579219221e+00 1.73132593582544e-01 -1.40776664039364e-01 + 2.03030303030303e+01 1.14904324940101e+00 1.83847599384671e-01 -1.46705689236554e-01 + 2.09090909090909e+01 1.13954137740033e+00 1.95220881544062e-01 -1.53430242057478e-01 + 2.15151515151515e+01 1.13215807394264e+00 2.06594163703453e-01 -1.60162370933814e-01 + 2.21212121212121e+01 1.12321585235273e+00 2.17919889776365e-01 -1.66781417553110e-01 + 2.27272727272727e+01 1.11431119585911e+00 2.29055440435074e-01 -1.72948251497559e-01 + 2.33333333333333e+01 1.10540653936549e+00 2.40190991093782e-01 -1.79121549823611e-01 + 2.39393939393939e+01 1.09650188287188e+00 2.51326541752491e-01 -1.85319591539483e-01 + 2.45454545454545e+01 1.08905958113101e+00 2.62981562785224e-01 -1.90662311121533e-01 + 2.51515151515151e+01 1.08177975975634e+00 2.74694301506801e-01 -1.95908674546375e-01 + 2.57575757575758e+01 1.07449993838168e+00 2.86407040228379e-01 -2.01153495137443e-01 + 2.63636363636364e+01 1.06803512793561e+00 2.98513482734492e-01 -2.05997699680956e-01 + 2.69696969696970e+01 1.06211374254334e+00 3.10882435217812e-01 -2.10574738593792e-01 + 2.75757575757576e+01 1.05619235715106e+00 3.23251387701133e-01 -2.15150805208106e-01 + 2.81818181818182e+01 1.05053677218194e+00 3.35798847250917e-01 -2.19587044062714e-01 + 2.87878787878788e+01 1.04550133499893e+00 3.48762787560062e-01 -2.23698575936724e-01 + 2.93939393939394e+01 1.04046589781592e+00 3.61726727869206e-01 -2.27809467517628e-01 + 3.00000000000000e+01 1.03543046063291e+00 3.74690668178350e-01 -2.31919713393992e-01 + 3.30000000000000e+01 1.01352784881378e+00 4.42267305815928e-01 -2.50242753909780e-01 + 3.60000000000000e+01 9.92539022396652e-01 5.12692903825368e-01 -2.67200657190209e-01 + 3.90000000000000e+01 9.70421727927888e-01 5.85819587866301e-01 -2.83055031736328e-01 + 4.20000000000000e+01 9.44855717457034e-01 6.60629032861292e-01 -2.98162017656836e-01 + 4.50000000000000e+01 9.18032014729747e-01 7.35859162213287e-01 -3.13059792814360e-01 + 4.80000000000000e+01 8.84152091109475e-01 8.11045812993735e-01 -3.27314348631916e-01 + 5.10000000000000e+01 8.46146395641528e-01 8.84692981012299e-01 -3.41300099207024e-01 + 5.40000000000000e+01 7.99888891241725e-01 9.55261084537245e-01 -3.54749948670230e-01 + 5.70000000000000e+01 7.53631324948729e-01 1.02582833468826e+00 -3.68198870181370e-01 + 6.00000000000000e+01 7.07373727709371e-01 1.09639515815556e+00 -3.81646953266444e-01 + 6.30000000000000e+01 6.45377123529131e-01 1.15375666765293e+00 -3.93810500184529e-01 + 6.60000000000000e+01 5.83380227301456e-01 1.21111806395980e+00 -4.05973624922660e-01 + 6.90000000000000e+01 5.21383016795821e-01 1.26847946026667e+00 -4.18136288721357e-01 + 7.20000000000000e+01 4.51929954630524e-01 1.31238655621395e+00 -4.29073410119878e-01 + 7.50000000000000e+01 3.78749119266611e-01 1.34956677740889e+00 -4.39397752827040e-01 + 7.80000000000000e+01 3.05567316722722e-01 1.38674742465954e+00 -4.49721404047000e-01 + 8.10000000000000e+01 2.31101650731069e-01 1.41568688386634e+00 -4.59194843301813e-01 + 8.40000000000000e+01 1.54068346468134e-01 1.42814453585376e+00 -4.66968167272936e-01 + 8.70000000000000e+01 7.70341547111549e-02 1.44060228301076e+00 -4.74741064431118e-01 + 9.00000000000000e+01 -3.36553857271529e-07 1.45305992224777e+00 -4.82513681756923e-01 + 9.30000000000000e+01 -5.39238186798111e-02 1.44060227026035e+00 -4.86445774433152e-01 + 9.60000000000000e+01 -1.07847463915400e-01 1.42814457068853e+00 -4.90136599398835e-01 + 9.90000000000000e+01 -1.61771435376163e-01 1.41568677594618e+00 -4.93816587592719e-01 + 1.02000000000000e+02 -2.13897328813262e-01 1.38674724458622e+00 -4.94219233630832e-01 + 1.05000000000000e+02 -2.65124202709163e-01 1.34956702339128e+00 -4.92980933650800e-01 + 1.08000000000000e+02 -3.16351063621799e-01 1.31238637614246e+00 -4.92020295748683e-01 + 1.11000000000000e+02 -3.64968138119650e-01 1.26847896334996e+00 -4.89968875412941e-01 + 1.14000000000000e+02 -4.08365719274481e-01 1.21111822435222e+00 -4.85404915466942e-01 + 1.17000000000000e+02 -4.51763647235390e-01 1.15375704715292e+00 -4.80840520657040e-01 + 1.20000000000000e+02 -4.95161727058530e-01 1.09639562502197e+00 -4.76275904937341e-01 + 1.23000000000000e+02 -5.27541955630656e-01 1.02582880155467e+00 -4.69936300398934e-01 + 1.26000000000000e+02 -5.59922158385802e-01 9.55261551412121e-01 -4.63596595371752e-01 + 1.29000000000000e+02 -5.92302309505059e-01 8.84693447887175e-01 -4.57173092895786e-01 + 1.32000000000000e+02 -6.17259998089925e-01 8.11031580816670e-01 -4.51522499663600e-01 + 1.35000000000000e+02 -6.38506464206380e-01 7.35822835648326e-01 -4.46286234978398e-01 + 1.38000000000000e+02 -6.59752709771772e-01 6.60614800800239e-01 -4.41049558888129e-01 + 1.41000000000000e+02 -6.79005402308234e-01 5.86897497139489e-01 -4.37992891545696e-01 + 1.44000000000000e+02 -6.94270972610212e-01 5.16161667949901e-01 -4.39296259388551e-01 + 1.47000000000000e+02 -7.09536340567078e-01 4.45426278146463e-01 -4.40599632549160e-01 + 1.50000000000000e+02 -7.24801607355002e-01 3.74691108028256e-01 -4.41903008368551e-01 + 1.53000000000000e+02 -7.42599775012969e-01 3.18083719972620e-01 -4.61912096005589e-01 + 1.56000000000000e+02 -7.59948055761679e-01 2.61476373424413e-01 -4.80619093073397e-01 + 1.59000000000000e+02 -7.77231254388352e-01 2.04869044049550e-01 -5.01430259356238e-01 + 1.62000000000000e+02 -7.14992328958953e-01 1.66181531595306e-01 -5.06906825399297e-01 + 1.65000000000000e+02 -6.12895046906355e-01 1.36454079153225e-01 -5.04317113525236e-01 + 1.68000000000000e+02 -5.10798334796026e-01 1.06726367365571e-01 -5.01726853472064e-01 + 1.71000000000000e+02 -3.98460526443325e-01 7.82171286957471e-02 -4.50000513056908e-01 + 1.74000000000000e+02 -2.65640047479978e-01 5.21448931484207e-02 -2.99999717902353e-01 + 1.77000000000000e+02 -1.32214471307849e-01 4.28782038261505e-02 -8.60306173704663e-02 + 1.80000000000000e+02 0.00000000000000e+00 4.20239297897650e-02 1.57138208863316e-01 diff --git a/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_25.dat b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_25.dat new file mode 100644 index 00000000..5afdaa9e --- /dev/null +++ b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_25.dat @@ -0,0 +1,254 @@ +! ------------ AirfoilInfo v1.01.x Input File ---------------------------------- +! AeroElasticSE FAST driver +! line +! line +! ------------------------------------------------------------------------------ +DEFAULT InterpOrd ! Interpolation order to use for quasi-steady table lookup {1=linear; 3=cubic spline; "default"} [default=3] +1 NonDimArea ! The non-dimensional area of the airfoil (area/chord^2) (set to 1.0 if unsure or unneeded) +@"NREL-2p8-127_AF25_Coords.txt" NumCoords ! The number of coordinates in the airfoil shape file. Set to zero if coordinates not included. +AF25_BL.txt BL_file ! The file name including the boundary layer characteristics of the profile. Ignored if the aeroacoustic module is not called. +1 NumTabs ! Number of airfoil tables in this file. Each table must have lines for Re and Ctrl. +! ------------------------------------------------------------------------------ +! data for table 1 +! ------------------------------------------------------------------------------ +6.000000 Re ! Reynolds number in millions +0 Ctrl ! Control setting (must be 0 for current AirfoilInfo) +True InclUAdata ! Is unsteady aerodynamics data included in this table? If TRUE, then include 30 UA coefficients below this line +!........................................ +-3.985066 alpha0 ! 0-lift angle of attack, depends on airfoil. +10.901847 alpha1 ! Angle of attack at f=0.7, (approximately the stall angle) for AOA>alpha0. (deg) +-9.933710 alpha2 ! Angle of attack at f=0.7, (approximately the stall angle) for AOA1] +0.000000 S2 ! Constant in the f curve best-fit for AOA> alpha1; by definition it depends on the airfoil. [ignored if UAMod<>1] +0.000000 S3 ! Constant in the f curve best-fit for alpha2<=AOA< alpha0; by definition it depends on the airfoil. [ignored if UAMod<>1] +0.000000 S4 ! Constant in the f curve best-fit for AOA< alpha2; by definition it depends on the airfoil. [ignored if UAMod<>1] +1.525701 Cn1 ! Critical value of C0n at leading edge separation. It should be extracted from airfoil data at a given Mach and Reynolds number. It can be calculated from the static value of Cn at either the break in the pitching moment or the loss of chord force at the onset of stall. It is close to the condition of maximum lift of the airfoil at low Mach numbers. +-0.831442 Cn2 ! As Cn1 for negative AOAs. +Default St_sh ! Strouhal's shedding frequency constant. [default = 0.19] +0.006462 Cd0 ! 2D drag coefficient value at 0-lift. +-0.113020 Cm0 ! 2D pitching moment coefficient about 1/4-chord location, at 0-lift, positive if nose up. [If the aerodynamics coefficients table does not include a column for Cm, this needs to be set to 0.0] +0.000000 k0 ! Constant in the \hat(x)_cp curve best-fit; = (\hat(x)_AC-0.25). [ignored if UAMod<>1] +0.000000 k1 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k2 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k3 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k1_hat ! Constant in the expression of Cc due to leading edge vortex effects. [ignored if UAMod<>1] +Default x_cp_bar ! Constant in the expression of \hat(x)_cp^v. [ignored if UAMod<>1, default = 0.2] +Default UACutout ! Angle of attack above which unsteady aerodynamics are disabled (deg). [Specifying the string "Default" sets UACutout to 45 degrees] +Default filtCutOff ! Cut-off frequency (-3 dB corner frequency) for low-pass filtering the AoA input to UA, as well as the 1st and 2nd derivatives (Hz) [default = 20] +!........................................ +! Table of aerodynamics coefficients +200 NumAlf ! Number of data lines in the following table +! Alpha Cl Cd Cm +! (deg) (-) (-) (-) +-1.80000000000000e+02 0.00000000000000e+00 3.88896555692602e-02 1.88439381768847e-01 +-1.77000000000000e+02 1.47085076149199e-01 3.88896555692602e-02 1.95344118058902e-01 +-1.74000000000000e+02 2.95517626324669e-01 4.66675428003909e-02 2.39999774321882e-01 +-1.71000000000000e+02 4.43277326259944e-01 7.00014598350941e-02 3.60000410445527e-01 +-1.68000000000000e+02 5.54775230424015e-01 9.73983403883863e-02 3.01232293768575e-01 +-1.65000000000000e+02 6.48142659931080e-01 1.26826655280201e-01 1.53081887186124e-01 +-1.62000000000000e+02 7.41511167200111e-01 1.56255257014288e-01 4.92973254323252e-03 +-1.59000000000000e+02 7.95540100041439e-01 1.95090056664802e-01 -8.77735264750430e-02 +-1.56000000000000e+02 7.70906453274779e-01 2.52736933946693e-01 -6.95971986266622e-02 +-1.53000000000000e+02 7.46262520842411e-01 3.10383851618106e-01 -5.14181728633164e-02 +-1.50000000000000e+02 7.21593009442639e-01 3.68030820520305e-01 -3.29558765859875e-02 +-1.47000000000000e+02 7.06704434537952e-01 4.38996595677444e-01 -1.77699153461743e-02 +-1.44000000000000e+02 6.91815791203747e-01 5.09962627721908e-01 -2.58387309352737e-03 +-1.41000000000000e+02 6.76927011005616e-01 5.80929173559367e-01 1.25078923479111e-02 +-1.38000000000000e+02 6.57959749926485e-01 6.54912916084138e-01 2.78036722103928e-02 +-1.35000000000000e+02 6.36953256680495e-01 7.30405250831853e-01 4.32213182447573e-02 +-1.32000000000000e+02 6.15946530568564e-01 8.05898408123014e-01 5.86392271290690e-02 +-1.29000000000000e+02 5.91202311709038e-01 8.79859730223254e-01 7.42120371863231e-02 +-1.26000000000000e+02 5.58983089632388e-01 9.50757374661013e-01 9.00945304458618e-02 +-1.23000000000000e+02 5.26763742046105e-01 1.02165410059611e+00 1.05977334757586e-01 +-1.20000000000000e+02 4.94544331707351e-01 1.09255036729705e+00 1.21860311283846e-01 +-1.17000000000000e+02 4.51251550031352e-01 1.15027637837716e+00 1.36984793751777e-01 +-1.14000000000000e+02 4.07958914685959e-01 1.20800214320170e+00 1.52109035307253e-01 +-1.11000000000000e+02 3.64666615300881e-01 1.26572746703947e+00 1.67232779609297e-01 +-1.08000000000000e+02 3.16124806380124e-01 1.31001514786660e+00 1.80754313543723e-01 +-1.05000000000000e+02 2.64958202719693e-01 1.34758390486677e+00 1.93478045106979e-01 +-1.02000000000000e+02 2.13791585385510e-01 1.38515223136569e+00 2.06201034298060e-01 +-9.90000000000000e+01 1.61712404778857e-01 1.41448412769015e+00 2.17579378110101e-01 +-9.60000000000000e+01 1.07808058099348e-01 1.42734280690261e+00 2.26268358308198e-01 +-9.30000000000000e+01 5.39041000974291e-02 1.44020138788200e+00 2.34956873390276e-01 +-9.00000000000000e+01 3.36430787768757e-07 1.45305991974575e+00 2.43645159242670e-01 +-8.70000000000000e+01 -5.39040449269041e-02 1.44020140104271e+00 2.47370504797659e-01 +-8.40000000000000e+01 -1.07808208827910e-01 1.42734277094688e+00 2.51096140965095e-01 +-8.10000000000000e+01 -1.61711937812911e-01 1.41448423908313e+00 2.54822075502831e-01 +-7.80000000000000e+01 -2.13791337572500e-01 1.38515241331870e+00 2.55274888244729e-01 +-7.50000000000000e+01 -2.64958541234654e-01 1.34758365631669e+00 2.54091230125327e-01 +-7.20000000000000e+01 -3.16124558572532e-01 1.31001532981777e+00 2.52907274609395e-01 +-6.90000000000000e+01 -3.64666240259218e-01 1.26572796711458e+00 2.50475282099874e-01 +-6.60000000000000e+01 -4.07959035740134e-01 1.20800198178982e+00 2.45546802529565e-01 +-6.30000000000000e+01 -4.51251836454270e-01 1.15027599646507e+00 2.40618557245280e-01 +-6.00000000000000e+01 -4.94544544869283e-01 1.09254989825106e+00 2.35690538113475e-01 +-5.70000000000000e+01 -5.26763955208036e-01 1.02165363155013e+00 2.29009342263561e-01 +-5.40000000000000e+01 -5.58983302793074e-01 9.50756905605912e-01 2.22328163344933e-01 +-5.10000000000000e+01 -5.91202524869724e-01 8.79859261168152e-01 2.15646770887959e-01 +-4.80000000000000e+01 -6.17609187893117e-01 8.05904457214662e-01 2.09254779518151e-01 +-4.50000000000000e+01 -6.41109664805937e-01 7.30421122636189e-01 2.03007644172430e-01 +-4.20000000000000e+01 -6.59622394239239e-01 6.54918965123690e-01 1.98342023604304e-01 +-3.90000000000000e+01 -6.77240098048986e-01 5.79843727554838e-01 1.94293653388780e-01 +-3.60000000000000e+01 -6.92396015978899e-01 5.06471062583234e-01 1.92463840058657e-01 +-3.30000000000000e+01 -7.06701742382219e-01 4.35818415197548e-01 1.93734767779497e-01 +-3.00000000000000e+01 -7.21593116705023e-01 3.68030379296879e-01 1.98453590087422e-01 +-2.93939393939394e+01 -7.25013851405679e-01 3.55027024133188e-01 2.00336203048920e-01 +-2.87878787878788e+01 -7.28434586106336e-01 3.42023668969498e-01 2.02218816010418e-01 +-2.81818181818182e+01 -7.31855320806992e-01 3.29020313805808e-01 2.04101428971916e-01 +-2.75757575757576e+01 -7.35700687071979e-01 3.16435173390334e-01 2.06644209454419e-01 +-2.69696969696970e+01 -7.39728053905235e-01 3.04029283243158e-01 2.09469943146406e-01 +-2.63636363636364e+01 -7.43755420738490e-01 2.91623393095983e-01 2.12295676838393e-01 +-2.57575757575758e+01 -7.48155857417494e-01 2.79481029799510e-01 2.15614520779263e-01 +-2.51515151515151e+01 -7.53115811916466e-01 2.67733895360822e-01 2.19672915167868e-01 +-2.45454545454545e+01 -7.58075766415437e-01 2.55986760922134e-01 2.23731309556473e-01 +-2.39393939393939e+01 -7.63184374708742e-01 2.44310701465517e-01 2.27866482494864e-01 +-2.33333333333333e+01 -7.69630895931130e-01 2.33274330608002e-01 2.32692677246016e-01 +-2.27272727272727e+01 -7.76077417153518e-01 2.22237959750487e-01 2.37506340633904e-01 +-2.21212121212121e+01 -7.82523938375906e-01 2.11201588892972e-01 2.42358034603878e-01 +-2.15151515151515e+01 -7.90135337461922e-01 2.00684998703353e-01 2.48462729786897e-01 +-2.09090909090909e+01 -7.98004310296648e-01 1.90298387115310e-01 2.54903342970304e-01 +-2.03030303030303e+01 -8.05878455195337e-01 1.79911775527268e-01 2.61343956153712e-01 +-1.96969696969697e+01 -8.14697917585567e-01 1.69812568423152e-01 2.68837595176999e-01 +-1.90909090909091e+01 -8.24455334435024e-01 1.60000749544382e-01 2.77384200470083e-01 +-1.84848484848485e+01 -8.23371484569383e-01 1.50522208073122e-01 2.74858417075755e-01 +-1.78787878787879e+01 -8.20283137594642e-01 1.41330694311538e-01 2.69517114356924e-01 +-1.72727272727273e+01 -8.16827722657021e-01 1.33081595034303e-01 2.60706462733926e-01 +-1.66666666666667e+01 -8.05487645465897e-01 1.24835482427222e-01 2.43743487370455e-01 +-1.60606060606061e+01 -7.87698090979399e-01 1.16591881249401e-01 2.20110391522602e-01 +-1.54545454545455e+01 -7.70279194203751e-01 1.08379515150144e-01 1.96405027014696e-01 +-1.48484848484848e+01 -7.53095337434051e-01 1.00185501796409e-01 1.72659305608295e-01 +-1.42424242424242e+01 -7.36494264951863e-01 9.20339115415058e-02 1.48824706874429e-01 +-1.36363636363636e+01 -7.20003204011376e-01 8.38888551728098e-02 1.25023839281306e-01 +-1.30303030303030e+01 -7.03596374099641e-01 7.57475802314855e-02 1.01231760751629e-01 +-1.24242424242424e+01 -6.85592076723291e-01 6.76111043119601e-02 7.80448576791677e-02 +-1.18181818181818e+01 -6.67194751585540e-01 5.96056150740760e-02 5.50235291976979e-02 +-1.12121212121212e+01 -6.48063815783503e-01 5.13317377912542e-02 3.23188744507143e-02 +-1.06060606060606e+01 -6.28468277340486e-01 4.31836623215413e-02 9.45993928821119e-03 +-1.00000000000000e+01 -6.08620538268602e-01 3.51540278791994e-02 -1.34796433221792e-02 +-9.39393939393939e+00 -5.88452257587033e-01 2.73199794208228e-02 -3.63905317831286e-02 +-8.78787878787879e+00 -5.62689873667493e-01 2.00084704728355e-02 -5.85506772245690e-02 +-8.18181818181818e+00 -5.26523769001160e-01 1.35978263788546e-02 -7.93058161363485e-02 +-7.57575757575758e+00 -4.55695305492732e-01 1.04092109922848e-02 -9.28284077848926e-02 +-6.96969696969697e+00 -3.69845487410935e-01 8.91871368739218e-03 -1.01630482628221e-01 +-6.36363636363636e+00 -2.93598733915834e-01 7.52845137064097e-03 -1.04647217860029e-01 +-5.75757575757576e+00 -2.18105319246992e-01 7.08800169590747e-03 -1.07214517170429e-01 +-5.15151515151515e+00 -1.43086395099137e-01 6.80050156749210e-03 -1.09441582594168e-01 +-4.54545454545454e+00 -6.85129984815250e-02 6.56750484797770e-03 -1.11442618030446e-01 +-3.93939393939394e+00 5.58385912432804e-03 6.45301670656877e-03 -1.13148191085356e-01 +-3.33333333333333e+00 7.94070262060676e-02 6.41289348325262e-03 -1.14695006520256e-01 +-2.72727272727273e+00 1.53241011838806e-01 6.34203948696765e-03 -1.16207049641120e-01 +-2.12121212121212e+00 2.26643908165568e-01 6.33526268400175e-03 -1.17673564802273e-01 +-1.51515151515152e+00 3.00105384199722e-01 6.33260375138770e-03 -1.19135271104034e-01 +-9.09090909090912e-01 3.73112750667490e-01 6.33272155108629e-03 -1.20666056314306e-01 +-3.03030303030302e-01 4.45821550130321e-01 6.37447853784405e-03 -1.22082515446199e-01 + 3.03030303030302e-01 5.18490342544224e-01 6.43313505799646e-03 -1.23487187085283e-01 + 9.09090909090912e-01 5.90981181373800e-01 6.43182319665414e-03 -1.24792255974836e-01 + 1.51515151515152e+00 6.63194082651710e-01 6.52639345810673e-03 -1.25965661272832e-01 + 2.12121212121212e+00 7.35342582721669e-01 6.56033089540737e-03 -1.27200682447364e-01 + 2.72727272727273e+00 8.07087488554538e-01 6.68351242329311e-03 -1.28376340413356e-01 + 3.33333333333333e+00 8.78653932202791e-01 6.80603711634661e-03 -1.29410676299065e-01 + 3.93939393939394e+00 9.49821767187520e-01 6.92963005547727e-03 -1.30468108847082e-01 + 4.54545454545455e+00 1.02040859265783e+00 7.05596856935910e-03 -1.31334420191275e-01 + 5.15151515151515e+00 1.09057426257294e+00 7.21258284329372e-03 -1.32167739152710e-01 + 5.75757575757576e+00 1.15956993076019e+00 7.50770133128459e-03 -1.32829150435812e-01 + 6.36363636363637e+00 1.22598231576016e+00 8.00921749308073e-03 -1.33054200393040e-01 + 6.96969696969697e+00 1.28698208452707e+00 8.95907167395873e-03 -1.32588516874154e-01 + 7.57575757575757e+00 1.33798080221868e+00 1.07198763892550e-02 -1.30460457192223e-01 + 8.18181818181818e+00 1.38474488602779e+00 1.24584314382430e-02 -1.27836892595172e-01 + 8.78787878787879e+00 1.43030567824273e+00 1.40331639261087e-02 -1.25090100383291e-01 + 9.39393939393939e+00 1.47200490845414e+00 1.59305690309036e-02 -1.22289478404177e-01 + 1.00000000000000e+01 1.50215101421504e+00 1.79091658579838e-02 -1.21813999638841e-01 + 1.06060606060606e+01 1.52370646388859e+00 2.02673536853439e-02 -1.21708944902389e-01 + 1.12121212121212e+01 1.54059319776331e+00 2.29572858937563e-02 -1.21848482617505e-01 + 1.18181818181818e+01 1.55195059906285e+00 3.24577496194005e-02 -1.22761051253168e-01 + 1.24242424242424e+01 1.52438898981163e+00 4.81678475665162e-02 -1.24233830041100e-01 + 1.30303030303030e+01 1.48202855383678e+00 6.38795341948320e-02 -1.25730475238576e-01 + 1.36363636363636e+01 1.42634733955077e+00 7.98865843582198e-02 -1.27696791571033e-01 + 1.42424242424242e+01 1.37740933666151e+00 9.28335727033232e-02 -1.29317173288097e-01 + 1.48484848484848e+01 1.33848755611934e+00 1.01192691262027e-01 -1.30420940714982e-01 + 1.54545454545455e+01 1.31190755280546e+00 1.09441241406769e-01 -1.31424351641477e-01 + 1.60606060606061e+01 1.28938235719693e+00 1.17642799704135e-01 -1.32380797174879e-01 + 1.66666666666667e+01 1.26634018563845e+00 1.25753041098846e-01 -1.33237196626024e-01 + 1.72727272727273e+01 1.23834102937778e+00 1.33971665700699e-01 -1.34168012171228e-01 + 1.78787878787879e+01 1.20427767029161e+00 1.42322760041168e-01 -1.35189926091386e-01 + 1.84848484848485e+01 1.18799320204888e+00 1.50716604683360e-01 -1.36311946607811e-01 + 1.90909090909091e+01 1.17586795447335e+00 1.59325448714249e-01 -1.38145765919180e-01 + 1.96969696969697e+01 1.16211889516567e+00 1.69092448832339e-01 -1.43872565373133e-01 + 2.03030303030303e+01 1.14927412966545e+00 1.79265230696872e-01 -1.50302804965374e-01 + 2.09090909090909e+01 1.13814235040425e+00 1.89843817264378e-01 -1.57438574430759e-01 + 2.15151515151515e+01 1.12766323714321e+00 2.00422403831884e-01 -1.64574965529124e-01 + 2.21212121212121e+01 1.11706175944146e+00 2.11099174825611e-01 -1.71481480893725e-01 + 2.27272727272727e+01 1.10811964282661e+00 2.22168582499681e-01 -1.77468729848466e-01 + 2.33333333333333e+01 1.09917752621176e+00 2.33237990173751e-01 -1.83456509220763e-01 + 2.39393939393939e+01 1.09023540959691e+00 2.44307397847821e-01 -1.89446318845786e-01 + 2.45454545454545e+01 1.08296339319592e+00 2.55986760922134e-01 -1.94609075142135e-01 + 2.51515151515151e+01 1.07587693949360e+00 2.67733895360822e-01 -1.99679830094226e-01 + 2.57575757575758e+01 1.06879048579128e+00 2.79481029799510e-01 -2.04750458453214e-01 + 2.63636363636364e+01 1.06250432210796e+00 2.91623393095983e-01 -2.09443081756152e-01 + 2.69696969696970e+01 1.05675176801362e+00 3.04029283243158e-01 -2.13883658690320e-01 + 2.75757575757576e+01 1.05099921391928e+00 3.16435173390334e-01 -2.18324155845132e-01 + 2.81818181818182e+01 1.04550641150444e+00 3.29020313805808e-01 -2.22633305796399e-01 + 2.87878787878788e+01 1.04061964435123e+00 3.42023668969498e-01 -2.26636130753221e-01 + 2.93939393939394e+01 1.03573287719801e+00 3.55027024133188e-01 -2.30638903172504e-01 + 3.00000000000000e+01 1.03084611004479e+00 3.68030379296879e-01 -2.34641622610226e-01 + 3.30000000000000e+01 1.00957720103222e+00 4.35818415197548e-01 -2.52554076744310e-01 + 3.60000000000000e+01 9.89136784047915e-01 5.06471062583234e-01 -2.69189950621486e-01 + 3.90000000000000e+01 9.67485857943026e-01 5.79843727554838e-01 -2.84796609339440e-01 + 4.20000000000000e+01 9.42317581833575e-01 6.54918965123690e-01 -2.99708632363911e-01 + 4.50000000000000e+01 9.15871274073578e-01 7.30421122636189e-01 -3.14427587661614e-01 + 4.80000000000000e+01 8.82298905466505e-01 8.05904457214662e-01 -3.28546217819211e-01 + 5.10000000000000e+01 8.44574853445087e-01 8.79859261168152e-01 -3.42409667613951e-01 + 5.40000000000000e+01 7.98547167692681e-01 9.50756905605912e-01 -3.55762881953981e-01 + 5.70000000000000e+01 7.52519428332893e-01 1.02165363155013e+00 -3.69115906506285e-01 + 6.00000000000000e+01 7.06491662169616e-01 1.09254989825106e+00 -3.82468805440661e-01 + 6.30000000000000e+01 6.44645585302091e-01 1.15027599646507e+00 -3.94568162072562e-01 + 6.60000000000000e+01 5.82799184406010e-01 1.20800198178982e+00 -4.06667464188502e-01 + 6.90000000000000e+01 5.20952406629315e-01 1.26572796711458e+00 -4.18766708415905e-01 + 7.20000000000000e+01 4.51606840984605e-01 1.31001532981777e+00 -4.29653737684229e-01 + 7.50000000000000e+01 3.78512034916063e-01 1.34758365631669e+00 -4.39934681615426e-01 + 7.80000000000000e+01 3.05416356557281e-01 1.38515241331870e+00 -4.50215120171697e-01 + 8.10000000000000e+01 2.31017478817704e-01 1.41448423908313e+00 -4.59650318443595e-01 + 8.40000000000000e+01 1.54012292275277e-01 1.42734277094688e+00 -4.67395115002369e-01 + 8.70000000000000e+01 7.70061458096371e-02 1.44020140104271e+00 -4.75139563653944e-01 + 9.00000000000000e+01 -3.36430788002270e-07 1.45305991974575e+00 -4.82883809780470e-01 + 9.30000000000000e+01 -5.39041000974291e-02 1.44020138788200e+00 -4.86608736540749e-01 + 9.60000000000000e+01 -1.07808058099348e-01 1.42734280690261e+00 -4.90252008054739e-01 + 9.90000000000000e+01 -1.61712404778857e-01 1.41448412769015e+00 -4.93892480524254e-01 + 1.02000000000000e+02 -2.13791585385510e-01 1.38515223136569e+00 -4.94260121211006e-01 + 1.05000000000000e+02 -2.64958202719694e-01 1.34758390486677e+00 -4.92991191870403e-01 + 1.08000000000000e+02 -3.16124806380124e-01 1.31001514786660e+00 -4.91810583583353e-01 + 1.11000000000000e+02 -3.64666615300881e-01 1.26572746703946e+00 -4.89432902349955e-01 + 1.14000000000000e+02 -4.07958914685959e-01 1.20800214320170e+00 -4.84556213718753e-01 + 1.17000000000000e+02 -4.51251550031352e-01 1.15027637837716e+00 -4.79679087834588e-01 + 1.20000000000000e+02 -4.94544331707352e-01 1.09255036729705e+00 -4.74801739879191e-01 + 1.23000000000000e+02 -5.26763742046105e-01 1.02165410059611e+00 -4.68166345460196e-01 + 1.26000000000000e+02 -5.58983089632388e-01 9.50757374661013e-01 -4.61530902688578e-01 + 1.29000000000000e+02 -5.91202311709038e-01 8.79859730223253e-01 -4.54866722642821e-01 + 1.32000000000000e+02 -6.15946530568564e-01 8.05898408123014e-01 -4.48999508288356e-01 + 1.35000000000000e+02 -6.36953256680495e-01 7.30405250831853e-01 -4.43540325890876e-01 + 1.38000000000000e+02 -6.57959749926485e-01 6.54912916084137e-01 -4.38080640740675e-01 + 1.41000000000000e+02 -6.76927011005616e-01 5.80929173559366e-01 -4.34763066576705e-01 + 1.44000000000000e+02 -6.91815791203747e-01 5.09962627721908e-01 -4.35729731767291e-01 + 1.47000000000000e+02 -7.06704434537952e-01 4.38996595677444e-01 -4.36696394806281e-01 + 1.50000000000000e+02 -7.21593009442639e-01 3.68030820520304e-01 -4.37663056769512e-01 + 1.53000000000000e+02 -7.45653551873146e-01 3.10460824874659e-01 -4.59043940512908e-01 + 1.56000000000000e+02 -7.69677114596338e-01 2.52890877728508e-01 -4.79978567205265e-01 + 1.59000000000000e+02 -7.93695164530012e-01 1.95320965150743e-01 -5.01585589518735e-01 + 1.62000000000000e+02 -7.33817088309609e-01 1.57056754662604e-01 -5.07101903167502e-01 + 1.65000000000000e+02 -6.31982311416204e-01 1.28445558491906e-01 -5.04439049525879e-01 + 1.68000000000000e+02 -5.30148101457015e-01 9.98340901844233e-02 -5.01775628100030e-01 + 1.71000000000000e+02 -4.16032857149841e-01 7.26838423842623e-02 -4.50000513056908e-01 + 1.74000000000000e+02 -2.77354970782234e-01 4.84561038187240e-02 -2.99999717902353e-01 + 1.77000000000000e+02 -1.38045242443721e-01 3.97799508651227e-02 -7.34244952105506e-02 + 1.80000000000000e+02 0.00000000000000e+00 3.88896555692602e-02 1.88439381768847e-01 diff --git a/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_26.dat b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_26.dat new file mode 100644 index 00000000..dbffc457 --- /dev/null +++ b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_26.dat @@ -0,0 +1,254 @@ +! ------------ AirfoilInfo v1.01.x Input File ---------------------------------- +! AeroElasticSE FAST driver +! line +! line +! ------------------------------------------------------------------------------ +DEFAULT InterpOrd ! Interpolation order to use for quasi-steady table lookup {1=linear; 3=cubic spline; "default"} [default=3] +1 NonDimArea ! The non-dimensional area of the airfoil (area/chord^2) (set to 1.0 if unsure or unneeded) +@"NREL-2p8-127_AF26_Coords.txt" NumCoords ! The number of coordinates in the airfoil shape file. Set to zero if coordinates not included. +AF26_BL.txt BL_file ! The file name including the boundary layer characteristics of the profile. Ignored if the aeroacoustic module is not called. +1 NumTabs ! Number of airfoil tables in this file. Each table must have lines for Re and Ctrl. +! ------------------------------------------------------------------------------ +! data for table 1 +! ------------------------------------------------------------------------------ +6.000000 Re ! Reynolds number in millions +0 Ctrl ! Control setting (must be 0 for current AirfoilInfo) +True InclUAdata ! Is unsteady aerodynamics data included in this table? If TRUE, then include 30 UA coefficients below this line +!........................................ +-4.024504 alpha0 ! 0-lift angle of attack, depends on airfoil. +11.306876 alpha1 ! Angle of attack at f=0.7, (approximately the stall angle) for AOA>alpha0. (deg) +-9.832558 alpha2 ! Angle of attack at f=0.7, (approximately the stall angle) for AOA1] +0.000000 S2 ! Constant in the f curve best-fit for AOA> alpha1; by definition it depends on the airfoil. [ignored if UAMod<>1] +0.000000 S3 ! Constant in the f curve best-fit for alpha2<=AOA< alpha0; by definition it depends on the airfoil. [ignored if UAMod<>1] +0.000000 S4 ! Constant in the f curve best-fit for AOA< alpha2; by definition it depends on the airfoil. [ignored if UAMod<>1] +1.557234 Cn1 ! Critical value of C0n at leading edge separation. It should be extracted from airfoil data at a given Mach and Reynolds number. It can be calculated from the static value of Cn at either the break in the pitching moment or the loss of chord force at the onset of stall. It is close to the condition of maximum lift of the airfoil at low Mach numbers. +-0.830241 Cn2 ! As Cn1 for negative AOAs. +Default St_sh ! Strouhal's shedding frequency constant. [default = 0.19] +0.006417 Cd0 ! 2D drag coefficient value at 0-lift. +-0.112920 Cm0 ! 2D pitching moment coefficient about 1/4-chord location, at 0-lift, positive if nose up. [If the aerodynamics coefficients table does not include a column for Cm, this needs to be set to 0.0] +0.000000 k0 ! Constant in the \hat(x)_cp curve best-fit; = (\hat(x)_AC-0.25). [ignored if UAMod<>1] +0.000000 k1 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k2 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k3 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k1_hat ! Constant in the expression of Cc due to leading edge vortex effects. [ignored if UAMod<>1] +Default x_cp_bar ! Constant in the expression of \hat(x)_cp^v. [ignored if UAMod<>1, default = 0.2] +Default UACutout ! Angle of attack above which unsteady aerodynamics are disabled (deg). [Specifying the string "Default" sets UACutout to 45 degrees] +Default filtCutOff ! Cut-off frequency (-3 dB corner frequency) for low-pass filtering the AoA input to UA, as well as the 1st and 2nd derivatives (Hz) [default = 20] +!........................................ +! Table of aerodynamics coefficients +200 NumAlf ! Number of data lines in the following table +! Alpha Cl Cd Cm +! (deg) (-) (-) (-) +-1.80000000000000e+02 0.00000000000000e+00 3.76960235595695e-02 1.99999773877240e-01 +-1.77000000000000e+02 1.49471735352601e-01 3.76960235595695e-02 1.99999908932130e-01 +-1.74000000000000e+02 3.00312823771888e-01 4.52351857356452e-02 2.39999774321882e-01 +-1.71000000000000e+02 4.50470172837611e-01 6.78529197680463e-02 3.60000410445527e-01 +-1.68000000000000e+02 5.62141155839517e-01 9.47828831363562e-02 3.00100260054970e-01 +-1.65000000000000e+02 6.54569405002126e-01 1.23868910842549e-01 1.50251816114612e-01 +-1.62000000000000e+02 7.46998713314856e-01 1.52955271849131e-01 4.01655036174478e-04 +-1.59000000000000e+02 7.99786871669241e-01 1.91656566827607e-01 -9.28122671239639e-02 +-1.56000000000000e+02 7.73294071101042e-01 2.49587404486670e-01 -7.27556273551054e-02 +-1.53000000000000e+02 7.46801068143765e-01 3.07518284704543e-01 -5.26992343631414e-02 +-1.50000000000000e+02 7.20307991381284e-01 3.65449216784473e-01 -3.26429713183966e-02 +-1.47000000000000e+02 7.05570279118452e-01 4.36504377442686e-01 -1.75932612156202e-02 +-1.44000000000000e+02 6.90832510562523e-01 5.07559809506317e-01 -2.54349362777964e-03 +-1.41000000000000e+02 6.76094629416376e-01 5.78615784400165e-01 1.25063869759018e-02 +-1.38000000000000e+02 6.57241681367617e-01 6.52702801625277e-01 2.78005506087723e-02 +-1.35000000000000e+02 6.36331208215415e-01 7.28305333867222e-01 4.32168556727977e-02 +-1.32000000000000e+02 6.15420495447980e-01 8.03908732446007e-01 5.86333373939491e-02 +-1.29000000000000e+02 5.90761768946044e-01 8.77986125240427e-01 7.42048196933668e-02 +-1.26000000000000e+02 5.58606997203396e-01 9.49011499212308e-01 9.00863038811510e-02 +-1.23000000000000e+02 5.26452071104699e-01 1.02003593058481e+00 1.05968066745090e-01 +-1.20000000000000e+02 4.94297067830864e-01 1.09105989067524e+00 1.21849968941896e-01 +-1.17000000000000e+02 4.51046459413193e-01 1.14892722035528e+00 1.36973650595313e-01 +-1.14000000000000e+02 4.07795994504977e-01 1.20679430326659e+00 1.52097072994041e-01 +-1.11000000000000e+02 3.64545860001903e-01 1.26466094411154e+00 1.67219979864857e-01 +-1.08000000000000e+02 3.16034194150131e-01 1.30909602388533e+00 1.80733002070115e-01 +-1.05000000000000e+02 2.64891722560637e-01 1.34681522084817e+00 1.93441069750703e-01 +-1.02000000000000e+02 2.13749237020859e-01 1.38453398558587e+00 2.06148391816051e-01 +-9.90000000000000e+01 1.61688764627702e-01 1.41401796960994e+00 2.17512374667702e-01 +-9.60000000000000e+01 1.07792278764948e-01 1.42703203551508e+00 2.26189620904871e-01 +-9.30000000000000e+01 5.38962046405121e-02 1.44004600200010e+00 2.34866400852709e-01 +-9.00000000000000e+01 3.36381509980986e-07 1.45305991877594e+00 2.43542947660101e-01 +-8.70000000000000e+01 -5.38961494780680e-02 1.44004601531985e+00 2.47180800161873e-01 +-8.40000000000000e+01 -1.07792429471529e-01 1.42703199912486e+00 2.50818607319856e-01 +-8.10000000000000e+01 -1.61688297729853e-01 1.41401808234901e+00 2.54456386687213e-01 +-7.80000000000000e+01 -2.13748989324725e-01 1.38453416826749e+00 2.54821414135407e-01 +-7.50000000000000e+01 -2.64892060915943e-01 1.34681497130280e+00 2.53550009143848e-01 +-7.20000000000000e+01 -3.16033946459415e-01 1.30909620656510e+00 2.52278018725637e-01 +-6.90000000000000e+01 -3.64545485325515e-01 1.26466144541088e+00 2.49759250841147e-01 +-6.60000000000000e+01 -4.07796115441250e-01 1.20679414145955e+00 2.44746825927138e-01 +-6.30000000000000e+01 -4.51046745557096e-01 1.14892683750823e+00 2.39734401012678e-01 +-6.00000000000000e+01 -4.94297280566681e-01 1.09105942078444e+00 2.34721961096712e-01 +-5.70000000000000e+01 -5.26452283840516e-01 1.02003546069401e+00 2.27959404332693e-01 +-5.40000000000000e+01 -5.58607209937681e-01 9.49011029312154e-01 2.21196621737505e-01 +-5.10000000000000e+01 -5.90761981680330e-01 8.77985655340273e-01 2.14433387476536e-01 +-4.80000000000000e+01 -6.17089681519895e-01 8.03911609903610e-01 2.07957006233653e-01 +-4.50000000000000e+01 -6.40503939057214e-01 7.28313277731023e-01 2.01624046889681e-01 +-4.20000000000000e+01 -6.58910854376636e-01 6.52705679055557e-01 1.96862418589880e-01 +-3.90000000000000e+01 -6.76417043986716e-01 5.77527415759156e-01 1.92714525781683e-01 +-3.60000000000000e+01 -6.91442145788392e-01 5.04059407890188e-01 1.90773036499847e-01 +-3.30000000000000e+01 -7.05593980685524e-01 4.33318752640849e-01 1.91909028051921e-01 +-3.00000000000000e+01 -7.20308097407842e-01 3.65448775028654e-01 1.96465078139101e-01 +-2.93939393939394e+01 -7.23687148982083e-01 3.52430142214952e-01 1.98306875240709e-01 +-2.87878787878788e+01 -7.27066200556324e-01 3.39411509401249e-01 2.00148672342317e-01 +-2.81818181818182e+01 -7.30445252130566e-01 3.26392876587547e-01 2.01990469443925e-01 +-2.75757575757576e+01 -7.34245004132877e-01 3.13793130446363e-01 2.04486479544941e-01 +-2.69696969696970e+01 -7.38225071786241e-01 3.01372922565738e-01 2.07262890698687e-01 +-2.63636363636364e+01 -7.42205139439605e-01 2.88952714685113e-01 2.10039301852433e-01 +-2.57575757575758e+01 -7.46555494689374e-01 2.76796428164473e-01 2.13304205864706e-01 +-2.51515151515151e+01 -7.51461195033535e-01 2.65035962173593e-01 2.17301735315320e-01 +-2.45454545454545e+01 -7.56366895377697e-01 2.53275496182714e-01 2.21299264765933e-01 +-2.39393939393939e+01 -7.61408712929841e-01 2.41586724908869e-01 2.25459999520073e-01 +-2.33333333333333e+01 -7.67675611706775e-01 2.30543219968779e-01 2.31089613603274e-01 +-2.27272727272727e+01 -7.73942510483708e-01 2.19499715028689e-01 2.36719227686470e-01 +-2.21212121212121e+01 -7.80209409260641e-01 2.08456210088599e-01 2.42348842244097e-01 +-2.15151515151515e+01 -7.88045843131190e-01 1.98028913518013e-01 2.49772937268922e-01 +-2.09090909090909e+01 -7.96274761734597e-01 1.87755708677063e-01 2.57645768551195e-01 +-2.03030303030303e+01 -8.04503680338007e-01 1.77482503836112e-01 2.65518599833468e-01 +-1.96969696969697e+01 -8.13721581766036e-01 1.67514312390042e-01 2.74509055953088e-01 +-1.90909090909091e+01 -8.23928410071538e-01 1.57851117084127e-01 2.84617073685583e-01 +-1.84848484848485e+01 -8.22646776262130e-01 1.48546940538688e-01 2.82973389715262e-01 +-1.78787878787879e+01 -8.19241192016627e-01 1.39555178352410e-01 2.78335523489406e-01 +-1.72727272727273e+01 -8.15446589363820e-01 1.31559887902139e-01 2.70012950129364e-01 +-1.66666666666667e+01 -8.03296483777369e-01 1.23564597452339e-01 2.53038201146750e-01 +-1.60606060606061e+01 -7.84310128533453e-01 1.15569307002924e-01 2.28984472824905e-01 +-1.54545454545455e+01 -7.65324759977866e-01 1.07574974865435e-01 2.04931438081052e-01 +-1.48484848484848e+01 -7.46339081540475e-01 9.95804834752580e-02 1.80878286802668e-01 +-1.42424242424242e+01 -7.27352144425903e-01 9.15851948410960e-02 1.56824554692099e-01 +-1.36363636363636e+01 -7.08366589041831e-01 8.35901811716822e-02 1.32771649802369e-01 +-1.30303030303030e+01 -6.89379329405081e-01 7.55946407967314e-02 1.08716220908226e-01 +-1.24242424242424e+01 -6.70394070681262e-01 6.75996503421858e-02 8.46633366461469e-02 +-1.18181818181818e+01 -6.51407025524249e-01 5.96041815994357e-02 6.06090692018439e-02 +-1.12121212121212e+01 -6.32421761536482e-01 5.16093484929349e-02 3.65561615953677e-02 +-1.06060606060606e+01 -6.13435225841655e-01 4.36139224210943e-02 1.25016108288645e-02 +-1.00000000000000e+01 -5.94449142982321e-01 3.56199339544178e-02 -1.15512079994493e-02 +-9.39393939393939e+00 -5.75463842145924e-01 2.76249494874552e-02 -3.56050262327576e-02 +-8.78787878787879e+00 -5.51403957680999e-01 2.01382266354268e-02 -5.87079502546054e-02 +-8.18181818181818e+00 -5.17926474912583e-01 1.35966762681344e-02 -8.00434679031281e-02 +-7.57575757575758e+00 -4.48013073952105e-01 1.04062079021587e-02 -9.38202181483299e-02 +-6.96969696969697e+00 -3.62306704515139e-01 8.91516259682469e-03 -1.02639355883834e-01 +-6.36363636363636e+00 -2.86592646559465e-01 7.49092009640339e-03 -1.05345389259135e-01 +-5.75757575757576e+00 -2.11681427543666e-01 7.05454354406601e-03 -1.07624248784689e-01 +-5.15151515151515e+00 -1.37278368249321e-01 6.76061495526902e-03 -1.09615083165669e-01 +-4.54545454545454e+00 -6.32446849221684e-02 6.51817990062387e-03 -1.11463657718864e-01 +-3.93939393939394e+00 1.03326039502837e-02 6.40000102450966e-03 -1.13157562089362e-01 +-3.33333333333333e+00 8.37357402666289e-02 6.36666345248257e-03 -1.14700049263230e-01 +-2.72727272727273e+00 1.57144890016423e-01 6.30000080854981e-03 -1.16209080405868e-01 +-2.12121212121212e+00 2.30132013733438e-01 6.30000067359949e-03 -1.17633366714045e-01 +-1.51515151515152e+00 3.03270133033896e-01 6.30000062134854e-03 -1.18966679175655e-01 +-9.09090909090912e-01 3.76007831012725e-01 6.30000062466049e-03 -1.20399983368341e-01 +-3.03030303030302e-01 4.48619593833060e-01 6.33939706788298e-03 -1.21733367482865e-01 + 3.03030303030302e-01 5.21162110305859e-01 6.40000063237506e-03 -1.23066648228140e-01 + 9.09090909090912e-01 5.93482962845902e-01 6.40000060506645e-03 -1.24318211551559e-01 + 1.51515151515152e+00 6.65499465508473e-01 6.50000049630823e-03 -1.25430305714767e-01 + 2.12121212121212e+00 7.37449721921112e-01 6.52424015611961e-03 -1.26642406027256e-01 + 2.72727272727273e+00 8.08982255779155e-01 6.64545608432346e-03 -1.27809109728731e-01 + 3.33333333333333e+00 8.80397540133069e-01 6.76666331848451e-03 -1.28833312226978e-01 + 3.93939393939394e+00 9.51421795343730e-01 6.88788064407856e-03 -1.29890930275742e-01 + 4.54545454545455e+00 1.02186277965824e+00 7.00909038513147e-03 -1.30763637928484e-01 + 5.15151515151515e+00 1.09189625174699e+00 7.16061521492726e-03 -1.31612160993914e-01 + 5.75757575757576e+00 1.16079950494080e+00 7.45454396592225e-03 -1.32306067865226e-01 + 6.36363636363637e+00 1.22720136736217e+00 7.96365014632842e-03 -1.32572739637886e-01 + 6.96969696969697e+00 1.28802461132675e+00 8.94546191359972e-03 -1.32130308376179e-01 + 7.57575757575757e+00 1.33932328366435e+00 1.07272367904880e-02 -1.30081875964063e-01 + 8.18181818181818e+00 1.38679182149843e+00 1.25091238234984e-02 -1.27572684159305e-01 + 8.78787878787879e+00 1.43442621343129e+00 1.40333059500536e-02 -1.25090961368079e-01 + 9.39393939393939e+00 1.48072468189907e+00 1.53666957749600e-02 -1.22230263597817e-01 + 1.00000000000000e+01 1.51619948622988e+00 1.65000203201040e-02 -1.21700002321685e-01 + 1.06060606060606e+01 1.54652613869201e+00 1.81605911900563e-02 -1.21700000182581e-01 + 1.12121212121212e+01 1.57015106631391e+00 2.03485522545774e-02 -1.21912123883377e-01 + 1.18181818181818e+01 1.58466270949876e+00 3.00903977018941e-02 -1.23218106611257e-01 + 1.24242424242424e+01 1.55439005671114e+00 4.64546703161752e-02 -1.25157568402582e-01 + 1.30303030303030e+01 1.50697011272490e+00 6.28179584205508e-02 -1.27096913764242e-01 + 1.36363636363636e+01 1.44636122440245e+00 7.91823777231142e-02 -1.29036401923583e-01 + 1.42424242424242e+01 1.39302933029550e+00 9.22728672271796e-02 -1.30587869102437e-01 + 1.48484848484848e+01 1.35060444483994e+00 1.00454826054870e-01 -1.31557584992825e-01 + 1.54545454545455e+01 1.32181783503487e+00 1.08636431096634e-01 -1.32527257164245e-01 + 1.60606060606061e+01 1.29757628829158e+00 1.16817964892734e-01 -1.33496920105626e-01 + 1.66666666666667e+01 1.27333348139179e+00 1.24999918769171e-01 -1.34466631124069e-01 + 1.72727272727273e+01 1.24363607861721e+00 1.33181874793555e-01 -1.35436343590531e-01 + 1.78787878787879e+01 1.20727187838534e+00 1.41363833443233e-01 -1.36406057826813e-01 + 1.84848484848485e+01 1.18992975180798e+00 1.49497904111867e-01 -1.37375729577547e-01 + 1.90909090909091e+01 1.17704327758037e+00 1.57851104306908e-01 -1.39089566615125e-01 + 1.96969696969697e+01 1.16246123156071e+00 1.67514298578136e-01 -1.45021783264679e-01 + 2.03030303030303e+01 1.14929279501434e+00 1.77482491349607e-01 -1.51632325921770e-01 + 2.09090909090909e+01 1.13753806488326e+00 1.87755699876179e-01 -1.58921232961736e-01 + 2.15151515151515e+01 1.12578334814572e+00 1.98028908402751e-01 -1.66210140001703e-01 + 2.21212121212121e+01 1.11458879313232e+00 2.08456208053037e-01 -1.73224589305943e-01 + 2.27272727272727e+01 1.10563435435787e+00 2.19499713649760e-01 -1.79141490064069e-01 + 2.33333333333333e+01 1.09667991558342e+00 2.30543219246483e-01 -1.85058390822194e-01 + 2.39393939393939e+01 1.08772547680897e+00 2.41586724843207e-01 -1.90975291580320e-01 + 2.45454545454545e+01 1.08052192847356e+00 2.53275496182714e-01 -1.96074563757929e-01 + 2.51515151515151e+01 1.07351291933540e+00 2.65035962173593e-01 -2.01082990269719e-01 + 2.57575757575758e+01 1.06650391019725e+00 2.76796428164473e-01 -2.06091416781509e-01 + 2.63636363636364e+01 1.06028929009176e+00 2.88952714685113e-01 -2.10729582407184e-01 + 2.69696969696970e+01 1.05460434497302e+00 3.01372922565738e-01 -2.15120869083270e-01 + 2.75757575757576e+01 1.04891939985428e+00 3.13793130446363e-01 -2.19512155759356e-01 + 2.81818181818182e+01 1.04349178876274e+00 3.26392876587547e-01 -2.23774943907361e-01 + 2.87878787878788e+01 1.03866457222799e+00 3.39411509401249e-01 -2.27737927876115e-01 + 2.93939393939394e+01 1.03383735569325e+00 3.52430142214952e-01 -2.31700911844869e-01 + 3.00000000000000e+01 1.02901013915851e+00 3.65448775028654e-01 -2.35663895813623e-01 + 3.30000000000000e+01 1.00799497239599e+00 4.33318752640849e-01 -2.53423032735973e-01 + 3.60000000000000e+01 9.87774208309456e-01 5.04059407890188e-01 -2.69936839647807e-01 + 3.90000000000000e+01 9.66310062840480e-01 5.77527415759156e-01 -2.85448460530465e-01 + 4.20000000000000e+01 9.41301077680331e-01 6.52705679055557e-01 -3.00284956735113e-01 + 4.50000000000000e+01 9.15005912938840e-01 7.28313277731023e-01 -3.14934033957096e-01 + 4.80000000000000e+01 8.81556716458514e-01 8.03911609903610e-01 -3.28999148408511e-01 + 5.10000000000000e+01 8.43945459545643e-01 8.77985655340274e-01 -3.42814120520528e-01 + 5.40000000000000e+01 7.98009814198267e-01 9.49011029312154e-01 -3.56128791872664e-01 + 5.70000000000000e+01 7.52074119773438e-01 1.02003546069401e+00 -3.69443361508008e-01 + 6.00000000000000e+01 7.06138400810069e-01 1.09105942078444e+00 -3.82757880285344e-01 + 6.30000000000000e+01 6.44352607936286e-01 1.14892683750823e+00 -3.94831155449636e-01 + 6.60000000000000e+01 5.82566479201223e-01 1.20679414145955e+00 -4.06904419974219e-01 + 6.90000000000000e+01 5.20779950464649e-01 1.26466144541088e+00 -4.18977684498238e-01 + 7.20000000000000e+01 4.51477437795751e-01 1.30909620656510e+00 -4.29844047643928e-01 + 7.50000000000000e+01 3.78417087022892e-01 1.34681497130280e+00 -4.40106984807332e-01 + 7.80000000000000e+01 3.05355899035943e-01 1.38453416826749e+00 -4.50369439573171e-01 + 8.10000000000000e+01 2.30983768185259e-01 1.41401808234901e+00 -4.59788640889162e-01 + 8.40000000000000e+01 1.53989842100278e-01 1.42703199912486e+00 -4.67521393514335e-01 + 8.70000000000000e+01 7.69949278241990e-02 1.44004601531985e+00 -4.75253805212904e-01 + 9.00000000000000e+01 -3.36381510214729e-07 1.45305991877594e+00 -4.82986020891325e-01 + 9.30000000000000e+01 -5.38962046405121e-02 1.44004600200010e+00 -4.86623800258682e-01 + 9.60000000000000e+01 -1.07792278764948e-01 1.42703203551508e+00 -4.90261391797100e-01 + 9.90000000000000e+01 -1.61688764627702e-01 1.41401796960994e+00 -4.93898611078009e-01 + 1.02000000000000e+02 -2.13749237020859e-01 1.38453398558587e+00 -4.94263399100741e-01 + 1.05000000000000e+02 -2.64891722560637e-01 1.34681522084817e+00 -4.92992006930170e-01 + 1.08000000000000e+02 -3.16034194150131e-01 1.30909602388533e+00 -4.91720002039579e-01 + 1.11000000000000e+02 -3.64545860001904e-01 1.26466094411154e+00 -4.89201398052675e-01 + 1.14000000000000e+02 -4.07795994504977e-01 1.20679430326659e+00 -4.84189631673154e-01 + 1.17000000000000e+02 -4.51046459413193e-01 1.14892722035528e+00 -4.79177427008757e-01 + 1.20000000000000e+02 -4.94297067830864e-01 1.09105989067524e+00 -4.74164999771467e-01 + 1.23000000000000e+02 -5.26452071104699e-01 1.02003593058481e+00 -4.67401844027926e-01 + 1.26000000000000e+02 -5.58606997203396e-01 9.49011499212308e-01 -4.60638662451069e-01 + 1.29000000000000e+02 -5.90761768946045e-01 8.77986125240427e-01 -4.53875428596403e-01 + 1.32000000000000e+02 -6.15420495447981e-01 8.03908732446007e-01 -4.47922999380913e-01 + 1.35000000000000e+02 -6.36331208215415e-01 7.28305333867222e-01 -4.42375971721764e-01 + 1.38000000000000e+02 -6.57241681367618e-01 6.52702801625276e-01 -4.36828407635875e-01 + 1.41000000000000e+02 -6.76094629416376e-01 5.78615784400164e-01 -4.33407828184422e-01 + 1.44000000000000e+02 -6.90832510562523e-01 5.07559809506317e-01 -4.34241235261194e-01 + 1.47000000000000e+02 -7.05570279118452e-01 4.36504377442686e-01 -4.35074635971279e-01 + 1.50000000000000e+02 -7.20307991381284e-01 3.65449216784472e-01 -4.35908033498135e-01 + 1.53000000000000e+02 -7.46801056114916e-01 3.07518286202364e-01 -4.57805090339867e-01 + 1.56000000000000e+02 -7.73294047043302e-01 2.49587407482254e-01 -4.79701903131578e-01 + 1.59000000000000e+02 -7.99786835582591e-01 1.91656571320831e-01 -5.01598162643685e-01 + 1.62000000000000e+02 -7.40790686340429e-01 1.53560875453361e-01 -5.07117800599876e-01 + 1.65000000000000e+02 -6.39049345205277e-01 1.25382917483086e-01 -5.04448986449598e-01 + 1.68000000000000e+02 -5.37308569933658e-01 9.72046824115369e-02 -5.01779602888075e-01 + 1.71000000000000e+02 -4.22533354527340e-01 7.05773220395183e-02 -4.50000513056908e-01 + 1.74000000000000e+02 -2.81688650312917e-01 4.70517834722228e-02 -2.99999717902353e-01 + 1.77000000000000e+02 -1.40202209005507e-01 3.86002803503690e-02 -6.87687043373218e-02 + 1.80000000000000e+02 0.00000000000000e+00 3.76960235595695e-02 1.99999773877240e-01 diff --git a/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_27.dat b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_27.dat new file mode 100644 index 00000000..e92595fb --- /dev/null +++ b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_27.dat @@ -0,0 +1,254 @@ +! ------------ AirfoilInfo v1.01.x Input File ---------------------------------- +! AeroElasticSE FAST driver +! line +! line +! ------------------------------------------------------------------------------ +DEFAULT InterpOrd ! Interpolation order to use for quasi-steady table lookup {1=linear; 3=cubic spline; "default"} [default=3] +1 NonDimArea ! The non-dimensional area of the airfoil (area/chord^2) (set to 1.0 if unsure or unneeded) +@"NREL-2p8-127_AF27_Coords.txt" NumCoords ! The number of coordinates in the airfoil shape file. Set to zero if coordinates not included. +AF27_BL.txt BL_file ! The file name including the boundary layer characteristics of the profile. Ignored if the aeroacoustic module is not called. +1 NumTabs ! Number of airfoil tables in this file. Each table must have lines for Re and Ctrl. +! ------------------------------------------------------------------------------ +! data for table 1 +! ------------------------------------------------------------------------------ +6.000000 Re ! Reynolds number in millions +0 Ctrl ! Control setting (must be 0 for current AirfoilInfo) +True InclUAdata ! Is unsteady aerodynamics data included in this table? If TRUE, then include 30 UA coefficients below this line +!........................................ +-4.024505 alpha0 ! 0-lift angle of attack, depends on airfoil. +11.306884 alpha1 ! Angle of attack at f=0.7, (approximately the stall angle) for AOA>alpha0. (deg) +-9.832557 alpha2 ! Angle of attack at f=0.7, (approximately the stall angle) for AOA1] +0.000000 S2 ! Constant in the f curve best-fit for AOA> alpha1; by definition it depends on the airfoil. [ignored if UAMod<>1] +0.000000 S3 ! Constant in the f curve best-fit for alpha2<=AOA< alpha0; by definition it depends on the airfoil. [ignored if UAMod<>1] +0.000000 S4 ! Constant in the f curve best-fit for AOA< alpha2; by definition it depends on the airfoil. [ignored if UAMod<>1] +1.557235 Cn1 ! Critical value of C0n at leading edge separation. It should be extracted from airfoil data at a given Mach and Reynolds number. It can be calculated from the static value of Cn at either the break in the pitching moment or the loss of chord force at the onset of stall. It is close to the condition of maximum lift of the airfoil at low Mach numbers. +-0.830241 Cn2 ! As Cn1 for negative AOAs. +Default St_sh ! Strouhal's shedding frequency constant. [default = 0.19] +0.006417 Cd0 ! 2D drag coefficient value at 0-lift. +-0.112920 Cm0 ! 2D pitching moment coefficient about 1/4-chord location, at 0-lift, positive if nose up. [If the aerodynamics coefficients table does not include a column for Cm, this needs to be set to 0.0] +0.000000 k0 ! Constant in the \hat(x)_cp curve best-fit; = (\hat(x)_AC-0.25). [ignored if UAMod<>1] +0.000000 k1 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k2 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k3 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k1_hat ! Constant in the expression of Cc due to leading edge vortex effects. [ignored if UAMod<>1] +Default x_cp_bar ! Constant in the expression of \hat(x)_cp^v. [ignored if UAMod<>1, default = 0.2] +Default UACutout ! Angle of attack above which unsteady aerodynamics are disabled (deg). [Specifying the string "Default" sets UACutout to 45 degrees] +Default filtCutOff ! Cut-off frequency (-3 dB corner frequency) for low-pass filtering the AoA input to UA, as well as the 1st and 2nd derivatives (Hz) [default = 20] +!........................................ +! Table of aerodynamics coefficients +200 NumAlf ! Number of data lines in the following table +! Alpha Cl Cd Cm +! (deg) (-) (-) (-) +-1.80000000000000e+02 0.00000000000000e+00 3.76960000000000e-02 2.00000000000000e-01 +-1.77000000000000e+02 1.49471782056503e-01 3.76960000000000e-02 2.00000000000000e-01 +-1.74000000000000e+02 3.00312917607843e-01 4.52351574641884e-02 2.39999774321882e-01 +-1.71000000000000e+02 4.50470313592540e-01 6.78528773607728e-02 3.60000410445527e-01 +-1.68000000000000e+02 5.62141300000530e-01 9.47828314689296e-02 3.00100237874998e-01 +-1.65000000000000e+02 6.54569530813285e-01 1.23868852352745e-01 1.50251760664942e-01 +-1.62000000000000e+02 7.46998820775784e-01 1.52955206537882e-01 4.01566317437541e-04 +-1.59000000000000e+02 7.99786954801670e-01 1.91656498833410e-01 -9.28123657821359e-02 +-1.56000000000000e+02 7.73294117948629e-01 2.49587342086377e-01 -7.27556892942309e-02 +-1.53000000000000e+02 7.46801078706125e-01 3.07518227898197e-01 -5.26992595835046e-02 +-1.50000000000000e+02 7.20307965658325e-01 3.65449165572087e-01 -3.26429649313102e-02 +-1.47000000000000e+02 7.05570256415403e-01 4.36504328003481e-01 -1.75932576097200e-02 +-1.44000000000000e+02 6.90832490879619e-01 5.07559761840581e-01 -2.54349280354572e-03 +-1.41000000000000e+02 6.76094612754094e-01 5.78615738508475e-01 1.25063869759013e-02 +-1.38000000000000e+02 6.57241666993606e-01 6.52702757782292e-01 2.78005506087711e-02 +-1.35000000000000e+02 6.36331195763501e-01 7.28305292210269e-01 4.32168556727960e-02 +-1.32000000000000e+02 6.15420484918018e-01 8.03908692975958e-01 5.86333373939468e-02 +-1.29000000000000e+02 5.90761760127430e-01 8.77986088072914e-01 7.42048196933640e-02 +-1.26000000000000e+02 5.58606989674918e-01 9.49011464578596e-01 9.00863038811478e-02 +-1.23000000000000e+02 5.26452064865786e-01 1.02003589848443e+00 1.05968066745086e-01 +-1.20000000000000e+02 4.94297062881228e-01 1.09105986110795e+00 1.21849968941892e-01 +-1.17000000000000e+02 4.51046455307775e-01 1.14892719359139e+00 1.36973650595308e-01 +-1.14000000000000e+02 4.07795991243718e-01 1.20679427930608e+00 1.52097072994036e-01 +-1.11000000000000e+02 3.64545857584686e-01 1.26466092295440e+00 1.67219979864852e-01 +-1.08000000000000e+02 3.16034192336304e-01 1.30909600565222e+00 1.80733001904303e-01 +-1.05000000000000e+02 2.64891721229873e-01 1.34681520559943e+00 1.93441069265733e-01 +-1.02000000000000e+02 2.13749236173153e-01 1.38453397332146e+00 2.06148391012093e-01 +-9.90000000000000e+01 1.61688764154489e-01 1.41401796036258e+00 2.17512373571396e-01 +-9.60000000000000e+01 1.07792278449096e-01 1.42703202935019e+00 2.26189619569497e-01 +-9.30000000000000e+01 5.38962044824732e-02 1.44004599891764e+00 2.34866399278379e-01 +-9.00000000000000e+01 3.36381508994621e-07 1.45305991877593e+00 2.43542945846872e-01 +-8.70000000000000e+01 -5.38961493200293e-02 1.44004601223740e+00 2.47180796579284e-01 +-8.40000000000000e+01 -1.07792429155678e-01 1.42703199295995e+00 2.50818601967904e-01 +-8.10000000000000e+01 -1.61688297256642e-01 1.41401807310167e+00 2.54456379565910e-01 +-7.80000000000000e+01 -2.13748988477021e-01 1.38453415600310e+00 2.54821405258420e-01 +-7.50000000000000e+01 -2.64892059585176e-01 1.34681495605404e+00 2.53549998518008e-01 +-7.20000000000000e+01 -3.16033944645590e-01 1.30909618833200e+00 2.52278006351131e-01 +-6.90000000000000e+01 -3.64545482908305e-01 1.26466142425377e+00 2.49759236748571e-01 +-6.60000000000000e+01 -4.07796112179989e-01 1.20679411749904e+00 2.44746810177687e-01 +-6.30000000000000e+01 -4.51046741451673e-01 1.14892681074432e+00 2.39734383606802e-01 +-6.00000000000000e+01 -4.94297275617037e-01 1.09105939121714e+00 2.34721942034639e-01 +-5.70000000000000e+01 -5.26452277601595e-01 1.02003542859361e+00 2.27959383679512e-01 +-5.40000000000000e+01 -5.58607202409195e-01 9.49010994678426e-01 2.21196599493265e-01 +-5.10000000000000e+01 -5.90761972861707e-01 8.77985618172743e-01 2.14433363641336e-01 +-4.80000000000000e+01 -6.17089671120620e-01 8.03911570370645e-01 2.07956980763680e-01 +-4.50000000000000e+01 -6.40503926932036e-01 7.28313235916803e-01 2.01624019763027e-01 +-4.20000000000000e+01 -6.58910840133311e-01 6.52705635149657e-01 1.96862389618034e-01 +-3.90000000000000e+01 -6.76417027511146e-01 5.77527369809482e-01 1.92714494884031e-01 +-3.60000000000000e+01 -6.91442126694186e-01 5.04059360049167e-01 1.90773003374389e-01 +-3.30000000000000e+01 -7.05593958510807e-01 4.33318703053973e-01 1.91908992233939e-01 +-3.00000000000000e+01 -7.20308071684859e-01 3.65448723816258e-01 1.96465039072780e-01 +-2.93939393939394e+01 -7.23687122424702e-01 3.52430090699486e-01 1.98306835359819e-01 +-2.87878787878788e+01 -7.27066173164544e-01 3.39411457582714e-01 2.00148631646857e-01 +-2.81818181818182e+01 -7.30445223904387e-01 3.26392824465942e-01 2.01990427933895e-01 +-2.75757575757576e+01 -7.34244974993610e-01 3.13793078035017e-01 2.04486437101527e-01 +-2.69696969696970e+01 -7.38225041700157e-01 3.01372869870364e-01 2.07262847270964e-01 +-2.63636363636364e+01 -7.42205108406705e-01 2.88952661705710e-01 2.10039257440401e-01 +-2.57575757575758e+01 -7.46555462653963e-01 2.76796374908870e-01 2.13304160376248e-01 +-2.51515151515151e+01 -7.51461161912085e-01 2.65035908653530e-01 2.17301688612281e-01 +-2.45454545454545e+01 -7.56366861170206e-01 2.53275442398190e-01 2.21299216848314e-01 +-2.39393939393939e+01 -7.61408677387006e-01 2.41586670872199e-01 2.25459952105595e-01 +-2.33333333333333e+01 -7.67675572584808e-01 2.30543165790786e-01 2.31089582151761e-01 +-2.27272727272727e+01 -7.73942467782610e-01 2.19499660709374e-01 2.36719212197927e-01 +-2.21212121212121e+01 -7.80209362980412e-01 2.08456155627962e-01 2.42348842244093e-01 +-2.15151515151515e+01 -7.88045801889462e-01 1.98028860914946e-01 2.49772963288095e-01 +-2.09090909090909e+01 -7.96274727686348e-01 1.87755658431417e-01 2.57645822511188e-01 +-2.03030303030303e+01 -8.04503653483233e-01 1.77482455947888e-01 2.65518681734281e-01 +-1.96969696969697e+01 -8.13721563222721e-01 1.67514267203666e-01 2.74509167058282e-01 +-1.90909090909091e+01 -8.23928400957602e-01 1.57851074944005e-01 2.84617215258648e-01 +-1.84848484848485e+01 -8.22646763588942e-01 1.48546901850923e-01 2.82973548468764e-01 +-1.78787878787879e+01 -8.19241173382965e-01 1.39555143470384e-01 2.78335696038153e-01 +-1.72727272727273e+01 -8.15446564330172e-01 1.31559857952983e-01 2.70013132308244e-01 +-1.66666666666667e+01 -8.03296442896411e-01 1.23564572435581e-01 2.53038383173389e-01 +-1.60606060606061e+01 -7.84310064075638e-01 1.15569286918180e-01 2.28984646695628e-01 +-1.54545454545455e+01 -7.65324664303493e-01 1.07574959135167e-01 2.04931605118311e-01 +-1.48484848484848e+01 -7.46338949873589e-01 9.95804717419686e-02 1.80878447733115e-01 +-1.42424242424242e+01 -7.27351964982053e-01 9.15851862245671e-02 1.56824711255353e-01 +-1.36363636363636e+01 -7.08366360011050e-01 8.35901755495681e-02 1.32771801638210e-01 +-1.30303030303030e+01 -6.89379049576426e-01 7.55946380877238e-02 1.08716367776058e-01 +-1.24242424242424e+01 -6.70393771825338e-01 6.75996503421813e-02 8.46634665540094e-02 +-1.18181818181818e+01 -6.51406715493019e-01 5.96041815994351e-02 6.06091788446317e-02 +-1.12121212121212e+01 -6.32421454753742e-01 5.16093541595814e-02 3.65562447387649e-02 +-1.06060606060606e+01 -6.13434931389144e-01 4.36139312036515e-02 1.25016705283901e-02 +-1.00000000000000e+01 -5.94448865749824e-01 3.56199434645880e-02 -1.15511700947924e-02 +-9.39393939393939e+00 -5.75463587974779e-01 2.76249557125666e-02 -3.56050107398163e-02 +-8.78787878787879e+00 -5.51403736673166e-01 2.01382292840361e-02 -5.87079533337773e-02 +-8.18181818181818e+00 -5.17926305822838e-01 1.35966762681340e-02 -8.00434824257992e-02 +-7.57575757575758e+00 -4.48012922709353e-01 1.04062079021576e-02 -9.38202376741164e-02 +-6.96969696969697e+00 -3.62306556115099e-01 8.91516259682331e-03 -1.02639375733790e-01 +-6.36363636363636e+00 -2.86592508663283e-01 7.49091941073086e-03 -1.05345402946346e-01 +-5.75757575757576e+00 -2.11681301136276e-01 7.05454293237208e-03 -1.07624256716558e-01 +-5.15151515151515e+00 -1.37278254009080e-01 6.76061420557612e-03 -1.09615086355391e-01 +-4.54545454545454e+00 -6.32445813538124e-02 6.51817895525840e-03 -1.11463657835562e-01 +-3.93939393939394e+00 1.03326972358679e-02 6.40000000000000e-03 -1.13157562089366e-01 +-3.33333333333333e+00 8.37358252318253e-02 6.36666256139732e-03 -1.14700049263232e-01 +-2.72727272727273e+00 1.57144966549608e-01 6.30000000000000e-03 -1.16209080405869e-01 +-2.12121212121212e+00 2.30132082000148e-01 6.30000000000000e-03 -1.17633365893514e-01 +-1.51515151515152e+00 3.03270194866406e-01 6.30000000000000e-03 -1.18966675734322e-01 +-9.09090909090912e-01 3.76007887483945e-01 6.30000000000000e-03 -1.20399977937206e-01 +-3.03030303030302e-01 4.48619648411214e-01 6.33939639599868e-03 -1.21733360355986e-01 + 3.03030303030302e-01 5.21162162400790e-01 6.40000000000000e-03 -1.23066639644014e-01 + 9.09090909090912e-01 5.93483011578421e-01 6.40000000000000e-03 -1.24318201875268e-01 + 1.51515151515152e+00 6.65499510346614e-01 6.50000000000000e-03 -1.25430294786980e-01 + 2.12121212121212e+00 7.37449762821818e-01 6.52423946422604e-03 -1.26642394642260e-01 + 2.72727272727273e+00 8.08982292442682e-01 6.64545535339469e-03 -1.27809098180552e-01 + 3.33333333333333e+00 8.80397573785818e-01 6.76666256139732e-03 -1.28833300491179e-01 + 3.93939393939394e+00 9.51421826139261e-01 6.88787983927956e-03 -1.29890918553516e-01 + 4.54545454545455e+00 1.02186280754731e+00 7.00908947762920e-03 -1.30763626343404e-01 + 5.15151515151515e+00 1.09189627700035e+00 7.16061420557612e-03 -1.31612149719516e-01 + 5.75757575757576e+00 1.16079952835358e+00 7.45454293237208e-03 -1.32306057243163e-01 + 6.36363636363637e+00 1.22720139059598e+00 7.96364926341358e-03 -1.32572729852683e-01 + 6.96969696969697e+00 1.28802463107430e+00 8.94546166938641e-03 -1.32130299072563e-01 + 7.57575757575757e+00 1.33932330958836e+00 1.07272369407300e-02 -1.30081868282978e-01 + 8.18181818181818e+00 1.38679186165234e+00 1.25091248425769e-02 -1.27572678796319e-01 + 8.78787878787879e+00 1.43442629439737e+00 1.40333059500537e-02 -1.25090961368079e-01 + 9.39393939393939e+00 1.48072485366775e+00 1.53666845487907e-02 -1.22230262389112e-01 + 1.00000000000000e+01 1.51619976429293e+00 1.64999922859505e-02 -1.21700000000000e-01 + 1.06060606060606e+01 1.54652659135150e+00 1.81605492792916e-02 -1.21700000000000e-01 + 1.12121212121212e+01 1.57015165312925e+00 2.03485003516014e-02 -1.21912125087900e-01 + 1.18181818181818e+01 1.58466335911404e+00 3.00903504536651e-02 -1.23218115609323e-01 + 1.24242424242424e+01 1.55439065028940e+00 4.64546360854226e-02 -1.25157586499013e-01 + 1.30303030303030e+01 1.50697060273102e+00 6.28179372626244e-02 -1.27096940712607e-01 + 1.36363636363636e+01 1.44636161651328e+00 7.91823635414146e-02 -1.29036428271575e-01 + 1.42424242424242e+01 1.39302963646758e+00 9.22728558241098e-02 -1.30587894023598e-01 + 1.48484848484848e+01 1.35060468299441e+00 1.00454811136793e-01 -1.31557607245842e-01 + 1.54545454545455e+01 1.32181803006545e+00 1.08636414852911e-01 -1.32527278797382e-01 + 1.60606060606061e+01 1.29757644961134e+00 1.16817948256172e-01 -1.33496942015546e-01 + 1.66666666666667e+01 1.27333361905524e+00 1.24999903568856e-01 -1.34466655237790e-01 + 1.72727272727273e+01 1.24363618274871e+00 1.33181858881539e-01 -1.35436368460034e-01 + 1.78787878787879e+01 1.20727193691457e+00 1.41363814194223e-01 -1.36406081682278e-01 + 1.84848484848485e+01 1.18992978938591e+00 1.49497879761678e-01 -1.37375750456550e-01 + 1.90909090909091e+01 1.17704330010331e+00 1.57851074944005e-01 -1.39089585145003e-01 + 1.96969696969697e+01 1.16246123752382e+00 1.67514267203666e-01 -1.45021805782080e-01 + 2.03030303030303e+01 1.14929279501435e+00 1.77482455947888e-01 -1.51632351934001e-01 + 2.09090909090909e+01 1.13753805254846e+00 1.87755658431417e-01 -1.58921261976074e-01 + 2.15151515151515e+01 1.12578331008257e+00 1.98028860914946e-01 -1.66210172018147e-01 + 2.21212121212121e+01 1.11458874358451e+00 2.08456155627962e-01 -1.73224623443957e-01 + 2.27272727272727e+01 1.10563430457793e+00 2.19499660709374e-01 -1.79141522802416e-01 + 2.33333333333333e+01 1.09667986557135e+00 2.30543165790786e-01 -1.85058422160874e-01 + 2.39393939393939e+01 1.08772542656477e+00 2.41586670872199e-01 -1.90975321519332e-01 + 2.45454545454545e+01 1.08052187960139e+00 2.53275442398190e-01 -1.96074592475065e-01 + 2.51515151515151e+01 1.07351287201350e+00 2.65035908653530e-01 -2.01083017784734e-01 + 2.57575757575758e+01 1.06650386442561e+00 2.76796374908870e-01 -2.06091443094404e-01 + 2.63636363636364e+01 1.06028924575223e+00 2.88952661705710e-01 -2.10729607665482e-01 + 2.69696969696970e+01 1.05460430198682e+00 3.01372869870364e-01 -2.15120893385337e-01 + 2.75757575757576e+01 1.04891935822142e+00 3.13793078035017e-01 -2.19512179105193e-01 + 2.81818181818182e+01 1.04349174843484e+00 3.26392824465942e-01 -2.23774966350859e-01 + 2.87878787878788e+01 1.03866453309221e+00 3.39411457582714e-01 -2.27737949543009e-01 + 2.93939393939394e+01 1.03383731774957e+00 3.52430090699486e-01 -2.31700932735158e-01 + 3.00000000000000e+01 1.02901010240694e+00 3.65448723816258e-01 -2.35663915927308e-01 + 3.30000000000000e+01 1.00799494072346e+00 4.33318703053973e-01 -2.53423049843193e-01 + 3.60000000000000e+01 9.87774181033947e-01 5.04059360049167e-01 -2.69936854350083e-01 + 3.90000000000000e+01 9.66310039303889e-01 5.77527369809482e-01 -2.85448473353340e-01 + 4.20000000000000e+01 9.41301057332367e-01 6.52705635149657e-01 -3.00284968060017e-01 + 4.50000000000000e+01 9.15005895616392e-01 7.28313235916803e-01 -3.14934043892456e-01 + 4.80000000000000e+01 8.81556701601667e-01 8.03911570370646e-01 -3.28999157277327e-01 + 5.10000000000000e+01 8.43945446946677e-01 8.77985618172744e-01 -3.42814128421300e-01 + 5.40000000000000e+01 7.98009803441727e-01 9.49010994678426e-01 -3.56128799002399e-01 + 5.70000000000000e+01 7.52074110859421e-01 1.02003542859361e+00 -3.69443367867275e-01 + 6.00000000000000e+01 7.06138393738624e-01 1.09105939121714e+00 -3.82757885874428e-01 + 6.30000000000000e+01 6.44352602071576e-01 1.14892681074432e+00 -3.94831160514253e-01 + 6.60000000000000e+01 5.82566474543015e-01 1.20679411749904e+00 -4.06904424514653e-01 + 6.90000000000000e+01 5.20779947012492e-01 1.26466142425377e+00 -4.18977688515053e-01 + 7.20000000000000e+01 4.51477435205418e-01 1.30909618833200e+00 -4.29844051243441e-01 + 7.50000000000000e+01 3.78417085122278e-01 1.34681495605404e+00 -4.40106988042700e-01 + 7.80000000000000e+01 3.05355897825734e-01 1.38453415600310e+00 -4.50369442444556e-01 + 8.10000000000000e+01 2.30983767510451e-01 1.41401807310167e+00 -4.59788643436343e-01 + 8.40000000000000e+01 1.53989841650875e-01 1.42703199295995e+00 -4.67521395816866e-01 + 8.70000000000000e+01 7.69949275996385e-02 1.44004601223740e+00 -4.75253807270785e-01 + 9.00000000000000e+01 -3.36381509228363e-07 1.45305991877593e+00 -4.82986022704544e-01 + 9.30000000000000e+01 -5.38962044824732e-02 1.44004599891764e+00 -4.86623800302551e-01 + 9.60000000000000e+01 -1.07792278449097e-01 1.42703202935019e+00 -4.90261391797104e-01 + 9.90000000000000e+01 -1.61688764154490e-01 1.41401796036258e+00 -4.93898611078011e-01 + 1.02000000000000e+02 -2.13749236173153e-01 1.38453397332146e+00 -4.94263399100743e-01 + 1.05000000000000e+02 -2.64891721229873e-01 1.34681520559943e+00 -4.92992006930171e-01 + 1.08000000000000e+02 -3.16034192336304e-01 1.30909600565222e+00 -4.91720000190610e-01 + 1.11000000000000e+02 -3.64545857584686e-01 1.26466092295440e+00 -4.89201393327162e-01 + 1.14000000000000e+02 -4.07795991243718e-01 1.20679427930608e+00 -4.84189624190406e-01 + 1.17000000000000e+02 -4.51046455307775e-01 1.14892719359139e+00 -4.79177416768754e-01 + 1.20000000000000e+02 -4.94297062881228e-01 1.09105986110795e+00 -4.74164986774198e-01 + 1.23000000000000e+02 -5.26452064865786e-01 1.02003589848443e+00 -4.67401828422766e-01 + 1.26000000000000e+02 -5.58606989674918e-01 9.49011464578596e-01 -4.60638644238479e-01 + 1.29000000000000e+02 -5.90761760127430e-01 8.77986088072913e-01 -4.53875408386550e-01 + 1.32000000000000e+02 -6.15420484918018e-01 8.03908692975958e-01 -4.47922977473614e-01 + 1.35000000000000e+02 -6.36331195763501e-01 7.28305292210269e-01 -4.42375948063776e-01 + 1.38000000000000e+02 -6.57241666993606e-01 6.52702757782291e-01 -4.36828382226539e-01 + 1.41000000000000e+02 -6.76094612754094e-01 5.78615738508474e-01 -4.33407800721224e-01 + 1.44000000000000e+02 -6.90832490879619e-01 5.07559761840581e-01 -4.34241205139103e-01 + 1.47000000000000e+02 -7.05570256415403e-01 4.36504328003481e-01 -4.35074603190205e-01 + 1.50000000000000e+02 -7.20307965658325e-01 3.65449165572087e-01 -4.35907998058031e-01 + 1.53000000000000e+02 -7.46801078706125e-01 3.07518227898197e-01 -4.57805065052203e-01 + 1.56000000000000e+02 -7.73294117948629e-01 2.49587342086377e-01 -4.79701897484255e-01 + 1.59000000000000e+02 -7.99786954801670e-01 1.91656498833410e-01 -5.01598162643690e-01 + 1.62000000000000e+02 -7.40790822868899e-01 1.53560806333696e-01 -5.07117800599882e-01 + 1.65000000000000e+02 -6.39049483540701e-01 1.25382856960915e-01 -5.04448986449602e-01 + 1.68000000000000e+02 -5.37308710076014e-01 9.72046304867630e-02 -5.01779602888076e-01 + 1.71000000000000e+02 -4.22533481739914e-01 7.05772804657932e-02 -4.50000513056908e-01 + 1.74000000000000e+02 -2.81688735121593e-01 4.70517557569334e-02 -2.99999717902353e-01 + 1.77000000000000e+02 -1.40202251216632e-01 3.86002570677554e-02 -6.87686132694523e-02 + 1.80000000000000e+02 0.00000000000000e+00 3.76960000000000e-02 2.00000000000000e-01 diff --git a/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_28.dat b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_28.dat new file mode 100644 index 00000000..1adeee56 --- /dev/null +++ b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_28.dat @@ -0,0 +1,254 @@ +! ------------ AirfoilInfo v1.01.x Input File ---------------------------------- +! AeroElasticSE FAST driver +! line +! line +! ------------------------------------------------------------------------------ +DEFAULT InterpOrd ! Interpolation order to use for quasi-steady table lookup {1=linear; 3=cubic spline; "default"} [default=3] +1 NonDimArea ! The non-dimensional area of the airfoil (area/chord^2) (set to 1.0 if unsure or unneeded) +@"NREL-2p8-127_AF28_Coords.txt" NumCoords ! The number of coordinates in the airfoil shape file. Set to zero if coordinates not included. +AF28_BL.txt BL_file ! The file name including the boundary layer characteristics of the profile. Ignored if the aeroacoustic module is not called. +1 NumTabs ! Number of airfoil tables in this file. Each table must have lines for Re and Ctrl. +! ------------------------------------------------------------------------------ +! data for table 1 +! ------------------------------------------------------------------------------ +6.000000 Re ! Reynolds number in millions +0 Ctrl ! Control setting (must be 0 for current AirfoilInfo) +True InclUAdata ! Is unsteady aerodynamics data included in this table? If TRUE, then include 30 UA coefficients below this line +!........................................ +-4.024505 alpha0 ! 0-lift angle of attack, depends on airfoil. +11.306884 alpha1 ! Angle of attack at f=0.7, (approximately the stall angle) for AOA>alpha0. (deg) +-9.832557 alpha2 ! Angle of attack at f=0.7, (approximately the stall angle) for AOA1] +0.000000 S2 ! Constant in the f curve best-fit for AOA> alpha1; by definition it depends on the airfoil. [ignored if UAMod<>1] +0.000000 S3 ! Constant in the f curve best-fit for alpha2<=AOA< alpha0; by definition it depends on the airfoil. [ignored if UAMod<>1] +0.000000 S4 ! Constant in the f curve best-fit for AOA< alpha2; by definition it depends on the airfoil. [ignored if UAMod<>1] +1.557235 Cn1 ! Critical value of C0n at leading edge separation. It should be extracted from airfoil data at a given Mach and Reynolds number. It can be calculated from the static value of Cn at either the break in the pitching moment or the loss of chord force at the onset of stall. It is close to the condition of maximum lift of the airfoil at low Mach numbers. +-0.830241 Cn2 ! As Cn1 for negative AOAs. +Default St_sh ! Strouhal's shedding frequency constant. [default = 0.19] +0.006417 Cd0 ! 2D drag coefficient value at 0-lift. +-0.112920 Cm0 ! 2D pitching moment coefficient about 1/4-chord location, at 0-lift, positive if nose up. [If the aerodynamics coefficients table does not include a column for Cm, this needs to be set to 0.0] +0.000000 k0 ! Constant in the \hat(x)_cp curve best-fit; = (\hat(x)_AC-0.25). [ignored if UAMod<>1] +0.000000 k1 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k2 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k3 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k1_hat ! Constant in the expression of Cc due to leading edge vortex effects. [ignored if UAMod<>1] +Default x_cp_bar ! Constant in the expression of \hat(x)_cp^v. [ignored if UAMod<>1, default = 0.2] +Default UACutout ! Angle of attack above which unsteady aerodynamics are disabled (deg). [Specifying the string "Default" sets UACutout to 45 degrees] +Default filtCutOff ! Cut-off frequency (-3 dB corner frequency) for low-pass filtering the AoA input to UA, as well as the 1st and 2nd derivatives (Hz) [default = 20] +!........................................ +! Table of aerodynamics coefficients +200 NumAlf ! Number of data lines in the following table +! Alpha Cl Cd Cm +! (deg) (-) (-) (-) +-1.80000000000000e+02 0.00000000000000e+00 3.76960000000000e-02 2.00000000000000e-01 +-1.77000000000000e+02 1.49471782056503e-01 3.76960000000000e-02 2.00000000000000e-01 +-1.74000000000000e+02 3.00312917607843e-01 4.52351574641884e-02 2.39999774321882e-01 +-1.71000000000000e+02 4.50470313592540e-01 6.78528773607728e-02 3.60000410445527e-01 +-1.68000000000000e+02 5.62141300000530e-01 9.47828314689296e-02 3.00100237874998e-01 +-1.65000000000000e+02 6.54569530813285e-01 1.23868852352745e-01 1.50251760664942e-01 +-1.62000000000000e+02 7.46998820775784e-01 1.52955206537882e-01 4.01566317437541e-04 +-1.59000000000000e+02 7.99786954801670e-01 1.91656498833410e-01 -9.28123657821359e-02 +-1.56000000000000e+02 7.73294117948629e-01 2.49587342086377e-01 -7.27556892942309e-02 +-1.53000000000000e+02 7.46801078706125e-01 3.07518227898197e-01 -5.26992595835046e-02 +-1.50000000000000e+02 7.20307965658325e-01 3.65449165572087e-01 -3.26429649313102e-02 +-1.47000000000000e+02 7.05570256415403e-01 4.36504328003481e-01 -1.75932576097200e-02 +-1.44000000000000e+02 6.90832490879619e-01 5.07559761840581e-01 -2.54349280354572e-03 +-1.41000000000000e+02 6.76094612754094e-01 5.78615738508475e-01 1.25063869759013e-02 +-1.38000000000000e+02 6.57241666993606e-01 6.52702757782292e-01 2.78005506087711e-02 +-1.35000000000000e+02 6.36331195763501e-01 7.28305292210269e-01 4.32168556727960e-02 +-1.32000000000000e+02 6.15420484918018e-01 8.03908692975958e-01 5.86333373939468e-02 +-1.29000000000000e+02 5.90761760127430e-01 8.77986088072914e-01 7.42048196933640e-02 +-1.26000000000000e+02 5.58606989674918e-01 9.49011464578596e-01 9.00863038811478e-02 +-1.23000000000000e+02 5.26452064865786e-01 1.02003589848443e+00 1.05968066745086e-01 +-1.20000000000000e+02 4.94297062881228e-01 1.09105986110795e+00 1.21849968941892e-01 +-1.17000000000000e+02 4.51046455307775e-01 1.14892719359139e+00 1.36973650595308e-01 +-1.14000000000000e+02 4.07795991243718e-01 1.20679427930608e+00 1.52097072994036e-01 +-1.11000000000000e+02 3.64545857584686e-01 1.26466092295440e+00 1.67219979864852e-01 +-1.08000000000000e+02 3.16034192336304e-01 1.30909600565222e+00 1.80733001904303e-01 +-1.05000000000000e+02 2.64891721229873e-01 1.34681520559943e+00 1.93441069265733e-01 +-1.02000000000000e+02 2.13749236173153e-01 1.38453397332146e+00 2.06148391012093e-01 +-9.90000000000000e+01 1.61688764154489e-01 1.41401796036258e+00 2.17512373571396e-01 +-9.60000000000000e+01 1.07792278449096e-01 1.42703202935019e+00 2.26189619569497e-01 +-9.30000000000000e+01 5.38962044824732e-02 1.44004599891764e+00 2.34866399278379e-01 +-9.00000000000000e+01 3.36381508994621e-07 1.45305991877593e+00 2.43542945846872e-01 +-8.70000000000000e+01 -5.38961493200293e-02 1.44004601223740e+00 2.47180796579284e-01 +-8.40000000000000e+01 -1.07792429155678e-01 1.42703199295995e+00 2.50818601967904e-01 +-8.10000000000000e+01 -1.61688297256642e-01 1.41401807310167e+00 2.54456379565910e-01 +-7.80000000000000e+01 -2.13748988477021e-01 1.38453415600310e+00 2.54821405258420e-01 +-7.50000000000000e+01 -2.64892059585176e-01 1.34681495605404e+00 2.53549998518008e-01 +-7.20000000000000e+01 -3.16033944645590e-01 1.30909618833200e+00 2.52278006351131e-01 +-6.90000000000000e+01 -3.64545482908305e-01 1.26466142425377e+00 2.49759236748571e-01 +-6.60000000000000e+01 -4.07796112179989e-01 1.20679411749904e+00 2.44746810177687e-01 +-6.30000000000000e+01 -4.51046741451673e-01 1.14892681074432e+00 2.39734383606802e-01 +-6.00000000000000e+01 -4.94297275617037e-01 1.09105939121714e+00 2.34721942034639e-01 +-5.70000000000000e+01 -5.26452277601595e-01 1.02003542859361e+00 2.27959383679512e-01 +-5.40000000000000e+01 -5.58607202409195e-01 9.49010994678426e-01 2.21196599493265e-01 +-5.10000000000000e+01 -5.90761972861707e-01 8.77985618172743e-01 2.14433363641336e-01 +-4.80000000000000e+01 -6.17089671120620e-01 8.03911570370645e-01 2.07956980763680e-01 +-4.50000000000000e+01 -6.40503926932036e-01 7.28313235916803e-01 2.01624019763027e-01 +-4.20000000000000e+01 -6.58910840133311e-01 6.52705635149657e-01 1.96862389618034e-01 +-3.90000000000000e+01 -6.76417027511146e-01 5.77527369809482e-01 1.92714494884031e-01 +-3.60000000000000e+01 -6.91442126694186e-01 5.04059360049167e-01 1.90773003374389e-01 +-3.30000000000000e+01 -7.05593958510807e-01 4.33318703053973e-01 1.91908992233939e-01 +-3.00000000000000e+01 -7.20308071684859e-01 3.65448723816258e-01 1.96465039072780e-01 +-2.93939393939394e+01 -7.23687122424702e-01 3.52430090699486e-01 1.98306835359819e-01 +-2.87878787878788e+01 -7.27066173164544e-01 3.39411457582714e-01 2.00148631646857e-01 +-2.81818181818182e+01 -7.30445223904387e-01 3.26392824465942e-01 2.01990427933895e-01 +-2.75757575757576e+01 -7.34244974993610e-01 3.13793078035017e-01 2.04486437101527e-01 +-2.69696969696970e+01 -7.38225041700157e-01 3.01372869870364e-01 2.07262847270964e-01 +-2.63636363636364e+01 -7.42205108406705e-01 2.88952661705710e-01 2.10039257440401e-01 +-2.57575757575758e+01 -7.46555462653963e-01 2.76796374908870e-01 2.13304160376248e-01 +-2.51515151515151e+01 -7.51461161912085e-01 2.65035908653530e-01 2.17301688612281e-01 +-2.45454545454545e+01 -7.56366861170206e-01 2.53275442398190e-01 2.21299216848314e-01 +-2.39393939393939e+01 -7.61408677387006e-01 2.41586670872199e-01 2.25459952105595e-01 +-2.33333333333333e+01 -7.67675572584808e-01 2.30543165790786e-01 2.31089582151761e-01 +-2.27272727272727e+01 -7.73942467782610e-01 2.19499660709374e-01 2.36719212197927e-01 +-2.21212121212121e+01 -7.80209362980412e-01 2.08456155627962e-01 2.42348842244093e-01 +-2.15151515151515e+01 -7.88045801889462e-01 1.98028860914946e-01 2.49772963288095e-01 +-2.09090909090909e+01 -7.96274727686348e-01 1.87755658431417e-01 2.57645822511188e-01 +-2.03030303030303e+01 -8.04503653483233e-01 1.77482455947888e-01 2.65518681734281e-01 +-1.96969696969697e+01 -8.13721563222721e-01 1.67514267203666e-01 2.74509167058282e-01 +-1.90909090909091e+01 -8.23928400957602e-01 1.57851074944005e-01 2.84617215258648e-01 +-1.84848484848485e+01 -8.22646763588942e-01 1.48546901850923e-01 2.82973548468764e-01 +-1.78787878787879e+01 -8.19241173382965e-01 1.39555143470384e-01 2.78335696038153e-01 +-1.72727272727273e+01 -8.15446564330172e-01 1.31559857952983e-01 2.70013132308244e-01 +-1.66666666666667e+01 -8.03296442896411e-01 1.23564572435581e-01 2.53038383173389e-01 +-1.60606060606061e+01 -7.84310064075638e-01 1.15569286918180e-01 2.28984646695628e-01 +-1.54545454545455e+01 -7.65324664303493e-01 1.07574959135167e-01 2.04931605118311e-01 +-1.48484848484848e+01 -7.46338949873589e-01 9.95804717419686e-02 1.80878447733115e-01 +-1.42424242424242e+01 -7.27351964982053e-01 9.15851862245671e-02 1.56824711255353e-01 +-1.36363636363636e+01 -7.08366360011050e-01 8.35901755495681e-02 1.32771801638210e-01 +-1.30303030303030e+01 -6.89379049576426e-01 7.55946380877238e-02 1.08716367776058e-01 +-1.24242424242424e+01 -6.70393771825338e-01 6.75996503421813e-02 8.46634665540094e-02 +-1.18181818181818e+01 -6.51406715493019e-01 5.96041815994351e-02 6.06091788446317e-02 +-1.12121212121212e+01 -6.32421454753742e-01 5.16093541595814e-02 3.65562447387649e-02 +-1.06060606060606e+01 -6.13434931389144e-01 4.36139312036515e-02 1.25016705283901e-02 +-1.00000000000000e+01 -5.94448865749824e-01 3.56199434645880e-02 -1.15511700947924e-02 +-9.39393939393939e+00 -5.75463587974779e-01 2.76249557125666e-02 -3.56050107398163e-02 +-8.78787878787879e+00 -5.51403736673166e-01 2.01382292840361e-02 -5.87079533337773e-02 +-8.18181818181818e+00 -5.17926305822838e-01 1.35966762681340e-02 -8.00434824257992e-02 +-7.57575757575758e+00 -4.48012922709353e-01 1.04062079021576e-02 -9.38202376741164e-02 +-6.96969696969697e+00 -3.62306556115099e-01 8.91516259682331e-03 -1.02639375733790e-01 +-6.36363636363636e+00 -2.86592508663283e-01 7.49091941073086e-03 -1.05345402946346e-01 +-5.75757575757576e+00 -2.11681301136276e-01 7.05454293237208e-03 -1.07624256716558e-01 +-5.15151515151515e+00 -1.37278254009080e-01 6.76061420557612e-03 -1.09615086355391e-01 +-4.54545454545454e+00 -6.32445813538124e-02 6.51817895525840e-03 -1.11463657835562e-01 +-3.93939393939394e+00 1.03326972358679e-02 6.40000000000000e-03 -1.13157562089366e-01 +-3.33333333333333e+00 8.37358252318253e-02 6.36666256139732e-03 -1.14700049263232e-01 +-2.72727272727273e+00 1.57144966549608e-01 6.30000000000000e-03 -1.16209080405869e-01 +-2.12121212121212e+00 2.30132082000148e-01 6.30000000000000e-03 -1.17633365893514e-01 +-1.51515151515152e+00 3.03270194866406e-01 6.30000000000000e-03 -1.18966675734322e-01 +-9.09090909090912e-01 3.76007887483945e-01 6.30000000000000e-03 -1.20399977937206e-01 +-3.03030303030302e-01 4.48619648411214e-01 6.33939639599868e-03 -1.21733360355986e-01 + 3.03030303030302e-01 5.21162162400790e-01 6.40000000000000e-03 -1.23066639644014e-01 + 9.09090909090912e-01 5.93483011578421e-01 6.40000000000000e-03 -1.24318201875268e-01 + 1.51515151515152e+00 6.65499510346614e-01 6.50000000000000e-03 -1.25430294786980e-01 + 2.12121212121212e+00 7.37449762821818e-01 6.52423946422604e-03 -1.26642394642260e-01 + 2.72727272727273e+00 8.08982292442682e-01 6.64545535339469e-03 -1.27809098180552e-01 + 3.33333333333333e+00 8.80397573785818e-01 6.76666256139732e-03 -1.28833300491179e-01 + 3.93939393939394e+00 9.51421826139261e-01 6.88787983927956e-03 -1.29890918553516e-01 + 4.54545454545455e+00 1.02186280754731e+00 7.00908947762920e-03 -1.30763626343404e-01 + 5.15151515151515e+00 1.09189627700035e+00 7.16061420557612e-03 -1.31612149719516e-01 + 5.75757575757576e+00 1.16079952835358e+00 7.45454293237208e-03 -1.32306057243163e-01 + 6.36363636363637e+00 1.22720139059598e+00 7.96364926341358e-03 -1.32572729852683e-01 + 6.96969696969697e+00 1.28802463107430e+00 8.94546166938641e-03 -1.32130299072563e-01 + 7.57575757575757e+00 1.33932330958836e+00 1.07272369407300e-02 -1.30081868282978e-01 + 8.18181818181818e+00 1.38679186165234e+00 1.25091248425769e-02 -1.27572678796319e-01 + 8.78787878787879e+00 1.43442629439737e+00 1.40333059500537e-02 -1.25090961368079e-01 + 9.39393939393939e+00 1.48072485366775e+00 1.53666845487907e-02 -1.22230262389112e-01 + 1.00000000000000e+01 1.51619976429293e+00 1.64999922859505e-02 -1.21700000000000e-01 + 1.06060606060606e+01 1.54652659135150e+00 1.81605492792916e-02 -1.21700000000000e-01 + 1.12121212121212e+01 1.57015165312925e+00 2.03485003516014e-02 -1.21912125087900e-01 + 1.18181818181818e+01 1.58466335911404e+00 3.00903504536651e-02 -1.23218115609323e-01 + 1.24242424242424e+01 1.55439065028940e+00 4.64546360854226e-02 -1.25157586499013e-01 + 1.30303030303030e+01 1.50697060273102e+00 6.28179372626244e-02 -1.27096940712607e-01 + 1.36363636363636e+01 1.44636161651328e+00 7.91823635414146e-02 -1.29036428271575e-01 + 1.42424242424242e+01 1.39302963646758e+00 9.22728558241098e-02 -1.30587894023598e-01 + 1.48484848484848e+01 1.35060468299441e+00 1.00454811136793e-01 -1.31557607245842e-01 + 1.54545454545455e+01 1.32181803006545e+00 1.08636414852911e-01 -1.32527278797382e-01 + 1.60606060606061e+01 1.29757644961134e+00 1.16817948256172e-01 -1.33496942015546e-01 + 1.66666666666667e+01 1.27333361905524e+00 1.24999903568856e-01 -1.34466655237790e-01 + 1.72727272727273e+01 1.24363618274871e+00 1.33181858881539e-01 -1.35436368460034e-01 + 1.78787878787879e+01 1.20727193691457e+00 1.41363814194223e-01 -1.36406081682278e-01 + 1.84848484848485e+01 1.18992978938591e+00 1.49497879761678e-01 -1.37375750456550e-01 + 1.90909090909091e+01 1.17704330010331e+00 1.57851074944005e-01 -1.39089585145003e-01 + 1.96969696969697e+01 1.16246123752382e+00 1.67514267203666e-01 -1.45021805782080e-01 + 2.03030303030303e+01 1.14929279501435e+00 1.77482455947888e-01 -1.51632351934001e-01 + 2.09090909090909e+01 1.13753805254846e+00 1.87755658431417e-01 -1.58921261976074e-01 + 2.15151515151515e+01 1.12578331008257e+00 1.98028860914946e-01 -1.66210172018147e-01 + 2.21212121212121e+01 1.11458874358451e+00 2.08456155627962e-01 -1.73224623443957e-01 + 2.27272727272727e+01 1.10563430457793e+00 2.19499660709374e-01 -1.79141522802416e-01 + 2.33333333333333e+01 1.09667986557135e+00 2.30543165790786e-01 -1.85058422160874e-01 + 2.39393939393939e+01 1.08772542656477e+00 2.41586670872199e-01 -1.90975321519332e-01 + 2.45454545454545e+01 1.08052187960139e+00 2.53275442398190e-01 -1.96074592475065e-01 + 2.51515151515151e+01 1.07351287201350e+00 2.65035908653530e-01 -2.01083017784734e-01 + 2.57575757575758e+01 1.06650386442561e+00 2.76796374908870e-01 -2.06091443094404e-01 + 2.63636363636364e+01 1.06028924575223e+00 2.88952661705710e-01 -2.10729607665482e-01 + 2.69696969696970e+01 1.05460430198682e+00 3.01372869870364e-01 -2.15120893385337e-01 + 2.75757575757576e+01 1.04891935822142e+00 3.13793078035017e-01 -2.19512179105193e-01 + 2.81818181818182e+01 1.04349174843484e+00 3.26392824465942e-01 -2.23774966350859e-01 + 2.87878787878788e+01 1.03866453309221e+00 3.39411457582714e-01 -2.27737949543009e-01 + 2.93939393939394e+01 1.03383731774957e+00 3.52430090699486e-01 -2.31700932735158e-01 + 3.00000000000000e+01 1.02901010240694e+00 3.65448723816258e-01 -2.35663915927308e-01 + 3.30000000000000e+01 1.00799494072346e+00 4.33318703053973e-01 -2.53423049843193e-01 + 3.60000000000000e+01 9.87774181033947e-01 5.04059360049167e-01 -2.69936854350083e-01 + 3.90000000000000e+01 9.66310039303889e-01 5.77527369809482e-01 -2.85448473353340e-01 + 4.20000000000000e+01 9.41301057332367e-01 6.52705635149657e-01 -3.00284968060017e-01 + 4.50000000000000e+01 9.15005895616392e-01 7.28313235916803e-01 -3.14934043892456e-01 + 4.80000000000000e+01 8.81556701601667e-01 8.03911570370646e-01 -3.28999157277327e-01 + 5.10000000000000e+01 8.43945446946677e-01 8.77985618172744e-01 -3.42814128421300e-01 + 5.40000000000000e+01 7.98009803441727e-01 9.49010994678426e-01 -3.56128799002399e-01 + 5.70000000000000e+01 7.52074110859421e-01 1.02003542859361e+00 -3.69443367867275e-01 + 6.00000000000000e+01 7.06138393738624e-01 1.09105939121714e+00 -3.82757885874428e-01 + 6.30000000000000e+01 6.44352602071576e-01 1.14892681074432e+00 -3.94831160514253e-01 + 6.60000000000000e+01 5.82566474543015e-01 1.20679411749904e+00 -4.06904424514653e-01 + 6.90000000000000e+01 5.20779947012492e-01 1.26466142425377e+00 -4.18977688515053e-01 + 7.20000000000000e+01 4.51477435205418e-01 1.30909618833200e+00 -4.29844051243441e-01 + 7.50000000000000e+01 3.78417085122278e-01 1.34681495605404e+00 -4.40106988042700e-01 + 7.80000000000000e+01 3.05355897825734e-01 1.38453415600310e+00 -4.50369442444556e-01 + 8.10000000000000e+01 2.30983767510451e-01 1.41401807310167e+00 -4.59788643436343e-01 + 8.40000000000000e+01 1.53989841650875e-01 1.42703199295995e+00 -4.67521395816866e-01 + 8.70000000000000e+01 7.69949275996385e-02 1.44004601223740e+00 -4.75253807270785e-01 + 9.00000000000000e+01 -3.36381509228363e-07 1.45305991877593e+00 -4.82986022704544e-01 + 9.30000000000000e+01 -5.38962044824732e-02 1.44004599891764e+00 -4.86623800302551e-01 + 9.60000000000000e+01 -1.07792278449097e-01 1.42703202935019e+00 -4.90261391797104e-01 + 9.90000000000000e+01 -1.61688764154490e-01 1.41401796036258e+00 -4.93898611078011e-01 + 1.02000000000000e+02 -2.13749236173153e-01 1.38453397332146e+00 -4.94263399100743e-01 + 1.05000000000000e+02 -2.64891721229873e-01 1.34681520559943e+00 -4.92992006930171e-01 + 1.08000000000000e+02 -3.16034192336304e-01 1.30909600565222e+00 -4.91720000190610e-01 + 1.11000000000000e+02 -3.64545857584686e-01 1.26466092295440e+00 -4.89201393327162e-01 + 1.14000000000000e+02 -4.07795991243718e-01 1.20679427930608e+00 -4.84189624190406e-01 + 1.17000000000000e+02 -4.51046455307775e-01 1.14892719359139e+00 -4.79177416768754e-01 + 1.20000000000000e+02 -4.94297062881228e-01 1.09105986110795e+00 -4.74164986774198e-01 + 1.23000000000000e+02 -5.26452064865786e-01 1.02003589848443e+00 -4.67401828422766e-01 + 1.26000000000000e+02 -5.58606989674918e-01 9.49011464578596e-01 -4.60638644238479e-01 + 1.29000000000000e+02 -5.90761760127430e-01 8.77986088072913e-01 -4.53875408386550e-01 + 1.32000000000000e+02 -6.15420484918018e-01 8.03908692975958e-01 -4.47922977473614e-01 + 1.35000000000000e+02 -6.36331195763501e-01 7.28305292210269e-01 -4.42375948063776e-01 + 1.38000000000000e+02 -6.57241666993606e-01 6.52702757782291e-01 -4.36828382226539e-01 + 1.41000000000000e+02 -6.76094612754094e-01 5.78615738508474e-01 -4.33407800721224e-01 + 1.44000000000000e+02 -6.90832490879619e-01 5.07559761840581e-01 -4.34241205139103e-01 + 1.47000000000000e+02 -7.05570256415403e-01 4.36504328003481e-01 -4.35074603190205e-01 + 1.50000000000000e+02 -7.20307965658325e-01 3.65449165572087e-01 -4.35907998058031e-01 + 1.53000000000000e+02 -7.46801078706125e-01 3.07518227898197e-01 -4.57805065052203e-01 + 1.56000000000000e+02 -7.73294117948629e-01 2.49587342086377e-01 -4.79701897484255e-01 + 1.59000000000000e+02 -7.99786954801670e-01 1.91656498833410e-01 -5.01598162643690e-01 + 1.62000000000000e+02 -7.40790822868899e-01 1.53560806333696e-01 -5.07117800599882e-01 + 1.65000000000000e+02 -6.39049483540701e-01 1.25382856960915e-01 -5.04448986449602e-01 + 1.68000000000000e+02 -5.37308710076014e-01 9.72046304867630e-02 -5.01779602888076e-01 + 1.71000000000000e+02 -4.22533481739914e-01 7.05772804657932e-02 -4.50000513056908e-01 + 1.74000000000000e+02 -2.81688735121593e-01 4.70517557569334e-02 -2.99999717902353e-01 + 1.77000000000000e+02 -1.40202251216632e-01 3.86002570677554e-02 -6.87686132694523e-02 + 1.80000000000000e+02 0.00000000000000e+00 3.76960000000000e-02 2.00000000000000e-01 diff --git a/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_29.dat b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_29.dat new file mode 100644 index 00000000..31764aed --- /dev/null +++ b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_29.dat @@ -0,0 +1,254 @@ +! ------------ AirfoilInfo v1.01.x Input File ---------------------------------- +! AeroElasticSE FAST driver +! line +! line +! ------------------------------------------------------------------------------ +DEFAULT InterpOrd ! Interpolation order to use for quasi-steady table lookup {1=linear; 3=cubic spline; "default"} [default=3] +1 NonDimArea ! The non-dimensional area of the airfoil (area/chord^2) (set to 1.0 if unsure or unneeded) +@"NREL-2p8-127_AF29_Coords.txt" NumCoords ! The number of coordinates in the airfoil shape file. Set to zero if coordinates not included. +AF29_BL.txt BL_file ! The file name including the boundary layer characteristics of the profile. Ignored if the aeroacoustic module is not called. +1 NumTabs ! Number of airfoil tables in this file. Each table must have lines for Re and Ctrl. +! ------------------------------------------------------------------------------ +! data for table 1 +! ------------------------------------------------------------------------------ +6.000000 Re ! Reynolds number in millions +0 Ctrl ! Control setting (must be 0 for current AirfoilInfo) +True InclUAdata ! Is unsteady aerodynamics data included in this table? If TRUE, then include 30 UA coefficients below this line +!........................................ +-4.024505 alpha0 ! 0-lift angle of attack, depends on airfoil. +11.306884 alpha1 ! Angle of attack at f=0.7, (approximately the stall angle) for AOA>alpha0. (deg) +-9.832557 alpha2 ! Angle of attack at f=0.7, (approximately the stall angle) for AOA1] +0.000000 S2 ! Constant in the f curve best-fit for AOA> alpha1; by definition it depends on the airfoil. [ignored if UAMod<>1] +0.000000 S3 ! Constant in the f curve best-fit for alpha2<=AOA< alpha0; by definition it depends on the airfoil. [ignored if UAMod<>1] +0.000000 S4 ! Constant in the f curve best-fit for AOA< alpha2; by definition it depends on the airfoil. [ignored if UAMod<>1] +1.557235 Cn1 ! Critical value of C0n at leading edge separation. It should be extracted from airfoil data at a given Mach and Reynolds number. It can be calculated from the static value of Cn at either the break in the pitching moment or the loss of chord force at the onset of stall. It is close to the condition of maximum lift of the airfoil at low Mach numbers. +-0.830241 Cn2 ! As Cn1 for negative AOAs. +Default St_sh ! Strouhal's shedding frequency constant. [default = 0.19] +0.006417 Cd0 ! 2D drag coefficient value at 0-lift. +-0.112920 Cm0 ! 2D pitching moment coefficient about 1/4-chord location, at 0-lift, positive if nose up. [If the aerodynamics coefficients table does not include a column for Cm, this needs to be set to 0.0] +0.000000 k0 ! Constant in the \hat(x)_cp curve best-fit; = (\hat(x)_AC-0.25). [ignored if UAMod<>1] +0.000000 k1 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k2 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k3 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k1_hat ! Constant in the expression of Cc due to leading edge vortex effects. [ignored if UAMod<>1] +Default x_cp_bar ! Constant in the expression of \hat(x)_cp^v. [ignored if UAMod<>1, default = 0.2] +Default UACutout ! Angle of attack above which unsteady aerodynamics are disabled (deg). [Specifying the string "Default" sets UACutout to 45 degrees] +Default filtCutOff ! Cut-off frequency (-3 dB corner frequency) for low-pass filtering the AoA input to UA, as well as the 1st and 2nd derivatives (Hz) [default = 20] +!........................................ +! Table of aerodynamics coefficients +200 NumAlf ! Number of data lines in the following table +! Alpha Cl Cd Cm +! (deg) (-) (-) (-) +-1.80000000000000e+02 0.00000000000000e+00 3.76960000000000e-02 2.00000000000000e-01 +-1.77000000000000e+02 1.49471782056503e-01 3.76960000000000e-02 2.00000000000000e-01 +-1.74000000000000e+02 3.00312917607843e-01 4.52351574641884e-02 2.39999774321882e-01 +-1.71000000000000e+02 4.50470313592540e-01 6.78528773607728e-02 3.60000410445527e-01 +-1.68000000000000e+02 5.62141300000530e-01 9.47828314689296e-02 3.00100237874998e-01 +-1.65000000000000e+02 6.54569530813285e-01 1.23868852352745e-01 1.50251760664942e-01 +-1.62000000000000e+02 7.46998820775784e-01 1.52955206537882e-01 4.01566317437541e-04 +-1.59000000000000e+02 7.99786954801670e-01 1.91656498833410e-01 -9.28123657821359e-02 +-1.56000000000000e+02 7.73294117948629e-01 2.49587342086377e-01 -7.27556892942309e-02 +-1.53000000000000e+02 7.46801078706125e-01 3.07518227898197e-01 -5.26992595835046e-02 +-1.50000000000000e+02 7.20307965658325e-01 3.65449165572087e-01 -3.26429649313102e-02 +-1.47000000000000e+02 7.05570256415403e-01 4.36504328003481e-01 -1.75932576097200e-02 +-1.44000000000000e+02 6.90832490879619e-01 5.07559761840581e-01 -2.54349280354572e-03 +-1.41000000000000e+02 6.76094612754094e-01 5.78615738508475e-01 1.25063869759013e-02 +-1.38000000000000e+02 6.57241666993606e-01 6.52702757782292e-01 2.78005506087711e-02 +-1.35000000000000e+02 6.36331195763501e-01 7.28305292210269e-01 4.32168556727960e-02 +-1.32000000000000e+02 6.15420484918018e-01 8.03908692975958e-01 5.86333373939468e-02 +-1.29000000000000e+02 5.90761760127430e-01 8.77986088072914e-01 7.42048196933640e-02 +-1.26000000000000e+02 5.58606989674918e-01 9.49011464578596e-01 9.00863038811478e-02 +-1.23000000000000e+02 5.26452064865786e-01 1.02003589848443e+00 1.05968066745086e-01 +-1.20000000000000e+02 4.94297062881228e-01 1.09105986110795e+00 1.21849968941892e-01 +-1.17000000000000e+02 4.51046455307775e-01 1.14892719359139e+00 1.36973650595308e-01 +-1.14000000000000e+02 4.07795991243718e-01 1.20679427930608e+00 1.52097072994036e-01 +-1.11000000000000e+02 3.64545857584686e-01 1.26466092295440e+00 1.67219979864852e-01 +-1.08000000000000e+02 3.16034192336304e-01 1.30909600565222e+00 1.80733001904303e-01 +-1.05000000000000e+02 2.64891721229873e-01 1.34681520559943e+00 1.93441069265733e-01 +-1.02000000000000e+02 2.13749236173153e-01 1.38453397332146e+00 2.06148391012093e-01 +-9.90000000000000e+01 1.61688764154489e-01 1.41401796036258e+00 2.17512373571396e-01 +-9.60000000000000e+01 1.07792278449096e-01 1.42703202935019e+00 2.26189619569497e-01 +-9.30000000000000e+01 5.38962044824732e-02 1.44004599891764e+00 2.34866399278379e-01 +-9.00000000000000e+01 3.36381508994621e-07 1.45305991877593e+00 2.43542945846872e-01 +-8.70000000000000e+01 -5.38961493200293e-02 1.44004601223740e+00 2.47180796579284e-01 +-8.40000000000000e+01 -1.07792429155678e-01 1.42703199295995e+00 2.50818601967904e-01 +-8.10000000000000e+01 -1.61688297256642e-01 1.41401807310167e+00 2.54456379565910e-01 +-7.80000000000000e+01 -2.13748988477021e-01 1.38453415600310e+00 2.54821405258420e-01 +-7.50000000000000e+01 -2.64892059585176e-01 1.34681495605404e+00 2.53549998518008e-01 +-7.20000000000000e+01 -3.16033944645590e-01 1.30909618833200e+00 2.52278006351131e-01 +-6.90000000000000e+01 -3.64545482908305e-01 1.26466142425377e+00 2.49759236748571e-01 +-6.60000000000000e+01 -4.07796112179989e-01 1.20679411749904e+00 2.44746810177687e-01 +-6.30000000000000e+01 -4.51046741451673e-01 1.14892681074432e+00 2.39734383606802e-01 +-6.00000000000000e+01 -4.94297275617037e-01 1.09105939121714e+00 2.34721942034639e-01 +-5.70000000000000e+01 -5.26452277601595e-01 1.02003542859361e+00 2.27959383679512e-01 +-5.40000000000000e+01 -5.58607202409195e-01 9.49010994678426e-01 2.21196599493265e-01 +-5.10000000000000e+01 -5.90761972861707e-01 8.77985618172743e-01 2.14433363641336e-01 +-4.80000000000000e+01 -6.17089671120620e-01 8.03911570370645e-01 2.07956980763680e-01 +-4.50000000000000e+01 -6.40503926932036e-01 7.28313235916803e-01 2.01624019763027e-01 +-4.20000000000000e+01 -6.58910840133311e-01 6.52705635149657e-01 1.96862389618034e-01 +-3.90000000000000e+01 -6.76417027511146e-01 5.77527369809482e-01 1.92714494884031e-01 +-3.60000000000000e+01 -6.91442126694186e-01 5.04059360049167e-01 1.90773003374389e-01 +-3.30000000000000e+01 -7.05593958510807e-01 4.33318703053973e-01 1.91908992233939e-01 +-3.00000000000000e+01 -7.20308071684859e-01 3.65448723816258e-01 1.96465039072780e-01 +-2.93939393939394e+01 -7.23687122424702e-01 3.52430090699486e-01 1.98306835359819e-01 +-2.87878787878788e+01 -7.27066173164544e-01 3.39411457582714e-01 2.00148631646857e-01 +-2.81818181818182e+01 -7.30445223904387e-01 3.26392824465942e-01 2.01990427933895e-01 +-2.75757575757576e+01 -7.34244974993610e-01 3.13793078035017e-01 2.04486437101527e-01 +-2.69696969696970e+01 -7.38225041700157e-01 3.01372869870364e-01 2.07262847270964e-01 +-2.63636363636364e+01 -7.42205108406705e-01 2.88952661705710e-01 2.10039257440401e-01 +-2.57575757575758e+01 -7.46555462653963e-01 2.76796374908870e-01 2.13304160376248e-01 +-2.51515151515151e+01 -7.51461161912085e-01 2.65035908653530e-01 2.17301688612281e-01 +-2.45454545454545e+01 -7.56366861170206e-01 2.53275442398190e-01 2.21299216848314e-01 +-2.39393939393939e+01 -7.61408677387006e-01 2.41586670872199e-01 2.25459952105595e-01 +-2.33333333333333e+01 -7.67675572584808e-01 2.30543165790786e-01 2.31089582151761e-01 +-2.27272727272727e+01 -7.73942467782610e-01 2.19499660709374e-01 2.36719212197927e-01 +-2.21212121212121e+01 -7.80209362980412e-01 2.08456155627962e-01 2.42348842244093e-01 +-2.15151515151515e+01 -7.88045801889462e-01 1.98028860914946e-01 2.49772963288095e-01 +-2.09090909090909e+01 -7.96274727686348e-01 1.87755658431417e-01 2.57645822511188e-01 +-2.03030303030303e+01 -8.04503653483233e-01 1.77482455947888e-01 2.65518681734281e-01 +-1.96969696969697e+01 -8.13721563222721e-01 1.67514267203666e-01 2.74509167058282e-01 +-1.90909090909091e+01 -8.23928400957602e-01 1.57851074944005e-01 2.84617215258648e-01 +-1.84848484848485e+01 -8.22646763588942e-01 1.48546901850923e-01 2.82973548468764e-01 +-1.78787878787879e+01 -8.19241173382965e-01 1.39555143470384e-01 2.78335696038153e-01 +-1.72727272727273e+01 -8.15446564330172e-01 1.31559857952983e-01 2.70013132308244e-01 +-1.66666666666667e+01 -8.03296442896411e-01 1.23564572435581e-01 2.53038383173389e-01 +-1.60606060606061e+01 -7.84310064075638e-01 1.15569286918180e-01 2.28984646695628e-01 +-1.54545454545455e+01 -7.65324664303493e-01 1.07574959135167e-01 2.04931605118311e-01 +-1.48484848484848e+01 -7.46338949873589e-01 9.95804717419686e-02 1.80878447733115e-01 +-1.42424242424242e+01 -7.27351964982053e-01 9.15851862245671e-02 1.56824711255353e-01 +-1.36363636363636e+01 -7.08366360011050e-01 8.35901755495681e-02 1.32771801638210e-01 +-1.30303030303030e+01 -6.89379049576426e-01 7.55946380877238e-02 1.08716367776058e-01 +-1.24242424242424e+01 -6.70393771825338e-01 6.75996503421813e-02 8.46634665540094e-02 +-1.18181818181818e+01 -6.51406715493019e-01 5.96041815994351e-02 6.06091788446317e-02 +-1.12121212121212e+01 -6.32421454753742e-01 5.16093541595814e-02 3.65562447387649e-02 +-1.06060606060606e+01 -6.13434931389144e-01 4.36139312036515e-02 1.25016705283901e-02 +-1.00000000000000e+01 -5.94448865749824e-01 3.56199434645880e-02 -1.15511700947924e-02 +-9.39393939393939e+00 -5.75463587974779e-01 2.76249557125666e-02 -3.56050107398163e-02 +-8.78787878787879e+00 -5.51403736673166e-01 2.01382292840361e-02 -5.87079533337773e-02 +-8.18181818181818e+00 -5.17926305822838e-01 1.35966762681340e-02 -8.00434824257992e-02 +-7.57575757575758e+00 -4.48012922709353e-01 1.04062079021576e-02 -9.38202376741164e-02 +-6.96969696969697e+00 -3.62306556115099e-01 8.91516259682331e-03 -1.02639375733790e-01 +-6.36363636363636e+00 -2.86592508663283e-01 7.49091941073086e-03 -1.05345402946346e-01 +-5.75757575757576e+00 -2.11681301136276e-01 7.05454293237208e-03 -1.07624256716558e-01 +-5.15151515151515e+00 -1.37278254009080e-01 6.76061420557612e-03 -1.09615086355391e-01 +-4.54545454545454e+00 -6.32445813538124e-02 6.51817895525840e-03 -1.11463657835562e-01 +-3.93939393939394e+00 1.03326972358679e-02 6.40000000000000e-03 -1.13157562089366e-01 +-3.33333333333333e+00 8.37358252318253e-02 6.36666256139732e-03 -1.14700049263232e-01 +-2.72727272727273e+00 1.57144966549608e-01 6.30000000000000e-03 -1.16209080405869e-01 +-2.12121212121212e+00 2.30132082000148e-01 6.30000000000000e-03 -1.17633365893514e-01 +-1.51515151515152e+00 3.03270194866406e-01 6.30000000000000e-03 -1.18966675734322e-01 +-9.09090909090912e-01 3.76007887483945e-01 6.30000000000000e-03 -1.20399977937206e-01 +-3.03030303030302e-01 4.48619648411214e-01 6.33939639599868e-03 -1.21733360355986e-01 + 3.03030303030302e-01 5.21162162400790e-01 6.40000000000000e-03 -1.23066639644014e-01 + 9.09090909090912e-01 5.93483011578421e-01 6.40000000000000e-03 -1.24318201875268e-01 + 1.51515151515152e+00 6.65499510346614e-01 6.50000000000000e-03 -1.25430294786980e-01 + 2.12121212121212e+00 7.37449762821818e-01 6.52423946422604e-03 -1.26642394642260e-01 + 2.72727272727273e+00 8.08982292442682e-01 6.64545535339469e-03 -1.27809098180552e-01 + 3.33333333333333e+00 8.80397573785818e-01 6.76666256139732e-03 -1.28833300491179e-01 + 3.93939393939394e+00 9.51421826139261e-01 6.88787983927956e-03 -1.29890918553516e-01 + 4.54545454545455e+00 1.02186280754731e+00 7.00908947762920e-03 -1.30763626343404e-01 + 5.15151515151515e+00 1.09189627700035e+00 7.16061420557612e-03 -1.31612149719516e-01 + 5.75757575757576e+00 1.16079952835358e+00 7.45454293237208e-03 -1.32306057243163e-01 + 6.36363636363637e+00 1.22720139059598e+00 7.96364926341358e-03 -1.32572729852683e-01 + 6.96969696969697e+00 1.28802463107430e+00 8.94546166938641e-03 -1.32130299072563e-01 + 7.57575757575757e+00 1.33932330958836e+00 1.07272369407300e-02 -1.30081868282978e-01 + 8.18181818181818e+00 1.38679186165234e+00 1.25091248425769e-02 -1.27572678796319e-01 + 8.78787878787879e+00 1.43442629439737e+00 1.40333059500537e-02 -1.25090961368079e-01 + 9.39393939393939e+00 1.48072485366775e+00 1.53666845487907e-02 -1.22230262389112e-01 + 1.00000000000000e+01 1.51619976429293e+00 1.64999922859505e-02 -1.21700000000000e-01 + 1.06060606060606e+01 1.54652659135150e+00 1.81605492792916e-02 -1.21700000000000e-01 + 1.12121212121212e+01 1.57015165312925e+00 2.03485003516014e-02 -1.21912125087900e-01 + 1.18181818181818e+01 1.58466335911404e+00 3.00903504536651e-02 -1.23218115609323e-01 + 1.24242424242424e+01 1.55439065028940e+00 4.64546360854226e-02 -1.25157586499013e-01 + 1.30303030303030e+01 1.50697060273102e+00 6.28179372626244e-02 -1.27096940712607e-01 + 1.36363636363636e+01 1.44636161651328e+00 7.91823635414146e-02 -1.29036428271575e-01 + 1.42424242424242e+01 1.39302963646758e+00 9.22728558241098e-02 -1.30587894023598e-01 + 1.48484848484848e+01 1.35060468299441e+00 1.00454811136793e-01 -1.31557607245842e-01 + 1.54545454545455e+01 1.32181803006545e+00 1.08636414852911e-01 -1.32527278797382e-01 + 1.60606060606061e+01 1.29757644961134e+00 1.16817948256172e-01 -1.33496942015546e-01 + 1.66666666666667e+01 1.27333361905524e+00 1.24999903568856e-01 -1.34466655237790e-01 + 1.72727272727273e+01 1.24363618274871e+00 1.33181858881539e-01 -1.35436368460034e-01 + 1.78787878787879e+01 1.20727193691457e+00 1.41363814194223e-01 -1.36406081682278e-01 + 1.84848484848485e+01 1.18992978938591e+00 1.49497879761678e-01 -1.37375750456550e-01 + 1.90909090909091e+01 1.17704330010331e+00 1.57851074944005e-01 -1.39089585145003e-01 + 1.96969696969697e+01 1.16246123752382e+00 1.67514267203666e-01 -1.45021805782080e-01 + 2.03030303030303e+01 1.14929279501435e+00 1.77482455947888e-01 -1.51632351934001e-01 + 2.09090909090909e+01 1.13753805254846e+00 1.87755658431417e-01 -1.58921261976074e-01 + 2.15151515151515e+01 1.12578331008257e+00 1.98028860914946e-01 -1.66210172018147e-01 + 2.21212121212121e+01 1.11458874358451e+00 2.08456155627962e-01 -1.73224623443957e-01 + 2.27272727272727e+01 1.10563430457793e+00 2.19499660709374e-01 -1.79141522802416e-01 + 2.33333333333333e+01 1.09667986557135e+00 2.30543165790786e-01 -1.85058422160874e-01 + 2.39393939393939e+01 1.08772542656477e+00 2.41586670872199e-01 -1.90975321519332e-01 + 2.45454545454545e+01 1.08052187960139e+00 2.53275442398190e-01 -1.96074592475065e-01 + 2.51515151515151e+01 1.07351287201350e+00 2.65035908653530e-01 -2.01083017784734e-01 + 2.57575757575758e+01 1.06650386442561e+00 2.76796374908870e-01 -2.06091443094404e-01 + 2.63636363636364e+01 1.06028924575223e+00 2.88952661705710e-01 -2.10729607665482e-01 + 2.69696969696970e+01 1.05460430198682e+00 3.01372869870364e-01 -2.15120893385337e-01 + 2.75757575757576e+01 1.04891935822142e+00 3.13793078035017e-01 -2.19512179105193e-01 + 2.81818181818182e+01 1.04349174843484e+00 3.26392824465942e-01 -2.23774966350859e-01 + 2.87878787878788e+01 1.03866453309221e+00 3.39411457582714e-01 -2.27737949543009e-01 + 2.93939393939394e+01 1.03383731774957e+00 3.52430090699486e-01 -2.31700932735158e-01 + 3.00000000000000e+01 1.02901010240694e+00 3.65448723816258e-01 -2.35663915927308e-01 + 3.30000000000000e+01 1.00799494072346e+00 4.33318703053973e-01 -2.53423049843193e-01 + 3.60000000000000e+01 9.87774181033947e-01 5.04059360049167e-01 -2.69936854350083e-01 + 3.90000000000000e+01 9.66310039303889e-01 5.77527369809482e-01 -2.85448473353340e-01 + 4.20000000000000e+01 9.41301057332367e-01 6.52705635149657e-01 -3.00284968060017e-01 + 4.50000000000000e+01 9.15005895616392e-01 7.28313235916803e-01 -3.14934043892456e-01 + 4.80000000000000e+01 8.81556701601667e-01 8.03911570370646e-01 -3.28999157277327e-01 + 5.10000000000000e+01 8.43945446946677e-01 8.77985618172744e-01 -3.42814128421300e-01 + 5.40000000000000e+01 7.98009803441727e-01 9.49010994678426e-01 -3.56128799002399e-01 + 5.70000000000000e+01 7.52074110859421e-01 1.02003542859361e+00 -3.69443367867275e-01 + 6.00000000000000e+01 7.06138393738624e-01 1.09105939121714e+00 -3.82757885874428e-01 + 6.30000000000000e+01 6.44352602071576e-01 1.14892681074432e+00 -3.94831160514253e-01 + 6.60000000000000e+01 5.82566474543015e-01 1.20679411749904e+00 -4.06904424514653e-01 + 6.90000000000000e+01 5.20779947012492e-01 1.26466142425377e+00 -4.18977688515053e-01 + 7.20000000000000e+01 4.51477435205418e-01 1.30909618833200e+00 -4.29844051243441e-01 + 7.50000000000000e+01 3.78417085122278e-01 1.34681495605404e+00 -4.40106988042700e-01 + 7.80000000000000e+01 3.05355897825734e-01 1.38453415600310e+00 -4.50369442444556e-01 + 8.10000000000000e+01 2.30983767510451e-01 1.41401807310167e+00 -4.59788643436343e-01 + 8.40000000000000e+01 1.53989841650875e-01 1.42703199295995e+00 -4.67521395816866e-01 + 8.70000000000000e+01 7.69949275996385e-02 1.44004601223740e+00 -4.75253807270785e-01 + 9.00000000000000e+01 -3.36381509228363e-07 1.45305991877593e+00 -4.82986022704544e-01 + 9.30000000000000e+01 -5.38962044824732e-02 1.44004599891764e+00 -4.86623800302551e-01 + 9.60000000000000e+01 -1.07792278449097e-01 1.42703202935019e+00 -4.90261391797104e-01 + 9.90000000000000e+01 -1.61688764154490e-01 1.41401796036258e+00 -4.93898611078011e-01 + 1.02000000000000e+02 -2.13749236173153e-01 1.38453397332146e+00 -4.94263399100743e-01 + 1.05000000000000e+02 -2.64891721229873e-01 1.34681520559943e+00 -4.92992006930171e-01 + 1.08000000000000e+02 -3.16034192336304e-01 1.30909600565222e+00 -4.91720000190610e-01 + 1.11000000000000e+02 -3.64545857584686e-01 1.26466092295440e+00 -4.89201393327162e-01 + 1.14000000000000e+02 -4.07795991243718e-01 1.20679427930608e+00 -4.84189624190406e-01 + 1.17000000000000e+02 -4.51046455307775e-01 1.14892719359139e+00 -4.79177416768754e-01 + 1.20000000000000e+02 -4.94297062881228e-01 1.09105986110795e+00 -4.74164986774198e-01 + 1.23000000000000e+02 -5.26452064865786e-01 1.02003589848443e+00 -4.67401828422766e-01 + 1.26000000000000e+02 -5.58606989674918e-01 9.49011464578596e-01 -4.60638644238479e-01 + 1.29000000000000e+02 -5.90761760127430e-01 8.77986088072913e-01 -4.53875408386550e-01 + 1.32000000000000e+02 -6.15420484918018e-01 8.03908692975958e-01 -4.47922977473614e-01 + 1.35000000000000e+02 -6.36331195763501e-01 7.28305292210269e-01 -4.42375948063776e-01 + 1.38000000000000e+02 -6.57241666993606e-01 6.52702757782291e-01 -4.36828382226539e-01 + 1.41000000000000e+02 -6.76094612754094e-01 5.78615738508474e-01 -4.33407800721224e-01 + 1.44000000000000e+02 -6.90832490879619e-01 5.07559761840581e-01 -4.34241205139103e-01 + 1.47000000000000e+02 -7.05570256415403e-01 4.36504328003481e-01 -4.35074603190205e-01 + 1.50000000000000e+02 -7.20307965658325e-01 3.65449165572087e-01 -4.35907998058031e-01 + 1.53000000000000e+02 -7.46801078706125e-01 3.07518227898197e-01 -4.57805065052203e-01 + 1.56000000000000e+02 -7.73294117948629e-01 2.49587342086377e-01 -4.79701897484255e-01 + 1.59000000000000e+02 -7.99786954801670e-01 1.91656498833410e-01 -5.01598162643690e-01 + 1.62000000000000e+02 -7.40790822868899e-01 1.53560806333696e-01 -5.07117800599882e-01 + 1.65000000000000e+02 -6.39049483540701e-01 1.25382856960915e-01 -5.04448986449602e-01 + 1.68000000000000e+02 -5.37308710076014e-01 9.72046304867630e-02 -5.01779602888076e-01 + 1.71000000000000e+02 -4.22533481739914e-01 7.05772804657932e-02 -4.50000513056908e-01 + 1.74000000000000e+02 -2.81688735121593e-01 4.70517557569334e-02 -2.99999717902353e-01 + 1.77000000000000e+02 -1.40202251216632e-01 3.86002570677554e-02 -6.87686132694523e-02 + 1.80000000000000e+02 0.00000000000000e+00 3.76960000000000e-02 2.00000000000000e-01 diff --git a/Test_Cases/NREL_2p8_127/NREL-2.8-127.xlsx b/Test_Cases/NREL_2p8_127/NREL-2.8-127.xlsx new file mode 100644 index 0000000000000000000000000000000000000000..5d5d8946639878b3e2597fa3f73ca99c53f5af73 GIT binary patch literal 14107 zcmeHu1$P`tvUQ6ki!8F(VrC|bnVFfHnJsEb7BkBNibyZdI>JKryO zulk&>Q=JvJvm)bWL}f(ENrHi+0w4j<004jhz|ZDCVFLmHfI|QPC;(_sO+i~5Cu18Y zT_txrV@GXTH)|{W9B@$bECA^H{r`9TFV;Y*(vVFz{l_-dLtdeFmC)?q;$mo=W*kl8 zeW+x&ST*AMT}<+4Z!!~kH>T_Rp~xFXFFSD7~cE`kEJO0KE)5l{SZcp5cJ zyUGlcQxK2OycDF+nh_6<2?+DCiUIW!-}Eaa9no6za3kY~o@F;Ly(3YK=8T>4dS~5d zF8`_MaOEu7xoX!Yi=R=jS1FEH$IOFyWuY{~8pg*mcQCJR7{*>Vw$wka(ETR%@iQ5s zFWlP#p&fxA&DQ|y%_m6LIF4nY`!E;RDs1TI=uhzok+baVQR&NoBv*a(m~ze=IB-9> zV?hVA#oKV4hmsY9wTv8oyv@W51nk#$p1r++0p$LJrgh5nMAz@OC-vS6`%Y6`2V*No zI@&+J|Bs&ki#hpkk6s!pE!#s62Rsvd4j#OlTZ{fEAnD34)u^$a*#Oz#gj5% zWdmE*VcbNT??Ph!0X%OAht%$OQq8W#Ir9q|xC!xEpkyYoF zP+AAdix-Vd`k(?KGx9y-gy;ZC){U=5E%U`lhI=m?Oi#(+`H+7YUg7$?$NF!QU@Mfb zrhowe_3y3?@m(`+R&=hm4weSCww8bRu~KDC+Y_VB2dDj<8wzqFec8v$smt zGEc}w4xJP#fSP{hqT;I!S1AFH6>VcrR*B<9L!S1O2NSPHYfaT<6g1qOF{J^r{PHQ% zJqXLs1&>kgKrihhV)G9Q7eJXC)8&JWai6ynr=C8Kp$84HulZ?*dGXd}7}`41sZM0A zdGKl~TC+mk3SY3asmLjsV-?g@fySws@+kBBT!C^p0bQz8i8FzF-qP4jU`Vxu$osA& zmMutS<57Mkp=x(D!|rRKy|KztJcwD%DtlWGhCLAKDx0^TT9#Eh7Xt8D^(*_?{0?SH zED~YYFA~0hm>G&b#=R{v)BB+NpX_1a1pmbF=V3_b0i)XTj!AIsywvHcd>Apq_`zaE z61eG&G{$XLb6qooRL`Bx)Q zTLp^eUzhMbtBl}*6NzZt$*U9MFWoavHCk?%oWA zy7ZAEQ`-{-0^at9Ab#E?e&J8#m+WhYNf*SbdYSx5*o#QFK6*jQ#3qn`#6FnP$Mn;X zjlT+glf6cP3wHGTX83t`dYn$8CkVxU(JA?mFSB;+iCLG)V$F6!e^}ESK8r7g$cpT4 zrA2~kxJ|QaQBhufo2hgco8sCn4PL9q=Y`YCRk(Ril|kfQtYie7rIQ!_B}16_s-qI= zLJDE);tnY-vMZW&d|r5ipTy-+{^VDaaGEjPBcu4CaelEEz?sPezZH7RF*)&uVnsu< zH;d0XrIv(BXCL?aVpi(suWyfNzH#2gBNL%Jo9=S$#HGDX;UPUAUV*AwF4zjf#rnLemO1(AR7%v zL<><;*yNm;r?Ual>?8cbVO+WN_v(^T5+{|NCXZQ09 z_9yq$bi8x)zgg_Z6Q6YT-qQT;>aYONAnz>xhqwE8F8|B(fxHK%?{mTb?xR#eTC(>& zFoS&!rgu$qK|@+{q9Z(3K0<^Zs-;*VC1CQo-oU18)>fOBqyw`Bx}S{=xZJTIY=fcP zbWs(4Lk9Oiu{z^|upPS^1A{g=Df{d%3W0)re0WrH0*jF9h|O>mvVs^qzStA6d$N0YHFvUr z82t7;@T|@GrE!DWhL^5fwP6G?*q7!E(f8pV&)4&9z~bfUrD4~>@oUh^6JqcNYg)@r zZtl~F?MPZ*oBA4!?ZZ&g+@nd=R@702=$-4)?)KHaB-?`M`m&o-O=C0nss_7GM_>Qp zNK(nju9fq{i-~*75|%n$1v>V;@7u}Y>Fd<;*skX28ufgKZ-=LAQ*%>KZ$ZgX$(U~L zR8K(K$j((oL&?qd49nR|!4Y~AlyCXN_r0^z3x*wE+e{}%=O&%Cigqiw#He~p8(m(! z-Q2$2xV+n!4Ws@W(WBicD*MeEinlYGp&&BN*Cn+(TdXkIexsK8fsG0tU-oC+4KlW& z`3}je@s6Vcn@id}b2s!IqhF*mOQqlY-?*OdU$4+UCpK`Z(RFySKhNR4&EEuz;%!7h z?faG|`mUnC`BbWVJw9D}xHqX^esp!i-@BTzxM=}QJji~EyCdS0qNQb1R5liJB+H?om;TQ{v1(vA&2Ap zYFXdf@iYF?Zl`Bv+B9rzd*|uqFbeF;IP1m+4YAK^mEjWI+u^`n66h-$^ZcoM0v=w5 zx9@d8pY|nNeaz2af}EC%a@{vzr1 zA%#e$GzOC)SD#{-w{wJzBJQoj?6&Q8F*!_a@9MI6aa?jMO4d^2d9fi46|1u+rkr0U z_bfE?N!UT_*P+sY_#H+ixTzE)^C5j-gkBH4YZEkOB`S}gc3viL=9hgi6v|zUb^O6f z+@42-H&zZIWF_sK@h4^#i`0e+))BfCE{0ah@4lQ`~wdak}JOmN8nFUNN{d z$*y&}pyem1?&#>CUB{_POK{wB42-*SDEp+v%h?7D@dV-+kafrl>%lk+GIBU;+xZOo zNf*@{srX;%DWH1|C+c3&u26oKne}iq{UYfih_`67(AWrm=4203uC4V-ozjVU47Fh2 zTzX`kfH9sxFmo}k{asNeRJw3{E~wwZhCa0=TefZDxN8K{d2yu2-{;!SmT;mH2_2C- zY;ZC%Eq;^MrIQQWKTLb?h`J<;HZ2f6_KYYS(=p+P2}v>rYug?%Tq)5_!de_MmUbsC zDbX8##w-XUT~}9cr1fbIE-?B@u4C04rkwk|GcoW2QE`gffubAWRg6aLAonAedg#HU zy2>9dulY1a30$*BaOHJdW4;+=H`z{%y?4f*9+v{52bV!Awe-#^r?V?{y$=;=1_o;x z>kM;>5;IyPW>YzJYnNYKny4p=YqzbF_L%Hd*s%KpoNQ0(kOLJbbkcP$COK)+tdN4o zrB}B;RJ*kPsTO=eM`dDl*Vq`Ej*L-l(~C<&Bkq!x`7uIg+|ylsazbaE0l2;*MS$b5 z8!8Ti>rWIJ>ejjyoGnGA*{@6{)1FAN$+d_*1jJj_M=?V4zh$=@_1gS z-{$53Df^y9Uw_10Wv)Yknf1;Nver}M^U}DO3NQp5+w)shk`#(nM&BQQ$>UO6=^1zl z?R(7_+!mE7jZOaaBS|ZvCsbgEIUtRHQf?Q}N(vhEd6a|)tOD6+jj)@+INf4Y1H!hX3Eq#xYmeFRHQ9rxFsE+W6 zRa-!-LHL%8n5W;`H+6p3&cwm2KZCZyPVG$0Jcc>KaZZvD7RX5-AeG6-l5S$FFQ`>_ z5G{^t=oZkImYr+(v@K%CrlhHPT1sEFUSpwu36G?>Z`2yZ-sg9tun-KiqH@|fbpUhe zZ(t2-Q8zfN&dulAAZ`fz@T%f^w!qBg$J?CtN+vOwzX{{Kg@Z<qD}l}f5ukU{+VNIr)8Db@6n&ln9Es-$AUK8NNm(O-HnA7gOO*)p&4+_*V=KS*+_ z0scmwQ+dCCZP(<)#WnPk$xbleCuBlVpm}nNPqlkVi+t2=sEr?QOIi(HsU1wcznwX< zM`(WEIgphcNDNWcEtApR%$zKycU4Va(>$cGI4)1l*-d9htzZ_i8d@*qOdkW`HqBg` z*73-x# zVnTi=yImQqBdOD}p!ZR_4kq`<%}vAJ!g> zIKQ>z8X>N;lAH>y0E5%oiOAwo#KEo2lFp!Ye})*a|M1(3|1i5KmQJ}6(NkBXon02h z*bEtK@*UU}*Gg%8D8PF+=I+ItH=3X^#up8aJ~%XKN@<@qkN_@H&*lwJbN0bV{S(LNkRsiT)t?ols4Y}=@+yr<+4q% zrF+O`J`qXQVAOQhJObTRCFdb&5nn3lg2Hx@;xYyiDCZ5a1A9tsraL*cP2#MdjeviB zd8mzXk{8I!Fo<;K2e~r0@`bPJsaf(ZqnOeq^Ha>JM0@gtlfpoRdELDqOhM}>FA|!L zZak91DCO(KGqA=uXGDTol;HcZxoz(1#I6#WD<_^b*hARUiCZ`_MrPg>O7z**Ag_W@ z2q+eT@du6Z0|tgMPp_KFkVQu|AV zxGV`BB>h>!LR6z#XN$Q6Ilu14On&UAfK1r^qbt5;KSIxUjJLPsaKr=Z{L8~@EWV3- zNp;F`iw#snh_@oIyJUVvdfg{6LW}(L3|ABzIE(BWBocYcIL(JowlOU`ccYzaT-go4 zmltL4kKp4~+`j-94iqe!uuC3Jy=j&|5u4*AOvq;n0r>P;j6Nz7n>$Ro zLo90QY`xofjqY5VHIW%v`3P!@E~grKuftnMxb;NcgezrpxcIT( zO6{7hnmeWdL=y>(niscMhkuT-|Hd3bER>r3cp4ypLMtRO0G50< z*asBxtl0DxRTB@*(wag=mCqv5DROM_E@xq;O*Tp<$3!Jv74ixVQVbhFQX$gzEg!#| zO;Ur=h+|?_$fr>lEa@r|sM+nGhLKChENU>EN3r%i@>Y8B<0!XW9MH;kb=MuS{fOm( zA@)Jq(sN`-O5J36GNL_nPl3d5S`8cGtvH zfp^7^=CyV@Wx^#)a-0ZSlB)K2`U{flt{bpSBa!8Orw>n?9`foi_{jQeqpFE0p>g;k zRC+UMLb~PK1joYYe#Kd~Z2Gz#>k|rX-QRriA-XGfMIw$(QS=Hz{zqS>-a13 z*i+2KfzfRuYc_?M%Lo*mj9vnMS%`)zcNUXWyEY9wb8W@r^eX&&_-$RhB>`MpIY#z^ z7TDK>{aextQkMB2UiLj}6Zy;Q>)Pq89jlw@2|&3d@H!?F-GkPF+z)XiEWOs{^Ho&) zb2e^09~vP5Yfd`8bY9<-*TrtbVuAKAye?8j5^F#MQ+Xo)cbD`7$Ziu zbgB32LR7KVZ3d`lO4$lIv>4(}lO!~6?sST*a(BS637JOP+ouaF71p+toyf^gS05~v zw9PS_^`f`?*AWC}3cbmeZ}(k3h~cvee>C&gY1=}0x6o^1`Y$#H3gJb=&XY-MHX8EV z@}+VW!VJY5=UQc$v_wI~-Ljx#vvL%s=q$;a2;i{tviOrpt^FsrC|9kYR`=%{`#Oac z)EvC`%yTMNj5c6=gpRyZD39l_(n(Xk4zYwjVx^1RIUttr*r0-^xU?C&@1`~!WTJ^i zQh6I5x!(Y}zUZC+uW91lXd~z3-SZQ1hz0HWW5SU4k>pyx5oS;^rw5-0?Z`I`7$VEA z&#`IE(G9+=N0ukk5NyDfc?hpwJi&MpJ;xMtNzCiXUqiZNsM>^jQ^;7aA?^lh^;o8P zu`Ac(AppFo;m{~*#_lDUufb}t^iv%&)UlSDs}%Pcu2X#NI%3o{6*>1FXKQ(4P*VGZ{fWJF;OP3B(2I&A3#wr1%!eP48 z*xry`zmm8&c$D6ej?JC1BAyHF=DGi_FbkC-*%N4~mUniRl4bxd!{p>IOJPHlCIm0 zd5!5A%#F0RcK9mbm;)#8XEsWsLF^B_v0Pa};iDQ|Bj}fchncK*O$VvNgI>IZ{~!pL zIIU97)Q0zyMh#Z$>&j-JYg?pakjZTZW}bc;SGNNSO@|%ia36S&j$9VgkH7$+*trM7 zqU`ojJe+8SAndpE(LBW_yP0%9v{px$nQ zhY*t9v?V^*u0g%coDQB0h;(OAFl*2?lne=bbrLcKv%(g#@ZRIebmxKReGAXH)>>KL z@-IX_zCn>+mJ2}%o`xoqtOK}|;ngNQD% z*7DCMei^-c68G_vdMf>O@A0F;=dti|=nhJXBsDqRLQ~V%ag2mNTQieg(JTaNnSogY zQX8&j#m!gzAeSKDFa}FQ^_4rGr_Dl1lbNR%(JGgHK5^nY(#{@xTu1;2kSH^w?9gBV z4+CAlY5g2Q!WOAB_$Z-b+)W&eU@wQo+`1w1d^@vufMZnGBB$u~6>2O4``ruM63Y`*YtR^iioy1jP1Im9zog^N7;LmnVm- zms7pE_HD<53(Z%=VAqlxleWg?^FYG~J1_57_b2g_nYXLXfj6kXTWjh<|JW|`-qMf% zN5cHiwI(MsV{2o&KfnK6W;#|M3&UnZ?LdFzg>!U$X4#1%S>K$nid!Q#%819Qt3Q@k zVPcGJ#YO=o;kZ#C|B;s@V9Omp%?AeGb{z#nTzh~wMK-obRJKc;W+kEF0v{&&+E!3- zm+9ki<#aLKmh2BH)>sM{`g$(;C79Wme3}f>EOZ_al^4-S) z$$AKSU=i#=$SOM#Pn=_g@>3r)Fs8B7gxzn0G<-m;o9O$e0UX?b_2f@fc?xA1M6vfe z{swZM-i!o9$M6XfzMe&`vRe!>0`TGF8>+=sB-vFvJ=FpsLHi1)xCG0W`k4$|pSL}y z@5qsneas$6UiQ!%=sr!UkP7WWstej=y)iaP>3OM5IbI%gSxn4Ft%4cr{P zXmr$17l4>C`zPerFLE9w*hK5Y%RSCzx2T>ek9=C6)YYzO!Yz&pTF6rJtpwu1HE#;T zR`65sX!QhVm=u^EEo7nUYW6Hhp6JLmTwBTsi90j`X@lx4T$`5BjJo$DQP$xC_}gMB zCgh{xOO6#3rPK)7b~VCJ8F>I-K^2I_w}<-RWGA7k8^g#sHhWh{W}uO6fyktKjY<^o z63X`#JbthFMBnP^8Gj^b>xHUeE8Myn^bSeYKT~DRvEkEYa(lj>A6x}@aQj~GKlJEU zH`P%}+CY&gDxS_o>At zp>KHK?8!#qF0bI=CZ7|8R-Kn`8J>}b>H8r(U4Zar^wJCT#_}QUyA+;|41(%t;vaT9 zSDtjQ;HdROw0`NZTx!OGAw|3WBWASn#|j)m3@o_qVMae0 z9ele)Nz3Vog*?7dTs<062TK0p48FnQ@Av?>gYfiOyO%Xq(qVtPDGY-thTCN^Lhg&> zvQ+F~uMa5#fpCm#fH=BW)Do8vw;+yOHN$EHOnvu@31K6|Pm9!evXDpPaonob@RT+@ zbSMAHFyrMf^^0|5p-fzyS49cSEf|VU;r$q%4Lpu&lln{}drecSgn9|M#}cJfgX79K z>3Sf>vBj426b?zyRK|A~@z#~5w)XyRpU6XzHhw%{39U(Jv+t%Wd1OQ)NN=)$?&AFn zo1s{M*r$(e=@37PfL1q6^7wS>rEN#$V_P$zr@PL5(hiR4Wr2x*+i*MfQQp%3i#`zg z104FAe+b&EmQY5ChSh0&+F}|jA{eTON*hYt&xpQ>&}y=0*Wu5uAdZj_QJNP|@tkSo z#(P43H86L0)RrD*nX8?4v89gl?#hljbN6pg#U?X4JQc>{mMK>n{WrHa{1z##UVg)* zXP5h#vaMCSOa$?#BM^Np0#%rDF-=uDo+?YtS41WYWQ=xsIEPIlFOp?go z*Wf-|FPlB`*;jH^Pl6<0n!(VQGQpO2#*o)V5J1&24b)jmQJZp7o020C3u!mw#lFg+kxpY0ujkln2@Z|kCaq#vX{%| zq0R!jfs%;X@&RQZqi4YlvWaL`6Fo<<(FIdH)8^h)KM@nXI#?*4Q!7qp7?L3-*)zVE zMwiAn0iJmZC&!vf_3K9-jh$3JD!erNk4{{JZj4<-=D;-!`Aiu+zb(abyVv5r4ct=V zC7kXyyojhaFwQ+Tq#tT(bW~80p(SAuT2D@#OU1P(W8+L>=|7DurM|n8w6n7BJ^%K72 zQgF7KGSB8khQ^`XlC}u}dCpy;b!*l;46KWu=KCn4w0f&d&$pTy`ITBGYG^pwS=M`N zXAySpi*hpF!HiK2XFlp9iH!Tl;nmhT6DU`|FCKQj>;($@asswVMC6at*n{z`dSR<^ z>JiWztsG=DZ$1=OP-_y4H1Sya9Uqkf6ta=(OM+Z5R7PGZwGN#r5jXW>KXis-`X~u$(!os9V~t_tz9gFOzODF!P{hV zCy(bjgLKL?&)_}QDyMM1oVO9dBP`F^$Q`kLsB>u0gtj0t_Q_Q*gi4U$Dr~@h$$G)3 zGSu6p@HT1(+*!2Lzx{2FA2Y}eRp33x|NNfghyREBb#!vKGIsnUzcZ?$Z97Ac>Mgp> ztL8ItS@okAe`XS3+4 zRPrc2_2Ep8$CdQR5109|5^*$8#btQ0ICZa5P=#}3WEnT;y#BiyEXB;|Uyq8bjW}Ks zPP?@miSc3p55{6XKRvqIS{fdM#Ij2c{L~-pu#zNFA$Kk4r2Xmq3gNph!<2N5O_KPw z^i{FgHYWY-D(@GiceL#DVn7b?9WsQG`JZqtyO&g$TFQw1FAQxFO0yL`7s)Vs*Rixm za!r{Y)x&L^>ZI)wA@nPu87)71uT4wHUmyJ9H+{os2(bOiw&R7|w;tUeZ3DDO>7vBy zcOAg$Cdp=ewCtIVYoU^k^!dpB#+S=ZRcbZYjA9<5Gyg(8>Y}Dsokc@~`~{Zl8b-fF zT(tbD6SqMEUGAnptIB*TZ8~{o8c=L9H|`TrT!v^2rzC=f9n9yFhi(PxM=i)wzoM26WOf4i9wzkVH8U^1+jDlBNgR4% z#WepCP5U5N_XW7yqa6&(;|GCMrFIwdw4^ysNnzGO5Rr}ZM6paU*51XhIiSL7_1&Sz zfonpa_hh7s1`iRf@{t$X#Uh|Rj<`8VV9$u}wodFEYDJB`)jlB0ti^Pd{(+|>GFMrI5XBVLf`5)NQZe_;X4Rp{P$i7qQzw@ezkndM%Qry|)mCGXZdFEWlTV(r$Y#1n$73)-C-qi)Q`VauJva9-~95DrtZVe>f; zC`?|^OJN_ML_*{+onTDckY*~1DvM4^DK98mN=>}d9Co0F0Xm<#6=1O5fi*=-tR#G= z^s+72?JT}#J!Ro@qHfq1;kbf$yzm(~F2L9astb~Y_yUJXnP&gZn<)xQ%J~N{aFyds zQ6+c;e?q)heSbVB3jw?hmE-wbK^_o1gGrE&w}?NPPJeCrfXA0jcXA3U_k4iAfySQ+ zjpO~rl8I&zNZq2_z;K<6JKVJ>V_kSK^5asaoUMe5qqbIA%>Pji3#!`#o@TiE#+Vuk z#=lit8@5yl_OXY^WJpWOG>I4Zqx;2`gwZGL8TaoL&t=Uh+4Zh)fp_H-{X_A8R6qPP zq5Y3?h`-X>e-=XoMskUa4VMvqVLQdJ~OQ8dr5CGk*q`k{v~?8(w%3+qc=s9HLix-;sZ-l_qd+zRTi z$C2K6Uu<$a#>Flt0>wF^^>}i`I0l7JF25S^AGzLUT6!aZ=Ub1CT;0O_od#<02o3w+ zpPm{G03iE^2JGH#&dJz8(b&o9596cz?V5qsz})6IenN6Z4`ZOi+UdwcUVpQ%CmL5s z!^(WsMbW&vjEI3iyl(`-cnm*FT%4$S2y(k)3vb(AH0lY=Wu3qO6+rjsZO|9dMQ(+@ z<*u9gh4<>GH*alJ82DKX!Oj5fH zFp#6A(iwa9+0T6Ty7#ykdAv~VPZvk1Ytd1ldOZ{h>kwZ;^8MWE+t1*{wx-x=y}?y5@$$(^TD@l3C=_0t<0;*qR_w%Gb!2;I zvqTAK9t=McdAV?2J%ook-Hs+I$3(ndor+u*7&|i^9i4*>`NF5nQdT{02-*+CyX0&T z%kH-1{gG#Uj7i|ZAGSp_hrHOAX;{O3D`_^vqp_*Gn7Y37(9pAjA>qdOBZ^&_A0gng z1F?w7&+Jlv+z%XeN!;!66@;f(UqYd9;_gH)`QL4CuD4jwvr5M?$I*%me&24G+i_H7 zDOYNtLMR-CC|Cu(T26#5!FERD{;II)%JEtJ1k3W*Go_W6qMsVh`08F{=V|dZ;@1!X z_GMKLii)_FryJx1%%SRJt$`)045UWU7?2yIs<#egImMqSd)YE zD>V>Py{^;;iLE!4&Ns}iCJrf$IbMjWpPF6rIE?t|>GmijzJ|l8dmTO1Cl|V#g9-tT zZHa!H;I_D??Slpp3sZN&z(*4Kbz4N&OCb#h#mM0+geZ8akYv1yLXLGdQ==Y7<#g{V z<~Hk@u@#o-7VB~n0_adlb!(y>J~Yd0(g7-Yey_4D9(-9Y?)|yFs}x-6Ttj?o4e&nk zv7m;-z^d@xr*bnPJ?z^-y`FA$ZZ2&?dV_^!L@*1~QNJ5F$p+-%=h4dA2z$)BL-VUpH&joO|n!km(ZFq+BQ=Rgf#Q;dQcN>b!l=;WU8kSgT~9A;;ag<()8{C>Z)) zKY<>o{uYk?-XPek1uN+cSMLbN#UTBK4Eu_oEvMr+n@)=CBbg^|i&1w>km5~Gkg1ng zi<>31&VoCS(#pJ1;RA%s5fA(>p+rq literal 0 HcmV?d00001 diff --git a/Test_Cases/NREL_2p8_127/NREL-2.8-127_pitch-speed.csv b/Test_Cases/NREL_2p8_127/NREL-2.8-127_pitch-speed.csv new file mode 100644 index 00000000..8a37882c --- /dev/null +++ b/Test_Cases/NREL_2p8_127/NREL-2.8-127_pitch-speed.csv @@ -0,0 +1,31 @@ +mps,pitch,speed +3,0,5 +3.889649963,0,5 +4.684006997,0,5.638983608 +5.377830234,0,6.474263714 +5.966542092,0,7.183002305 +6.446258474,0,7.760523392 +6.813814392,0,8.20301671 +7.066784852,0,8.507562856 +7.203500851,0,8.67215255 +7.223060389,0,8.695699891 +7.320786359,0,8.813350259 +7.535153079,0,9.071422123 +7.864746237,0,9.468212823 +8.307391303,1.972625303,10.00110448 +8.860167873,3.729032675,10.66658129 +9.519428937,5.277405528,11.46025268 +10.28082494,6.571034001,12.0388027 +10.68187298,7.135654103,12.0388027 +11.13933248,8.260696288,12.0388027 +12.08928745,10.26526353,12.0388027 +13.1244224,12.14867141,12.0388027 +14.23790791,13.95715081,12.0388027 +15.42239763,15.71431664,12.0388027 +16.67007674,17.45490652,12.0388027 +17.97271352,19.14151062,12.0388027 +19.32171368,20.8231505,12.0388027 +20.70817701,22.44383927,12.0388027 +22.12295617,24.03032967,12.0388027 +23.55671697,25.61093372,12.0388027 +25,27.13341342,12.0388027 diff --git a/Test_Cases/NREL_2p8_127/NREL-2p8-127.fst b/Test_Cases/NREL_2p8_127/NREL-2p8-127.fst new file mode 100644 index 00000000..c177d10c --- /dev/null +++ b/Test_Cases/NREL_2p8_127/NREL-2p8-127.fst @@ -0,0 +1,71 @@ +------- OpenFAST INPUT FILE ------------------------------------------- +Generated with AeroElasticSE FAST driver +---------------------- SIMULATION CONTROL -------------------------------------- +False Echo - Echo input data to .ech (flag) +"FATAL" AbortLevel - Error level when simulation should abort (string) {"WARNING", "SEVERE", "FATAL"} +300.0 TMax - Total run time (s) +0.005 DT - Recommended module time step (s) +2 InterpOrder - Interpolation order for input/output time history (-) {1=linear, 2=quadratic} +0 NumCrctn - Number of correction iterations (-) {0=explicit calculation, i.e., no corrections} +99999.0 DT_UJac - Time between calls to get Jacobians (s) +1000000.0 UJacSclFact - Scaling factor used in Jacobians (-) +---------------------- FEATURE SWITCHES AND FLAGS ------------------------------ +1 CompElast - Compute structural dynamics (switch) {1=ElastoDyn; 2=ElastoDyn + BeamDyn for blades} +1 CompInflow - Compute inflow wind velocities (switch) {0=still air; 1=InflowWind; 2=external from OpenFOAM} +2 CompAero - Compute aerodynamic loads (switch) {0=None; 1=AeroDyn v14; 2=AeroDyn v15} +1 CompServo - Compute control and electrical-drive dynamics (switch) {0=None; 1=ServoDyn} +0 CompHydro - Compute hydrodynamic loads (switch) {0=None; 1=HydroDyn} +0 CompSub - Compute sub-structural dynamics (switch) {0=None; 1=SubDyn; 2=External Platform MCKF} +0 CompMooring - Compute mooring system (switch) {0=None; 1=MAP++; 2=FEAMooring; 3=MoorDyn; 4=OrcaFlex} +0 CompIce - Compute ice loads (switch) {0=None; 1=IceFloe; 2=IceDyn} +0 MHK - MHK turbine type (switch) {0=Not an MHK turbine; 1=Fixed MHK turbine; 2=Floating MHK turbine} +---------------------- ENVIRONMENTAL CONDITIONS -------------------------------- + 9.80665 Gravity - Gravitational acceleration (m/s^2) + 1.225 AirDens - Air density (kg/m^3) + 0 WtrDens - Water density (kg/m^3) + 1.464E-05 KinVisc - Kinematic viscosity of working fluid (m^2/s) + 335 SpdSound - Speed of sound in working fluid (m/s) + 103500 Patm - Atmospheric pressure (Pa) [used only for an MHK turbine cavitation check] + 1700 Pvap - Vapour pressure of working fluid (Pa) [used only for an MHK turbine cavitation check] + 0 WtrDpth - Water depth (m) + 0 MSL2SWL - Offset between still-water level and mean sea level (m) [positive upward] +---------------------- INPUT FILES --------------------------------------------- +"NREL-2p8-127_ElastoDyn.dat" EDFile - Name of file containing ElastoDyn input parameters (quoted string) +"none" BDBldFile(1) - Name of file containing BeamDyn input parameters for blade 1 (quoted string) +"none" BDBldFile(2) - Name of file containing BeamDyn input parameters for blade 2 (quoted string) +"none" BDBldFile(3) - Name of file containing BeamDyn input parameters for blade 3 (quoted string) +"NREL-2p8-127_InflowFile.dat" InflowFile - Name of file containing inflow wind input parameters (quoted string) +"NREL-2p8-127_AeroDyn15.dat" AeroFile - Name of file containing aerodynamic input parameters (quoted string) +"NREL-2p8-127_ServoDyn.dat" ServoFile - Name of file containing control and electrical-drive input parameters (quoted string) +"none" HydroFile - Name of file containing hydrodynamic input parameters (quoted string) +"none" SubFile - Name of file containing sub-structural input parameters (quoted string) +"none" MooringFile - Name of file containing mooring system input parameters (quoted string) +"none" IceFile - Name of file containing ice input parameters (quoted string) +---------------------- OUTPUT -------------------------------------------------- +False SumPrint - Print summary data to ".sum" (flag) +10.0 SttsTime - Amount of time between screen status messages (s) +99999.0 ChkptTime - Amount of time between creating checkpoint files for potential restart (s) +default DT_Out - Time step for tabular output (s) (or "default") +0.0 TStart - Time to begin tabular output (s) +1 OutFileFmt - Format for tabular (time-marching) output file (switch) {1: text file [.out], 2: binary file [.outb], 3: both} +True TabDelim - Use tab delimiters in text tabular output file? (flag) {uses spaces if false} +"ES10.3E2" OutFmt - Format used for text tabular output, excluding the time channel. Resulting field should be 10 characters. (quoted string) +---------------------- LINEARIZATION ------------------------------------------- +False Linearize - Linearization analysis (flag) +False CalcSteady - Calculate a steady-state periodic operating point before linearization? [unused if Linearize=False] (flag) +3 TrimCase - Controller parameter to be trimmed {1:yaw; 2:torque; 3:pitch} [used only if CalcSteady=True] (-) +0.001 TrimTol - Tolerance for the rotational speed convergence [used only if CalcSteady=True] (-) +0.01 TrimGain - Proportional gain for the rotational speed error (>0) [used only if CalcSteady=True] (rad/(rad/s) for yaw or pitch; Nm/(rad/s) for torque) +0.0 Twr_Kdmp - Damping factor for the tower [used only if CalcSteady=True] (N/(m/s)) +0.0 Bld_Kdmp - Damping factor for the blades [used only if CalcSteady=True] (N/(m/s)) +2 NLinTimes - Number of times to linearize (-) [>=1] [unused if Linearize=False] +30.000000, 60.000000 LinTimes - List of times at which to linearize (s) [1 to NLinTimes] [used only when Linearize=True and CalcSteady=False] +1 LinInputs - Inputs included in linearization (switch) {0=none; 1=standard; 2=all module inputs (debug)} [unused if Linearize=False] +1 LinOutputs - Outputs included in linearization (switch) {0=none; 1=from OutList(s); 2=all module outputs (debug)} [unused if Linearize=False] +False LinOutJac - Include full Jacobians in linearization output (for debug) (flag) [unused if Linearize=False; used only if LinInputs=LinOutputs=2] +False LinOutMod - Write module-level linearization output files in addition to output for full system? (flag) [unused if Linearize=False] +---------------------- VISUALIZATION ------------------------------------------ +0 WrVTK - VTK visualization data output: (switch) {0=none; 1=initialization data only; 2=animation} +2 VTK_type - Type of VTK visualization data: (switch) {1=surfaces; 2=basic meshes (lines/points); 3=all meshes (debug)} [unused if WrVTK=0] +False VTK_fields - Write mesh fields to VTK data files? (flag) {true/false} [unused if WrVTK=0] +10.0 VTK_fps - Frame rate for VTK output (frames per second){will use closest integer multiple of DT} [used only if WrVTK=2] diff --git a/Test_Cases/NREL_2p8_127/NREL-2p8-127_AeroDyn15.dat b/Test_Cases/NREL_2p8_127/NREL-2p8-127_AeroDyn15.dat new file mode 100644 index 00000000..a3742899 --- /dev/null +++ b/Test_Cases/NREL_2p8_127/NREL-2p8-127_AeroDyn15.dat @@ -0,0 +1,134 @@ +------- AERODYN v15.03.* INPUT FILE ------------------------------------------------ +Generated with AeroElasticSE FAST driver +====== General Options ============================================================================ +False Echo - Echo the input to ".AD.ech"? (flag) +default DTAero - Time interval for aerodynamic calculations {or "default"} (s) +1 WakeMod - Type of wake/induction model (switch) {0=none, 1=BEMT, 2=DBEMT, 3=OLAF} [WakeMod cannot be 2 or 3 when linearizing] +2 AFAeroMod - Type of blade airfoil aerodynamics model (switch) {1=steady model, 2=Beddoes-Leishman unsteady model} [AFAeroMod must be 1 when linearizing] +0 TwrPotent - Type tower influence on wind based on potential flow around the tower (switch) {0=none, 1=baseline potential flow, 2=potential flow with Bak correction} +0 TwrShadow - Calculate tower influence on wind based on downstream tower shadow (switch) {0=none, 1=Powles model, 2=Eames model} +False TwrAero - Calculate tower aerodynamic loads? (flag) +False FrozenWake - Assume frozen wake during linearization? (flag) [used only when WakeMod=1 and when linearizing] +False CavitCheck - Perform cavitation check? (flag) [AFAeroMod must be 1 when CavitCheck=true] +False Buoyancy - Include buoyancy effects? (flag) +False CompAA - Flag to compute AeroAcoustics calculation [only used when WakeMod=1 or 2] +AeroAcousticsInput.dat AA_InputFile - AeroAcoustics input file [used only when CompAA=true] +====== Environmental Conditions =================================================================== +"default" AirDens - Air density (kg/m^3) +"default" KinVisc - Kinematic air viscosity (m^2/s) +"default" SpdSound - Speed of sound (m/s) +"default" Patm - Atmospheric pressure (Pa) [used only when CavitCheck=True] +"default" Pvap - Vapour pressure of fluid (Pa) [used only when CavitCheck=True] +====== Blade-Element/Momentum Theory Options ====================================================== [used only when WakeMod=1] +2 SkewMod - Type of skewed-wake correction model (switch) {1=uncoupled, 2=Pitt/Peters, 3=coupled} [unused when WakeMod=0 or 3] +1.4726215563702154 SkewModFactor - Constant used in Pitt/Peters skewed wake model {or "default" is 15/32*pi} (-) [used only when SkewMod=2; unused when WakeMod=0 or 3] +True TipLoss - Use the Prandtl tip-loss model? (flag) [unused when WakeMod=0 or 3] +True HubLoss - Use the Prandtl hub-loss model? (flag) [unused when WakeMod=0 or 3] +True TanInd - Include tangential induction in BEMT calculations? (flag) [unused when WakeMod=0 or 3] +True AIDrag - Include the drag term in the axial-induction calculation? (flag) [unused when WakeMod=0 or 3] +True TIDrag - Include the drag term in the tangential-induction calculation? (flag) [unused when WakeMod=0,3 or TanInd=FALSE] +default IndToler - Convergence tolerance for BEMT nonlinear solve residual equation {or "default"} (-) [unused when WakeMod=0 or 3] +500 MaxIter - Maximum number of iteration steps (-) [unused when WakeMod=0] +====== Dynamic Blade-Element/Momentum Theory Options ====================================================== [used only when WakeMod=1] +2 DBEMT_Mod - Type of dynamic BEMT (DBEMT) model {1=constant tau1, 2=time-dependent tau1} (-) [used only when WakeMod=2] +2.0 tau1_const - Time constant for DBEMT (s) [used only when WakeMod=2 and DBEMT_Mod=1] +====== OLAF -- cOnvecting LAgrangian Filaments (Free Vortex Wake) Theory Options ================== [used only when WakeMod=3] +NREL-2p8-127_OLAF.dat OLAFInputFileName - Input file for OLAF [used only when WakeMod=3] +====== Beddoes-Leishman Unsteady Airfoil Aerodynamics Options ===================================== [used only when AFAeroMod=2] +3 UAMod - Unsteady Aero Model Switch (switch) {1=Baseline model (Original), 2=Gonzalez's variant (changes in Cn,Cc,Cm), 3=Minnema/Pierce variant (changes in Cc and Cm)} [used only when AFAeroMod=2] +True FLookup - Flag to indicate whether a lookup for f' will be calculated (TRUE) or whether best-fit exponential equations will be used (FALSE); if FALSE S1-S4 must be provided in airfoil input files (flag) [used only when AFAeroMod=2] +====== Airfoil Information ========================================================================= +1 AFTabMod - Interpolation method for multiple airfoil tables {1=1D interpolation on AoA (first table only); 2=2D interpolation on AoA and Re; 3=2D interpolation on AoA and UserProp} (-) +1 InCol_Alfa - The column in the airfoil tables that contains the angle of attack (-) +2 InCol_Cl - The column in the airfoil tables that contains the lift coefficient (-) +3 InCol_Cd - The column in the airfoil tables that contains the drag coefficient (-) +4 InCol_Cm - The column in the airfoil tables that contains the pitching-moment coefficient; use zero if there is no Cm column (-) +0 InCol_Cpmin - The column in the airfoil tables that contains the Cpmin coefficient; use zero if there is no Cpmin column (-) +30 NumAFfiles - Number of airfoil files used (-) +"Airfoils/NREL-2p8-127_AeroDyn15_Polar_00.dat" AFNames - Airfoil file names (NumAFfiles lines) (quoted strings) +"Airfoils/NREL-2p8-127_AeroDyn15_Polar_01.dat" +"Airfoils/NREL-2p8-127_AeroDyn15_Polar_02.dat" +"Airfoils/NREL-2p8-127_AeroDyn15_Polar_03.dat" +"Airfoils/NREL-2p8-127_AeroDyn15_Polar_04.dat" +"Airfoils/NREL-2p8-127_AeroDyn15_Polar_05.dat" +"Airfoils/NREL-2p8-127_AeroDyn15_Polar_06.dat" +"Airfoils/NREL-2p8-127_AeroDyn15_Polar_07.dat" +"Airfoils/NREL-2p8-127_AeroDyn15_Polar_08.dat" +"Airfoils/NREL-2p8-127_AeroDyn15_Polar_09.dat" +"Airfoils/NREL-2p8-127_AeroDyn15_Polar_10.dat" +"Airfoils/NREL-2p8-127_AeroDyn15_Polar_11.dat" +"Airfoils/NREL-2p8-127_AeroDyn15_Polar_12.dat" +"Airfoils/NREL-2p8-127_AeroDyn15_Polar_13.dat" +"Airfoils/NREL-2p8-127_AeroDyn15_Polar_14.dat" +"Airfoils/NREL-2p8-127_AeroDyn15_Polar_15.dat" +"Airfoils/NREL-2p8-127_AeroDyn15_Polar_16.dat" +"Airfoils/NREL-2p8-127_AeroDyn15_Polar_17.dat" +"Airfoils/NREL-2p8-127_AeroDyn15_Polar_18.dat" +"Airfoils/NREL-2p8-127_AeroDyn15_Polar_19.dat" +"Airfoils/NREL-2p8-127_AeroDyn15_Polar_20.dat" +"Airfoils/NREL-2p8-127_AeroDyn15_Polar_21.dat" +"Airfoils/NREL-2p8-127_AeroDyn15_Polar_22.dat" +"Airfoils/NREL-2p8-127_AeroDyn15_Polar_23.dat" +"Airfoils/NREL-2p8-127_AeroDyn15_Polar_24.dat" +"Airfoils/NREL-2p8-127_AeroDyn15_Polar_25.dat" +"Airfoils/NREL-2p8-127_AeroDyn15_Polar_26.dat" +"Airfoils/NREL-2p8-127_AeroDyn15_Polar_27.dat" +"Airfoils/NREL-2p8-127_AeroDyn15_Polar_28.dat" +"Airfoils/NREL-2p8-127_AeroDyn15_Polar_29.dat" +====== Rotor/Blade Properties ===================================================================== +True UseBlCm - Include aerodynamic pitching moment in calculations? (flag) +"NREL-2p8-127_AeroDyn15_blade.dat" ADBlFile(1) - Name of file containing distributed aerodynamic properties for Blade #1 (-) +"NREL-2p8-127_AeroDyn15_blade.dat" ADBlFile(2) - Name of file containing distributed aerodynamic properties for Blade #2 (-) [unused if NumBl < 2] +"NREL-2p8-127_AeroDyn15_blade.dat" ADBlFile(3) - Name of file containing distributed aerodynamic properties for Blade #3 (-) [unused if NumBl < 3] +====== Hub Properties ============================================================================== [used only when Buoyancy=True] +0.0 VolHub - Hub volume (m^3) +0.0 HubCenBx - Hub center of buoyancy x direction offset (m) +====== Nacelle Properties ========================================================================== [used only when Buoyancy=True] +0.0 VolNac - Nacelle volume (m^3) +0,0,0 NacCenB - Position of nacelle center of buoyancy from yaw bearing in nacelle coordinates (m) +====== Tail fin Aerodynamics ======================================================================== +False TFinAero - Calculate tail fin aerodynamics model (flag) +"unused" TFinFile - Input file for tail fin aerodynamics [used only when TFinAero=True] +====== Tower Influence and Aerodynamics ============================================================= [used only when TwrPotent/=0, TwrShadow/=0, or TwrAero=True] +10 NumTwrNds - Number of tower nodes used in the analysis (-) [used only when TwrPotent/=0, TwrShadow/=0, or TwrAero=True] +TwrElev TwrDiam TwrCd TwrTI TwrCb !TwrTI used only with TwrShadow=2, TwrCb used only with Buoyancy=True +(m) (m) (-) (-) (-) + 8.650000000000000e+00 3.999999999999999e+00 5.000000000000000e-01 1.000000000000000e-01 0.0 + 1.730800925925926e+01 4.000000000000000e+00 5.000000000000000e-01 1.000000000000000e-01 0.0 + 2.595800925925926e+01 4.000000000000000e+00 5.000000000000000e-01 1.000000000000000e-01 0.0 + 3.461601851851852e+01 3.953273204469021e+00 5.000000000000000e-01 1.000000000000000e-01 0.0 + 4.326601851851852e+01 3.712118013878008e+00 5.000000000000000e-01 1.000000000000000e-01 0.0 + 5.191601851851851e+01 3.433099970059946e+00 5.000000000000000e-01 1.000000000000000e-01 0.0 + 6.057402777777778e+01 3.130385763598736e+00 5.000000000000000e-01 1.000000000000000e-01 0.0 + 6.922402777777778e+01 2.796113422345067e+00 5.000000000000000e-01 1.000000000000000e-01 0.0 + 7.787402777777778e+01 2.382646880140990e+00 5.000000000000000e-01 1.000000000000000e-01 0.0 + 8.650000000000000e+01 2.324880163918676e+00 5.000000000000000e-01 1.000000000000000e-01 0.0 +====== Outputs ==================================================================================== +False SumPrint - Generate a summary file listing input options and interpolated properties to ".AD.sum"? (flag) +0 NBlOuts - Number of blade node outputs [0 - 9] (-) +4, 7, 10, 13, 15, 18, 21, 24, 27 BlOutNd - Blade nodes whose values will be output (-) +0 NTwOuts - Number of tower node outputs [0 - 9] (-) +0 TwOutNd - Tower nodes whose values will be output (-) + OutList - The next line(s) contains a list of output parameters. See OutListParameters.xlsx for a listing of available output channels, (-) +"B1Azimuth" +"B2Azimuth" +"B3Azimuth" +END of input file (the word "END" must appear in the first 3 columns of this last OutList line) +====== Outputs for all blade stations (same ending as above for B1N1.... =========================== [optional section] +3 BldNd_BladesOut - Number of blades to output all node information at. Up to number of blades on turbine. (-) +"All" BldNd_BlOutNd - Future feature will allow selecting a portion of the nodes to output. Not implemented yet. (-) + OutList - The next line(s) contains a list of output parameters. See OutListParameters.xlsx for a listing of available output channels, (-) +"Fx, Fy" +"Vx, Vy" +Vrel +TnInd +AxInd +Theta +Phi +Vindx +Vindy +Alpha +Fl +Fd +END (the word "END" must appear in the first 3 columns of this last OutList line in the optional nodal output section) +--------------------------------------------------------------------------------------- diff --git a/Test_Cases/NREL_2p8_127/NREL-2p8-127_AeroDyn15_blade.dat b/Test_Cases/NREL_2p8_127/NREL-2p8-127_AeroDyn15_blade.dat new file mode 100644 index 00000000..fd4b728f --- /dev/null +++ b/Test_Cases/NREL_2p8_127/NREL-2p8-127_AeroDyn15_blade.dat @@ -0,0 +1,36 @@ +------- AERODYN v15.00.* BLADE DEFINITION INPUT FILE ------------------------------------- +Generated with AeroElasticSE FAST driver +====== Blade Properties ================================================================= +30 NumBlNds - Number of blade nodes used in the analysis (-) + BlSpn BlCrvAC BlSwpAC BlCrvAng BlTwist BlChord BlAFID + (m) (m) (m) (deg) (deg) (m) (-) + 0.000000000000000e+00 0.000000000000000e+00 0.000000000000000e+00 0.000000000000000e+00 1.999622705006573e+01 2.565746018075444e+00 1 + 2.119199517912653e+00 0.000000000000000e+00 0.000000000000000e+00 0.000000000000000e+00 1.931018243810786e+01 3.361938565422448e+00 2 + 4.238399035825307e+00 0.000000000000000e+00 0.000000000000000e+00 -2.621743302803628e-03 1.831714953780435e+01 4.045185045024725e+00 3 + 6.357598553737958e+00 -1.939408866995070e-04 0.000000000000000e+00 -6.412784123456707e-02 1.708763041181490e+01 4.534861529323176e+00 4 + 8.476798071650611e+00 -4.743793103448273e-03 0.000000000000000e+00 -1.978684279841359e-01 1.569212712279918e+01 4.750344090758699e+00 5 + 1.059599758956327e+01 -1.483103448275862e-02 0.000000000000000e+00 -3.150569530999122e-01 1.382289586770404e+01 4.737620755206947e+00 6 + 1.271519710747592e+01 -2.804970443349753e-02 0.000000000000000e+00 -4.200820236296363e-01 1.124554309027298e+01 4.683448688307037e+00 7 + 1.483439662538857e+01 -4.590591133004925e-02 0.000000000000000e+00 -5.312359339597873e-01 8.602632953470145e+00 4.602338372007760e+00 8 + 1.695359614330122e+01 -6.734679802955665e-02 0.000000000000000e+00 -6.413089831677180e-01 6.549224739725965e+00 4.505595976960268e+00 9 + 1.907279566121387e+01 -9.334512315270936e-02 0.000000000000000e+00 -7.594874026577699e-01 5.408188380153923e+00 4.380463162058345e+00 10 + 2.119199517912653e+01 -1.235274876847291e-01 0.000000000000000e+00 -8.814019981123943e-01 4.552816793256156e+00 4.183546777131121e+00 11 + 2.331119469703918e+01 -1.585433990147783e-01 0.000000000000000e+00 -1.022348344095032e+00 3.850103071189125e+00 3.945902894366683e+00 12 + 2.543039421495183e+01 -1.991506896551724e-01 0.000000000000000e+00 -1.183293448295596e+00 3.210053831367405e+00 3.702763428157307e+00 13 + 2.754959373286449e+01 -2.460701477832512e-01 0.000000000000000e+00 -1.342781789240282e+00 2.548277995517243e+00 3.476193009639851e+00 14 + 2.966879325077715e+01 -2.984725615763546e-01 0.000000000000000e+00 -1.515812813319435e+00 1.868987870564891e+00 3.235485886652345e+00 15 + 3.178799276868979e+01 -3.581878325123153e-01 0.000000000000000e+00 -1.698337241682368e+00 1.247026288989173e+00 2.994660335764964e+00 16 + 3.390719228660245e+01 -4.240869950738916e-01 0.000000000000000e+00 -1.908238044665007e+00 7.591906266374636e-01 2.774705218558286e+00 17 + 3.602639180451509e+01 -4.993217733990146e-01 0.000000000000000e+00 -2.133886441082087e+00 4.659000465949885e-01 2.591930205580583e+00 18 + 3.814559132242776e+01 -5.819026600985221e-01 0.000000000000000e+00 -2.384324918476038e+00 2.731580237682558e-01 2.424912635092513e+00 19 + 4.026479084034041e+01 -6.756489655172412e-01 0.000000000000000e+00 -2.659453831887105e+00 1.231485664729688e-01 2.273929330687443e+00 20 + 4.238399035825307e+01 -7.785625123152710e-01 0.000000000000000e+00 -2.957313507988756e+00 -1.889923787502366e-02 2.146862384202469e+00 21 + 4.450318987616572e+01 -8.943162068965517e-01 0.000000000000000e+00 -3.294896483624423e+00 -1.841259535939614e-01 2.051800999525918e+00 22 + 4.662238939407835e+01 -1.022164926108374e+00 0.000000000000000e+00 -3.676725314021781e+00 -3.432314804149588e-01 1.991284282831078e+00 23 + 4.874158891199102e+01 -1.166111724137931e+00 0.000000000000000e+00 -4.102651579820645e+00 -5.034899071419768e-01 1.944879951099011e+00 24 + 5.086078842990366e+01 -1.325395270935961e+00 0.000000000000000e+00 -4.585680344442696e+00 -6.944182383563149e-01 1.888109521438915e+00 25 + 5.297998794781633e+01 -1.504970886699507e+00 0.000000000000000e+00 -5.166689492052464e+00 -9.464479611794926e-01 1.795137265041130e+00 26 + 5.509918746572898e+01 -1.707078275862069e+00 0.000000000000000e+00 -5.829761241403034e+00 -1.331448785580028e+00 1.572950482786750e+00 27 + 5.721838698364163e+01 -1.935478029556650e+00 0.000000000000000e+00 -6.607040906671076e+00 -1.857716459023805e+00 1.205686533770803e+00 28 + 5.933758650155428e+01 -2.194745172413793e+00 0.000000000000000e+00 -7.654100340223317e+00 -2.493070572147947e+00 7.343636341297369e-01 29 + 6.145678601946693e+01 -2.500000000000000e+00 0.000000000000000e+00 -8.281837270494590e+00 -3.205330715589577e+00 1.999999999999999e-01 30 diff --git a/Test_Cases/NREL_2p8_127/NREL-2p8-127_Cp_Ct_Cq.txt b/Test_Cases/NREL_2p8_127/NREL-2p8-127_Cp_Ct_Cq.txt new file mode 100644 index 00000000..2268df83 --- /dev/null +++ b/Test_Cases/NREL_2p8_127/NREL-2p8-127_Cp_Ct_Cq.txt @@ -0,0 +1,111 @@ +# ----- Rotor performance tables for the WISDEM tuning wind turbine ----- +# ------------ Written on Jul-01-21 using the ROSCO toolbox ------------ + +# Pitch angle vector, 30 entries - x axis (matrix columns) (deg) +-5.0 -3.793 -2.586 -1.379 -0.1724 1.034 2.241 3.448 4.655 5.862 7.069 8.276 9.483 10.69 11.9 13.1 14.31 15.52 16.72 17.93 19.14 20.34 21.55 22.76 23.97 25.17 26.38 27.59 28.79 30.0 +# TSR vector, 30 entries - y axis (matrix rows) (-) +2.0 2.345 2.69 3.034 3.379 3.724 4.069 4.414 4.759 5.103 5.448 5.793 6.138 6.483 6.828 7.172 7.517 7.862 8.207 8.552 8.897 9.241 9.586 9.931 10.28 10.62 10.97 11.31 11.66 12.0 +# Wind speed vector - z axis (m/s) +10.68 + +# Power coefficient + +0.005733 0.008358 0.010931 0.013451 0.015923 0.018353 0.020747 0.023112 0.025459 0.027794 0.030128 0.032473 0.034841 0.037250 0.039720 0.042275 0.044947 0.047736 0.050369 0.052438 0.053782 0.054536 0.054902 0.055053 0.055070 0.054924 0.054451 0.053413 0.051671 0.049088 +0.010473 0.014052 0.017571 0.021038 0.024463 0.027857 0.031232 0.034602 0.037982 0.041391 0.044855 0.048407 0.052073 0.055894 0.059917 0.063725 0.066595 0.068386 0.069435 0.070068 0.070525 0.070875 0.070899 0.070223 0.068520 0.065563 0.061477 0.056461 0.050687 0.044351 +0.016648 0.021451 0.026198 0.030903 0.035583 0.040258 0.044950 0.049690 0.054525 0.059496 0.064610 0.069956 0.075525 0.080323 0.083509 0.085464 0.086777 0.087879 0.088967 0.089747 0.089510 0.087678 0.083964 0.078635 0.072110 0.064721 0.056667 0.048586 0.039467 0.029816 +0.024451 0.030790 0.037088 0.043370 0.049664 0.056017 0.062499 0.069156 0.075949 0.082980 0.090401 0.096848 0.101076 0.103789 0.105878 0.107957 0.110172 0.111665 0.111132 0.107849 0.102059 0.094460 0.085644 0.075982 0.066327 0.055369 0.043639 0.032509 0.020157 0.007204 +0.034042 0.042277 0.050504 0.058774 0.067185 0.075810 0.084575 0.093427 0.102846 0.111995 0.118495 0.122686 0.126019 0.129475 0.133430 0.136352 0.136037 0.131773 0.124323 0.114686 0.103692 0.091818 0.079871 0.066581 0.053315 0.038287 0.023162 0.007449 -0.008632 -0.024586 +0.045585 0.056130 0.066777 0.077664 0.088762 0.099834 0.111077 0.123170 0.133767 0.140785 0.145956 0.151011 0.157146 0.162829 0.164232 0.160094 0.151678 0.140464 0.127481 0.113476 0.099240 0.083738 0.067897 0.050473 0.032437 0.013439 -0.006199 -0.025342 -0.045516 -0.065143 +0.059260 0.072709 0.086474 0.100339 0.113961 0.127912 0.142939 0.155463 0.163934 0.171005 0.179040 0.188615 0.194301 0.192393 0.184326 0.172304 0.157818 0.142304 0.125481 0.108163 0.089149 0.070050 0.048899 0.026622 0.003778 -0.018932 -0.042759 -0.066818 -0.089995 -0.111563 +0.075452 0.092497 0.109469 0.125954 0.142837 0.161240 0.176710 0.187609 0.197446 0.209785 0.222490 0.226531 0.221214 0.209858 0.194803 0.177987 0.159296 0.139878 0.119164 0.097278 0.073947 0.048842 0.022621 -0.004023 -0.031153 -0.059069 -0.087357 -0.114578 -0.140484 -0.164736 +0.094511 0.115022 0.134762 0.154737 0.176972 0.196672 0.211032 0.224473 0.242210 0.257277 0.259309 0.251325 0.237445 0.219974 0.200798 0.179364 0.157090 0.133189 0.107637 0.080632 0.051709 0.021678 -0.009667 -0.041001 -0.073080 -0.105950 -0.138447 -0.169104 -0.197971 -0.224775 +0.115766 0.139262 0.162531 0.188762 0.214007 0.233062 0.250893 0.274820 0.291963 0.292630 0.283030 0.267459 0.248387 0.227009 0.203460 0.177863 0.150485 0.121761 0.090582 0.058077 0.023979 -0.011436 -0.047266 -0.084214 -0.121988 -0.160064 -0.196335 -0.230319 -0.262503 -0.292769 +0.138202 0.165180 0.195145 0.226872 0.252196 0.275177 0.305983 0.325658 0.326244 0.316157 0.300345 0.280365 0.256598 0.230927 0.201729 0.171679 0.139290 0.105344 0.069408 0.031095 -0.008598 -0.049591 -0.091288 -0.133915 -0.178094 -0.220525 -0.260789 -0.299211 -0.335296 -0.368913 +0.161551 0.194903 0.233072 0.266466 0.295512 0.333944 0.357168 0.359266 0.350611 0.334697 0.314121 0.289567 0.260693 0.230418 0.196940 0.161915 0.124757 0.085182 0.042894 -0.000790 -0.046411 -0.092800 -0.140820 -0.191037 -0.240613 -0.287931 -0.333389 -0.376354 -0.416036 -0.453961 +0.187222 0.230589 0.273386 0.309857 0.356719 0.384733 0.390248 0.383896 0.370565 0.350414 0.324413 0.295499 0.262058 0.226919 0.188856 0.149185 0.106270 0.060944 0.012546 -0.037082 -0.088941 -0.142059 -0.197711 -0.254659 -0.309941 -0.363301 -0.414317 -0.461320 -0.506034 -0.548809 +0.218182 0.270155 0.315870 0.371977 0.406056 0.416968 0.415541 0.404376 0.386195 0.360803 0.331422 0.297575 0.260704 0.220885 0.178443 0.132842 0.084899 0.032868 -0.022005 -0.078304 -0.136540 -0.197173 -0.261078 -0.325020 -0.387095 -0.447192 -0.502963 -0.555496 -0.605861 -0.653204 +0.254532 0.310663 0.376823 0.417704 0.436754 0.440281 0.435650 0.419393 0.397694 0.368784 0.336011 0.298185 0.257418 0.212716 0.165233 0.114373 0.059332 0.000710 -0.060597 -0.123897 -0.189821 -0.259087 -0.331270 -0.402899 -0.472743 -0.538898 -0.600642 -0.659473 -0.715589 -0.767490 +0.291345 0.362540 0.414077 0.442759 0.456364 0.457699 0.448489 0.431127 0.405674 0.375079 0.338260 0.297381 0.251595 0.202536 0.149608 0.092156 0.031270 -0.034407 -0.103383 -0.174606 -0.248877 -0.327443 -0.408776 -0.488867 -0.566514 -0.639447 -0.707853 -0.773526 -0.835768 -0.891588 +0.334267 0.392389 0.429122 0.454490 0.467414 0.468861 0.458486 0.439783 0.413047 0.379503 0.339810 0.294277 0.244514 0.190251 0.131042 0.067919 -0.000899 -0.074042 -0.150532 -0.230353 -0.313772 -0.402998 -0.493743 -0.583001 -0.669214 -0.748849 -0.825066 -0.898389 -0.966410 -1.025596 +0.357581 0.399673 0.430692 0.453633 0.471348 0.474079 0.465908 0.446519 0.418911 0.382644 0.339619 0.290170 0.235615 0.175506 0.110900 0.039947 -0.035948 -0.117185 -0.202556 -0.291136 -0.385516 -0.485608 -0.586336 -0.686466 -0.780338 -0.868234 -0.953223 -1.034163 -1.107681 -1.169678 +0.359089 0.395909 0.422920 0.446887 0.467916 0.476719 0.470246 0.452129 0.422792 0.384528 0.337886 0.284550 0.224670 0.159553 0.087437 0.009559 -0.074879 -0.164757 -0.258939 -0.357948 -0.463740 -0.575130 -0.688215 -0.798454 -0.900816 -0.998198 -1.092491 -1.181114 -1.259757 -1.324162 +0.352122 0.384922 0.412733 0.437293 0.459923 0.475065 0.473237 0.455603 0.425796 0.384974 0.335221 0.277195 0.212880 0.140688 0.062025 -0.024286 -0.117337 -0.216450 -0.320583 -0.430204 -0.548805 -0.673230 -0.799147 -0.919437 -1.031241 -1.139238 -1.243211 -1.339491 -1.422841 -1.489579 +0.337476 0.371192 0.400519 0.426291 0.450198 0.470638 0.473926 0.458015 0.427354 0.384641 0.331021 0.269346 0.198533 0.120306 0.033570 -0.061171 -0.163388 -0.272615 -0.386793 -0.509148 -0.641390 -0.779702 -0.918883 -1.049570 -1.172336 -1.291740 -1.405715 -1.509537 -1.597202 -1.666605 +0.318547 0.355113 0.386350 0.414679 0.439769 0.463178 0.472160 0.458769 0.428164 0.383342 0.326610 0.259227 0.183042 0.097321 0.002524 -0.100828 -0.213043 -0.332841 -0.458853 -0.594695 -0.741354 -0.895436 -1.047980 -1.189453 -1.324645 -1.456077 -1.580322 -1.691499 -1.783230 -1.855996 +0.296861 0.336357 0.371125 0.401227 0.428782 0.453625 0.468379 0.458572 0.427993 0.381040 0.320153 0.248295 0.165371 0.072165 -0.031080 -0.144120 -0.266822 -0.398094 -0.536575 -0.686751 -0.849789 -1.020458 -1.186248 -1.339816 -1.488593 -1.632618 -1.767333 -1.885639 -1.981441 -2.058554 +0.272813 0.316283 0.353808 0.387167 0.416653 0.443733 0.462868 0.457131 0.426821 0.377287 0.313149 0.235527 0.145893 0.044924 -0.067233 -0.190687 -0.324377 -0.467771 -0.619850 -0.786143 -0.967008 -1.154934 -1.333959 -1.501288 -1.664564 -1.821724 -1.967047 -2.092251 -2.192423 -2.275093 +0.246069 0.293978 0.335450 0.371711 0.404252 0.432681 0.455569 0.454421 0.424708 0.373151 0.304575 0.221274 0.124762 0.015593 -0.106430 -0.240075 -0.386009 -0.542363 -0.709498 -0.892981 -1.093361 -1.298929 -1.491618 -1.674356 -1.852938 -2.023747 -2.179757 -2.311694 -2.416806 -2.506397 +0.216826 0.269453 0.315238 0.355775 0.390496 0.421499 0.446849 0.450470 0.421163 0.367613 0.294770 0.205703 0.101961 -0.016317 -0.147823 -0.293601 -0.452261 -0.622484 -0.805520 -1.007723 -1.229078 -1.452472 -1.659852 -1.859420 -2.054090 -2.239027 -2.405773 -2.544411 -2.655240 -2.753201 +0.185378 0.242932 0.294130 0.338148 0.376456 0.409645 0.437023 0.444746 0.416677 0.361007 0.283893 0.188900 0.076999 -0.050213 -0.192792 -0.350430 -0.522552 -0.707567 -0.908176 -1.130888 -1.374382 -1.615659 -1.839260 -2.056853 -2.268390 -2.467901 -2.645409 -2.790903 -2.908382 -3.016187 +0.151541 0.215077 0.270909 0.319887 0.361564 0.397134 0.425931 0.437697 0.411248 0.353437 0.271813 0.170258 0.050180 -0.086481 -0.240782 -0.411284 -0.597745 -0.798619 -1.017747 -1.262940 -1.529489 -1.788749 -2.030361 -2.267024 -2.496202 -2.710710 -2.898994 -3.051693 -3.176877 -3.295979 +0.116719 0.184724 0.246682 0.300410 0.345826 0.383484 0.414182 0.429382 0.404775 0.344986 0.258834 0.150170 0.022144 -0.125552 -0.291478 -0.476005 -0.677661 -0.895479 -1.134529 -1.404210 -1.694559 -1.972164 -2.233589 -2.490305 -2.737888 -2.967794 -3.166880 -3.327314 -3.461362 -3.593163 +0.083160 0.153221 0.220860 0.279749 0.328690 0.369159 0.401864 0.419718 0.397476 0.335735 0.244382 0.129245 -0.008566 -0.166737 -0.345714 -0.544710 -0.762454 -0.998353 -1.258854 -1.554935 -1.869688 -2.166410 -2.449315 -2.727062 -2.993813 -3.239497 -3.449471 -3.618299 -3.762458 -3.908311 + + +# Thrust coefficient + +0.092617 0.091973 0.091282 0.090551 0.089789 0.089009 0.088223 0.087443 0.086683 0.085957 0.085280 0.084668 0.084140 0.083714 0.083409 0.083241 0.083187 0.083136 0.082900 0.082292 0.081228 0.079766 0.078062 0.076284 0.074489 0.072639 0.070589 0.068103 0.065041 0.061235 +0.107807 0.107099 0.106370 0.105637 0.104916 0.104226 0.103585 0.103012 0.102531 0.102166 0.101942 0.101882 0.102014 0.102313 0.102613 0.102616 0.102036 0.100793 0.099051 0.097090 0.095137 0.093216 0.091122 0.088501 0.085056 0.080536 0.075010 0.068694 0.061744 0.054369 +0.125690 0.125020 0.124378 0.123788 0.123275 0.122867 0.122595 0.122492 0.122590 0.122922 0.123517 0.124280 0.124878 0.124839 0.123887 0.122169 0.120092 0.118075 0.116232 0.114243 0.111480 0.107417 0.101732 0.094621 0.086475 0.077627 0.068292 0.059385 0.049429 0.039068 +0.146469 0.145968 0.145568 0.145305 0.145219 0.145353 0.145746 0.146440 0.147476 0.148736 0.149769 0.149930 0.148898 0.147006 0.144888 0.143119 0.141664 0.139693 0.136101 0.130177 0.122042 0.112323 0.101588 0.090223 0.079407 0.067285 0.054557 0.043004 0.030260 0.017273 +0.170322 0.170162 0.170211 0.170521 0.171142 0.172124 0.173518 0.175280 0.176969 0.177796 0.177163 0.175410 0.173408 0.172028 0.171348 0.169865 0.165714 0.158160 0.147807 0.135540 0.122189 0.108233 0.094835 0.080132 0.065961 0.050014 0.034389 0.018544 0.003193 -0.010886 +0.197455 0.197860 0.198615 0.199780 0.201413 0.203541 0.205932 0.207836 0.208292 0.207137 0.205373 0.204234 0.204557 0.204565 0.200976 0.192600 0.180449 0.165872 0.149876 0.133238 0.117061 0.099744 0.082616 0.064007 0.045159 0.025713 0.006302 -0.011125 -0.028289 -0.044210 +0.228108 0.229335 0.231075 0.233378 0.236206 0.239147 0.241258 0.241561 0.240420 0.239344 0.240052 0.242465 0.241498 0.233969 0.220968 0.204514 0.186057 0.167281 0.147603 0.127937 0.106751 0.086199 0.063660 0.040417 0.017219 -0.004685 -0.025932 -0.045670 -0.063692 -0.079450 +0.262520 0.264837 0.267792 0.271266 0.274765 0.277277 0.277848 0.277232 0.277418 0.280948 0.284986 0.281401 0.269491 0.252166 0.231752 0.210486 0.187865 0.165132 0.141511 0.117131 0.091777 0.064983 0.037642 0.010798 -0.015186 -0.039683 -0.062267 -0.082642 -0.100832 -0.116042 +0.300899 0.304470 0.308545 0.312661 0.315868 0.317175 0.317479 0.319387 0.326537 0.331420 0.324563 0.308564 0.287341 0.263390 0.239016 0.212699 0.186421 0.158835 0.130094 0.100520 0.069495 0.038176 0.006565 -0.023392 -0.051487 -0.077331 -0.101050 -0.121896 -0.139281 -0.152655 +0.343271 0.347913 0.352697 0.356873 0.359360 0.360881 0.364797 0.376183 0.381530 0.371589 0.352097 0.327447 0.300692 0.272771 0.243417 0.212456 0.180280 0.147567 0.112935 0.077849 0.042129 0.006311 -0.028141 -0.060918 -0.090649 -0.117951 -0.142121 -0.162077 -0.177778 -0.190200 +0.389280 0.394727 0.400026 0.404078 0.407075 0.413055 0.429223 0.435350 0.423077 0.400722 0.374104 0.344727 0.312349 0.279252 0.242837 0.206780 0.169140 0.130977 0.091820 0.051267 0.010784 -0.029060 -0.066758 -0.100984 -0.132612 -0.160509 -0.184044 -0.202810 -0.217522 -0.228949 +0.438633 0.445040 0.450918 0.455672 0.463524 0.485007 0.492799 0.479208 0.455888 0.426352 0.393770 0.358519 0.319308 0.280331 0.238875 0.197193 0.154621 0.110858 0.065544 0.020470 -0.024506 -0.067347 -0.107384 -0.144048 -0.176562 -0.204438 -0.227047 -0.244755 -0.258294 -0.268897 +0.491706 0.499452 0.506279 0.515668 0.542884 0.553453 0.539904 0.515588 0.485998 0.450602 0.410018 0.368368 0.323023 0.277884 0.231163 0.184623 0.136206 0.086882 0.036071 -0.013663 -0.062666 -0.108746 -0.151171 -0.189073 -0.222113 -0.249567 -0.271188 -0.287669 -0.300602 -0.310227 +0.549345 0.558514 0.569279 0.602408 0.616664 0.604690 0.582220 0.550051 0.512271 0.468142 0.422118 0.373239 0.323447 0.272627 0.221194 0.168412 0.115188 0.059566 0.003362 -0.051146 -0.103573 -0.152467 -0.196894 -0.235916 -0.269224 -0.295885 -0.316232 -0.332225 -0.344350 -0.352382 +0.612101 0.624375 0.664085 0.681142 0.674153 0.650222 0.621076 0.578484 0.533557 0.482845 0.431122 0.376532 0.321741 0.265249 0.208409 0.150399 0.090234 0.028797 -0.032224 -0.091118 -0.147230 -0.198731 -0.244615 -0.284679 -0.317626 -0.343032 -0.363010 -0.378328 -0.389183 -0.395374 +0.681140 0.722494 0.744937 0.741819 0.723240 0.692359 0.650892 0.603471 0.550332 0.495575 0.437299 0.378355 0.317265 0.255902 0.193374 0.128796 0.063320 -0.003921 -0.070382 -0.133867 -0.193205 -0.246832 -0.294513 -0.334907 -0.366839 -0.391968 -0.411381 -0.425701 -0.435248 -0.438943 +0.784148 0.809192 0.808836 0.792982 0.766161 0.727627 0.678346 0.624772 0.566940 0.506098 0.442987 0.377600 0.311662 0.244545 0.175539 0.105591 0.033001 -0.039972 -0.111103 -0.178920 -0.241079 -0.297271 -0.346084 -0.386032 -0.417835 -0.442342 -0.461133 -0.474603 -0.482332 -0.482920 +0.878798 0.878837 0.863060 0.835105 0.802967 0.756008 0.703552 0.644299 0.581942 0.515391 0.446747 0.375978 0.304277 0.230822 0.156465 0.079145 0.000687 -0.078083 -0.154487 -0.225874 -0.291394 -0.349551 -0.398730 -0.438965 -0.470211 -0.494454 -0.512604 -0.524870 -0.530317 -0.527179 +0.954018 0.939321 0.909436 0.873286 0.832514 0.783431 0.725750 0.663095 0.594833 0.523420 0.448910 0.372835 0.294905 0.216166 0.134425 0.050923 -0.034393 -0.118873 -0.199777 -0.275311 -0.343458 -0.403080 -0.453308 -0.493210 -0.524351 -0.548257 -0.565667 -0.576443 -0.579083 -0.571691 +1.023567 0.991396 0.952287 0.906521 0.858662 0.807150 0.747584 0.679776 0.607111 0.529975 0.450234 0.367981 0.284931 0.198845 0.110913 0.020042 -0.071681 -0.161822 -0.247543 -0.326338 -0.397314 -0.458714 -0.509404 -0.549186 -0.580227 -0.603771 -0.620315 -0.629247 -0.628527 -0.616549 +1.082395 1.041804 0.991706 0.937500 0.883506 0.829745 0.767582 0.695892 0.617983 0.535899 0.450029 0.362870 0.272561 0.180369 0.084918 -0.012918 -0.111052 -0.207054 -0.296861 -0.379668 -0.453228 -0.515758 -0.566811 -0.606870 -0.637885 -0.661022 -0.676524 -0.683203 -0.678594 -0.661917 +1.139470 1.088591 1.028946 0.968630 0.908004 0.850049 0.785703 0.710556 0.628371 0.540937 0.449853 0.355602 0.259321 0.159705 0.057014 -0.047554 -0.152331 -0.253888 -0.348541 -0.434946 -0.510661 -0.574581 -0.626062 -0.666337 -0.697360 -0.720024 -0.734260 -0.738241 -0.729302 -0.707987 +1.193356 1.132284 1.066459 0.998428 0.932385 0.868695 0.802509 0.724743 0.637956 0.545168 0.447725 0.347749 0.244209 0.137366 0.027344 -0.084534 -0.195804 -0.303098 -0.402185 -0.491831 -0.569969 -0.635054 -0.687035 -0.727643 -0.758678 -0.780783 -0.793478 -0.794302 -0.780726 -0.754961 +1.246139 1.176860 1.102810 1.028791 0.956073 0.887434 0.818433 0.738064 0.646836 0.548098 0.445275 0.338296 0.227647 0.113522 -0.003991 -0.123338 -0.241002 -0.353871 -0.457470 -0.550699 -0.630979 -0.697211 -0.749803 -0.790834 -0.821861 -0.843294 -0.854136 -0.851351 -0.832973 -0.803032 +1.297833 1.220927 1.139862 1.058606 0.980276 0.905327 0.833196 0.750616 0.655027 0.550899 0.441477 0.327617 0.209871 0.088199 -0.037295 -0.163462 -0.287985 -0.406413 -0.514793 -0.611346 -0.693698 -0.761096 -0.814426 -0.855942 -0.886923 -0.907540 -0.916195 -0.909382 -0.886156 -0.852355 +1.349499 1.264699 1.176444 1.089146 1.003822 0.923619 0.847140 0.762383 0.662108 0.552546 0.436663 0.315954 0.190856 0.061078 -0.071728 -0.205866 -0.337083 -0.461115 -0.573945 -0.673753 -0.758148 -0.826758 -0.880950 -0.922989 -0.953877 -0.973504 -0.979625 -0.968430 -0.940389 -0.903039 +1.401303 1.308592 1.213895 1.119148 1.027971 0.941861 0.860452 0.772903 0.668581 0.553361 0.431060 0.303363 0.170279 0.032750 -0.108329 -0.249749 -0.387655 -0.517261 -0.634906 -0.737912 -0.824352 -0.894252 -0.949413 -0.991994 -1.022726 -1.041166 -1.044395 -1.028546 -0.995775 -0.955152 +1.452242 1.353400 1.250891 1.149892 1.052236 0.960061 0.872934 0.782638 0.674455 0.553511 0.424528 0.289397 0.148463 0.002987 -0.146530 -0.295534 -0.440250 -0.575517 -0.697662 -0.803821 -0.892330 -0.963626 -1.019849 -1.062972 -1.093473 -1.110511 -1.110480 -1.089791 -1.052396 -1.008724 +1.502155 1.397642 1.288756 1.180858 1.076625 0.977784 0.885198 0.791667 0.679649 0.553086 0.417399 0.274454 0.126013 -0.028498 -0.185977 -0.343001 -0.494588 -0.635562 -0.762201 -0.871489 -0.962109 -1.034918 -1.092283 -1.135935 -1.166113 -1.181520 -1.177866 -1.152220 -1.110323 -1.063759 +1.548197 1.442437 1.326903 1.212074 1.100665 0.995531 0.897392 0.799857 0.684430 0.552127 0.409217 0.259083 0.101756 -0.061061 -0.227233 -0.392126 -0.550655 -0.697385 -0.828511 -0.940928 -1.033720 -1.108161 -1.166734 -1.210891 -1.240644 -1.254176 -1.246561 -1.215880 -1.169616 -1.120255 + + +# Torque coefficient + +0.002876 0.004193 0.005484 0.006749 0.007989 0.009208 0.010409 0.011596 0.012773 0.013945 0.015116 0.016292 0.017480 0.018689 0.019929 0.021210 0.022551 0.023950 0.025271 0.026309 0.026984 0.027362 0.027545 0.027621 0.027630 0.027557 0.027319 0.026798 0.025925 0.024629 +0.004482 0.006014 0.007519 0.009003 0.010469 0.011921 0.013366 0.014808 0.016254 0.017713 0.019195 0.020715 0.022284 0.023919 0.025641 0.027270 0.028499 0.029265 0.029714 0.029985 0.030180 0.030330 0.030340 0.030051 0.029322 0.028057 0.026309 0.024162 0.021691 0.018980 +0.006211 0.008003 0.009774 0.011529 0.013275 0.015019 0.016770 0.018538 0.020342 0.022197 0.024104 0.026099 0.028177 0.029967 0.031155 0.031885 0.032374 0.032786 0.033192 0.033483 0.033394 0.032711 0.031325 0.029337 0.026902 0.024146 0.021141 0.018126 0.014724 0.011124 +0.008085 0.010182 0.012264 0.014342 0.016423 0.018524 0.020667 0.022868 0.025115 0.027440 0.029894 0.032026 0.033424 0.034321 0.035012 0.035699 0.036432 0.036925 0.036749 0.035664 0.033749 0.031236 0.028321 0.025126 0.021933 0.018310 0.014430 0.010750 0.006666 0.002382 +0.010108 0.012554 0.014996 0.017452 0.019950 0.022511 0.025113 0.027742 0.030539 0.033256 0.035186 0.036430 0.037420 0.038446 0.039620 0.040488 0.040395 0.039128 0.036916 0.034054 0.030790 0.027264 0.023717 0.019770 0.015831 0.011369 0.006878 0.002212 -0.002563 -0.007300 +0.012283 0.015124 0.017993 0.020926 0.023916 0.026900 0.029929 0.033187 0.036043 0.037934 0.039327 0.040689 0.042342 0.043873 0.044251 0.043136 0.040869 0.037847 0.034349 0.030575 0.026740 0.022563 0.018294 0.013600 0.008740 0.003621 -0.001670 -0.006828 -0.012264 -0.017552 +0.014614 0.017931 0.021325 0.024745 0.028104 0.031544 0.035250 0.038339 0.040428 0.042171 0.044153 0.046514 0.047916 0.047446 0.045456 0.042492 0.038919 0.035093 0.030945 0.026674 0.021985 0.017275 0.012059 0.006565 0.000932 -0.004669 -0.010545 -0.016478 -0.022194 -0.027513 +0.017154 0.021028 0.024887 0.028635 0.032473 0.036657 0.040174 0.042652 0.044888 0.047693 0.050582 0.051500 0.050292 0.047710 0.044287 0.040464 0.036215 0.031800 0.027091 0.022115 0.016811 0.011104 0.005143 -0.000914 -0.007082 -0.013429 -0.019860 -0.026048 -0.031938 -0.037452 +0.019929 0.024255 0.028417 0.032629 0.037318 0.041472 0.044500 0.047334 0.051075 0.054252 0.054680 0.052997 0.050070 0.046386 0.042342 0.037822 0.033125 0.028085 0.022697 0.017003 0.010904 0.004571 -0.002038 -0.008646 -0.015410 -0.022342 -0.029194 -0.035659 -0.041746 -0.047398 +0.022762 0.027382 0.031957 0.037115 0.042078 0.045825 0.049331 0.054035 0.057406 0.057537 0.055650 0.052588 0.048838 0.044635 0.040005 0.034972 0.029588 0.023941 0.017810 0.011419 0.004715 -0.002249 -0.009294 -0.016558 -0.023985 -0.031472 -0.038603 -0.045286 -0.051614 -0.057565 +0.025454 0.030422 0.035941 0.041785 0.046449 0.050681 0.056355 0.059978 0.060087 0.058229 0.055317 0.051637 0.047259 0.042531 0.037154 0.031619 0.025654 0.019402 0.012783 0.005727 -0.001584 -0.009134 -0.016813 -0.024664 -0.032801 -0.040616 -0.048031 -0.055108 -0.061754 -0.067945 +0.027983 0.033760 0.040371 0.046156 0.051187 0.057844 0.061866 0.062230 0.060731 0.057974 0.054410 0.050157 0.045156 0.039912 0.034113 0.028046 0.021610 0.014755 0.007430 -0.000137 -0.008039 -0.016074 -0.024392 -0.033090 -0.041677 -0.049874 -0.057748 -0.065190 -0.072063 -0.078632 +0.030608 0.037697 0.044694 0.050656 0.058317 0.062897 0.063799 0.062760 0.060581 0.057286 0.053036 0.048309 0.042842 0.037097 0.030875 0.024389 0.017373 0.009963 0.002051 -0.006062 -0.014540 -0.023224 -0.032322 -0.041632 -0.050670 -0.059393 -0.067733 -0.075418 -0.082728 -0.089721 +0.033772 0.041816 0.048892 0.057577 0.062852 0.064541 0.064320 0.062592 0.059778 0.055847 0.051300 0.046061 0.040353 0.034190 0.027621 0.020562 0.013141 0.005088 -0.003406 -0.012120 -0.021134 -0.030520 -0.040411 -0.050309 -0.059917 -0.069219 -0.077852 -0.085983 -0.093779 -0.101107 +0.037408 0.045658 0.055381 0.061390 0.064189 0.064708 0.064027 0.061638 0.058449 0.054200 0.049383 0.043824 0.037832 0.031263 0.024284 0.016809 0.008720 0.000104 -0.008906 -0.018209 -0.027898 -0.038078 -0.048686 -0.059214 -0.069479 -0.079201 -0.088276 -0.096922 -0.105169 -0.112797 +0.040760 0.050721 0.057931 0.061943 0.063847 0.064034 0.062745 0.060316 0.056755 0.052475 0.047324 0.041605 0.035199 0.028335 0.020931 0.012893 0.004375 -0.004814 -0.014464 -0.024428 -0.034819 -0.045810 -0.057189 -0.068394 -0.079257 -0.089461 -0.099031 -0.108219 -0.116927 -0.124736 +0.044620 0.052378 0.057282 0.060668 0.062393 0.062586 0.061201 0.058705 0.055136 0.050658 0.045360 0.039282 0.032639 0.025396 0.017492 0.009066 -0.000120 -0.009884 -0.020094 -0.030749 -0.041884 -0.053794 -0.065908 -0.077822 -0.089331 -0.099961 -0.110134 -0.119922 -0.129002 -0.136902 +0.045638 0.051011 0.054970 0.057898 0.060159 0.060507 0.059464 0.056990 0.053466 0.048837 0.043346 0.037035 0.030072 0.022400 0.014154 0.005098 -0.004588 -0.014956 -0.025852 -0.037158 -0.049204 -0.061979 -0.074835 -0.087614 -0.099595 -0.110814 -0.121661 -0.131991 -0.141374 -0.149287 +0.043905 0.048407 0.051710 0.054640 0.057211 0.058288 0.057496 0.055281 0.051694 0.047016 0.041313 0.034791 0.027470 0.019508 0.010691 0.001169 -0.009155 -0.020145 -0.031660 -0.043766 -0.056701 -0.070320 -0.084147 -0.097626 -0.110141 -0.122048 -0.133577 -0.144413 -0.154028 -0.161903 +0.041317 0.045166 0.048429 0.051311 0.053967 0.055743 0.055529 0.053460 0.049962 0.045172 0.039334 0.032526 0.024979 0.016508 0.007278 -0.002850 -0.013768 -0.025398 -0.037617 -0.050479 -0.064396 -0.078996 -0.093770 -0.107885 -0.121004 -0.133676 -0.145876 -0.157174 -0.166954 -0.174785 +0.038064 0.041867 0.045175 0.048081 0.050778 0.053083 0.053454 0.051660 0.048201 0.043384 0.037336 0.030380 0.022393 0.013569 0.003786 -0.006900 -0.018429 -0.030748 -0.043627 -0.057427 -0.072343 -0.087943 -0.103641 -0.118381 -0.132228 -0.145696 -0.158551 -0.170261 -0.180149 -0.187977 +0.034588 0.038559 0.041951 0.045027 0.047751 0.050293 0.051268 0.049814 0.046491 0.041624 0.035464 0.028147 0.019875 0.010567 0.000274 -0.010948 -0.023133 -0.036140 -0.049823 -0.064573 -0.080497 -0.097228 -0.113791 -0.129153 -0.143832 -0.158103 -0.171594 -0.183666 -0.193626 -0.201527 +0.031074 0.035208 0.038848 0.041999 0.044883 0.047484 0.049028 0.048001 0.044800 0.039886 0.033512 0.025991 0.017310 0.007554 -0.003253 -0.015086 -0.027930 -0.041671 -0.056166 -0.071886 -0.088952 -0.106817 -0.124171 -0.140246 -0.155820 -0.170896 -0.184997 -0.197381 -0.207409 -0.215481 +0.027565 0.031958 0.035749 0.039120 0.042099 0.044835 0.046769 0.046189 0.043127 0.038122 0.031641 0.023798 0.014741 0.004539 -0.006793 -0.019267 -0.032775 -0.047264 -0.062630 -0.079433 -0.097708 -0.116696 -0.134785 -0.151692 -0.168190 -0.184069 -0.198753 -0.211404 -0.221525 -0.229878 +0.024029 0.028707 0.032757 0.036298 0.039475 0.042252 0.044487 0.044375 0.041473 0.036438 0.029742 0.021608 0.012183 0.001523 -0.010393 -0.023443 -0.037694 -0.052962 -0.069283 -0.087200 -0.106767 -0.126841 -0.145657 -0.163502 -0.180941 -0.197620 -0.212855 -0.225738 -0.236003 -0.244751 +0.020486 0.025458 0.029784 0.033614 0.036894 0.039823 0.042218 0.042560 0.039792 0.034732 0.027850 0.019435 0.009633 -0.001542 -0.013966 -0.027739 -0.042730 -0.058812 -0.076106 -0.095210 -0.116123 -0.137230 -0.156823 -0.175678 -0.194071 -0.211544 -0.227298 -0.240396 -0.250867 -0.260123 +0.016964 0.022230 0.026916 0.030944 0.034449 0.037486 0.039992 0.040698 0.038130 0.033035 0.025979 0.017286 0.007046 -0.004595 -0.017642 -0.032068 -0.047818 -0.064749 -0.083106 -0.103486 -0.125768 -0.147847 -0.168309 -0.188221 -0.207578 -0.225835 -0.242079 -0.255393 -0.266143 -0.276008 +0.013445 0.019081 0.024035 0.028380 0.032078 0.035233 0.037788 0.038832 0.036486 0.031357 0.024115 0.015105 0.004452 -0.007673 -0.021362 -0.036489 -0.053031 -0.070853 -0.090294 -0.112047 -0.135695 -0.158696 -0.180132 -0.201128 -0.221461 -0.240492 -0.257196 -0.270744 -0.281850 -0.292416 +0.010049 0.015904 0.021238 0.025864 0.029774 0.033016 0.035659 0.036967 0.034849 0.029701 0.022284 0.012929 0.001906 -0.010809 -0.025095 -0.040981 -0.058343 -0.077096 -0.097676 -0.120894 -0.145892 -0.169792 -0.192299 -0.214401 -0.235717 -0.255510 -0.272650 -0.286463 -0.298004 -0.309351 +0.006954 0.012812 0.018468 0.023393 0.027485 0.030869 0.033604 0.035097 0.033237 0.028074 0.020435 0.010808 -0.000716 -0.013943 -0.028909 -0.045549 -0.063757 -0.083483 -0.105266 -0.130024 -0.156344 -0.181156 -0.204813 -0.228038 -0.250344 -0.270888 -0.288446 -0.302563 -0.314618 -0.326814 + diff --git a/Test_Cases/NREL_2p8_127/NREL-2p8-127_DISCON.IN b/Test_Cases/NREL_2p8_127/NREL-2p8-127_DISCON.IN new file mode 100644 index 00000000..e2bd1347 --- /dev/null +++ b/Test_Cases/NREL_2p8_127/NREL-2p8-127_DISCON.IN @@ -0,0 +1,156 @@ +! Controller parameter input file for the WISDEM tuning wind turbine +! - File written using ROSCO version 2.3.0 controller tuning logic on 07/01/21 + +!------- 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 and/or tower fore-aft motion (for floating) {0: disable, 1: generator speed, 2: tower-top fore-aft motion, 3: generator speed and tower-top fore-aft motion} +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: Immersion and Invariance Estimator, 2: Extended Kalman Filter} +1 ! PS_Mode - Pitch saturation mode {0: no pitch saturation, 1: implement pitch saturation} +0 ! SD_Mode - Shutdown mode {0: no shutdown procedure, 1: pitch to max pitch at shutdown} +0 ! Fl_Mode - Floating specific feedback mode {0: no nacelle velocity feedback, 1: feed back translational velocity, 2: feed back rotational veloicty} +0 ! TD_Mode - Tower damper mode {0: no tower damper, 1: feed back translational nacelle accelleration to pitch angle} +0 ! Flp_Mode - Flap control mode {0: no flap control, 1: steady state flap angle, 2: Proportional flap control, 2: Cyclic (1P) flap control} +0 ! OL_Mode - Open loop control mode {0: no open loop control, 1: open loop control vs. time} +0 ! PA_Mode - Pitch actuator mode {0 - not used, 1 - first order filter, 2 - second order filter} +0 ! PF_Mode - Pitch fault mode {0 - not used, 1 - constant offset on one or more blades} +0 ! Ext_Mode - External control mode {0 - not used, 1 - call external dynamic library} +0 ! ZMQ_Mode - Fuse ZeroMQ interface {0: unused, 1: Yaw Control} + +!------- FILTERS ---------------------------------------------------------- +2.09625 ! F_LPFCornerFreq - Corner frequency (-3dB point) in the low-pass filters, [rad/s] +0.00000 ! F_LPFDamping - Damping coefficient {used only when F_FilterType = 2} [-] +100.00000 ! F_NotchCornerFreq - Natural frequency of the notch filter, [rad/s] +0.00000 0.25000 ! F_NotchBetaNumDen - Two notch damping values (numerator and denominator, resp) - determines the width and depth of the notch, [-] +0.628320000000 ! F_SSCornerFreq - Corner frequency (-3dB point) in the first order low pass filter for the setpoint smoother, [rad/s]. +0.20944 ! F_WECornerFreq - Corner frequency (-3dB point) in the first order low pass filter for the wind speed estimate [rad/s]. +0.17952 ! F_YawErr - Low pass filter corner frequency for yaw controller [rad/s]. +0.20000 1.00000 ! F_FlCornerFreq - Natural frequency and damping in the second order low pass filter of the tower-top fore-aft motion for floating feedback control [rad/s, -]. +0.01042 ! F_FlHighPassFreq - Natural frequency of first-order high-pass filter for nacelle fore-aft motion [rad/s]. +1.74957 1.00000 ! F_FlpCornerFreq - Corner frequency and damping in the second order low pass filter of the blade root bending moment for flap control [rad/s, -]. + +!------- BLADE PITCH CONTROL ---------------------------------------------- +29 ! PC_GS_n - Amount of gain-scheduling table entries +0.086568 0.116114 0.139911 0.160483 0.179061 0.196300 0.212523 0.227992 0.242512 0.256650 0.270553 0.283361 0.296184 0.308667 0.320716 0.332616 0.343903 0.355566 0.366454 0.377409 0.387896 0.398463 0.408845 0.419345 0.429098 0.438839 0.448558 0.458211 0.467708 ! PC_GS_angles - Gain-schedule table: pitch angles [rad]. +-0.013659 -0.011910 -0.010483 -0.009298 -0.008298 -0.007442 -0.006701 -0.006054 -0.005484 -0.004977 -0.004525 -0.004118 -0.003750 -0.003416 -0.003111 -0.002832 -0.002575 -0.002338 -0.002119 -0.001915 -0.001726 -0.001549 -0.001384 -0.001229 -0.001083 -0.000947 -0.000818 -0.000696 -0.000581 ! PC_GS_KP - Gain-schedule table: pitch controller kp gains [s]. +-0.001637 -0.001470 -0.001335 -0.001222 -0.001127 -0.001045 -0.000975 -0.000913 -0.000859 -0.000811 -0.000768 -0.000729 -0.000694 -0.000662 -0.000633 -0.000607 -0.000582 -0.000560 -0.000539 -0.000520 -0.000502 -0.000485 -0.000469 -0.000454 -0.000440 -0.000427 -0.000415 -0.000404 -0.000393 ! 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 ! 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 ! PC_GS_TF - Gain-schedule table: pitch controller tf gains (derivative filter) +1.570000000000 ! PC_MaxPit - Maximum physical pitch limit, [rad]. +0.000000000000 ! PC_MinPit - Minimum physical pitch limit, [rad]. +0.122170000000 ! PC_MaxRat - Maximum pitch rate (in absolute value) in pitch controller, [rad/s]. +-0.12217000000 ! PC_MinRat - Minimum pitch rate (in absolute value) in pitch controller, [rad/s]. +122.2879500000 ! PC_RefSpd - Desired (reference) HSS speed for pitch controller, [rad/s]. +0.000000000000 ! PC_FinePit - Record 5: Below-rated pitch angle set-point, [rad] +0.017450000000 ! PC_Switch - Angle above lowest minimum pitch angle for switch, [rad] + +!------- INDIVIDUAL PITCH CONTROL ----------------------------------------- +0.0 0.0 ! IPC_Vramp - Start and end wind speeds for cut-in ramp function. First entry: IPC inactive, second entry: IPC fully active. [m/s] +0.1 ! IPC_IntSat - Integrator saturation (maximum signal amplitude contribution to pitch from IPC), [rad] +0.000e+00 0.000e+00 ! IPC_KP - Proportional gain for the individual pitch controller: first parameter for 1P reductions, second for 2P reductions, [-] +0.000e+00 0.000e+00 ! IPC_KI - Integral gain for the individual pitch controller: first parameter for 1P reductions, second for 2P reductions, [-] +0.000000 0.000000 ! 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 ------------------------------------------------ +93.94773000000 ! VS_GenEff - Generator efficiency mechanical power -> electrical power, [should match the efficiency defined in the generator properties!], [%] +24371.81831000 ! VS_ArSatTq - Above rated generator torque PI control saturation, [Nm] +1500000.000000 ! VS_MaxRat - Maximum torque rate (in absolute value) in torque controller, [Nm/s]. +26809.00014000 ! VS_MaxTq - Maximum generator torque in Region 3 (HSS side), [Nm]. +0.000000000000 ! VS_MinTq - Minimum generator (HSS side), [Nm]. +50.78908000000 ! VS_MinOMSpd - Optimal mode minimum speed, cut-in speed towards optimal mode gain path, [rad/s] +2.055580000000 ! VS_Rgn2K - Generator torque constant in Region 2 (HSS side), [Nm/(rad/s)^2] +2800000.000000 ! VS_RtPwr - Wind turbine rated power [W] +24371.81831000 ! VS_RtTq - Rated torque, [Nm]. +122.2879500000 ! VS_RefSpd - Rated generator speed [rad/s] +1 ! VS_n - Number of generator PI torque controller gains +-585.918650000 ! VS_KP - Proportional gain for generator PI torque controller [-]. (Only used in the transitional 2.5 region if VS_ControlMode =/ 2) +-84.3526100000 ! VS_KI - Integral gain for generator PI torque controller [s]. (Only used in the transitional 2.5 region if VS_ControlMode =/ 2) +8.00 ! VS_TSRopt - Power-maximizing region 2 tip-speed-ratio [rad]. + +!------- SETPOINT SMOOTHER --------------------------------------------- +1.00000 ! SS_VSGain - Variable speed torque controller setpoint smoother gain, [-]. +0.00100 ! SS_PCGain - Collective pitch controller setpoint smoother gain, [-]. + +!------- WIND SPEED ESTIMATOR --------------------------------------------- +63.457 ! WE_BladeRadius - Blade length (distance from hub center to blade tip), [m] +1 ! WE_CP_n - Amount of parameters in the Cp array +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], [-] +19841843.18798 ! 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] +"NREL-2p8-127_Cp_Ct_Cq.txt" ! PerfFileName - File containing rotor performance tables (Cp,Ct,Cq) +30 30 ! PerfTableSize - Size of rotor performance tables, first number refers to number of blade pitch angles, second number referse to number of tip-speed ratios +59 ! WE_FOPoles_N - Number of first-order system poles used in EKF +3.00 3.24 3.48 3.72 3.97 4.21 4.45 4.69 4.93 5.17 5.41 5.66 5.90 6.14 6.38 6.62 6.86 7.10 7.34 7.59 7.83 8.07 8.31 8.55 8.79 9.03 9.28 9.52 9.76 10.00 10.52 11.03 11.55 12.07 12.59 13.10 13.62 14.14 14.66 15.17 15.69 16.21 16.72 17.24 17.76 18.28 18.79 19.31 19.83 20.34 20.86 21.38 21.90 22.41 22.93 23.45 23.97 24.48 25.00 ! WE_FOPoles_v - Wind speeds corresponding to first-order system poles [m/s] +-0.03755370 -0.04057526 -0.04359682 -0.04661839 -0.04963995 -0.05266151 -0.05568307 -0.05870463 -0.06172620 -0.06474776 -0.06776932 -0.07079088 -0.07381244 -0.07683401 -0.07985557 -0.08287713 -0.08589869 -0.08892026 -0.09194182 -0.09496338 -0.09798494 -0.10100650 -0.10402807 -0.10704963 -0.11007119 -0.11309275 -0.11611431 -0.11913588 -0.12215744 -0.12442309 -0.08151313 -0.09670796 -0.11491145 -0.13526498 -0.15708028 -0.18040671 -0.20314889 -0.22784461 -0.25427479 -0.28079304 -0.30962195 -0.33563012 -0.36680258 -0.39642727 -0.42479673 -0.45403549 -0.48608257 -0.52014667 -0.55456520 -0.58971549 -0.61985547 -0.65379097 -0.69212406 -0.73040974 -0.75941587 -0.79271437 -0.82808748 -0.86351689 -0.90081887 ! WE_FOPoles - First order system poles [1/s] + +!------- YAW CONTROL ------------------------------------------------------ +0.00000 ! Y_uSwitch - Wind speed to switch between Y_ErrThresh. If zero, only the first value of Y_ErrThresh is used [m/s] +4.000000 8.000000 ! Y_ErrThresh - Yaw error threshold/deadband. Turbine begins to yaw when it passes this. If Y_uSwitch is zero, only the first value is used. [deg]. +0.00870 ! Y_Rate - Yaw rate [rad/s] +0.00000 ! Y_MErrSet - Integrator saturation (maximum signal amplitude contribution to pitch from yaw-by-IPC), [rad] +0.00000 ! Y_IPC_IntSat - Integrator saturation (maximum signal amplitude contribution to pitch from yaw-by-IPC), [rad] +0.00000 ! Y_IPC_KP - Yaw-by-IPC proportional controller gain Kp +0.00000 ! Y_IPC_KI - Yaw-by-IPC integral controller gain Ki + +!------- 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_HPFCornerFreq - 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] + +!------- MINIMUM PITCH SATURATION ------------------------------------------- +59 ! PS_BldPitchMin_N - Number of values in minimum blade pitch lookup table (should equal number of values in PS_WindSpeeds and PS_BldPitchMin) +3.0000 3.2414 3.4828 3.7241 3.9655 4.2069 4.4483 4.6897 4.9310 5.1724 5.4138 5.6552 5.8966 6.1379 6.3793 6.6207 6.8621 7.1034 7.3448 7.5862 7.8276 8.0690 8.3103 8.5517 8.7931 9.0345 9.2759 9.5172 9.7586 10.0000 10.5172 11.0345 11.5517 12.0690 12.5862 13.1034 13.6207 14.1379 14.6552 15.1724 15.6897 16.2069 16.7241 17.2414 17.7586 18.2759 18.7931 19.3103 19.8276 20.3448 20.8621 21.3793 21.8966 22.4138 22.9310 23.4483 23.9655 24.4828 25.0000 ! PS_WindSpeeds - Wind speeds corresponding to minimum blade pitch angles [m/s] +0.00000000 0.00000000 0.00000000 0.00000000 0.00000000 0.00000000 0.00000000 0.00000000 0.00000000 0.00000000 0.00000000 0.00000000 0.00000000 0.00000000 0.00000000 0.00000000 0.00000000 0.00000000 0.00000000 0.00000000 0.00000000 0.00000000 0.00763391 0.02582598 0.04121469 0.05415541 0.06572411 0.07607035 0.08541836 0.09383601 0.10711337 0.11980981 0.13230324 0.14429856 0.15620583 0.16769078 0.17903230 0.19036255 0.20094970 0.21164306 0.22225798 0.23236325 0.24250097 0.25268462 0.26261996 0.27261663 0.28234372 0.29204627 0.30171741 0.31126513 0.32058559 0.33032494 0.33977293 0.34883344 0.35807953 0.36776628 0.37731052 0.38609588 0.39489943 ! PS_BldPitchMin - Minimum blade pitch angles [rad] + +!------- SHUTDOWN ----------------------------------------------------------- +0.567710000000 ! SD_MaxPit - Maximum blade pitch angle to initiate shutdown, [rad] +0.418880000000 ! SD_CornerFreq - Cutoff Frequency for first order low-pass filter for blade pitch angle, [rad/s] + +!------- Floating ----------------------------------------------------------- +0.000000000000 ! Fl_Kp - Nacelle velocity proportional feedback gain [s] + +!------- FLAP ACTUATION ----------------------------------------------------- +0.000000000000 ! Flp_Angle - Initial or steady state flap angle [rad] +0.00000000e+00 ! Flp_Kp - Blade root bending moment proportional gain for flap control [s] +0.00000000e+00 ! Flp_Ki - Flap displacement integral gain for flap control [-] +0.000000000000 ! Flp_MaxPit - Maximum (and minimum) flap pitch angle [rad] + +!------- Open Loop Control ----------------------------------------------------- +"unused" ! OL_Filename - Input file with open loop timeseries (absolute path or relative to this file) +0 ! Ind_Breakpoint - The column in OL_Filename that contains the breakpoint (time if OL_Mode = 1) +0 ! Ind_BldPitch - The column in OL_Filename that contains the blade pitch input in rad +0 ! Ind_GenTq - The column in OL_Filename that contains the generator torque in Nm +0 ! Ind_YawRate - The column in OL_Filename that contains the generator torque in Nm + +!------- Pitch Actuator Model ----------------------------------------------------- +3.140000000000 ! PA_CornerFreq - Pitch actuator bandwidth/cut-off frequency [rad/s] +0.707000000000 ! PA_Damping - Pitch actuator damping ratio [-, unused if PA_Mode = 1] + +!------- Pitch Actuator Faults ----------------------------------------------------- +0.00000000 0.00000000 0.00000000 ! PF_Offsets - Constant blade pitch offsets for blades 1-3 [rad] + +!------- AWC Modifications ----------------------------------------------------- +1 ! AWC_NumModes +1 ! AWC_n - AWC azimuthal number +0.3141592653 ! AWC_omega - AWC frequency [rad/s] +0.01745329222222222222 ! AWC_amp - AWC amplitude [rad] +0.0 ! AWC_clockangle - AWC clock angle [deg] + +!------- External Controller Interface ----------------------------------------------------- +"unused" ! DLL_FileName - Name/location of the dynamic library in the Bladed-DLL format +"unused" ! DLL_InFile - Name of input file sent to the DLL (-) +"DISCON" ! DLL_ProcName - Name of procedure in DLL to be called (-) + +!------- ZeroMQ Interface --------------------------------------------------------- +"tcp://localhost:5555" ! ZMQ_CommAddress - Communication address for ZMQ server, (e.g. "tcp://localhost:5555") +2 ! ZMQ_UpdatePeriod - Call ZeroMQ every [x] seconds, [s] diff --git a/Test_Cases/NREL_2p8_127/NREL-2p8-127_ElastoDyn.dat b/Test_Cases/NREL_2p8_127/NREL-2p8-127_ElastoDyn.dat new file mode 100644 index 00000000..6cced857 --- /dev/null +++ b/Test_Cases/NREL_2p8_127/NREL-2p8-127_ElastoDyn.dat @@ -0,0 +1,210 @@ +------- ELASTODYN v1.03.* INPUT FILE ------------------------------------------- +Generated with AeroElasticSE FAST driver +---------------------- SIMULATION CONTROL -------------------------------------- +False Echo - Echo input data to ".ech" (flag) +3 Method - Integration method: {1: RK4, 2: AB4, or 3: ABM4} (-) +default DT Integration time step (s) +---------------------- DEGREES OF FREEDOM -------------------------------------- +True FlapDOF1 - First flapwise blade mode DOF (flag) +True FlapDOF2 - Second flapwise blade mode DOF (flag) +True EdgeDOF - First edgewise blade mode DOF (flag) +False TeetDOF - Rotor-teeter DOF (flag) [unused for 3 blades] +False DrTrDOF - Drivetrain rotational-flexibility DOF (flag) +True GenDOF - Generator DOF (flag) +False YawDOF - Yaw DOF (flag) +False TwFADOF1 - First fore-aft tower bending-mode DOF (flag) +False TwFADOF2 - Second fore-aft tower bending-mode DOF (flag) +False TwSSDOF1 - First side-to-side tower bending-mode DOF (flag) +False TwSSDOF2 - Second side-to-side tower bending-mode DOF (flag) +False PtfmSgDOF - Platform horizontal surge translation DOF (flag) +False PtfmSwDOF - Platform horizontal sway translation DOF (flag) +False PtfmHvDOF - Platform vertical heave translation DOF (flag) +False PtfmRDOF - Platform roll tilt rotation DOF (flag) +False PtfmPDOF - Platform pitch tilt rotation DOF (flag) +False PtfmYDOF - Platform yaw rotation DOF (flag) +---------------------- INITIAL CONDITIONS -------------------------------------- +0.0 OoPDefl - Initial out-of-plane blade-tip displacement (meters) +0.0 IPDefl - Initial in-plane blade-tip deflection (meters) +0.0 BlPitch(1) - Blade 1 initial pitch (degrees) +0.0 BlPitch(2) - Blade 2 initial pitch (degrees) +0.0 BlPitch(3) - Blade 3 initial pitch (degrees) [unused for 2 blades] +0.0 TeetDefl - Initial or fixed teeter angle (degrees) [unused for 3 blades] +0.0 Azimuth - Initial azimuth angle for blade 1 (degrees) +7.223281620282807 RotSpeed - Initial or fixed rotor speed (rpm) +0.0 NacYaw - Initial or fixed nacelle-yaw angle (degrees) +0.0 TTDspFA - Initial fore-aft tower-top displacement (meters) +0.0 TTDspSS - Initial side-to-side tower-top displacement (meters) +0.0 PtfmSurge - Initial or fixed horizontal surge translational displacement of platform (meters) +0.0 PtfmSway - Initial or fixed horizontal sway translational displacement of platform (meters) +0.0 PtfmHeave - Initial or fixed vertical heave translational displacement of platform (meters) +0.0 PtfmRoll - Initial or fixed roll tilt rotational displacement of platform (degrees) +0.0 PtfmPitch - Initial or fixed pitch tilt rotational displacement of platform (degrees) +0.0 PtfmYaw - Initial or fixed yaw rotational displacement of platform (degrees) +---------------------- TURBINE CONFIGURATION ----------------------------------- +3 NumBl - Number of blades (-) +63.45678601946693 TipRad - The distance from the rotor apex to the blade tip (meters) +2.0 HubRad - The distance from the rotor apex to the blade root (meters) +-3.0 PreCone(1) - Blade 1 cone angle (degrees) +-3.0 PreCone(2) - Blade 2 cone angle (degrees) +-3.0 PreCone(3) - Blade 3 cone angle (degrees) [unused for 2 blades] +0.0 HubCM - Distance from rotor apex to hub mass [positive downwind] (meters) +0.0 UndSling - Undersling length [distance from teeter pin to the rotor apex] (meters) [unused for 3 blades] +0.0 Delta3 - Delta-3 angle for teetering rotors (degrees) [unused for 3 blades] +0.0 AzimB1Up - Azimuth value to use for I/O when blade 1 points up (degrees) +-5.0 OverHang - Distance from yaw axis to rotor apex [3 blades] or teeter pin [2 blades] (meters) +0.0 ShftGagL - Distance from rotor apex [3 blades] or teeter pin [2 blades] to shaft strain gages [positive for upwind rotors] (meters) +-4.999629720311564 ShftTilt - Rotor shaft tilt angle (degrees) +0.8829822658380706 NacCMxn - Downwind distance from the tower-top to the nacelle CM (meters) +-0.08924556522324154 NacCMyn - Lateral distance from the tower-top to the nacelle CM (meters) +0.8326312050685473 NacCMzn - Vertical distance from the tower-top to the nacelle CM (meters) +0.0 NcIMUxn - Downwind distance from the tower-top to the nacelle IMU (meters) +0.0 NcIMUyn - Lateral distance from the tower-top to the nacelle IMU (meters) +0.0 NcIMUzn - Vertical distance from the tower-top to the nacelle IMU (meters) +1.1177004388298077 Twr2Shft - Vertical distance from the tower-top to the rotor shaft (meters) +86.5 TowerHt - Height of tower above ground level [onshore] or MSL [offshore] (meters) +0.0 TowerBsHt - Height of tower base above ground level [onshore] or MSL [offshore] (meters) +0.0 PtfmCMxt - Downwind distance from the ground level [onshore] or MSL [offshore] to the platform CM (meters) +0.0 PtfmCMyt - Lateral distance from the ground level [onshore] or MSL [offshore] to the platform CM (meters) +0.0 PtfmCMzt - Vertical distance from the ground level [onshore] or MSL [offshore] to the platform CM (meters) +0.0 PtfmRefzt - Vertical distance from the ground level [onshore] or MSL [offshore] to the platform reference point (meters) +---------------------- MASS AND INERTIA ---------------------------------------- +0.0 TipMass(1) - Tip-brake mass, blade 1 (kg) +0.0 TipMass(2) - Tip-brake mass, blade 2 (kg) +0.0 TipMass(3) - Tip-brake mass, blade 3 (kg) [unused for 2 blades] +7482.264184443234 HubMass - Hub mass (kg) +28639.287453422658 HubIner - Hub inertia about rotor axis [3 blades] or teeter axis [2 blades] (kg m^2) +4940.938090969189 GenIner - Generator inertia about HSS (kg m^2) +113487.2812241146 NacMass - Nacelle mass (kg) +693579.6265889656 NacYIner - Nacelle inertia about yaw axis (kg m^2) +3353.0472655982394 YawBrMass - Yaw bearing mass (kg) +0.0 PtfmMass - Platform mass (kg) +0.0 PtfmRIner - Platform inertia for roll tilt rotation about the platform CM (kg m^2) +0.0 PtfmPIner - Platform inertia for pitch tilt rotation about the platform CM (kg m^2) +0.0 PtfmYIner - Platform inertia for yaw rotation about the platform CM (kg m^2) +---------------------- BLADE --------------------------------------------------- +50 BldNodes - Number of blade nodes (per blade) used for analysis (-) +"NREL-2p8-127_ElastoDyn_blade.dat" BldFile1 - Name of file containing properties for blade 1 (quoted string) +"NREL-2p8-127_ElastoDyn_blade.dat" BldFile2 - Name of file containing properties for blade 2 (quoted string) +"NREL-2p8-127_ElastoDyn_blade.dat" BldFile3 - Name of file containing properties for blade 3 (quoted string) [unused for 2 blades] +---------------------- ROTOR-TEETER -------------------------------------------- +0 TeetMod - Rotor-teeter spring/damper model {0: none, 1: standard, 2: user-defined from routine UserTeet} (switch) [unused for 3 blades] +0.0 TeetDmpP - Rotor-teeter damper position (degrees) [used only for 2 blades and when TeetMod=1] +0.0 TeetDmp - Rotor-teeter damping constant (N-m/(rad/s)) [used only for 2 blades and when TeetMod=1] +0.0 TeetCDmp - Rotor-teeter rate-independent Coulomb-damping moment (N-m) [used only for 2 blades and when TeetMod=1] +0.0 TeetSStP - Rotor-teeter soft-stop position (degrees) [used only for 2 blades and when TeetMod=1] +0.0 TeetHStP - Rotor-teeter hard-stop position (degrees) [used only for 2 blades and when TeetMod=1] +0.0 TeetSSSp - Rotor-teeter soft-stop linear-spring constant (N-m/rad) [used only for 2 blades and when TeetMod=1] +0.0 TeetHSSp - Rotor-teeter hard-stop linear-spring constant (N-m/rad) [used only for 2 blades and when TeetMod=1] +---------------------- DRIVETRAIN ---------------------------------------------- +95.5 GBoxEff - Gearbox efficiency (%) +97.0 GBRatio - Gearbox ratio (-) +283287696.9043701 DTTorSpr - Drivetrain torsional spring (N-m/rad) +1500541.6644456587 DTTorDmp - Drivetrain torsional damper (N-m/(rad/s)) +---------------------- FURLING ------------------------------------------------- +False Furling - Read in additional model properties for furling turbine (flag) [must currently be FALSE) +"none" FurlFile - Name of file containing furling properties (quoted string) [unused when Furling=False] +---------------------- TOWER --------------------------------------------------- +20 TwrNodes - Number of tower nodes used for analysis (-) +"NREL-2p8-127_ElastoDyn_tower.dat" TwrFile - Name of file containing tower properties (quoted string) +---------------------- OUTPUT -------------------------------------------------- +False SumPrint - Print summary data to ".sum" (flag) +1 OutFile - Switch to determine where output will be placed: {1: in module output file only; 2: in glue code output file only; 3: both} (currently unused) +True TabDelim - Use tab delimiters in text tabular output file? (flag) (currently unused) +"ES10.3E2" OutFmt - Format used for text tabular output (except time). Resulting field should be 10 characters. (quoted string) (currently unused) +0.0 TStart - Time to begin tabular output (s) (currently unused) +1 DecFact - Decimation factor for tabular output {1: output every time step} (-) (currently unused) +9 NTwGages - Number of tower nodes that have strain gages for output [0 to 9] (-) +2, 4, 6, 8, 10, 12, 14, 16, 18 TwrGagNd - List of tower nodes that have strain gages [1 to TwrNodes] (-) [unused if NTwGages=0] +9 NBlGages - Number of blade nodes that have strain gages for output [0 to 9] (-) +6, 11, 16, 21, 26, 31, 36, 41, 46 BldGagNd - List of blade nodes that have strain gages [1 to BldNodes] (-) [unused if NBlGages=0] + OutList - The next line(s) contains a list of output parameters. See OutListParameters.xlsx for a listing of available output channels, (-) +"Azimuth" +"BldPitch1" +"BldPitch2" +"BldPitch3" +"GenSpeed" +"LSSTipMys" +"LSSTipMzs" +"LSShftFys" +"LSShftFzs" +"NacYaw" +"RootFxb1" +"RootFxb2" +"RootFxb3" +"RootFxc1" +"RootFxc2" +"RootFxc3" +"RootFyb1" +"RootFyb2" +"RootFyb3" +"RootFyc1" +"RootFyc2" +"RootFyc3" +"RootFzb1" +"RootFzb2" +"RootFzb3" +"RootFzc1" +"RootFzc2" +"RootFzc3" +"RootMxb1" +"RootMxb2" +"RootMxb3" +"RootMxc1" +"RootMxc2" +"RootMxc3" +"RootMyb1" +"RootMyb2" +"RootMyb3" +"RootMyc1" +"RootMyc2" +"RootMyc3" +"RootMzb1" +"RootMzb2" +"RootMzb3" +"RootMzc1" +"RootMzc2" +"RootMzc3" +"RotSpeed" +"RotThrust" +"RotTorq" +"Spn1MLxb1" +"Spn1MLyb1" +"Spn2MLxb1" +"Spn2MLyb1" +"Spn3MLxb1" +"Spn3MLyb1" +"Spn4MLxb1" +"Spn4MLyb1" +"Spn5MLxb1" +"Spn5MLyb1" +"Spn6MLxb1" +"Spn6MLyb1" +"Spn7MLxb1" +"Spn7MLyb1" +"Spn8MLxb1" +"Spn8MLyb1" +"Spn9MLxb1" +"Spn9MLyb1" +"TipDxb1" +"TipDxb2" +"TipDxb3" +"TipDxc1" +"TipDxc2" +"TipDxc3" +"TipDyb1" +"TipDyb2" +"TipDyb3" +"TipDyc1" +"TipDyc2" +"TipDyc3" +"TipDzb1" +"TipDzb2" +"TipDzb3" +"TipDzc1" +"TipDzc2" +"TipDzc3" +"TwrBsMxt" +"TwrBsMyt" +"TwrBsMzt" +END of input file (the word "END" must appear in the first 3 columns of this last OutList line) +--------------------------------------------------------------------------------------- diff --git a/Test_Cases/NREL_2p8_127/NREL-2p8-127_ElastoDyn_blade.dat b/Test_Cases/NREL_2p8_127/NREL-2p8-127_ElastoDyn_blade.dat new file mode 100644 index 00000000..662c3af1 --- /dev/null +++ b/Test_Cases/NREL_2p8_127/NREL-2p8-127_ElastoDyn_blade.dat @@ -0,0 +1,62 @@ +------- ELASTODYN V1.00.* INDIVIDUAL BLADE INPUT FILE -------------------------- +Generated with AeroElasticSE FAST driver +---------------------- BLADE PARAMETERS ---------------------------------------- +30 NBlInpSt - Number of blade input stations (-) +1.0 BldFlDmp1 - Blade flap mode #1 structural damping in percent of critical (%) +1.0 BldFlDmp2 - Blade flap mode #2 structural damping in percent of critical (%) +1.0 BldEdDmp1 - Blade edge mode #1 structural damping in percent of critical (%) +---------------------- BLADE ADJUSTMENT FACTORS -------------------------------- +1.0 FlStTunr1 - Blade flapwise modal stiffness tuner, 1st mode (-) +1.0 FlStTunr2 - Blade flapwise modal stiffness tuner, 2nd mode (-) +1.0 AdjBlMs - Factor to adjust blade mass density (-) +1.0 AdjFlSt - Factor to adjust blade flap stiffness (-) +1.0 AdjEdSt - Factor to adjust blade edge stiffness (-) +---------------------- DISTRIBUTED BLADE PROPERTIES ---------------------------- + BlFract PitchAxis StrcTwst BMassDen FlpStff EdgStff + (-) (-) (deg) (kg/m) (Nm^2) (Nm^2) + 0.000000000000000e+00 5.000000000000000e-01 1.999622705006573e+01 9.710303775720137e+02 8.916645581889803e+09 8.916996828171421e+09 + 3.448275862068966e-02 4.797651657064801e-01 1.931018243810786e+01 9.360384963432447e+02 1.473326655503917e+10 1.503401326999529e+10 + 6.896551724137932e-02 4.100052021425268e-01 1.831714953780435e+01 7.384411481979697e+02 1.350641277548294e+10 1.668758117393011e+10 + 1.034482758620690e-01 3.512493343557562e-01 1.708763041181490e+01 5.242503736808504e+02 7.750625550591639e+09 1.313891689544163e+10 + 1.379310344827586e-01 3.110092285118687e-01 1.569212712279918e+01 4.095720481213451e+02 4.517970071596079e+09 1.065397599903997e+10 + 1.724137931034483e-01 2.834806852225638e-01 1.382289586770404e+01 2.986034040547503e+02 2.639603257135735e+09 7.691984348826207e+09 + 2.068965517241379e-01 2.649028377616424e-01 1.124554309027298e+01 2.242709960488304e+02 1.722995952419500e+09 5.352469758607450e+09 + 2.413793103448276e-01 2.524820938264642e-01 8.602632953470145e+00 2.129606273581960e+02 1.483184105878141e+09 4.327677642529569e+09 + 2.758620689655172e-01 2.449189056667618e-01 6.549224739725965e+00 2.091698491908484e+02 1.365990134494710e+09 3.614205549153540e+09 + 3.103448275862069e-01 2.413757812153578e-01 5.408188380153923e+00 1.968505270832688e+02 1.161884350732890e+09 3.059348888224575e+09 + 3.448275862068965e-01 2.409997816578705e-01 4.552816793256156e+00 1.840381495123537e+02 9.314103670023195e+08 2.635487762688528e+09 + 3.793103448275861e-01 2.438939371115084e-01 3.850103071189125e+00 1.707777565800272e+02 7.316000308334582e+08 2.188136539118910e+09 + 4.137931034482759e-01 2.495413982689942e-01 3.210053831367405e+00 1.577448933617357e+02 5.813400904874783e+08 1.847593613150510e+09 + 4.482758620689655e-01 2.579313748558032e-01 2.548277995517243e+00 1.472572881966913e+02 4.757592505107988e+08 1.631226610849327e+09 + 4.827586206896552e-01 2.680075313847211e-01 1.868987870564891e+00 1.385288690289785e+02 3.862376543475163e+08 1.405932074273394e+09 + 5.172413793103448e-01 2.786890302281694e-01 1.247026288989173e+00 1.303134456935171e+02 3.086236872618167e+08 1.086079003669758e+09 + 5.517241379310345e-01 2.889455550381649e-01 7.591906266374636e-01 1.214132928926456e+02 2.441246000330141e+08 7.279449241103762e+08 + 5.862068965517241e-01 2.981867550411185e-01 4.659000465949885e-01 1.130051988362277e+02 1.889011712485603e+08 4.718010458987974e+08 + 6.206896551724138e-01 3.061372927610646e-01 2.731580237682558e-01 1.057369028682480e+02 1.426024838771875e+08 3.311232129595062e+08 + 6.551724137931035e-01 3.119763987397355e-01 1.231485664729688e-01 9.974549711305480e+01 1.081121588014881e+08 2.531064287089206e+08 + 6.896551724137934e-01 3.154698036179193e-01 -1.889923787502366e-02 9.455111640202743e+01 8.496507419955346e+07 1.976683193694704e+08 + 7.241379310344830e-01 3.174252972719749e-01 -1.841259535939614e-01 8.918927437076574e+01 6.699354322582775e+07 1.803010747112424e+08 + 7.586206896551723e-01 3.157084507688791e-01 -3.432314804149588e-01 8.015835414506564e+01 5.106806818035772e+07 1.739724378313888e+08 + 7.931034482758621e-01 3.095467116664537e-01 -5.034899071419768e-01 7.140526341375902e+01 3.929235153694874e+07 1.684420237335510e+08 + 8.275862068965517e-01 2.996558060513167e-01 -6.944182383563149e-01 5.563937030326857e+01 2.849850000919442e+07 7.873543089740016e+07 + 8.620689655172414e-01 2.881116856742882e-01 -9.464479611794926e-01 4.591127859162181e+01 1.982854313004774e+07 6.415110790287662e+07 + 8.965517241379312e-01 2.777712184636389e-01 -1.331448785580028e+00 3.521480844524145e+01 1.075138794875714e+07 4.514001039735875e+07 + 9.310344827586208e-01 2.706279229199988e-01 -1.857716459023805e+00 2.414179066974884e+01 3.638232945365374e+06 2.616242592743580e+07 + 9.655172413793103e-01 2.665260978643628e-01 -2.493070572147947e+00 3.678240377890068e+00 8.650778718250984e+04 1.574666086617074e+06 + 1.000000000000000e+00 2.500000000000000e-01 -3.205330715589577e+00 1.002353815775734e+00 1.628296293397697e+03 3.168732291579445e+04 +---------------------- BLADE MODE SHAPES --------------------------------------- +0.004521475330089924 BldFl1Sh(2) - Flap mode 1, coeff of x^2 +1.0698094815587011 BldFl1Sh(3) - , coeff of x^3 +-0.1043639462789789 BldFl1Sh(4) - , coeff of x^4 +0.7886224122132662 BldFl1Sh(5) - , coeff of x^5 +-0.7585894228230783 BldFl1Sh(6) - , coeff of x^6 +-0.5138424457535536 BldFl2Sh(2) - Flap mode 2, coeff of x^2 +2.93531699885226 BldFl2Sh(3) - , coeff of x^3 +-19.409314950811712 BldFl2Sh(4) - , coeff of x^4 +32.48595903814384 BldFl2Sh(5) - , coeff of x^5 +-14.498118640430834 BldFl2Sh(6) - , coeff of x^6 +0.17685846482119558 BldEdgSh(2) - Edge mode 1, coeff of x^2 +1.9926745320317614 BldEdgSh(3) - , coeff of x^3 +-4.492670447108128 BldEdgSh(4) - , coeff of x^4 +6.331998738711197 BldEdgSh(5) - , coeff of x^5 +-3.0088612884560257 BldEdgSh(6) - , coeff of x^6 diff --git a/Test_Cases/NREL_2p8_127/NREL-2p8-127_ElastoDyn_tower.dat b/Test_Cases/NREL_2p8_127/NREL-2p8-127_ElastoDyn_tower.dat new file mode 100644 index 00000000..670d3ccc --- /dev/null +++ b/Test_Cases/NREL_2p8_127/NREL-2p8-127_ElastoDyn_tower.dat @@ -0,0 +1,50 @@ +------- ELASTODYN V1.00.* TOWER INPUT FILE ------------------------------------- +Generated with AeroElasticSE FAST driver +---------------------- TOWER PARAMETERS ---------------------------------------- +9 NTwInpSt - Number of input stations to specify tower geometry +1.0 TwrFADmp(1) - Tower 1st fore-aft mode structural damping ratio (%) +1.0 TwrFADmp(2) - Tower 2nd fore-aft mode structural damping ratio (%) +1.0 TwrSSDmp(1) - Tower 1st side-to-side mode structural damping ratio (%) +1.0 TwrSSDmp(2) - Tower 2nd side-to-side mode structural damping ratio (%) +---------------------- TOWER ADJUSTMUNT FACTORS -------------------------------- +1.0 FAStTunr(1) - Tower fore-aft modal stiffness tuner, 1st mode (-) +1.0 FAStTunr(2) - Tower fore-aft modal stiffness tuner, 2nd mode (-) +1.0 SSStTunr(1) - Tower side-to-side stiffness tuner, 1st mode (-) +1.0 SSStTunr(2) - Tower side-to-side stiffness tuner, 2nd mode (-) +1.0 AdjTwMa - Factor to adjust tower mass density (-) +1.0 AdjFASt - Factor to adjust tower fore-aft stiffness (-) +1.0 AdjSSSt - Factor to adjust tower side-to-side stiffness (-) +---------------------- DISTRIBUTED TOWER PROPERTIES ---------------------------- + HtFract TMassDen TwFAStif TwSSStif + (-) (kg/m) (Nm^2) (Nm^2) + 0.000000000000000e+00 3.027735301310815e+03 1.474853951124582e+11 1.474853951124582e+11 + 1.250433977548895e-01 2.718841246770161e+03 1.326329677125010e+11 1.326329677125010e+11 + 2.500867955097790e-01 2.405464101729817e+03 1.161354662267779e+11 1.161354662267779e+11 + 3.751301932646685e-01 2.112377458665061e+03 9.479550671463214e+10 9.479550671463214e+10 + 5.001157273463720e-01 1.947002758491315e+03 7.586780853389151e+10 7.586780853389151e+10 + 6.251591251012615e-01 1.783363103134093e+03 5.857866350808070e+10 5.857866350808070e+10 + 7.502025228561510e-01 1.603905893716689e+03 4.289862070041790e+10 4.289862070041790e+10 + 8.751880569378545e-01 1.409173987955922e+03 2.871944175926664e+10 2.871944175926664e+10 + 1.000000000000000e+00 1.161806938102961e+03 1.956567246347168e+10 1.956567246347168e+10 +---------------------- TOWER FORE-AFT MODE SHAPES ------------------------------ +1.0623105807354711 TwFAM1Sh(2) - Mode 1, coefficient of x^2 term +-0.12782107145017788 TwFAM1Sh(3) - , coefficient of x^3 term +-0.11374039457578099 TwFAM1Sh(4) - , coefficient of x^4 term +0.4380734650926717 TwFAM1Sh(5) - , coefficient of x^5 term +-0.2588225798021839 TwFAM1Sh(6) - , coefficient of x^6 term +916.0158542297875 TwFAM2Sh(2) - Mode 2, coefficient of x^2 term +-524.0268078619857 TwFAM2Sh(3) - , coefficient of x^3 term +-620.6941658768418 TwFAM2Sh(4) - , coefficient of x^4 term +844.0762210901079 TwFAM2Sh(5) - , coefficient of x^5 term +-614.3711015810677 TwFAM2Sh(6) - , coefficient of x^6 term +---------------------- TOWER SIDE-TO-SIDE MODE SHAPES -------------------------- +1.0569471838310198 TwSSM1Sh(2) - Mode 1, coefficient of x^2 term +-0.1296167767277 TwSSM1Sh(3) - , coefficient of x^3 term +-0.09657367230257455 TwSSM1Sh(4) - , coefficient of x^4 term +0.4145201607812788 TwSSM1Sh(5) - , coefficient of x^5 term +-0.24527689558202392 TwSSM1Sh(6) - , coefficient of x^6 term +66.717537330485 TwSSM2Sh(2) - Mode 2, coefficient of x^2 term +-28.88940079202735 TwSSM2Sh(3) - , coefficient of x^3 term +-68.66726547883196 TwSSM2Sh(4) - , coefficient of x^4 term +94.08317763633714 TwSSM2Sh(5) - , coefficient of x^5 term +-62.24404869596283 TwSSM2Sh(6) - , coefficient of x^6 term diff --git a/Test_Cases/NREL_2p8_127/NREL-2p8-127_InflowFile.dat b/Test_Cases/NREL_2p8_127/NREL-2p8-127_InflowFile.dat new file mode 100644 index 00000000..401fd0a0 --- /dev/null +++ b/Test_Cases/NREL_2p8_127/NREL-2p8-127_InflowFile.dat @@ -0,0 +1,57 @@ +------- InflowWind v3.01.* INPUT FILE ------------------------------------------------------------------------- +Generated with AeroElasticSE FAST driver +--------------------------------------------------------------------------------------------------------------- +False Echo - Echo input data to .ech (flag) +1 WindType - switch for wind file type (1=steady; 2=uniform; 3=binary TurbSim FF; 4=binary Bladed-style FF; 5=HAWC format; 6=User defined; 7=native Bladed FF) +0.0 PropagationDir - Direction of wind propagation (meteoroligical rotation from aligned with X (positive rotates towards -Y) -- degrees) +0.0 VFlowAng - Upflow angle (degrees) (not used for native Bladed format WindType=7) +1 NWindVel - Number of points to output the wind velocity (0 to 9) +0.0 WindVxiList - List of coordinates in the inertial X direction (m) +0.0 WindVyiList - List of coordinates in the inertial Y direction (m) +88.5 WindVziList - List of coordinates in the inertial Z direction (m) +================== Parameters for Steady Wind Conditions [used only for WindType = 1] ========================= +6.0 HWindSpeed - Horizontal windspeed (m/s) +87.66 RefHt - Reference height for horizontal wind speed (m) +0.0 PLexp - Power law exponent (-) +================== Parameters for Uniform wind file [used only for WindType = 2] ============================ +"none" Filename_Uni - Filename of time series data for uniform wind field. (-) +87.66 RefHt_Uni - Reference height for horizontal wind speed (m) +1.0 RefLength - Reference length for linear horizontal and vertical sheer (-) +================== Parameters for Binary TurbSim Full-Field files [used only for WindType = 3] ============== +"none" FileName_BTS - Name of the Full field wind file to use (.bts) +================== Parameters for Binary Bladed-style Full-Field files [used only for WindType = 4] ========= +"none" FilenameRoot - Rootname of the full-field wind file to use (.wnd, .sum) +False TowerFile - Have tower file (.twr) (flag) +================== Parameters for HAWC-format binary files [Only used with WindType = 5] ===================== +"none" FileName_u - name of the file containing the u-component fluctuating wind (.bin) +"none" FileName_v - name of the file containing the v-component fluctuating wind (.bin) +"none" FileName_w - name of the file containing the w-component fluctuating wind (.bin) +2 nx - number of grids in the x direction (in the 3 files above) (-) +2 ny - number of grids in the y direction (in the 3 files above) (-) +2 nz - number of grids in the z direction (in the 3 files above) (-) +10 dx - distance (in meters) between points in the x direction (m) +10 dy - distance (in meters) between points in the y direction (m) +10 dz - distance (in meters) between points in the z direction (m) +0.0 RefHt_Hawc - reference height; the height (in meters) of the vertical center of the grid (m) +------------- Scaling parameters for turbulence --------------------------------------------------------- +0 ScaleMethod - Turbulence scaling method [0 = none, 1 = direct scaling, 2 = calculate scaling factor based on a desired standard deviation] +1.0 SFx - Turbulence scaling factor for the x direction (-) [ScaleMethod=1] +1.0 SFy - Turbulence scaling factor for the y direction (-) [ScaleMethod=1] +1.0 SFz - Turbulence scaling factor for the z direction (-) [ScaleMethod=1] +1.0 SigmaFx - Turbulence standard deviation to calculate scaling from in x direction (m/s) [ScaleMethod=2] +1.0 SigmaFy - Turbulence standard deviation to calculate scaling from in y direction (m/s) [ScaleMethod=2] +1.0 SigmaFz - Turbulence standard deviation to calculate scaling from in z direction (m/s) [ScaleMethod=2] +------------- Mean wind profile parameters (added to HAWC-format files) --------------------------------- +0.0 URef - Mean u-component wind speed at the reference height (m/s) +0 WindProfile - Wind profile type (0=constant;1=logarithmic,2=power law) +0.0 PLExp_Hawc - Power law exponent (-) (used for PL wind profile type only) +0.0 Z0 - Surface roughness length (m) (used for LG wind profile type only) +0 XOffset - Initial offset in +x direction (shift of wind box) (-) +====================== OUTPUT ================================================== +False SumPrint - Print summary data to .IfW.sum (flag) +OutList - The next line(s) contains a list of output parameters. See OutListParameters.xlsx for a listing of available output channels, (-) +"Wind1Velx" +"Wind1Vely" +"Wind1Velz" +END of input file (the word "END" must appear in the first 3 columns of this last OutList line) +--------------------------------------------------------------------------------------- diff --git a/Test_Cases/NREL_2p8_127/NREL-2p8-127_ServoDyn.dat b/Test_Cases/NREL_2p8_127/NREL-2p8-127_ServoDyn.dat new file mode 100644 index 00000000..bdc2d74d --- /dev/null +++ b/Test_Cases/NREL_2p8_127/NREL-2p8-127_ServoDyn.dat @@ -0,0 +1,110 @@ +------- SERVODYN v1.05.* INPUT FILE -------------------------------------------- +Generated with AeroElasticSE FAST driver +---------------------- SIMULATION CONTROL -------------------------------------- +False Echo - Echo input data to .ech (flag) +default DT - Communication interval for controllers (s) (or "default") +---------------------- PITCH CONTROL ------------------------------------------- +5 PCMode - Pitch control mode {0: none, 3: user-defined from routine PitchCntrl, 4: user-defined from Simulink/Labview, 5: user-defined from Bladed-style DLL} (switch) +0.0 TPCOn - Time to enable active pitch control (s) [unused when PCMode=0] +99999.0 TPitManS(1) - Time to start override pitch maneuver for blade 1 and end standard pitch control (s) +99999.0 TPitManS(2) - Time to start override pitch maneuver for blade 2 and end standard pitch control (s) +99999.0 TPitManS(3) - Time to start override pitch maneuver for blade 3 and end standard pitch control (s) [unused for 2 blades] +7.0 PitManRat(1) - Pitch rate at which override pitch maneuver heads toward final pitch angle for blade 1 (deg/s) +7.0 PitManRat(2) - Pitch rate at which override pitch maneuver heads toward final pitch angle for blade 2 (deg/s) +7.0 PitManRat(3) - Pitch rate at which override pitch maneuver heads toward final pitch angle for blade 3 (deg/s) [unused for 2 blades] +90.0 BlPitchF(1) - Blade 1 final pitch for pitch maneuvers (degrees) +90.0 BlPitchF(2) - Blade 2 final pitch for pitch maneuvers (degrees) +90.0 BlPitchF(3) - Blade 3 final pitch for pitch maneuvers (degrees) [unused for 2 blades] +---------------------- GENERATOR AND TORQUE CONTROL ---------------------------- +5 VSContrl - Variable-speed control mode {0: none, 1: simple VS, 3: user-defined from routine UserVSCont, 4: user-defined from Simulink/Labview, 5: user-defined from Bladed-style DLL} (switch) +1 GenModel - Generator model {1: simple, 2: Thevenin, 3: user-defined from routine UserGen} (switch) [used only when VSContrl=0] +93.94772808556249 GenEff - Generator efficiency [ignored by the Thevenin and user-defined generator models] (%) +True GenTiStr - Method to start the generator {T: timed using TimGenOn, F: generator speed using SpdGenOn} (flag) +True GenTiStp - Method to stop the generator {T: timed using TimGenOf, F: when generator power = 0} (flag) +99999.0 SpdGenOn - Generator speed to turn on the generator for a startup (HSS speed) (rpm) [used only when GenTiStr=False] +0.0 TimGenOn - Time to turn on the generator for a startup (s) [used only when GenTiStr=True] +99999.0 TimGenOf - Time to turn off the generator (s) [used only when GenTiStp=True] +---------------------- SIMPLE VARIABLE-SPEED TORQUE CONTROL -------------------- +99999.0 VS_RtGnSp - Rated generator speed for simple variable-speed generator control (HSS side) (rpm) [used only when VSContrl=1] +99999.0 VS_RtTq - Rated generator torque/constant generator torque in Region 3 for simple variable-speed generator control (HSS side) (N-m) [used only when VSContrl=1] +99999.0 VS_Rgn2K - Generator torque constant in Region 2 for simple variable-speed generator control (HSS side) (N-m/rpm^2) [used only when VSContrl=1] +99999.0 VS_SlPc - Rated generator slip percentage in Region 2 1/2 for simple variable-speed generator control (%) [used only when VSContrl=1] +---------------------- SIMPLE INDUCTION GENERATOR ------------------------------ +99999.0 SIG_SlPc - Rated generator slip percentage (%) [used only when VSContrl=0 and GenModel=1] +99999.0 SIG_SySp - Synchronous (zero-torque) generator speed (rpm) [used only when VSContrl=0 and GenModel=1] +99999.0 SIG_RtTq - Rated torque (N-m) [used only when VSContrl=0 and GenModel=1] +99999.0 SIG_PORt - Pull-out ratio (Tpullout/Trated) (-) [used only when VSContrl=0 and GenModel=1] +---------------------- THEVENIN-EQUIVALENT INDUCTION GENERATOR ----------------- +99999.0 TEC_Freq - Line frequency [50 or 60] (Hz) [used only when VSContrl=0 and GenModel=2] +0 TEC_NPol - Number of poles [even integer > 0] (-) [used only when VSContrl=0 and GenModel=2] +99999.0 TEC_SRes - Stator resistance (ohms) [used only when VSContrl=0 and GenModel=2] +99999.0 TEC_RRes - Rotor resistance (ohms) [used only when VSContrl=0 and GenModel=2] +99999.0 TEC_VLL - Line-to-line RMS voltage (volts) [used only when VSContrl=0 and GenModel=2] +99999.0 TEC_SLR - Stator leakage reactance (ohms) [used only when VSContrl=0 and GenModel=2] +99999.0 TEC_RLR - Rotor leakage reactance (ohms) [used only when VSContrl=0 and GenModel=2] +99999.0 TEC_MR - Magnetizing reactance (ohms) [used only when VSContrl=0 and GenModel=2] +---------------------- HIGH-SPEED SHAFT BRAKE ---------------------------------- +0 HSSBrMode - HSS brake model {0: none, 1: simple, 3: user-defined from routine UserHSSBr, 4: user-defined from Simulink/Labview, 5: user-defined from Bladed-style DLL} (switch) +99999.0 THSSBrDp - Time to initiate deployment of the HSS brake (s) +99999.0 HSSBrDT - Time for HSS-brake to reach full deployment once initiated (sec) [used only when HSSBrMode=1] +99999.0 HSSBrTqF - Fully deployed HSS-brake torque (N-m) +---------------------- NACELLE-YAW CONTROL ------------------------------------- +0 YCMode - Yaw control mode {0: none, 3: user-defined from routine UserYawCont, 4: user-defined from Simulink/Labview, 5: user-defined from Bladed-style DLL} (switch) +99999.0 TYCOn - Time to enable active yaw control (s) [unused when YCMode=0] +0.0 YawNeut - Neutral yaw position--yaw spring force is zero at this yaw (degrees) +496739375.65069634 YawSpr - Nacelle-yaw spring constant (N-m/rad) +187442.5509148155 YawDamp - Nacelle-yaw damping constant (N-m/(rad/s)) +99999.0 TYawManS - Time to start override yaw maneuver and end standard yaw control (s) +0.25 YawManRat - Yaw maneuver rate (in absolute value) (deg/s) +0.0 NacYawF - Final yaw angle for override yaw maneuvers (degrees) +---------------------- AERODYNAMIC FLOW CONTROL -------------------------------- + 0 AfCmode - Airfoil control mode {0: none, 1: cosine wave cycle, 4: user-defined from Simulink/Labview, 5: user-defined from Bladed-style DLL} (switch) + 0 AfC_Mean - Mean level for cosine cycling or steady value (-) [used only with AfCmode==1] + 0 AfC_Amp - Amplitude for for cosine cycling of flap signal (-) [used only with AfCmode==1] + 0 AfC_Phase - Phase relative to the blade azimuth (0 is vertical) for for cosine cycling of flap signal (deg) [used only with AfCmode==1] +---------------------- STRUCTURAL CONTROL -------------------------------------- +0 NumBStC - Number of blade structural controllers (integer) +"unused" BStCfiles - Name of the files for blade structural controllers (quoted strings) [unused when NumBStC==0] +0 NumNStC - Number of nacelle structural controllers (integer) +"unused" NStCfiles - Name of the files for nacelle structural controllers (quoted strings) [unused when NumNStC==0] +0 NumTStC - Number of tower structural controllers (integer) +"unused" TStCfiles - Name of the files for tower structural controllers (quoted strings) [unused when NumTStC==0] +0 NumSStC - Number of substructure structural controllers (integer) +"unused" SStCfiles - Name of the files for substructure structural controllers (quoted strings) [unused when NumSStC==0] +---------------------- CABLE CONTROL ------------------------------------------- + 0 CCmode - Cable control mode {0: none, 4: user-defined from Simulink/Labview, 5: user-defined from Bladed-style DLL} (switch) +---------------------- BLADED INTERFACE ---------------------------------------- [used only with Bladed Interface] +"/pscratch/ndeveld/awc/ROSCO_B/ROSCO/build/libdiscon.so" DLL_FileName - Name/location of the dynamic library {.dll [Windows] or .so [Linux]} in the Bladed-DLL format (-) [used only with Bladed Interface] +"NREL-2p8-127_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] +False DLL_Ramp - Whether a linear ramp should be used between DLL_DT time steps [introduces time shift when true] (flag) [used only with Bladed Interface] +99999.0 BPCutoff - Cuttoff frequency for low-pass filter on blade pitch from DLL (Hz) [used only with Bladed Interface] +0.0 NacYaw_North - Reference yaw angle of the nacelle when the upwind end points due North (deg) [used only with Bladed Interface] +1 Ptch_Cntrl - Record 28: Use individual pitch control {0: collective pitch; 1: individual pitch control} (switch) [used only with Bladed Interface] +0.0 Ptch_SetPnt - Record 5: Below-rated pitch angle set-point (deg) [used only with Bladed Interface] +0.0 Ptch_Min - Record 6: Minimum pitch angle (deg) [used only with Bladed Interface] +0.0 Ptch_Max - Record 7: Maximum pitch angle (deg) [used only with Bladed Interface] +0.0 PtchRate_Min - Record 8: Minimum pitch rate (most negative value allowed) (deg/s) [used only with Bladed Interface] +0.0 PtchRate_Max - Record 9: Maximum pitch rate (deg/s) [used only with Bladed Interface] +0.0 Gain_OM - Record 16: Optimal mode gain (Nm/(rad/s)^2) [used only with Bladed Interface] +0.0 GenSpd_MinOM - Record 17: Minimum generator speed (rpm) [used only with Bladed Interface] +0.0 GenSpd_MaxOM - Record 18: Optimal mode maximum speed (rpm) [used only with Bladed Interface] +0.0 GenSpd_Dem - Record 19: Demanded generator speed above rated (rpm) [used only with Bladed Interface] +0.0 GenTrq_Dem - Record 22: Demanded generator torque above rated (Nm) [used only with Bladed Interface] +0.0 GenPwr_Dem - Record 13: Demanded power (W) [used only with Bladed Interface] +---------------------- BLADED INTERFACE TORQUE-SPEED LOOK-UP TABLE ------------- +0 DLL_NumTrq - Record 26: No. of points in torque-speed look-up table {0 = none and use the optimal mode parameters; nonzero = ignore the optimal mode PARAMETERs by setting Record 16 to 0.0} (-) [used only with Bladed Interface] +GenSpd_TLU GenTrq_TLU +(rpm) (Nm) +---------------------- OUTPUT -------------------------------------------------- +False SumPrint - Print summary data to .sum (flag) (currently unused) +1 OutFile - Switch to determine where output will be placed: {1: in module output file only; 2: in glue code output file only; 3: both} (currently unused) +True TabDelim - Use tab delimiters in text tabular output file? (flag) (currently unused) +"ES10.3E2" OutFmt - Format used for text tabular output (except time). Resulting field should be 10 characters. (quoted string) (currently unused) +0.0 TStart - Time to begin tabular output (s) (currently unused) + OutList - The next line(s) contains a list of output parameters. See OutListParameters.xlsx for a listing of available output channels, (-) +"GenPwr" +"GenTq" +END of input file (the word "END" must appear in the first 3 columns of this last OutList line) +--------------------------------------------------------------------------------------- From a1cf97bbebc47f117a67dad1e4d7044619854f92 Mon Sep 17 00:00:00 2001 From: dzalkind <65573423+dzalkind@users.noreply.github.com> Date: Tue, 7 Feb 2023 14:26:19 -0700 Subject: [PATCH 026/224] Rename examples (#215) * Allow PA_Mode 1 * Add update_discon_version function * Add update_rosco_discons to testing, add example for updating version * Rename and consolidate examples * Rename to test_examples.py to follow pytest convention * Fix tuning_yaml name in example_19 * Change to pytest for test_examples * Revert "Change to pytest for test_examples" This reverts commit 2f996d98b34a3f15e3f9333c52491f8b0d86a0ec. * Remove dev_branch input, clean up old code, fix reader * Fix load_from_fast in 09 * Update reader/writer/inputs for OpenFAST v3.4.0 * Finish updating inputs for 3.4.0 * Tidy up some more example naming * Fix airfoil reader * Remove remaining dev_branch references * Increment openfast version * Fix example paths * Fix ROSCO_walkthrough notebook * Include ROSCO_walkthrough outputs --- .github/workflows/CI_rosco-pytools.yml | 6 +- .../{example_01.py => 01_turbine_model.py} | 18 +- Examples/{example_03.py => 02_ccblade.py} | 5 +- .../{example_04.py => 03_tune_controller.py} | 3 +- Examples/{example_05.py => 04_simple_sim.py} | 3 +- .../{example_06.py => 05_openfast_sim.py} | 12 +- .../{example_07.py => 06_peak_shaving.py} | 3 +- .../{example_08.py => 07_openfast_outputs.py} | 2 +- Examples/{example_09.py => 08_run_turbsim.py} | 0 .../{example_10.py => 09_distributed_aero.py} | 6 +- .../{example_11.py => 10_linear_params.py} | 3 +- .../{example_12.py => 11_robust_tuning.py} | 5 +- Examples/{example_13.py => 12_tune_ipc.py} | 13 +- ...{example_14.py => 14_open_loop_control.py} | 4 +- .../{example_15.py => 15_pass_through.py} | 2 +- .../{example_16.py => 16_external_dll.py} | 2 +- .../{example_17.py => 17_zeromq_interface.py} | 3 +- .../{example_18.py => 18_pitch_offsets.py} | 2 +- Examples/19_update_discon_version.py | 29 + Examples/ROSCO_walkthrough.ipynb | 117 +- Examples/example_02.py | 37 - .../{ => example_inputs}/Cp_Ct_Cq.NREL5MW.txt | 0 .../{ => example_inputs}/Example_OL_Input.dat | 0 .../{run_examples.py => test_examples.py} | 37 +- ROSCO_testing/ROSCO_testing.py | 12 +- ROSCO_testing/run_Testing.py | 1 - ROSCO_toolbox/ofTools/case_gen/CaseLibrary.py | 8 +- ROSCO_toolbox/ofTools/case_gen/run_FAST.py | 10 +- ROSCO_toolbox/ofTools/fast_io/FAST_reader.py | 1391 ++++++----------- .../ofTools/fast_io/FAST_vars_out.py | 20 +- ROSCO_toolbox/ofTools/fast_io/FAST_writer.py | 1215 ++++++-------- ROSCO_toolbox/tune.py | 1 - ROSCO_toolbox/turbine.py | 26 +- Test_Cases/BAR_10/BAR_10_AeroDyn15.dat | 58 +- .../IEA-15-240-RWT_AeroDyn15.dat | 78 +- .../NRELOffshrBsline5MW_Onshore_AeroDyn15.dat | 56 +- Tune_Cases/tune_ROSCO.py | 68 - 37 files changed, 1312 insertions(+), 1944 deletions(-) rename Examples/{example_01.py => 01_turbine_model.py} (80%) rename Examples/{example_03.py => 02_ccblade.py} (93%) rename Examples/{example_04.py => 03_tune_controller.py} (96%) rename Examples/{example_05.py => 04_simple_sim.py} (97%) rename Examples/{example_06.py => 05_openfast_sim.py} (89%) rename Examples/{example_07.py => 06_peak_shaving.py} (96%) rename Examples/{example_08.py => 07_openfast_outputs.py} (96%) rename Examples/{example_09.py => 08_run_turbsim.py} (100%) rename Examples/{example_10.py => 09_distributed_aero.py} (91%) rename Examples/{example_11.py => 10_linear_params.py} (97%) rename Examples/{example_12.py => 11_robust_tuning.py} (97%) rename Examples/{example_13.py => 12_tune_ipc.py} (91%) rename Examples/{example_14.py => 14_open_loop_control.py} (98%) rename Examples/{example_15.py => 15_pass_through.py} (96%) rename Examples/{example_16.py => 16_external_dll.py} (98%) rename Examples/{example_17.py => 17_zeromq_interface.py} (98%) rename Examples/{example_18.py => 18_pitch_offsets.py} (98%) create mode 100644 Examples/19_update_discon_version.py delete mode 100644 Examples/example_02.py rename Examples/{ => example_inputs}/Cp_Ct_Cq.NREL5MW.txt (100%) rename Examples/{ => example_inputs}/Example_OL_Input.dat (100%) rename Examples/{run_examples.py => test_examples.py} (73%) delete mode 100644 Tune_Cases/tune_ROSCO.py diff --git a/.github/workflows/CI_rosco-pytools.yml b/.github/workflows/CI_rosco-pytools.yml index c5c31b1c..dbfe77ab 100644 --- a/.github/workflows/CI_rosco-pytools.yml +++ b/.github/workflows/CI_rosco-pytools.yml @@ -129,13 +129,13 @@ jobs: # Install OpenFAST - name: Install OpenFAST run: | - conda install openfast==3.3 + conda install openfast==3.4 # Run examples - name: Run examples run: | cd Examples - python run_examples.py + python test_examples.py # Test walkthrough notebook - name: Test walkthrough notebook @@ -194,7 +194,7 @@ jobs: # Install OpenFAST - name: Install OpenFAST run: | - conda install openfast==3.3 + conda install openfast==3.4 # Run ROSCO Testing - name: Run ROSCO testing diff --git a/Examples/example_01.py b/Examples/01_turbine_model.py similarity index 80% rename from Examples/example_01.py rename to Examples/01_turbine_model.py index 14cf3bbd..14a30fc2 100644 --- a/Examples/example_01.py +++ b/Examples/01_turbine_model.py @@ -17,6 +17,7 @@ # ROSCO Modules from ROSCO_toolbox import turbine as ROSCO_turbine from ROSCO_toolbox.inputs.validation import load_rosco_yaml +import matplotlib.pyplot as plt # Load yaml file @@ -33,7 +34,6 @@ turbine.load_from_fast( path_params['FAST_InputFile'], os.path.join(tune_dir,path_params['FAST_directory']), - dev_branch=True, rot_source='txt',txt_filename=os.path.join(tune_dir,path_params['FAST_directory'],path_params['rotor_performance_filename']) ) @@ -45,4 +45,18 @@ if not os.path.isdir(example_out_dir): os.makedirs(example_out_dir) -turbine.save(os.path.join(example_out_dir,'01_NREL5MW_saved.p')) \ No newline at end of file +turbine.save(os.path.join(example_out_dir,'01_NREL5MW_saved.p')) + +# Now load the turbine and plot the Cp surface + +# Load quick from python pickle +turbine = turbine.load(os.path.join(example_out_dir,'01_NREL5MW_saved.p')) + +# plot rotor performance +print('Plotting Cp data') +turbine.Cp.plot_performance() + +if False: + plt.show() +else: + plt.savefig(os.path.join(example_out_dir,'01_NREL5MW_Cp.png')) \ No newline at end of file diff --git a/Examples/example_03.py b/Examples/02_ccblade.py similarity index 93% rename from Examples/example_03.py rename to Examples/02_ccblade.py index a5ea447a..8d09aaff 100644 --- a/Examples/example_03.py +++ b/Examples/02_ccblade.py @@ -10,7 +10,7 @@ - Write a text file with rotor performance properties ''' # Python modules -import yaml, os +import os # ROSCO toolbox modules from ROSCO_toolbox import turbine as ROSCO_turbine from ROSCO_toolbox.utilities import write_rotor_performance @@ -38,10 +38,9 @@ turbine.load_from_fast( path_params['FAST_InputFile'], os.path.join(this_dir,path_params['FAST_directory']), - dev_branch=True, rot_source='cc-blade', txt_filename=None) # Write rotor performance text file -txt_filename = os.path.join(example_out_dir,'03_Cp_Ct_Cq.Ex03.txt') +txt_filename = os.path.join(example_out_dir,'02_Cp_Ct_Cq.Ex03.txt') write_rotor_performance(turbine,txt_filename=txt_filename) diff --git a/Examples/example_04.py b/Examples/03_tune_controller.py similarity index 96% rename from Examples/example_04.py rename to Examples/03_tune_controller.py index 69da8392..a4308390 100644 --- a/Examples/example_04.py +++ b/Examples/03_tune_controller.py @@ -38,7 +38,6 @@ turbine.load_from_fast( path_params['FAST_InputFile'], os.path.join(tune_dir,path_params['FAST_directory']), - dev_branch=True, rot_source='txt',txt_filename= cp_filename ) @@ -78,4 +77,4 @@ if False: plt.show() else: - plt.savefig(os.path.join(example_out_dir,'04_GainSched.png')) \ No newline at end of file + plt.savefig(os.path.join(example_out_dir,'03_GainSched.png')) \ No newline at end of file diff --git a/Examples/example_05.py b/Examples/04_simple_sim.py similarity index 97% rename from Examples/example_05.py rename to Examples/04_simple_sim.py index 9555aeb3..29d0c7b2 100644 --- a/Examples/example_05.py +++ b/Examples/04_simple_sim.py @@ -59,7 +59,6 @@ turbine.load_from_fast( path_params['FAST_InputFile'], os.path.join(tune_dir,path_params['FAST_directory']), - dev_branch=True, rot_source='txt',txt_filename=cp_filename ) @@ -108,5 +107,5 @@ if False: plt.show() else: - plt.savefig(os.path.join(example_out_dir,'05_NREL5MW_SimpSim.png')) + plt.savefig(os.path.join(example_out_dir,'04_NREL5MW_SimpSim.png')) diff --git a/Examples/example_06.py b/Examples/05_openfast_sim.py similarity index 89% rename from Examples/example_06.py rename to Examples/05_openfast_sim.py index 6eab3834..a11f1b30 100644 --- a/Examples/example_06.py +++ b/Examples/05_openfast_sim.py @@ -37,10 +37,12 @@ controller = ROSCO_controller.Controller(controller_params) # Load turbine data from OpenFAST and rotor performance text file -turbine.load_from_fast(path_params['FAST_InputFile'], \ - os.path.join(this_dir,path_params['FAST_directory']), \ - dev_branch=True,rot_source='txt',\ - txt_filename=os.path.join(this_dir,path_params['FAST_directory'],path_params['rotor_performance_filename'])) +turbine.load_from_fast( + path_params['FAST_InputFile'], + os.path.join(this_dir,path_params['FAST_directory']), + rot_source='txt', + txt_filename=os.path.join(this_dir,path_params['FAST_directory'],path_params['rotor_performance_filename']) + ) # Tune controller controller.tune_controller(turbine) @@ -79,7 +81,7 @@ if False: plt.show() else: - plt.savefig(os.path.join(example_out_dir,'06_GainSched.png')) + plt.savefig(os.path.join(example_out_dir,'05_GainSched.png')) # Run OpenFAST # --- May need to change fastcall if you use a non-standard command to call openfast diff --git a/Examples/example_07.py b/Examples/06_peak_shaving.py similarity index 96% rename from Examples/example_07.py rename to Examples/06_peak_shaving.py index 3fc16f85..fdad7db8 100644 --- a/Examples/example_07.py +++ b/Examples/06_peak_shaving.py @@ -44,7 +44,6 @@ turbine.load_from_fast( path_params['FAST_InputFile'], os.path.join(tune_dir,path_params['FAST_directory']), - dev_branch=True, rot_source='txt',txt_filename=os.path.join(tune_dir,path_params['FAST_directory'],path_params['rotor_performance_filename']) ) # Tune controller @@ -61,4 +60,4 @@ if False: plt.show() else: - plt.savefig(os.path.join(example_out_dir,'07_MinPitch.png')) + plt.savefig(os.path.join(example_out_dir,'06_MinPitch.png')) diff --git a/Examples/example_08.py b/Examples/07_openfast_outputs.py similarity index 96% rename from Examples/example_08.py rename to Examples/07_openfast_outputs.py index 0307f738..a794baf0 100644 --- a/Examples/example_08.py +++ b/Examples/07_openfast_outputs.py @@ -49,6 +49,6 @@ fastout = fast_out.load_fast_out(filenames) fast_out.plot_fast_out(cases=cases,showplot=False) -plt.savefig(os.path.join(example_out_dir,'08_IEA-15MW_Semi_Out.png')) +plt.savefig(os.path.join(example_out_dir,'07_IEA-15MW_Semi_Out.png')) diff --git a/Examples/example_09.py b/Examples/08_run_turbsim.py similarity index 100% rename from Examples/example_09.py rename to Examples/08_run_turbsim.py diff --git a/Examples/example_10.py b/Examples/09_distributed_aero.py similarity index 91% rename from Examples/example_10.py rename to Examples/09_distributed_aero.py index 7a7b0693..6d970194 100644 --- a/Examples/example_10.py +++ b/Examples/09_distributed_aero.py @@ -34,8 +34,10 @@ # Load turbine data from openfast model turbine = ROSCO_turbine.Turbine(turbine_params) -turbine.load_from_fast(path_params['FAST_InputFile'], \ - os.path.join(this_dir,path_params['FAST_directory']),dev_branch=True) +turbine.load_from_fast( + path_params['FAST_InputFile'], + os.path.join(this_dir,path_params['FAST_directory']) + ) # Tune controller controller = ROSCO_controller.Controller(controller_params) diff --git a/Examples/example_11.py b/Examples/10_linear_params.py similarity index 97% rename from Examples/example_11.py rename to Examples/10_linear_params.py index 6b1e9680..b0c2470f 100644 --- a/Examples/example_11.py +++ b/Examples/10_linear_params.py @@ -33,7 +33,7 @@ if not os.path.isdir(example_out_dir): os.makedirs(example_out_dir) -linmod_filename = os.path.join(example_out_dir,'11_IEA15MW_LinMod.dat') +linmod_filename = os.path.join(example_out_dir,'10_IEA15MW_LinMod.dat') # Instantiate turbine, controller, and file processing classes turbine = ROSCO_turbine.Turbine(turbine_params) @@ -44,7 +44,6 @@ turbine.load_from_fast( path_params['FAST_InputFile'], os.path.join(this_dir,path_params['FAST_directory']), - dev_branch=True, rot_source='txt', txt_filename=os.path.join(tune_dir,path_params['FAST_directory'],path_params['rotor_performance_filename']) ) diff --git a/Examples/example_12.py b/Examples/11_robust_tuning.py similarity index 97% rename from Examples/example_12.py rename to Examples/11_robust_tuning.py index 9d8c593d..65f676d3 100644 --- a/Examples/example_12.py +++ b/Examples/11_robust_tuning.py @@ -43,7 +43,7 @@ def run_example(): # Path options example_out_dir = os.path.join(os.path.dirname(os.path.abspath(__file__)), 'examples_out') - output_name = '12_robust_scheduling' + output_name = '11_robust_scheduling' path_options = {'output_dir': example_out_dir, 'output_name': output_name } @@ -54,7 +54,6 @@ def run_example(): turbine.load_from_fast( path_params['FAST_InputFile'], os.path.join(this_dir, path_params['FAST_directory']), - dev_branch=True, rot_source='txt', txt_filename=os.path.join(this_dir,path_params['FAST_directory'],path_params['rotor_performance_filename']) ) @@ -124,7 +123,7 @@ def run_example(): if False: plt.show() else: - fig.savefig(os.path.join(example_out_dir, '12_RobustSched.png')) + fig.savefig(os.path.join(example_out_dir, '11_RobustSched.png')) # ---- Plot nyquist ---- # Re-load and trimlinturb for plotting diff --git a/Examples/example_13.py b/Examples/12_tune_ipc.py similarity index 91% rename from Examples/example_13.py rename to Examples/12_tune_ipc.py index b326491d..d4040a68 100644 --- a/Examples/example_13.py +++ b/Examples/12_tune_ipc.py @@ -1,5 +1,5 @@ ''' ------------ Example_13 -------------- +----------- 12_tune_ipc -------------- Load a turbine, tune a controller with IPC ------------------------------------- @@ -28,7 +28,8 @@ this_dir = os.path.dirname(os.path.abspath(__file__)) rosco_dir = os.path.dirname(this_dir) example_out_dir = os.path.join(this_dir,'examples_out') -run_dir = os.path.join(example_out_dir, '13_ipc_sim') +example_name = '12_ipc_sim' +run_dir = os.path.join(example_out_dir, example_name) # Load yaml file (Open Loop Case) parameter_filename = os.path.join(rosco_dir,'Tune_Cases/BAR.yaml') @@ -47,8 +48,10 @@ controller = ROSCO_controller.Controller(controller_params) # Load turbine data from OpenFAST and rotor performance text file -turbine.load_from_fast(path_params['FAST_InputFile'], - os.path.join(this_dir, path_params['FAST_directory']), dev_branch=True) +turbine.load_from_fast( + path_params['FAST_InputFile'], + os.path.join(this_dir, path_params['FAST_directory']) + ) # Tune controller controller.tune_controller(turbine) @@ -102,7 +105,7 @@ cases = {} cases['Baseline'] = ['Wind1VelX', ('BldPitch1', 'BldPitch2', 'BldPitch3'), 'RootMyc1', 'RotSpeed'] -out_file = os.path.join(example_out_dir,'13_ipc_sim/ipc_example_0.outb') +out_file = os.path.join(example_out_dir,example_name,'ipc_example_0.outb') op = output_processing.output_processing() fastout = op.load_fast_out(out_file, tmin=0) fig, ax = op.plot_fast_out(cases=cases,showplot=False) diff --git a/Examples/example_14.py b/Examples/14_open_loop_control.py similarity index 98% rename from Examples/example_14.py rename to Examples/14_open_loop_control.py index 2b14f249..7ca79462 100644 --- a/Examples/example_14.py +++ b/Examples/14_open_loop_control.py @@ -1,5 +1,5 @@ ''' ------------ Example_14 -------------- +----------- 14_open_loop_control -------------- Load a turbine, tune a controller with open loop control commands ------------------------------------- @@ -76,7 +76,7 @@ # Load turbine data from OpenFAST and rotor performance text file turbine.load_from_fast(path_params['FAST_InputFile'], \ os.path.join(this_dir,path_params['FAST_directory']), \ - dev_branch=True,rot_source='txt',\ + rot_source='txt',\ txt_filename=os.path.join(this_dir,path_params['FAST_directory'],path_params['rotor_performance_filename'])) # Tune controller diff --git a/Examples/example_15.py b/Examples/15_pass_through.py similarity index 96% rename from Examples/example_15.py rename to Examples/15_pass_through.py index 2b4716e9..f33fd3f7 100644 --- a/Examples/example_15.py +++ b/Examples/15_pass_through.py @@ -1,5 +1,5 @@ ''' ------------ Example_15 -------------- +----------- 15_pass_through -------------- Use the runFAST scripts to set up an example, use pass through in yaml ------------------------------------- diff --git a/Examples/example_16.py b/Examples/16_external_dll.py similarity index 98% rename from Examples/example_16.py rename to Examples/16_external_dll.py index b040c2af..afb629ec 100644 --- a/Examples/example_16.py +++ b/Examples/16_external_dll.py @@ -1,5 +1,5 @@ ''' ------------ Example_16 -------------- +----------- 16_external_dll -------------- Run openfast with ROSCO and external control interface ------------------------------------- diff --git a/Examples/example_17.py b/Examples/17_zeromq_interface.py similarity index 98% rename from Examples/example_17.py rename to Examples/17_zeromq_interface.py index c77e8cc6..ae8a34ae 100644 --- a/Examples/example_17.py +++ b/Examples/17_zeromq_interface.py @@ -1,5 +1,5 @@ ''' ------------ Example_17 -------------- +----------- 17_zeromq_interface -------------- Run ROSCO using the ROSCO toolbox control interface and execute communication with ZeroMQ ------------------------------------- @@ -80,7 +80,6 @@ def sim_rosco(): turbine.load_from_fast( path_params['FAST_InputFile'], os.path.join(tune_dir, path_params['FAST_directory']), - dev_branch=True, rot_source='txt', txt_filename=cp_filename ) diff --git a/Examples/example_18.py b/Examples/18_pitch_offsets.py similarity index 98% rename from Examples/example_18.py rename to Examples/18_pitch_offsets.py index 00a4d4d4..ace996c5 100644 --- a/Examples/example_18.py +++ b/Examples/18_pitch_offsets.py @@ -1,5 +1,5 @@ ''' ------------ Example_18 ------------------------ +----------- 18_pitch_offsets ------------------------ Run openfast with ROSCO and pitch offset faults ----------------------------------------------- diff --git a/Examples/19_update_discon_version.py b/Examples/19_update_discon_version.py new file mode 100644 index 00000000..342cd4d2 --- /dev/null +++ b/Examples/19_update_discon_version.py @@ -0,0 +1,29 @@ +''' +----------- 19_update_discon_version ----------------- +Test and demonstrate update_discon_version() function for converting an old ROSCO input +to the current version +''' + +import os +from ROSCO_toolbox.tune import update_discon_version + +this_dir = os.path.dirname(os.path.abspath(__file__)) +rosco_dir = os.path.dirname(this_dir) + + +def main(): + + old_discon_filename = os.path.join(this_dir,'example_inputs','DISCON_v2.2.0.IN') # An IEA-15MW input + + # Tuning yaml can be anything, does not have to correspond to old discon + tuning_yaml = os.path.join(rosco_dir,'Tune_Cases','NREL5MW.yaml') # dummy for now + update_discon_version( + old_discon_filename, + tuning_yaml, + os.path.join(this_dir,'examples_out','18_UPDATED_DISCON.IN') + ) + + + +if __name__ == "__main__": + main() \ No newline at end of file diff --git a/Examples/ROSCO_walkthrough.ipynb b/Examples/ROSCO_walkthrough.ipynb index 8f078be6..d3f912b7 100644 --- a/Examples/ROSCO_walkthrough.ipynb +++ b/Examples/ROSCO_walkthrough.ipynb @@ -33,23 +33,9 @@ "name": "stdout", "output_type": "stream", "text": [ + "WARNING: Be sure to pip install simpy and marmot-agents for offshore BOS runs\n", "Using ofTools in ROSCO_toolbox...\n" ] - }, - { - "name": "stderr", - "output_type": "stream", - "text": [ - "/Users/dzalkind/opt/anaconda3/envs/rosco-env/lib/python3.8/site-packages/openmdao/utils/general_utils.py:130: OMDeprecationWarning:simple_warning is deprecated. Use openmdao.utils.om_warnings.issue_warning instead.\n", - "/Users/dzalkind/opt/anaconda3/envs/rosco-env/lib/python3.8/site-packages/openmdao/utils/notebook_utils.py:171: UserWarning:Tabulate is not installed. Run `pip install openmdao[notebooks]` to install required dependencies. Using ASCII for outputs.\n" - ] - }, - { - "name": "stdout", - "output_type": "stream", - "text": [ - "WARNING: Be sure to pip install simpy and marmot-agents for offshore BOS runs\n" - ] } ], "source": [ @@ -193,15 +179,19 @@ "Loading wind turbine data for NREL's ROSCO tuning and simulation processeses\n", "-----------------------------------------------------------------------------\n", "Loading FAST model: NREL-5MW.fst \n", - "Loading rotor performace data from text file: /Users/dzalkind/Tools/ROSCO/Test_Cases/NREL-5MW/Cp_Ct_Cq.NREL5MW.txt\n", - "Loading rotor performace data from text file: Cp_Ct_Cq.NREL5MW.txt\n" + "Loading rotor performace data from text file: /Users/dzalkind/Tools/ROSCO3/Test_Cases/NREL-5MW/Cp_Ct_Cq.NREL5MW.txt\n", + "Loading rotor performace data from text file: ../Tune_Cases/../Test_Cases/NREL-5MW/Cp_Ct_Cq.NREL5MW.txt\n" ] } ], "source": [ "# Load turbine data from openfast model\n", "turbine = ROSCO_turbine.Turbine(turbine_params)\n", - "turbine.load_from_fast(path_params['FAST_InputFile'],path_params['FAST_directory'],dev_branch=True,rot_source='txt',txt_filename=path_params['rotor_performance_filename'])\n" + "turbine.load_from_fast(\n", + " path_params['FAST_InputFile'],\n", + " os.path.join('../Tune_Cases/',path_params['FAST_directory']),\n", + " rot_source='txt',txt_filename=os.path.join('../Tune_Cases/',path_params['FAST_directory'],path_params['rotor_performance_filename'])\n", + " )\n" ] }, { @@ -241,14 +231,12 @@ }, { "data": { - "image/png": "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\n", + "image/png": "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\n", "text/plain": [ - "
" + "
" ] }, - "metadata": { - "needs_background": "light" - }, + "metadata": {}, "output_type": "display_data" } ], @@ -320,14 +308,12 @@ "outputs": [ { "data": { - "image/png": "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\n", + "image/png": "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\n", "text/plain": [ - "
" + "
" ] }, - "metadata": { - "needs_background": "light" - }, + "metadata": {}, "output_type": "display_data" } ], @@ -366,7 +352,11 @@ "source": [ "# Write parameter input file\n", "param_file = 'DISCON.IN' # This must be named DISCON.IN to be seen by the compiled controller binary. \n", - "ROSCO_utilities.write_DISCON(turbine,controller,param_file=param_file, txt_filename=path_params['rotor_performance_filename'])" + "ROSCO_utilities.write_DISCON(\n", + " turbine,controller,\n", + " param_file=param_file, \n", + " txt_filename=os.path.join('../Tune_Cases/',path_params['FAST_directory'],path_params['rotor_performance_filename'])\n", + ")" ] }, { @@ -404,14 +394,12 @@ }, { "data": { - "image/png": "iVBORw0KGgoAAAANSUhEUgAAAYIAAAEGCAYAAABo25JHAAAAOXRFWHRTb2Z0d2FyZQBNYXRwbG90bGliIHZlcnNpb24zLjUuMiwgaHR0cHM6Ly9tYXRwbG90bGliLm9yZy8qNh9FAAAACXBIWXMAAAsTAAALEwEAmpwYAAA8sklEQVR4nO3dd3xN9//A8dc7g9ibIkjsFYLEVqM6VI0aVa1dVIeur7Za3eure+rwrVGqatSqaqlaRYvEjC0EMWOFkJ3P749z5RckcZGbm3vv+/l4eLj3nHPPed/juu97Pp/zeX/EGINSSinP5eXsAJRSSjmXJgKllPJwmgiUUsrDaSJQSikPp4lAKaU8nI+zA7hRpUuXNgEBAc4OQymlXEp4ePgpY0yZzNa5XCIICAggLCzM2WEopZRLEZGDWa3TpiGllPJwmgiUUsrDaSJQSikP53J9BJlJTk4mOjqahIQEZ4eiPIifnx/+/v74+vo6OxSlbolbJILo6GiKFClCQEAAIuLscJQHMMZw+vRpoqOjCQwMdHY4St0St2gaSkhIoFSpUpoEVK4REUqVKqVXocotODQRiMg9IrJbRPaJyOhstgsVkVQR6XULx7rZlyp1U/Qzp9yFwxKBiHgD44BOQF2gr4jUzWK794HFjopFKaVcWXJqGt+siGTz4XMO2b8jrwiaAvuMMfuNMUnAz0C3TLYbCfwCnHRgLA737rvvUq9ePRo0aEBwcDDr1q0D4LPPPuPSpUs5coyoqCjq169v9/aXLl3i4YcfJigoiPr169O6dWvi4uI4d+4cX3/99XVfb+92V4uNjWXAgAFUq1aNatWqMWDAAGJjY294Pzdq3rx57NixI/35a6+9xtKlSx1+XKUcaeOhs3T5cjXv/7GLPyKOO+QYjkwEFYHDGZ5H25alE5GKwP3At9ntSESGi0iYiITFxMTkeKC36p9//mHhwoVs3LiRrVu3snTpUipVqgTkbCK4UZ9//jnlypVj27ZtREREMGHCBHx9fR2eCB555BGqVq1KZGQkkZGRBAYGMnTo0Jt5C9dITU3Nct3VieCtt96iY8eOOXJcpXLb+YRkXpm3jZ7frCU2Ppnx/ZswulNthxzLkYkgswbUq6dD+wx40RiT9f9uwBgz3hgTYowJKVMm01IZTnXs2DFKly5N/vz5AShdujQVKlTgiy++4OjRo7Rv35727dsDsGTJElq0aEHjxo3p3bs3cXFxgPWlFRoaSv369Rk+fDiXZ44LDw+nYcOGtGjRgnHjxqUfs02bNmzevDn9eatWrdi6des1cVWs+P+5t1atWuTPn5/Ro0cTGRlJcHAwzz//PHFxcdxxxx00btyYoKAg5s+fD3DNdgAffvghoaGhNGjQgNdff/2ac7Fv3z7Cw8N59dVX05e99tprhIWFERkZyYoVK7j99tu5//77qVu3LiNGjCAtLS3bcxMQEMBbb71F69atmTVrFv/73/8IDQ2lYcOG9OzZk0uXLrF27VoWLFjA888/T3BwMJGRkQwaNIjZs2cD8Ndff9GoUSOCgoIYMmQIiYmJ6ft+/fXX09/7rl27bujfXqmcZoxh0bZjdPx4JT+tO8SglgH8+Vxb7qp3m2MP6og/QAtgcYbnLwEvXbXNASDK9icOq3moe3b7bdKkibnajh070h+/sSDCPPDt2hz988aCiGuOmdGFCxdMw4YNTY0aNcxjjz1mVqxYkb6uSpUqJiYmxhhjTExMjGnTpo2Ji4szxhgzduxY8+abbxpjjDl9+nT6a/r162cWLFhgjDEmKCgofX+jRo0y9erVM8YYM3nyZPP0008bY4zZvXu3yey8bNq0yZQpU8Y0b97cjBkzxuzZs8cYY8yBAwfS92OMMcnJySY2NjY9xmrVqpm0tLRrtlu8eLEZNmyYSUtLM6mpqaZz585m5cqVVxxz/vz5pnv37tfE0r17dzN//nyzfPlykz9/fhMZGWlSUlJMx44dzaxZs7I9N1WqVDHvv/9++r5OnTqV/njMmDHmiy++MMYYM3DgQDNr1qz0dZefx8fHG39/f7N7925jjDH9+/c3n376afq+L79+3Lhx5pFHHrkm9uxk/OwpdasOn7lohkxab6q8uNDc+/kqs+Xw2RzbNxBmsvhedeQVwQaghogEikg+4EFgwVVJKNAYE2CMCQBmA48bY+Y5MCaHKFy4MOHh4YwfP54yZcrQp08fJk+efM12//77Lzt27KBVq1YEBwfzww8/cPCgVQdq+fLlNGvWjKCgIJYtW8b27duJjY3l3LlztG3bFoD+/fun76t3794sXLiQ5ORkJk6cyKBBg645XnBwMPv37+f555/nzJkzhIaGsnPnzmu2M8bw8ssv06BBAzp27MiRI0c4ceLENdstWbKEJUuW0KhRIxo3bsyuXbvYu3fvNfvK7G6ajMubNm1K1apV8fb2pm/fvqxevTrbcwPQp0+f9McRERG0adOGoKAgpk2bxvbt2685Xka7d+8mMDCQmjVrAjBw4EBWrVqVvr5Hjx4ANGnShKioqGz3pZQjpKSm8f3f+7nr01WsjTzNK53rMP+JVjTwL54rx3fYgDJjTIqIPIl1N5A3MNEYs11ERtjWZ9svcLNe71LPEbu9Lm9vb9q1a0e7du0ICgrihx9+uObL2RjDnXfeyfTp069YnpCQwOOPP05YWBiVKlXijTfeICEhIcsvVYCCBQty5513Mn/+fGbOnJllRdbChQvTo0cPevTogZeXF4sWLaJnz55XbDNt2jRiYmIIDw/H19eXgICATO+PN8bw0ksv8eijj2Z5HurVq8emTZtIS0vDy8v6nZGWlsaWLVuoU6cO0dHR17wnEcny3FxWqFCh9MeDBg1i3rx5NGzYkMmTJ7NixYos47kcd3YuN+l5e3uTkpKS7bZK5bSII7GMnrOViCPn6VC7LG91q4d/iYK5GoNDxxEYYxYZY2oaY6oZY961Lfs2syRgjBlkjJntyHgcZffu3Vf8Mt68eTNVqlQBoEiRIly4cAGA5s2bs2bNGvbt2wdYd/Xs2bMn/Uu3dOnSxMXFpbdrFy9enGLFirF69WrA+sLOaOjQoTz11FOEhoZSsmTJa+Jas2YNZ8+eBSApKYkdO3ZQpUqVK2IC6y6fsmXL4uvry/Lly9N/iV+93d13383EiRPT2+6PHDnCyZNX3uxVvXp1GjVqxDvvvJO+7J133qFx48ZUr14dgPXr13PgwAHS0tKYMWMGrVu3zvLcZObChQuUL1+e5OTkK87J1fFeVrt2baKiotL3PXXq1PSrLKWc5WJiCu8s3EHXr1ZzPDaRrx5qxISBIbmeBMBNSkw4W1xcHCNHjuTcuXP4+PhQvXp1xo8fD8Dw4cPp1KkT5cuXZ/ny5UyePJm+ffumd1a+88471KxZk2HDhhEUFERAQAChoaHp+540aRJDhgyhYMGC3H333Vcct0mTJhQtWpTBgwdnGldkZCSPPfYYxhjS0tLo3LkzPXv2RERo1aoV9evXp1OnTrz44ot06dKFkJAQgoODqV3bujOhVKlSV2z34YcfsnPnTlq0aAFYVxs//vgjZcuWveK4EyZMYOTIkVSvXh1jDC1atGDChAnp61u0aMHo0aPZtm1besexl5dXlufmam+//TbNmjWjSpUqBAUFpX/5P/jggwwbNowvvvgiPZmCVRNo0qRJ9O7dm5SUFEJDQxkxYoQd/7JKOcaK3ScZMzeCI+fieahZZV68pzbFCjivZpVc77I5rwkJCTFXN4Ps3LmTOnXqOCki5zl69Cjt2rVj165d6c0wed2KFSv46KOPWLhwobNDyRGe+tlTN+fMxSTeXriDuZuOUL1sYf7bI4jQgGuv5h1BRMKNMSGZrdMrAhc1ZcoUxowZwyeffOIySUApT2WMYcGWo7z16w5i45N56o4aPNG+Gvl9vJ0dGqBXBErdEv3sqes5FhvPK3Mj+GvXSRpWKs77PYOofVvRXI9DrwiUUiqXpaUZflp/iLG/7yI1zfBK5zoMbhWIt1feK1aoiUAppXLYgVMXefGXraw/cIZW1Uvx3/sbULlU7t8NZC9NBEoplUNSUtP4fvUBPv1zD/l8vPigZwN6h/jn+ZLlmgiUUioH7Dh6nhd/2cq2I7HcVbccb3evT7mifs4Oyy56u0kOEZErSkCkpKRQpkwZ7rvvPgAWLFjA2LFjs93H0aNH6dXrpufmuWVvvPEGFStWJDg4mPr167NggVURZOjQoelVPd97773r7idjsbfsZFW6OzOTJ0/mySeftPOdXGvFihXp/xbZKVy48E0fQ3mmxJRUPl6ym65freZYbDxfP9yY7/o3cZkkAHpFkGMKFSpEREQE8fHxFChQgD///POKyp9du3ala9eu2e6jQoUKdn2BOtKzzz7LqFGj2LlzJ23atOHkyZN8//336evfe+89Xn755Vs+TsbS3fnz5+fUqVMkJSXd8n6Vyk1bo8/x/Kyt7D5xgR6NKvLqfXUpUSifs8O6YXpFkIM6derEb7/9BsD06dPp27dv+rqMv2gHDRrEU089RcuWLalatWr6l3/GiWcmT55M9+7d6dKlC4GBgXz11Vd88sknNGrUiObNm3PmzBkA2rVrl15n6NSpUwQEBNzQ67NSp04dfHx8OHXqVPoxRo8eTXx8PMHBwTz88MOANZ6hQYMGNGzY8IorolWrVl3z/jLKqnQ3wIYNG2jZsiUNGzakadOm6SOHjx49yj333EONGjV44YUX0veVVfnqP/74g9q1a9O6dWvmzJmTvv0bb7zBRx99lP68fv36mRabu17JbeW5ElNS+eCPXdz/9VrOxScxaVAon/QJdskkAO54RfD7aDi+LWf3eVsQdMq+WQesEgdvvfUW9913H1u3bmXIkCH8/fffmW577NgxVq9eza5du+jatWumTUIRERFs2rSJhIQEqlevzvvvv8+mTZt49tlnmTJlCs8880y28dzK69etW4eXlxcZ538YO3YsX331Vfo8CNu3b+fdd99lzZo1lC5d+orkcr33d9ddd/HWW29Rs2ZNOnbsSJ8+fWjbti1JSUn06dOHGTNmEBoayvnz5ylQoABg1XDatGkT+fPnp1atWowcOZICBQrwzjvvsHTpUgoVKsT777/PJ598wgsvvMCwYcNYtmwZ1atXv6J6qT2WLFnC3r17Wb9+PcYYunbtyqpVq7j99ttvaD/K/Ww5fI5Rs7aw92QcD4T4M6ZzXaeWh8gJ7pcInKhBgwZERUUxffp07r333my37d69O15eXtStWzfTks8A7du3p0iRIhQpUoRixYrRpUsXAIKCgq6ZhCanXv/pp5/y448/UqRIEWbMmJHt3Q7Lli2jV69elC5dGuCKwnfXe3+XS3f//fffLF++nD59+jB27FiaNGlC+fLl0+stFS36/wNv7rjjDooVKwZA3bp1OXjwIOfOnUsvXw1Wcb0WLVqwa9cuAgMDqVGjBgD9+vVLr/9kj4wlt8GqJ7V3715NBB4sITmVz5buZfyqSMoV9WPy4FDa1Sp7/Re6APdLBHb8cnekrl27MmrUKFasWMHp06ez3O5ykwhkXSY54zZeXl7pz728vNLLJfv4+KTP8HV16Wh7Xn+1y30E9siuTLY97y+z0t2NGze2a5+XS0ZnVb568+bNWe4n4zmDa8/b5ZivV3JbeY5Nh87y/Oyt7DsZR5+QSoy5rw5F/Vz7KiAj7SPIYUOGDOG1114jKCgoV44XEBBAeHg4QK50NPv6+pKcnAxYv9BnzpyZnvCu1++QUValu2vXrs3Ro0fZsGEDYJWczm6OgKzKV9euXZsDBw4QGRkJcEWiCAgIYOPGjQBs3LiRAwcOXLNfe0puK/eXkJzKf3/fSc9v1nIxMYXJg0N5v1cDt0oC4I5XBE7m7+/P008/nWvHGzVqFA888ABTp06lQ4cODj/e8OHDadCgAY0bN2batGmMGTOGtm3b4u3tTaNGjTKdmS0zWZXuzpcvHzNmzGDkyJHpd2AtXbo0y/2UKVMmy/LV48ePp3PnzpQuXZrWrVsTEREBQM+ePZkyZQrBwcGEhoZmWur6rrvusqvktnJfGw+d5flZW4iMuciDoZV4ubN7XQVkpEXnlLoF+tlzPwnJqXz65x7+9/d+bivqx9ieDbi9ZpnrvzCP06JzSillhy2Hz/HczM1Exlykb9PKvHxvbYq46VVARpoIlFIeLykljS+X7eXrFZGULZKfKUOausVVgL3cJhFkdweLUo7gas2qKnM7j53nuZlb2HnsPD0b+/NaF9cfF3Cj3CIR+Pn5cfr0aUqVKqXJQOUKYwynT5/Gz8916smoK6WkpjH+7/18+uceihXwZXz/JtxV7zZnh+UUbpEI/P39iY6OJiYmxtmhKA/i5+eHv7+/s8NQN2F/TBz/mbWFTYfO0TmoPG93r09JFy0PkRPcIhH4+voSGBjo7DCUUnlcWprhh3+ieP+PXeT38eaLvo3o2rCCs8NyOrdIBEopdT2Hz1zi+dlb+Hf/GTrULsvYHkGUdaFS0Y6kiUAp5daMMcwMO8zbC3cCuMysYblJE4FSym2dvJDA6F+2sWzXSVpULcUHvRpQqWTenTvYWTQRKKXc0h8Rx3lpzlYuJaXyepe6DGwRgJeXXgVkRhOBUsqtxCWm8OaC7cwKjyaoYjE+7RNM9bI6BWl2NBEopdxGWNQZnp25mSNn43myfXWeuqMG+Xy0yPL1aCJQSrm8pJQ0Pv9rD9+siMS/REFmjWhBkyolr/9CVxKzGwqUhMI5X/pCE4FSyqXtO3mBZ2ZsJuLIefqEVOLVLnUpnN+NvtoSL8DK9+Hfb6DJIOj8cY4fwo3OllLKkxhjmPrvQd79bSeF8vvwXf8m3O1OJSKMgW2zYckrEHcCGg+Adi875FCaCJRSLufk+QSen72VlXtiaFerDB/0akDZIm40OOzEdlj0PBxcAxUaw4M/gX8Thx1OE4FSyqX8EXGMl+ZsIz45lbe71aNf8yruMzgsIRaW/xfWjwe/YtDlc2g0ALwc2+GtiUAp5RIuJaXw5oIdzAg77H63hRoDEb/A4jFWM1DIYOjwKhTMnQ5vTQRKqTwv4kgsT03fxIHTF3m8XTWe6VjTfW4LPbUPFv0H9q+A8sHQdzpUbJyrIWgiUErlWWlpholrDvD+H7soWSgf04Y2o2W10s4OK2ckx8Pfn8Caz8DHD+79CEKGgJd3roeiiUAplSfFXEhk1KwtrNwTw511y/FBzwaUcJc5A/YuhUWj4OwBCOoNd70LRco5LRyHJgIRuQf4HPAGvjfGjL1qfTfgbSANSAGeMcasdmRMSqm8b+WeGP4zcwvnE5Ldq0M4Nhr+GA07f4VS1WHAfKjaztlROS4RiIg3MA64E4gGNojIAmPMjgyb/QUsMMYYEWkAzARqOyompVTelpSSxkdLdjN+1X5qlivMj0ObUvu2os4O69alJMG/42DlB1bHcIdXoeVI8Mnv7MgAx14RNAX2GWP2A4jIz0A3ID0RGGPiMmxfCNDZwJXyUFGnLvLUz5vYGh3Lw80q8+p9dfHzzf328hx3YBX8NgpO7YZaneGe/0KJKs6O6gqOTAQVgcMZnkcDza7eSETuB/4LlAU6Z7YjERkODAeoXLlyjgeqlHKueZuOMGbuNry9hG/7Neae+uWdHdKtu3ACloyBbbOgeBXoOwNq3ePsqDLlyESQWYPeNb/4jTFzgbkicjtWf0HHTLYZD4wHCAkJ0asGpdzExcQUXp0fwZyNRwgNKMFnDzaiYvECzg7r1qSlQvgkWPoWpMTD7c9Dm/+Ab959X45MBNFApQzP/YGjWW1sjFklItVEpLQx5pQD41JK5QHbj8by5E+bOHj6Ik/dUYOnOlTHx9vFxwYc3QwLn4WjGyHwduj8CZSu4eyorsuRiWADUENEAoEjwIPAQxk3EJHqQKSts7gxkA847cCYlFJOZozhx3WHeHvhDkoU9OWnYc1pXrWUs8O6NQnnYfl7sP47KFgKenwPQb3ARe50clgiMMakiMiTwGKs20cnGmO2i8gI2/pvgZ7AABFJBuKBPsYYbfpRyk2dT0jmpTnb+G3rMdrWLMMnDzSkVOG8cefMTTEGdsyDP16CC8ch9BHrjqACxZ0d2Q0RV/veDQkJMWFhYc4OQyl1gyKOxPLETxuJPhvPqLtq8ejtVV17DuHTkVaF0Mi/4LYGcN9nDq0QeqtEJNwYE5LZOh1ZrJRyKGMMU/6x5g0oVTgfM4Y3JyTAhWcPS06wykL8/Yk1DqDTBxA61CmlIXKKJgKllMOcT0hm9C9bWbTtOB1ql+Xj3g1du0xE5DL47T9wZj/U7wV3vwtFXH8yHE0ESimH2H40liembeTw2Xhe6lSbYW1cuCnownGrH2D7HKs0RP95UK29s6PKMZoIlFI5yhjDjA2HeW3BdkoWdPGmoLRUCJsIf70FKYnQfgy0ejrPlIbIKZoIlFI55lJSCq/MjWDOpiO0qVGaz/oEu+5dQce2wK/PWGMCqrazxgSUqubsqBzC7kQgIoWABGNMqgPjUUq5qH0nL/D4tI3sPRnHMx1rMLJDDbxdsSko8YI1JmDdt9aYgJ4ToH5PlxkTcDOyTAQi4oU1COxhIBRIBPKLSAywCBhvjNmbK1EqpfK0BVuOMvqXrRTw9WbqkGa0ruGik8fsXAi/vwDnj1rTRd7xGhQo4eyoHC67K4LlwFLgJSDCGJMGICIlgfbAWBGZa4z50fFhKqXyoqSUNN5btJPJa6NoUqUE4x5qzG3F/Jwd1o2LjYZFL8Du36BsPeg9GSo1dXZUuSa7RNDRGJN89UJjzBngF+AXEfF1WGRKqTztWGw8j0/byKZD53ikdSCjO9XG19VqBaWmWE1Ay98DDNz5FjR/HLw966stu0RQJLsZgYwxZzJLFEop97d67yme+nkTicmpjHuoMZ0buGDZ6CPh8OvTcHwb1Lgb7v0wz80TkFuySwThWGWjBagMnLU9Lg4cAgIdHZxSKm9JSzN8vWIfH/+5hxplC/NNvyZUK1PY2WHdmMQLsOxdq0Bc4XLwwBSo09WtO4OvJ8tEYIwJBBCRb7Gmk1xke96JTOYMUEq5t/MJyTw3YwtLd56gW3AF/tsjiIL5XOwO9N2/W7OFnT9iFYi74zXwK+bsqJzOnn/FUGPMiMtPjDG/i8jbDoxJKZXH7DsZx/CpYRw8fYk3utRlYMsA15pM/sJx+P1Fq1JomTrwyBKP6gy+HnsSwSkReQX4EaupqB86Z4BSHmPx9uP8Z+YW/Hy9mDa0mWvNHZCWBht/gD9fh5QE6PAKtHwafFy43pED2JMI+gKvA3Ntz1fZliml3FhqmuGzpXv4ctk+GlYqzrf9GlO+WN6dbvEaMXuszuBDayGgjVUmunR1Z0eVJ103EdhuF306F2JRSuURsfHJPPPzJpbvjuGBEH/e6lYfP18XKbOckgRrPodVH1jzBHf9Chr18+jO4Ou5biIQkTLAC0A9IH2kiDGmgwPjUko5yd4TFxg+NZzos5d4p3t9Hm5W2XX6Aw5vgF+fgpM7oN79cM/7UKScs6PK8+xpGpoGzADuA0YAA4EYRwallHKOJduP89zMLfj5ejN9mAtVDU2Mg2Vvw7rvoGgF6Psz1Ork7Khchj2JoJQxZoKIPG2MWQmsFJGVjg5MKZV70tIMXyzby2dL99LQvxjf9m/iOv0Be5fCwmesMhFNh1lzBvsVdXZULsWeRHB59PAxEekMHAX8HReSUio3xSWm8NyMzSzZcYKejf15934X6Q+4dMaaLGbrz1C6JgxZDJWbOTsql2RPInhHRIoB/wG+BIoCzzo0KqVUrog6dZFhU8LYf+oir3epyyBXGB9gDET8Yo0LSDgHt78At49yu8liclO2iUBEvIEaxpiFQCxW1VGllBtYG3mKx37ciJfA1Eea0rKaC5SOjj1izRm853eo0Bi6LYBy9ZwdlcvLNhEYY1JFpCvwaS7Fo5TKBdPXH+LVeREEli7EhIGhVC5V0NkhZS8tDTZOhiWvQVoK3PUuNH8MvFygCcsF2NM0tFZEvsK6c+ji5YXGmI0Oi0op5RCpaYZ3f9vJxDUHaFerDF/2bUQRvzxecvl0pDUwLOpvCLwdunwOJas6Oyq3Yk8iaGn7+60Mywyg4wiUciEXEpIZOX0TK3bHMKRVIC/fWxufvDx/QGoK/Ps1LH8XvPNBly+g8QAdGOYA9ows1n4BpVzcodOXeOSHDRw4dZF376/Pw83yeN39E9th/hNwdBPUuhc6f2yND1AOkd2cxf2Any5PUZnJ+mpAeWPMakcFp5S6deEHzzJsShipaYYpQ5rSsnoe7hROSYK/P4K/Pwa/4tBrItTroVcBDpbdFUEpYJOIhGNNUhODVWKiOtAWOAWMdniESqmbtnDrUZ6buYUKxfyYOCiUqnl5EpnocOsqIGYnBD0A94yFQi5U6dSFZTcxzee2TuIOQCugARAP7AT6G2MO5U6ISqkbZYzhm5WRfPDHbkKqlGD8gBBKFsqjpZeTLln9AP9+DYVvg4dmQs27nR2VR7nu7aPAn7Y/SikXkJyaxitzI5gRdpiuDSvwQa8GeXekcNRqmP8knD0ATQbDnW/qjGFO4GLzzCmlshMbn8zj08JZs+80IztU57k7a+bNkcKJF6zJYsImQIlAGLgQAts4OyqPpYlAKTdx5Fw8gyetZ3/MRT7s1YDeIZWcHVLm9i2FX5+xisQ1f8KaNSxfHh/Q5uY0ESjlBiKOxDJk8gbik1Pz7p1B8Wdh8Suw+UcoXQse+RMqhTo7KoV9E9PkB3oCARm3N8a8ldVrlFK5Z+WeGB7/MZxiBXz55bGW1CxXxNkhXWvXIlj4LFyMgTb/sQrF+fpd/3UqV9hzRTAfq+BcOJDo2HCUUjdi5obDvDR3G7XKFWHS4FDKFc1jX66XzsDvL8C2WVCuPjw0AyoEOzsqdRV7EoG/MeYeh0eilLKbMYZPl+7li7/20qZGab7p14TC+fNYS++OBfDbc1aTULuXoPVz4JNHb2H1cPYWnQsyxmxzeDRKqetKTk3jpTnbmB0eTe8m/rzXIwjfvFQz6OIpWPQ8bJ8DtzWA/nPhtiBnR6WykV2JiW1YxeV8gMEish+raUgAY4xpkDshKqUui09K5bFp4azYHcMzHWvw9B018tbtodvnWfMFJMRC+1eg9TPgncerm6psrwjuu9Wdi8g9wOeAN/C9MWbsVesfBl60PY0DHjPGbLnV4yrljmLjk3lk8gY2HjrLf3sE0bdpZWeH9P8unrISwI55UD4YBv4K5eo6Oyplp+xKTBwEEJHmwHZjzAXb8yJAXeBgdju2zW42DrgTiAY2iMgCY8yODJsdANoaY86KSCdgPKCTjip1lZPnExgw0Roj8NVDjbk3qLyzQ/p/O+bDwucg8Tzc8Rq0fBq881h/hcqWPf9a3wCNMzy/mMmyzDQF9hlj9gOIyM9ANyA9ERhj1mbY/l/A3454lPIoh05fot+EdZyKS2TioFBa18gjYwQunYFFo6z5g8sHQ/dv9CrARdmTCMQYYy4/McakiYg9r6sIHM7wPJrsf+0/AvyeaQAiw4HhAJUr56HLYaUcbNfx8/SfsJ7k1DR+Gtac4ErFnR2SZedCa1xA/FntC3AD9nyh7xeRp7CuAgAeB/bb8brMerBMJssQkfZYiaB1ZuuNMeOxmo0ICQnJdB9KuZvwg2cYPGkDBfP58NOjLaiRFwaKxZ+FRS/AtpnWnUD958Jt9Z0dlbpF9txzNgJrusoj/P+v+mF2vC4ayFjsxB84evVGItIA+B7oZow5bcd+lXJ7a/edot/36ylVOD+zH8sjSWDvn/B1C+u20LajYdhyTQJuwp4rghrGmAczLhCRVlgT1WRnA1BDRAKxksiDwENX7acyMAdrfoM9dketlBtbvuskj/4YTmCpQvw4tBlliuR3bkAJ52HJGNg4BcrUgb4/6+hgN2NPIviSazuGM1t2BWNMiog8CSzGun10ojFmu4iMsK3/FngNaya0r233QqcYY0Ju7C0o5T7+iDjGyOmbqHVbEaYOaUYJZ08mc2AVzHsCzkdD62etEcI+Tk5MKsdlN6CsBVaTUBkReS7DqqJYX+zXZYxZBCy6atm3GR4PBYbeSMBKuav5m4/w3MwtNPQvxqTBTSlWwImdr0mX4K83Yd23ULIaDFkMlZo6Lx7lUNldEeQDCtu2ydhAeR7o5ciglPI0MzYcYvScbTQLLMmEgaEUcmbdoMMbYN4IOL0Pmo2AO17X+QLcXHYDylYCK0Vk8uXBZUqpnPfD2iheX7Cd22uW4bt+TSiQz0nTSqYkwcqxsPpTKFoRBiyAqm2dE4vKVdk1DX1mjHkG+EpErrll0xjT1ZGBKeUJJq05wJu/7uDOuuX46qFG5PdxUhI4HgFzR8CJbRDcD+55T+cO9iDZXX9Otf39UW4EopSnuZwE7q5Xji/7NiafjxMqiKamwNovYPl7UKCEdUdQrU65H4dyquyahsJtf68UkXxAbawBYbuNMUm5FJ9SbmmyLQncVdeJSeB0pHUVEL0e6naHzp9AoVK5H4dyOnumquwMfAtEYo0WDhSRR40xmZaDUEpl74e1UbxhSwJfPeSEJGAMhE2EJa9YZSF6fA9BvSAvlbNWucqeWxM+BtobY/YBiEg14DeyqAuklMralH+sjmGnJYHzx2DBk7BvKVTrAN3GQdEKuRuDynPsSQQnLycBm/3ASQfFo5TbmvJPFK/N327rGHZCEoj4xSoXnZII934EoUP1KkAB9iWC7SKyCJiJ1UfQG2tugR4Axpg5DoxPKbcwff2h9CQwLreTQPxZ+G0URMyGiiFw/3dQunruHV/lefYkAj/gBHD5huIYoCTQBSsxaCJQKhvzNx/h5bnbaF+rTO4ngchlVomIiyeh/RhrAnmdNEZd5bqfCGPM4NwIRCl3tGT7cZ6buYVmgSX5pl+T3EsCSZdg6Ruw/jsoXRP6/gQVGuXOsZXL0Z8GSjnI33tjePKnTQRVLMb3A0Px882lwWJHNsLcR+HUHqtERMc3wLdA7hxbuSRNBEo5wIaoMwyfEk7VMoX4YXBTCudG7aDUFKs8xMqxUKgs9J8H1do7/rjK5WkiUCqHbYuOZcikDZQv5sfUR5pRrGAuVBE9c8C6Cji8Dur3gs4fWSOFlbKDPQPKygHvARWMMZ1EpC7QwhgzweHRKeVi9p64wICJ6yhawDd3JpUxBrb8DIueB/GCnhOswWFK3QB7eq4mY00uc3nUyR7gGQfFo5TLOnE+gYET1+Pj7cVPw5pRobiD2+Xjz8LswVbJ6PIN4LHVmgTUTbEnEZQ2xswE0sCaeQxIdWhUSrmYCwnJDJq0gdj4ZCYNCqVKqUKOPeCBVfBNK9j5qzVfwMBfoXhlxx5TuS17+gguikgprDEDiEhzINahUSnlQpJT03h82kb2nrjAxEGh1K/owPLNKUmw7G1Y+yWUqg5Dl+ptoeqW2ZMIngMWANVEZA1QBp2hTCkAjDGM/mUbf+89xYe9GnB7zTKOO1jMbvhlKBzfCk0Gw93vQj4HX3koj2DPgLKNItIWqIVVfXS3MSbZ4ZEp5QI+/XMPv2yM5tmONekdUskxBzEGwibA4lesKSMfnA6173XMsZRHym6Gsh5ZrKopIlpjSHm86esP8cWyffQJqcRTdziodk9cjFUtdM8fUO0O6P4NFCnnmGMpj5XdFUEX299lgZbAMtvz9sAKtMaQ8mDLd53klXkRtK1Zhnfur484oorn3qXWHUEJ5+Ge96HpcPBywgQ2yu1lN0PZYAARWQjUNcYcsz0vD4zLnfCUynv2nrjAkz9tpPZtRRj3cGN8vXP4yzklEZa+Cf+Og7J1YcB8KFcvZ4+hVAb2dBYHXE4CNieAmg6KR6k8LTY+meFTwymQz5v/DQjJ+dIRp/ZZYwOOb7WuAO58G3z9cvYYSl3Fnk/xChFZDEzHuoX0QWC5Q6NSKg9KTTM8NX0T0Wcv8dOw5jk7YMwY2PyTNULYJx88+BPU7pxz+1cqG/bcNfSkreO4jW3ReGPMXMeGpVTe8+Hi3azcE8O799cnNKBkzu04IdaaOSxiNgS0gR7jdfpIlavsuq613SGkncPKYy3YcpRvV0byULPKPNysSs7tODoMZg+B2Gjo8Io1cYxXLpWrVsrmur1cItJcRDaISJyIJIlIqoicz43glMoLIo7E8sLsLYRUKcEbXXKo0zYtDf7+BCbebTULDf4dbn9ek4ByCnuuCL7C6heYBYQAAwCd8FR5hNNxiTw6NZziBfLxdb8cmmby/DGrZPSBlVC3O3T5HAoUv/X9KnWT7G0a2ici3saYVGCSiKx1cFxKOV1KahpP/rSJmLhEZo9oQdkiOXD3zp7FMO8xSI6Hrl9Co/7giDEISt0AexLBJRHJB2wWkQ+AY4AWOFFu78tl+/hn/2k+6t2QBv7Fb21nKYnw5+uw7hsoFwS9JkCZWjkSp1K3yp7r3P6AN/AkcBGoBPR0ZFBKOdu6/af5ctleejSuSK8m/re2szP7YcJdVhJoNsKqGKpJQOUh9tw+etD2MB5407HhKOV85y4l8cyMzVQuWZC3utW/tZ1tnwcLRlrNPzo2QOVR2RWd24ZtDoLMGGMaOCQipZzIGMOLv2zlVFwicx5rdfMjh5MTYMkY2PA9VAyBXhOhRA7edqpUDsruU35frkWhVB4xbd0hFm8/wZh76xDkf5MTzJyOhFmDrDIRLZ60ZhDzyZejcSqVk7IrOnfw6mUiUho4bYzJ8kpBKVe1+/gF3l64g7Y1y/BI68Cb28n2uTB/pDUeoO/PUKtTzgaplANk2VlsG0i2QkTmiEgjEYkAIoATInJP7oWolOPFJ6UycvpGivj58lHvhnh53eAtnSmJ8Nso60qgbG0YsVqTgHIZ2TUNfQW8DBTDmougkzHmXxGpjVWA7o9ciE+pXPHObzvYcyKOKUOaUqZI/ht78ZkDVgI4ttlqCur4Bnj7OiBKpRwju9tHfYwxS4wxs4Djxph/AYwxu+zduYjcIyK7RWSfiIzOZH1tEflHRBJFZNSNh6/UrVu26wTT1h3i0dur3vicwzt/he/aWsmgzzRrHmFNAsrFZHdFkJbhcfxV667bRyAi3lgT2NwJRAMbRGSBMWZHhs3OAE8B3e2KVqkcdikphVfnbadG2cL8564buLc/JQmWvg7/fg0VGkHvyVAiwFFhKuVQ2SWChrbicgIUyFBoTgB7xto3BfYZY/YDiMjPQDcgPREYY04CJ0VEb65WTvHFX/s4ci6emY+2sL+OUGy01RQUvQGaPgp3vQ0+N9icpFQekt1dQ7daBrEicDjD82ig2S3uU6kcs/v4Bb7/ez8PhPjTNNDO+QUil8EvQ63O4d6Tod79Do1RqdzgyJmwM7vt4qZuOxWR4SISJiJhMTExtxiWUpCWZhgzdxtF/HwY3amOPS+AlR/C1B5QqCwMX6FJQLkNRyaCaKy6RJf5A0dvZkfGmPHGmBBjTEiZMjfYmadUJmaFHybs4FleurcOJQtdZ7DXpTMwvQ8sfweCesGwv6B0jdwJVKlckMMzb19hA1BDRAKBI1hzGjzkwOMpZZfTcYn89/ddNA0sSe/rFZQ7shFmDoQLx+DejyB0qJaNVm7HYYnAGJMiIk8Ci7Gql040xmwXkRG29d+KyG1AGFAUSBORZ4C6xhidAU05zH9/30VcQgrvdq+PZPelvnEq/PYfKFQGhvwB/iG5F6RSuciRVwQYYxYBi65a9m2Gx8exmoyUyhX/7j/N7PBoHm9XjRrlimS+UUoi/P4ihE+CwLbQaxIUKpW7gSqVixyaCJTKS5JS0hgzdxuVShZgZIcs2vhjj8DMAXAkDFo9Ax1eBW/9b6Lcm37ClceYuOYAkTEXmTQolAL5Mrk7Omq1NT4gOR4emAJ1u+V6jEo5gyYC5REuJaXw3cpI2tUqQ/vaZa9caQys+xYWj4GSgTBwoVU4TikPoYlAeYSf1h3i7KVkRnaofuWK5Hj49WnYOgNqdYb7vwG/m5yHQCkXpYlAub3ElFT+9/d+mlctSZMqGUYQnzsMMx6GY1ug/RhoMwq8HDm0Rqm8SROBcnuzw6M5cT6Rj3sH///CqDVWp3BKok4gozye/vxRbi0lNY1vV0bSsFJxWlUvZfUHrP8fTOkKBUrAsGWaBJTH0ysC5dYWbDnK4TPxvHZfPSQ1CX57Djb9CDXvgR7jtT9AKTQRKDeWlmb4ekUktW8rwh2VBCbfB9Hr4fYXoN1L2h+glI0mAuW2Fm8/zr6TcUzqXAiv7++AizHQ+weo193ZoSmVp2giUG7JGMNXy/fxYPGdtPv7M8hXCAYvgoqNnR2aUnmOJgLlllbsPkmzEzN4xXcaclt9686gYhWdHZZSeZImAuV2TEoSyfOf4TXfRaTV6gw9/2ddESilMqW9Zcq9JMQSO6E7d8UvYlvgELz6/KhJQKnr0ESg3Me5wzDhbgof+5c3vZ6gxkMf6Z1BStlB/5co93BsC3zfEXM+miEpo/Fp0g8/30wqjCqlrqGJQLm+PUtgYifw8iHi7lmsSqlH00CdSEYpe2kiUK4tbCJMfxBKVYOhS1kVWwaAkColnByYUq5DE4FyTWlp8OfrsPBZqH4HDP4dipYnLOoMNcoWpkShfM6OUCmXoYlAuZ7UZJj3GKz5DEKGwIPTIX9h0tIMYQfPEhJQ8rq7UEr9Px1HoFxL0kWYORD2/QkdXrHmEBABYM/JC1xISCE0QJuFlLoRmgiU67h0Bqb1hqMbocvn0GTQFas3RJ0FIFSvCJS6IZoIlGuIPQJTu8PZg/DAVKhz3zWbhEWdoVzR/PiXKJD78SnlwjQRqLzvzH74oRvEn4X+cyCgdaabhUVZ/QNiaypSStlHO4tV3nZypzVGICkOBv2aZRI4ci6eI+fiCdXbRpW6YZoIVN51ZCNMsk0jOXgRVGiU5aZhUWcA9I4hpW6CJgKVNx1eDz90hfxFYMjvULZOtpuHRZ2lcH4fat9WJJcCVMp9aB+BynsOb4CpPaBwGRi40K55BDZEnaFR5eL4eOtvG6VulP6vUXlLdBj82AMKlbY7CcTGJ7P7xAW9bVSpm6SJQOUd0WEw9X4oWAoG/Wb3jGIbD53FGAjRgWRK3RRNBCpvOB1pNQcVLAmD7LsSuCws6gw+XkJwpeKOi08pN6aJQDlfajL88ohVKmLgr1DM/4ZeviHqLPUqFqNgPu3yUupmaCJQzrf8PTi6Cbp+AcUr39BLE1NS2XL4nI4fUOoWaCJQzhW1GlZ/Co36Q91uN/zyiCPnSUxJ0/EDSt0CTQTKeeLPwpxHoWRVuGfsTe3i/weS6RWBUjdLG1WVcxhjTSoTdxweWQL5C9/UbjZEnaVq6UKULpw/hwNUynPoFYFyjnXfwfa50P5lqNjkpnaRlmYIP3hGrwaUukWaCFTu2/cXLH4Jat8HrZ696d3sPxXH2UvJ2j+g1C3SRKBy16m9MGswlK0L938HXjf/EdSJaJTKGQ5NBCJyj4jsFpF9IjI6k/UiIl/Y1m8VkcaOjEc5WfxZmP4gePtC3+k33S9w2YaoM5QunI+AUgVzKEClPJPDOotFxBsYB9wJRAMbRGSBMWZHhs06ATVsf5oB39j+znEHd23k6LrZjti1slOV02sodyGK+Q2/5dimJGAf+by9yOfjRX4fL/L7elHUz5cShfJRomA+ShXOR1E/3yz3FxZ1lpAqOhGNUrfKkXcNNQX2GWP2A4jIz0A3IGMi6AZMMcYY4F8RKS4i5Y0xx3I6mFP7t9DiwLic3q26AYnGhxeSh/LLvwWB3dfd3sdLGPdwY+6ud9s166JOXeTQmUsMaFHFAZEq5VkcmQgqAoczPI/m2l/7mW1TEbgiEYjIcGA4QOXKNzby9LLgu/qT2KHPTb1W5RDx4j1vX96zPTUGklPTSEpJIzEljYTkVGLjkzl3KZmzl5IYt3wfHy7ezZ11yuHldeWv/u9WRZLPx4suDSvk/vtQys04MhFkdr1ubmIbjDHjgfEAISEh16y3h7ePD94+Omwir/Hz9c5ynY+3F09N38Qf249zb1D59OVHzsUzOzyaB0MrU66oX26EqZRbc2RncTRQKcNzf+DoTWyjPFTnoPJULVOIL5ftw2o9tHy3MhJj4NG2VZ0YnVLuw5GJYANQQ0QCRSQf8CCw4KptFgADbHcPNQdiHdE/oFyTt5fwRLvq7Dx2nqU7TwJw8nwCP284TM/G/viX0LuFlMoJDksExpgU4ElgMbATmGmM2S4iI0RkhG2zRcB+YB/wP+BxR8WjXFO34ApUKlmAr5btxRjD+FX7SU0zPN6+mrNDU8ptOLTR3BizCOvLPuOybzM8NsATjoxBuTYfby8eb1edl+ZsY97mI0xbd4huDStQpVQhZ4emlNvQkcUqz+vZ2J8Kxfx4ftZWElJSebx9dWeHpJRb0USg8rx8Pl6MaFeNlDTDvUHlqV721kYkK6WupPdTKpfwQEglDp6+xKCWAc4ORSm3o4lAuQQ/X29eva+us8NQyi1p05BSSnk4TQRKKeXhNBEopZSH00SglFIeThOBUkp5OE0ESinl4TQRKKWUh9NEoJRSHk4y1nl3BSISAxx0dhx2Kg2ccnYQeYyek2vpOcmcnpdr3co5qWKMKZPZCpdLBK5ERMKMMSHOjiMv0XNyLT0nmdPzci1HnRNtGlJKKQ+niUAppTycJgLHGu/sAPIgPSfX0nOSOT0v13LIOdE+AqWU8nB6RaCUUh5OE4FSSnk4TQQOIiJRIrJNRDaLSJiz43EGEZkoIidFJCLDspIi8qeI7LX9XcKZMea2LM7JGyJyxPZZ2Swi9zozxtwmIpVEZLmI7BSR7SLytG25x35WsjknDvmsaB+Bg4hIFBBijPHYATEicjsQB0wxxtS3LfsAOGOMGSsio4ESxpgXnRlnbsrinLwBxBljPnJmbM4iIuWB8saYjSJSBAgHugOD8NDPSjbn5AEc8FnRKwLlMMaYVcCZqxZ3A36wPf4B68PtMbI4Jx7NGHPMGLPR9vgCsBOoiAd/VrI5Jw6hicBxDLBERMJFZLizg8lDyhljjoH1YQfKOjmevOJJEdlqazrymCaQq4lIANAIWId+VoBrzgk44LOiicBxWhljGgOdgCdsTQJKZeYboBoQDBwDPnZqNE4iIoWBX4BnjDHnnR1PXpDJOXHIZ0UTgYMYY47a/j4JzAWaOjeiPOOErf3zcjvoSSfH43TGmBPGmFRjTBrwPzzwsyIivlhfeNOMMXNsiz36s5LZOXHUZ0UTgQOISCFbBw8iUgi4C4jI/lUeYwEw0PZ4IDDfibHkCZe/7Gzux8M+KyIiwARgpzHmkwyrPPazktU5cdRnRe8acgARqYp1FQDgA/xkjHnXiSE5hYhMB9phlc49AbwOzANmApWBQ0BvY4zHdJ5mcU7aYV3qGyAKePRy27gnEJHWwN/ANiDNtvhlrDZxj/ysZHNO+uKAz4omAqWU8nDaNKSUUh5OE4FSSnk4TQRKKeXhNBEopZSH00SglFIeThOBytNE5FMReSbD88Ui8n2G5x+LyHMi0tVWmOxG9j1ZRHrlYLg3TEQGichXWazrLiKv3cQ+XxKRh7NYFyQik290n8q9aSJQed1aoCWAiHhh3X9fL8P6lsAaY8wCY8xYJ8TnSC8AX9/E6+4ClmS2whizDfAXkcq3EphyL5oIVF63BlsiwEoAEcAFESkhIvmBOsCmjL+sbb/0vxCRtSKy//KvfrF8JSI7ROQ3sihiJiJP2bbZKiI/25a9ISJTRWSZrT7+sAzbPy8iG2zbv5lheT8RWW+rG/+diHjblg8WkT0ishJolUUMNYHEy2XMbe/pG1uN+v0i0tZWdGxnxl/4IlIUyGeMiRGR3iISISJbRGRVht3/Cjxo97+Acns+zg5AqewYY46KSIrtF2xL4B+scrwtgFhgqzEmyRqRf4XyQGugNlapgtlYQ/JrAUFAOWAHMDGTw44GAo0xiSJSPMPyBkBzoBBW8vkNqA/UwKr5IsACW4HBGKAPVvHBZBH5GnhYRP4E3gSa2OJfDmzKJIZWwMarlpUAOgBdsb7MWwFDgQ0iEmyM2Qx0BP6ybf8acLcx5shV7yPM9h4/yOS4ygNpIlCu4PJVQUvgE6xE0BLri3RtFq+ZZyvMtUNEytmW3Q5MN8akAkdFZFkWr90KTBOReVglMS6bb4yJB+JFZDnWl39rrKaYy1/mhbESQwOsL/sNtiRVAKtoWjNghTEmBkBEZgA1M4mhPFYyyehXY4wRkW3ACVszDyKyHQgANgP3AJNs268BJovITGBOhv2cBCpk8d6VB9KmIeUKLvcTBGE1Df2LdUXQEuvLLjOJGR5nvFywp6ZKZ2Ac1hd5uIhc/sF09WuNbd//NcYE2/5UN8ZMsC3/IcPyWsaYN24ghnjA76pll99TGle+vzT+/0ddU2A9gDFmBPAKUAnYLCKlbNv42favFKCJQLmGNcB9WNMWptoKjxXHSgb/3MB+VgEPioi3rYpj+6s3sHVIVzLGLMfqrC2O9SsfoJuI+Nm+UNsBG4DFwBBb3XhEpKKIlMVqnulle3x5/t0qWIXU2olIKVuZ4d5ZxLoTqH4D7w0RqQfssl3xICLVjDHrjDGvAaewEgJYVyAeVeFUZU+bhpQr2IZ1t9BPVy0rfINzQs/FamPfBuwBVmayjTfwo4gUw/pV/6kx5pyteWc98BtWNcy3bXNOHBWROsA/tm3igH7GmB0i8grWLHVeQDLwhDHmX7HmKP4Ha2KRjbZjXm0V8LGIiLG/MmQn4I8Mzz8UkRq29/EXsMW2vL3tfSgFaPVRpewiTphgXkQ+x+oXWGrn9n8CA7IrS2y702ol0NoYk5IzkSpXp01DSuVd7wEF7d3YGHOnHbXpKwOjNQmojPSKQCmlPJxeESillIfTRKCUUh5OE4FSSnk4TQRKKeXhNBEopZSH+z87rv7LmOzOqwAAAABJRU5ErkJggg==\n", + "image/png": "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\n", "text/plain": [ - "
" + "
" ] }, - "metadata": { - "needs_background": "light" - }, + "metadata": {}, "output_type": "display_data" } ], @@ -459,13 +447,13 @@ "text": [ " \n", "------------------------------------------------------------------------------\n", - "Running ROSCO-v2.5.0\n", + "Running ROSCO-v2.6.0\n", "A wind turbine controller framework for public use in the scientific field \n", "Developed in collaboration: National Renewable Energy Laboratory \n", " Delft University of Technology, The Netherlands \n", "------------------------------------------------------------------------------\n", "Generator speed: 9.5 RPM, Pitch angle: 0.0 deg, Power: 0.0 kW, Est. wind Speed: 10.0 m/s\n", - "Generator speed: 673.4 RPM, Pitch angle: 0.1 deg, Power: 340.7 kW, Est. wind Speed: 4.6 m/s\n", + "Generator speed: 673.4 RPM, Pitch angle: 0.1 deg, Power: 340.8 kW, Est. wind Speed: 4.6 m/s\n", "Generator speed: 751.3 RPM, Pitch angle: 0.1 deg, Power: 853.4 kW, Est. wind Speed: 7.1 m/s\n", "Generator speed: 800.7 RPM, Pitch angle: 0.1 deg, Power: 1072.2 kW, Est. wind Speed: 6.8 m/s\n", "Generator speed: 781.4 RPM, Pitch angle: 0.1 deg, Power: 1190.5 kW, Est. wind Speed: 6.8 m/s\n", @@ -569,14 +557,12 @@ }, { "data": { - "image/png": "iVBORw0KGgoAAAANSUhEUgAAAZAAAAJNCAYAAAAf9yOgAAAAOXRFWHRTb2Z0d2FyZQBNYXRwbG90bGliIHZlcnNpb24zLjUuMiwgaHR0cHM6Ly9tYXRwbG90bGliLm9yZy8qNh9FAAAACXBIWXMAAAsTAAALEwEAmpwYAABp20lEQVR4nO3dd5xU1f3/8ddnZxu9u9IUNKhBRBEsiEkWe9RYYoqmaxLSjOmJ+aaZYjT+0o0laIwmGkhi11iwsPYGioKggkhZQHrZXmY+vz/u3WVYlmV35u7M7s77+XiMM7eec3ZxPnvKPcfcHRERkY7Ky3YGRESke1IAERGRlCiAiIhIShRAREQkJQogIiKSEgUQERFJSX62M5BJQ4cO9TFjxqR0bVVVFX369Ik2Q12cypwbVObckE6Z58+fv8ndh7Xcn1MBZMyYMcybNy+la8vKyigtLY02Q12cypwbVObckE6ZzWxla/vVhCUiIinJqRqIiEi2VNU18tKKLWRr8o+K+ugTTjuAmNko4HzgfcAIoAZYBPwPeNDdE+mmISLS3d3w1HL++OjSrKX/7clFkd8zrQBiZn8HRgL3A78BNgDFwEHAacCPzOxSd38y3YyKiHRnlbWNFBfkMXvG1Kykv+aNVyK/Z7o1kN+5+6JW9i8C7jSzQmC/NNMQEen2GhNOQSyPI0YPzEr62962yO+ZVid6a8HDzAaZ2cTweL27L0snDRGRniDhTiwv+i/xbIpkFJaZlZlZfzMbDLwK/N3Mfh/FvUVEeoJ4wslXAGnVAHffAXwY+Lu7TwZOiujeIiLdXjzh5JkCSGvyzWw48DGCDvV2MbObzGyDmS1K2neZma0xswXh6/Q9XHuamb1pZsvM7NL0iyAi0nniCTVh7ckvgIeBZe7+kpkdALRnvNrNBKO1WvqDux8Rvh5oedDMYsA1wAeB8cAFZjY+5dyLiHSyuKsGsgszu8DMhrj7f919ort/FcDdl7v7eXu7PhzeuyWFpI8mCFbL3b0emA2cncJ9REQyoifWQNIdxrs/8F8zKwAeAx4EXvT0F1q/2Mw+A8wDvuPuW1scHwmsTtouB45JM00RyQHfnP0K85ZV0+eVzD6etnZbDUP7Rf8wXzZZ+t/1YGb9CDrNTyOoHSwBHgIedvf1e7l2DHC/u08It0uATYADvwSGu/tFLa75KHCqu38h3P40cLS7f72V+88AZgCUlJRMnj17dkplrKyspG/fvild212pzLkh18p84UNV7NPLGdU/8zM5HTokxgn7FWQ8XUjv9zx9+vT57j6l5f5IfoLuXgHcFb4I+yM+CPwDOLWD92oOOGZ2A613ypcDo5O2RwFr93C/mcBMgClTpniqs1Fq9s7coDL3bO6OP/QAx44o5E9fPCXb2cmozvg9RxaCw4cHxyTd8x1371DwCO8z3N3XhZvnEjzV3tJLwDgzGwusIZiL6xMdzrSI5JRE2ODSw7oisiaSAGJmNwETgdeBpskTHbhzL9fNAkqBoWZWDvwMKDWzI8LrVwBfCs8dAdzo7qe7e6OZXUww8isG3OTur0dRFhHpueJhBFEAiUZUNZBj3b3Dw2jd/YJWdv9tD+euBU5P2n4A2G2Ir4jIniiARCuq50Ce03MYItLVxb0pgCiCRCGqGsgtBEHkXaAOMMDdfWJE9xcRSZtqINGKKoDcBHwaWMjOPhARkS4loQASqagCyCp3vzeie4lID1dTH+exN9bTGM/s+q4VdY2AAkhUogogb5jZv4D7CJqwAHD3NkdhiUhuumfBGi69c2HW0u9fqAgShagCSC+CwJH8ZM5eh/GKSG6qro8DcO/F0+hXnNknswtixrJXX8xomj1VVE+iXxjFfUQkNyTC0VBjhvahf4YDCICWSY1GurPx/jhchXBPx08wszPTSUNEep6m0VA9bYW+XJNuDWQhcJ+Z1QIvAxuBYmAccATwKPDrNNMQkR6mMaHnMXqCtAKIu98D3GNm44BpwHBgB3ArMMPda9LPooj0NE3DaXva+hi5Jqo+kKW0bwVCEZHmJ8JjqoF0a1FNZSIi0m7ND/SpBtKtKYCISMY1Jlwd6D1A5pfkEpEu44d3LuTh16opeu6xjKa7o6ZB/R89QFoBxMyuJnhgsFXufkk69xeRzvX0so3k58H7xg3NeNqH7Ns/42lKtNKtgcwL36cB44F/h9sfBebv7eJwIaozgQ1Ja6L/P+BDQD3wNnChu29r5doVQAUQBxpbW69XRNqWSMC4gTGu+sjh2c6KdENp9YG4+y3ufgvBcx/T3f1qd78aOJHgOZC9uRk4rcW+R4AJ4VTwbwE/bOP66e5+hIKHSGriCdfEgpKyqDrRRwD9krb7hvva5O5PAlta7Jvj7o3h5vPAqIjyKCItNCacmAKIpCiqTvQrgVfMbG64/QHgsgjuexE7m8VacmCOmTnwV3efGUF6Ijkl4aqBSOrMPZr5+M1sX+CYcPMFd3+3ndeNAe5v6gNJ2v8jYArwYW8lk2Y2wt3Xmtk+BM1eXw9rNC3PmwHMACgpKZk8e/bsDpRqp8rKSvr27ZvStd2Vytzzfe2xKiYPdS46PHfKDLn3e4b0yjx9+vT5rXUVRFIDMTMDTgIOcPdfmNl+Zna0u6c0Z7KZfZagc/3E1oIHgLuvDd83mNldwNHAbgEkrJnMBJgyZYqXlpamkiXKyspI9druSmXu+fLmPkxxITlVZsi93zN0Tpmj6gO5FpgKXBBuVwDXpHIjMzsN+AFwlrtX7+GcPmbWr+kzwToki1JJTySXxdWEJWmIqg/kGHc/0sxeAXD3rWZWuLeLzGwWUAoMNbNy4GcEo66KgEeCig3Pu/uXzWwEcKO7nw6UAHeFx/OBf7n7QxGVRSSj6hrj3PPKWmoa4hlPu74xQZ7peWJJTVT/chrMLEb4UKGZDQMSe7vI3S9oZfff9nDuWuD08PNyQAPXpUd4fvkWvn/Ha1lLf0gvVUEkNVEFkD8DdwElZnY58BHgxxHdW6RHqw1rHv/64jEZfzo7z2DBi89mNE3pOaKazv02M5tP8AChAee4+5Io7i3S0zXNTDu4TyGD++y15Veky4hyNt6hQLW7/wXYZGZjI7y3SI+ltTGku4okgJjZzwhGTjVNO1JAsCqhiOxFXGtjSDcVVQ3kXOAsoAqaO7z7tXmFiAA7A4hqINLdRBVA6sMH/ppGYfWJ6L4iPV5c64NLNxVVAPmPmf0VGGhmXwQeBW6I6N4iPZoCiHRXUY3C+q2ZnQzsAA4Cfuruj0Rxb5GerrkTXQFEupkoH0FdCPQiaMZaGOF9RTLiigeWcPMzVcQez+ykBo3xIIBojXDpbqKaTPELwE+BxwmeA7nazH7h7jdFcX+RTHi1fBu9842PHL1fxtPed0AvhvQtyni6IumIqgbyPWCSu28GMLMhwLOAAoh0G4kElPQxfnTG+GxnRaRbiKoTvZxgBt4mFcDqiO4tkhGNiYRW5xPpgKhqIGuAF8zsHoI+kLOBF83s2wDu/vuI0hHpNHEH07MYIu0WVQB5O3w1uSd818OE0m0kElobQ6QjohrG+/Omz2Y2CNi2p5UEk5nZTQQrD25oWtLWzAYTrIM+BlgBfMzdt7Zy7WnAn4AYwTohV6ZfEsll8YRTpAAi0m5p9YGY2U/N7JDwc5GZPU5QE1lvZie14xY3A6e12Hcp8Ji7jwMeC7dbphsjWPHwg8B44AIzU8+npCWh1flEOiTdTvSPA2+Gnz8b3m8Y8AHg13u72N2fBLa02H02cEv4+RbgnFYuPRpY5u7L3b0emB1eJ5KyxoSj+CHSfuk2YdUnNVWdCsxy9ziwxCzldTJL3H0dgLuvM7N9WjlnJLuO8ioHjkkxPelCEgnn1hdWsq26IeNpb66sY0hm13MS6dbSDSB1ZjYBWA9MB76bdKx3mvduS2t/KLba52JmM4AZACUlJZSVlaWUYGVlZcrXdlfZKPOaygQ/fbomo2kmGzrU9XvOASpzNNININ8AbidotvqDu78DYGanA6+keM/1ZjY8rH0MBza0ck45MDppexSwtrWbuftMYCbAlClTvLS0NKVMlZWVkeq13VU2yrxozXZ4+mmu/9SRnDx+34ymDfDUk0/o95wDVOZopBVA3P0F4JBW9j8APJDibe8l6E+5Mny/p5VzXgLGhasergHOBz6RYnrShSTCFtGCWJ4mFxTp4qJc0rbDzGwW8BxwsJmVm9nnCQLHyWa2FDg53MbMRpjZAwDu3ghcDDwMLAH+4+6vZ6MMEq1Grc4n0m1EORtvh7n7BXs4dGIr564FTk/aTqeWI11UQqvziXQbWa2BiLTUtLiSpjYX6frSqoGY2YfbOu7ud6Zzf8k9cTVhiXQb6TZhfSh83wc4jmA9EAiG9JYBCiDSIVqdT6T7SHcU1oUAZnY/ML7pAcBw+O016WdPsqkx4TTEExlNs74xSC9PfSAiXV5UnehjmoJHaD3B2ujSTV1btoyr5lTDnAezkn5RvrrnRLq6qAJImZk9DMwieCL8fGBuRPeWLHh7QxW98uFrJ2T+74B+xQW8d7jmFBHp6qKazv3isEP9feGume5+VxT3luyIJxL0LTAuPmFctrMiIl1UZM+BhCOu1GneQ8QdTW0uIm2KpKHZzD5sZkvNbLuZ7TCzCjPbEcW9JTu0Op+I7E1UNZCrgA+5+5KI7idZFk84MQUQEWlDVENd1it49Cxxd0xDaUWkDVHVQOaZ2b+Bu4G6pp16Er37iqsJS0T2IqoA0h+oBk5J2ueoU73bUgARkb2JahjvhVHcR3b392feoXxr5lfoW7ahkl4KICLShnQnU/y+u19lZlfTypKy7n5JOvfPdZV1jfz8vsUUxvIozMKT2eP31dPgIrJn6dZAmjrO56WbkWRmdjDw76RdBwA/dfc/Jp1TSrBa4Tvhrjvd/RdR5iPbGsN5qH54+iFcOG1sxtPPtTWjRaRj0g0gB5rZUcBt4SqBkXD3N4EjAMwsRrBsbWtPtj/l7mdGlW5X07Q6n2amFZGuKN0AMgr4E3CImb0GPAs8Azzn7lvSzVzoROBtd18Z0f26jabV+TQzrYh0RWk1crv7d939OGBf4P+ALcBFwCIzWxxB/iCYmHHWHo5NNbNXzexBMzs0ovS6jKa1MbQ6n4h0Rea+W993x29iNgCYCkwL3wcCC9MdnWVmhcBa4FB3X9/iWH8g4e6VZnY68Cd3323mPzObAcwAKCkpmTx79uyU8lJZWUnfvn1TujZVm2oSfPeJGj4/oZD3jSrIaNqQnTJnm8qcG1Tmjpk+ffp8d5+y2wF3T/kFzCRosnoI+DnwQWBQOvdscf+zgTntPHcFMLStcyZPnuypmjt3bsrXpmrFpkrf/wf3++3zVmc8bffslDnbVObcoDJ3DDDPW/lOTXec5n5AEfAuQUd3ObAtzXsmu4A9NF+Z2b4WzrVhZkcTNMdtjjDtrIurE11EurB0l7Q9LfwSP5RgTfTvABPMbAtBR/rPUr23mfUGTga+lLTvy2G61wMfAb5iZo1ADXB+GCkjV1nXyI46Z1Nl3d5PjtDmqnoA8hRARKQLSvtJ9PBLe5GZbQO2h68zgaOBlAOIu1cDQ1rsuz7p81+Av6R6/474zYNv8M/nq2Huo5lIbjfFWt5VRLqgdJ9Ev4Sg5jENaCAcwgvcBCxMO3ddxJkTh8OOdRw0LvOr8xUVxHj/QcMynq6IyN6kWwMZA9wOfMvd16Wfna7pmAOGULOqgNKpY7KdFRGRLiPdPpBvR5URERHpXtS4LiIiKYnkQcLuwsw2AqlOiTIU2BRhdroDlTk3qMy5IZ0y7+/uu3XG5lQASYeZzfPWnsTswVTm3KAy54bOKLOasEREJCUKICIikhIFkPabme0MZIHKnBtU5twQeZnVByIiIilRDURERFKiACIiIilRABERkZQogIiISEoUQEREJCUKICIikhIFEBERSYkCiIiIpEQBREREUqIAIiIiKVEAERGRlCiAiIhIShRAREQkJfnZTNzMTgP+BMSAG939yhbHLTx+OlANfM7dXw6PrQAqgDjQ2J6VtoYOHepjxoxJKa9VVVX06dMnpWu7K5U5N6jMuSGdMs+fP39Ta0va4u5ZeREEjbeBA4BC4FVgfItzTgceBAw4Fngh6dgKYGhH0pw8ebKnau7cuSlf212pzLlBZc4N6ZQZmOetfKdmswnraGCZuy9393pgNnB2i3POBv4RluF5YKCZDc90RkVEZHfZDCAjgdVJ2+Xhvvae48AcM5tvZjM6LZciItKqbPaBWCv7Wi6P2NY509x9rZntAzxiZm+4+5O7JRIElxkAJSUllJWVpZTZysrKlK/trlTm3KAy54bOKHM2A0g5MDppexSwtr3nuHvT+wYzu4ugSWy3AOLuMwnXAp4yZYqXlpamlNmysjJSvba7UplzQybK3NDQQHl5ObW1tZ2aTnsNGDCA4uLibGcjo9pT5uLiYkaNGkVBQUG77pnNAPISMM7MxgJrgPOBT7Q4517gYjObDRwDbHf3dWbWB8hz94rw8ynALzKYdxHpgPLycvr168eYMWMIBldmV0VFBf369ct2NjJqb2V2dzZv3kx5eTljx45t1z2zFkDcvdHMLgYeJhiRdZO7v25mXw6PXw88QDASaxnBMN4Lw8tLgLvCf4j5wL/c/aEMF0FE2qm2trbLBA9pnZkxZMgQNm7c2O5rsvociLs/QBAkkvddn/TZga+1ct1y4PBOz6CIREbBo+vr6O9IT6KLSE741re+xR//+Mfm7VNPPZUvfOELzdvf+c53+MUvfsGVV17ZytV79rnPfY7bb78dgNLSUg4++GAmTpzIIYccwsUXX8y2bduazz3uuOPSKkOTm2++mbVrd3YZf+ELX2Dx4sWR3LsjFEBEJCccd9xxPPvsswAkEgk2bdrE66+/3nz82Wef5dRTT+XSSy9NK53bbruN1157jddee42ioiLOPnvn421N6SeLx+MdTqNlALnxxhsZP358ahlOgwKIiOSEadOmNX+BL1myhAkTJtCvXz+2bt1KXV0dS5Ys4dVXX+Xiiy8GgprFJZdcwnHHHccBBxzQXMtwdy6++GLGjx/PGWecwYYNG1pNr7CwkKuuuopVq1bx6quvAtC3b18gGPk2ffp0PvGJT3DYYYcRj8f53ve+x1FHHcXEiRP561//2nyfq666isMOO4zDDz+cSy+9lNtvv5158+bxyU9+kiOOOIKamhpKS0uZN28eALNmzeKwww5jwoQJ/OAHP2i+z/Dhw/nRj37E4YcfzrHHHsv69evT/plmtQ9ERHLPz+97ncVrd0R6z/Ej+vOzDx3a5jkjRowgPz+fVatW8cILLzB16lTWrFnDc889x4ABA5g4cSKFhYW7XLNu3Tqefvpp3njjDc466yw+8pGPcNddd/Hmm2+ycOFC1q9fz/jx47noootaTTMWi3H44YfzxhtvcPjhu3bbvvjiiyxatIixY8cyc+ZMBgwYwEsvvURdXR3Tpk3jlFNO4Y033uDuu+/mhRdeoHfv3mzZsoXBgwfzl7/8hd/+9rdMmbLrFIBr167lBz/4AfPnz2fQoEGccsop3H333ZxzzjlUVVVx7LHHcvnll/P973+fG264gR//+Mcp/LR3Ug1ERHJGUy2kKYBMnTqVZ599lmeffbbV/olzzjmHvLw8xo8f3/wX+5NPPskFF1xALBZjxIgRnHDCCW2mGYwF2t3RRx/dPFx2zpw5/OMf/+CII47gmGOOYfPmzSxdupRHH32UCy+8kN69ewMwePDgNtN66aWXKC0tZdiwYeTn5/PJT36SJ58MHo8rLCzkzDPPBGDy5MmsWLGizXu1h2ogIpJRe6spdKamfpDFixczYcIERo8eze9+9zv69+/PRRddxObNm3c5v6ioqPlzciBo72ileDzOwoULee9737vbseSZcd2dq6++mlNPPXWXcx566KEOjYzaU7ACKCgoaL5XLBajsbGx3ffdE9VARCRnTJs2jfvvv59BgwYRi8UYPHgw27Zt47nnnmPq1Kntusf73/9+Zs+eTTweZ926dcydO7fV8xoaGvjhD3/I6NGjmThxYpv3PPXUU7nuuutoaGgA4K233qKqqopTTjmFm266ierqagC2bNkCQL9+/aioqNjtPscccwxPPPEEmzZtIh6PM2vWLD7wgQ+0q1ypUA1ERHLGYYcdxqZNmzjvvPN22VdZWcnQoUPbdY9zzz2Xxx9/nMMOO4yDDjpoty/oT37ykxQVFVFXV8dJJ53EPffcs9d7fuELX2DFihUceeSRuDvDhg3j7rvv5rTTTmPBggVMmTKFwsJCTj/9dH7961/zuc99ji9/+cv06tWL5557rvk+w4cP54orrmD69Om4O6effvouo8CiZm1VeXqaKVOmeNNIhY7SHEm5QWXuHEuWLGm1GSdbNJXJnrX2uzKz+d7Kon1qwhIRkZQogIiISEoUQEREJCV77UQPF2yaBowAaoBFBOvjJjo5byIi0oXtMYCY2XTgUmAw8AqwASgGzgEONLPbgd+5e7SPlIqISLfQVg3kdOCL7r6q5QEzywfOBE4G7uikvImISBe2xz4Qd/9ea8EjPNbo7ne7u4KHiHQLZsZ3vvOd5u3f/va3XHbZZZGmkTyp4ZgxY9i0adNer3nllVcwMx5++OG00i4rK2ueqiRT9tqJbmbfbuX1eTM7IgP5ExGJRFFREXfeeWe7vtQzadasWRx//PHMmjUr21npsPaMwpoCfBkYGb5mAKXADWb2/c7LmohIdPLz85kxYwZ/+MMfdjt23333ccwxxzBp0iROOumk5okTKysrufDCCznssMOYOHEid9wRNLrMmTOHqVOncuSRR/LRj36UysrKNtO+9dZbOfroozniiCP40pe+1LwGiLtz++23c/PNNzNnzhxqa2sBWLFiBe9973v54he/yKGHHsopp5xCTU0NEEyYOHHiRKZOncr3vvc9JkyYsFt6VVVVXHTRRRx11FFMmjSpXU/Dp6I9U5kMAY5090oAM/sZcDvwfmA+cFWn5ExEeqYHL4V3F0Z7z30Pgw/ufSXBr33ta0ycOJGvfOUru+w//vjjef755zEzbrzxRq666ip+97vf8ctf/pIBAwawcGGQ361bt7Jp0yZ+9atf8eijj9KnTx9+85vf8Pvf/56f/vSnraa5ZMkS/v3vf/PMM89QUFDAV7/6VW677TY+85nP8MwzzzB27FgOPPBASktLeeCBB/jwhz8MwNKlS5k1axY33HADH/vYx7jjjjv41Kc+xYUXXsjMmTM57rjj9rj41eWXX84JJ5zATTfdxLZt2zj66KN58sknI3/6vj0BZD+gPmm7Adjf3WvMrC7S3IiIdKL+/fvzmc98huuvv56BAwc27y8vL+fjH/8469ato76+vnma9UcffZTZs2c3nzdo0CDuv/9+Fi9ezLRp0wCor69vcyLGxx57jPnz53PUUUcBUFNTwz777AMEzVfnn38+AOeffz7//Oc/mwPI2LFjOeKII4Cd069v27aNioqK5qnnP/GJT3D//ffvluacOXO49957+e1vfwtAbW0t5eXl7Lvvvh3+mbWlPQHkX8DzZtZUB/oQMMvM+gCZX4RXRLq3dtQUOtM3v/lNJk2atMsiUF//+tf59re/zVlnnUVZWVlz57q77zadurtz8sknt7vPwt357Gc/yxVXXLHL/ng8zh133MG9997L5ZdfjruzefPm5ll2k6eSj8Vi1NTUtDlde8s077jjDg4++ODmfa3N3puuvfaBuPsvgS8C24DtwJfd/RfuXuXun4w8RyIinWjw4MGce+65/O1vf2vet337dkaOHAnALbfc0rz/lFNO4S9/+Uvz9tatWzn22GN55plnWLZsGQDV1dW89dZbe0zvxBNP5Pbbb29e+nbLli2sXLmSRx99lMMPP5zVq1ezYsUKVq5cyXnnncfdd9+9x3sNGjSIfv368fzzzwPsUjtKduqpp3L11Vc3B5xXXnmlrR9Jyto7lUkvYIe7/xFYaWZjOyU3IiIZ8PWvf32X0ViXXXYZH/3oR3nf+963y7TuP/7xj9m6dSsTJkzg8MMPZ+7cuQwbNoybb76ZCy64gIkTJ3Lsscfyxhtv7DGt8ePH86tf/YpTTjmFiRMncvLJJ7Nu3TpmzZrFueeeu8u55513Hv/617/azPvf/vY3ZsyYwdSpU3F3BgwYsNs5P/nJT2hoaGDixIlMmDCBn/zkJ+390XSMu7f5An4G3Ae8FW6PAJ7Z23Vd8TV58mRP1dy5c1O+trtSmXNDJsq8ePHiTk+jI3bs2JHtLKSsoqKi+fMVV1zhl1xySbuua2+ZW/tdEUxftdt3anv6QM4FJgEvhwFnrZnl1kT6IiJdxP/+9z+uuOIKGhsb2X///bn55puzlpf2BJB6d3czc4Cw81xERLLg4x//OB//+MeznQ2gfX0g/zGzvwIDzeyLwKPADZ2bLRER6er2WgNx99+a2cnADuBg4Kfu/kin50xEehRvZUisdC3ewSXO29OERRgwFDREJCXFxcVs3ryZIUOGKIh0UR4+h1JcXNzua9paD6QC2GM4cvf+HcueiOSqUaNGUV5ezsaNG7OdFSB4MrsjX5Q9QXvKXFxczKhRo9p9zz0GEHfvB2BmvwDeBf4JGPBJQKOwRKTdCgoKmqcH6QrKysqYNGlStrORUZ1R5vZ0op/q7te6e4W773D364DzIs2FiIh0O+0JIHEz+6SZxcwsz8w+CcQ7O2MiItK1tSeAfAL4GLA+fH003CciIjmsPZMprnD3s919qLsPc/dz3H1FFImb2Wlm9qaZLTOz3Sa2t8Cfw+OvmdmR7b1WREQ61x4DiJn92MwGt3H8BDNLeQFeM4sB1wAfBMYDF5jZ+BanfRAYF75mANd14FoREelEbT0HshC4z8xqCebB2ggUE3yZH0HwRPqv00j7aGCZuy8HMLPZwNnsusbI2cA/wsm8njezgWY2HBjTjmsjs/adN9i+ZjFvzMutrp/ta95UmXOAypwb6mqqI79nW8N47wHuMbNxwDRgOMHT6LcCM9y9Js20RwKrk7bLgWPacc7IPexveW1kVv/vN5y96U5Y2lkpdE2HgMqcA1Tm3PDmfj8mWA8wOu2ZymQpsNTM+rh7VYRpt/Y4assHF/d0TnuuDW5gNoOg+YuSkhLKyso6kMVARUkp/y14D4UFhR2+tjurb6hXmXOAypwb4v1GpvT915a9BhAzmwr8DegL7GdmhwNfcvevppl2OTA6aXsUsLad5xS241oA3H0mMBNgypQpXlpamlJmy8rKSPXa7kplzg0qc27ojDK3ZxjvH4FTgc0A7v4q8P4I0n4JGGdmY82sEDgfuLfFOfcCnwlHYx0LbHf3de28VkREOlF7J1Nc3WICtLR7n9y90cwuBh4GYsBN7v66mX05PH498ABwOrAMqAYubOvadPMkIiLt154AstrMjgM8/Gv/EmBJFIm7+wMEQSJ53/VJnx34WnuvFRGRzGlPE9aXCb7ERxL0SRzBHr7URUQkd7RnFNYmghl4RUREmrW1HsjVtL0eyCWdkiMREekW2qqBzMtYLkREpNtp60n0WzKZERER6V7a8yDhfezelLWdoIbyV3ev7YyMiYhI19aeUVjLgUrghvC1g2BdkIPCbRERyUHteQ5kkrsnP3l+n5k96e7vNzM9vCcikqPaUwMZZmb7NW2En4eGm/WdkisREeny2lMD+Q7wtJm9TTAL7ljgq2bWB1BHu4hIjmrPg4QPhGuCHEIQQN5I6jj/YyfmTUREurB2TaYITCZYBTAfmGhmuPs/Oi1XIiLS5bVnGO8/gQOBBeychdcBBRARkRzWnhrIFGB8ODOuiIgI0L5RWIuAfTs7IyIi0r20pwYyFFhsZi8CdeE+d/ezOy9bIiLS1bUngFyW9NmA44ELOiU3IiLSbey1CcvdnyCY++oM4GbgROD6tq4REZGer631QA4CzieobWwG/g2Yu0/PUN5ERKQLa6sJ6w3gKeBD7r4MwMy+lZFciYhIl9dWE9Z5wLvAXDO7wcxOJOgDERER2XMAcfe73P3jBFOYlAHfAkrM7DozOyVD+RMRkS6qPZ3oVe5+m7ufCYwieCL90s7OmIiIdG3teZCwmbtvcfe/uvsJnZUhERHpHjoUQERERJoogIiISEoUQEREJCUKICIikhIFEBERSYkCiIiIpEQBREREUqIAIiIiKVEAERGRlGQlgJjZYDN7xMyWhu+D9nDeaWb2ppktM7NLk/ZfZmZrzGxB+Do9c7kXERHIXg3kUuAxdx8HPEYrc2uZWQy4BvggMB64wMzGJ53yB3c/Inw9kIlMi4jITtkKIGcDt4SfbwHOaeWco4Fl7r7c3euB2eF1IiLSBWQrgJS4+zqA8H2fVs4ZCaxO2i4P9zW52MxeM7Ob9tQEJiIincfcvXNubPYosG8rh34E3OLuA5PO3eruuwQBM/socKq7fyHc/jRwtLt/3cxKgE2AA78Ehrv7RXvIxwxgBkBJScnk2bNnp1SeyspK+vbtm9K13ZXKnBtU5tyQTpmnT58+392ntNzf1pK2aXH3k/Z0zMzWm9lwd19nZsOBDa2cVg6MTtoeBawN770+6V43APe3kY+ZwEyAKVOmeGlpaUeK0aysrIxUr+2uVObcoDLnhs4oc7aasO4FPht+/ixwTyvnvASMM7OxZlYInB9eRxh0mpwLLOrEvIqISCs6rQayF1cC/zGzzwOrgI8CmNkI4EZ3P93dG83sYuBhIAbc5O6vh9dfZWZHEDRhrQC+lOH8i4jkvE7rA+mKzGwjsDLFy4cS9LvkEpU5N6jMuSGdMu/v7sNa7sypAJIOM5vXWidST6Yy5waVOTd0Rpk1lYmIiKREAURERFKiANJ+M7OdgSxQmXODypwbIi+z+kBERCQlqoGIiEhKFEBERCQlCiAiKTCzIUnr0bybtD5NpZld20lpftPMPtPG8TPN7OedkbZIa9QHIpImM7sMqHT333ZiGvnAy8CR7t64h3MsPGeau1d3Vl5EmqgGIhIhMys1s/vDz5eZ2S1mNsfMVpjZh83sKjNbaGYPmVlBeN5kM3vCzOab2cMt5nprcgLwclPwMLNLzGxxuKTBbAAP/hosA87MSGEl5ymAiHSuA4EzCBZDuxWY6+6HATXAGWEQuRr4iLtPBm4CLm/lPtOA+UnblwKT3H0i8OWk/fOA90VeCpFWZGsyRZFc8aC7N5jZQoJJQR8K9y8ExgAHAxOAR4IWKGLAulbuMxxYkrT9GnCbmd0N3J20fwMwIrrsi+yZAohI56oDcPeEmTX4zk7HBMH/fwa87u5T93KfGqA4afsM4P3AWcBPzOzQsHmrODxXpNOpCUsku94EhpnZVAAzKzCzQ1s5bwnwnvCcPGC0u88Fvg8MBJqWmjsIrY8jGaIAIpJF7l4PfAT4jZm9CiwAjmvl1AcJahwQNHPdGjaLvQL8wd23hcemA//rzDyLNNEwXpFuwszuAr7v7kv3cLwE+Je7n5jZnEmuUgAR6SbM7GCgxN2f3MPxo4AGd1+Q0YxJzlIAERGRlOTUKKyhQ4f6mDFjUrq2qqqKPn36RJuhLk5lzg0qc25Ip8zz58/f1NqStjkVQMaMGcO8efNSurasrIzS0tJoM9TFqcy5QWXODemU2cxWtrZfo7BERCQlCiAiXcA7m6rYUlWf8XTjCWdjdSLj6QKs3VZDXWM84+lW1TXyblXmy+zuPPv2JmrqM1/mzpLVAGJmN5nZBjNr9cEnM/tkOFnca2b2rJkdnnRsRTgp3QIzS61dSmQPahviJBKZGWBS35jgjD8/xSWzXslIesn+9OhbfO/JGhas3pbRdNfvqOW4Kx/nB7e/ltF0AS69cyE/erqGddsz+8D+Syu28okbXuDyBxZnNN3OlHYAMbNRZvZdM7vHzF4ysyfN7FozOyN8YrYtNwOntXH8HeAD4YRxv2T3NX2nu/sR7j4l9RKI7GpbdT0f+H9zOf3PT9EYT1DbEGdh+XbiYUBJJJyqukaiGsG4dEMF1fVxnl62ie3VDcx6cRWvlW8DgkAWbyWQufsur1Q99sYGAO6YX457UK7q+kZq6uPUNsSpb0zQGE8QTziJCF+vrNoKwN0L1jZ/kUd5/7ZeDy1aR9zh1udX0hBPUFW3a3mjLmvTa8HqoMy3Pr+K7TUNJBJOXWOcxngiI+XujBG3aXWim9nfgZHA/cBvCCZyKyaYTuE04Edmdumexq27+5NmNmZP93f3Z5M2nwdGpZNfkfa4ruxt1u+oY/2OOr71n1d5dfU2Vm2pZuzQPvQujLF8YxU1DXEK8/MoyDMa4k59PGgSCeZD3Kmj/8+ec+0zvLOpCoADhvZhxeYq8mN5FOXn0RBPUN+YYG8Vo6Y8WPP2rplK/iJputc/n1/JnS+XU5WF5pXjrnyc3gWxjKd9zdy3ubbs7Q7/jqIw+ZePkGfW/O8mE749uYjpEd8z3VFYv3P31pqfFgF3mlkhsF+aaTT5PMF0Dk0cmGNmDvzV3VvWTkQ6rD7uzHpxFWdMHM7abTXc9+paDirpy9emH8hLK7bSqyDGMWOHMKxfEVur60kknIIwkGCGu2Mtb9oyqrRiaN9CrnroTd7ZVMXph+1LUX6MitoGzpw4nNrGBA3xBIWxPApiecTybJfbNn0BetJG03eiOziOtchVc5Axo3/ValZSQizPGD4gmK8xEV7nHtYMOuFL9j379KW6vpHnlm9mUO9C+hXn75bPzpAfM3ptX8lrtYMZNag3/Xvlk3BIePCXemd+p0/abyCL1m7ntdXb2X9Ib/r3KiCe8IwEsZK61ZHfM/IHCc1sEMFEb+1q3AxrIPe7+4Q2zpkOXAsc7+6bw30j3H2tme0DPAJ8vbWajpnNAGYAlJSUTJ49e3ZHiwRAZWUlffv23fuJPUgulvnx5ZX84y3jB0cVs1//PFbtSHDQoJ1f2p1p4cZGVlYkOG1MAfkZSK9JLv6eVeaOmT59+vxWuwpatqWm8iJYBa0/MBhYRbDwze/bee0YYFEbxycCbwMHtXHOZcB395bW5MmTPVVz585N+druKhfL/OHfP+jH/vpRTyQS2c5KxuTi71ll7hhgnrfynRrVKKwB7r4D+DDwdw9WVjsp3Zua2X7AncCn3f2tpP19zKxf02fgFDSFtaSpIZ5g8eY4pQcP263fQER2F9WT6PnhOs4fA37U3ovMbBZQCgw1s3LgZ0ABgLtfD/wUGAJcG/4P3ehBNaoEuCvcl08wA+lDuyUg0gFvvltBTSMcd+DQbGdFpFuIKoD8AngYeNrdXzKzA4BWp5xO5u4X7OX4F4AvtLJ/OXD47leIpG7xuh0AHDqif5ZzItI9pDuM9wJgjrv/F/hv0/7wC/68NPMm0uzppZt4etkm9ulXxAcOHsaBw6LvAH1jXQWFebD/kNyaZE8kVenWQPYH/mtmBcBjBMNsXww7XUQi8ftH3uLPjy0llmfBQ3X3w4HD+nDqofty4nv3Yb/BfehTFKMh7jSED/7VNgTvdY1xaurDfY3B/uDhreDchrjTGE/QkHDmvrmBUf0yM+JKpCdIK4C4+5XAlWGH9knARcD1ZrYEeAh42N3Xp59NyVVlb27gz48t5bwjR/HrD09gY0Udj7+xgYdff5e/Prmca8vejiyt/DzjQwfk1ATVImmJ5P8Wd68A7gpfmNl44IPAP4BTo0hDck884fzqf0s4YFgfLj93AkX5MUYN6s1npo7hM1PHsK26nueXb2FDRS3V9XHy84yCWB69CmIUFeRRXBCjuCBGr4IYxU3b+cGx/DwjP5ZHQSy4Jj/PMDPKysqyXWyRbiPdPpAj2zg8191/l879Jbfd/coalm2o5NpPHklxQWy34wN7F3LahH2zkDMRgQimMgnfi4EpwKsEU/BMBF4Ajk/z/pKjGuIJ/vjYWxw6oj+nHaogIdIVpfUgobtPd/fpwErgSHefEj5EOAlYFkUGJTc9/Pq7rN5SwzdOHEeeOrVFuqSonkQ/xN0XNm14MMHiERHdW3LQ359Zwf5DenPSe0uynRUR2YOoAsgSM7vRzErN7ANmdgOwJKJ7S45ZvaWa+Su3csHR+6n2IdKFRTVm8ULgK8A3wu0ngesiurfkmEeXBCO/T1Xfh0iXFtUw3lrgD+FLJC0vvrOF/Qb3ZuxQPREu0pVFEkDMbBxwBTCeYEQWAO5+QBT3l66ltiFOYSyv05qXFq7ZzuGjB3bKvUUkOlE1Yf2dYCbdPwDTCZq01Hjdw6zdVsN3//sqz769mT6FMaYfsg9nThxB6cHDWn1Oo6MSCWdzVT3lW2v41LH7R5BjEelMUQWQXu7+mJmZu68ELjOzpwiCivQAlXWNfPpvL7BhRx1fm34gW6rqefj19dz/2jr6FuVz2MgBjBzUi8L8PNydqro41fVxqusbqa6PU9sQ323uqYZ4ImlOql3X+p44ckD2Cisi7RJVAKk1szxgqZldDKwB9ono3tIFXDt3GW9vrOJfXzymeb2MX56d4Lnlm3lw0bssWbeDZ5ZtoiGewMzoUxijV2E+fQpj9CvOZ1i/IgrDtcPzw7W9C2JGfl4eBflGQV4e+eG0Iv17FXDMAUOyXGIR2ZuoAsg3gd7AJcAvCZqxPhvRvSXLyrdWc+PT7/DhSSN3WWwpP5bH+8YN433jhmUxdyKSLWk/B2JmMeBj7l7p7uXufqG7n+fuz7fj2pvMbIOZtbocrQX+bGbLzOy15Lm3zOw0M3szPHZpuuWQPbvqoTfJM/juqQdnOysi0oWkHUDcPQ5MttQWkb4ZOK2N4x8ExoWvGYTPloRB65rw+HjggnAGYInYK6u2cu+ra5nxvgMYMbBXtrMjIl1IVE1YrwD3mNl/gaqmne5+Z1sXufuTZjamjVPOBv4RLlD1vJkNDNdeHwMsC1c+xMxmh+cuTqsUspvfP/IWQ/sW8qUPHJjtrIhIFxNVABkMbAZOSNrnQJsBpB1GAquTtsvDfa3tPybNtKSF5dviPLV0E/93+iH0KdJCSyKyq6ieRL8wivu0orVmMW9j/+43MJtB0PxFSUlJygsGVVZW5txiQ4+vqKEwZuxXv4qystV7v6AHyMXfs8qcGzqjzOkuKPVj4Fp337KH4ycAvd39/hSTKAdGJ22PAtYChXvYvxt3nwnMBJgyZYqXlpamlJGysjJSvbY7iiecrz/2AKdOGMFpJ03KdnYyJtd+z6Ay54rOKHO6NZCFwH1mVgu8DGwkmMpkHMF07o8Cv07j/vcCF4d9HMcA2919nZltBMaZ2ViCZ07OBz6RRjrSwrINlVQ0QOlBGqIrIq1LK4C4+z0EnefjgGnAcGAHcCsww91r2rrezGYBpcBQMysneHK9ILz39cADwOkEi1NVE0yRgrs3hg8sPgzEgJvc/fV0ytKdJBLOP59fyQMLg6fATx5fwhkTh9OvuCCyNF5etRWAI/cfFNk9RaRniaoPZCmwNIXrLtjLcQe+todjDxAEmJzzo7sXMevFVbx3eH/W76jlsTs38LN7X+ek8SVMPWAIowb1oig/RkM8QXV9YzitSCN1jcFUIsEUIsF0Io3xBI0JJ5Hw4N2dxrizYPU2+hXAmCG9s11cEemiNLSmm/nfa+uY9eIqvvSBA7j0tEMAWLB6G3e9sob7X1vH/15b1+57NU0lkp9nxGJGzIxYXvDKM+MDowtI7fEeEckFCiDdSEVtAz+793UOGzmA751ycPOX+6T9BjFpv0H8/KxDWbOthvU7aqlrTFAYy6N3YT59imL0KoxRXBCjIC+YgyqWZ3sNDrk2SkVEOkYBpBu5ruxtNlXW8bfPTiE/tvskAmbGqEG9GTVIzU4i0vnSHcZ7NXt4/gLA3S9J5/6y0+otOyc01GJLItIVpDsX1jxgPsHQ3SMJOtKXEgzhjad5b0ly1cPBhIbfO00TGopI15DuMN5bAMzsc8B0d28It68H5qSdOwFg/sqt3PfqWi454T0MH6AJDUWka0h7Nt7QCKBf0nbfcJ9E4KqH3mCffkWa0FBEupSoOtGvBF4xs7nh9geAyyK6d5fn7tz87AqeXrqJUw4t4WNTRkc2/HXZhgpeeGcLl35QExqKSNcS1YOEfzezB9k5I+6l7v5uFPfuDv7x3Ep+ft9ihvYt4rE3NrBg9XZ+dc4EYnnpB5H/vfYuZnDekaMiyKmISHQiacIKF5M6CTg8nN6k0MyOjuLeXV1tQ5xr5i7jmLGDefH/TuSrpQcy68VVfGP2KzTEE2nf/7nlm3jvvv0Z1q8ogtyKiEQnqjaRa4EEwXogvwAqgDuAoyK6f5f133mr2VBRxx/PP4K8POP7px3CgF4FXPHgG2yrbuAnZ47noJK+JBw2VtTx7o5aNuyoZUNFHXWNieYpRJqY7Zyr3gxeXrWNTx+7f3YKJyLShqgCyDHufqSZvQLg7lvNrDCie3dZ9Y0Jrit7m8n7D2LqAUOa93/pAwcysHcBP79vMaf+8UkK8/OIJ5x4Yo+PzOxRnsFJ7y2JMtsiIpGIKoA0hOuUO4CZDSOokfRod75cztrttfz6w4ft1mn+8aP244RDSpiz+F1WbammIC+PfQcUs2//Ykr6FzOsXxG9CmLNc1CZgTs4jodxxoH8PKO4IJb5womI7EVUAeTPwF1AiZldDnwE+HFE9+6SahviXP34MiaOGsAH9rBmxrB+RXzyGDU/iUjPFNUorNvMbD5wIkET/jnuviSKe3dF7s5P7l7Emm01XPWRiZqxVkRyUlQPEgIMBard/S/ApnC1wDaZ2Wlm9qaZLTOzS1s5/j0zWxC+FplZ3MwGh8dWmNnC8Ni8CMuxV7NeXM1/55dzyYnjmPaeoZlMWkSky4ikBmJmPwOmAAcDfydYVfBWglUK93RNDLgGOJlg7fOXzOxed1/cdI67/z/g/4Xnfwj4Vov116e7+6YoytBeiYRz3RPLmLL/IL554rhMJi0i0qVEVQM5FzgLqAJw97XsOrVJa44Glrn7cnevB2YDZ7dx/gXArAjympaVW6pZvaWG8yaPIi+CBwVFRLqrqAJIfbj8bNMorD7tuGYksDppuzzctxsz6w2cRvBsSRMH5pjZfDObkVKuU7BozXYAJo4akKkkRUS6pKhGYf3HzP4KDDSzLwIXATfs5ZrW/nzf04MSHwKeadF8Nc3d15rZPsAjZvaGuz+5WyJBcJkBUFJSkvIqe5WVlZSVlfHo0noMWPfGy2x8q2fXQJrKnEtU5tygMkcjqlFYvzWzk4EdwEHAT939kb1cVg6MTtoeBazdw7nn06L5Kmwmw903mNldBE1iuwUQd58JzASYMmWKl5aW7rU8rSkrK6O0tJQ5WxcyZP27nHTC9JTu0500lTmXqMy5QWWORpSjsBYCTxF8iS9sx/kvAePMbGz41Pr5wL0tTzKzAQSz+96TtK+PmfVr+gycAixKuwTtsLGijqF9NS+ViEhUkyl+AXgR+DDBQ4TPm9lFbV3j7o3AxcDDwBLgP+7+upl92cy+nHTqucAcd69K2lcCPG1mr4bp/s/dH4qiLHuzqbJOExuKiBBdH8j3gEnuvhnAzIYAzwI3tXWRuz8APNBi3/Uttm8Gbm6xbzlweLqZTsXGijrGDGnPGAERkZ4tqiascoIZeJtUsOsIqx7B3dlYoRqIiAhEVwNZA7xgZvcQjKQ6G3jRzL4N4O6/jyidrKqsa6SuMcEw9YGIiEQWQN4OX02aOrz39jBht7Kxog6Aof16/Ez1IiJ7FdUw3p83fTazQcC28MHCHmVTZT0Aw/oWZzknIiLZl1YfiJn91MwOCT8XmdnjBDWR9WZ2UhQZ7EpUAxER2SndTvSPA2+Gnz8b3m8YwXMbv07z3l3OpsoggKgPREQk/QBSn9RUdSowy93j4VogUfWvdBkbK+qI5RmDeqsGIiKSbgCpM7MJ4RK204E5Scd6p3nvLmdjRR1D+hRqFl4REdKvJXwDuJ2g2eoP7v4OgJmdDryS5r27nE2VmsZERKRJWgHE3V8ADmll/25PmPcEmyrrGKqHCEVEgGgnU+zxNlXWM7Sv+j9EREABpN2apzFRE5aICBDdbLy7fau2tq87q26E+nhCfSAiIqGoaiDPtXNft7WjLhitrIkURUQCaXWim9m+BOuY9zKzSexcprY/PWwY7476IICoBiIiEkh3GO+pwOcIlqNNnnG3Avi/NO/dpWxvCiCaxkREBEizCcvdb3H36cDn3H160ussd79zb9eb2Wlm9qaZLTOzS1s5Xmpm281sQfj6aXuvjVpTE5ZqICIigaimG3nMzH4PvD/cfgL4hbtv39MFZhYDrgFOJliQ6iUzu9fdF7c49Sl3PzPFayOzvd7JMzSNiYhIKKpO9L8RNFt9LHztAP6+l2uOBpa5+3J3rwdmEyxE1R7pXJuSHXXO4D5FxDSNiYgIEF0AOdDdfxZ+oS8P1wc5YC/XjGTXZW/Lw30tTTWzV83sQTM7tIPXRmZ7neshQhGRJFE1YdWY2fHu/jSAmU0DavZyTWt/yrdchOplYH93rwzn17obGNfOawnzMgOYAVBSUkJZWdlestW6zdWNDOpVnfL13VFlZWVOlRdU5lyhMkcjqgDyFeAWMxtA8OW+hWB9kLaUA6OTtkcBa5NPcPcdSZ8fMLNrzWxoe65Num4mMBNgypQpXlpa2p7y7Gbb4//j+ENHUlp6WErXd0dlZWWk+vPqrlTm3KAyRyOSJix3X+DuhwMTgcOAo8L3trwEjDOzsWZWCJwP3Jt8gpnta2YWfj46zO/m9lwbpdqGOBX1MHyAlrIVEWmS7oOE/YGvEfQ/3AM8Gm5/F3gVuG1P17p7o5ldDDwMxICb3P11M/tyePx64CPAV8yskaBJ7PxwAatWr02nLG3ZsCNYiXBfBRARkWbpNmH9E9hKMG3JF4HvA4XAOe6+YG8Xtzbtexg4mj7/BfhLe6/tLGu3B905Iwb0ykRyIiLdQroB5AB3PwzAzG4ENgH7uXtF2jnrQt7dXguoBiIikizdPpCGpg/uHgfe6WnBA3bWQNQHIiKyU7o1kMPNrGmklBFMqrgj/Ozu3j/N+3cJ726vpXc+9CmKatCaiEj3l+6StrGoMtKVfWzKaPrWvJvtbIiIdCn6k7odJowcwKZ99aMSEUmmJW1FRCQlCiAiIpISC57Lyw1mthFYmeLlQwmGKecSlTk3qMy5IZ0y7+/uw1ruzKkAkg4zm+fuU7Kdj0xSmXODypwbOqPMasISEZGUKICIiEhKFEDab2a2M5AFKnNuUJlzQ+RlVh+IiIikRDUQERFJiQKIiIikRAFERERSogAiIiIpUQAREZGUKICIiEhKFEBERCQlCiAiIpISBRAREUmJAoiIiKREAURERFKiACIiIilRABERkZTkZzsDmTR06FAfM2ZMStdWVVXRp0+faDPUxanMuUFlzg3plHn+/PmbWlvSNqcCyJgxY5g3b15K15aVlVFaWhpthro4lTk3qMy5IZ0ym9nK1varCUtERFKSUzUQka6svjFBRW0DQ/oWZSzNf7+0iv8tquPQyXUsWrudxniwwJyFx82CV7Cv+UPzm4UHjY5ZvrGSe19dy08/dCiN8QRbqxuS7hm+khJqSquj6bRm5pPLGZSo5+BJNSxeuwN3yMsL7p8XURqtmbdiC8+8vZnfffRwKusaeXd7LXl5BGlaZ6W6U0V99IsHKoCIdAE3PrWcX/1vCf2K8nny+9O57YWVfG7aWPoWde7/ojc+9Q5LNzRy1OWPdmo6e3LONc9kJV2A+654PCvplv62LCvpfnty9H+YKICIdAH3vbYOgIq6Rv702FJufnYFW6oa+NDhw3nirY186PARvL52B8X5eQzqU9jmX8l5eUZ+nhHLM/Lz8sL3cDu26/5EuKT19049mCn7D6JPUT5Nq1w7nvQ5fA93OLBzNezU/rKtrIvzwvLNTBw1kFGDeuG+M83k9HamFdVf0Ma/H3uJg8a9h0n7DaIwlkfCvfnVmTZV1vPyyq0cOnIA+w/ujQPxRGaWFX/3rQWR31MBRKQLGDGgmFdXB59vfnYFADc98w43PfMOAH98dGmnpX3qmHy+Nv09nXb/tnzgoN0G9mRExQGFlL7vgKykfeqh+2Yl3bJ3om8mUwAR6QJqGuL0K8qnoq4RgLMOH8Eb7+5g3D79+OQx+7FiczXvHd4PM6OitmGP93GHhDvxhNOYSH5P0Bjffb+7M7hqRYZKKT2NAohIF1BdH+eQ4f1Yt72W8q01fPOkcRwwrG/z8eM6sYJQVraq824uPZoCiEgXUFMfZ0jfQv775anUNiQYOzS3HnKT7kkBRKQLqGmI07swxvABvbKdFZF2SzmAmFkecDgwAqgBXnf39VFlTCSX1NTHKS6IZTsbIh3S4QBiZgcCPwBOApYCG4Fi4CAzqwb+Ctzi7okoMyrSkzXVQES6k1RqIL8CrgO+5L7roGkz2wf4BPBp4Jb0syeSG6rrG+ldqBZl6V46/C/W3S9o49gG4I/pZEgk1yQSTm1DQk1Y0u10eDJFM3vVzK4xs0+a2ZhOyJNI1iUSznVlb7NiU1Wnp1VVHzz70UdNWNLNpDIb7yeBV4GTgTlmtsbM/mtm3zKzY6LNnkh2vL2xkt889Abf+PeCTk+rojYIIP17FXR6WiJRSqUJaxGwCJgJYGZDgfOBbwK/BfRnlHR7KzZXA7CwfBsAW6rqcfdOmSm3OYAUK4BI95LKKKwYMAk4DpgGHAisAW4Enos0dyJZsnJz0HQVTOTnXDDzedZsq+Gp709nQK8Cnly6kf0G925+WjyRcOrjqfVjbK2uB6B/L3WiS/eSyr/YHcAS4BrgUnd/J9osiWTfiqYA4jD3zQ28ub4CgItnvUxdQ4J5K7diBvv0K6K6Lk5lfSPuUBAz2lxRwiDPgjUggnUgds7GOnpQ704vl0iUUgkgXwCmhu8XmtlLBDWP59x9TZSZE8mWlWETFsCP7lpEUX4eHz5yJLNeXM3Igb34/mkHU9+YYN22WnoXxehfXEBhfh6V4WSIrWmarpxwwsNE+O4Ow/oVsf8QBRDpXlLpA5kFzAIws97A0QRNWVeYWaG777+3e4TNYPOANe5+ppkNBv4NjAFWAB9z963huT8EPg/EgUvc/eFw/2TgZqAX8ADwjZbPpYik6p1NVZxwyD68sHwz67bXcuG0MfzsQ4fy4zPG07swlpEV5ES6upQaXc2sD3AMO/tBjgJWA+1dXuwbBM1g/cPtS4HH3P1KM7s03P6BmY0n6KA/lGDKlEfN7CB3jxM8zDgDeJ4ggJwGPJhKeUSS1TXGWbuthg8fOYqvn/Ae3t5YxbmTRgLQp5NXCBTpTlJ5DuQVYBXwfYIRV78Dxrj7JHe/uB3XjwLOIOh0b3I2O59cvwU4J2n/bHevC/talgFHm9lwoL+7PxfWOv6RdI1IWu5/dR0Jh4NL+jFpv0F8ZPIoYnmqcYi0lMqfU58FFqbRXPRHguDTL2lfibuvA3D3deGUKAAjCWoYTcrDfQ3h55b7RdJSWe9cdt/rHD1mMKceWpLt7Ih0aakEkInAwj0dDCdbHO7uT7dy7Exgg7vPN7PSdqTV2p993sb+1vIzg6Cpi5KSEsrKytqR7O4qKytTvra7ysUyP7eqiopa4/Th1Tz91JPZzk5G5OLvWWWORioBZAiwwMzmA/PZORvve4APAJsI+jBaMw04y8xOD6/pb2a3AuvNbHhY+xgObAjPLwdGJ10/Clgb7h/Vyv7duPtMwocep0yZ4qWlpR0rbaisrIxUr+2ucrHMf33tIfbpl89nzzohZzrKc/H3rDJHo8N9IO7+J+BIgpFYw4ATw+01wKfd/Tx3X7qHa3/o7qPcfQxB5/jj7v4p4F6CpjHC93vCz/cC55tZkZmNBcYBL4bNXRVmdqwF/5d/JukakZRtqHLGlfTNmeAhko6UhpSEo6AeCV9RuBL4j5l9nqCD/qNhOq+b2X+AxUAj8LUwbYCvsHMY74NoBJZEYGONc5Qe6BNpl6yNSXT3MqAs/LyZoCbT2nmXA5e3sn8eMKHzcii5prq+kR31zujBCiAi7ZHKbLwiPVL51hoABRCRdkopgJhZnpl9LOrMiGTTqnD6ktGDemU5JyLdQ0oBJFzvfK8PDYp0J6u3hgFENRCRdkmnCesRM/uumY02s8FNr8hyJtKKNdtqeGzJel5dvY2GeCLSe6/aUk1hDIb0KYz0viI9VTqd6BeF719L2ufAAWncU2SP/vrE21z18JvN05/3Lowxab+BTNl/MO8d3o99+hfTpzAfC6dMd6d5xtumWW89aTvhwVofDtQ1JFiwehv79DIN4RVpp5QDiLuPjTIjIm15aNE6rnjwDU4/bF8+f/xY3t1ex4vvbOalFVv58+NLiWoe5mkjNFmiSHul/H9LOJX7t4H93H2GmY0DDnb3+yPLnQhQ2xDnV/9bwiH79uNP50+iIBa0vJ4xcTgAFbUNrNpSzfodtdQ2JJprFzsXbgKzYJmnPDPy8oLtvKR9BTGjf68C1iyZn72CinQz6fy59XeCqUyOC7fLgf8CCiASqVueXUH51hpu/fwxzcEjWb/iAg4dMYBDRwxIO631b6r5SqS90ulEP9DdryKYGRd3r6H1SQ5FUralqp6/zF1G6cHDOH7c0GxnR0SSpBNA6s2sF+EsuOEsvHWR5EoEqG9M8JO7F1FV18j/nf7ebGdHRFpIpwnrMuAhYLSZ3UYw0+7nIsiTCG9vrOSzN71I+dYafnDaIRxU0m/vF4lIRqUzCmtOOKX7sQRNV99w902R5Uxy2hUPLKGitpF/XHQ07z9oWLazIyKtSGcU1j+BJ4Gn3P2N6LIkua6mPs7cNzfyhePHKniIdGHp9IH8HRgOXG1mb5vZHWb2jYjyJTns7Y2VxBPOEaMHZjsrItKGdJqwHjezJ4CjgOnAl4FDgT9FlDfJUcs2VAIwrqRvlnMiIm1JpwnrMaAP8BzwFHCUu29o+yqRvVu6oYL8PGP/IX2ynRURaUM6TVivAfUEizpNBCaEw3pF0rJ0fSVjhvZp9aFBEek60mnC+haAmfUFLiToE9kXKIoma5Krlm2o5OB9NWxXpKtLpwnrYuB9wGRgJXATQVOW9HA19XH++fwKFqzexoBehbx3eD8mjBzA+OH9KS6IpXXvusY4KzZXNc9zJSJdVzoPEvYCfg/Md/fGiPIjXVxVXSOfuPEFXl29jTFDerOtpoFZL64CIJZnjNunL6MH96YwP4+CPCPukEg48YQTdw8+e7CdCN+bXw51DXESDofs2z/LJRWRvUmnCev/mdnhwJfD9ROecvdXI8uZdEmX3fs6r5Vv4/pPHclpE4bj7qzbXsvCNdtZtGY7C9dsZ/WWaurjCRrjTiwvmA03eDdiebbb5/y8PIryjbw8I9a7gHEl/TTvlUg3kE4T1iXADODOcNetZjbT3a+OJGfS5cx9YwP/nV/O16YfyGkTgiYmM2PEwF6MGNiLUw/dN8s5FJFMSqcJ6wvAMe5eBWBmvyEY0qsA0gNV1zfyk3sW8Z59+vKNEw/KdnZEpAtIZ5ykAfGk7Th7mc49XD99rpktMbPXm55cD9dTf8TMlobvg5Ku+aGZLTOzN83s1KT9k81sYXjsz6Z1SDvF6i3V3PzMO1z495dYu62Gy8+ZQGG+hteKSPoLSr1gZneF2+cAf9vLNY3Ad9z9ZTPrB8w3s0cIZvF9zN2vNLNLgUuBH5jZeOB8gifcRwCPmtlB7h4HriNoQnseeAA4DXgwjfJIC1UNztnXPMOWqnp6FcS44sOHccwBQ7KdLRHpItLpRP+9mZUBxxPUPC5091f2cs06YF34ucLMlgAjgbOB0vC0W4Ay4Afh/tnuXge8Y2bLgKPNbAXQ392fAzCzfxAEMAWQCL2wrpEtVfXMnnEsR48ZTF6eKnkislOHA4iZHQPMBA4EFgKfd/fFKdxnDDAJeAEoCYML7r7OzPYJTxtJUMNoUh7uawg/t9wvEXp7W4KhfYs4Zuxg1EIoIi2lUgO5BvguwVTuZwF/AE5t84oWwqfX7wC+6e472vhyau2At7G/tbRmEDR1UVJSQllZWUey2qyysjLla7urt7c2MLKv88QTT2Q7KxmTi79nlTk3dEaZUwkgee7+SPj5v2b2w45cbGYFBMHjNndvGgK83syGh7WP4UDTpIzlwOiky0cBa8P9o1rZvxt3n0lQY2LKlCleWlrakew2KysrI9Vru6OK2gbWPzSHC6YdSGnpuGxnJ2Ny7fcMKnOu6IwypzKcZqCZfbjp1cr2HoUjpf4GLHH33ycduhf4bPj5s8A9SfvPN7MiMxsLjANeDJu7Kszs2PCen0m6Jue4O+6tVsBStnDNdhw4fPSASO8rIj1HKjWQJ4AP7WHb2flgYWumAZ8GFprZgnDf/wFXAv8xs88Dq4CPArj762b2H2AxwQiur4UjsAC+AtxMMKXKg+RgB/qyDRX87N7XeWH5FnoVxjhk335MHDWQw0cP5LCRAxjcu5BehTHMIOGOO7iHnwnfE7tuJ9zBYc7r6wGYOGpgNosoIl1YhwOIu1+YamLu/jR7flbkxD1cczlweSv75xFMJZ+Tlm+s5Nxrn6UglsfnjhtDbWOcxWt3cOvzK/nb0+9EksaIvsbgPoWR3EtEep50ngORLKmub+Qrt75Mfp5xz9emMXpw7+ZjDfEEb75bweJ1O6iobaSmPpjn0swwgzwzjPDdgv154f48A8L3grw84uuXZqeAItItKIB0M+7O/925kLc2VPCPi47eJXgAFMTymDByABNGpt93UVb2dtr3EJGeSwGkG9hQUctVD71J78IY1fVx7l6wlu+echDvGzcs21kTkRyWVgAxs+OAMcn3cfd/pJknaeEndy/ikcXrKczPo74xwUXTxvLV0vdkO1sikuPSmc79nwRPoy9g56SKDiiARGh7dQOPLF7PjPcfyHdOOYi6xgR9i1RxFJHsS+ebaAow3qN+AEF28dzyzSQcTjhkHwpieRTENBOuiHQN6QSQRcC+hJMjCmyrrueb/17A00s3cejIAXzzpHGUHjQsrXmknn17E70KYhwxemB0GRURiUA6AWQosNjMXgTqmna6+1lp56qbumT2Ap5fvplPHLMfT7y1kQv//hLT3jOEb598EJNGD9ptNlt3p64xQXV9nPrGBA3xppc3f35q6SaOHjtYa3CISJeTTgC5LKpM9ATPLtvEk29t5MdnvJcvvO8A6hsT3Pr8Sv78+FLOu+45+hXnM6xfEY1xp6YhTk19nOr6RhLtaAD89LH7d34BREQ6KJ31QJ4ws/2Bce7+qJn1BmLRZa1re2t9BaMG9aJ3YT7uzm/nvMnwAcV8KvyyL8zP46Ljx/KRKaN45PX1LFi9jS1V9RTm51FckEfvwnx6F8boVRijd0GMwvwYBTFr7ufIjxmFsTyKCvKYsv/gLJdWRGR36YzC+iLBNOmDCUZjjQSuZw9TkvQkLyzfzMdnPs+k/Qby3y9N5cmlG3l51TZ+fe5hFBfsGkP7Fxdw3uRRnDd51B7uJiLSPaXThPU14GiCBaFw96VJC0H1aA8ueheAV1Zt4y9zl/HgwnfZf0hvPjpFQUJEckc6AaTO3eubRhiZWT57WNSpp1m0ZjtHjxnMPv2L+OOjwXxR13/qSA2xFZGckk4AecLM/g/oZWYnA18F7osmW13bmm01TD1wCD89czwDehUwYeQATpswPNvZEhHJqHQCyKXA5wnWRf8S8ABwYxSZ6soa4gnW76hl1MBeDOxdyOXnHpbtLImIZEU6o7ASwA3hK2e8u72WhMPIQb2ynRURkazqcKO9mZ1tZl9L2n7BzJaHr49Gm72uZ3NVPQDD+hVlOSciItmVSq/v9wnWKm9SBBwFlAJfjiBPXdr2mgYABvQqyHJORESyK5UmrEJ3X520/bS7bwY2m1mfiPLVZSmAiIgEUqmBDErecPeLkzZ7/ApHTQGkvwKIiOS4VALIC+FT6Lswsy8BL6afpa5th2ogIiJAak1Y3wLuNrNPAC+H+yYT9IWcE1G+uqztNQ0UF+RRlJ8z036JiLSqwwHE3TcAx5nZCcCh4e7/ufvjkeasi9pe3aDah4gI6T0H8jiQ1aBhZqcBfyKYBfhGd7+ys9PcXqMAIiICqfWBdAlmFgOuAT4IjAcuMLPxnZ2uAoiISKDbBhCCmYCXuftyd68HZgNnd3ai22sa6F+sACIiks5cWNk2Ekh+HqUcOKYzEvrXC6v478u13PzOiyzfVMkh+/brjGRERLqV7hxArJV9u00nb2YzCBa+oqSkhLKysg4nNO/tejZUNbKtdjOj+sBo25TSfbqbysrKnChnMpU5N6jM0ejOAaQcGJ20PQpY2/Ikd58JzASYMmWKl5aWdjih0lIoKysjlWu7M5U5N6jMuaEzytyd+0BeAsaZ2VgzKwTOZ9c5ukREpBN12xqIuzea2cXAwwTDeG9y99eznC0RkZxh7jmxCi0AZrYRWJni5UOBTRFmpztQmXODypwb0inz/u6+21yHORVA0mFm89x9SrbzkUkqc25QmXNDZ5S5O/eBiIhIFimAiIhIShRA2m9mtjOQBSpzblCZc0PkZVYfiIiIpEQ1EBERSYkCiIiIpEQBREREUqIAIiIiKVEAERGRlCiAiIhIShRAREQkJQogIiKSEgUQERFJiQKIiIikRAFERERSogAiIiIpUQAREZGUdNs10VMxdOhQHzNmTErXVlVV0adPn2gz1MWpzLlBZc4N6ZR5/vz5m1pb0janAsiYMWOYN29eSteWlZVRWloabYa6OJU5N6jMuSGdMpvZytb2qwlLRERSogAiIpIhKzZVMX/l1mxnIzIKICIiGfKDO17jvOuepSGeyHZWIqEAIiKSIS+8swWA19fuyHJOoqEAIiKSIf2Kg3FL81ZsyXJOopFTo7BERLKpd2GMitpGXnxnC5P3H0RlXSO9C/PJM3DAvfPSrmqI/uYKICIiGVJZ2wjAnMXrmbN4fUbT/vbkosjvqQAiIpIB8YRTVR/njMOGk3DnuAOHcPC+/amub6SpbmCAmXVK+jtWLIr8ngogIiIZUFkX1D6O3H8Qnz9+bMbTL1sbfWBSJ7qISAZU1DYA0K+o5/zdnrGSmNkU4H3ACKAGWAQ86u49YziCiEgbmmogTSOxeoJOr4GY2efM7GXgh0Av4E1gA3A88IiZ3WJm+3V2PkREsqki7EDv24MCSCZK0geY5u41rR00syOAccCqDORFRHJcTX2cv7xSS8nBO3jv8P4ZS7dpBFa/4oKMpdnZOr0G4u7X7Cl4hMcXuPtjnZ0PERGA5Zsqmbc+zsX/ejmj6e4I+0D6qg+k48zsaqDlkyzbgXnufk8b190EnAlscPcJ4b7BwL+BMcAK4GPu3nNmKBORTlNdHwdg+aaqjKbb1ITVvwc1YWVyFFYRcASwNHxNBAYDnzezP7Zx3c3AaS32XQo85u7jgMfCbRGRvaoKO7M786nv1jR1oqsPJDXvAU5w90YAM7sOmAOcDCzc00Xu/qSZjWmx+2ygNPx8C1AG/CDa7IpIT1RVF2/+vKWqnsF9CjOS7o6aBvLzjF4FsYyklwmZDCAjCTrUt4fbfYAR7h43s7oO3qvE3dcBuPs6M9snwnyKSA/WVAMBOOeaZ2iIJ+hdGKN3YT6ON9dM3Jvmp/Kk7aTj4TEPN5K3d54TnO8O26rrGdi7sNOeNM+GTAaQq4AFZlZG8MT++4Ffm1kf4NHOStTMZgAzAEpKSigrK0vpPpWVlSlf212pzLkh18q8YEXQmV2QB+9uq+bIkhgJb6C2fmebftNXfNN3vSV/bvlOK+eE/zGs+Ti9jYMGe9Z+1p3ye3b3jL2A4QTNT+cQ1D7ae90YYFHS9pvA8KR7vtme+0yePNlTNXfu3JSv7a5U5tyQa2W++rG3fP8f3O8bdtT6lsq6bGcnY9L5PRMMdtrtOzVjnegW1NtOBA5397uBfDM7OsXb3Qt8Nvz8WWCPo7hERJJV1sWJGQzrV8SgDPV/9FSZHIV1LTAVuCDcrgCu2dtFZjYLeA442MzKzezzwJXAyWa2lKAT/srOybKI9DRVdY30oIFQWZXJH+Mx7n6kmb0C4O5bzWyv4d/dL9jDoRMjzZ2I5ISq+kaKYz2nIzubMlkDaTCzGOHDhGY2DOgZK8uLSIfFE051fePeT4yYaiDRyWQA+TNwF7CPmV0OPA38OoPpi0gX8pN7FjH+pw83D5PNlKq6uGogEclYHHb328xsPkHTkwHnuPuSTKUvIl3Lv14I5k/dWFHHPv2LM5ZuVb1qIFHp9B9jOG9Vkw3ArORjrvVARHJS78IY1fVxVm6pzmwAqWukX75qIFHIRBPWfGBe+L4ReItgLqyN4T4RyUHD+hUBsGpzdUbTVRNWdDIxnftYdz8AeBj4kLsPdfchBDPs3tnZ6YtI19Q0B9XKLZkNIJXqRI9MJjvRj3L3B5o23P1B4AMZTF9EupDGeNB5vmpzFfGEZ6Qz3d2prGukl5qwIpHJOLzJzH4M3EowlPdTwOYMpi8iXUhNQzAr7t0L1vLYGxuoro8zqHcBZhZORhhMRJhImqDQ25i8MLHLMd9lMsTkCQ4B+hYogEQhkwHkAuBnBEN5HXiSnU+li0iOqamPUxjLoz6e4LCRAzhi9EC2VjcQfD0YZsFwzTzb+blpJltrmqjQIM+C/btMYGg7Jzc0jLxww4DC/DxG16/OTqF7mEwO490CfCNT6YlI11bTEOdjR43i0g++lz6FsYxOc15WVp6xtHqyTu8DMbOZZnbYHo71MbOLzOyTnZ0PEelaaurj9CqI0bcov0etkZFLMlEDuRb4SRhEFhEM3y0GxgH9gZuA2zKQDxHpItydmoY4vQo1HKo76/TfnrsvAD5mZn2BKQTrd9QAS9z9zc5OX0S6ntqGYBq8nrS8ay7KZB9IJcHa5SKS45pGYPUqyOSTBBI1/fZEctxrGxvZVFmX0TSbAkhvNWF1awogIjmsur6R38+v4xM3PJ/RdGvqgwBSXKgmrO5MAUQkh5VvrQHgrfWVGU23KYD0Vh9It5ax+qOZHQR8D9g/OV13PyFTeRCRXVXVZX5BJ0jqA1ENpFvLZAPkf4HrgRuAeAbTFZE9qG/MzqKgTQGkWDWQbi2TAaTR3a/LYHoishd1SQGkrjFOUX5mvtBrwqVse6sG0q1l4kn0weGiUveZ2VfNbHjTvhaLTYlIhiXXQDbsyNxIrJ3DeBVAurNM1EDm0zQ7WuB7ScccOCADeRCRViTXQN7dUcvowb0zkm5VXdMwXgWQ7iwTT6KP7ew0RCQ19fGd3ZErN1ezeks1BbE8BvYuaJ4OPRF+SHjL6dV9l3N2mT49nFI9kdh9nzs8+/YmAPoVF2Sh1BKVTI7C+hpwm7tvC7cHARe4+7WZyoOI7KquYWcN5Lv/fTWjaQ/rV0SxnkTv1jLZif5Fd7+macPdt5rZFwkmWxSRLGhqwrpw2hiee3szXz9hHAfu04eK2sbm9TeCNTds17U5dlmPY9f1OnZfxyPpGgvW5jCMAb0KNAtvN5fJAJJnZubhupVmFgMKM5i+iLTQ1In+nVMOpm+RphWRjslk/XEO8B8zO9HMTgBmAQ+lc0MzW2FmC81sgZnNiySXIllw36tr+fqsVzKebl1j0AdSlK+mJOm4TP7J8X1gBvAVghruHIKHCtM13d03RXAfkaxpCh6/++jhFGbwy7y+MYEB+XlqSpKOy2QA+bq7/4ngaXQAzOwbwJ8ymAeRLm1bdT379C/OWHp1jQkK8lBfhKQkk/XWz7ay73Np3tOBOWY238xmpHkvkayrrs/sLD91jQnUeiWp6vQaiJldAHwCGGtm9yYd6gdsTvP209x9rZntAzxiZm+4+5Mt0p9B0HRGSUkJZWVlKSVUWVmZ8rXdlcqceU899wIr+mXuG33F6jpi5vo954DOKHMmmrCeBdYBQ4HfJe2vAF5L58buvjZ832BmdwFHA0+2OGcmMBNgypQpXlpamlJaZWVlpHptd6UyZ9BD/wNg/MRJTN5/UMaS/d/GVyncuEa/5xzQGWXOxJPoK4GVwNQo72tmfYA8d68IP58C/CLKNEQyrSbDTVgNcTVhSeoy0YT1tLsfb2YVBH0WzYcAd/f+Kd66BLgr7PzLB/7l7mkNCxbJtqZJBjOlPp4gpgAiKcpEDeT48L1fxPddDhwe5T1Fsq26PrMLPNU3OvkagSUpysR07uPM7B4zW2Rm/zKzkZ2dpkh3Ewufw1ATlnQnmfincxNwP3Ae8ApwdQbSFOlWmgJIpofxKoBIOjIxCqufuzc9cf7/zOzlDKQp0q3k5xn1ZL4PpCGeIKYWLElRJgJIsZlNYueCUr2St91dAUUklPk+kISmMZGUZSKArAN+n7T9btK2AydkIA8iXVpDPJgVt6ouzkOL1rFwzXa+d+ohnZ5ufdwpVhOWpCgTo7Cmd3YaIt1ZIuE0xIMR7jX1cb58a1Apn/G+AxnQu3NX7GuIJ+irACIp0j8dkSyrj+9cFbAqqQnrrQ0VLN9YSWVd5zVr1TcmyFcLlqRIK8iIZFlyANle09D8+amlm7iubBn7De7N9Z+azJzF65my/yCKC2LsqG2gb1E+eWY0xBPUxxPUNyZoiHv4HmzXx3d+3rnPmz9vqKjlwD76O1JSowAi0opVm6v597xVfOukg8jv5Ee1m1YFBFixuar5858fWwrA2xurOPkPT+52XaoK8/MojOVRmJ/HwF6FHDzY936RSCsyMZXJkW0d1ygs6Yr+8Ohb3PXKGk44pKTTJzdsSKqBrN5Ss8uxS04cR0n/IqrqGik9eB+Wrq8kP2YM6l1IVV0jCXcK8/MoCANCYWzn54KY7RIsCmJ55OfZbmt/5NqstBKdTNRAmmbgLQamAK8SDOGdCLwAHJ+BPIh0yJJ1OwDYWFHb6Wkl10Ca3PGVqRw6YgDFBbFd9h9UEumMQCJp6fTGT3efHo7EWgkc6e5T3H0yMAlY1tnpi6Si6Yt7Y2V9p6fVFECa1iXvX5zPYSMH7hY8RLqaTPaeHeLuC5s23H0RcEQG0xdpt6apRSpqG/ZyZvrqwgDSpyhoEDjl0H0zui66SKoy2Ym+xMxuBG4leIDwU8CSDKYv0m6NYb9ERW3nPxneNAprS1VQ2zn9sH07PU2RKGTyz5wLgdeBbwDfBBaH+0S6nKZnL5pqIG9vrGy1ryIKTfed8f4DOKikL9PeM7RT0hGJWsYCiLvXuvsf3P3c8PUHd+/8HkqRFFTVBZMaVtQ28tb6Ck783RP88dG3OiWtplFYJ48vYc63PkBRvvo+pHvIxDDehey6EuEu3H1iZ+dBpKOqmmsgjby0YgsA/5lXzvdPi35+qqYaSKGWBpRuJhN9IGdmIA2RyLg7lfU7m7AWrw2G9G6vqaeuMc5r5du5+vFl/PysQxk7tA+JhPPWhgrGDu1DUX6MRMJbPAHuzU+FNz8RHk/Q0JigLp7g/tfWAajjXLqdTEymuLLlPjMbCmx2dz0CK11OdX2cpn+ZmyvreXLHRgAa4s5Xbn2Z+Su3sr2mgTP+/BQDehWwvaaB6vp487TojYmO/7POzzNK+hdHVgaRTMhEE9axwJXAFuCXwD+BoUCemX3G3R/q7DyIdETy5IXLNwVTi3zxfWN57I0NvL2xkkNH9OeU8SW8uGILvQvz6VecT0n/YrZW1xMza37quyg/+anwpifFdx4vjOVRED4pPrRvEYP7FGaryCIpyUQT1l+A/wMGAI8DH3T3583sEGAWoAAiXUpTAPnYlFEUxPI4bcK+TDtwKD86Y/wu531u2thsZE+ky8hEAMl39zkAZvYLd38ewN3faDknj0hX0NSBfsr4fTlpfEmWcyPSdWWi1y558HxNi2PqA5EupzJ8eLDpyXARaV0m/g853Mx2EEyg2Cv8TLitXkPpcpqasPoVK4CItCUTo7D0VJR0K9uqg6fPFUBE2qaB5yItLF63g96FMUYN6p3trIh0ad06gJjZaWb2ppktM7NLs50f6RleK9/GhBEDmmfkFZHWddsAYmYx4Brgg8B44AIzG9/2Vampa4yzobpzJtKTriWecF5fu4PDRg3IdlZEurzu3Mh7NLDM3ZcDmNls4GyCWX4jdcuzK/j1kzU8tf0VhuTQw17l5XWU7Xg929nIqKUr6qlrTDBRAURkr7pzABkJrE7aLgeO6YyElm2oBOCJNzd0xu27rMbGRvI3lO+2hnZP1tjYyKhBvTj2gCHZzopIl9edA0hr32q7PVdiZjOAGQAlJSWUlZV1OKEjihMMO9Q5anRRh6/tziorG+jbN9fKXE/fvnksefn5nFntrLKyMqX/L7ozlTka3TmAlAOjk7ZHAWtbnuTuM4GZAFOmTPHS0tKUEisrKyPVa7srlTk3qMy5oTPK3G070YGXgHFmNtbMCoHzgXuznCcRkZzRbWsg7t5oZhcDDwMx4CZ3z60eXxGRLLJcWpLDzDYCu61P0k5DgU0RZqc7UJlzg8qcG9Ip8/7uPqzlzpwKIOkws3nuPiXb+cgklTk3qMy5oTPK3J37QEREJIsUQEREJCUKIO03M9sZyAKVOTeozLkh8jKrD0RERFKiGoiIiKREAaQdeuK08WY22szmmtkSM3vdzL4R7h9sZo+Y2dLwfVDSNT8MfwZvmtmp2ct9eswsZmavmNn94XaPLrOZDTSz283sjfD3PTUHyvyt8N/1IjObZWbFPa3MZnaTmW0ws0VJ+zpcRjObbGYLw2N/to5MfufuerXxInhI8W3gAKAQeBUYn+18RVCu4cCR4ed+wFsE0+JfBVwa7r8U+E34eXxY9iJgbPgziWW7HCmW/dvAv4D7w+0eXWbgFuAL4edCYGBPLjPBRKvvAL3C7f8An+tpZQbeDxwJLEra1+EyAi8CUwnmF3wQ+GB786AayN41Txvv7vVA07Tx3Zq7r3P3l8PPFcASgv/xzib4wiF8Pyf8fDYw293r3P0dYBnBz6ZbMbNRwBnAjUm7e2yZzaw/wRfN3wDcvd7dt9GDyxzKB3qZWT7Qm2CevB5VZnd/EtjSYneHymhmw4H+7v6cB9HkH0nX7JUCyN61Nm38yCzlpVOY2RhgEvACUOLu6yAIMsA+4Wk95efwR+D7QPIKYT25zAcAG4G/h812N5pZH3pwmd19DfBbYBWwDtju7nPowWVO0tEyjgw/t9zfLgoge9euaeO7KzPrC9wBfNPdd7R1aiv7utXPwczOBDa4+/z2XtLKvm5VZoK/xI8ErnP3SUAVQdPGnnT7Moft/mcTNNWMAPqY2afauqSVfd2qzO2wpzKmVXYFkL1r17Tx3ZGZFRAEj9vc/c5w9/qwWkv43rSKVk/4OUwDzjKzFQRNkSeY2a307DKXA+Xu/kK4fTtBQOnJZT4JeMfdN7p7A3AncBw9u8xNOlrG8vBzy/3togCydz1y2vhwpMXfgCXu/vukQ/cCnw0/fxa4J2n/+WZWZGZjgXEEnW/dhrv/0N1HufsYgt/j4+7+KXp2md8FVpvZweGuEwmWfe6xZSZoujrWzHqH/85PJOjj68llbtKhMobNXBVmdmz4s/pM0jV7l+2RBN3hBZxOMErpbeBH2c5PRGU6nqCq+hqwIHydDgwBHgOWhu+Dk675UfgzeJMOjNToii+glJ2jsHp0mYEjgHnh7/puYFAOlPnnwBvAIuCfBKOPelSZgVkEfTwNBDWJz6dSRmBK+HN6G/gL4QPm7XnpSXQREUmJmrBERCQlCiAiIpISBRAREUmJAoiIiKREAURERFKiACKSAjMbYmYLwte7ZrYm/FxpZtd2UprfNLPPtHH8TDP7eWekLdIaDeMVSZOZXQZUuvtvOzGNfOBlghmUG/dwjoXnTHP36s7Ki0gT1UBEImRmpUnrjFxmZreY2RwzW2FmHzazq8K1Fx4Kp5JpWo/hCTObb2YPN01F0cIJwMtNwcPMLjGzxWb2mpnNBvDgr8Ey4MyMFFZyngKISOc6kGD6+LOBW4G57n4YUAOcEQaRq4GPuPtk4Cbg8lbuMw1IngTyUmCSu08Evpy0fx7wvshLIdKK/GxnQKSHe9DdG8xsIcHiZA+F+xcCY4CDgQnAI+FCcDGC6SlaGk4wn1OT14DbzOxugulJmmwgmIFWpNMpgIh0rjoAd0+YWYPv7HRMEPz/Z8Dr7j51L/epAYqTts8gWCjqLOAnZnZo2LxVHJ4r0unUhCWSXW8Cw8xsKgRT7JvZoa2ctwR4T3hOHjDa3ecSLI41EOgbnncQwcR4Ip1OAUQkizxYJvkjwG/M7FWCWZGPa+XUBwlqHBA0c90aNou9AvzBg2VqAaYD/+vMPIs00TBekW7CzO4Cvu/uS/dwvAT4l7ufmNmcSa5SABHpJsJFoUrc/ck9HD8KaHD3BRnNmOQsBRAREUmJ+kBERCQlCiAiIpISBRAREUmJAoiIiKREAURERFKiACIiIin5/6gkcMmK8bJFAAAAAElFTkSuQmCC\n", + "image/png": "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\n", "text/plain": [ - "
" + "
" ] }, - "metadata": { - "needs_background": "light" - }, + "metadata": {}, "output_type": "display_data" } ], @@ -593,7 +579,7 @@ "lib_name = (f'../ROSCO/build/libdiscon.{ext}')\n", "\n", "# Load the simulator and controller interface\n", - "controller_int = ROSCO_ci.ControllerInterface(lib_name)\n", + "controller_int = ROSCO_ci.ControllerInterface(lib_name,param_filename=param_file)\n", "sim = ROSCO_sim.Sim(turbine,controller_int)\n", "\n", "# Define a wind speed history\n", @@ -650,39 +636,35 @@ "outputs": [ { "data": { - "image/png": "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\n", + "image/png": "iVBORw0KGgoAAAANSUhEUgAAAosAAAHrCAYAAACn9tfQAAAAOXRFWHRTb2Z0d2FyZQBNYXRwbG90bGliIHZlcnNpb24zLjYuMiwgaHR0cHM6Ly9tYXRwbG90bGliLm9yZy8o6BhiAAAACXBIWXMAAA9hAAAPYQGoP6dpAACuU0lEQVR4nOzdd3hU1dbA4d+kTfqk9wYhoYbQqxA6ggIqVryKFZX7oYhcrtgQCyoqYEGxAyLYEC8qCkG6AaRIDwESSO9t0jPJnO+PwEhMAjOQMiHrfZ55MnPKnjUuM6zss8/eKkVRFIQQQgghhKiHRUsHIIQQQgghzJcUi0IIIYQQokFSLAohhBBCiAZJsSiEEEIIIRokxaIQQgghhGiQFItCCCGEEKJBUiwKIYQQQogGSbEohBBCCCEaJMWiEEIIIYRokBSLQghxFZYvX45Kpar18PT0ZNiwYfz8888tHR7Dhg1j2LBhtbapVCpefPHFFolHCNH6WLV0AEIIcS344osv6NSpE4qikJGRwfvvv8+ECRNYv349EyZMaOnwatm9ezcBAQEtHYYQopWQYlEIIRpBt27d6NOnj+H19ddfj6urK2vWrDG7YnHAgAEtHYIQohWRy9BCCNEEbG1tsbGxwdra2rBt/vz59O/fHzc3N5ydnenVqxefffYZiqLUOnfLli0MGzYMd3d37OzsCAoKYvLkyZSWlhqOqays5JVXXqFTp06o1Wo8PT25//77yc7Ovmxs/7wMfeFS+tatW3nsscfw8PDA3d2dW265hbS0tDrnf/PNNwwcOBAHBwccHR0ZO3Ysf/311xX8VxJCtAZSLAohRCOorq6mqqoKnU5HSkoKM2fOpKSkhClTphiOOXfuHI888gjffvstP/zwA7fccgszZszg5ZdfrnXMDTfcgI2NDZ9//jm//fYbr7/+Og4ODlRWVgKg1+uZNGkSr7/+OlOmTOGXX37h9ddfJzo6mmHDhlFWVnZFn+Ghhx7C2tqa1atXs3DhQrZt28a//vWvWscsWLCAu+66iy5duvDtt9/y5ZdfUlRUxJAhQzhx4sQVva8QwswpQgghrtgXX3yhAHUearVa+eCDDxo8r7q6WtHpdMpLL72kuLu7K3q9XlEURfn+++8VQDl06FCD565Zs0YBlLVr19bavm/fPgWo9b5RUVFKVFRUreMAZd68eXU+w/Tp02sdt3DhQgVQ0tPTFUVRlKSkJMXKykqZMWNGreOKiooUHx8f5fbbb28wZiFE6yU9i0II0QhWrlzJvn372LdvH7/++itTp07l3//+N++//77hmC1btjBq1Cg0Gg2WlpZYW1vzwgsvkJubS1ZWFgA9evTAxsaGadOmsWLFChISEuq8188//4yLiwsTJkygqqrK8OjRowc+Pj5s27btij7DxIkTa73u3r07AImJiQBs3LiRqqoq7r333lrva2trS1RU1BW/rxDCvMkNLkII0Qg6d+5c5waXxMRE5syZw7/+9S9OnTrFmDFjGDZsGJ988gkBAQHY2Njw448/8uqrrxouHYeGhrJ582YWLlzIv//9b0pKSmjfvj2PP/44TzzxBACZmZkUFBRgY2NTbyw5OTlX9Bnc3d1rvVar1QCG2DIzMwHo27dvvedbWEj/gxDXIikWhRCiiXTv3p2NGzdy6tQpvv76a6ytrfn555+xtbU1HPPjjz/WOW/IkCEMGTKE6upq9u/fz3vvvcfMmTPx9vbmzjvvNNyA8ttvv9X7vk5OTk3yeTw8PAD4/vvvCQ4ObpL3EEKYHykWhRCiiRw6dAgAT09PVCoVVlZWWFpaGvaXlZXx5ZdfNni+paUl/fv3p1OnTnz11VccPHiQO++8kxtvvJGvv/6a6upq+vfv39Qfw2Ds2LFYWVkRHx/P5MmTm+19hRAtS4pFIYRoBMeOHaOqqgqA3NxcfvjhB6Kjo7n55ptp164dN9xwA4sWLWLKlClMmzaN3Nxc3nrrLcOl3guWLVvGli1buOGGGwgKCqK8vJzPP/8cgFGjRgFw55138tVXXzF+/HieeOIJ+vXrh7W1NSkpKWzdupVJkyZx8803N/pnDAkJ4aWXXuLZZ58lISHBMJdkZmYmf/75Jw4ODsyfP7/R31cI0bKkWBRCiEZw//33G55rNBratWvHokWLmD59OgAjRozg888/54033mDChAn4+/vz8MMP4+XlxYMPPmg4t0ePHmzatIl58+aRkZGBo6Mj3bp1Y/369YwZMwao6XFcv34977zzDl9++SWvvfYaVlZWBAQEEBUVRURERJN9zrlz59KlSxfeeecd1qxZQ0VFBT4+PvTt25dHH320yd5XCNFyVIryj9lghRBCCCGEOE9uXRNCCCGEEA2SYlEIIYQQQjRIikUhhBBCCNEgKRaFEEIIIUSDpFgUQgghhBANkmJRCCGEEEI0SOZZNCN6vZ60tDScnJxQqVQtHY4QQgghrmGKolBUVISfn9+l13ZX2qDt27crN954o+Lr66sAyrp162rt1+v1yrx58xRfX1/F1tZWiYqKUo4dO3bJNr/44gsFqPMoKyszOq7k5OR625CHPOQhD3nIQx7yaKpHcnLyJeuTNtmzWFJSQmRkJPfff3+965suXLiQRYsWsXz5csLDw3nllVcYPXo0cXFxODk5Ndius7MzcXFxtbbZ2toaHdeFtpOTk3F2djb6PGPpdDo2bdrEmDFjsLa2bvT2hfEkF+ZDcmEeJA/mQ3JhHpojD1qtlsDAwEvWNtBGL0OPGzeOcePG1btPURSWLFnCs88+yy233ALAihUr8Pb2ZvXq1TzyyCMNtqtSqfDx8bniuC5cenZ2dm6yYtHe3h5nZ2f5AmhhkgvzIbkwD5IH8yG5MA/NmYfLDX1rk8XipZw9e5aMjAzDGqwAarWaqKgoYmJiLlksFhcXExwcTHV1NT169ODll1+mZ8+eDR5fUVFBRUWF4bVWqwVq/gfR6XSN8Glqu9BmU7QtTCO5MB+SC/MgeTAfkgvz0Bx5MLZtKRb/ISMjAwBvb+9a2729vUlMTGzwvE6dOrF8+XIiIiLQarW88847DB48mMOHDxMWFlbvOa+99hrz58+vs33Tpk3Y29tfxae4tOjo6CZrW5hGcmE+JBfmQfJgPiQX5qEp81BaWmrUcVIsNuCfXbKKolyym3bAgAEMGDDA8Hrw4MH06tWL9957j3fffbfec+bOncusWbMMry+MHRgzZkyTXYaOjo5m9OjRcmmhhUkuzIfkwjxIHsyH5MI8NEceLlzRvBwpFv/hwpjDjIwMfH19DduzsrLq9DZeioWFBX379uX06dMNHqNWq1Gr1XW2W1tbN+kvaFO3L4wnuTAfkgvzIHkwH5IL89CUeTC2XZmU+x/atWuHj49PrW7fyspKtm/fzqBBg4xuR1EUDh06VKvgFEIIIYRobdpkz2JxcTFnzpwxvD579iyHDh3Czc2NoKAgZs6cyYIFCwgLCyMsLIwFCxZgb2/PlClTDOfce++9+Pv789prrwEwf/58BgwYQFhYGFqtlnfffZdDhw6xdOnSZv98QgghhBCNpU0Wi/v372f48OGG1xfGDU6dOpXly5czZ84cysrKmD59Ovn5+fTv359NmzbVmocoKSmp1mznBQUFTJs2jYyMDDQaDT179mTHjh3069ev+T6YEEIIIUQja5PF4rBhw1AUpcH9KpWKF198kRdffLHBY7Zt21br9eLFi1m8eHEjRSiEEEIIYR6MHrN44sSJyx6zatWqqwpGCCGEEEKYF6OLxd69e/PWW2/V2yOXmZnJxIkTeeyxxxo1OCGEEEII0bKMLhZXrVrFwoULGTp0KPHx8bW2d+nShcLCQg4dOtQUMQohhBBCiBZidLE4efJkjh07hoeHB5GRkbz11ltMmjSJRx55hBdeeIFt27YRGhralLEKIYQQQohmZtINLl5eXqxbt467776bOXPm4ODgwJ49e4iIiGiq+IQQQgghRAsyaVLu/Px8pkyZwo8//sjTTz+Nl5cXd9xxB/v27Wuq+IQQQgghRAsyulj8+eef6dKlC/Hx8Rw4cIAFCxZw5MgRoqKiuO6663juueeoqqpqyliFEEIIIUQzM7pYvPXWW5kxYwa7d++mU6dOADg4OPDhhx/y888/8+WXX9KnT58mC1QIIYQQQjQ/o8cs/vnnn3Tv3r3efaNHj+bo0aM8+eSTjRaYEEIIIYRoeUb3LDZUKF7g7OzMZ599dtUBCSGEEEII82FUz+L69euNakylUjFhwoSrCkgIIYQQQpgPo4rFm266yajGVCoV1dXVVxOPEEIIIYQwI0YVi3q9vqnjEEIIIYQQZsikeRb/qby8vLHiEEIIIYQQZsjkYrG6upqXX34Zf39/HB0dSUhIAOD555+XG1yEEEIIIa4xJheLr776KsuXL2fhwoXY2NgYtkdERPDpp58a3U5ycjI7d+5k48aNHDx4kIqKClNDEUIIIYQQTczkYnHlypV8/PHH3H333VhaWhq2d+/enZMnT17y3MTERObOnUtISAghISFERUUxbtw4+vTpg0ajYfTo0Xz33XcyRlIIIYQQwkyYXCympqbSoUOHOtv1ej06na7B85544gkiIiI4ffo0L730EsePH6ewsJDKykoyMjLYsGED1113Hc8//zzdu3eX9aaFEEIIIcyA0Su4XNC1a1d27txJcHBwre3fffcdPXv2bPA8Gxsb4uPj8fT0rLPPy8uLESNGMGLECObNm8eGDRtITEykb9++poYnhBBCCCEakcnF4rx587jnnntITU1Fr9fzww8/EBcXx8qVK/n5558bPO/NN980+j3Gjx9valhCCCGEEKIJGH0ZOjs7G4AJEybwzTffsGHDBlQqFS+88AKxsbH89NNPjB492qi2ysrKKC0tNbxOTExkyZIlbNy40cTwhRBCCCFEUzK6Z9Hf35+JEyfy4IMPcv311zN27NgrftNJkyZxyy238Oijj1JQUED//v2xtrYmJyeHRYsW8dhjj11x20IIIYQQovEY3bO4YsUKtFotEyZMIDAwkOeff94wx6KpDh48yJAhQwD4/vvv8fb2JjExkZUrV/Luu+9eUZtCCCGEEKLxGV0s3nXXXWzatImzZ8/y8MMP89VXXxEWFsbw4cP56quvTFrNpbS0FCcnJwA2bdrELbfcgoWFBQMGDCAxMdH0TyGEEEIIIZqEyVPnBAYGMm/ePBISEti0aRP+/v5MmzYNX19fpk+fblQbHTp04McffyQ5OZmNGzcyZswYALKysnB2djY1JCGEEEII0USuam3okSNHsmrVKlauXImFhQUfffSRUee98MILzJ49m5CQEPr378/AgQOBml7GS02/I4QQQgghmpfJU+dccO7cOb744gtWrFhBSkoKw4cP58EHHzTq3FtvvZXrrruO9PR0IiMjDdtHjhzJzTfffKUhCSGEEEKIRmZSsVheXs53333HF198wY4dO/D39+e+++7j/vvvJyQk5LLn+/n5MWnSJCZOnMjIkSPx8fGptb9fv34mBS+EEEIIIZqW0Zehp02bho+PDw8//DCenp788ssvnDt3jvnz5xtVKAKsXr0ae3t7Hn/8cTw8PLjtttv48ssvycvLu9L4hRBCCCFEEzK6WNyzZw/z588nLS2Nb775hrFjx6JSqUx6s2HDhvH2229z+vRpdu/eTa9evVi6dCm+vr4MGzaMxYsXEx8fb/KHMNWOHTuYMGECfn5+qFQqfvzxx1r7FUXhxRdfxM/PDzs7O4YNG8bx48cv2+7atWvp0qULarWaLl26sG7duib6BEIIIYQQzcPoYvHIkSM88cQTuLm5Ncobd+3alblz57Jnzx4SExO5++672bJlCxEREXTr1o1ffvmlUd6nPiUlJURGRvL+++/Xu3/hwoUsWrSI999/n3379uHj48Po0aMpKipqsM3du3dzxx13cM8993D48GHuuecebr/9dvbu3dtUH0MIIYQQosld8Q0u/5ScnMy8efP4/PPPTT73wuXthx9+mNLSUjZu3IharW6s0OoYN24c48aNq3efoigsWbKEZ599lltuuQWomZDc29ub1atX88gjj9R73pIlSxg9ejRz584FYO7cuWzfvp0lS5awZs2apvkgJlAUhdLKKiqqobSyCmvFtF5h0bh0OsmFuZBcmAfJg/mQXJiHC3lQFKWlQ0GlNFIUhw8fplevXlRXVxt9TlZWFllZWej1+lrbu3fv3hghGUWlUrFu3TpuuukmABISEggNDeXgwYO1pvGZNGkSLi4urFixot52goKCePLJJ3nyyScN2xYvXsySJUsanGi8oqKCiooKw2utVktgYCA5OTmNPt9kaWUVkS9vadQ2hRBCCNG09j89FI2DbZO0rdVq8fDwoLCw8JJ1h9E9i+vXr7/kflOW/jtw4ABTp04lNja2TsWsUqlMKjgbW0ZGBgDe3t61tl9YkvBS59V3zoX26vPaa68xf/78Ots3bdqEvb29KWFfVkU1NGJHshBCCCGawZYtW1BbNk3bpaWlRh1ndPVw0003oVKpLtkdauwNL/fffz/h4eF89tlneHt7m3yjTHP4Z0yKolw2TlPPmTt3LrNmzTK8vtCzOGbMmEbvWVQUhREjKtiyZQsjRozA2loKx5ak01VJLsyE5MI8SB7Mh+TCPFzIww1jR2FjY9Mk76HVao06zuj/C3x9fVm6dKnhcu0/HTp0iN69exvV1tmzZ/nhhx/o0KGDsW/fbC7M/ZiRkYGvr69he1ZWVp2ew3+e989exMudo1ar6x2baW1tjbW1tamhX5ZGpUJtCRoH2yZpXxhPp9NJLsyE5MI8SB7Mh+TCPFzIg42NTZPlwdh2jb4bunfv3hw8eLDB/ZfrdbzYyJEjOXz4sLFv3azatWuHj48P0dHRhm2VlZVs376dQYMGNXjewIEDa50DNZeTL3WOEEIIIYS5M7pn8T//+Q8lJSUN7u/QoQNbt241qq1PP/2UqVOncuzYMbp161ansp04caKxYV2R4uJizpw5Y3h99uxZDh06hJubG0FBQcycOZMFCxYQFhZGWFgYCxYswN7enilTphjOuffee/H39+e1114D4IknnmDo0KG88cYbTJo0if/9739s3ryZXbt2NelnEUIIIYRoSkYXi0OGDLnkfgcHB6KiooxqKyYmhl27dvHrr7/W2dccN7js37+f4cOHG15fGDc4depUli9fzpw5cygrK2P69Onk5+fTv39/Nm3ahJOTk+GcpKQkLCz+7pgdNGgQX3/9Nc899xzPP/88oaGhfPPNN/Tv379JP4sQQgghRFNqkZGrjz/+OPfccw/PP//8Jcf0NZVhw4Zd9kadF198kRdffLHBY7Zt21Zn26233sqtt97aCBEKIYQQQpgHo4rFC5NTG+OHH3647DG5ubk8+eSTLVIoCiGEEEII4xl1g4tGozE8nJ2d+f3339m/f79h/4EDB/j999/RaDRGvektt9xi9PhGIYQQQgjRcozqWfziiy8Mz//73/9y++23s2zZMiwta2aJrK6uZvr06UbPDRgeHs7cuXPZtWsXERERdW5wefzxx42NXwghhBBCNCGTxyx+/vnn7Nq1y1AoAlhaWjJr1iwGDRrEm2++edk2Pv30UxwdHdm+fTvbt2+vtU+lUkmxKIQQQghhJkwuFquqqoiNjaVjx461tsfGxtZZ47khZ8+eNfVthRBCCCFECzC5WLz//vt54IEHOHPmDAMGDABgz549vP7669x///2NHqAQQgghhGg5JheLb731Fj4+PixevJj09HSgZinAOXPm8NRTTzV43uuvv87jjz+Ovb39Zd9j79695OTkcMMNN5ganhBCCCGEaEQmF4sWFhbMmTOHOXPmGBagNubGlhMnThAUFMRtt93GxIkT6dOnD56enkDNpe0TJ06wa9cuVq1aRXp6OitXrjQ1NCGEEEII0ciualJuY+9+Bli5ciVHjhxh6dKl3H333RQWFmJpaYlaraa0tBSAnj17Mm3aNKZOnYparb6a0IQQQgghRCMwuVjMzMxk9uzZ/P7772RlZdVZCeVSS/V1796djz76iGXLlnHkyBHOnTtHWVkZHh4e9OjRAw8PD9M/gRBCCCGEaDImF4v33XcfSUlJPP/88/j6+qJSqUx+U5VKRWRkJJGRkSafK4QQQgghmo/JxeKuXbvYuXMnPXr0aIJwhBBCCCGEOTFqub+LBQYG1rn0LIQQQgghrk0mF4tLlizh6aef5ty5c00QjhBCCCGEMCcmX4a+4447KC0tJTQ0FHt7+zrrOufl5TVacEIIIYQQomWZXCwuWbKkCcIQQgghhBDmyORicerUqU0RhxBCCCGEMENGFYtardYwAfeFVVsaYspE3UIIIYQQwrwZVSy6urqSnp6Ol5cXLi4u9c6tqCgKKpXqkpNyCyGEEEKI1sWoYnHLli24ubkZnl/JRNxCCCGEEKL1MapYjIqK4syZM3To0IFhw4Y1cUhCCCGEEMJcGD3PYnh4OIGBgdx777188cUXMs+iEEIIIUQbYPTd0Nu3b2f79u1s27aN//u//6O8vJygoCBGjBjB8OHDGT58OP7+/k0ZqxBCCCGEaGZGF4tDhgxhyJAhPPfcc+h0Onbv3s22bdvYtm0ba9asoaKigg4dOhAXF9eU8QohhBBCiGZk8jyLANbW1gwdOpS+ffsycOBANm7cyCeffMKZM2caOz4hhBBCCNGCTCoWy8vLiYmJYevWrWzbto19+/bRrl07oqKi+PDDD4mKimqqOIUQQgghRAswuliMiopi3759hIaGMnToUGbMmEFUVBTe3t5NGZ8QQgghhGhBRheLMTEx+Pr6Mnz4cIYNG8bQoUPx8PBoytiEEEIIIUQLM3rqnIKCAj7++GPs7e1544038Pf3JyIigv/7v//j+++/Jzs7uynjFEIIIYQQLcDonkUHBweuv/56rr/+egCKiorYtWsXW7duZeHChdx9992EhYVx7NixJgtWCCGEEEI0L6N7Fv/JwcEBNzc33NzccHV1xcrKitjY2MaMrUUVFRUxc+ZMgoODsbOzY9CgQezbt6/B47dt24ZKparzOHnyZDNGLYQQQgjRuIzuWdTr9ezfv59t27axdetW/vjjD0pKSvD392f48OEsXbqU4cOHN2Wszeqhhx7i2LFjfPnll/j5+bFq1SpGjRrFiRMnLjn5eFxcHM7OzobXnp6ezRGuEEIIIUSTMLpYdHFxoaSkBF9fX4YNG8aiRYsYPnw4oaGhTRlfiygrK2Pt2rX873//Y+jQoQC8+OKL/Pjjj3z44Ye88sorDZ7r5eWFi4tLM0UqhBBCCNG0jC4W33zzTYYPH054eHhTxmMWqqqqqK6uxtbWttZ2Ozs7du3adclze/bsSXl5OV26dOG55567ZG9rRUUFFRUVhtdarRYAnU6HTqe7ik9QvwttNkXbwjSSC/MhuTAPkgfzIbkwD82RB2PbVimKojRZFK3YoEGDsLGxYfXq1Xh7e7NmzRruvfdewsLC6l3SMC4ujh07dtC7d28qKir48ssvWbZsGdu2bTP0Tv7Tiy++yPz58+tsX716Nfb29o3+mYQQQgghLigtLWXKlCkUFhbWGkL3T1IsNiA+Pp4HHniAHTt2YGlpSa9evQgPD+fgwYOcOHHCqDYmTJiASqVi/fr19e6vr2cxMDCQnJycSybtSul0OqKjoxk9ejTW1taN3r4wnuTCfEguzIPkwXxILsxDc+RBq9Xi4eFx2WLxitaGbgtCQ0PZvn07JSUlaLVafH19ueOOO2jXrp3RbQwYMIBVq1Y1uF+tVqNWq+tst7a2btJf0KZuXxhPcmE+JBfmQfJgPiQX5qEp82Bsu1IsXoaDgwMODg7k5+ezceNGFi5caPS5f/31F76+vkYff6GT98LYxcam0+koLS1Fq9XKF0ALk1yYD8mFeZA8mA/JhXlojjxcqDcud5FZisUGbNy4EUVR6NixI2fOnOE///kPHTt25P777wdg7ty5pKamsnLlSgCWLFlCSEgIXbt2pbKyklWrVrF27VrWrl1r9HsWFRUBEBgY2PgfSAghhBCiHkVFRWg0mgb3S7HYgMLCQubOnUtKSgpubm5MnjyZV1991VDdp6enk5SUZDi+srKS2bNnk5qaip2dHV27duWXX35h/PjxRr+nn58fycnJODk5oVKpGv0zXRgTmZyc3CRjIoXxJBfmQ3JhHiQP5kNyYR6aIw+KolBUVISfn98lj5MbXNoQrVaLRqO57EBW0fQkF+ZDcmEeJA/mQ3JhHswpD1e83J8QQgghhLj2SbEohBBCCCEaJMViG6JWq5k3b1690/WI5iW5MB+SC/MgeTAfkgvzYE55kDGLQgghhBCiQdKzKIQQQgghGiTFohBCCCGEaJAUi0IIIYQQokFSLAohhBBCiAZJsSiEEEIIIRoky/2ZEb1eT1paWpMt9yeEEEIIccHFy/1ZWDTcfyjFohlJS0sjMDCwpcMQQgghRBuSnJxMQEBAg/ulWDQjTk5OAE22aLhOp2PTpk2MGTMGa2vrRm9fGE9yYT4kF+ZB8mA+JBfmoTnyoNVqCQwMNNQfDZFi0YxcuPTs7OzcZMWivb09zs7O8gXQghRFkVyYEcmFeZA8mA/JhXlozjxcbuibFItCXIXc4grO5pSQVlhORmEZ6YXlZBSWk19aibasiqIKHdqyKsp01ej1CtWKwoU1k6xVlrx4eCv2NlbY21ji5mCDl7Mtno5qvJzV+LvY0d7TgfYejtjZWLbsBxVCCNFmSbEohBFKK6s4lqrlaGohZ7KKOJNVzJmsYvJLdVfcpk5RkV+qM6oNfxc7Qr0ciQzQ0D3AhchADV5Otlf83kIIIYSxpFgU4h8URSEhp4S9CXkcTi7gcEoBpzKL0Dewirq/ix3+Lnb4utjiq7HDV2OLm4MNTrZWONtZ42xrjZ2NJZYqFRYqsLBQUaXTsWHT7wwYPJRKRUVpRRU5JZVkacvJKqogS1tOUl4pCTklFJTqSC0oI7WgjB2nsg3v66expX97d67r4MHgDh74aKR4FEII0fikWBQCSM4rJSY+h5j4XHbH55JVVFHnGB9nWyICNHT0dqKDlyMdvBxp7+mAvY3pv0Y6nQXuthDm7XjZsSh5JZXEZxdzMqOII+eL19NZxaQVlrPur1TW/ZUKQAcvR4aFe3J9Nx96BbliYSHTLwkhhLh6UiyKNqmqWs/BpAJ+j81kc2wm8dkltfbbWFnQK8iF3sGuRAa4EBnogrdzy/TcuTnY4ObgRt8QNxgQDEBxRRWHkwv440wOf5zJ4UhqoeHS+Ke7zuLlpGZsVx/GRfgwoJ27FI5CCCGumBSLos0o11Wz5WQWm45nsO1UNgUXjRW0slDRI9CFgaHuDAx1p1eQK7bW5ntTiaPaisHnLz8DFJRWEhOfy6bjGfwem0VWUQVf7knkyz2J+LvYMbmXP7f2DiTI3b6FIxdCCNHaSLEormkVVdXsPJXDz0fSiD6RSUlltWGfxs6a4R09GdnZm6HhnmjsWu8UES72NoyP8GV8hC+VVXr+iM/ht6MZ/HosndSCMt7dcoZ3t5xhQHs37u4fzPXdfLC2lNU+hRBCXJ4Ui+Kao9cr7E7I5X+HUvntWAba8irDPn8XO27o7suozt70CnLB6hosmGysLBje0YvhHb2YP6krm05k8t3+ZHadyWFPQh57EvLw1djyrwHBTOkXhKuDTUuHLIQQwoxJsSiuGcl5pXx3IIW1B1JILSgzbPdyUnNDd18mRPrRM9ClTa27bWttycRIPyZG+pFaUMY3+5JZvTeR9MJy3twYx7u/n2Zy7wAeiwol0E0uUQshhKhLikXRqpXrqvntWAbf7k8mJj7XsN3J1oobu9cUSf3auWEpN3jg72LHrNHh/Ht4KD8fTueLmLMcS9Wyem8S3+xL5qYe/vx7eCjtPR1bOlQhhBBmRIpF0Sqdziziyz2JrPsrlaLzl5lVKhgc6sFtfQIY29XHrG9QaUlqK0sm9w7gll7+/Hk2j/e3nmHn6RzWHkxh3V8p3NjdjydHh9POw6GlQxVCCGEGpFgUrUZVtZ7oE5ms3J3I7oS/exEDXO24rXcgk3v7E+Aql1KNpVKp6N/enf7t3fkrKZ+lW8+wOTaL9YfT2HA0nTv7BfL4yDBZKUYIIdo4KRaF2csuquDrP5NY/WcS6YXlAFioYHQXb+4ZEMKgUJlH8Gr1DHLl06l9OZ5WyFsb49gal82qPUmsPZDKQ0Pa8UhUKI5q+boQQoi2SL79hVlSFIWDSfmsiEnk12Pp6Kpr1tpzd7Dhzn6BTOkfjL+LXQtHee3p6qfhi/v7sSchl9d/Pcmh5ALe23KGr/clM3dcJ27q4S+FuRBCtDGNViwePnyYXr16UV1dffmDhWhAWWU16w+nsiImkRPpWsP2XkEu3DswhHERPqitZCxiUxvQ3p110wex8Xgmr/8ay7ncUmZ9e5hVexKZP7EbEQGalg5RCCFEM2nUnkVFURqzOdGGJOaW8OXuRL47kEJhWc3KKmorCyb18OPegSF085fipLmpVCqu7+bD8E6efL7rHO9tOc3BpAImLt3FnX0DmTO2k8zRKIQQbYDRxeItt9xyyf2FhYVtav46cfWq9QrbT2WxIiaR7aeyDduD3Oz514Agbu8TiIu9FCMtTW1lyWPDQrm5pz+v/xrLj4fSWPNnMpuOZ/LChC5MjPST330hhLiGGV0s/vTTT4wePRpvb+9698vlZ2Gs/JJKvt2fzKq9iSTn1UyerVJBVLgnUweGEBXuKePizJCPxpYld/bk7gHBPLvuKKcyi3ni60Os+yuVV27qJneiCyHENcroYrFz585MnjyZBx98sN79hw4d4ueff260wMS150hKASt3J/LT4TQqqvRAzfrMt/cJ4F8Dggl2l3n9WoO+IW78PGMIy7bH8/6WM2yLy2bM4h3MHtORqYNCZAJ0IYS4xhhdLPbu3ZuDBw82WCyq1WqCgoIaLTBxbSiuqOLnw2ms2ZfM4eQCw/aufs5MHRjChEg/7GzkhpXWxsbKgsdHhjE+wpdnfjjKn+fyeOnnE/x2LIO3boskyF16GYUQ4lphdLG4bNmyS15q7ty5M2fPnm2UoETrpigK+xPz+WZfMr8cSadMV/P/jbWlihsifLlnYAi9gtrWGs3Xqg5ejnw9bQBr9iWx4JdY/jyXx/Xv7OC5G7pwV79AybEQQlwDjC4W1Wp1U8YhrgHnckr45Wg6aw+kkJBTYtje3tOB2/sEMrlXAJ5O8v/RtcbCQsXd/YMZGubJU98d5s+zeTyz7iibTmTwxuTueDvLCjBCCNGaXdHUOXq9njNnzpCVlYVer6+1b+jQoY0SmGgdkvNK+eVoOj8fSeNY6t/zItrbWHJjd19u7xNI72BX6WFqAwLd7Pn64QF8/sdZFm6MM4xlfPmmbkyM9Gvp8IQQQlwhk4vFPXv2MGXKFBITE+vMq6hSqYy6Kzo5OZlz585RWlqKp6cnXbt2Nbueyx07dvDmm29y4MAB0tPTWbduHTfddNMlz9m+fTuzZs3i+PHj+Pn5MWfOHB599NHmCbiZVFRVs+9sPtvisth2KpszWcWGfZYWKgaFujMh0o8bInxxkOXh2hwLCxUPDWlPVLgnT357iGOpWh5f8xdbYjN5+aZuONlat3SIQgghTGTyv+aPPvooffr04ZdffsHX19foHqPExESWLVvGmjVrSE5OrlVo2tjYMGTIEKZNm8bkyZOxsLAwNaxGV1JSQmRkJPfffz+TJ0++7PFnz55l/PjxPPzww6xatYo//viD6dOn4+npadT55qiySk9SXglxGcUcTMrnYFI+x1O1VFb/3ZtsaaGiX4gbN0b6cn1XH9wdzavoFy0jzNuJddMH8/6WM7y/9Qw/HkrjYFIB79zZg55Bri0dnhBCCBOYXCyePn2a77//ng4dOhh9zhNPPMEXX3zBmDFjeOmll+jXrx/+/v7Y2dmRl5fHsWPH2LlzJ88//zzz58/niy++oG/fvqaG1qjGjRvHuHHjjD5+2bJlBAUFsWTJEqDmhp/9+/fz1ltvmU2xuD8xn50ZKrJ3J4LKAl21QrVeT5VeQVetp6BUR35pJbnFlWQVVZCUV0q1vu6qPJ5OaqLCPRne0YvrOnigsZfeIlGXtaUFT44OZ2i4B4+vOURSXim3LdvNk6PDeTQqVKbYEUKIVsLkYrF///6cOXPGpGLRxsaG+Ph4PD096+zz8vJixIgRjBgxgnnz5rFhwwYSExNbvFg01e7duxkzZkytbWPHjuWzzz5Dp9NhbV23oKqoqKCiosLwWqutGfOn0+nQ6XSNHuMvR9L5/qwlnI0z+hx7G0vaezgQGaChZ6CGHkEuBLna1epRbopYr3UX/pu1hf923f2cWD99AC/8FMsvRzN4c2McO09l8eatEfiYwc0vbSkX5kzyYD4kF+ahOfJgbNsqxYgFnY8cOWJ4Hh8fz3PPPcd//vMfIiIi6hRB3bt3NzFU86dSqS47ZjE8PJz77ruPZ555xrAtJiaGwYMHk5aWhq+vb51zXnzxRebPn19n++rVq7G3b/x56vZkqTiRr8JCBRYqsDz/uPDczgocrRQcrcHJGjxtFTQ2NaurCHG1FAX+zFbx/VkLKvUq7K0UpoTqiXCTNeWFEKIllJaWMmXKFAoLC3F2dm7wOKN6Fnv06IFKpao1zvCBBx4wPL+wz9gbXK5V/xy/eeG/V0PjOufOncusWbMMr7VaLYGBgYwZM+aSSbtSo3U6oqOjGT16dL09naL56NpoLm4A7ssp4cnvjnA8rYhP4yy5u18gT18fjq11y0zO3lZzYW4kD+ZDcmEemiMPF65oXo5RxWJjTrbds2fPeosnlUqFra0tHTp04L777mP48OGN9p7NwcfHh4yMjFrbsrKysLKywt3dvd5z1Gp1vXeBW1tbN+kvaFO3L4zXFnMR7uvCuunX8damOD7ekcBXfyazP7GA96b0JNzbqcXiaou5MEeSB/MhuTAPTZkHY9s16rbj4OBgox+Xc/3115OQkICDgwPDhw9n2LBhODo6Eh8fT9++fUlPT2fUqFH873//M+oDmIuBAwcSHR1da9umTZvo06eP/LIJ8Q82VhY8M74zKx/oh4ejmrjMIia+v4vVe5PqTMklhBCiZZk8R81rr73G559/Xmf7559/zhtvvHHZ83NycnjqqafYuXMnb7/9NosWLWLHjh3Mnj2bkpISNm3axHPPPcfLL79samiNqri4mEOHDnHo0CGgpnf10KFDJCUlATWXkO+9917D8Y8++iiJiYnMmjWL2NhYPv/8cz777DNmz57dEuEL0SoMDffk1yeGMDTck3KdnmfWHeXfqw9SWCoD64UQwlyYXCx+9NFHdOrUqc72rl27smzZssue/+2333LXXXfV2X7nnXfy7bffAnDXXXcRF2f8HbtNYf/+/fTs2ZOePXsCMGvWLHr27MkLL7wAQHp6uqFwBGjXrh0bNmxg27Zt9OjRg5dffpl3333XbKbNEcJceTqpWX5fX54d3xlrSxUbjmYw/t2dHEjMa+nQhBBCcAVT52RkZNR7Z6+npyfp6emXPd/W1paYmJg6U+/ExMRga1szjYZer2/xFV2GDRt2ycthy5cvr7MtKiqKgwcPNmFUQlybLCxUPDy0Pf3buzFjzV8k5pZy+0d7eHJUGI8N6yBzMgoh2pRqvcLes3lsTVMxvqWD4QqKxcDAQP744w/atWtXa/sff/yBn9/l13+dMWMGjz76KAcOHKBv376oVCr+/PNPPv30U8O0Mxs3bjT06Akh2o7uAS78POM6nv/xGD8eSuOtTaf440wui+/ogY+m5edkFEKIplKtV9h/Lo9fjqaz4WgGOcUVqLDgv8UV+Lq27L0PJheLDz30EDNnzkSn0zFixAgAfv/9d+bMmcNTTz112fOfe+452rVrx/vvv8+XX34JQMeOHfnkk0+YMmUKUDP+77HHHjM1NCHENcDJ1pold/ZkSJgnz//vGLsTchn3zg7eui2SkZ29Wzo8IYRoNFXVev48l8evRzP47XgG2UV/L9ShsbOik2MlFVX6S7TQPEwuFufMmUNeXh7Tp0+nsrISqLm0/N///penn37aqDbuvvtu7r777gb329nZmRqWEOIaM7l3AD2DXJix5i+Op2l5cMV+7hsUwtzxnVBbtcycjEIIcbWqqvXsSchjw7F0Nh7LILek0rDPydaKsV19uKG7L/2CNGze9Bv+Li1fE5lcLKpUKt544w2ef/55YmNjsbOzIywszKQxhgUFBXz//fckJCQwe/Zs3NzcOHjwIN7e3vj7+5sakhDiGtXe05Efpg/ijV/j+PyPsyyPOcefZ/N4b0pPQj0dWzo8IYQwiq5aT0x8LhuOpLPpRAb5F8344GJvzZgu3oyL8GVwqAc2VjX3HpvTcosmF4sPPPAA77zzDk5OTrXWby4pKWHGjBn1TqtzsSNHjjBq1Cg0Gg3nzp3joYcews3NjXXr1pGYmMjKlStN/xRCiGuW2sqSFyZ04bowd2Z/d4QT6VomvLeL+RO7cmvvgAZXSBJCiJZUUVXNH2dy2HA0g+gTmRSW/V38uTnYMLarN+O6+TIw1B1rS5Mnp2lWJke3YsUKysrK6mwvKyszqtCbNWsW9913H6dPnzbc/Qwwbtw4duzYYWo4Qog2YkQnb359YgiDQt0prazmP98f4YmvD1FUbj5/fQsh2rZyXTXRJzKZ9c0h+ryymQeW7+f7AykUlunwcFTzrwFBrH6oP38+M5LXbunO0HBPsy8UwYSeRa1Wi6IoKIpCUVFRrUKvurqaDRs24OXlddl29u3bx0cffVRnu7+/f53l8oQQ4mLezrZ8+WB/lm2PZ1H0KdYfTuNQcgHv3tWTHoEuLR2eEKINKtdVsy0um1+PpfN7bBbFFVWGfV5OasZ182FchC99Q9xa7TRgRheLLi4uqFQqVCoV4eHhdfarVCrmz59/2XZsbW3rXbg6Li4OT09PY8MRQrRRlhYq/j28AwPau/P4mr9Iyivl1g9jmD22I9OGtMeilX4ZCyFaj5KKKrbFZbPhWDpbT2ZRWllt2OersWVcN1/GR/jQK8j1mvhOMrpY3Lp1K4qiMGLECNauXYubm5thn42NDcHBwUbNszhp0iReeuklw2otKpWKpKQknn76aVntRAhhtN7Brmx4YgjP/HCUX46m8/qvJ/njTA5v3x6Jl5PMySiEaFy5xRVsjs1k4/FMdp3JofKiKW38XewYH1HTg9gjwOWaKBAvZnSxGBUVBdSskRwUFHTFg8rfeustxo8fj5eXF2VlZURFRZGRkcHAgQN59dVXr6hNIUTbpLGz5v0pPblunwfzfzrOztM5jH9nJ2/f3oOocLlSIYS4Oin5pWw8nsnG4xnsP5eH/qKF3dp5ODCmqzc3RPgS4a+5pm+2M6pYPHLkCN26dcPCwoLCwkKOHj3a4LHdu3e/ZFvOzs7s2rWLLVu2cPDgQfR6Pb169WLUqFGmRS6EENRcnbirXxB9gl2ZseYvTmYUMfXzP5k2tD2zx3Q0TEMhhBCXoygKpzKL2Xg8g43HMzieVnvYXDd/Z8Z28WFsNx/CvByv6QLxYkYViz169CAjIwMvLy969OiBSqWqd91klUpFdXV1PS3UNWLECMMKMEIIcbXCvJ348d+DefWXWL7ck8jHOxLYk1CzVKDMySiEaIher/BXcj6bzvcgnsstNeyzUEHfEDfGdvVhTFdvAlztWzDSlmNUsXj27FnDzSdnz541+U3effddo499/PHHTW5fCCEAbK0tefmmblwX5sGc749wJKWQG97dyX+v78TUgSHX3DgiIcSVqazSszshl43Ha+ZAvHiZPRsrC4Z08GBsVx9GdvbC3dH4RUeuVUYVi8HBwQAUFRVx6tQpdDod/fr1w8PDw6g3Wbx4ca3X2dnZlJaW4uLiAtSs6GJvb4+Xl5cUi0KIqza2qw/dAzTM+f4IO0/nMP+nE2w6nsmbt3Vvsz0DQrR1ucUVbI3L5vfYTHaezqk1xY2T2orhnbwY29WHqI6eOKpNXrPkmmb0f40jR44wbtw4MjIyUBQFZ2dnvv/+e6PGGl7cG7l69Wo++OADPvvsMzp27AjUTJvz8MMP88gjj1zBRxBCiLp8NXasfKAfq/YmseCXWHYn5HL9kp08f2Nnbu8T2GbGGgnRVimKwumsYjbHZvJ7bBYHk/K5eASdh6Oa0V28GdvVm0EXLbMn6jK6WHz66acJCgriu+++w9bWlvnz5/N///d/nDx50qQ3fP755/n+++8NhSJAx44dWbx4Mbfeeit33323Se0JIURDVCoV9wwIZkgHD2Z/d5j9ifn8d+1RNh7P5PVbIvBylil2hLiWVFbp2Xcuz1AgJuWV1trf2deZUZ29GNnZm+7+GhmaYiSji8X9+/ezYcMG+vTpA8Dnn3+Ol5cXxcXFODoaP3g8PT293sWxq6uryczMNLodIYQwVoiHA988MpBPdybw9qZTbDmZxZglO3h5UjfGdjZuOI0Qwjzll1Sy7VQWm2Oz2BGXTdFFl5dtLC0YGOrOqM5ejOjsjb+LXQtG2noZXSzm5OQQFBRkeO3u7o69vT3Z2dkmFYsjR47k4Ycf5rPPPqN3796oVCr279/PI488ItPnCCGajKWFikeiQhneyYtZ3x7iWKqWGWv+YnRnL4bIMEYhWg29XuF4mpZtcVlsP5XNwaT8WvMfejjaMLxjTe/hkDAPHGT84VUz+r+gSqWqtSa0oiiGbRcv3+fs7HzJdj7//HOmTp1Kv379sLa2BqCqqoqxY8fy6aefXslnEEIIo4V7O7Fu+mDe33KGpVvPEB2bxU5LS1T+Kdw9QO6YFsIc5ZdUsuN0NttPZbPjVDY5xZW19nfycWLk+cvL1+IKKi3N6GJRUZQ6a0IrikLPnj0Nz42ZZ9HT05MNGzZw+vRpYmNjURSFzp0717vetBBCNAVrSwueHB3OuAgf5nx/mCMpWp5ff4Kfj2bw+uTutPNwaOkQhWjT9HqFo6mFbIvLZtupLA4nF9TqPXSwsWRQBw+GdfQkKtxTZjloYiatDd2YwsLCCAsLa9Q2hRDCFJ18nPn24f7M/eI3fku1Zu/ZPMYu2cHMUWE8PKQ91pZyd6QQzSWrqJw/zuSwPS6bHadzyCup3XvY0dvJUBz2CXGTu5ebkclrQ1+J119/nccffxx7+8tX/nv37iUnJ4cbbrjhit9PCCGMZWmhYpivwoxbBjHvp5PsPJ3Dwt/i+OlwOq/c1JXewW4tHaIQ16TSyir2JuSx60wOu07nEJdZVGu/o9qKwR3cGdbRi6hwT/zk5pQWY1SxePGYxMupb8ziiRMnCAoK4rbbbmPixIn06dPHsCJMVVUVJ06cYNeuXaxatYr09HRWrlxp9PsJIURjCHS1Z+UD/Vh7MJWXfz5BbLqWyR/u5rbeATw9rpOs4iDEVaqq1nM0tZBdp3PYeSaHv5Ly0VXXXjq4q58zQ8I8GdbRk15BrtJ7aCaMKhZdXFyMnsC2vjGLK1eu5MiRIyxdupS7776bwsJCLC0tUavVlJbWzIHUs2dPpk2bxtSpU1GrzeNL+YMPPuDNN98kPT2drl27smTJEoYMGVLvsdu2bWP48OF1tsfGxtKpU6emDlUI0QhUKhW39g5geEdP3vjtJN/uT+G7AylsPJ7Bf67vxJR+QVjKwHkhjKIoCudyS9l1OptdZ3KIic+lqLyq1jH+LnYMCfNgcAcPBoW6yx9lZsqoYvHi8Yrnzp3j6aef5r777mPgwIEA7N69mxUrVvDaa6812Eb37t356KOPWLZsGUeOHOHcuXOUlZXh4eFBjx49jF46sLl88803zJw5kw8++IDBgwfz0UcfMW7cOEMvaUPi4uJq9a5e6EEVQrQe7o5qFt4ayR19A3nux+PEpmt5/sdjfLsvmZdv6kaPQJeWDlEIs6MoCkl5peyOz2VPQi57EvLI0JbXOsbZ1opBoR4MDvNgSAcPgt3tZTWlVsCoYvHi8YovvfQSixYt4q677jJsmzhxIhEREXz88cdMnTr1km2pVCoiIyOJjIy8wpCbx6JFi3jwwQd56KGHAFiyZAkbN27kww8/vGRR7OXlZVjzWgjRuvUOduOn/xvMqj2JvL3pFEdTC7n5gz+4vXcgT40Nx8tJVoARbZeiKCTnlbE7IYc9CXnsScglvbB2cWhjaUGvYBeGhHkyuIMHEf4a6Z1vhUyeqXL37t0sW7aszvY+ffoYCqvWrrKykgMHDvD000/X2j5mzBhiYmIueW7Pnj0pLy+nS5cuPPfcc/Vemr6goqKCiooKw+sLY0N1Ol29q9xcrQttNkXbwjSSC/NhTC7u7hfA2C6evPHbKX48nM43+5P5+Uga04a044HBwdhaWzZXuNcs+Z0wHw3lQlEUUgrK2Hs2n70Jeew9l1+nOLS2VBEZoKF/Ozf6t3OlR4ALdjZ//37oq6vQX3qGPXFec/xOGNu2SlEU5fKH/a1jx47ceOONvP3227W2P/XUU/z888/ExcWZ0pxZSktLw9/fnz/++INBgwYZti9YsIAVK1bU+xnj4uLYsWMHvXv3pqKigi+//JJly5axbds2hg4dWu/7vPjii8yfP7/O9tWrVxt157gQovklaOHHREsSi2t6R1xsFCYE6enloSAdJuJaoiiQVQ4JWhUJRSpOF6rIr6z9P7mlSiHYETo4K3TQKLRzVLCRv51ajdLSUqZMmUJhYeElF1UxuVjcsGEDkydPJjQ0lAEDBgCwZ88e4uPjWbt2LePHj7+6yM3AhWIxJibGMC4T4NVXX+XLL7/k5MmTRrUzYcIEVCoV69evr3d/fT2LgYGB5OTkXHYlnCuh0+mIjo5m9OjRhtVzRMuQXJiPK8mFXq/wy7EM3tp0mrTzPSvd/Z2ZO64jfYJdmzLca5b8TrS8qmo9J9KL+PNsLr/uP0VKuZq80to9T1YWKroHaOjfzpX+7dzoGajB3kaW02sKzfE7odVq8fDwuGyxaHKGx48fz6lTp/jwww85efIkiqIwadIkHn30UQIDA68qaHPh4eGBpaUlGRkZtbZnZWXh7e1tdDsDBgxg1apVDe5Xq9X13vltbW3dpF+WTd2+MJ7kwnyYmotbegcxvrs/n+06ywdbz3AkVctdn+5jdBdvnhoTTiefxv+Dry2Q34nmU1JRxaHkAv48m8f+xDz+SiqgtPLCNWILQIeNlQU9Al3oG+LKgPbu9A52leKwmTXl74Sx7V5RxgMDA1mwYMGVnNoq2NjY0Lt3b6Kjo7n55psN26Ojo5k0aZLR7fz111/4+vo2RYhCCDNga23Jv4d34PY+gSzefIqv/0wi+kQmm2MzmdDdjydHh8vSgcJs5BRXsP9cPvvO5bH/XB7H0rRU62tfXHS2taJ3sAuOZZn8a+xAegS7obaS68ptnVHF4pEjR4xusHv37lccjDmZNWsW99xzD3369GHgwIF8/PHHJCUl8eijjwIwd+5cUlNTDROIL1myhJCQELp27UplZSWrVq1i7dq1rF27tiU/hhCiGXg6qVlwcwQPDG7H4uhT/HI0nfWH0/jlaDq39Q7g8ZFhsvqEaFbVeoXTWUUcTCzgQGI+fyXlk5BTUuc4P40tfdu50SfEjX4hboR5OVJdXcWGDRvoFeSCtRSKAiOLxR49eqBSqbjc8EaVSlXvpNyt0R133EFubi4vvfQS6enpdOvWjQ0bNhAcHAxAeno6SUlJhuMrKyuZPXs2qamp2NnZ0bVrV3755ZdrYgynEMI4HbwcWXp3Lx5LLWRR9Cm2nMzi633J/HAwlTv7BTJtaHsCXOXmNdH4tOU6DiXVFIYHk/I5lFRAUUVVnePCvR3pG+JW82jnhn89f8RcI/+Mi0ZkVLF49uzZpo7DLE2fPp3p06fXu2/58uW1Xs+ZM4c5c+Y0Q1RCCHPXzV/D5/f15UBiHm9ujGNPQh4rdyeyem8SN/X057FhoYR6OrZ0mKKVUhSFhJwSDp4vDA8mFnAqq4h/9ufY21jSI9CFXkGu9A52pWeQCy72Ni0TtGjVjCoWL/SmCSGEMF7vYDfWPDyA3fG5LN12hj/O5PL9gRTWHkxhfDdfpg8PpaufpqXDFGautLLmRpS/kv6+pJxfWnd+vCA3e3oHu9IryIVewa509HbCylLWVhZXz+QbXHJzc3F3dwcgOTmZTz75hLKyMiZOnNjguslCCNFWqVQqBnXwYFAHDw4m5fPB1ng2x2byy9F0fjmaztBwT+4fHEJUmCcWMlFjm6fXKyTkFPNXUgGHU2oKxJMZRXVuRFFbWdA9QEOvYFd6BdU8PJ1kXWXRNIwuFo8ePcqECRNITk4mLCyMr7/+muuvv56SkhIsLCxYvHgx33//PTfddFMThiuEEK1XryBXPp3ah5MZWj7YGs/PR9LYcSqbHaeyae/hwNRBIUzuHYCjWqYmaSuyiyo4lFzAoeR8DicXcjilgKLyumMNfTW29Ap2pXeQK72CXeni64yNlfQaiuZh9DfSnDlziIiIYNWqVaxatYobb7yR8ePH8+mnnwIwY8YMXn/9dSkWhRDiMjr5OPPuXT15akw4K3cn8u2+ZBJySpi3/jhvbozjtj4BTOkXRJi3U0uHKhpRWWU1x9IKOZRUcL5ALCC1oKzOcbbWFnT3dyEyUEOPwJqxhnI3vWhJRheL+/btY8uWLXTv3p0ePXrw8ccfM336dCwsav6ymTFjhmFFFyGEEJcX7O7A8zd2YdbocNYeTGF5zDkSskv44o9zfPHHOXoGuXB7n0Bu7O6Lk61MVN2aVFXrOZNdzJGUwprCMKmAuMy6l5NVKgjzcqRHoAuRgS70CHSRsYbC7BhdLObl5eHj4wOAo6MjDg4OuLm5Gfa7urpSVFTU+BEKIcQ1zkFtxb0DQ/hX/2B2nslh1Z5EtpzM4q+kmjFr8386zvhuvkzs4cfgDh5YSyFhVqqq9ZzOKuZoaiHHUgs5mlpIbLqWcp2+zrFeTmp6BLrQI8iFHgEuRARo5A8BYfZMGhijUqku+VoIIcSVs7BQERXuSVS4J1lF5aw7mMq3+5OJzy7hh79S+eGvVFztrbm+mw83dvejfzs36YFqZobCMKWmKLxQGFZU1S0MHdVWdPVzrikOz/cc+mps5d9O0eqYVCzed999hrWMy8vLefTRR3FwqFnKqqKiovGjE0KINsrLyZZHokKZNrQ9B5MKWPdXCr8ezSC3pJI1fyaz5s9k3B1sGNbRixGdvBgS7oGz9FA1qrySSk6mazmRruVkRhGx6VpOZxVT2UBh2M3fmQh/Dd38NUT4awhxd5A73MU1wehicerUqbVe/+tf/6pzzL333nv1EQkhhDBQqVT0Dq6ZVPnFCV3ZezaPn4+k89uxdHJLKll7sGbeRisLFX1CXBnW0YuB7d3p6ucsvY5GqqzSczanhJMZ5wvD9JrCMKuo/k4QJ7UVXaUwFG2I0cXiF1980ZRxCCGEuAwrSwsGd/BgcAcPXprUlX3n8th6MostJ7OIzy5hT0IeexLygJqerr4hrvRv706/dm508XXG1rptr/OrLdcRn1XMmaxi4rNLOJNVTEJ2MYl5pXVuPLkg2N2eTj5OdPZ1ppOPM519nQh0tZfCULQpMpmXEEK0QtaWFgwK9WBQqAfP3tCFpNxStpzMZNeZHPaezaOovIqtcdlsjcsGwMpCRZi3E939NUQEaOgeoCHMywk7m2urgCws1ZGUV0pSXinJ+TU/z2aXEJ9d3GBPIdQU1518nOjk63S+KHSmo4+TzHkpBFIsCiHENSHI3Z77BrfjvsHtqNYrxKZr2ZOQy56EPP5Kyie3pJLYdC2x6Vq+2Z8M1Ezb4u9iR6inY83Dy4F27g74udjho7E1u57Icl01mdpyMrUVZGjLydKWk1FYTlphWU2BmFuKtp4JrS/m7awm1NORDl6OtX56O6vlxhMhGiDFohBCXGMsLVR0Oz+e7qEh7VEUhfTCco6kFHI0tYCjqVqOphSQX6ojJb+MlPwytp/KrtOOu4MNvi62+Grs8HBU42pvjYu9NS72Nrja26Cxs8bW2gJba0tsrSyxtbZAbW2J+h8riygKKCgoClRU6SnTVVNWWU25rpoyXc1PbWkFuzNVpOw8i7aimoISHfmllRSU6SgorSSrqIKCetZDro+Ho5ogNzuC3OxrHu4OdPBypL2ng9wEJMQVkGJRCCGucSqVCj8XO/xc7Li+m49he25xBfHnL9HGZxUTn11MYm4paYVllOv05JZUkltSybFUbTNFagkJpy95hNrKAh+NLd7ONQ8fZzU+mr8Lw0A3O+xt5J82IRqT/EYJIUQb5e6oxt1RTb92brW2K4pCQamOtMIy0gvKSS8sI+9CT19pJfmlNb192vIqys/3DJbr9JRXVaPUf59ILWqrmt5IO2tL7Gwszz+3oKIoj/Bgf9wcbXGxs8bFwaamN9POBk8nNd7OajR21nK5WIhmJsWiEEKIWlQqFa4ONrg62NDVT2P0eYqioKtWqKiqNrRzoaxTqUCFCrWVRb13Eut0OjZs2MD48RFYW8ulYiHMiRSLQgghGoVKpcLGSoWNlczvKMS1RIpFM6Kcv36j1TbN+CCdTkdpaSlarVb+cm9hkgvzIbkwD5IH8yG5MA/NkYcL9YZymfEjUiyakaKiIgACAwNbOBIhhBBCtBVFRUVoNA0POVEplysnRbPR6/WkpaXh5OTUJAO4tVotgYGBJCcn4+zs3OjtC+NJLsyH5MI8SB7Mh+TCPDRHHhRFoaioCD8/PywsGh4+Ij2LZsTCwoKAgIAmfx9nZ2f5AjATkgvzIbkwD5IH8yG5MA9NnYdL9SheIKOQhRBCCCFEg6RYFEIIIYQQDZJisQ1Rq9XMmzcPtVrd0qG0eZIL8yG5MA+SB/MhuTAP5pQHucFFCCGEEEI0SHoWhRBCCCFEg6RYFEIIIYQQDZJiUQghhBBCNEiKRSGEEEII0SApFoUQQgghRINkBRcz0tTL/QkhhBBCXCDL/bVCaWlpBAYGtnQYQgghhGhDkpOTL7ncsBSLZsTJyQmgyRYN1+l0bNq0iTFjxmBtbd3o7QvjSS7Mh+TCPEgezIfkwjw0Rx60Wi2BgYGG+qMhUiyakQuXnptq0XCdToe9vT3Ozs7yBdDCJBfmQ3JhHiQP5kNyYR6aMw+XG/omxaIQQgghRAsqrqgiNb+M1IJSUvPLSCkoIyW3lBOJloy9XqGlS3YpFoUQQgghmoiiKBSW6UjJLyMlv5SU/DJSC8rOF4dlpOSXUVima+BsFVlFFQSpbZo15n+SYlEIIYQQ4ioUlulIziutVRD+/bOM4oqqy7bhbGtFgKs9/q52+LvY4etsQ0ZCLM62LV+qtXwEQgghhBBmTFuuIyXv7wIw+aJCMCW/lKLyyxeDHo42+LvaE+BiR4CrnaEovPDTybb2xWadTseGwhM4qFu+VGv5CIQQQgghWlBpZRVJeaWk5F1cCP5dEDZ8mfhvhmLQ1e78w57A8z/9Xeyws7Fshk/SNKRYFEIIIcQ1TVEUcoorScorISmvlMTcUpJyS0k8/zynuOKybbg52BgKwUBDUWhv6CW0t7l2S6pW/cl27NjBm2++yYEDB0hPT2fdunXcdNNNhv2KojB//nw+/vhj8vPz6d+/P0uXLqVr166GYyoqKpg9ezZr1qyhrKyMkSNH8sEHH9SanDI/P5/HH3+c9evXAzBx4kTee+89XFxcDMckJSXx73//my1btmBnZ8eUKVN46623sLFp2UGpF4vPLmHpCQu69i+lg4+mpcMRQgghGo2uWk9aQRmJ54vApNySmqIwr5TkvFJKKqsveb7GzppAt7qF4IWf5nA5uKW06k9eUlJCZGQk999/P5MnT66zf+HChSxatIjly5cTHh7OK6+8wujRo4mLizNMQDlz5kx++uknvv76a9zd3Xnqqae48cYbOXDgAJaWNV3GU6ZMISUlhd9++w2AadOmcc899/DTTz8BUF1dzQ033ICnpye7du0iNzeXqVOnoigK7733XjP917i8l36O5VShBROWxvDM+M78a0CwLCsohBCi1SiuqCIxt4Sk80VgTVFYSmJeCWkF5VTrlQbPVanAT2NHoJsdwW4OBLnbE+xuT5CbPcFuDmjsW3qCGvPVqovFcePGMW7cuHr3KYrCkiVLePbZZ7nlllsAWLFiBd7e3qxevZpHHnmEwsJCPvvsM7788ktGjRoFwKpVqwgMDGTz5s2MHTuW2NhYfvvtN/bs2UP//v0B+OSTTxg4cCBxcXF07NiRTZs2ceLECZKTk/Hz8wPg7bff5r777uPVV19tkgm2r8SCm7vy0CfbOaOF5/93nE0nMll4a3d8NXYtHZoQQggBQEVVNUm5pSTklHAup4SzOSWG51lFl75crLayqCn+3O0JcnMgyM2OYPeawjDA1Q61VesdN9iSWnWxeClnz54lIyODMWPGGLap1WqioqKIiYnhkUce4cCBA+h0ulrH+Pn50a1bN2JiYhg7diy7d+9Go9EYCkWAAQMGoNFoiImJoWPHjuzevZtu3boZCkWAsWPHUlFRwYEDBxg+fHi9MVZUVFBR8ff/+FqtFqi5A0qnu/xgWlN5OVjx7y56sjThLPo9gZ2ncxizeAfzbujExEhf6WVsRhfy2xR5FqaRXJgHyYP5aI5cVOsVUgvKOJdbWvPIKeHs+Z9pheVcooMQV3trgtxqbh4JcrMnyO3vn56OaiwsGvi3TNGj0+mb5gM1gebIg7FtX7PFYkZGBgDe3t61tnt7e5OYmGg4xsbGBldX1zrHXDg/IyMDLy+vOu17eXnVOuaf7+Pq6oqNjY3hmPq89tprzJ8/v872TZs2YW9vf7mPeEUsVOCjPclT3WDVaUuSSqqYvfYYK7ce4Y72ehylF75ZRUdHt3QI4jzJhXmQPJiPq82FooBWB1llKrLLIbtMRVY5ZJeryCmHaqXhDgq1pYKXLXjaKnjZ1fz0tFPwtAV7qyqgrObASiADsjMg+6qiNV9N+TtRWlpq1HHXbLF4wT97yxRFuWwP2j+Pqe/4Kznmn+bOncusWbMMry8s6D1mzJgmWxs6Ojqa0aNHY21tzT3Vej7aeY73t8ZzJM+C1ApbXpnUhVGd6xbHonH9Mxei5UguzIPkwXyYmgtdtZ7kvDLis2suF8fnlJBw/vml5h+0sbIg2M2OEHcH2nnYE+Jub3ju7mDT5q92NcfvxIUrmpdzzRaLPj4+QE2vn6+vr2F7VlaWoRfQx8eHyspK8vPza/UuZmVlMWjQIMMxmZmZddrPzs6u1c7evXtr7c/Pz0en09XpcbyYWq1GrVbX2W5tbd2kX5YX2re2hpmjOzKqiw9PfXuYuMwiHlt9iMm9Apg3sQvOtvKF3dSaOtfCeJIL8yB5MB//zIW2XEdCdgnxWcXEZxdz5vzPxNxSqhq4bmyhgkA3e9p5ONDOw4H2Hg6EnH/up7Fr+JKxMGjK3wlj271mi8V27drh4+NDdHQ0PXv2BKCyspLt27fzxhtvANC7d2+sra2Jjo7m9ttvByA9PZ1jx46xcOFCAAYOHEhhYSF//vkn/fr1A2Dv3r0UFhYaCsqBAwfy6quvkp6ebihMN23ahFqtpnfv3s36ua9EN38N62cMZlH0KT7ekcDagynsjs/hrdsiGdTBo6XDE0II0UwURSG9sJy4AhU5e5I4l1tGfHZNUZipbfjmEjtrS0K9HOjg6UiopyOhXjU/Qzzs5aaSa0CrLhaLi4s5c+aM4fXZs2c5dOgQbm5uBAUFMXPmTBYsWEBYWBhhYWEsWLAAe3t7pkyZAoBGo+HBBx/kqaeewt3dHTc3N2bPnk1ERITh7ujOnTtz/fXX8/DDD/PRRx8BNVPn3HjjjXTs2BGAMWPG0KVLF+655x7efPNN8vLymD17Ng8//LDZ3Al9OWorS+aO68yozt489e1hkvJKmfLpXu4bFMJ/r+/UqmeeF0IIUZuiKGRqKziVWXTRo6a3sGYdY0uIPVnnPE8ndU1B6OVQUxR6OtLByxEfZ1vpJbyGtepicf/+/bXuNL4w/m/q1KksX76cOXPmUFZWxvTp0w2Tcm/atMkwxyLA4sWLsbKy4vbbbzdMyr18+XLDHIsAX331FY8//rjhrumJEyfy/vvvG/ZbWlryyy+/MH36dAYPHlxrUu7Wpm+IG78+MYQFG2L5am8Sy2POseNUNm/fHknPINfLNyCEEMJsKIpCdnEFpzOLDQXhheKwofGElhYq3G30dA/xooO3Mx28HAn1dKC9pyMaOxki0BapFEW5xA3qojlptVo0Gg2FhYVNdoPLhg0bGD9+vFHjFLbFZfHftUfI1FZgoYLHhoXyxMhwbKwsGj22tsbUXIimI7kwD5KHq5dXUlmnp/B0ZhH5pfVPj2JpoSLY3Z6O3k6EeTsR7u1IuLcT/s42bN70m+SihTXH74SxdUer7lkUTWtYRy82zYxi3vpj/HgojaVb49lyMptFt0fS2bd1XF4XQohrTbmumjNZxcSmazmZUURsupZTmUXkFFfWe7xKBcFu9oR5O50vDGuKwvaeDvWOJ5S5LsU/SbEoLkljb82SO3sypqsPz647Smy6lonv72LW6I5MG9oeSxmjIoQQTUJRFLKLKjiRriU2vYiTGVpi07XEZ5c0uKxdoJsd4V41PYUdfRwJ83Kig5cjttYy7lxcuWYvFuPi4lizZg07d+7k3LlzlJaW4unpSc+ePRk7diyTJ0+udzoZ0bLGR/jSJ8SVZ344yubYLN747SSbYzN5+7ZIQjwcWjo8IYRo1SqqLvQWFnEyXUtsRk2BmFdSf2+hxs6azr5OdPZ1prOvs6HH0N5G+oBE42u2/6v++usv5syZw86dOxk0aBD9+vXjpptuws7Ojry8PI4dO8azzz7LjBkzmDNnDjNnzpSi0cx4Odnyyb19+O5ACi/9dIIDifmMe2cnz4zvxL8GBLf5CVSFEMIYxRVVnEjTcjS1kOOphRxP0xKfXVzvXIUWKmjv6UgnnwuFYc1PH2db+c4VzabZisWbbrqJ//znP3zzzTe4ubk1eNzu3btZvHgxb7/9Ns8880xzhSeMpFKpuL1PIINC3Zn93WH2JOTx/P+Os+lEJgtv7Y6vxq6lQxRCCLOhLddxLLWQ46k1xeGxtELO5pRQ362lzrZWhp7CLr7OdPJ1ItzbSS4hixbXbMXi6dOnsbGxuexxAwcOZODAgVRW1t/1LsxDgKs9qx8awPKYc7zx20l2ns5hzOIdvDSpKzf18Je/eIUQbU5BaSXHLioKj6UWkphb/9q7vhpbuvlr6OanoZt/TYHoq5HeQmGeTC4Wjxw5YvSx3bt3Nzw3plC8mKnHi+ZnYaHigevaMTTck6e+O8zh5AKe/OYwG49l8urN3XB3lGEEQohrU7mumuNphfyVVMDhlEIOJeeTnFdW77EBrnZ089MQEaChq58z3fw1eMj3o2hFTC4We/Tocdm/fBRFQaVSUV1d3eAxf/75J9u2bSMrKwu9Xl9r36JFi0wNS7SgDl6OrH10IB9ui+ed30/z2/EM9ifmseDmCMZ09Wnp8IQQ4qro9QoJOcX8lVTAoeQCDqcUcDK9qN4xhiHu9nQ932MY4V9THLo6SOeHaN1MLhZ/+OEHZs+ezX/+8x8GDhwI1IwzfPvtt1m4cKFhHeZLWbBgAc899xwdO3bE29u7VvEpXfCtk5WlBTNGhjG8kxdPfXuYuMwipn15gMm9Apg3sQvOtjKxqxCidcjSlnMo+e/C8EhyIUUVdVc78XBU0yPQhZ5BLkQGuBARoJEVTsQ1yeRiccGCBbz77ruMHz/esK179+4EBgby/PPPc+DAgcu28c477/D5559z3333mfr2wsx189ewfsZgFkWf4uMdCaw9mMLu+Bzeui2SQR08Wjo8IYSopapaT2x6EfsT89ifmM9fifmkFZbXOc7O2pIIfw09zheGPYJc8JMxhqKNMLlYPHr0KO3atauzvV27dpw4ccKoNiwsLBg8eLCpby1aCbWVJXPHdWZUZ2+e+vYwSXmlTPl0L/cNCuG/13fCzkbu7BNCtAxtuY6DifkcSMxn/7l8DiUXUKarPWRKpYJwLyd6BLoQGehCj0AXwr0dsbKUpU5F22Rysdi5c2deeeUVPvvsM2xtbQGoqKjglVdeoXPnzka18eSTT7J06VKWLFli6tuLVqRviBu/PjGEBRti+WpvEstjzrHjVDZv3x5JzyDXlg5PCHGNUxSF5LwyQ6/hwcR84jKL6kxb42xrRa9gV/oEu9Ir2JXuAS44qmVyayEuMPm3YdmyZUyYMIHAwEAiIyMBOHz4MCqVip9//tmoNmbPns0NN9xAaGgoXbp0qbNA9g8//GBqWMJMOaitePXmCEZ38ea/a4+QkFPC5A9jeGxYKE+MDMfGSv5SF0I0jqpqPcfTtOw7l1fTc5iYT3ZRRZ3jgt3t6R3sSp9gN3oHuxLm5YiFLF0qRINMLhb79evH2bNnWbVqFSdPnkRRFO644w6mTJmCg4Nxy77NmDGDrVu3Mnz4cNzd3WXMRxswrKMXm2ZGMW/9MX48lMbSrfFsOZnNotsj6ezr3NLhCSFaocoqPUdTC9iTkMfes3kcOJdHSWXtS8rWliq6+mnoE+xKn5CankMvJ9sWiliI1snoYvGBBx7gnXfewcnJCXt7e6ZNm3bFb7py5UrWrl3LDTfccMVtiNZHY2/Nkjt7MqarD8+uO0psupaJ7+9i1uiOTBvaHkv5y14IcQkVVdUcTi5kb0JuTXGYmF9nvKGzrRV9Q9zoHVLTc9g9QCMroAhxlYwuFlesWMHrr7+Ok5PTVb+pm5sboaGhV92OaJ3GR/jSJ8SVZ344yubYLN747SSbYzN5+7ZIQjyM650WQlz7ynXVHEzKZ29CHnvP5vJXUgEVVbXn5XW1t6ZfOzf6t3Onf3s3Ovk4yx+eQjQyo4tFpb6FLK/Qiy++yLx58/jiiy+wt7dvtHZF6+HlZMsn9/bhuwMpvPTTCQ4k5jPunZ08M74T/xoQLEMThGiDKqvhj/hcDiQVsichl8PJhVRW1y4OPRxtDIVh/3buMt5QiGZg0pjFxvoH/N133yU+Ph5vb29CQkLq3OBy8ODBRnkfYd5UKhW39wlkUKg7s787zJ6EPJ7/33E2nchk4a3d8dXYtXSIQogmpKvWcySlgD/O5LLrdDYHEi2p/rP2XL1eTmr6t3dnwPniMNTTQf6YFKKZmVQshoeHX/aXNC8v77Lt3HTTTaa8rbjGBbjas/qhASyPOccbv51k5+kcxizewUuTunJTD3/5h0GIa4RerxCXWcQfZ3KIic9lb0LuP25IUeHjrGZgqAf927nRv707Ie728h0gRAszqVicP38+Go3mqt903rx5V92GuLZYWKh44Lp2DA335KnvDnM4uYAnvznMxmOZvHpzN9wd1S0dohDiCiTllvJHfA5/nMlhd3wuuSWVtfa72FszKNSd/iGuVCYfZeoto7GxkbWUhTAnJhWLd955J15eXo0awPTp03nppZfw8JCl4AR08HJk7aMD+XBbPO/8fprfjmewPzGPBTdHMKarT0uHJ4S4jJziipqewzO5/BGfQ0p+Wa39dtaW9GvnxuAO7gwK9aCLrzMWFip0Oh0bco5KL6IQZsjoYrGpfoFXrVrF7NmzpVgUBlaWFswYGcbwTl489e1h4jKLmPblASb3CmDexC4421pfvhEhRLOorNKzPzGPnadz2HEqm+Np2lr7rSxU9Ah0YVAHDwaHutMzyFUm4xeilWmRu6Gbo13R+nXz17B+xmAWRZ/i4x0JrD2Ywu74HN66LZJBHeSPCyFagqIonMstZcepbHacymZ3Qi6l/5gIu7OvM4ND3RncwYN+7dxwkKXzhGjVjP4N1uv1lz9IiEamtrJk7rjOjOrszVPfHiYpr5Qpn+7lvkEh/Pf6TtjZyGS7QjS1onIdMfG5NQXi6WyS82pfWvZwtGFImCdDwz24roMnnk4yxliIa4nJf+6VlJTw+uuv8/vvv5OVlVWniExISDCpvaKiIlNDEG1Q3xA3fn1iCAs2xPLV3iSWx5xjx6ls3ro9kl5Bri0dnhDXFL1e4WhqITtOZbPzdA4Hk/Kp0v99FcjaUkWfYDeGhnsyJOzvcYdCiGuTycXiQw89xPbt27nnnnvw9fWVwcii2TiorXj1/I0uc74/TEJOCbd+GMNjw0J5YmS4jIMS4ipkFZWzPS6bHadz2HU6m/xSXa397TwcGBrmwdBwTwa0d5dLy0K0ISb/tv/666/88ssvDB482OQ3s7CwuGxxqVKpqKqqMrlt0XZEhXuyaWYU89Yf48dDaSzdGs+Wk9ksuj2Szr7OLR2eEK1CtV7hSEoBW+Oy2Xoyi6OphbX2O6qtGBTqztBwT6LCPQl0k9W2hGirTC4WXV1dcXNzu6I3W7duXYP7YmJieO+99xr9hpcXX3yR+fPn19rm7e1NRkYGUDNYe/78+Xz88cfk5+fTv39/li5dSteuXQ3HV1RUMHv2bNasWUNZWRkjR47kgw8+ICAgwHBMfn4+jz/+OOvXrwdg4sSJvPfee7i4uDTq5xE1NPbWLLmzJ2O6+vDsuqPEpmuZ+P4uZo3uyLSh7WVtWCHqUVBayY7TOWw7mcW2U9nk/WPOwwh/DcM6ejI03JMegS5YW0pvvRDiCorFl19+mRdeeIEVK1aYvK7zpEmT6mw7efIkc+fO5aeffuLuu+/m5ZdfNjWky+ratSubN282vLa0/PumiIULF7Jo0SKWL19OeHg4r7zyCqNHjyYuLg4nJycAZs6cyU8//cTXX3+Nu7s7Tz31FDfeeCMHDhwwtDVlyhRSUlL47bffAJg2bRr33HMPP/30U6N/HvG38RG+9Alx5ZkfjrI5Nos3fjvJ5thM3r4tkhAPh5YOT4gWpSgKselFbI3LYltcFgcS87lo6CFOaiuGhnsyrKMnwzp6yY0pQoh6mVwsvv32242yrnNaWhrz5s1jxYoVjB07lkOHDtGtWzdTwzGKlZUVPj51J3RWFIUlS5bw7LPPcssttwCwYsUKvL29Wb16NY888giFhYV89tlnfPnll4waNQqomRsyMDCQzZs3M3bsWGJjY/ntt9/Ys2cP/fv3B+CTTz5h4MCBxMXF0bFjxyb5XKKGl5Mtn9zbh+8OpPDSTyc4kJjPuHd28sz4TvxrQLCMqxVtSklFFbvO5LAtLoutJ7PJ0JbX2h/u7cjwTl4M7+hF72BX6T0UQlyWycXi1a7rXFhYyIIFC3jvvffo0aMHv//+O0OGDLmqNi/n9OnT+Pn5oVar6d+/PwsWLKB9+/acPXuWjIwMxowZYzhWrVYTFRVFTEwMjzzyCAcOHECn09U6xs/Pj27duhETE8PYsWPZvXs3Go3GUCgCDBgwAI1GQ0xMTIPFYkVFBRUVFYbXWm3NZLY6nQ6dTlfvOVfjQptN0bY5uDnSh37BGv77wzH2ns3n+f8dZ+PxDBbc1BVfjW1Lh1fLtZ6L1uRayEVyfilbTmazJS6bfefy0VX/3X1oZ23BwPbuRIV7EBXugb+L3d8n6qvR6avrabH5XQt5uFZILsxDc+TB2LZNLhavZl3nhQsX8sYbb+Dj48OaNWvqvSzd2Pr378/KlSsJDw8nMzOTV155hUGDBnH8+HHDuEVvb+9a53h7e5OYmAhARkYGNjY2uLq61jnmwvkZGRn1LoPo5eVlOKY+r732Wp3xlACbNm0y+RK/KaKjo5usbXNwpzf4Kyp+SrRg15lcxi7ezuR2evp4KJhbJ+O1novWpDXlQq9AcjEcy7fgaL6K9NLa/2N7qBW6uNY8OjhXYW2RDjnpHM6Bwy0Us7FaUx6udZIL89CUeSgtLTXquCua+6CgoIDvv/+e+Ph4/vOf/+Dm5sbBgwfx9vbG39+/wfOefvpp7Ozs6NChAytWrGDFihX1HvfDDz9cSVj1GjdunOF5REQEAwcOJDQ0lBUrVjBgwACg7lKGiqJc9tLlP4+p7/jLtTN37lxmzZpleK3VagkMDGTMmDE4Ozf+Xb06nY7o6GhGjx5dZ/jAteZGYFp2CXN+OMqRFC2rzliSZePFSxO74O5g09LhtalcmLvWkouyympiEnLZGpfNlpPZZBf/fXOKpYWK3kEujOjkyYiOnoS427e64RetJQ9tgeTCPDRHHi5c0bwck4vFI0eOMGrUKDQaDefOnePhhx/Gzc2NdevWkZiYyMqVKxs89957723xLzAHBwciIiI4ffq04ZJ6RkYGvr6+hmOysrIMvY0+Pj5UVlaSn59fq3cxKyuLQYMGGY7JzMys817Z2dl1ei0vplarUavrDii3trZu0l/Qpm7fXHTyc+GHxwbz4bZ43vn9NJtOZHEwqYAF5+dqNAdtJRetgTnmIruogi0nM4k+kcWuM9mU6/5eBMFRbUVUR09Gd/ZmWEdPXOxb/o+gxmCOeWirJBfmoSnzYGy7JheLs2bN4r777mPhwoWGu4WhpgdvypQplzx3+fLlpr5do6uoqCA2NpYhQ4bQrl07fHx8iI6OpmfPngBUVlayfft23njjDQB69+6NtbU10dHR3H777QCkp6dz7NgxFi5cCMDAgQMpLCzkzz//pF+/fgDs3buXwsJCQ0EpWoaVpQUzRoYxvJMXT317mLjMIqZ9eYDJvQKYN7ELzrbyRSjMh6IonM4qJvpEJptjMzmUXMDFs4n5u9gxqrMXo7p407+du0xEL4RoFiYXi/v27eOjjz6qs93f3/+S4/Mu9vvvvzNy5Mh6973//vv83//9n6lhNWj27NlMmDCBoKAgsrKyeOWVV9BqtUydOhWVSsXMmTNZsGABYWFhhIWFsWDBAuzt7Q2Fr0aj4cEHH+Spp57C3d0dNzc3Zs+eTUREhOHu6M6dO3P99dfz8MMPG/7bTJs2jRtvvFHuhDYT3fw1rJ8xmEXRp/h4RwJrD6awOz6Ht26LZFAHj5YOT7Rhumo9+87mER1bUyD+c93l7gEaRnX2ZlRnbzr7OrX41RkhRNtjcrFoa2tb7zXuuLg4PD09jWpj8uTJREdH07dv31rblyxZwgsvvNCoxWJKSgp33XUXOTk5eHp6MmDAAPbs2UNwcDAAc+bMoaysjOnTpxsm5d60aVOtXtPFixdjZWXF7bffbpiUe/ny5bXma/zqq694/PHHDXdNT5w4kffff7/RPoe4emorS+aO68yozt489e1hkvJKmfLpXu4bFMJ/r++EnY3l5RsRohEUlunYfiqbzScy2RqXRVH536tW2VhZcF0HD0Z19mZkZy+8nc3rTn4hRNtjcrE4adIkXnrpJb799lug5saOpKQknn76aSZPnmxUG4sXL2b8+PFs376dLl26APDWW2/x8ssv88svv5ga0iV9/fXXl9yvUql48cUXefHFFxs8xtbWlvfee4/33nuvwWPc3NxYtWrVlYYpmlHfEDd+fWIICzbE8tXeJJbHnGPHqWzeuj2SXkGul29AiCuQnFfK5vO9h3sT8qi6aHZsdwcbRnSqubw8JMwDextZd1kIYT5M/kZ66623GD9+PF5eXpSVlREVFUVGRgYDBw7k1VdfNaqN+++/n9zcXMaMGcOuXbv45ptvWLBgAb/++quM8RPNwkFtxavnb3SZ8/1hEnJKuPXDGB4bFsoTI8NlLJi4anq9wuGUgpoC8UQWcZlFtfZ38HJkVGdvRnfxokegqyxRKYQwWyYXi87OzuzatYstW7Zw8OBB9Ho9vXr1MozfM9bs2bPJzc2lT58+VFdXs2nTplqTWgvRHKLCPdk0M4p564/x46E0lm6NZ8vJbBbdHkln38afvkhc28oqq/njTM75HsQscor/nnTf0kJF3xBXw/hDWY5SCNFaXPG1jhEjRjBixAijj3/33XfrbPP19cXe3p6hQ4eyd+9e9u7dC8Djjz9+pWEJYTKNvTVL7uzJmK4+PLvuKLHpWia+v4tZozsybWh76fERl5RVVM6W2Cw2x2ay60xOm5jeRgjRthhdLJaVlfH7779z4403AjUTSl+8VJ2lpSUvv/wytrb1D8ZevHhxvdstLS35448/+OOPP4CaMYRSLIqWMD7Clz4hrjzzw1E2x2bxxm8n2Rybydu3RUovkDBQFIVTmcVsjs0k+kTN9DYXk+lthBDXGqOLxZUrV/Lzzz8bisX333+frl27YmdXs87oyZMn8fPz48knn6z3/LNnzzZCuEI0LS8nWz65tw/fHUjhpZ9OcCAxn3Hv7OSZ8Z3414Bgmbakjaqs0vPn2Tw2x2by+8m609tEXpjepos3nXxkehshxLXF6GLxq6++qlMIrl69mvbt2wOwatUqli5d2mCxKERroVKpuL1PIINC3Zn93WH2JOTx/P+Os+lEJgtv7Y6vxq6lQxTNIK+kkq0ns/j9ZCY7TuVQXCHT2wgh2iaji8VTp04RHh5ueG1ra4uFxd+XV/r168e///3vBs9//fXXmTFjBg4Ol7+ct3fvXnJycrjhhhuMDU+IRhfgas/qhwawYvc5Xv/1JDtP5zBm8Q7mT+zKzT39pffoGlNzebmI32Oz+D02k4NJ+Vw0uw0ejmpGdPJkZGeZ3kYI0bYY/W1XWFiIldXfh2dnZ9far9fra41h/KcTJ04QHBzMbbfdxsSJE+nTp49hEu+qqipOnDjBrl27WLVqFenp6ZdcY1qI5mJhoeL+we0YEubJU98d5nByAbO+Pcym45m8enM33B3rru0tWo/KKj0x8bmsPWvBm4t3kZJf+/JyZ19nRnX2YkQnLyIDXLCQm52EEG2Q0cViQEAAx44da3D5uiNHjhAQENDg+StXruTIkSMsXbqUu+++m8LCQiwtLVGr1ZSWlgLQs2dPpk2bxtSpU1Gr5R9hYT46eDmy9tGBfLgtnnd+P81vxzPYn5jHgvNzNYrW48Ll5S0ns9hxKpuiiirAAijDxsqCQaHujOzkxYjO3vi7yJADIYQwulgcP348L7zwAjfccEOdO57LysqYP3/+ZS8bd+/enY8++ohly5Zx5MgRzp07R1lZGR4eHvTo0QMPD1mjV5gvK0sLZowMY3gnL5769jBxmUVM+/IAk3sFMG9iF5xtrVs6RFEPvV7hSGoh2+Ky2BaXzeGUApRal5dtCLUrZ+qoXkR18sZBLZeXhRDiYkZ/Kz7zzDN8++23dOzYkf/7v/8jPDwclUrFyZMnef/996mqquKZZ54xqi2VSkVkZCSRkZFXHLgQLaWbv4b1MwazKPoUH+9IYO3BFHbH5/DWbZEM6iB/8JiDvJJKdpzKZltcFjtO55BXUllr/8WXl7t4O/Dbb78yuosX1tZSKAohxD8Z/c3o7e1NTEwMjz32GE8//TTK+T/NVSoVo0eP5oMPPsDb27vJAhXCnKitLJk7rjOjOnvz1LeHScorZcqne7lvUAj/vb4TdjaWLR1im1KtVziSUsC2uGy2ncrmyD96D53UVgzu4MGwjp5EdfSsdUe7TqdrgYiFEKL1MOnP6Hbt2vHbb7+Rl5fHmTNnAOjQoQNubm5NEpwQ5q5viBu/PjGEBRti+WpvEstjzrHjVDZv3R5JryDXlg7vmnah93BrXBY76+k97OTjxLCOXgzr6EnvYFesLWVybCGEuBJXdM3Fzc2Nfv36NXYsQrRKDmorXj1/o8uc7w+TkFPCrR/G8NiwUJ4YGS4reDSScl01+8/ls+tMDrvOZHM8TVun9/C6sPO9h+Fe+Ghk7kMhhGgMMkBHiEYSFe7JpplRzFt/jB8PpbF0azxbTmaz6PZIOvs6t3R4rY5erxCboWXX6Rx2ncnhz7N5VFTpax3T2deZYR09GRbuSS/pPRRCiCYhxaIQjUhjb82SO3sypqsPz647Smy6lonv72LW6I5MG9oeS5mn75JS8kuJOZPLzjM5xJzJIfcfl5a9nNRcF+bBkDAPBnfwwMtJeg+FEKKpSbEoRBMYH+FLnxBXnvnhKJtjs3jjt5Nsjs3k7dsiCfG4/CpGbYGiKKTkl7EnIZc9CXnsPZtbZ1JsextLBrR3Z3CHmgIxzMtRVs4RQohmJsWiEE3Ey8mWT+7tw3cHUnjppxMcSMxn3Ds7eWZ8J+7o7dfS4TU7RVFIzrtQHOay92weqQW1i0NLCxUR/hqGhHlwXQcPega5yphPIYRoYVIsCtGEVCoVt/cJZFCoO//57gi7E3J5/n/H+e1YBmM0LR1d09JV64lN13IwMZ8DSQXsP5dHemF5rWOsLFR0D9AwoL07/du70zvYFUeZFFsIIcyKfCsL0QwCXO356qH+rNh9jtd/Pckf8bkctLTEvl0at/YJuiYureaVVJ4vDPM5kJjPkZQCynW1b0ixtlQRGeByvjh0o3ewK/Y28jUkhBDmTL6lhWgmFhYq7h/cjiFhnsz69i+OpGj5z9pj/H4yh1dv7oa7Y+tZD71cV01supajqYUcSi7gr6QCzuaU1DlOY2dNzyAXege50ivYlV5BrjJhuRBCtDJSLArRzDp4OfLNQ/146rONbEq14rfjGexPzGPB+bkazU1FVTUn04s4mlrI0ZRCjqQWciqziGq9UufYMC9HegW50jvYlV7BLrT3cMRC7gAXQohWTYpFIVqAlaUFYwMUpt3Yn//+cJy4zCKmfXmAyb0CmDexC8621i0SV05xBXEZRZzMKCIuQ8uJdC1xGUXoqusWhh6ONkT4a4gIcKFXkAs9A13R2LdM3EIIIZqOFItCtKCufs6snzGYRdGn+HhHAmsPprA7Poe3botkUAePJnlPRVHIL9VxNqeE+KzimsIws6YozCmurPccV3trIgJc6O6vISJAQ/cADT7OttfEWEshhBCXJsWiEC1MbWXJ3HGdGdXZm6e+PUxSXilTPt3LfYNC+O/1na5ojJ+iKOSWVJKaX0ZiXilns0s4l1tCQk4J53JKKCzT1XueSgXBbvZ09HGio48znX2ciAjQ4O9iJ4WhEEK0UVIsCmEm+oa48esTQ1iwIZav9iaxPOYcO05l89btkfQKcjUcV1WtJ6+kkuziCnKKK8ksLCe1oIy0gjLSCstIK6h5XfmPpfH+yVdjSzsPBzr6ONHJx4lOPs6EeTvK3clCCCFqkX8VGtkHH3zAm2++SXp6Ol27dmXJkiUMGTKkpcMSrYSD2opXz9/oMuf7wyTklHDrhzF089dQVllNTnEF+aX19wr+k0oFno5qgtzsaefhQIiHA+3P/wxxd5C7koUQQhhFisVG9M033zBz5kw++OADBg8ezEcffcS4ceM4ceIEQUFBLR2eaEWiwj3ZNDOKeeuP8eOhNI6kFNbab6ECNwcbPBzVeDvb4udih79Lzc+a53Z4O9vK6idCCCGumhSLjWjRokU8+OCDPPTQQwAsWbKEjRs38uGHH/Laa6+1cHSitdHYW7Pkzp48eF17EnKK8XBU4+Goxt3RBld7GyxlShohhBDNQIrFRlJZWcmBAwd4+umna20fM2YMMTEx9Z5TUVFBRUWF4bVWqwVAp9Oh0xl3qdEUF9psiraFaUzJRSdvezp529fapq+uQl/dJKG1OfJ7YR4kD+ZDcmEemiMPxrYtxWIjycnJobq6Gm9v71rbvb29ycjIqPec1157jfnz59fZ/uOPP2Jvb1/PGY3jf//7X5O1LUwjuTAfkgvzIHkwH5IL89CUeSgtLQVqZtC4FCkWG9k/pxdRFKXBKUfmzp3LrFmzDK9TU1Pp0qWL4TK2EEIIIURTKyoqQqPRNLhfisVG4uHhgaWlZZ1exKysrDq9jReo1WrU6r/XA3Z0dCQ5ORknJ6cmmdNOq9USGBhIcnIyzs7Ojd6+MJ7kwnxILsyD5MF8SC7MQ3PkQVEUioqK8PPzu+RxUiw2EhsbG3r37k10dDQ333yzYXt0dDSTJk0yqg0LCwsCAgKaKkQDZ2dn+QIwE5IL8yG5MA+SB/MhuTAPTZ2HS/UoXiDFYiOaNWsW99xzD3369GHgwIF8/PHHJCUl8eijj7Z0aEIIIYQQV0SKxUZ0xx13kJuby0svvUR6ejrdunVjw4YNBAcHt3RoQgghhBBXRIrFRjZ9+nSmT5/e0mHUS61WM2/evFrjJEXLkFyYD8mFeZA8mA/JhXkwpzyolMvdLy2EEEIIIdosWQtMCCGEEEI0SIpFIYQQQgjRICkWhRBCCCFEg6RYFEIIIYQQDZJiUQghhBBCNEiKRSGEEEII0SApFoUQQgghRIOkWBRCCCGEEA2SFVzMiF6vJy0tDScnJ1QqVUuHI4QQQohrmKIoFBUV4efnh4VFw/2HUiyakbS0NAIDA1s6DCGEEEK0IcnJyQQEBDS4X4pFM+Lk5ATUJM3Z2bnR29fpdGzatIkxY8ZgbW3d6O0L40kuzIfkwjxIHsyH5MI8NEcetFotgYGBhvqjIVIsmpELl56dnZ2brFi0t7fH2dlZvgBamOTCfEguzIPkwXxILsyDTqfD1s4eJycnbGxsmvS9Ljf0TYpFIYQQQlwVvV6hslpPRZWecl01JRVVlFZWU1xRRWllFbpqBUWpGSOnV0Dh/E+lZrv+Hz//3n9hm4ICWFlYYGN1/mFpgfr8cysLFbpqhYqqaiqq9FRUVVOu01NZpadaX3Puxe8FnN/G+ec1+6r1ClXVenQXflYrVOn1VFUr6KoV9IqCSgUWKhUW53+qLnpuoYJqRUFXpaA7346uSo+uWk9ldc1PXXXNvsoqPVV6peY99XqqqxV051/rqvSUV1Wjq7Zi6Igq3Ju4WLwcKRaFEEKINkCvVyivqqa0sprSimpKdTUFXVllNUXlOgpKdRSW6cgrruBoggUbvzlMUUU15bpqKqtqCsHK80VO5T+eV+mVlv5416zyKn1LhyDFohBCCNEa6fUKhWU6sooqyC6qILu4nCzthecVNc+LK8gvqawpCnXVJrRuAZmZVxSXpYUKextLHGyscFBbYm9jhbWl6nwvHIaeOBUqLCxqfl683UKlQkXN65pevL+P0VXX9GDq/lGs6vT6mp5Ga0vUVhbnHzXPLSwuvF9N25xvD+D8S8NzSwsLrC1VWF34Weu5BZYqlaHX09Abqv/7tV5RsFCpsLGqOcfa0gIrSwtszj+/8LCxqnltaXH+GIua97G0qHlPa0sLLNGzc9sWPBxatlcRpFgUQgghWpyiKOSWVJJRWE5aQRmZ2nIKy3QUVVRRXF5FSUUVReVVFJTpyC+tNPQCVl9hj56ttQX2NlbY21hib2OJk601GjtrXOyscVRbkpVylj7du+DqYIudjSU2lhdd/r3oErDayrLOdmtLlUz/1gh0Oh2O1mBh0fL/LaVYFEIIIRpZRVU1WdoKcoorKKmoprSyijJdteF5QamOtIIy0grLSC8sJ72wnMorvNzoYm+Nl5MaTyc1no41P72cbGteO6lxc7DBwcYKu/OFoZ215SULEJ1Ox4YNCYwfGCw3uAhAikUhhBDCKBVV1RSe79HLLakkq6iCLG052UUVNc+Lai4DZxVVUFimM7l9lQo8HNX4amzxcbbFzcEGR7UVDmornGxrfrrYWeNib4OrgzWu9ja42FujtrJsgk8rxN+kWBRCCNEmKYpCfqmOlPxSUvLLSMkvJTW/pqevqLyKksqaS8DFFVVoy3WU60zr+bOxtMDTSY2T7cW9ejWXfjV21vi62OKnscPPxQ5fjS3ezrbYWMkqvML8SLEohBDimlCuqyZTW462rIqich3ach1F54u9C0VfUUUVmYXlJJ8vEEsrTbnpo6b3z9nWGjcHm/OXe2su+Xo5132usbOWsXvimiDFohBCiFajWq+Qkl/Kmaxiw+NsTglJeaVkFVVcUZteTmoCXO0IcLXH39UOP40tznbWNZd+bWou/2rsrGu2qa3M4oYDIZqTFItCCCHMgk4PiXml5JRUkVFYTob2whjAcsP0MGkFZVRc4kYQO+uaS7xOtjXj/Bxta54721oZxv95OdmeLw5rLgHbWsuYPyEuRYrFRhISEkJiYmKd7dOnT2fp0qUtEJEQQpivwjIdJ9K0HE8r5FhqIUdTC0nItkTZu+uy59pYWdDew4Ewbyc6eDrS3tOBYHd7gtzs5dKvEE1AisVGsm/fPqqr/x77cuzYMUaPHs1tt93WglEJIUTLUBQFbVkVWUXlZJ7vHUzILuFkRhEnM7Sk5JfVc5YKW2sLfDV2+Djb4qO5MP7P9vx4QDW+Gjv8Xe2wlEvBQjQbKRYbiaenZ63Xr7/+OqGhoURFRbVQREII0bQURSEpr5TjaVqOpRYSl1FEZlE5ucWV5BZXUll96buH/V3s6ObvTDc/DZ18HEg/sY87J43DpoXXwRVC1GZUsbh+/XqjG5w4ceIVB3OtqKysZNWqVcyaNeuSl0MqKiqoqPh7QLZWqwVqJkTV6Uyfo+tyLrTZFG0L00guzIfkwjgVVXoSc0uITS/ieHoRJ9K1nEgvoqi86pLnaeysDHcJB7jaEu7tREdvR8K9HXG1/7so1Ol0RJ+BqqoquYzcwuR3wjw0Rx6MbVulKMpl1wqysKg975NKpeLi0y7+xb74Umxb9e233zJlyhSSkpLw8/Nr8LgXX3yR+fPn19m+evVq7O3tmzJEIYSoQ1GgoBIyy1RklUF2+d8/8ypAoW4RZ6lS8LOHAAcFfwcFNzU4Wis4WYOTNVjLtIFCmK3S0lKmTJlCYWEhzs7ODR5nVLF4sc2bN/Pf//6XBQsWMHDgQFQqFTExMTz33HMsWLCA0aNHX3Xwrd3YsWOxsbHhp59+uuRx9fUsBgYGkpOTc8mkXSmdTkd0dDSjR4+WJZxamOTCfLTlXJRUVLE/MZ/dCXkcTCrgdFYJxRUN9xQ6qC3p5O1EFz9nuvg60dXXmQ5eDlhbXn1F2JbzYG4kF+ahOfKg1Wrx8PC4bLFo8pjFmTNnsmzZMq677jrDtrFjx2Jvb8+0adOIjY29soivEYmJiWzevJkffvjhsseq1WrUanWd7dbW1k36C9rU7QvjSS7MR1vIRbVe4UhKATtO5bDzdDaHkguo0tfuL7C0UBHibk+opyPtPB1o7+FAOw9HQjzs8XRUN/kl4raQh9ZCcmEemjIPxrZrcrEYHx+PRqOps12j0XDu3DlTm7vmfPHFF3h5eXHDDTe0dChCiDZMW64jo7Cc5LxSTqRpOZpayN6zeXXWLA50s2NQew8GhLrRxVdDOw8HWXJOCFGLycVi3759mTlzJqtWrcLX1xeAjIwMnnrqKfr169foAbYmer2eL774gqlTp2JlJTeaCyGaTmWVnoScYk6mFxGXWUR6QRmZ2goyi2omsm7ocrKTrRXXdfBgaLgn13XwINBNxkcLIS7N5Irm888/5+abbyY4OJigoCAAkpKSCA8P58cff2zs+FqVzZs3k5SUxAMPPNDSoQghrjFpBWUcTMrnYGIBfyXnczxVe9mpaTR21vhqbOns60xXP2d6BrkQGeCCVSOMMRRCtB0mF4sdOnTgyJEjREdHc/LkSRRFoUuXLowaNarNT3cwZswYTLxfSAghDBRFIUNbzpmsYuKzionPLiE+u5jTWcVk17PusZPaik6+TnT0cSLIzb5m8urzk1j7amxxUMsVDiHE1buibxKVSsWYMWMYOnQoanXTD3gWQohrUVG5jj/P5rE7PpeDSfmcziymqIHLx5YWKjr7OtEryJVeQa70DHIhyM1evn+FEE3O5GJRr9fz6quvsmzZMjIzMzl16hTt27fn+eefJyQkhAcffPCybeh0OjIyMigtLcXT0xM3N7crCl4IIVqbsspqfj+ZyfpDaWyLy65zKfnC3cgdvBwJ9ax5tPd0oKOPE/Y20lMohGh+Jn/zvPLKK6xYsYKFCxfy8MMPG7ZHRESwePHiBovF4uJivvrqK9asWcOff/5Za37BgIAAxowZw7Rp0+jbt+8VfAwhhDBfVdV6/ojP5X9/pbLxeAYllX8vXhDsbs+gUHf6t3Ons6+z3I0shDA7JheLK1eu5OOPP2bkyJE8+uijhu3du3fn5MmT9Z6zePFiXn31VUJCQpg4cSJPP/00/v7+2NnZkZeXx7Fjx9i5cyejR49mwIABvPfee4SFhV35pxJCiBZUVK4jIbuEo6mF7E7IZXd8LnkllYb9/i52TOzhx8RIPzr5OMmlZCGEWTO5WExNTaVDhw51tuv1+gbXGIyJiWHr1q1ERETUu79fv3488MADLFu2jM8++4zt27dLsSiEMGtlldUcSSngaGohqQVlpBeUk15YRmpBOTnFdW9GcXOw4cbuvkzq4UevIFcpEIUQrYbJxWLXrl3ZuXMnwcHBtbZ/99139OzZs95zvvvuO6PaVqvVTJ8+3dSQhBCiSSmKQlJeKX8lFdRMX5OUT2x6EdX6hmc/8HRSE+blyID27gwKdScy0KVRlsUTQojmZnKxOG/ePO655x5SU1PR6/X88MMPxMXFsXLlSn7++eemiFEIIZpNRVU18VklxGVqOZlRRFxGEcdSC8kprqxzrI+zLT0CXQj2sMdPY4evxhY/FzsC3ezR2MkyaUKIa4PJxeKECRP45ptvWLBgASqVihdeeIFevXrx008/MXr06MueX15eznvvvcfWrVvJyspCr699J+DBgwdNDUkIIa6IoigcT9OyPV3F1u+PciKjiITskjrrJQPYWFrQ1d+ZnoGu9Ap2oVeQK34udi0QtRBCNK8rmodh7NixjB079ore8IEHHiA6Oppbb72Vfv36ybgdIUSzSy8sY3nMOf73VxoZ2nLAEkg37HeytaKTT81k1518nA0roNhaW7ZYzEII0VKuqFgsKCjg+++/JyEhgdmzZ+Pm5sbBgwfx9vbG39//kuf+8ssvbNiwgcGDB19RwEIIcaWOpRby6c4Efj6Sbug9tLexJMRex6ieYUQGudLZ1xlfja38ISuEEOeZXCweOXKEUaNGodFoOHfuHA899BBubm6sW7eOxMREVq5cecnz/f39cXJyuuKAhRDCFHq9wvZT2XyyM4GY+FzD9n7t3HhgcDuua+/C79EbGT8iFGtrGWcohBD/ZHKxOGvWLO677z4WLlxYq+gbN24cU6ZMuez5b7/9Nv/9739ZtmxZnTuqhRCiseSVVLL2QApr/kwiIacEqFkdZXyELw8PaUf3ABeABqf8EkIIUcPkYnHfvn189NFHdbb7+/uTkZFx2fP79OlDeXk57du3x97evs5f8nl5eaaGJIQQ5BRXEJuu5Viqlp2ns9l3Lg9ddc2lZke1FXf2DeT+69rhLzelCCGESUwuFm1tbdFqtXW2x8XF4enpednz77rrLlJTU1mwYAHe3t4yLkgIYTJdtZ7jaVr2nc1j79k8jqQUkFVUdyLsbv7OTOkXzMQefjiqZV1lIYS4EiZ/e06aNImXXnqJb7/9FgCVSkVSUhJPP/00kydPvuz5MTEx7N69m8jISNOjFUK0SWWV1fyVnM++s/n8eS6Xg4kFlOmqax2jUkGIuwOdfZ3oE+zG8E5etPNwaKGIhRDi2mFysfjWW28xfvx4vLy8KCsrIyoqioyMDAYOHMirr7562fM7derE/7d373FRVWsDx3/DxeEiiIAwoKKQKDcVUVNEBUnRLnp8T1qaGmbp8Wih0MXMVMq8njKPWRqGnmNqpallb2paAkre7wpohvcL4gUBuTMz7x+8TE2AggIzwPP9fOZTs/baez8zS9gPa++1Vl5e3kMFK4So/0onxT6dlkXK9SwOX8zg5NVM3S3lUk0szenauildW9vTuVXJKGZr6T0UQohqV+XfrLa2tiQmJrJz506OHDmCRqMhICCAvn37Vmr/efPm8frrrzN79mzat29f5plFW1vbqoYkhKij8grVnLqWyfHLdzl1NZOU69mk3rxX7qTYKlsLurrb83jrpjzu7oCnU2NMTOQxFiGEqGkP/Wd4aGgooaGhVd5vwIABADzxxBN65VqtFoVCgVqtLm83IUQ9odFo+SkpjY1Hr5Lw200KizVl6thamOHlYou3yob2Lezo5m5Pi6aW8oyzEEIYwEMli7/88gsff/wxKSkpKBQKvLy8mDx5cqV6F+Pi4h7mlEKIOk6r1bLr7C0WbDtN0rU/Bsk52Sjp2NKODs2b4ONqi5eLLa4yKbYQQhiNKieLS5YsITIykiFDhjBp0iQA9u3bx1NPPcXChQt59dVX77t/cHDww0UqhKizjlzKYMG20+w7VzI1VmOlGS8GtmJgR1e8VDaSGAohhBGrcrI4d+5cPv74Y72kMCIigqCgIGbPnv3AZBEgIyOD2NhYXc+kt7c3L730Evb29lUNRwhhxH67kc2HP51he/INABqZmfBi91ZM6NMGe+tGBo5OCCFEZZhUdYesrCzdc4d/FhYWVu78i3+VkJBA69atWbx4MRkZGdy5c4fFixfj7u5OQkJCVcMxKlevXmXkyJE4ODhgZWWFv78/hw8fNnRYQtS6szeyifzmGAMW7WJ78g1MFPBclxbEvRHCu8/4SKIohBB1SJV7FgcNGsSmTZt488039cq///57Bg4c+MD9J06cyPPPP8/SpUsxNTUFQK1WM2HCBCZOnMipU6eqGpJRyMjIICgoiD59+rB161acnJxITU3Fzs7O0KEJUeO0Wi3XMvPZ8/stvj92jV9Tb6H9/wHNA3xVvNG/LW2cZE14IYSoi6qcLHp7ezN79mzi4+MJDAwESp5Z/PXXX3n99ddZvHixrm5ERESZ/VNTU9mwYYMuUQQwNTUlKiqKVatWPcxnMArz58+nZcuWrFy5UlfWunVrwwUkRA3KL1Jz4komRy9lcPTSXY5cyiizgkp/X2de7eNJ+xZNDBSlEEKI6lDlZDE2NpamTZuSnJxMcnKyrtzOzo7Y2Fjde4VCUW6yGBAQQEpKCu3atdMrT0lJwd/fv6rhGI3NmzfTv39/hg4dSkJCAs2bN2fChAmMHTu2wn0KCgooKPjjAlt6G7+oqIiioqJqj7H0mDVxbFE1da0tcgqKOXLpLgcuZHDwQgYnypkk29REgbfKhr7eTgzqqKJlUyvA+D9jXWuL+krawXhIWxiH2miHyh5bodVqy85+W4O++eYb3nrrLV577TW6d+8OlPRMfvrpp8ybNw9vb29d3Q4dOtRmaI/EwsICgKioKIYOHcqBAweYPHkyn3/+OS+++GK5+0RHR/Pee++VKV+7di1WVlY1Gq8QFSnWQEYB3MxXkJql4PcsBZfugQb9Ecu25lpa22hp3bjkvy2toZFpBQcVQghhdHJzc3nhhRfIzMy876Ioj5wsFhcXk5+fT+PGjStV38Tk/mNqFApFnZygu1GjRnTp0oU9e/boyiIiIjh48CB79+4td5/yehZbtmzJrVu3amQlm6KiInbs2EG/fv3KrJwjapeh20Kr1ZJ6M4fTadn8fjOHKxl5XL2bx5WMPG5kF1Deb4XmdhY8/v/L63Vzb0rLejJJtqHbQpSQdjAe0hbGoTbaISsrC0dHxwcmi5W+Db1lyxZu377NqFGjdGWzZ89m1qxZFBcXExoayjfffEPTpk3ve5zz589X9pR1iouLCz4+Pnpl3t7ebNiwocJ9lEolSqWyTLm5uXmN/oDW9PFF5dV2W9zIymflrxf48eQ1Lt+peI12C3MTWjS1omMLO7p72NPdw4GW9vW7t1t+LoyDtIPxkLYwDjXZDpU9bqWTxQ8//JBnn31W937Pnj3MmDGD999/H29vb6ZNm8asWbNYuHBhhccoKioiOjqa6dOn4+HhUdlT1wlBQUGcOXNGr+y3336jVatWBopIiD/cKyjmo+1nWLP/km55PQtzE3xdm9DW2YZWDla0aGpJi6Yl/3WwblQveg2FEEI8ukoni6dOneKjjz7Svf/222/p168f06ZNA0qe2Zs0adJ9k0Vzc3M2bdrE9OnTHyFk4xQZGUmPHj2YM2cOzz33HAcOHCAmJoaYmBhDhyYauMSzt5iy4QRX75b0JHZt3ZSXgtwJadcMq0YPvTy8EEKIBqLSk3JnZ2fj4OCge5+YmEhoaKjuva+vL9euXXvgcf7nf/6H7777rmpR1gFdu3Zl06ZNfPXVV/j5+TFr1iwWLVrEiBEjDB2aaKCy84uYuvEEI2P3c/VuHi3tLVk15nHW/SOQp9q7SKIohBCiUip9tXB1dSUlJQU3Nzfu3bvH8ePH+fjjj3Xbb9++XakRvG3atGHWrFns2bOHzp07Y21trbe9vOl26opnnnmGZ555xtBhCEHCbzeZuuEE1zLzAQgPbMVbA7ywVkqCKIQQomoqfeUYMmQIkydP5p133mHLli2oVCrd1DcAhw4dKjN3Ynm++OIL7OzsOHz4cJml8Cqam1EIUTk3swtYsO006w9fAcDN3or5z3Yg8DGHB+wphBBClK/SyeLMmTO5du0aERERqFQqVq9erbcKy1dffVWp5f7q62hoIQzp1r0Cvtx7kS92nyOnUI1CAeGBrXlrQDu53SyEEOKRVPoqYmVlxZdfflnh9ri4uGoJSAhROVn5RcSdTmd78g12JN2gUF0yyrlDiybMeMaHLq3tDRyhEEKI+qDKXQ6hoaFs3LgROzs7vfKsrCwGDx7Mzp07y+wzb948IiIiKvVM4/79+7l16xZPP/10VUMTot67npnHz8k32J58g33nbustueff0o5XernzlJ8LJiYy7Y0QQojqUeVkMT4+nsLCwjLl+fn57N69u9x9kpOTcXNzY+jQoQwaNIguXbrQrFkzoGQFmOTkZBITE1m9ejXXr19n1apVVQ1LiHpJq9Vy5kY2O5JKEsSTVzP1trdxakyYjzNP+rnQvkUTA0UphBCiPqt0snjixAnd/ycnJ5OWlqZ7r1ar2bZtG82bNy9331WrVnHixAk+/fRTRowYQWZmJqampiiVSnJzcwHo1KkT48aNIzw8vNxVTYSoT4rUGjIL4XpmPhaN1CXLW2q0FKk13M4pJDX9HocuZrD77E2uZPyx0opCAZ3dmtLPx5l+Ps54NKvcMptCCCHEw6p0sujv749CoUChUOjNr1jK0tKSTz75pML9O3TowOeff86yZcs4ceIEFy5cIC8vD0dHR/z9/XF0dHy4TyBEHVCs1hB/5iY/nLjGwfN3uJ6Vj1ZrBod3PXBfpZkJvTwd6efjTKiXM81s5I8pIYQQtafSyeL58+fRarV4eHhw4MAB3W1kgEaNGuHk5KQ3OroiCoWCjh070rFjx4eLWIg6JuG3m8z632R+T7+nV65Ai5mpCWqNFo0WzEwUNDIzwcbCDHdHa3xcmtDT04HuHg4yolkIIYTBVPoKVLrGsUajqbFghKhPcgqKmbbpJN8dK1nZyM7KnCEBLQj1dsLD3oK9Cb/wzNP9a2yBeCGEEKI6PFR3RWpqKosWLSIlJQWFQoG3tzeTJk3iscceq+74hKiTUq5nMXHtEc7dzMHURMHoHq2JeMKTJpYliWFRUREyYFkIIURdUOm1oUv99NNP+Pj4cODAATp06ICfnx/79+/H19eXHTt21ESMQtQp6w5dZvCnv3LuZg4qWwu+Hted6c/46BJFIYQQoi6pcs/i22+/TWRkJPPmzStTPmXKFPr161dtwQlRl+QWFhO9OYl1h0qW2uvdthkfP9cRh8YyIEUIIUTdVeVkMSUlhXXr1pUpHzNmDIsWLaqOmISoc+JOpzP9+1NcycjDRAFR/doyIaSNTI4thBCizqtystisWTOOHTuGp6enXvmxY8dwcnKqtsCEMHYajZZdZ2/yWVwqBy7cAaC5nSX/GtKBHm1kKighhBD1Q5WTxbFjxzJu3DjOnTtHjx49UCgUJCYmMn/+fF5//fWaiFEIo5J68x4bj1xh05GrXMvMB6CRqQnhPVoxuW9brJUyzY0QQoj6o8pXtenTp2NjY8NHH33E1KlTAXB1dSU6OpqIiIhqD1CIR6HWaNl5Op2fktJIupZFbmExTjZKOrk1JaRdM7q2tsfc9P7jvDQaLcev3GVH8g12JN/g7J/mS7S1MOPZzi0Y19sDlyaWNf1xhBBCiFpX5WRRoVAQGRlJZGQk2dnZANjY2ABw9erVCpf8E6K27T57k5mbkzh3M0ev/OLtXA5eyCBm1zlsLcx4wtuZXp6OtHFqjK2FOYVqDVfv5nH2RjaHLmRw6GIGd3L+WA/dzERBL09HhnRuyRPeTliYP3gyeiGEEKKueqT7ZaVJYlpaGrNnz+aLL74gLy/vAXsJUbPuFRQz47tTbDx6FYAmluYM6dyCQA8HbC3NuZKRy6+/3yb+TDq3cwrZdPQqm/6/bkUaK80IbteMMB9nQto5yTQ4QgghGoxKJ4t3795l4sSJbN++HXNzc95++21effVVoqOj+fDDD/H19WXFihU1GasQD/R7ejb/+PIwqTdzMFFAeI/WRPVri43FH8nd4+72/D2gBWqNliOXMtielMbxK5mcu5lDfpEaM1MFKlsL3B2t6djSjq6t7WnfvAmNzKo8LakQQghR51U6WXznnXfYtWsX4eHhbNu2jcjISLZt20Z+fj5bt24lODi4JuMU4oG2nLzOm+uPk1OoxtlWyacvBNCltX2F9U1NFHRtbU/X+9QRQgghGrpKJ4s//vgjK1eupG/fvkyYMIE2bdrQtm1bmVtRGJxao+XD7WdYGp8KQHcPez4ZHkAzG5kMWwghhHhUlU4Wr127ho+PDwAeHh5YWFjwyiuv1FhgdU10dDTvvfeeXpmzszNpaWkGiqj2FKs1nLqWxd7U2+w9d5sjFzPIL1LjamdJSLtmjAlyp7WjdY2cOzOviElfHyX+zE0A/tHbgzf7t8PsASOchRBCCFE5lU4WNRoN5uZ/PPdlamqKtXXNJAB1la+vLz///LPuvalp/Rwle/lOLkcuZXDiSiYnrtzl1NUs8orUZepdupPLqr0XWb3vIi/3dOf1sHbVOnL46KUMIr85xoXbuViYm7BgSEcGdXSttuMLIYQQogrJolarZfTo0SiVJbf28vPzGT9+fJmEcePGjdUbYR1iZmaGSqUydBgV0mq1HLutYIBG+1D7bjmZxrKEVE5ezSyz3dbCjG4eDgR6ONDdw4Gm1uakXM9i9b5L7DydzvLd5/k5JZ2PnutIgFvTR/ocmXlFfBb3O8t3n0OjLVk15fNRnfFr3uSRjiuEEEKIsiqdLIaHh+u9HzlyZLUHU9edPXsWV1dXlEol3bp1Y86cOXh4eFRYv6CggIKCAt37rKwsAIqKiigqKqr2+N7acJLvfjPFeudZJvVtW+n9jl6+y7xtv3Hk0l2gZGCIn6stHZrb0r55E9o3t8XD0brMOsi9HrOn12P2xJ25yfTNyZy/lcOQpXv4Z7AHE0M8HjgZ9l/lFhbz5b7LxOw+T1Z+MQCDOrgw/Wkv7KzMa+Q7qymlsdalmOsraQvjIO1gPKQtjENttENlj63QarVV72YSZWzdupXc3Fzatm3LjRs3+OCDDzh9+jRJSUk4ODiUu095zzkCrF27Fisrq2qP8UC6gjWppijQMs5Lg0/T+zd9eh5suWzC0dslSV0jEy2hrlp6qTQ0ruI0g7nFsPG8CQdvlRyrpbWWUZ5qnCux6EmBGhLTFOy8ZsK94pKEVGWpZaCbBj97+ecrhBBCPIzc3FxeeOEFMjMzsbW1rbCeJIs1JCcnh8cee4y33nqLqKiocuuU17PYsmVLbt26dd9Ge1hFRUW88vkv7LlhglUjU1aGdybAzU6vjkaj5eDFDDYcucrmE2moNVoUCvh7J1cmP9EGla3FI8Ww9VQaMzancDevCKWZCa+GePBSj1Yoy3mWMaegmDUHLvNF4gUyckv++mnZ1JKI0McY2MEF07/0ZNYlRUVF7Nixg379+uk9Cyxqn7SFcZB2MB7SFsahNtohKysLR0fHByaLj7SCi6iYtbU17du35+zZsxXWUSqVumdA/8zc3LzG/mE821qDonEzfk29zagVhxgd1Jpu7vZk5xdz+GIGcWfSuZLxxyo8oV5OvB7WFl/X6nkecFCnlnR7rBlvrD/O7rO3+Ojn31l35Cpje3nQz8cZB2slF27n8N3Rq6zed1F3u7mVgxWvhXoy2N+1Xo10rsm2FlUjbWEcpB2Mh7SFcajJdqjscSVZrCEFBQWkpKTQq1cvQ4eix8wElr7gT9S3p/g55QYxu84Rs+ucXp3GSjOebu/C8G5u+Le0q/YYnG0tWDXmcTYdvcr8bae5fCePGd8nMeP7pDJ13R2tebVPG/5Wz5JEIYQQoq6QZLGavPHGGwwcOBA3NzfS09P54IMPyMrKKjMwyBhYNjJl+Yud+SnpBj+cuMa5mznYKM3wbW5Ldw8Hens2w7JRzU77o1Ao+HtAC/r7qlh/6DIbjlwl+XoWao0WC3MTHnd3YEQ3N/p6O9fp281CCCFEXSfJYjW5cuUKw4cP59atWzRr1ozu3buzb98+WrVqZejQyqVQKBjgp2KAn2Gn+rFWmjE6yJ3RQe7kF6kpKNJgrTSVXkQhhBDCSEiyWE2+/vprQ4dQ51mYm1brpN1CCCGEeHSSLBqR0oHppfMtVreioiJyc3PJysqSh5YNTNrCeEhbGAdpB+MhbWEcaqMdSvONB02MI8miEcnOzgagZcuWBo5ECCGEEA1FdnY2TZpUPOuJzLNoRDQaDdeuXcPGxgaFovoHdZTO43j58uUamcdRVJ60hfGQtjAO0g7GQ9rCONRGO2i1WrKzs3F1dcXEpOKxAtKzaERMTExo0aJFjZ/H1tZWfgEYCWkL4yFtYRykHYyHtIVxqOl2uF+PYikZciqEEEIIISokyaIQQgghhKiQJIsNiFKpZObMmeUuMShql7SF8ZC2MA7SDsZD2sI4GFM7yAAXIYQQQghRIelZFEIIIYQQFZJkUQghhBBCVEiSRSGEEEIIUSFJFoUQQgghRIUkWWxAPvvsM9zd3bGwsKBz587s3r3b0CE1OHPnzqVr167Y2Njg5OTE4MGDOXPmjKHDavDmzp2LQqFg8uTJhg6lQbp69SojR47EwcEBKysr/P39OXz4sKHDalCKi4t59913cXd3x9LSEg8PD95//300Go2hQ6v3du3axcCBA3F1dUWhUPDdd9/pbddqtURHR+Pq6oqlpSUhISEkJSXVaoySLDYQ33zzDZMnT2batGkcPXqUXr168eSTT3Lp0iVDh9agJCQkMHHiRPbt28eOHTsoLi4mLCyMnJwcQ4fWYB08eJCYmBg6dOhg6FAapIyMDIKCgjA3N2fr1q0kJyfz0UcfYWdnZ+jQGpT58+ezbNkylixZQkpKCgsWLOBf//oXn3zyiaFDq/dycnLo2LEjS5YsKXf7ggULWLhwIUuWLOHgwYOoVCr69etHdnZ2rcUoU+c0EN26dSMgIIClS5fqyry9vRk8eDBz5841YGQN282bN3FyciIhIYHevXsbOpwG5969ewQEBPDZZ5/xwQcf4O/vz6JFiwwdVoPy9ttv8+uvv8qdDgN75plncHZ2JjY2Vlf27LPPYmVlxZdffmnAyBoWhULBpk2bGDx4MFDSq+jq6srkyZOZMmUKAAUFBTg7OzN//nz+8Y9/1Epc0rPYABQWFnL48GHCwsL0ysPCwtizZ4+BohIAmZmZANjb2xs4koZp4sSJPP300/Tt29fQoTRYmzdvpkuXLgwdOhQnJyc6derE8uXLDR1Wg9OzZ09++eUXfvvtNwCOHz9OYmIiTz31lIEja9jOnz9PWlqa3vVbqVQSHBxcq9dvs1o7kzCYW7duoVarcXZ21it3dnYmLS3NQFEJrVZLVFQUPXv2xM/Pz9DhNDhff/01R44c4eDBg4YOpUE7d+4cS5cuJSoqinfeeYcDBw4QERGBUqnkxRdfNHR4DcaUKVPIzMzEy8sLU1NT1Go1s2fPZvjw4YYOrUErvUaXd/2+ePFircUhyWIDolAo9N5rtdoyZaL2vPrqq5w4cYLExERDh9LgXL58mUmTJrF9+3YsLCwMHU6DptFo6NKlC3PmzAGgU6dOJCUlsXTpUkkWa9E333zD6tWrWbt2Lb6+vhw7dozJkyfj6upKeHi4ocNr8Ax9/ZZksQFwdHTE1NS0TC9ienp6mb9WRO147bXX2Lx5M7t27aJFixaGDqfBOXz4MOnp6XTu3FlXplar2bVrF0uWLKGgoABTU1MDRthwuLi44OPjo1fm7e3Nhg0bDBRRw/Tmm2/y9ttvM2zYMADat2/PxYsXmTt3riSLBqRSqYCSHkYXFxddeW1fv+WZxQagUaNGdO7cmR07duiV79ixgx49ehgoqoZJq9Xy6quvsnHjRnbu3Im7u7uhQ2qQnnjiCU6ePMmxY8d0ry5dujBixAiOHTsmiWItCgoKKjN91G+//UarVq0MFFHDlJubi4mJfkpgamoqU+cYmLu7OyqVSu/6XVhYSEJCQq1ev6VnsYGIiopi1KhRdOnShcDAQGJiYrh06RLjx483dGgNysSJE1m7di3ff/89NjY2ut7eJk2aYGlpaeDoGg4bG5syz4laW1vj4OAgz4/WssjISHr06MGcOXN47rnnOHDgADExMcTExBg6tAZl4MCBzJ49Gzc3N3x9fTl69CgLFy5kzJgxhg6t3rt37x6///677v358+c5duwY9vb2uLm5MXnyZObMmYOnpyeenp7MmTMHKysrXnjhhdoLUisajE8//VTbqlUrbaNGjbQBAQHahIQEQ4fU4ADlvlauXGno0Bq84OBg7aRJkwwdRoP0ww8/aP38/LRKpVLr5eWljYmJMXRIDU5WVpZ20qRJWjc3N62FhYXWw8NDO23aNG1BQYGhQ6v34uLiyr0uhIeHa7VarVaj0WhnzpypValUWqVSqe3du7f25MmTtRqjzLMohBBCCCEqJM8sCiGEEEKICkmyKIQQQgghKiTJohBCCCGEqJAki0IIIYQQokKSLAohhBBCiArJPItC1ENqtZqioiJDhyGEqCHm5uYyebyoNZIsClGPaLVa0tLSuHv3rqFDEULUMDs7O1QqVa2uESwaJkkWhahHShNFJycnrKys5CIiRD2k1WrJzc0lPT0dQG/NYCFqgiSLQtQTarValyg6ODgYOhwhRA0qXR40PT0dJycnuSUtapQMcBGinih9RtHKysrAkQghakPpz7o8nyxqmiSLQtQzcutZiIZBftZFbZFkUQghhBBCVEiSRSGEEPXC6NGjGTx4sKHDqDYhISFMnjzZ0GEIIcmiEMLw/nyRHz16NAqFosxrwIABZfabM2cOpqamzJs3r1Ln2bhxI/3798fR0RGFQsGxY8fK1AkJCSlz7mHDht33uMePH2f48OG0bNkSS0tLvL29+fe//11h/d9//x0bGxvs7OzKbEtISKBz585YWFjg4eHBsmXLHvi5/vydmZmZ4ebmxj//+U8yMjIAOH36NAqFgv379+vt161bN5RKJbm5ubqywsJCrKysiImJKbcd/vwaPXp0mViio6Px9/cvU3737l0UCgXx8fEAXLhwQRfv1atX9epev34dMzMzFAoFFy5ceODnL/Xvf/+b//znP5WuXxlqtZq5c+fi5eWFpaUl9vb2dO/enZUrV1brecqzceNGZs2aVePnEeJBJFkUQhidAQMGcP36db3XV199VabeypUreeutt1ixYkWljpuTk0NQUNADk8uxY8fqnfvzzz+/b/3Dhw/TrFkzVq9eTVJSEtOmTWPq1KksWbKkTN2ioiKGDx9Or169ymw7f/48Tz31FL169eLo0aO88847REREsGHDhgd+ttLv7MKFC3zxxRf88MMPTJgwAQAvLy9cXFyIi4vT1b937x5Hjx7FycmJPXv26Mr3799PXl4effr00fsOFi1ahK2trV7Z/RLiynJ1dWXVqlV6Zf/9739p3rx5lY/VpEmTchPwRxEdHc2iRYuYNWsWycnJxMXFMXbsWF0iXpPs7e2xsbGp8fMI8SCSLAohjI5SqUSlUum9mjZtqlcnISGBvLw83n//fXJycti1a9cDjztq1ChmzJhB375971vPyspK79xNmjS5b/0xY8awePFigoOD8fDwYOTIkbz00kts3LixTN13330XLy8vnnvuuTLbli1bhpubG4sWLcLb25tXXnmFMWPG8OGHHz7ws5V+Zy1atCAsLIznn3+e7du367aHhIToevUAdu/eTdu2bRk0aJBeeXx8PM2bN8fT07PMd6BQKKr0vVRGeHh4mV66//znP4SHh+uVqdVqXn75Zdzd3bG0tKRdu3ZlktW/3oYOCQkhIiKCt956C3t7e1QqFdHR0Xr7ZGZmMm7cOJycnLC1tSU0NJTjx4/rtpcm3UOHDsXd3Z2OHTvy8ssvExUVpauj1WpZsGABHh4eWFpa0rFjR7799lvd9vj4eBQKBT/99BOdOnXC0tKS0NBQ0tPT2bp1K97e3tja2jJ8+HC9Xl65DS2MhSSLQtRjWq2W3MJig7y0Wm2NfrbY2FiGDx+Oubk5w4cPJzY2ttqOvWbNGhwdHfH19eWNN94gOzu7ysfIzMzE3t5er2znzp2sX7+eTz/9tNx99u7dS1hYmF5Z//79OXToUJWmRzl37hzbtm3D3NxcV9anTx8SExMpLi4GIC4ujpCQEIKDg/V6HOPi4ujTp0+lz/WoBg0aREZGBomJiQAkJiZy584dBg4cqFdPo9HQokUL1q1bR3JyMjNmzOCdd95h3bp19z3+f//7X6ytrdm/fz8LFizg/fffZ8eOHUDJz8fTTz9NWloaW7Zs4fDhwwQEBPDEE09w584dAFQqFTt37uTmzZsVnuPdd99l5cqVLF26lKSkJCIjIxk5ciQJCQl69aKjo1myZAl79uzh8uXLPPfccyxatIi1a9fy448/smPHDj755JMqf4dC1DSZlFuIeiyvSI3PjJ8Mcu7k9/tj1ejhfsX87//+L40bN9YrmzJlCtOnTwcgKyuLDRs26G6fjhw5kqCgID755BNsbW0fKe4RI0bg7u6OSqXi1KlTTJ06lePHj+sSjMrYu3cv69at48cff9SV3b59m9GjR7N69eoKY0xLS8PZ2VmvzNnZmeLiYm7dunXflTpKvzO1Wk1+fj4ACxcu1G0PCQkhJyeHgwcPEhgYSHx8PG+++Sa9e/dm1KhR5ObmYmZmxr59+8q9fV5TzM3NGTlyJCtWrKBnz56sWLGCkSNH6iW6pfXee+893Xt3d3f27NnDunXryu2lLdWhQwdmzpwJgKenJ0uWLOGXX36hX79+xMXFcfLkSdLT01EqlQB8+OGHfPfdd3z77beMGzeOhQsXMmTIEFQqFb6+vvTo0YO//e1vPPnkk0DJow0LFy5k586dBAYGAuDh4UFiYiKff/45wcHBulg++OADgoKCAHj55ZeZOnUqqampeHh4ADBkyBDi4uKYMmXKo36tQlQr6VkUQhidPn36cOzYMb3XxIkTddvXrl2Lh4cHHTt2BMDf3x8PDw++/vproKRnsHHjxrrX7t27K33usWPH0rdvX/z8/Bg2bBjffvstP//8M0eOHAHgySef1B3X19e3zP5JSUn87W9/Y8aMGfTr10/vuC+88AK9e/e+7/n/OndeaQ+tQqFg9+7dep9rzZo1Zb6z/fv389prr9G/f39ee+013XZPT09atGhBfHw8WVlZHD16lODgYJydnXF3d+fXX39l37595OXlERoaWqnv6s+xjB8/vlL7lOfll19m/fr1pKWlsX79esaMGVNuvWXLltGlSxeaNWtG48aNWb58OZcuXbrvsTt06KD33sXFRbdM3uHDh7l37x4ODg56n+X8+fOkpqYC4OPjw6lTp9i3bx8vvfQSN27cYODAgbzyyisAJCcnk5+fT79+/fSOsWrVKt0xyovF2dkZKysrXaJYWlYamxDGRHoWhajHLM1NSX6/v8HO/bCsra1p06ZNhdtXrFhBUlISZmZ//ArTaDTExsYybtw4Bg0aRLdu3XTbHmawRKmAgADMzc05e/YsAQEBfPHFF+Tl5QGU6f1KTk4mNDSUsWPH8u677+pt27lzJ5s3b9Y9f6jVatFoNJiZmRETE8OYMWNQqVSkpaXp7Zeeno6ZmRkODg40adJEbwT3n3sh//ydLV68mD59+vDee+/pjaYNCQkhLi6ODh064OnpiZOTE4DuVrRSqaRVq1a0bt26Ut/Nn2Mp7S21tbUlMzOzTN27d+8ClPuco5+fH15eXgwfPhxvb2/8/PzKjFRft24dkZGRfPTRRwQGBmJjY8O//vWvMiO8/+qvbaRQKNBoNEDJvxkXFxe9ZzZL/XmgjImJCV27dqVr165ERkayevVqRo0axbRp03TH+vHHH8v8OyvtrSwvFoVCcd/YhDAmkiwKUY8pFIqHvhVsrE6ePMmhQ4eIj4/Xeybw7t279O7dm1OnTuHn51dto0iTkpIoKirS3QKuKPFMSkoiNDSU8PBwZs+eXWb73r17UavVuvfff/898+fPZ8+ePbpjBgYG8sMPP+jtt337drp06YK5uTnm5ub3TaL/bObMmTz55JP885//xNXVFSjpfYyIiMDHx4eQkBBd3eDgYJYsWYJSqax0ryJQbixeXl5cuXKFtLQ0VCqVrvzgwYOYmJhUGP+YMWOYMGECS5cuLXf77t276dGjh26EN1Cm566qAgICSEtLw8zMrNIJMpT0NkLJLWgfHx+USiWXLl3Su+UsRH1Sv64iQoh6oaCgoEwPm5mZGY6OjsTGxvL444+Xezs3MDCQ2NhYPv7443KPe+fOHS5dusS1a9cAOHPmDIBudG9qaipr1qzhqaeewtHRkeTkZF5//XU6deqke9asPElJSfTp04ewsDCioqJ0sZuamtKsWTMAvL299fY5dOgQJiYm+Pn56crGjx/PkiVLiIqKYuzYsezdu5fY2Nhypw16kJCQEHx9fZkzZ47uGcQ+ffqQk5PDihUrWL58ua5ucHAwo0ePxtTUtMJbwJUVFhaGt7c3w4YNY/bs2bi6unLixAneeOMNxo8fX2ESP3bsWIYOHVrh1Ddt2rRh1apV/PTTT7i7u/Pll19y8OBB3N3dHzrWvn37EhgYyODBg5k/fz7t2rXj2rVrbNmyhcGDB9OlSxeGDBlCUFAQPXr0QKVScf78eaZOnUrbtm3x8vLCzMyMN954g8jISDQaDT179iQrK4s9e/bQuHHjMqO6haiL5JlFIYTR2bZtGy4uLnqvnj17UlhYyOrVq3n22WfL3e/ZZ59l9erVFBYWlrt98+bNdOrUiaeffhqAYcOG0alTJ93E140aNeKXX36hf//+tGvXjoiICMLCwvj5558xNa34tvr69eu5efMma9as0Yu5a9euVfrc7u7ubNmyhfj4ePz9/Zk1axaLFy+u8PM+SFRUFMuXL+fy5cu647dq1Yrs7Gy9XrDmzZvj5uZGfn7+I4+ENjMzY/v27Xh4eDBixAh8fX15++23eeWVV/QG3JS3n6Ojo96jBX82fvx4/v73v/P888/TrVs3bt++rdfL+DAUCgVbtmyhd+/ejBkzhrZt2zJs2DAuXLigu8Xfv39/fvjhBwYOHEjbtm0JDw/Hy8uL7du362KdNWsWM2bMYO7cuXh7e+v2eZREVghjotDW9PwWQohakZ+fz/nz53F3d8fCwsLQ4Qghapj8zIvaIj2LQgghhBCiQpIsCiGEEEKICkmyKIQQQgghKiTJohBCCCGEqJAki0LUMzJmTYiGQX7WRW2RZFGIeqJ0NYjc3FwDRyKEqA2lP+t/XQlGiOomk3ILUU+YmppiZ2enW1vWysqqzDrDQoi6T6vVkpubS3p6OnZ2dvedA1SI6iDzLApRj2i1WtLS0nTr8Aoh6i87OztUKpX8UShqnCSLQtRDarWaoqIiQ4chhKgh5ubm0qMoao0ki0IIIYQQokIywEUIIYQQQlRIkkUhhBBCCFEhSRaFEEIIIUSFJFkUQgghhBAVkmRRCCGEEEJUSJJFIYQQQghRIUkWhRBCCCFEhf4PNMVW1O6FUgUAAAAASUVORK5CYII=\n", "text/plain": [ - "
" + "
" ] }, - "metadata": { - "needs_background": "light" - }, + "metadata": {}, "output_type": "display_data" }, { "data": { - "image/png": "iVBORw0KGgoAAAANSUhEUgAAAbgAAAEoCAYAAAAqrOTwAAAAOXRFWHRTb2Z0d2FyZQBNYXRwbG90bGliIHZlcnNpb24zLjUuMiwgaHR0cHM6Ly9tYXRwbG90bGliLm9yZy8qNh9FAAAACXBIWXMAAAsTAAALEwEAmpwYAABayklEQVR4nO3dd3xc1Zn4/88zVdKMerdkWe5yN7YxxcTYhoApCWSpIQUSICFtyZIQyIYEvtlsNr8ksCQhJCGUUAIkgVDW9AAGjGk2uONu2ZbVu0Zt2vn9cUeyykiWJUsai+f9es1LM+fee+aZ0cx95px77rlijEEppZQaa2yjHYBSSik1HDTBKaWUGpM0wSmllBqTNMEppZQakzTBKaWUGpM0wSmllBqTNMEpNYaJyHQR+UhEmkTk30c7HqVGkiY49YknIsUi0ioiPhEpF5G/iIj3KLY98xjHY0SkORLPIRG5Q0Tsg6zuB8BqY0yiMea3xzJOpWKdJjilLJ8xxniB+cAJwA+H+wlFxNHP4nmReM4ArgCuHWTdE4CtwxCfUjFPE5xSXRhjyoGXsBIdACLyWRHZKiL1IrJaRGZEyh8GCoD/i7S2ftDf+pFlxSJyk4hsApqPlESMMduBt4DZke3PF5ENkbrXisjcfup+DVgO3BWJb5qIJIvIQyJSJSL7ReQWEbFFtr9KRN4Wkf8VkVrgtkhr9m4ReSFSx9sikiMid4pInYhsF5ETusRws4jsiXSJbhORz3VZdpWIrBGRX0e23Sci53RZniYiD4hIaWT5012W9fm6leqTMUZvevtE34Bi4MzI/XxgM/CbyONpQDPwacCJ1eW3G3D13PYo1t8AjAfi+4jHAFMi92cC5cDVwAKgEjgJsANXRupz91U3sBq4pkvdDwHPAIlAIbATuDqy7CogCHwHcADxwF+AamAhEAe8BuwDvhyJ4WfA613qvwQYh/Xj+bLIe5Hbpf4AVmvUDnwDKAUksvw54G9AauS9Oz1S3u/r1pve+rqNegB609to3yI7Sx/QFEkurwIpkWU/Bv7eZV0bcAhY1mXbrgluIOt/9QjxGKARqAP2RJKIDfgD8F891t3RJRH0qrtrgoskh3ZgZpflX8c6RteRgA702P4vwJ+7PP4O8HGXx3OA+n5eywbggi717+6yLCHyWnOAXCAMpEapo9/XrTe99XXTLkqlLBcaYxKBZUARkBEpHwfs71jJGBMGDgJ5fdQzkPUPDiCeBcaYVGPMZGPMLZF6JgDfi3TT1YtIPVZrbdwA684AXF3ji9w/UmwVXe63RnncOSBHRL7cpSuxHqtrNaPL+uUdd4wxLZG73sjrqDXG1EV5/oG8bqV60QSnVBfGmDewWi2/jhSVYu1gARARwdq5HurYpEcVR1o/2jYDdRD4b2NMSpdbgjHmsQHWXY3VRTihS1nBMYoNEZkA/Bn4NpBujEkBtgAygM0PAmkiktLHsiO9bqV60QSnVG93Ap8WkfnA34HzROQMEXEC38Pq5lsbWbcCmNRl2yOtPxR/Bq4TkZPE4hGR80QkcSAbG2NCkfj+W0QSIwnpBuCRYxAbgAcrQVYBiMhXiAyOGUBsZcALwN0ikioiThFZGlk8pNetPrk0wSnVgzGmCmswxo+NMTuALwK/w2oBfQbrlAJ/ZPX/AW6JdJ19fwDrDyWudVgDNO7COj63G+u41tH4DtbAj73AGuBR4P6hxhaJbxtwO/AOVuKfA7x9FFV8CauFuR1rUMl3I/Uei9etPoE6Ri8ppZRSY4q24JRSSo1JmuCUUkqNSZrglFJKjUma4JRSSo1JmuCUUkqNSTEzW7iI3A+cD1QaYzomlk3DmpuuEGsaokujzXQgIiuB32BNRXSvMeYXR3q+jIwMU1hYOKSYm5ub8Xg8Q6pjpGnMI0NjHhka88iI5ZjXr19fbYzJjLpwtOcK67gBS7EmVd3SpeyXwM2R+zcD/1+U7exY8/VNwpqGaCNd5trr67Zw4UIzVK+//vqQ6xhpGvPI0JhHhsY8MmI5ZmCd6WM/HzMtOGPMmyJS2KP4Aqy5AQEexJo49qYe6yzGmsB1L4CIPB7ZbttwxarUaDHG8NHBevZWNTMp08MJ41MA2FPlY9WmMoqrm5mc6eXyxQUEQmG2lzeyamMZpQ2tzMhN4qtLJuIPhanx+Xl1ewU7ypuYmZvEF0+eQKPfsOFgPa9tr6Ta1878/BQuPCEPl8OGPxhm7Z5qiqubmTc+hfnjUxARwmFDcU0zdS0Bpuck4nU7usUaDBucdj0SokZHTJ3oHUlwq8zhLsp6Y81n17G8zhiT2mObi4GVxphrIo+/BJxkjPl2lPq/BnwNIDs7e+Hjjz8+pHh9Ph9e74Au/BwzNOaRcTQxl/nCVLSEyYi3kecVfAHYUx/ixeIApT6r/ORcBxUtYfY1hNnbEO7c1mGDYOShAKlxQl2b6TahpNcJ2Qk29jeFO9cFsAuM89o45AsT7rKBAHEOaA0eLnPZwN9l23yvkOgSKloMtW3Wxi47rCx0Yhcobw6zoSpEWxAKk218booTgIoWw47aEM0Bw5QUO5+e4MTrsl7DtpoQNW2GKSk2ChJtWNN4WsLGYJPeU1qO9c9GrIjlmJcvX77eGLMo2rKYacENQbSJXKNmbWPMPcA9AIsWLTLLli0b9JM+8PY+Nlfs4o7zB1/HaFi9ejVDed2jYSzEXFzdzPNbyiipa2VyppezZmbz6scVPL2hlA0H66PWkZcSzzlzM9hYUs+j25sAmJbt5b+WTeDUKRm8s6eGW57eAsB3z5zKl06eQLrXze5KH9c8+AGBkOHH589k2fRM4px2SutbuebBdQTDYb6zYipLp2aSnOBkd6WPy/70Dk1tfn547kwuXpiP1+1g9Y4qvvKXDwC4aFEBK4qymJOXzDMbDvE/L2wHDCdNTOPCE/LI8Lr554clPLvFuliAx2XnvHn5ZCe5eW5TGXesb+l8XePT4klLcPHcvgb+b28AABHo+lt7yZR0CtISqGhs54PiWnztQeblp3D9mVOZNS6JkrpW3t9Xy4aSPZxz8lRWzs7B7bADEAobGloDpMQ7sdkGMs/zyBoLn+fjRawnuAoRyTXGlIlILtb8dD2VYM3W3iEfa0b3YfXGzir2V4SG+2lUjDLGsKfKhz9omJrtxWm30dgW4C9vF/PClnJqGlo4uewj5o9P4fUdlazdU0MobEhNcFLXEuC/Vlk96FmJbm79zEzm5qfwQXEtv3xxO4lxTn524WxWzs7BabcRDhvueWsv6R4Xlyw6/FGfnOllyZQMbAIT0g8PAJiS5eXF71rzFMc57Z3l41LiWfWd0wiZ7t2GU7K8vHLD6bz3ztucs2RiZ/nyoize+sFyRCA/NaGz/OunT2ZKlheP28HJk9I7y8+ckcXdq/fgcdm5qks931g2ha8+8AEuh42bVhYxOy8JEeHjskYu/eM7GODyE8fzqWmZTM708MyGUn710g7epobEOAfnz80lOd7FS1vL+coDH3T7Pzhs8GLxBvJS4slOchM2sK2sEX8wTGqCk6tOncgVJxWwu9LHrsomPtxfR4bXzYUn5DE7LxmA8oY2dlQ0kRLvZOa4JO1SHSENrQHW769lRVH2sD1HrCe4Z7Gu3vuLyN9noqzzATBVRCZiXfbjcuCK4Q7MJtKtmRgIhXn0vQNcMH8cKQmu4X56dYxVNbVzoLaF8WnxZCXGAdYX8LlNZby3r4bkeCfnzM4lzePiXx9X8H8bS9lebrWqMrwuwgZqm635lE+amEaisfH6jkqe3ViKy2HjiycV8I1lU8hJjmNzSQO3PL2Zz8wbx5WnFnbuUBdOSGX59CxykuJITnB2xmazCdedPjlq3BMzoo9s65rYurLZBFuUTo80j4t4R+/y8WkJvcoAzpjRe6ckInxr+ZRe5V63g79fd0qv8hm5Sbz2/WUAZCa6O8u/tXwK+anxtAfCXHri4YR+w6enceuzW1m/v5b/OHMaJxSksu3Dd7CNm8XXHlrPofpWFhSk8PkTxzM+LYH399Xyv//ayf/+a2dnHdlJbupbAty7Zh9JcQ4S45wcqm/tXJ6fGs83lk2moqGNjSUNbDnUgAGWTMngu2dOJRw2VPv8rCuuZV9NM3Pzkrn0xPEkuBy0+kO8X1xLZWMbEzM8LJyQ2tnNaoyhorGdpPjY2+U2tAZIdDu6tXbrW/xsL28iwWVnZm5SZ/m+6mbe3l1NIBRm4YRU5kR+JGw51MiTH5ZQ0djG1OxELl2Uj689yI7yJlZtKuP9fbVkeF1cvHA8yfFOVu+o5PUdlQRChrdvXkFeSvywvLaYOQYnIo9hDSjJwJqJ/FbgaazLexQAB4BLjDG1IjIO63SAcyPbnot1iRM7cL8x5r+P9HyLFi0y69atG3S81zz4AbsOVfPGf54DwKpNpXz70Y+4YP44fnP5CYOud7gYY3hrVzUPvPIh8SkZZHjdfHbeOGqb/YTChp0VPvbXNLNgQiqXnzgeRwz9ih1M90hbIIQI3bqt3tpVxdMfHaKm2c/svGQunJ/H+8W1vLWzile3VxIKG0Rg1rgkmtqClNa3EggZspPc+NqCNPsPt9jn5CVz6aJ8EuOc/GH1HnZUNLGiKIvvnjmVufkprF69mjmLTuFPb+7lisUFFPaRiGLJ8dgN1RFzaX0rm0oaWDk7p9vypz86xL1r9nLZiQWcPjWTgvQEGtsC3PiPjby0tYIJ6QlctCCfkyelU9bQyu9e283uSh8A45LjWDotk1DY8MKWcnztwW51Z3hdVPsOXyTCZbfhDx0+UDkzN4kTClKobw2w8WA9JXWtiMCcdDs3X7iIbWWNfHSgng0H63HahZMnpfONZZOpafaz8WA9b+2qpqnNGrxz9WmT8LjtlNW38e7eGt7dW0Nqgot/W5DP/IIUtpU28sq2cj48UI/DJpw6OYPPLx7P1tJG3thZxes7KvG1BSnKTeTrSyfTHgyz4WAdr35c2ZnILl00npQEJ5tKGnhzZxXByIHZ3OQ48uMDVAbc7K9p6fYedH3NboeN/NR49lU3dzumm53kZtm0LPbXNvPu3lrA6n5fUZTFhSeMY/74VOxD6EoWkT6PwcVMghtpQ01w1z60ju0Hq3jjhyt5d28Nf33/AM9tKsPjsrPulk8T74r+C3qkBENhapv9pHpcbDxYz38//zEfHagn3gH5aV5K6lppDRzeYYtAusdNta+dEwtT+c6KqTS3B6lvDZCa4Oo8jjMa+trx+oNhqnztpCY4SXA5aG4P8vqOSv6weg9bSxsRgVMmpVNS10pds5+m9iApCU4mpCWwpbSRUORbmO5xcfFCayf3fnEtf1i9B4CrT5vIZ+eNY25+Mu3BMPet2cfbu6v5f5+dxdTsw5cia/EHWVdcx2lTMjp/BR/PyeJ4MtiYA6Ew6/fXcWJhWreda1VTO//7r51ctmg8c/OTO1tgB2pauOov7zMx3cMXT57ACQUppCS4+KC4lm888iGNbQEuWpDHObNzGZ+WwLriWm57divN/hBOu7BsehYnT0qnxtfOA2v2dA7gyfC6WDIlg/ZAmNd3VNLeZRTQ5EwP6R43mw81dPuudiyrawl09hoAOO3CCeNT8YfC3Y7ruuw2Tp+eSYbXzVu7qiipO9xiPWliGkunZbKnysc/P7Sue5sY5+CyReNZOi2TuhY/v3l1F3urmlk4IZUVRVl8Zu444lw2HlxbzO9f30NBWgLXnT6Z8+bmkhzvpLi6ma8/vB5vnIP/PHcG88endL7H96/Zx77qZm79zMxj9iNaE1wUQ01wX394HVv3V3LLhSdw3SMfAlZ30b7qZm45bwbXfGrSEWoYPn95ex+/emkHzf5Q5y+sDK+Lby+fQn57MWeuWE5TW4DbX95JdlIcp05O7zym8syGQ1z/+IZedWYnufnvC+dw5szh6y/vS8+dmK89yANr9nHPW3tpagtitwkel53GNmuvMTnTw2fn5dEaCPHoe/tpbAty1sxsLjwhjzNmZOF22NlyqIGfrtrGFYsLOH9ubrcv24aD9XjdDqZkDX7U2CcpWYymWIi5oSVAWzBEdlJct/Lt5Y28t7eWL548oVsSfXTVa6xpSOZLJxeycEIqLof12dtT5ePrD69nXn4KV582kZnjrK7ByqY2vv+PTZTWt/Lt5VM4eVI6OclxtAdD3PXabh57/yDfXDaZz84fR4bX6up9e3c1P3pqMxfMz+MLJxd0dru3B0P8+qUdOOw2vrlsMolxh7vC1+6pZsPBer5x+uRuI1hrm/387p9vcNPlK3r9yN1W2sikTE+v8o680rWe4aIJLoqhJrjrHl7P5v0V/Nviyfzutd0A/PObp3Lnv3ZZ3Qs3LceEoak90O0A/XC7f80+frpqG6dPy+SMGVlsL29i7e5q7rpiAbPzkge0Q3h3bw2rd1Rxzuwc0jwuimua+fnz2/m4rJGJGR4WFKSSmejG5bDxqakZLOpyrOFYamwLcP+afTzx7m58YQdz81MoqW3hYF0LgZDh0zOzWVGUxZ5KHw++U0xBWgK3nDeTpdMyO3cojW0Btpc1sXhi2jGPrz+xsOM9WhrzyBhszMaYqN+zvsqPpVh+n/tLcLF3xPM4YbNZ5yLUtwRITXDy5g+Wkxjn5AdnT+f8363hrDvepNkfpNUf4qlvLmFOfvKwxGGM4WBtKykeJ3//4CA/f/5jzp6Vzd1fWDjofu2TJ6V3Gx03Pi2Bp76Zxjf/+iGvba9kX3UzLoeNYCjMb1/dxczcJH558VzGpcQT57Sxr7qZQMgwNdIq7KrVH8LtsHU7oF1c3cyj7x+guLoZb5yDUydn8K9tFazZXY2vPcjMdBufmpzLa9srqGhs55zZOVx3+mTmRU5yBrhu2WTcDlu3X6QASXHOEU9uSg2HvpLYSLSSjlea4AZJRDDGaiEkxTs7d6yz85I5f24uqzaVcdqUDNbsrubPb+3lt58/9gNPfO1Brnt4PWt2V3eWnTkji9svnT+kg7bRxDnt/PGLC9lwsJ4TC60WW1NbgOc3l3Hnv3Zx/u/W9NrG47Jz3emTmV+QwoYD9Tz10SH2RpLjp2dmMz8/hVc+ruCD4locNmFyppfKpvbOYwGfX1zAF04qoHrXRyxbNoe2wEw2HKxncWFar/ObOrpmlFKqgya4QbJFElxTW5DEuO5v4x2XzufWz8wiM9HNbc9u5dH3DlDf4j+mpw+0B0N8/eF1vLu3lhvPns6eSh91LX7+8MWFw3Yej8th69YaSoxzctmJBSwvyuLmJzeTnRRHXkocEzO8OOzCUx8e4vZXDg/RXlCQwvfPmkZFYzv//LCE5zaVkZMUx7eXT+FLJ08gKymOYCjMI+/upzDDw7LpWQCs3mVtH+e0d2tZKqVUf46Y4ERkCXAbMCGyvgDGGDN6oyhigE2sLsrG1gCJ7u7dYi6HrfO8nksW5fOXtcX89b0DfGv5FPzBMC3+4JCSna89yA+e2Mjbu2u4/ZJ5XLQwfygvZciyEuO4/6oTe5WfNTOb37++m4bWAN9ePrXbuV1XLSlk1cYyvnJaIUlduhUddlu3k4SVUmqwBtKCuw/4D2A9oFN3RAgQjrTgCjP6HkQya1wyZ8/K5jf/2sW4lDhuf3knZQ1t3H7JPC48Ie+onnN3ZRP3v13MY+8fwBi45bwZo57c+iMifHvF1KjLJmd6uf7M6MuUUupYGEiCazDGvDDskRxnOiZ+bWwL9BrY0NPPPzeHFbe/wX/8bSPZSW6mZHr5z6c2s3RaJmmeI7fk/MEwd6/eze9e200obFg4IZXrz5jK0mnRL4GklFKqnwQnIgsid18XkV8B/wTaO5YbYz4c5thimogQNtAaCBF/hBOg071uHr56Me/treXihflU+9o56843uW/NXm48u4iDtS3c9dpuZuQm8uVTCrHZhP01zfz5rb28s6eGsoY2WvwhPjNvHJcszOfUyekxNdOIUkrFov5acLf3eNz1PAMDrDj24Rw/Oo7BBUMDu97V3PwU5uanAJDqcXHu7FweXLufOXnJ/PiZrVQ1Wb8d1uyu4VcXz+VL971PeUMbS6dlctqUDFbMyOZ0bbEppdSA9ZngjDHLRzKQ403HKMpAKIzTfvRD8r975lSe21zGdY98yIT0BF75j6Ws3VPDT1dt44T/egWA+65cFHVSW6WUUkc2kFGUDwPfNsY0RB5PwJrQ+IzhDi6WSUcLLmxwDCLBTc1O5JvLJrOnysevL5lHYpyTqdmJzM5L5uWt5WQmullRlHXsA1dKqU+IgQwyWQO8JyI3AHnAjcD3hjWq40DHMbhQ2OCwDe542A9WFvUqWzghlYUTUqOsrZRS6mgcMcEZY/4kIluB14Fq4ARjTHlf64uIDZgHjANaga3GmIpjFG/MsAmdl5MYTBelUkqp4TWQLsovAT8GvgzMBZ4Xka8YYzb2WG8ycBNwJrALqALigGki0gL8CXjQGBNmDLCJ0HFlCx3RqJRSsWcgXZQXAacZYyqBx0TkKeBBYH6P9X4G/AH4uulxiQIRycK6yvaXItse92wCgY4Ed4znfVRKKTV0A+mivLDH4/dFZHGU9T7fTx2VWFfcHjNEhI4s3nE9J6WUUrFjIF2Uv41S3CAi64wxz0RZ/xLgRWNMk4jcAiwAfjbWTgzveoWKwQ4yUUopNXwGsmeOw+qO3BW5zQXSgKtF5M4o6/84ktxOA87G6pL8wzGJNobYumS4wZwmoJRSangNJMFNAVYYY35njPkd1iCSGcDngLOirN8xIfN5wB8irbxBT50vItNFZEOXW6OIfLfHOstEpKHLOj8Z7PMNVNfDbjqKUimlYs9ABpnkAR6gIfLYA4wzxoREpD3K+odE5E9YifD/ExE3A0ukURljdhAZ0CIiduAQ8FSUVd8yxpw/2Oc5Wt1acNpFqZRSMWcgCe6XwAYRWY11lZilwM9FxAP8K8r6lwIrgV8bY+pFJBfr5PBj4QxgjzFm/zGqb/C0BaeUUjFtIKMo7xOR54HFWLv1/zTGlEYWdyYuEVkHvA28ADxvjGmLbF8GlB2jeC8HHutj2SkishEoBb5vjNl6jJ4zqq4tOLu24JRSKuZIj1PWeq8g8ixWUnnWGNPcz3oO4DSs1ttyoAZ4CXjBGLNzyIGKuLCS16yeM6OISBIQNsb4RORc4DfGmF5X0xSRrwFfA8jOzl74+OOPDzqeJ3b6WbU3AMANC93MzRxIY3j0+Xw+vF7vaIdxVDTmkaExjwyN+dhavnz5emPMoqgLjTH93oDTgbuB/cA/gIuBuAFslwt8Ffg78BFw95G2OUJ9FwAvD3DdYiCjv3UWLlxohuLXL203E25aZSbctMq8tbNqSHWNpNdff320QzhqGvPI0JhHhsZ8bAHrTB/7+YF0Ub4BvBEZ4LECuBa4H0g6wnZlkfXuj8xPecqRnusIPk8f3ZMikgNUGGNM5CR0G1YLcthIty5KPQanlFKxZkD9aiISD3wGuAzrxO0+p9sSkUXAj4AJXes3xswdbJAikgB8Gvh6l7LrIvX+EatV+Q0RCWJN8Hx5JLMPm64pTc+DU0qp2DOQmUz+BpwEvAj8Hlht+p8w+a9Yg082A8dkYmVjTAuQ3qPsj13u3wXcdSyea6Bs2oJTSqmYNpAW3APAFcaYEICILBGRK4wx3+pj/SpjzLPHLMIYZes2VZcmOKWUijUDOQb3oojMF5HPY3VR7gP+2c8mt4rIvcCrQOeJ4MaY/rY57ths2oJTSqlY1meCE5FpWOedfR5rwMbfsE4rWH6EOr8CFAFODndRGvpPiscdnWxZKaViW38tuO3AW8BnjDG7AUTkPwZQ5zxjzJxjEVwsE7QFp5RSsay/psdFQDnwuoj8WUTOoPvgwb68KyIzj0l0MUyPwSmlVGzrM8EZY54yxlyG1d24GvgPIFtE/iAi0a4i0OE0rLkrd4jIJhHZLCKbjmnUMUBHUSqlVGzr7xjcxcD/GWt6rr8CfxWRNOAS4Gbg5T42XXnMo4xB0m2yZT0Gp5RSsaa/PfMXgIMi8pCInCMidmNMrTHmT8aYFT1XFhEvgDFmf7Rb13XGAm3BKaVUbOuvi/JzWBc7fRX4d6xk9wcRWdrHJs+IyO0isjRyKR0ARGSSiFwtIi8xhlp3XZOaHoNTSqnY0+95cMaYRqxpuR4UkXSsKbF+JyLpxpj8HuueEZnJ/+vAEhFJBYLADuA54EpjTPlwvIjR0DXB2XWqLqWUijkDnYsyFfg3rBO904Anoq1njHkeeP6YRRfDHNqCU0qpmNbfIJNE4EKsE70XAM8CPwNeH+6JjI8HOpOJUkrFtv5acPuwLlh6N/CSMSYwMiEdH7q34HQUpVJKxZr+9swFxpgvAJN7JjcRuX54w4p9XVtt2oBTSqnY098oypbI3SujLL5qWKI5jnRttXW9+KlSSqnY0N8xuM8DVwATRaTr5W8SGearZR8P9LibUkrFtv6Owa0FyoAM4PYu5U3AmJt662jpyEmllIptfSa4yOwj+4FTupaLiB3rMjp/Hd7QYpue+6aUUrGtz2NwIpIkIj8UkbtE5CyxfBvYC1w6ciHGJm3BKaVUbOuvi/JhoA54B7gGuBFwARcYYzYMf2iHiUgxVtdoCAgaYxb1WC7Ab4BzgRbgKmPMh8MZkx6DU0qp2NZfgpvUceFSEbkXqMY6daBpRCLrbbkxprqPZecAUyO3k4A/RP4OGz33TSmlYlt/e+nOc9+MMSFg3ygmtyO5AHjIWN4FUkQkdzifUFtwSikV2/prwc0TkcbIfQHiI48FMMaYpGGP7jADvCwiBviTMeaeHsvzgINdHpdEysqGKyA9BqeUUrGtv1GU9pEM5AiWGGNKRSQLeEVEthtj3uyyPFq26TVfpoh8DfgaQHZ2NqtXrx50QPsbQ533h1LPSPP5fMdVvKAxjxSNeWRozCNnQFcTGG3GmNLI30oReQpYDHRNcCXA+C6P84HSKPXcA9wDsGjRIrNs2bJBx/RxWSOsfQuAodQz0lavXn1cxQsa80jRmEeGxjxyYn6khIh4Ilc2IHIh1bOALT1Wexb4cuRUhpOBBmPMsHVPgnZRKqVUrDseWnDZwFOR+R4dwKPGmBdF5DoAY8wfsa5Bdy6wG+s0ga8Md1AuR8z/NlBKqU+0mE9wxpi9wLwo5X/sct8A3xrJuLzumH/rlFLqE02bIYPkjdMEp5RSsUz30oPkdtjJjBcuPXnSaIeilFIqCk1wQ/D/LY1nxfKi0Q5DKaVUFNpFOQQ2vdCpUkrFLLHGZ3zyiEgV1uWAhiIDa47O44nGPDI05pGhMY+MWI55gjEmM9qCT2yCOxZEZF3PKxvEOo15ZGjMI0NjHhnHY8ygXZRKKaXGKE1wSimlxiRNcEPT86oGxwONeWRozCNDYx4Zx2PMegxOKaXU2KQtOKWUUmOSJjillFJjkiY4pZRSY5ImOKWUUmPSJ3YuyoyMDFNYWDikOpqbm/F4PMcmoBGiMY8MjXlkaMwjI5ZjXr9+fXVfM5l8YhNcYWEh69atG1Idx+Nl3DXmkaExjwyNeWTEcswi0ueUi9pFOQRvHwqwrbRxtMNQSikVhSa4IfjzZj/n/vat0Q5DKaVUFJrglFJKjUma4AYpEAqPdghKKaX6oQlukNoCodEOQSmlVD80wQ1SW0BbcEopFcs0wQ1SKKyTVCulVCzTBDdIYb0Kg1JKxTRNcIOkLTillIptmuAGSVtwSikV2zTBDZI24JRSKrYddwlORO4XkUoR2dKl7DYROSQiGyK3c4c7Du2iVEqp2HbcJTjgL8DKKOX/a4yZH7k9P9xBaBelUkrFtuMuwRlj3gRqRzsOTXBKKRXbxByHO2oRKQRWGWNmRx7fBlwFNALrgO8ZY+qibPc14GsA2dnZCx9//PFBx7C/McSta9sA+MvK2LxOUjQ+nw+v1zvaYRwVjXlkaMwjQ2M+tpYvX77eGLMo6kJjzHF3AwqBLV0eZwN2rBbpfwP3H6mOhQsXmqHYdLDeTLhplZlw06oh1TPSXn/99dEO4ahpzCNDYx4ZGvOxBawzfeznj7suymiMMRXGmJAxJgz8GVg83M8ZOg5bvkop9UkyJhKciOR2efg5YEtf6x4regxOKaVim2O0AzhaIvIYsAzIEJES4FZgmYjMBwxQDHx9uOMI62kCSikV0467BGeM+XyU4vtGOg49D04ppWLbmOiiHA2a35RSKrYddYITEbuIfGE4gjme6DE4pZSKbX0mOBFJEpEfishdInKWWL4D7AUuHbkQY5N2USqlVGzr7xjcw0Ad8A5wDXAj4AIuMMZsGP7QYpu24JRSKrb1l+AmGWPmAIjIvUA1UGCMaRqRyGKcJjillIpt/R2DC3TcMcaEgH2a3A4LhUc7AqWUUv3prwU3T0QaI/cFiI88FsAYY5KGPboYpi04pZSKbX0mOGOM/WgrE5E44HzgU8A4oBVrVpHnjDFbBxtkLOp6orcxBhEZxWiUUkr11GeCE5EEIGCMCUQeTwfOBYqNMU9FWf824DPAauA9oBKIA6YBv4gkv+8ZYzYd49cwKrrORRk2YNf8ppRSMaW/LsoXgauBXSIyBWs05V+B80XkJGPMzT3W/8AYc1sfdd0hIllAwVADjhVdTxMIhsPYbUfd4FVKKTWM+htkkmqM2RW5fyXwmDHmO8A5wHk9VzbGPNezTERyuiyvNMasG2K8MaPrIbiwDjhRSqmY01+C6zqKYgXwCoAxxg8MdJf+/CDjink9W3BKKaViS39dlJtE5NfAIWAK8DKAiKQcRf1j9shU12NwwZCOqFRKqVjTXwvuWqyTuwuBs4wxLZHymcCvB1j/nwcfWmwzXROcTtullFIxp78W3B+MMVf1LDTGrAXW9iwXEa8xxtdj3buPtM7xquuJ3jovpVJKxZ7+WnBzj7KuZ0TkdhFZKiKejkIRmSQiV4vIS8DKQUUZg7p1UeoxOKWUijn9teASROQE+jiOZoz5sMfjM0TkXKyraS8RkVQgCOwAngOuNMaUH5uwR1/XLkptwSmlVOzpL8HlAbcTPcEZrJGV3QuNeZ4xPHKyq+6jKDXBKaVUrOkvwe02xvRKYsrSNcFpC04ppWLPUV/RW1nCepqAUkrFtP4S3E0AInJ9zwXRyj5pujbatAWnlFKxp88EZ4x5OXL3yiiLrxqWaI4jOpOJUkrFtv6uJvB54Apgoog822VRIlAz3IHFurAeg1NKqZjW3yCTtUAZkIE1mrJDEzAmLnkzFF1z2mBHUfrag/iDYdI8rmMUlVJKqQ79XfB0P7AfOKVruYjYgcuxLp3ziTXUuShDYcMX732P7eWN/OT8WVy8MJ+yhlZuf3knW0sbmJGbxK8unke8Sy/Do5RSg9FfF2US8C2s8+GexbqawLeAG4ENjFKCE5H7sa4aXmmMmR0pSwP+hjVvZjFwqTGmbjjjCA/xGNyDa4vZcLAegP98ajO/fXUX1b52nHYbiwpTWbWpjFDY8P2zpzMpw6NXDFdKqaPUXxflw0Ad1oVOr8FKbC7gAmPMhuEPrU9/Ae4CHupSdjPwqjHmFyJyc+TxTcMZRHgIM5kcqm/l1y/vYPn0TO6/6kRe2FLOfWv2sXJ2Dt9cNpmspDj++7lt/PmtfbywpRyPy87Zs3P4wdlF5CTHHeuXopRSY1J/CW6SMWYOgIjci3VlgQJjTNOIRNYHY8ybIlLYo/gCYFnk/oPAaoY5wYWO8moCdc1+/vVxBVlJcdzz5h6Mgf+6cDYiwrlzcjl3Tm639X903ky+etpEXv24kq2lDTy5/hAvbC7n3Dm5nD0rm9OnZ+J2aPelUkr1RbrOqdhtgciHxpgFfT0eTZEEt6pLF2W9MSaly/I6Y0xqlO2+BnwNIDs7e+Hjjz8+6Bge397Oi8VBAL41382JOX3/Vggbw8/fa2N3/eGuzKtmuVg23jng56tsCfPPXX4+qgzRHoJEF1w7x83czP5+o/Tm8/nwer1Htc1AhI1BIGpXqjFmSF2swxXzcNKYR4bGPDJiOebly5evN8Ysirasv73jPBFpjNwXID7yWABjjEk6xnEOO2PMPcA9AIsWLTLLli0bdF1v+bZB8T4Aps+YybJ54/pc98G1xeyu38p/nlvE/PGpZHhdTMo8+g/LpUBTW4AXNpdz/9v7+N8Pm/jO8vH8+xlTKa5pJmxgWnZiv3WsXr2awb7uNbuqeW9fDXPykklwOYh32SiubmHd/jr++WEJBWkJTEhPYF5+Cnmp8VQ0tvN/G0sJG8M1n5rEaVMyOrtYm9uD7KnyMXtcMjZb/8lvKDGPFo15ZGjMI+N4jBn6H0V5PPV/VYhIrjGmTERygcrhfsLuc1H2PcikoTXAr17awaemZnDtpyYNebBIYpyTS08cz2fnj+PHT2/ht6/t5o9v7sUfDGO3CdefMZUrTy0kOX7grcOe3thZxaaD9UzM9OBxO6j1+XlmYylv7qyKun6c08bJk9JpbAtQXNPCvz4+/PbnJsdR2+zn+//YiN0mTMzwEOe0saO8iUDIMDc/mc/OG8cF8/PI8LoIG/i4rJFUj4u8lPhBv4aRNtRW6rF+7vZgCKBXN3aNrx0DZHjd3cp3VjRR3tz7c7yjvIlgOMysccm9ykNhw8xx3X/nvr+vlsQ4BzNyu5dvOFhPnNNGUU7vcqddetW/t8pHQ2uAEwq6d8RsK22kvsXPqVMyupXvrmxiX3ULZ87I6vZeNLQG+PBAHUunZmLv8kOqsS3A2t3VrCjKxuU4PN9FOGx4d18N8/JT8Li77x53lDeRlegmtcdpPTW+dtqDYcb1+Ly2B0OU1rcxMcPTrdwYw86KJqZkenv9uKtobCMpztlr9HRz5JSins9tjKGxNUhyQu/vuz8Y7vbaur5GkeHpbRnIc4TD5og/ao+Vo+vfil3PYs248ovI32eG+wkHOhflMxsO4WsP8oOzi47pDjDOaedXl8xj5ewc1u6pwet28EFxLXe8spO/fXCQb6+YQrzTzrt7a9hf08JVSwo5dXJ65/b7qpt59L39pHpcpCa4SIxz0NQW5MUt5bwRJZFleN386NwZnDEji4rGdkSg1R9iQnoC49MScNoPf5Ea2wLU+Px43Q4yE90EQ2F2Vfp4YUs520ob8YfCXH1aJs3tQd7eU83PnvuYnz33MR6XnWDY0B4ME+e0cdLEdD49Mxu7L0xlUxs7y31sLKnnvDm5FKQldPuSVDa14XbYeyX2tkCIA7UtvVq27cEQb+6spjA9gYL0hM5EcLC2hd+9tguXw8bCCakUpnvI8LrZU+XjifUlbC9vYkVRFuPTEpienUhja4DnNpfx6scVnDkjmynZXublp7C1OsTbz23j6Q2lnDYlgxm5iSwoSMXtsPPO3moe/+Ag8/JTOLEwjcUTUwmEDFsONfDX9w6QlxrPgoJUpmV7KUhLYFNJA39fdxCbCCcWpjIlK5G8lHg2lNTz8DvF2EQ4eVI603MSSfe42FLayKPvHQAMJxSkUpieQF5KPNvKGvm/jdbo3ClZXiZneclLiWfLoQbW7K4G4K4tr7F4Yhpuh42dFT7W77cGI+enxjNrXBJJcU62lzex+VADABMzPEzL9uJ1O9ld2cTGEqs83ePilMnpOO02dlY0sbXU6gzKTHRz6uR0HDarvKOeDK9VHu+0s7fax7r9dRgDWYlupuckkuZxUVzd3Fm/y25jWo4XT6iN3257mw8P1Hf+b0+elEZ2Uhx1LQHe21tDe9BK3LPzkpiS6cXXHmTN7mraAmEcNqEgLYE5+VavxJrdVRysbSXeaWdCegJz85NJTXCxfn8d6/bXEee0MSnDS1FuIhPSPOyqbOLVjysJhMJMy05kek4ikzM9VDa189LWcioa25mW7WVyppeinCRaAyFWrW+l5KU3yUuJZ1Kmh1njkkmMc7B+fx1v7KwiNzmOOXnJzM5Lxut2sL+mhac+KqEtEGb++BSmZXuZnpNEXYufF7eUs7W0gVMmpzMpw8vc/GRsIry9p5pVm8pYOjWT2XlJzMxNIs5pZ3t5I395uxhvnIMTC9MoyklkcpaXktpWnvroELsqfZw5I4uJGR5m5CbR4g/xr48reHFTM0sOrmNqViKz85KJc9p4e3c1T31UysSMBGbnJTMjJ4m81HjW76/jbx8cJN5l5+RJaUzJ9DIlK5H9tc08ub6Eg3WtnDkjm6lZXhZMSGXWuKRu+49jqc9jcLFKRB7DGlCSAVQAtwJPA38HCoADwCXGmNr+6lm0aJFZt27doOP40VOb+et7BwD4xb/N4fLFBb3WMcZw4e/fpj0Y5sXvLh30cx2NDw/U8f1/bGRvVTMAiW4HgXCYtoDVwktxgR87TW3BqNtnJbq5akkh588ZR7M/SFNbkDSPk8J0D45h+hBuL29kza5qSuvbsNsgJcHF5pIGdlY2db6Onjp2oB6Xg91VPj46UIfH5WDGuCRmj0smwWWnvLGN17ZXUtvsZ2ZuEpmJbtI9Lprag7y3t4bGyHsgAuOS4wmGw1Q0tvcZp8thwx8MIwJdvzaJbkfnD55mf6iz3GkXBCFkTK+Rth11DVRSnINAyNAaCPUqbwtaO+qWyHOLwLSsRFoDIZx24WBdK/5gGI/Lztz8FMLGEO+ys7vSR3lDG/mp8SyZksHu/YfwpKSztbSBsIGcpDiWTMnA1x6grjnA1tIG2gJhxqfFc8qkdGpb/NT4/Hxc1kh7MExuchyLJ6bTFghR1dTOpkP1CEJmopslk9OpbvZT1+xnUyRJZSS6WT49k2pfO7XNfjYebCAUNqR7XZw+LZO2QJjGtgBbDjXQGgiR5nFx5oxsmtqs1sz28kb2lNWSk57Mp2dkEQwbanx+PjpYh68tSJzTzsmT0kmKd9IUqae80fohdNLENDK8bqp87VQ3tbP5UANtgRDzxqeQlxJPiz9EXYsVq689yKQMD/PyU2hoDdAaCLG1tJFqXzsZXjeLJqTSFgxhjPVZrmhs7+zVCBtrP3CgtoX9NS2IwJRkGxNyM/GHwtQ2t3f2ZhSkJTAxw0NTW4Bqn58DtS0AuB025uYnYwwEwoZdFU2d/+vZeUkYY/3IPlTfiq/d+kwnxztJ97iobfHT0Bro9nnNTY4jEArjD4Y7vwMAqQlOQmGrBdfQGugs97odZMeFaQg5qGsJdH6WO1reVU3W/6/rZ7MwPYGG1gDBsOm2rxmXHEezP0QobDpjfeeHK8hNHnxvjYgM6hhcTDLGfL6PRWeMZBwDmcnkvjX72FjSwM8unD1CUcGCglReveF09lY3EwiFmZLppbk9xNo91WwtbeTDHcVMK8xnQnoCK2fn0OoP4XbaaWwN4HU7yE2OG7ZE1peinKReXVdg7Rh2VDTxz9feJ69wChPSExiXEs+aXdWs31/H5kMNNLdbrcirTp1IRWMb5Y1tPPLufkLGkBjnYMnkDBCri6e8oY09VT5cDhsrZ+dw8qR06loC1DX7Ka1vxW4TpuckcvasHMBq5e2ubKaxLUBWopuTJ6Xjirw35Y1t7Kr0EeewMb8gpbMFWNfsZ1tZIxs3buQL5ywlOcFJOGyoafaz8WA9BpiS5WVihgdfe5CDtS3srGjCZbeRmxLPvPxkGiM78F0VTZTUtzIhLYFFhWkYY2gLhjsT04T0BIpyEhERjDHsr2mhqS1Ibkpcty7IUNhQ2+wnJcHZ7y/l1atrWLbsxGP4nx1+1rGhJSP+vMYYgmET9f1sC4Rw2W29uuHaAiGcdhtvvfkGy5Yd3h/7g2FCYRO1W7I1ECI5vvv/LRQ2lDW04nE5unVZhsKG/TXNhI3p9oO0qS3A3qpm2oNhJqQnkJ0U1/kaShvaKK5uJjPRzdQsb2cvU22znx3lTbidNmaPS2btmjdZtmwZbYEQH5c14g+GmRFp0YPV7bi/toXyhjYmZXq6PUdFYzt7q31kJbqZnHn4OcoaWtlc0jCk5HYkx12CixXhsMEhEDS9z4PztQe56v73Wbe/jrNnZfP5KK274SQiTO4yiCU5wcY5c3I5Z04uq91lLFs2q9c2sXi8S0Qoykni1HEOlp1a2Fk+LTuRr542sc/tjuXxsClZ0QftjEuJ73XMBSDV42LJlAwCJfbO4yI2m9WKOXNmdrd1vW7rWFXP41Ud3ayZid2Pk4HgtduYPz4FxvdYIkJhj2M9HeyR51fHjojgtEf/jMU5ow9f6Ks82nEyAI/b0es4IFj/z/zUhKjl0QavJcY5mTc+pVe5iJCXEh/1u58W6SHpKc5p73VcFKzP+MQMT6/jjSJCTnJc1PN3c5PjhzW5gSa4QQsZg8MGwVDvFtzdr+9m3f46bvj0NK47fXK3g9tq+OmsL0op0AQ3aGFjcNqgLQTB0OFjKQdrW7h3zT7+7YQ8/v2MqaMYoVJKfbLpFb0HKRw2OCIts64tuEfe2084bLhx5fTRCk0ppRSa4AYtZMBlB4dNaI6MBgqGwjz14SGWTc8a9r5lpZRS/dMEN0hhY7AJJMU7aWyzhtS+tbuayqZ2Ll6YP8rRKaWU0mNwg9Rxpn6S20Fts5+mtgD3vLGXdI+LFUVZox2eUkp94mmCG6RQ2GDDasE9v7mc5zeXA/CzC2f3OexXKaXUyNEEN0hWF6V0m6br55+bwxUnjew5b0oppaLTBDdIYQM2gUWFqWwra+RfNyzt86RgpZRSI08T3CCFIsfg/vPcGVy8MF+Tm1JKxRg9WDRIP/nMTK6e7SbOaU1gq5RSKrZoghukyZle8hP17VNKqVile2illFJj0nF3PbhjRUSqgP1DrCYDqD4G4YwkjXlkaMwjQ2MeGbEc8wRjTGa0BZ/YBHcsiMi6vi60F6s05pGhMY8MjXlkHI8xg3ZRKqWUGqM0wSmllBqTNMENzT2jHcAgaMwjQ2MeGRrzyDgeY9ZjcEoppcYmbcEppZQakzTBKaWUGpM0wSmllBqTPrGTLWdkZJjCwsIh1dHc3IzH4zk2AY0QjXlkaMwjQ2MeGbEc8/r166v7OtH7E5vgCgsLWbdu3ZDqWL16NcuWLTs2AY0QjXlkaMwjQ2MeGbEcs4j0OSOVdlEOweaqIHXN/tEOQymlVBSa4AapsqmN29e386OnN492KEoppaLQBDdIgZB1/uCH++tHNxCllFJRaYIbpI4T5INhPVFeKaVikSa4QQqHrb+hjjtKKaViiia4QQppC04ppWKaJrhBCkUSm4xyHEoppaLTBDdIYZ2kWimlYpomuEEKadekUkrFNE1wg9TZRSnaSamUUrFIE9wgdXRRan5TSqnYpAlukHSQiVJKxbYBJzgRSRKRxOEM5niig0yUUiq2HTHBicgiEdkMbAK2iMhGEVk4/KHFto4xJnoMTimlYtNALpdzP/BNY8xbACJyGvAAMHc4A4t12kWplFKxbSBdlE0dyQ3AGLMGaBq+kI4PYT1NQCmlYtpAEtz7IvInEVkmIqeLyN3AahFZICILhjtAEblfRCpFZEsfy0VEfisiu0Vk00jEBIen6tIeSqWUik0D6aKcH/l7a4/yUwEDrDiWAUXxF+Au4KE+lp8DTI3cTgL+EPk7rA6f6K0ZTimlYtERE5wxZvlIBNLP878pIoX9rHIB8JCxrl/zroikiEiuMaZsOOPSUZRKKRXb+kxwInID0GCMua9H+XcAuzHmzmGObaDygINdHpdEynolOBH5GvA1gOzsbFavXj3oJ91YGQQgEPAPqZ6R5vP5jqt4QWMeKRrzyNCYR05/LbivAtGOZ90DfADcORwBDUK0PsKozStjzD1Y8bNo0SKzbNmyQT9p25Zy+HA9bpeLodQz0lavXn1cxQsa80jRmEeGxjxy+htkYowx/iiF7cTWgacSYHyXx/lA6XA/qU7VpZRSsa3fUZQikj2QslH2LPDlyGjKk7G6VYf1+Bvo1QSUUirW9ddF+SvgORH5HvBhpGwh8Evg18MdWAcReQxYBmSISAnWaE4ngDHmj8DzwLnAbqAF+MpIxNXZgoupxqxSSqkOfSY4Y8xDIlIF/BSYHSneAtxqjHlhJIKLxPH5Iyw3wLdGKJxOhy+XM9LPrJRSaiD6PU0gkshGLJkdT7SLUimlYttAJlvOF5F/RmYTqRCRJ0UkfySCi2WHuyiVUkrFooFM1fUA8H/AOKzzy/4vUvaJFgpbf/VqAkopFZsGMlVXpjGma0L7i4h8N9qKIhIHnA98CishtmIdt3vOGLN1iLHGlJDOZKKUUjFtIC24ahH5oojYI7cvAjU9VxKR24C3gVOA94A/AX8HgsAvROQVERkzl9jRqwkopVRsG0gL7qtYkx3/L9YMIWsjZT19YIy5rY867hCRLKBgMEHGIh1FqZRSsa3fBCciduDnxpjPHqkiY8xzUbbPMcaUR5ZXApWDDTTW6EwmSikV2/rtojTGhIBMEXENsv7nB7ldzNPTBJRSKrYNpIuyGHhbRJ4FmjsKjTF3DGDbMdu+CelMJkopFdMGkuBKIzcbkHiU9f/5qCM6ToT1GJxSSsW0gVzw9P8BiIjHGNPc13oi4jXG+Hpse/eR1jledZwHp5RSKjYNZCaTU0RkG/Bx5PE8Ebk7yqrPiMjtIrJURDxdtp8kIleLyEvAymMW+SjT8+CUUiq2DeQ8uDuBs4mc+2aM2Qgs7bmSMeYM4FXg68BWEWkQkRrgESAHuNIY88QxinvUdXRRhjXRKaVUTBrIMTiMMQd7TEkV6mO95xnDIye76khsoZAmOKWUikUDSXAHReRUwEROF/h3It2Vn2QdXZTaVamUUrFpIF2U12Fdby0PKAHmA98cxpiOCx1dlHo+nFJKxaaBjKKsBr7Q8VhE4rEmVP7HMMYV8zrymiY4pZSKTQNpwRGZZPkcEXkI2AdcNrxhxb6OxBbUBKeUUjHpSHNRLgWuAM4D3geWAJOMMS0jEFtMM5Fjb3pVAaWUik19tuBEpAT4BdYlcGYaYy4CWkcjuYnIShHZISK7ReTmKMuXRU5L2BC5/WS4Y+oYXKItOKWUik39teCeBC7E6o4MicgzWJfLGVGRKxr8Hvg01iCXD0TkWWPMth6rvmWMOX+k4urIa3oenFJKxaY+W3DGmOuBQuAOYDmwE+vKApeKiHdkwgNgMbDbGLPXGOMHHgcuGMHnj8r004IL9JjHq7k92Lm+UkqpkXGky+UYY8xrxphrsZLdFVituuJhj+ywPOBgl8clkbKeThGRjSLygojMGu6gOgaZGHP4OFyrP8QtT2+m6Mcv8qOnNuMPhrnj5R3MuvUlVtz+Bu/s6XUh9JjUFggRPM4m22wPRp17AGNMnz8udASs+iT6JP3YliO9WBG53hjzmx5l/2mM+fmwRnb4uS4BzjbGXBN5/CVgsTHmO13WSQLCxhifiJwL/MYYMzVKXV8DvgaQnZ298PHHHx90XPdubmfNoaB1/6wEHDbhjnVtbKoOkesRypoNiU5oCsCMNBt1bYb6dsPNi+MwwGPb/fj8hi/OdDMz3X5Uz90aNLjtYBPBGMPWmhDvlIbIShDmZdrJTLCxsy7E1uoQpc1hHCIUJttw26G22U9TyEFtm6G2zeBxChnxQma8UNliONAUjpTD5GQ7+Yk26trDlPkMVa1h3HahMMlGjseGTcDnNxzyhWn0G/K8NjLihawEG01+Q1lzmKoWQ1q8MD7RRkGijbp2a/1SX5jWIExKPlxXZYtVXtVqSI8TMhNsZCcINT4/NQEHBxrD+MOGwiQb47w2nDahoiXMvgYr5nyvkO2xkRkvNPgNVS3Wc9kE8rw2cj3W77nq1jCHfIaGdkNBko2cBCElznr9Zb4w1W2GnAQhx2MjO8FGY+S1VDSH8TiFvESrLhGobTVUt4YJhKEg0Uau10YwbDjU4KcuYMcXsMrzEgVBqG4NU9FiqG8Lk5VgY3yijQSn9TrKfGGqWw0Tk636vS6hrs1Q2WK9JyluId9rIzXOqqe02VDRHCYtTpiSaifVLVS3Gkp9Ycqbw6TGCVNT7aS4hZpW6zWUt4RJdQtTUuwku4XaNkN5sxVTgj1EUborUv/hepLdwvQ0q56y5jAHGsOUNRvyvMI4r/X/q2k1lDSFqWkLk+K2yrMTbNRE6q9sscrzE21kxtuobj38nia5rfc612Ojvi3MgaYwJb4w+V4bE5JspMbZqGoJc7ApTGmzVV6QaCMlzkZVUzs1AQdlzWEcArle67PhDxkO+az3R4TOz197yPqcVbYYWoPWZ3ZCko2wgapWq7yh3SrPT7ThtEFVq/U/qG41ZMYLeV4byZH3uqLFem2JLus1j/PYaGi3yitaDALkJ9rI99poCxlqWg2VzUHawlZZXqL1maxssd7rmlZDrtdGjkfIiLfqKmkKU9Z8+H0d57XKS31WuQ0oiHwnBChrtpb5AoYJke9qsluobbW+36W+MFNSrPVT3EJdu6G61VDdEsZpF8Z5rOfxBQzlzdb/ry0YpiDJzvhEGzaxPgelke99QeLhuqojz1Hdan2+cz3Wa2mK7CeqWqx9Tp7XRp5XaPQbLp3uwjaEy7IsX758vTFmUbRlA0lwHxpjFvQo+8gYc8KgIzoKInIKcJsx5uzI4x8CGGP+p59tioFFkXP4olq0aJFZt27doOO64e8b+OeHhwC464oT+Ou7B3hnbw03nj2dby2fwtMfHeIPq/ewcnYO3z1zKhWN7Vz0h7Ucqm8FIMPrwmW30dQe5J4vLSLV4+SXL+5gT5WPUyal8+VTCmlsC7DhYD37a1rIT42nqqmdF7aUUdHYTobXxfzxKRysbWVHRRM2OXxcsEO80870nERK61upbGoHwGGD8WkecpPjSPO4qG32c6i+laqmdvJS4pk1LonxaQl8XNZEcU0z+2uayfS6mZzlZUJ6AnurmilraONgrTXWKDneyaRMD0lxTnZV+qhqaqc1EMImkJ+aQG5yHDsrmqhvDdDxUUt0O5iabfVy76rw0dRu/VDwuOxMzPSQmxzPnkoftS1+6lsCOG0wKTORmeOSaPEHOVDbyr5qH6GwIT81gdl5yeSlxLOuuJaayOvJ9LrJT41nSpaXGp+fKl87e6p82EXIi5S7HXb2VPoobWilsrGdCekJTMnykpnoZlNJA/Utfg7UtpDhdTM500thRgJ7qpqpamrnQG0LxhhykuLITYmnttlPdVN752tJdMGUnBTaAmFKalsOl7sdFGZ4cNqFA7Ut1Db7CRurfEq2F2Ngb5X1nhgDLruN/LR4kuKcHKhtoaE1QChscDtsTMr0kpcSx7bSRkob2gBw2oVJGV7yUuPZXna43GETCjOs//vHZU1U+9o7ywvSEshKcrO1pJYmP73W317eRFXk8+N22CjKTWJcchwfHqijoTVAW8DaMU7JSiQ53sGeqmaa2qxyl91GYUYCaR4Xe6uaqW8J4A+FcTlsTMrwkJMcx96qZhrbAtS3BKz6cxLJS41nXXFd5/oel51pOYlkJ8ax4WA9dS1+2oNhnDaYkp3ExIwEDtW10tAa4EBtC067jSlZXiZmeCipa6Xa105JXStOuzA+LYHCdA++9iBlDa0crG3FJjAuJZ7CdA8GQ0ldKwdrWwgbGJccx4R0D8nxToprmjlU10pTe5DsJDeF6R7yUuLZU2V99ksb2kjzuJiQnsCEtATKGtqoafazt8qHx+UgLzWe+HALnqRUShta2V/Tgl2EgnQrpjSPk50Vvs7vbIbXFXkdXnZVNFHla2d/TQupCU6mZiUyJdtLXbP1Od1bZV3sZVKmh8mZXpx2G7sqmyipa6WuxU9uUhyTs7zkJMXx0cF6yhva8LUHSU1wMj7N+q52vFcVje2d38eJGV4OlFbQZktgX00z4bBhQnoC07ITcdpt7Kxo6nxPMrxuZuQmkpUYx9bSBmqb/VQ2WXVNzvIyPi2BHeVN1PjaqWsJEOe08fr3l5GbHD/ofbGIHH2CE5HPY3VJnga81WVREhA0xpw56IiOgog4sI7/nQEcAj4ArjDGbO2yTg5QYYwxIrIYeAKYYPrJ3kNNcIU3Pxe1fOv/OxuPO/rYnb1VPu54ZSfTsxO5ckkhDS0Brrj3XQ7WWkkvJcHJiYVpvLWrirbA4S7ClARn55f/tCkZTMr0UNbQxu5KH+leF+fOyeWSheM5WNfClkMNlNa3MTc/mUWFqbgddsJhQ8gY/MEw7699i+XLlw/6dXcIhQ02gR5zlBIOG6p97STFO4lzHm6ZNrQE2FfTTE5SHNlJ7m7bVfvaMcZK+l3LjTE0+0N8ECXmUNj6dWyzDe8F+cJhE/U5/EGrZeC0H+7lN8ZQ2+wnzmnng3fWsGzZss5ltc1+7CIkxTu6vcamNithJcc7u5U3tgXwB8OkJriwd3l+X3uQtkCoV3ljW4C2QIi0BBeOLjE1tAZoD4RI9bi6xdrQEqA92L189erVzF98Kq2BEOkeNy7H4fXrmv20BEJkJ7q71R8Mhan2+cnwdn9efzBMfYufdK+7W5yt/hDN/mCv+I0x1LcESI53dnu/2wIhWv2hXuWBUJi2QIgP3lnDih6fjfZgCIfN1q1+gBZ/kDiHvdf/sy0Qwmnvvb4/GMZuk17lHV3bPcs73o+u70O08tWrV3d+Nvr6fPVXVyAU7va/7NBxqKRnfcYYQmHTq66O/ULPuowxBMMGh006P5MdMQdCYWzS+z0Jhw2BcBi3o3dvVFsg1G1f0LF+ayBEvLP3/+No9Zfg+htFuRYoAzKA27uUNwGbhhTRUTDGBEXk28BLgB243xizVUSuiyz/I3Ax8A0RCQKtwOX9JbfhcOrkdL531vQ+kxvApEwvd11xuDGcFOfkpe8u5Y+r9+Cw2/jyKRNISXBR3+Ln6Y8OkeZ1s2RyOuleN772IE67RP0AdZic6WVyZu/xPzabYENw2m29EtJgRftydzxXVlJcr/LkBCfzE1KibpPhdUctFxG8bkfUmPt6/mOtry9f151/BxEhvY/XkuZxRS1PjHNGLU/qo9zrduCN8hlLinNG3SY53gnxUcoTnEDv8pQEFylRnjfV4yI1SrnDbiMnuff/2+WwRf0cxLvsxLt6f4ZFhNQo71Gc095r5wjWDwun3Ra1a6uv70iCK/p3M1r9EP1/DP1/9qIlpP7K+9u597VNtOTWX10igsPee1nHfiHa+s4o6x/pud226O9jtPfXZpN+95XHSp/PYIzZD+wHTulaHhm2fznw1+ENrVssva5SEElsHffvAu4aqXgAvrlsMnev3tP5+NpPTWLhhGi7gP4luBzccNb0bmUpCS6uWjKxW1m0nZpSSqm+9Xeid5KI/FBE7hKRs8TybWAvcOnIhRibfrCyiC/OOPyLM9qvWKWUUqOnv2bBw0Ad8A5wDXAj4AIuMMZsGP7QYl/XVnx6H11QSimlRkd/CW6SMWYOgIjcC1QDBcaYphGJ7DjQtcs7KcpxDqWUUqOnvxO9Ax13jDEhYJ8mt+66Jri+DlQrpZQaHf214OaJSGPkvgDxkceCNclJ0rBHF+NGaiSfUkqpo9ffKEptkhyBc0BX01NKKTUadBc9BG79CaCUUjFLE9wQuCLDKPs6IVQppdTo0T3zEHS04Fx9nN2vlFJq9OieeQg6WnBubcEppVTM0T3zEHQMMtEuSqWUij26Zx4CV+TdO7EwbXQDUUop1YvO4DsEKXE2nrjuFGbnJY92KEoppXrQBDdEi7T1ppRSMUm7KJVSSo1JfV7Re6wTkSqs690NRQbWJNTHE415ZGjMI0NjHhmxHPMEY0xmtAWf2AR3LIjIur4ulR6rNOaRoTGPDI15ZByPMYN2USqllBqjNMEppZQakzTBDc09ox3AIGjMI0NjHhka88g4HmPWY3BKKaXGJm3BKaWUGpM0wQ2CiKwUkR0isltEbh7teKIRkfEi8rqIfCwiW0Xk+kh5moi8IiK7In9TRzvWnkTELiIficiqyOOYjllEUkTkCRHZHnm/TzkOYv6PyOdii4g8JiJxsRaziNwvIpUisqVLWZ8xisgPI9/JHSJydgzF/KvIZ2OTiDwlIimxHnOXZd8XESMiGV3KRj3mgdIEd5RExA78HjgHmAl8XkRmjm5UUQWB7xljZgAnA9+KxHkz8KoxZirwauRxrLke+LjL41iP+TfAi8aYImAeVuwxG7OI5AH/DiwyxswG7MDlxF7MfwFW9iiLGmPks305MCuyzd2R7+pI+wu9Y34FmG2MmQvsBH4IMR8zIjIe+DRwoEtZrMQ8IJrgjt5iYLcxZq8xxg88DlwwyjH1YowpM8Z8GLnfhLXTzcOK9cHIag8CF45KgH0QkXzgPODeLsUxG7OIJAFLgfsAjDF+Y0w9MRxzhAOIFxEHkACUEmMxG2PeBGp7FPcV4wXA48aYdmPMPmA31nd1REWL2RjzsjEmGHn4LpAfuR+zMUf8L/ADoOtAjZiIeaA0wR29POBgl8clkbKYJSKFwAnAe0C2MaYMrCQIZI1iaNHcifWlCncpi+WYJwFVwAORbtV7RcRDDMdsjDkE/Brrl3kZ0GCMeZkYjrmLvmI8Xr6XXwVeiNyP2ZhF5LPAIWPMxh6LYjbmaDTBHT2JUhazQ1FFxAs8CXzXGNM42vH0R0TOByqNMetHO5aj4AAWAH8wxpwANDP6XXv9ihy3ugCYCIwDPCLyxdGNashi/nspIj/COnTw146iKKuNeswikgD8CPhJtMVRykY95r5ogjt6JcD4Lo/zsbp3Yo6IOLGS21+NMf+MFFeISG5keS5QOVrxRbEE+KyIFGN1/a4QkUeI7ZhLgBJjzHuRx09gJbxYjvlMYJ8xpsoYEwD+CZxKbMfcoa8YY/p7KSJXAucDXzCHz82K1ZgnY/342Rj5LuYDH4pIDrEbc1Sa4I7eB8BUEZkoIi6sA67PjnJMvYiIYB0X+tgYc0eXRc8CV0buXwk8M9Kx9cUY80NjTL4xphDrfX3NGPNFYjvmcuCgiEyPFJ0BbCOGY8bqmjxZRBIin5MzsI7RxnLMHfqK8VngchFxi8hEYCrw/ijE14uIrARuAj5rjGnpsigmYzbGbDbGZBljCiPfxRJgQeSzHpMx98kYo7ejvAHnYo2G2gP8aLTj6SPG07C6DjYBGyK3c4F0rNFnuyJ/00Y71j7iXwasityP6ZiB+cC6yHv9NJB6HMT8/4DtwBbgYcAdazEDj2EdIwxg7WSv7i9GrG61PcAO4JwYink31nGrju/hH2M95h7Li4GMWIp5oDedyUQppdSYpF2USimlxiRNcEoppcYkTXBKKaXGJE1wSimlxiTHaAegPnnWr1+f5XA47gVmoz+y1PEvDGwJBoPXLFy4MBbPHfzE0gSnRpzD4bg3JydnRmZmZp3NZtNhvOq4Fg6HpaqqamZ5efm9wGdHOx51mP56VqNhdmZmZqMmNzUW2Gw2k5mZ2YDVI6FiiCY4NRpsmtzUWBL5POv+NMboP0R9IiUkJJwAsGPHDldcXNyCoqKimR23u+66K71jvbfffjteRBY++eSTSX3Vdf/996dOmTJlls1mW/jmm28mdJT3rPuKK64oiLb9U089lTRr1qwZ06ZNmzlr1qwZzz77bGLPdVasWDFl6tSpszoet7a2ynnnnTepoKBg9ty5c4t27Njhilb3DTfcMC4rK2tuUVHRzMmTJ8/605/+lAZw9dVXj//pT3/aebWA0047bepll102oePxtddem/+9730vtyP25OTk+Xl5eXOKiopmnnrqqdN6PsdPfvKT7K5leXl5c8rKyhwAIrLwwgsvnNixLBAIkJqaOm/58uVT+npPAd58882Eq666anx/6/TnzjvvTJ82bdrMadOmzZw6deqsRx55JGWwdXV1+umnT6muro7Za6Cpw/QYnPrEGz9+fPv27du3RVv28MMPpy9YsMD36KOPpl100UVRr8Ywf/781ieffHL3tddeW3g0dXfIysoKPPfcc7sLCwsDH3zwQdx55503rbKyclPH8gcffDDF4/GEum7zm9/8JiM5OTl44MCBLffcc0/qDTfckP/cc8/tjVb/ddddV/HTn/60YvPmze5TTjll5lVXXVW3ZMkS3xNPPJEKVIZCIerq6hw+n69zp/3BBx9477jjjoO33357GcBFF11UeP755zd85StfqevvtUQTHx8f3rFjR7zP5xOv12ueeuqppOzs7MCRtlu6dGnL0qVLW460XjR79uxx3n777bkbNmz4OD09PdTQ0GDrSLhD9cYbb+w+FvWo4actOKX6EA6HWbVqVepDDz1U/NZbbyW1tLREu1QICxYsaJs3b177YJ9nyZIlrYWFhQGAhQsXtvn9fltra6sANDQ02H77299m33bbbWVdt1m1alXKV7/61RqAr3zlK3Vr165NDIfDvSvvYs6cOe1xcXHh6upq+4oVK3zr16/3Aqxfvz5++vTprR6PJ1RVVWVvbW2VPXv2xJ166qmDSi7RnHHGGQ3/+Mc/UgAee+yxtIsuuqjzApuvv/56wgknnFA0Y8aMmSeccELRxo0b3ZHXmNjRyrvhhhvGXXLJJYWLFy+enp+fP+dnP/tZZ+vz7rvvTpszZ86MSCt5QjAYpKyszOnxeMLJyckhgOTk5HBRUZEfYOvWre5PfepTU2fNmjVj4cKF0z/66KM4sJL4F77whYKTTjppWn5+/pznnnvOe8kllxROmjRp1kUXXVTY8XxdW6cqtuk/SY2qG5/YOH5neVPCkdccuGk5iS2/unjewSOvaTl48KC7qKhoZsfjO++888DKlSt9r7zyinf8+PHts2bNaj/ppJOa/vGPfyRfeeWV9UcTS0lJiWvGjBkzvV5v6L/+678OrVy50tff+g8++GDqzJkzW+Lj4w3ADTfckHf99ddXeL3ebtmroqLCNXHiRD+A0+nE6/WGKioqHLm5ucFo9QKsWbMmYcKECW15eXlBAIfDYXbt2uV64403PCeffHLzoUOHnK+99po3NTU1OH369Na4uLhjdpz0S1/6Uu2tt96ae9lll9V//PHHCVdffXXN2rVrvQDz5s1re//997c7nU6efvrpxB/84Af5L7300p6edezevTtu7dq1O+rr6+0zZsyYfeONN1Zt3brV/cQTT6StW7duu9vtNl/84hcL/vjHP6Zfd911NRkZGYHx48fPWbJkSdO//du/1V1xxRUNANdcc82Ee+65Z/+cOXPaX3vtNc83vvGNgnfffXcnQENDg+Odd97Z+eijj6ZcdtllU1977bXtCxcubJ07d+6MtWvXxp966qmtx+o9UcNPE5z6xOurG/GRRx5Ju/jii2sBLr/88tpHHnkk/WgSXEFBQWDfvn2bcnJyQm+99VbCJZdcMmXbtm1b0tLSoja11q1bF/eTn/wk78UXX9wFsHbt2vh9+/a577vvvoM9j7FFmyRdRKImpD/+8Y/ZDz30UGZJSYnrySef3NVRvnDhQt/rr7/ueeedd7w33nhjxYEDB1xvv/22Jzk5ObR48eJ+E/FAnrdr+UknndRaUlLi/vOf/5x25plnNnRdr7a21n7ZZZdNLC4ujhMREwgEoraUzzrrrPr4+HgTHx8fTEtLC5SUlDhefPHFxC1btiTMmzdvBkBbW5stKysr6HA4ePPNN3e98cYbCS+//HLSzTffPH7dunWeW2+9tfyjjz7yXnLJJZM76vX7/Z3Pd95559XbbDYWLFjQkp6eHli8eHErwLRp01r37Nnj1gR3fNEEp0bV0bS0RlIwGOSFF15IfeWVV1LuuOOOXGMM9fX1jrq6Otu1115bsGXLloTs7Gx/f8djIjvjEMCnPvWploKCgvYtW7bEFRcXu37+85+PA7jnnnuKly5d2rJnzx7nxRdfPOW+++7bN2vWrHaAt956y7tly5aEvLy8OcFgUGprax2LFy+e/v777+/Iycnx79u3zzV58uRAIBDA5/PZs7KyQt/5znfyXnnllWSAjqTdcQzuwQcfTLn22msnfvrTn96ckJBgTjnlFN/atWu927dvjz/xxBNbJ02a5L/zzjuzvV5v6Ctf+Up1X6/rf/7nfzIffPDBTIAXX3xxV3p6erCsrKxbAm5ubrZnZGR0O264cuXK+ltvvXX8yy+/vKOysrJz33PTTTflnX766U2vvPLKnh07drhWrFgxnSjcbndnwrTb7QSDQTHGyCWXXFLz+9///lDP9W02G8uXL29Zvnx5yznnnNN4zTXXFN5yyy3liYmJwb6Oi3a0Wu12Oy6Xy3StKxgMRk28KnbpMTilonjmmWeSioqKWsrLyzcdOnRoc2lp6eaVK1fWPfrooylPPPFE8fbt27cdabBBaWmpIxi0egy3bdvmKi4udk+fPr39y1/+cv327du3bd++fdvSpUtbqqur7eeee+7U2267reSss85q7tj+pptuqqqsrNx06NChzW+++eb2wsLC9vfff38HWC2N+++/Px3ggQceSD3llFOabDYbv/vd7w511N0zniuvvLJ+zpw5zb///e/TAU4//XTfv/71r5SUlJSQw+EgOzs71NjYaP/oo4+8y5cvb+65fYcf/vCHVR3PUVhYGDjjjDN8L730UnJdXZ0NrEExRUVFLQ5H99/P3/jGN6q/973vlXa0ijo0Njba8/Pz/QB/+tOfMvp7T3tauXJl46pVq1IPHTrkAKioqLDv3LnTVVxc7FyzZk1n1/e6desS8vLy/GlpaeH8/Hz//fffnwrWcdZ33nkn/mieUx0/NMGpT7yOY3Adt5/97GdZjz76aNpnP/vZ+q7rXXTRRXV/+9vf0ntu/9BDD6VkZ2fP3bBhg+dzn/vc1NNOO20qwMsvv+wtKiqaNX369JkXX3zx5DvvvHN/dnZ2qOf2v/zlL7MOHDjg/sUvfjGuI4aOHXZfrr/++uq6ujpHQUHB7N/97nc5v/71r0sG8lpvu+22st///vc5oVCIxYsXt9bX1zsWLVrU2R1ZVFTU6vV6Q/0dy+vppJNOar322msrTz755KKioqKZ99xzT+b9999f3HO9yZMnB3784x/3msrqpptuKr/tttvyFyxYUBQK9Xp7+rVw4cK2W2655dAZZ5wxbdq0aTNXrFgx7eDBg06/3y/f//738ydOnDirqKho5hNPPJF61113HQR47LHH9j7wwAMZ06dPnzl16tRZTz75ZMpRPak6bugFT9WI27hxY/G8efP67AJT6ni0cePGjHnz5hWOdhzqMG3BKaWUGpM0wSmllBqTNMEppZQakzTBqdEQDofDOuRajRmRz3P/U8moEacJTo2GLVVVVcma5NRYELkeXDKwZbRjUd3pid5qxAWDwWvKy8vvLS8v1yt6q7Gg84reox2I6k5PE1BKKTUm6a9npZRSY5ImOKWUUmOSJjillFJjkiY4pZRSY5ImOKWUUmPS/w/MKQoSZuVs1QAAAABJRU5ErkJggg==\n", + "image/png": "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\n", "text/plain": [ - "
" + "
" ] }, - "metadata": { - "needs_background": "light" - }, + "metadata": {}, "output_type": "display_data" }, { "data": { "text/plain": [ - "([
,
],\n", - " [array([,\n", - " ,\n", - " ,\n", - " ], dtype=object),\n", - " array([,\n", - " ,\n", - " ], dtype=object)])" + "([
,
],\n", + " [array([,\n", + " ,\n", + " ,\n", + " ], dtype=object),\n", + " array([,\n", + " ,\n", + " ], dtype=object)])" ] }, "execution_count": 11, @@ -702,7 +684,7 @@ "# Define Plot cases \n", "cases = {}\n", "cases['Baseline'] = ['Wind1VelX', 'BldPitch1', 'GenTq', 'RotSpeed']\n", - "cases['Rotor Performance'] = ['RtVAvgxh', 'RtTSR', 'RtAeroCp']\n", + "cases['Rotor Performance'] = ['RtVAvgxh', 'RtTSR', 'RtFldCp']\n", "\n", "# Plot, woohoo!\n", "op.plot_fast_out(fast_out, cases)" @@ -762,6 +744,13 @@ "I would finally like to note that there has been a lot of work from a lot of very smart (and really great) people that has gone into all of this, some of which are acknowledged on the [ROSCO toolbox](www.github.com/nrel/ROSCO_toolbox) and [ROSCO](www.github.com/nrel/ROSCO_toolbox) github pages. " ] }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [] + }, { "cell_type": "code", "execution_count": null, @@ -773,9 +762,9 @@ "metadata": { "celltoolbar": "Slideshow", "kernelspec": { - "display_name": "rosco-env", + "display_name": "rosco-env3", "language": "python", - "name": "rosco-env" + "name": "rosco-env3" }, "language_info": { "codemirror_mode": { @@ -787,7 +776,7 @@ "name": "python", "nbconvert_exporter": "python", "pygments_lexer": "ipython3", - "version": "3.8.13" + "version": "3.10.8" } }, "nbformat": 4, diff --git a/Examples/example_02.py b/Examples/example_02.py deleted file mode 100644 index a513ddd9..00000000 --- a/Examples/example_02.py +++ /dev/null @@ -1,37 +0,0 @@ -''' ------------ Example_02 -------------- -Load a turbine model from saved pickle, make a quick cp plot -------------------------------------- - -In this example: - - Load a turbine from a saved pickle - - Plot Cp Surface -''' - -# Python modules -import os -import matplotlib.pyplot as plt -# ROSCO toolbox modules -from ROSCO_toolbox import turbine as ROSCO_turbine - -this_dir = os.path.dirname(os.path.abspath(__file__)) -example_out_dir = os.path.join(this_dir,'examples_out') -if not os.path.isdir(example_out_dir): - os.makedirs(example_out_dir) - -# Initialize a turbine class -- Don't need to instantiate! -turbine = ROSCO_turbine.Turbine - -# Load quick from python pickle -turbine = turbine.load(os.path.join(example_out_dir,'01_NREL5MW_saved.p')) - -# plot rotor performance -print('Plotting Cp data') -turbine.Cp.plot_performance() - - - -if False: - plt.show() -else: - plt.savefig(os.path.join(example_out_dir,'02_NREL5MW_Cp.png')) \ No newline at end of file diff --git a/Examples/Cp_Ct_Cq.NREL5MW.txt b/Examples/example_inputs/Cp_Ct_Cq.NREL5MW.txt similarity index 100% rename from Examples/Cp_Ct_Cq.NREL5MW.txt rename to Examples/example_inputs/Cp_Ct_Cq.NREL5MW.txt diff --git a/Examples/Example_OL_Input.dat b/Examples/example_inputs/Example_OL_Input.dat similarity index 100% rename from Examples/Example_OL_Input.dat rename to Examples/example_inputs/Example_OL_Input.dat diff --git a/Examples/run_examples.py b/Examples/test_examples.py similarity index 73% rename from Examples/run_examples.py rename to Examples/test_examples.py index 9486b3ee..89d9e6c9 100644 --- a/Examples/run_examples.py +++ b/Examples/test_examples.py @@ -4,25 +4,24 @@ import runpy all_scripts = [ - 'example_01', - 'example_02', - 'example_03', - 'example_04', - 'example_05', - 'example_06', - 'example_07', - 'example_08', - 'example_09', - 'example_10', - 'example_11', - 'example_12', - 'example_13', - 'example_14', - 'example_15', - 'example_16', - 'example_17', # NJA: only runs on unix in CI - 'example_18', - 'example_19', + '01_turbine_model', + '02_ccblade', + '03_tune_controller', + '04_simple_sim', + '05_openfast_sim', + '06_peak_shaving', + '07_openfast_outputs', + '08_run_turbsim', + '09_distributed_aero', + '10_linear_params', + '11_robust_tuning', + '12_tune_ipc', + '14_open_loop_control', + '15_pass_through', + '16_external_dll', + '17_zeromq_interface', + '18_pitch_offsets', # NJA: only runs on unix in CI + '19_update_discon_version', 'update_rosco_discons', ] diff --git a/ROSCO_testing/ROSCO_testing.py b/ROSCO_testing/ROSCO_testing.py index d65eaa3a..55c5d60f 100644 --- a/ROSCO_testing/ROSCO_testing.py +++ b/ROSCO_testing/ROSCO_testing.py @@ -47,7 +47,6 @@ def __init__(self, **kwargs): self.rosco_path = glob.glob(os.path.join(os.path.dirname(os.path.realpath(__file__)),'../ROSCO/build/libdiscon.*'))[0] except: print('No compiled ROSCO version found, please provide ROSCO_testing.rosco_path.') - self.dev_branch = True # openfast dev branch? self.debug_level = 2 # debug level. 0 - no outputs, 1 - minimal outputs, 2 - all outputs self.overwrite = False # overwrite existing files? self.cores = 4 # number of cores to use @@ -114,8 +113,7 @@ def ROSCO_Test_lite(self, more_case_inputs={}, U=[]): else: WindSpeeds = [5, 8, 11, 14, 17] - fastRead = InputReader_OpenFAST( - FAST_ver=self.FAST_ver, dev_branch=self.dev_branch) + fastRead = InputReader_OpenFAST() fastRead.FAST_InputFile = self.FAST_InputFile # FAST input file (ext=.fst) # Path to fst directory files fastRead.FAST_directory = self.FAST_directory @@ -215,7 +213,6 @@ def ROSCO_Test_lite(self, more_case_inputs={}, U=[]): fastBatch.FAST_InputFile = self.FAST_InputFile # FAST input file (ext=.fst) fastBatch.FAST_directory = self.FAST_directory # Path to fst directory files fastBatch.debug_level = self.debug_level - fastBatch.dev_branch = self.dev_branch fastBatch.case_list = case_list fastBatch.case_name_list = case_name_list @@ -270,8 +267,7 @@ def ROSCO_Test_heavy(self, more_case_inputs={}, U=[]): else: WindSpeeds = [[4, 6, 8, 10, 12, 14, 16, 18, 20, 22, 24], [8.88, 12.88]] - fastRead = InputReader_OpenFAST( - FAST_ver=self.FAST_ver, dev_branch=self.dev_branch) + fastRead = InputReader_OpenFAST() fastRead.FAST_InputFile = self.FAST_InputFile # FAST input file (ext=.fst) # Path to fst directory files fastRead.FAST_directory = self.FAST_directory @@ -380,7 +376,6 @@ def ROSCO_Test_heavy(self, more_case_inputs={}, U=[]): fastBatch.FAST_InputFile = self.FAST_InputFile # FAST input file (ext=.fst) fastBatch.FAST_directory = self.FAST_directory # Path to fst directory files fastBatch.debug_level = self.debug_level - fastBatch.dev_branch = self.dev_branch fastBatch.case_list = case_list fastBatch.case_name_list = case_name_list @@ -555,7 +550,6 @@ def print_results(self,outfiles): rt.namebase = 'IEA-15MW' # Base name for FAST files rt.FAST_exe = 'openfast' # OpenFAST executable path rt.Turbsim_exe = 'turbsim' # Turbsim executable path - rt.FAST_ver = 'OpenFAST' # FAST version # path to compiled ROSCO controller if platform.system() == 'Windows': rt.rosco_path = os.path.join(os.getcwd(), '../ROSCO/build/libdiscon.dll') @@ -563,14 +557,12 @@ def print_results(self,outfiles): rt.rosco_path = os.path.join(os.getcwd(), '../ROSCO/build/libdiscon.dylib') else: rt.rosco_path = os.path.join(os.getcwd(), '../ROSCO/build/libdiscon.so') - rt.dev_branch = True # dev branch of Openfast? rt.debug_level = 2 # debug level. 0 - no outputs, 1 - minimal outputs, 2 - all outputs rt.overwrite = True # overwite fast sims? rt.cores = 4 # number of cores if multiprocessings rt.mpi_run = False # run using mpi rt.mpi_comm_map_down = [] # core mapping for MPI rt.outfile_fmt = 2 # 1 = .txt, 2 = binary, 3 = both - rt.dev_branch= 'True' # Setup turbine rt.Turbine_Class = 'I' diff --git a/ROSCO_testing/run_Testing.py b/ROSCO_testing/run_Testing.py index ef201d42..f10c0d01 100644 --- a/ROSCO_testing/run_Testing.py +++ b/ROSCO_testing/run_Testing.py @@ -91,7 +91,6 @@ def run_testing(turbine2test, testtype, rosco_binaries=[], discon_files=[], **kw rt_kwargs['wind_dir'] = os.path.join('/scratch/dzalkind/ROSCO_testing','wind','IEA-15_heavy') # OpenFAST executable path rt_kwargs['Turbsim_exe']= 'turbsim' # Turbsim executable path rt_kwargs['FAST_ver'] = 'OpenFAST' # FAST version - rt_kwargs['dev_branch'] = True # dev branch of Openfast? rt_kwargs['debug_level']= 2 # debug level. 0 - no outputs, 1 - minimal outputs, 2 - all outputs rt_kwargs['overwrite'] = False # overwite fast sims? rt_kwargs['cores'] = 36 # number of cores if multiprocessing diff --git a/ROSCO_toolbox/ofTools/case_gen/CaseLibrary.py b/ROSCO_toolbox/ofTools/case_gen/CaseLibrary.py index a637885e..aa4d1ce4 100644 --- a/ROSCO_toolbox/ofTools/case_gen/CaseLibrary.py +++ b/ROSCO_toolbox/ofTools/case_gen/CaseLibrary.py @@ -54,7 +54,7 @@ def load_tuning_yaml(tuning_yaml): cp_filename = os.path.join(tune_case_dir,path_params['FAST_directory'],path_params['rotor_performance_filename']) turbine.load_from_fast(path_params['FAST_InputFile'], \ os.path.join(tune_case_dir,path_params['FAST_directory']), \ - dev_branch=True,rot_source='txt',\ + rot_source='txt',\ txt_filename=cp_filename) return turbine, controller, cp_filename @@ -395,7 +395,7 @@ def sweep_rated_torque(start_group, **control_sweep_opts): cp_filename = os.path.join(tune_case_dir,path_params['FAST_directory'],path_params['rotor_performance_filename']) turbine.load_from_fast(path_params['FAST_InputFile'], \ os.path.join(tune_case_dir,path_params['FAST_directory']), \ - dev_branch=True,rot_source='txt',\ + rot_source='txt',\ txt_filename=cp_filename) controller.tune_controller(turbine) @@ -479,7 +479,7 @@ def sweep_ps_percent(start_group, **control_sweep_opts): # make default controller, turbine objects for ROSCO_toolbox turbine = ROSCO_turbine.Turbine(turbine_params) - turbine.load_from_fast( path_params['FAST_InputFile'],path_params['FAST_directory'], dev_branch=True) + turbine.load_from_fast( path_params['FAST_InputFile'],path_params['FAST_directory']) controller = ROSCO_controller.Controller(controller_params) @@ -523,7 +523,7 @@ def test_pitch_offset(start_group, **control_sweep_opts): # # make default controller, turbine objects for ROSCO_toolbox # turbine = ROSCO_turbine.Turbine(turbine_params) -# turbine.load_from_fast( path_params['FAST_InputFile'],path_params['FAST_directory'], dev_branch=True) +# turbine.load_from_fast( path_params['FAST_InputFile'],path_params['FAST_directory']) # controller = ROSCO_controller.Controller(controller_params) diff --git a/ROSCO_toolbox/ofTools/case_gen/run_FAST.py b/ROSCO_toolbox/ofTools/case_gen/run_FAST.py index 17944e46..c5b33519 100644 --- a/ROSCO_toolbox/ofTools/case_gen/run_FAST.py +++ b/ROSCO_toolbox/ofTools/case_gen/run_FAST.py @@ -93,10 +93,12 @@ def run_FAST(self): path_params['FAST_directory'], path_params['rotor_performance_filename'] ) - turbine.load_from_fast(path_params['FAST_InputFile'], \ - os.path.join(tune_yaml_dir,path_params['FAST_directory']), \ - dev_branch=True,rot_source='txt',\ - txt_filename=cp_filename) + turbine.load_from_fast( + path_params['FAST_InputFile'], + os.path.join(tune_yaml_dir,path_params['FAST_directory']), + rot_source='txt', + txt_filename=cp_filename + ) # tune base controller defined by the yaml controller.tune_controller(turbine) diff --git a/ROSCO_toolbox/ofTools/fast_io/FAST_reader.py b/ROSCO_toolbox/ofTools/fast_io/FAST_reader.py index 9a9719db..2f809f3b 100644 --- a/ROSCO_toolbox/ofTools/fast_io/FAST_reader.py +++ b/ROSCO_toolbox/ofTools/fast_io/FAST_reader.py @@ -4,7 +4,7 @@ from functools import reduce import operator -from ROSCO_toolbox.ofTools.fast_io.FAST_vars import FstModel +from ROSCO_toolbox.ofTools.fast_io.FAST_vars_out import FstOutput from ROSCO_toolbox.utilities import read_DISCON, load_from_txt from ROSCO_toolbox import turbine as ROSCO_turbine ROSCO = True @@ -18,8 +18,6 @@ def readline_filterComments(f): read = False return line - - def fix_path(name): """ split a path, then reconstruct it using os.path.join """ name = re.split("\\\|/", name) @@ -48,7 +46,6 @@ def float_read(text): except: return str(text) - def int_read(text): # return int with error handing for "default" values if 'default' in text.lower(): @@ -59,30 +56,34 @@ def int_read(text): except: return str(text) +class InputReader_OpenFAST(object): + """ OpenFAST input file reader """ -class InputReader_Common(object): - """ Methods for reading input files that are (relatively) unchanged across FAST versions.""" + def __init__(self): - def __init__(self, **kwargs): - - self.FAST_ver = 'OPENFAST' self.FAST_InputFile = None # FAST input file (ext=.fst) self.FAST_directory = None # Path to fst directory files self.path2dll = None # Path to dll file - self.fst_vt = FstModel - - # Optional population class attributes from key word arguments - for (k, w) in kwargs.items(): - try: - setattr(self, k, w) - except: - pass - - super(InputReader_Common, self).__init__() - - def read_yaml(self): - f = open(self.FAST_yamlfile, 'r') - self.fst_vt = yaml.load(f) + self.fst_vt = {} + self.fst_vt['Fst'] = {} + self.fst_vt['outlist'] = FstOutput + self.fst_vt['ElastoDyn'] = {} + self.fst_vt['ElastoDynBlade'] = {} + self.fst_vt['ElastoDynTower'] = {} + self.fst_vt['InflowWind'] = {} + self.fst_vt['AeroDyn15'] = {} + self.fst_vt['AeroDyn14'] = {} + self.fst_vt['AeroDynBlade'] = {} + self.fst_vt['AeroDynTower'] = {} + self.fst_vt['AeroDynPolar'] = {} + self.fst_vt['ServoDyn'] = {} + self.fst_vt['DISCON_in'] = {} + self.fst_vt['HydroDyn'] = {} + self.fst_vt['MoorDyn'] = {} + self.fst_vt['SubDyn'] = {} + self.fst_vt['MAP'] = {} + self.fst_vt['BeamDyn'] = {} + self.fst_vt['BeamDynBlade'] = {} def set_outlist(self, vartree_head, channel_list): """ Loop through a list of output channel names, recursively set them to True in the nested outlist dict """ @@ -109,325 +110,6 @@ def loop_dict(vartree, search_var, branch): var = var.replace(' ', '') loop_dict(vartree_head, var, []) - def read_ElastoDynBlade(self): - # ElastoDyn v1.00 Blade Input File - # Currently no differences between FASTv8.16 and OpenFAST. - if self.FAST_ver.lower() == 'fast7': - blade_file = os.path.join(self.FAST_directory, self.fst_vt['Fst7']['BldFile1']) - else: - blade_file = os.path.join(self.FAST_directory, self.fst_vt['ElastoDyn']['BldFile1']) - - f = open(blade_file) - # print blade_file - f.readline() - f.readline() - f.readline() - if self.FAST_ver.lower() == 'fast7': - f.readline() - - # Blade Parameters - self.fst_vt['ElastoDynBlade']['NBlInpSt'] = int(f.readline().split()[0]) - if self.FAST_ver.lower() == 'fast7': - self.fst_vt['ElastoDynBlade']['CalcBMode'] = bool_read(f.readline().split()[0]) - self.fst_vt['ElastoDynBlade']['BldFlDmp1'] = float_read(f.readline().split()[0]) - self.fst_vt['ElastoDynBlade']['BldFlDmp2'] = float_read(f.readline().split()[0]) - self.fst_vt['ElastoDynBlade']['BldEdDmp1'] = float_read(f.readline().split()[0]) - - # Blade Adjustment Factors - f.readline() - self.fst_vt['ElastoDynBlade']['FlStTunr1'] = float_read(f.readline().split()[0]) - self.fst_vt['ElastoDynBlade']['FlStTunr2'] = float_read(f.readline().split()[0]) - self.fst_vt['ElastoDynBlade']['AdjBlMs'] = float_read(f.readline().split()[0]) - self.fst_vt['ElastoDynBlade']['AdjFlSt'] = float_read(f.readline().split()[0]) - self.fst_vt['ElastoDynBlade']['AdjEdSt'] = float_read(f.readline().split()[0]) - - # Distrilbuted Blade Properties - f.readline() - f.readline() - f.readline() - self.fst_vt['ElastoDynBlade']['BlFract'] = [None] * self.fst_vt['ElastoDynBlade']['NBlInpSt'] - self.fst_vt['ElastoDynBlade']['PitchAxis'] = [None] * self.fst_vt['ElastoDynBlade']['NBlInpSt'] - self.fst_vt['ElastoDynBlade']['StrcTwst'] = [None] * self.fst_vt['ElastoDynBlade']['NBlInpSt'] - self.fst_vt['ElastoDynBlade']['BMassDen'] = [None] * self.fst_vt['ElastoDynBlade']['NBlInpSt'] - self.fst_vt['ElastoDynBlade']['FlpStff'] = [None] * self.fst_vt['ElastoDynBlade']['NBlInpSt'] - self.fst_vt['ElastoDynBlade']['EdgStff'] = [None] * self.fst_vt['ElastoDynBlade']['NBlInpSt'] - if self.FAST_ver.lower() == 'fast7': - self.fst_vt['ElastoDynBlade']['GJStff'] = [None] * self.fst_vt['ElastoDynBlade']['NBlInpSt'] - self.fst_vt['ElastoDynBlade']['EAStff'] = [None] * self.fst_vt['ElastoDynBlade']['NBlInpSt'] - self.fst_vt['ElastoDynBlade']['Alpha'] = [None] * self.fst_vt['ElastoDynBlade']['NBlInpSt'] - self.fst_vt['ElastoDynBlade']['FlpIner'] = [None] * self.fst_vt['ElastoDynBlade']['NBlInpSt'] - self.fst_vt['ElastoDynBlade']['EdgIner'] = [None] * self.fst_vt['ElastoDynBlade']['NBlInpSt'] - self.fst_vt['ElastoDynBlade']['PrecrvRef'] = [None] * self.fst_vt['ElastoDynBlade']['NBlInpSt'] - self.fst_vt['ElastoDynBlade']['PreswpRef'] = [None] * self.fst_vt['ElastoDynBlade']['NBlInpSt'] - self.fst_vt['ElastoDynBlade']['FlpcgOf'] = [None] * self.fst_vt['ElastoDynBlade']['NBlInpSt'] - self.fst_vt['ElastoDynBlade']['Edgcgof'] = [None] * self.fst_vt['ElastoDynBlade']['NBlInpSt'] - self.fst_vt['ElastoDynBlade']['FlpEAOf'] = [None] * self.fst_vt['ElastoDynBlade']['NBlInpSt'] - self.fst_vt['ElastoDynBlade']['EdgEAOf'] = [None] * self.fst_vt['ElastoDynBlade']['NBlInpSt'] - for i in range(self.fst_vt['ElastoDynBlade']['NBlInpSt']): - data = f.readline().split() - self.fst_vt['ElastoDynBlade']['BlFract'][i] = float_read(data[0]) - self.fst_vt['ElastoDynBlade']['PitchAxis'][i] = float_read(data[1]) - self.fst_vt['ElastoDynBlade']['StrcTwst'][i] = float_read(data[2]) - self.fst_vt['ElastoDynBlade']['BMassDen'][i] = float_read(data[3]) - self.fst_vt['ElastoDynBlade']['FlpStff'][i] = float_read(data[4]) - self.fst_vt['ElastoDynBlade']['EdgStff'][i] = float_read(data[5]) - if self.FAST_ver.lower() == 'fast7': - self.fst_vt['ElastoDynBlade']['GJStff'][i] = float_read(data[6]) - self.fst_vt['ElastoDynBlade']['EAStff'][i] = float_read(data[7]) - self.fst_vt['ElastoDynBlade']['Alpha'][i] = float_read(data[8]) - self.fst_vt['ElastoDynBlade']['FlpIner'][i] = float_read(data[9]) - self.fst_vt['ElastoDynBlade']['EdgIner'][i] = float_read(data[10]) - self.fst_vt['ElastoDynBlade']['PrecrvRef'][i] = float_read(data[11]) - self.fst_vt['ElastoDynBlade']['PreswpRef'][i] = float_read(data[12]) - self.fst_vt['ElastoDynBlade']['FlpcgOf'][i] = float_read(data[13]) - self.fst_vt['ElastoDynBlade']['Edgcgof'][i] = float_read(data[14]) - self.fst_vt['ElastoDynBlade']['FlpEAOf'][i] = float_read(data[15]) - self.fst_vt['ElastoDynBlade']['EdgEAOf'][i] = float_read(data[16]) - - f.readline() - self.fst_vt['ElastoDynBlade']['BldFl1Sh'] = [None] * 5 - self.fst_vt['ElastoDynBlade']['BldFl2Sh'] = [None] * 5 - self.fst_vt['ElastoDynBlade']['BldEdgSh'] = [None] * 5 - for i in range(5): - self.fst_vt['ElastoDynBlade']['BldFl1Sh'][i] = float_read(f.readline().split()[0]) - for i in range(5): - self.fst_vt['ElastoDynBlade']['BldFl2Sh'][i] = float_read(f.readline().split()[0]) - for i in range(5): - self.fst_vt['ElastoDynBlade']['BldEdgSh'][i] = float_read(f.readline().split()[0]) - - f.close() - - def read_ElastoDynTower(self): - # ElastoDyn v1.00 Tower Input Files - # Currently no differences between FASTv8.16 and OpenFAST. - - if self.FAST_ver.lower() == 'fast7': - tower_file = os.path.join(self.FAST_directory, self.fst_vt['Fst7']['TwrFile']) - else: - tower_file = os.path.join(self.FAST_directory, self.fst_vt['ElastoDyn']['TwrFile']) - - f = open(tower_file) - - f.readline() - f.readline() - if self.FAST_ver.lower() == 'fast7': - f.readline() - - # General Tower Paramters - f.readline() - self.fst_vt['ElastoDynTower']['NTwInpSt'] = int(f.readline().split()[0]) - if self.FAST_ver.lower() == 'fast7': - self.fst_vt['ElastoDynTower']['CalcTMode'] = bool_read(f.readline().split()[0]) - self.fst_vt['ElastoDynTower']['TwrFADmp1'] = float_read(f.readline().split()[0]) - self.fst_vt['ElastoDynTower']['TwrFADmp2'] = float_read(f.readline().split()[0]) - self.fst_vt['ElastoDynTower']['TwrSSDmp1'] = float_read(f.readline().split()[0]) - self.fst_vt['ElastoDynTower']['TwrSSDmp2'] = float_read(f.readline().split()[0]) - - # Tower Adjustment Factors - f.readline() - self.fst_vt['ElastoDynTower']['FAStTunr1'] = float_read(f.readline().split()[0]) - self.fst_vt['ElastoDynTower']['FAStTunr2'] = float_read(f.readline().split()[0]) - self.fst_vt['ElastoDynTower']['SSStTunr1'] = float_read(f.readline().split()[0]) - self.fst_vt['ElastoDynTower']['SSStTunr2'] = float_read(f.readline().split()[0]) - self.fst_vt['ElastoDynTower']['AdjTwMa'] = float_read(f.readline().split()[0]) - self.fst_vt['ElastoDynTower']['AdjFASt'] = float_read(f.readline().split()[0]) - self.fst_vt['ElastoDynTower']['AdjSSSt'] = float_read(f.readline().split()[0]) - - # Distributed Tower Properties - f.readline() - f.readline() - f.readline() - self.fst_vt['ElastoDynTower']['HtFract'] = [None] * self.fst_vt['ElastoDynTower']['NTwInpSt'] - self.fst_vt['ElastoDynTower']['TMassDen'] = [None] * self.fst_vt['ElastoDynTower']['NTwInpSt'] - self.fst_vt['ElastoDynTower']['TwFAStif'] = [None] * self.fst_vt['ElastoDynTower']['NTwInpSt'] - self.fst_vt['ElastoDynTower']['TwSSStif'] = [None] * self.fst_vt['ElastoDynTower']['NTwInpSt'] - if self.FAST_ver.lower() == 'fast7': - self.fst_vt['ElastoDynTower']['TwGJStif'] = [None] * self.fst_vt['ElastoDynTower']['NTwInpSt'] - self.fst_vt['ElastoDynTower']['TwEAStif'] = [None] * self.fst_vt['ElastoDynTower']['NTwInpSt'] - self.fst_vt['ElastoDynTower']['TwFAIner'] = [None] * self.fst_vt['ElastoDynTower']['NTwInpSt'] - self.fst_vt['ElastoDynTower']['TwSSIner'] = [None] * self.fst_vt['ElastoDynTower']['NTwInpSt'] - self.fst_vt['ElastoDynTower']['TwFAcgOf'] = [None] * self.fst_vt['ElastoDynTower']['NTwInpSt'] - self.fst_vt['ElastoDynTower']['TwSScgOf'] = [None] * self.fst_vt['ElastoDynTower']['NTwInpSt'] - - for i in range(self.fst_vt['ElastoDynTower']['NTwInpSt']): - data = f.readline().split() - self.fst_vt['ElastoDynTower']['HtFract'][i] = float_read(data[0]) - self.fst_vt['ElastoDynTower']['TMassDen'][i] = float_read(data[1]) - self.fst_vt['ElastoDynTower']['TwFAStif'][i] = float_read(data[2]) - self.fst_vt['ElastoDynTower']['TwSSStif'][i] = float_read(data[3]) - if self.FAST_ver.lower() == 'fast7': - self.fst_vt['ElastoDynTower']['TwGJStif'][i] = float_read(data[4]) - self.fst_vt['ElastoDynTower']['TwEAStif'][i] = float_read(data[5]) - self.fst_vt['ElastoDynTower']['TwFAIner'][i] = float_read(data[6]) - self.fst_vt['ElastoDynTower']['TwSSIner'][i] = float_read(data[7]) - self.fst_vt['ElastoDynTower']['TwFAcgOf'][i] = float_read(data[8]) - self.fst_vt['ElastoDynTower']['TwSScgOf'][i] = float_read(data[9]) - - # Tower Mode Shapes - f.readline() - self.fst_vt['ElastoDynTower']['TwFAM1Sh'] = [None] * 5 - self.fst_vt['ElastoDynTower']['TwFAM2Sh'] = [None] * 5 - for i in range(5): - self.fst_vt['ElastoDynTower']['TwFAM1Sh'][i] = float_read(f.readline().split()[0]) - for i in range(5): - self.fst_vt['ElastoDynTower']['TwFAM2Sh'][i] = float_read(f.readline().split()[0]) - f.readline() - self.fst_vt['ElastoDynTower']['TwSSM1Sh'] = [None] * 5 - self.fst_vt['ElastoDynTower']['TwSSM2Sh'] = [None] * 5 - for i in range(5): - self.fst_vt['ElastoDynTower']['TwSSM1Sh'][i] = float_read(f.readline().split()[0]) - for i in range(5): - self.fst_vt['ElastoDynTower']['TwSSM2Sh'][i] = float_read(f.readline().split()[0]) - - f.close() - - def read_AeroDyn14Polar(self, aerodynFile): - # AeroDyn v14 Airfoil Polar Input File - - # open aerodyn file - f = open(aerodynFile, 'r') - - airfoil = copy.copy(self.fst_vt['AeroDynPolar']) - - # skip through header - airfoil['description'] = f.readline().rstrip() # remove newline - f.readline() - airfoil['number_tables'] = int(f.readline().split()[0]) - - IDParam = [float_read(val) for val in f.readline().split()[0:airfoil['number_tables']]] - StallAngle = [float_read(val) for val in f.readline().split()[0:airfoil['number_tables']]] - f.readline() - f.readline() - f.readline() - ZeroCn = [float_read(val) for val in f.readline().split()[0:airfoil['number_tables']]] - CnSlope = [float_read(val) for val in f.readline().split()[0:airfoil['number_tables']]] - CnPosStall = [float_read(val) for val in f.readline().split()[0:airfoil['number_tables']]] - CnNegStall = [float_read(val) for val in f.readline().split()[0:airfoil['number_tables']]] - alphaCdMin = [float_read(val) for val in f.readline().split()[0:airfoil['number_tables']]] - CdMin = [float_read(val) for val in f.readline().split()[0:airfoil['number_tables']]] - - data = [] - airfoil['af_tables'] = [] - while True: - line = f.readline() - if 'EOT' in line: - break - line = [float_read(s) for s in line.split()] - if len(line) < 1: - break - data.append(line) - - # loop through tables - for i in range(airfoil['number_tables']): - polar = {} - polar['IDParam'] = IDParam[i] - polar['StallAngle'] = StallAngle[i] - polar['ZeroCn'] = ZeroCn[i] - polar['CnSlope'] = CnSlope[i] - polar['CnPosStall'] = CnPosStall[i] - polar['CnNegStall'] = CnNegStall[i] - polar['alphaCdMin'] = alphaCdMin[i] - polar['CdMin'] = CdMin[i] - - alpha = [] - cl = [] - cd = [] - cm = [] - # read polar information line by line - for datai in data: - if len(datai) == airfoil['number_tables']*3+1: - alpha.append(datai[0]) - cl.append(datai[1 + 3*i]) - cd.append(datai[2 + 3*i]) - cm.append(datai[3 + 3*i]) - elif len(datai) == airfoil['number_tables']*2+1: - alpha.append(datai[0]) - cl.append(datai[1 + 2*i]) - cd.append(datai[2 + 2*i]) - - polar['alpha'] = alpha - polar['cl'] = cl - polar['cd'] = cd - polar['cm'] = cm - airfoil['af_tables'].append(polar) - - f.close() - - return airfoil - - # def WndWindReader(self, wndfile): - # # .Wnd Wind Input File for Inflow - # wind_file = os.path.join(self.FAST_directory, wndfile) - # f = open(wind_file) - - # data = [] - # while 1: - # line = f.readline() - # if not line: - # break - # if line.strip().split()[0] != '!' and line[0] != '!': - # data.append(line.split()) - - # self.fst_vt['wnd_wind']['TimeSteps'] = len(data) - # self.fst_vt['wnd_wind']['Time'] = [None] * len(data) - # self.fst_vt['wnd_wind']['HorSpd'] = [None] * len(data) - # self.fst_vt['wnd_wind']['WindDir'] = [None] * len(data) - # self.fst_vt['wnd_wind']['VerSpd'] = [None] * len(data) - # self.fst_vt['wnd_wind']['HorShr'] = [None] * len(data) - # self.fst_vt['wnd_wind']['VerShr'] = [None] * len(data) - # self.fst_vt['wnd_wind']['LnVShr'] = [None] * len(data) - # self.fst_vt['wnd_wind']['GstSpd'] = [None] * len(data) - # for i in range(len(data)): - # self.fst_vt['wnd_wind']['Time'][i] = float_read(data[i][0]) - # self.fst_vt['wnd_wind']['HorSpd'][i] = float_read(data[i][1]) - # self.fst_vt['wnd_wind']['WindDir'][i] = float_read(data[i][2]) - # self.fst_vt['wnd_wind']['VerSpd'][i] = float_read(data[i][3]) - # self.fst_vt['wnd_wind']['HorShr'][i] = float_read(data[i][4]) - # self.fst_vt['wnd_wind']['VerShr'][i] = float_read(data[i][5]) - # self.fst_vt['wnd_wind']['LnVShr'][i] = float_read(data[i][6]) - # self.fst_vt['wnd_wind']['GstSpd'][i] = float_read(data[i][7]) - - # f.close() - - -class InputReader_OpenFAST(InputReader_Common): - """ OpenFAST / FAST 8.16 input file reader """ - - def execute(self): - - self.read_MainInput() - self.read_ElastoDyn() - self.read_ElastoDynBlade() - self.read_ElastoDynTower() - self.read_InflowWind() - - # if file_wind.split('.')[1] == 'wnd': - # self.WndWindReader(file_wind) - # else: - # print 'Wind reader for file type .%s not implemented yet.' % file_wind.split('.')[1] - # AeroDyn version selection - if self.fst_vt['Fst']['CompAero'] == 1: - self.read_AeroDyn14() - elif self.fst_vt['Fst']['CompAero'] == 2: - self.read_AeroDyn15() - - self.read_ServoDyn() - if ROSCO: - self.read_DISCON_in() - - - if self.fst_vt['Fst']['CompHydro'] == 1: # SubDyn not yet implimented - self.read_HydroDyn() - if self.fst_vt['Fst']['CompSub'] == 1: # SubDyn not yet implimented - self.read_SubDyn() - if self.fst_vt['Fst']['CompMooring'] == 1: # only MAP++ implimented for mooring models - self.read_MAP() - if self.fst_vt['Fst']['CompMooring'] == 3: # MoorDyn implimented - self.read_MoorDyn() - - if self.fst_vt['Fst']['CompElast'] == 2: # BeamDyn read assumes all 3 blades are the same - self.read_BeamDyn() - def read_MainInput(self): # Main FAST v8.16-v8.17 Input File # Currently no differences between FASTv8.16 and OpenFAST. @@ -536,11 +218,10 @@ def read_MainInput(self): self.fst_vt['Fst']['MooringFile_path'] = os.path.split(self.fst_vt['Fst']['MooringFile'])[0] self.fst_vt['Fst']['IceFile_path'] = os.path.split(self.fst_vt['Fst']['IceFile'])[0] - def read_ElastoDyn(self): + def read_ElastoDyn(self, ed_file): # ElastoDyn v1.03 Input File # Currently no differences between FASTv8.16 and OpenFAST. - ed_file = os.path.join(self.FAST_directory, self.fst_vt['Fst']['EDFile']) f = open(ed_file) f.readline() @@ -682,14 +363,13 @@ def read_ElastoDyn(self): self.fst_vt['ElastoDyn']['TStart'] = float_read(f.readline().split()[0]) self.fst_vt['ElastoDyn']['DecFact'] = int(f.readline().split()[0]) self.fst_vt['ElastoDyn']['NTwGages'] = int(f.readline().split()[0]) - twrg = f.readline().split(',') if self.fst_vt['ElastoDyn']['NTwGages'] != 0: #loop over elements if there are gauges to be added, otherwise assign directly - for i in range(self.fst_vt['ElastoDyn']['NTwGages']): - self.fst_vt['ElastoDyn']['TwrGagNd'].append(twrg[i]) - self.fst_vt['ElastoDyn']['TwrGagNd'][-1] = self.fst_vt['ElastoDyn']['TwrGagNd'][-1][:-1] #remove last (newline) character + self.fst_vt['ElastoDyn']['TwrGagNd'] = f.readline().strip().split()[:self.fst_vt['ElastoDyn']['NTwGages']] + for i, bldgag in enumerate(self.fst_vt['ElastoDyn']['TwrGagNd']): + self.fst_vt['ElastoDyn']['TwrGagNd'][i] = int(bldgag.strip(',')) else: - self.fst_vt['ElastoDyn']['TwrGagNd'] = twrg - self.fst_vt['ElastoDyn']['TwrGagNd'][-1] = self.fst_vt['ElastoDyn']['TwrGagNd'][-1][:-1] + self.fst_vt['ElastoDyn']['TwrGagNd'] = 0 + f.readline() self.fst_vt['ElastoDyn']['NBlGages'] = int(f.readline().split()[0]) if self.fst_vt['ElastoDyn']['NBlGages'] != 0: self.fst_vt['ElastoDyn']['BldGagNd'] = f.readline().strip().split()[:self.fst_vt['ElastoDyn']['NBlGages']] @@ -699,25 +379,140 @@ def read_ElastoDyn(self): self.fst_vt['ElastoDyn']['BldGagNd'] = 0 f.readline() - # Loop through output channel lines + # Loop through output channel lines + f.readline() + data = f.readline() + if data != '': + while data.split()[0] != 'END': + channels = data.split('"') + channel_list = channels[1].split(',') + self.set_outlist(self.fst_vt['outlist']['ElastoDyn'], channel_list) + + data = f.readline() + + f.close() + + def read_ElastoDynBlade(self, blade_file): + # ElastoDyn v1.00 Blade Input File + # Currently no differences between FASTv8.16 and OpenFAST. + + f = open(blade_file) + # print blade_file + f.readline() + f.readline() + f.readline() + + # Blade Parameters + self.fst_vt['ElastoDynBlade']['NBlInpSt'] = int(f.readline().split()[0]) + self.fst_vt['ElastoDynBlade']['BldFlDmp1'] = float_read(f.readline().split()[0]) + self.fst_vt['ElastoDynBlade']['BldFlDmp2'] = float_read(f.readline().split()[0]) + self.fst_vt['ElastoDynBlade']['BldEdDmp1'] = float_read(f.readline().split()[0]) + + # Blade Adjustment Factors + f.readline() + self.fst_vt['ElastoDynBlade']['FlStTunr1'] = float_read(f.readline().split()[0]) + self.fst_vt['ElastoDynBlade']['FlStTunr2'] = float_read(f.readline().split()[0]) + self.fst_vt['ElastoDynBlade']['AdjBlMs'] = float_read(f.readline().split()[0]) + self.fst_vt['ElastoDynBlade']['AdjFlSt'] = float_read(f.readline().split()[0]) + self.fst_vt['ElastoDynBlade']['AdjEdSt'] = float_read(f.readline().split()[0]) + + # Distrilbuted Blade Properties + f.readline() + f.readline() + f.readline() + self.fst_vt['ElastoDynBlade']['BlFract'] = [None] * self.fst_vt['ElastoDynBlade']['NBlInpSt'] + self.fst_vt['ElastoDynBlade']['PitchAxis'] = [None] * self.fst_vt['ElastoDynBlade']['NBlInpSt'] + self.fst_vt['ElastoDynBlade']['StrcTwst'] = [None] * self.fst_vt['ElastoDynBlade']['NBlInpSt'] + self.fst_vt['ElastoDynBlade']['BMassDen'] = [None] * self.fst_vt['ElastoDynBlade']['NBlInpSt'] + self.fst_vt['ElastoDynBlade']['FlpStff'] = [None] * self.fst_vt['ElastoDynBlade']['NBlInpSt'] + self.fst_vt['ElastoDynBlade']['EdgStff'] = [None] * self.fst_vt['ElastoDynBlade']['NBlInpSt'] + + for i in range(self.fst_vt['ElastoDynBlade']['NBlInpSt']): + data = f.readline().split() + self.fst_vt['ElastoDynBlade']['BlFract'][i] = float_read(data[0]) + self.fst_vt['ElastoDynBlade']['PitchAxis'][i] = float_read(data[1]) + self.fst_vt['ElastoDynBlade']['StrcTwst'][i] = float_read(data[2]) + self.fst_vt['ElastoDynBlade']['BMassDen'][i] = float_read(data[3]) + self.fst_vt['ElastoDynBlade']['FlpStff'][i] = float_read(data[4]) + self.fst_vt['ElastoDynBlade']['EdgStff'][i] = float_read(data[5]) + + f.readline() + self.fst_vt['ElastoDynBlade']['BldFl1Sh'] = [None] * 5 + self.fst_vt['ElastoDynBlade']['BldFl2Sh'] = [None] * 5 + self.fst_vt['ElastoDynBlade']['BldEdgSh'] = [None] * 5 + for i in range(5): + self.fst_vt['ElastoDynBlade']['BldFl1Sh'][i] = float_read(f.readline().split()[0]) + for i in range(5): + self.fst_vt['ElastoDynBlade']['BldFl2Sh'][i] = float_read(f.readline().split()[0]) + for i in range(5): + self.fst_vt['ElastoDynBlade']['BldEdgSh'][i] = float_read(f.readline().split()[0]) + + f.close() + + def read_ElastoDynTower(self, tower_file): + # ElastoDyn v1.00 Tower Input Files + # Currently no differences between FASTv8.16 and OpenFAST. + + f = open(tower_file) + + f.readline() + f.readline() + + # General Tower Paramters + f.readline() + self.fst_vt['ElastoDynTower']['NTwInpSt'] = int(f.readline().split()[0]) + self.fst_vt['ElastoDynTower']['TwrFADmp1'] = float_read(f.readline().split()[0]) + self.fst_vt['ElastoDynTower']['TwrFADmp2'] = float_read(f.readline().split()[0]) + self.fst_vt['ElastoDynTower']['TwrSSDmp1'] = float_read(f.readline().split()[0]) + self.fst_vt['ElastoDynTower']['TwrSSDmp2'] = float_read(f.readline().split()[0]) + + # Tower Adjustment Factors + f.readline() + self.fst_vt['ElastoDynTower']['FAStTunr1'] = float_read(f.readline().split()[0]) + self.fst_vt['ElastoDynTower']['FAStTunr2'] = float_read(f.readline().split()[0]) + self.fst_vt['ElastoDynTower']['SSStTunr1'] = float_read(f.readline().split()[0]) + self.fst_vt['ElastoDynTower']['SSStTunr2'] = float_read(f.readline().split()[0]) + self.fst_vt['ElastoDynTower']['AdjTwMa'] = float_read(f.readline().split()[0]) + self.fst_vt['ElastoDynTower']['AdjFASt'] = float_read(f.readline().split()[0]) + self.fst_vt['ElastoDynTower']['AdjSSSt'] = float_read(f.readline().split()[0]) + + # Distributed Tower Properties + f.readline() + f.readline() + f.readline() + self.fst_vt['ElastoDynTower']['HtFract'] = [None] * self.fst_vt['ElastoDynTower']['NTwInpSt'] + self.fst_vt['ElastoDynTower']['TMassDen'] = [None] * self.fst_vt['ElastoDynTower']['NTwInpSt'] + self.fst_vt['ElastoDynTower']['TwFAStif'] = [None] * self.fst_vt['ElastoDynTower']['NTwInpSt'] + self.fst_vt['ElastoDynTower']['TwSSStif'] = [None] * self.fst_vt['ElastoDynTower']['NTwInpSt'] + + for i in range(self.fst_vt['ElastoDynTower']['NTwInpSt']): + data = f.readline().split() + self.fst_vt['ElastoDynTower']['HtFract'][i] = float_read(data[0]) + self.fst_vt['ElastoDynTower']['TMassDen'][i] = float_read(data[1]) + self.fst_vt['ElastoDynTower']['TwFAStif'][i] = float_read(data[2]) + self.fst_vt['ElastoDynTower']['TwSSStif'][i] = float_read(data[3]) + + # Tower Mode Shapes f.readline() - data = f.readline() - if data != '': - while data.split()[0] != 'END': - channels = data.split('"') - channel_list = channels[1].split(',') - self.set_outlist(self.fst_vt['outlist']['ElastoDyn'], channel_list) - - data = f.readline() + self.fst_vt['ElastoDynTower']['TwFAM1Sh'] = [None] * 5 + self.fst_vt['ElastoDynTower']['TwFAM2Sh'] = [None] * 5 + for i in range(5): + self.fst_vt['ElastoDynTower']['TwFAM1Sh'][i] = float_read(f.readline().split()[0]) + for i in range(5): + self.fst_vt['ElastoDynTower']['TwFAM2Sh'][i] = float_read(f.readline().split()[0]) + f.readline() + self.fst_vt['ElastoDynTower']['TwSSM1Sh'] = [None] * 5 + self.fst_vt['ElastoDynTower']['TwSSM2Sh'] = [None] * 5 + for i in range(5): + self.fst_vt['ElastoDynTower']['TwSSM1Sh'][i] = float_read(f.readline().split()[0]) + for i in range(5): + self.fst_vt['ElastoDynTower']['TwSSM2Sh'][i] = float_read(f.readline().split()[0]) f.close() - def read_BeamDyn(self): + def read_BeamDyn(self, bd_file): # BeamDyn Input File - - bd_file = os.path.join(self.FAST_directory, self.fst_vt['Fst']['BDBldFile(1)']) f = open(bd_file) - f.readline() f.readline() f.readline() @@ -728,7 +523,7 @@ def read_BeamDyn(self): self.fst_vt['BeamDyn']['quadrature'] = int_read(f.readline().split()[0]) self.fst_vt['BeamDyn']['refine'] = int_read(f.readline().split()[0]) self.fst_vt['BeamDyn']['n_fact'] = int_read(f.readline().split()[0]) - self.fst_vt['BeamDyn']['DTBeam'] = float_read(f.readline().split()[0]) + self.fst_vt['BeamDyn']['DTBeam'] = float_read(f.readline().split()[0]) self.fst_vt['BeamDyn']['load_retries'] = int_read(f.readline().split()[0]) self.fst_vt['BeamDyn']['NRMax'] = int_read(f.readline().split()[0]) self.fst_vt['BeamDyn']['stop_tol'] = float_read(f.readline().split()[0]) @@ -906,119 +701,24 @@ def read_InflowWind(self): f.readline() self.fst_vt['InflowWind']['SumPrint'] = bool_read(f.readline().split()[0]) - # NO INFLOW WIND OUTPUT PARAMETERS YET DEFINED IN FAST - # f.readline() - # data = f.readline() - # while data.split()[0] != 'END': - # channels = data.split('"') - # channel_list = channels[1].split(',') - # for i in range(len(channel_list)): - # channel_list[i] = channel_list[i].replace(' ','') - # if channel_list[i] in self.fst_vt.outlist.inflow_wind_vt.__dict__.keys(): - # self.fst_vt.outlist.inflow_wind_vt.__dict__[channel_list[i]] = True - # data = f.readline() - - f.close() - - def read_AeroDyn14(self): - # AeroDyn v14.04 - - ad_file = os.path.join(self.FAST_directory, self.fst_vt['Fst']['AeroFile']) - f = open(ad_file) - # AeroDyn file header (aerodyn) - f.readline() - f.readline() - self.fst_vt['AeroDyn14']['StallMod'] = f.readline().split()[0] - self.fst_vt['AeroDyn14']['UseCm'] = f.readline().split()[0] - self.fst_vt['AeroDyn14']['InfModel'] = f.readline().split()[0] - self.fst_vt['AeroDyn14']['IndModel'] = f.readline().split()[0] - self.fst_vt['AeroDyn14']['AToler'] = float_read(f.readline().split()[0]) - self.fst_vt['AeroDyn14']['TLModel'] = f.readline().split()[0] - self.fst_vt['AeroDyn14']['HLModel'] = f.readline().split()[0] - self.fst_vt['AeroDyn14']['TwrShad'] = f.readline().split()[0] - - if self.fst_vt['AeroDyn14']['TwrShad'] == "NEWTOWER": #w tower influence - self.fst_vt['AeroDyn14']['TwrPotent'] = bool_read(f.readline().split()[0]) - self.fst_vt['AeroDyn14']['TwrShadow'] = bool_read(f.readline().split()[0]) - self.fst_vt['AeroDyn14']['TwrFile'] = f.readline().split()[0].replace('"','').replace("'",'') - self.fst_vt['AeroDyn14']['CalcTwrAero'] = bool_read(f.readline().split()[0]) - else: #w/o tower influence - self.fst_vt['AeroDyn14']['ShadHWid'] = float_read(f.readline().split()[0]) - self.fst_vt['AeroDyn14']['T_Shad_Refpt'] = float_read(f.readline().split()[0]) - - self.fst_vt['AeroDyn14']['AirDens'] = float_read(f.readline().split()[0]) - self.fst_vt['AeroDyn14']['KinVisc'] = float_read(f.readline().split()[0]) - self.fst_vt['AeroDyn14']['DTAero'] = float_read(f.readline().split()[0]) - - # AeroDyn Blade Properties (blade_aero) - self.fst_vt['AeroDyn14']['NumFoil'] = int(f.readline().split()[0]) - self.fst_vt['AeroDyn14']['FoilNm'] = [None] * self.fst_vt['AeroDyn14']['NumFoil'] - for i in range(self.fst_vt['AeroDyn14']['NumFoil']): - af_filename = f.readline().split()[0] - af_filename = fix_path(af_filename) - self.fst_vt['AeroDyn14']['FoilNm'][i] = af_filename[1:-1] - - self.fst_vt['AeroDynBlade']['BldNodes'] = int(f.readline().split()[0]) + # InflowWind Outlist f.readline() - self.fst_vt['AeroDynBlade']['RNodes'] = [None] * self.fst_vt['AeroDynBlade']['BldNodes'] - self.fst_vt['AeroDynBlade']['AeroTwst'] = [None] * self.fst_vt['AeroDynBlade']['BldNodes'] - self.fst_vt['AeroDynBlade']['DRNodes'] = [None] * self.fst_vt['AeroDynBlade']['BldNodes'] - self.fst_vt['AeroDynBlade']['Chord'] = [None] * self.fst_vt['AeroDynBlade']['BldNodes'] - self.fst_vt['AeroDynBlade']['NFoil'] = [None] * self.fst_vt['AeroDynBlade']['BldNodes'] - self.fst_vt['AeroDynBlade']['PrnElm'] = [None] * self.fst_vt['AeroDynBlade']['BldNodes'] - for i in range(self.fst_vt['AeroDynBlade']['BldNodes']): - data = f.readline().split() - self.fst_vt['AeroDynBlade']['RNodes'][i] = float_read(data[0]) - self.fst_vt['AeroDynBlade']['AeroTwst'][i] = float_read(data[1]) - self.fst_vt['AeroDynBlade']['DRNodes'][i] = float_read(data[2]) - self.fst_vt['AeroDynBlade']['Chord'][i] = float_read(data[3]) - self.fst_vt['AeroDynBlade']['NFoil'][i] = int(data[4]) - self.fst_vt['AeroDynBlade']['PrnElm'][i] = data[5] + data = f.readline() + while data.split()[0] != 'END': + if data.find('"')>=0: + channels = data.split('"') + channel_list = channels[1].split(',') + else: + row_string = data.split(',') + if len(row_string)==1: + channel_list = row_string[0].split('\n')[0] + else: + channel_list = row_string + self.set_outlist(self.fst_vt['outlist']['InflowWind'], channel_list) + data = f.readline() f.close() - - # create airfoil objects - self.fst_vt['AeroDynBlade']['af_data'] = [] - for i in range(self.fst_vt['AeroDyn14']['NumFoil']): - self.fst_vt['AeroDynBlade']['af_data'].append(self.read_AeroDyn14Polar(os.path.join(self.FAST_directory,self.fst_vt['Fst']['AeroFile_path'],self.fst_vt['AeroDyn14']['FoilNm'][i]))) - - # tower - if self.fst_vt['AeroDyn14']['TwrShad'] == "NEWTOWER": - self.read_AeroDyn14Tower() - - def read_AeroDyn14Tower(self): - # AeroDyn v14.04 Tower - - ad_tower_file = os.path.join(self.FAST_directory, self.fst_vt['aerodyn']['TwrFile']) - f = open(ad_tower_file) - - f.readline() - f.readline() - self.fst_vt['AeroDynTower']['NTwrHt'] = int(f.readline().split()[0]) - self.fst_vt['AeroDynTower']['NTwrRe'] = int(f.readline().split()[0]) - self.fst_vt['AeroDynTower']['NTwrCD'] = int(f.readline().split()[0]) - self.fst_vt['AeroDynTower']['Tower_Wake_Constant'] = float_read(f.readline().split()[0]) - - f.readline() - f.readline() - self.fst_vt['AeroDynTower']['TwrHtFr'] = [None]*self.fst_vt['AeroDynTower']['NTwrHt'] - self.fst_vt['AeroDynTower']['TwrWid'] = [None]*self.fst_vt['AeroDynTower']['NTwrHt'] - self.fst_vt['AeroDynTower']['NTwrCDCol'] = [None]*self.fst_vt['AeroDynTower']['NTwrHt'] - for i in range(self.fst_vt['AeroDynTower']['NTwrHt']): - data = [float(val) for val in f.readline().split()] - self.fst_vt['AeroDynTower']['TwrHtFr'][i] = data[0] - self.fst_vt['AeroDynTower']['TwrWid'][i] = data[1] - self.fst_vt['AeroDynTower']['NTwrCDCol'][i] = data[2] - - f.readline() - f.readline() - self.fst_vt['AeroDynTower']['TwrRe'] = [None]*self.fst_vt['AeroDynTower']['NTwrRe'] - self.fst_vt['AeroDynTower']['TwrCD'] = np.zeros((self.fst_vt['AeroDynTower']['NTwrRe'], self.fst_vt['AeroDynTower']['NTwrCD'])) - for i in range(self.fst_vt['AeroDynTower']['NTwrRe']): - data = [float(val) for val in f.readline().split()] - self.fst_vt['AeroDynTower']['TwrRe'][i] = data[0] - self.fst_vt['AeroDynTower']['TwrCD'][i,:] = data[1:] - + def read_AeroDyn15(self): # AeroDyn v15.03 @@ -1034,10 +734,11 @@ def read_AeroDyn15(self): self.fst_vt['AeroDyn15']['WakeMod'] = int(f.readline().split()[0]) self.fst_vt['AeroDyn15']['AFAeroMod'] = int(f.readline().split()[0]) self.fst_vt['AeroDyn15']['TwrPotent'] = int(f.readline().split()[0]) - self.fst_vt['AeroDyn15']['TwrShadow'] = int(f.readline().split()[0]) + self.fst_vt['AeroDyn15']['TwrShadow'] = int(f.readline().split()[0]) self.fst_vt['AeroDyn15']['TwrAero'] = bool_read(f.readline().split()[0]) self.fst_vt['AeroDyn15']['FrozenWake'] = bool_read(f.readline().split()[0]) self.fst_vt['AeroDyn15']['CavitCheck'] = bool_read(f.readline().split()[0]) + self.fst_vt['AeroDyn15']['Buoyancy'] = bool_read(f.readline().split()[0]) self.fst_vt['AeroDyn15']['CompAA'] = bool_read(f.readline().split()[0]) self.fst_vt['AeroDyn15']['AA_InputFile'] = f.readline().split()[0] @@ -1052,8 +753,8 @@ def read_AeroDyn15(self): # Blade-Element/Momentum Theory Options f.readline() - self.fst_vt['AeroDyn15']['SkewMod'] = int(f.readline().split()[0]) - self.fst_vt['AeroDyn15']['SkewModFactor'] = float_read(f.readline().split()[0]) + self.fst_vt['AeroDyn15']['SkewMod'] = int_read(f.readline().split()[0]) + self.fst_vt['AeroDyn15']['SkewModFactor'] = float_read(f.readline().split()[0]) self.fst_vt['AeroDyn15']['TipLoss'] = bool_read(f.readline().split()[0]) self.fst_vt['AeroDyn15']['HubLoss'] = bool_read(f.readline().split()[0]) self.fst_vt['AeroDyn15']['TanInd'] = bool_read(f.readline().split()[0]) @@ -1076,8 +777,8 @@ def read_AeroDyn15(self): f.readline() self.fst_vt['AeroDyn15']['UAMod'] = int(f.readline().split()[0]) self.fst_vt['AeroDyn15']['FLookup'] = bool_read(f.readline().split()[0]) - self.fst_vt['AeroDyn15']['UAStartRad'] = float_read(f.readline().split()[0]) - self.fst_vt['AeroDyn15']['UAEndRad'] = float_read(f.readline().split()[0]) + # self.fst_vt['AeroDyn15']['UAStartRad'] = float_read(f.readline().split()[0]) + # self.fst_vt['AeroDyn15']['UAEndRad'] = float_read(f.readline().split()[0]) # Airfoil Information f.readline() @@ -1100,21 +801,36 @@ def read_AeroDyn15(self): self.fst_vt['AeroDyn15']['ADBlFile2'] = f.readline().split()[0][1:-1] self.fst_vt['AeroDyn15']['ADBlFile3'] = f.readline().split()[0][1:-1] + # Hub, nacelle, and tail fin aerodynamics + f.readline() + self.fst_vt['AeroDyn15']['VolHub'] = float_read(f.readline().split()[0]) + self.fst_vt['AeroDyn15']['HubCenBx'] = float_read(f.readline().split()[0]) + f.readline() + self.fst_vt['AeroDyn15']['VolNac'] = float_read(f.readline().split()[0]) + # data = [float(val) for val in f.readline().split(',')] + self.fst_vt['AeroDyn15']['NacCenB'] = [idx.strip() for idx in f.readline().split('NacCenB')[0].split(',')] + f.readline() + self.fst_vt['AeroDyn15']['TFinAero'] = bool_read(f.readline().split()[0]) + tfa_filename = fix_path(f.readline().split()[0])[1:-1] + self.fst_vt['AeroDyn15']['TFinFile'] = os.path.abspath(os.path.join(self.FAST_directory, tfa_filename)) + # Tower Influence and Aerodynamics f.readline() self.fst_vt['AeroDyn15']['NumTwrNds'] = int(f.readline().split()[0]) f.readline() f.readline() - self.fst_vt['AeroDyn15']['TwrElev'] = [None]*self.fst_vt['AeroDyn15']['NumTwrNds'] - self.fst_vt['AeroDyn15']['TwrDiam'] = [None]*self.fst_vt['AeroDyn15']['NumTwrNds'] - self.fst_vt['AeroDyn15']['TwrCd'] = [None]*self.fst_vt['AeroDyn15']['NumTwrNds'] - self.fst_vt['AeroDyn15']['TwrTI'] = [None]*self.fst_vt['AeroDyn15']['NumTwrNds'] + self.fst_vt['AeroDyn15']['TwrElev'] = [None]*self.fst_vt['AeroDyn15']['NumTwrNds'] + self.fst_vt['AeroDyn15']['TwrDiam'] = [None]*self.fst_vt['AeroDyn15']['NumTwrNds'] + self.fst_vt['AeroDyn15']['TwrCd'] = [None]*self.fst_vt['AeroDyn15']['NumTwrNds'] + self.fst_vt['AeroDyn15']['TwrTI'] = [None]*self.fst_vt['AeroDyn15']['NumTwrNds'] + self.fst_vt['AeroDyn15']['TwrCb'] = [None]*self.fst_vt['AeroDyn15']['NumTwrNds'] for i in range(self.fst_vt['AeroDyn15']['NumTwrNds']): data = [float(val) for val in f.readline().split()] self.fst_vt['AeroDyn15']['TwrElev'][i] = data[0] self.fst_vt['AeroDyn15']['TwrDiam'][i] = data[1] self.fst_vt['AeroDyn15']['TwrCd'][i] = data[2] self.fst_vt['AeroDyn15']['TwrTI'][i] = data[3] + self.fst_vt['AeroDyn15']['TwrCb'][i] = data[4] # Outputs f.readline() @@ -1128,8 +844,15 @@ def read_AeroDyn15(self): f.readline() data = f.readline() while data.split()[0] != 'END': - channels = data.split('"') - channel_list = channels[1].split(',') + if data.find('"')>=0: + channels = data.split('"') + channel_list = channels[1].split(',') + else: + row_string = data.split(',') + if len(row_string)==1: + channel_list = row_string[0].split('\n')[0] + else: + channel_list = row_string self.set_outlist(self.fst_vt['outlist']['AeroDyn'], channel_list) data = f.readline() @@ -1138,10 +861,9 @@ def read_AeroDyn15(self): self.read_AeroDyn15Blade() self.read_AeroDyn15Polar() self.read_AeroDyn15Coord() - if self.fst_vt['AeroDyn15']['WakeMod'] == 3: - if self.fst_vt['AeroDyn15']['AFAeroMod'] == 2: - raise Exception('OLAF is called with unsteady airfoil aerodynamics, but OLAF currently only supports AFAeroMod == 1') - self.read_AeroDyn15OLAF() + olaf_filename = os.path.join(self.FAST_directory, self.fst_vt['AeroDyn15']['OLAFInputFileName']) + if os.path.isfile(olaf_filename): + self.read_AeroDyn15OLAF(olaf_filename) def read_AeroDyn15Blade(self): # AeroDyn v5.00 Blade Definition File @@ -1204,6 +926,8 @@ def read_AeroDyn15Polar(self): polar['alpha0'] = float_read(readline_filterComments(f).split()[0]) polar['alpha1'] = float_read(readline_filterComments(f).split()[0]) polar['alpha2'] = float_read(readline_filterComments(f).split()[0]) + # polar['alphaUpper'] = float_read(readline_filterComments(f).split()[0]) + # polar['alphaLower'] = float_read(readline_filterComments(f).split()[0]) polar['eta_e'] = float_read(readline_filterComments(f).split()[0]) polar['C_nalpha'] = float_read(readline_filterComments(f).split()[0]) polar['T_f0'] = float_read(readline_filterComments(f).split()[0]) @@ -1254,88 +978,260 @@ def read_AeroDyn15Polar(self): if self.fst_vt['AeroDyn15']['InCol_Cpmin'] > 0: polar['Cpmin'][i] = data[self.fst_vt['AeroDyn15']['InCol_Cpmin']-1] - self.fst_vt['AeroDyn15']['af_data'][afi][tab] = copy.copy(polar) # For multiple tables - - f.close() + self.fst_vt['AeroDyn15']['af_data'][afi][tab] = copy.copy(polar) # For multiple tables + + f.close() + + def read_AeroDyn15Coord(self): + + self.fst_vt['AeroDyn15']['af_coord'] = [] + self.fst_vt['AeroDyn15']['ac'] = np.zeros(len(self.fst_vt['AeroDyn15']['AFNames'])) + + for afi, af_filename in enumerate(self.fst_vt['AeroDyn15']['AFNames']): + self.fst_vt['AeroDyn15']['af_coord'].append({}) + if not (self.fst_vt['AeroDyn15']['af_data'][afi][0]['NumCoords'] == 0 or self.fst_vt['AeroDyn15']['af_data'][afi][0]['NumCoords'] == '0'): + coord_filename = af_filename[0:af_filename.rfind(os.sep)] + os.sep + self.fst_vt['AeroDyn15']['af_data'][afi][0]['NumCoords'][2:-1] + f = open(coord_filename) + n_coords = int_read(readline_filterComments(f).split()[0]) + x = np.zeros(n_coords) + y = np.zeros(n_coords) + f.readline() + f.readline() + f.readline() + self.fst_vt['AeroDyn15']['ac'][afi] = float(f.readline().split()[0]) + f.readline() + f.readline() + f.readline() + for j in range(n_coords - 1): + x[j], y[j] = f.readline().split() + + self.fst_vt['AeroDyn15']['af_coord'][afi]['x'] = x + self.fst_vt['AeroDyn15']['af_coord'][afi]['y'] = y + + f.close() + + def read_AeroDyn15OLAF(self, olaf_filename): + + self.fst_vt['AeroDyn15']['OLAF'] = {} + f = open(olaf_filename) + f.readline() + f.readline() + f.readline() + self.fst_vt['AeroDyn15']['OLAF']['IntMethod'] = int_read(f.readline().split()[0]) + self.fst_vt['AeroDyn15']['OLAF']['DTfvw'] = float_read(f.readline().split()[0]) + self.fst_vt['AeroDyn15']['OLAF']['FreeWakeStart'] = float_read(f.readline().split()[0]) + self.fst_vt['AeroDyn15']['OLAF']['FullCircStart'] = float_read(f.readline().split()[0]) + f.readline() + self.fst_vt['AeroDyn15']['OLAF']['CircSolvMethod'] = int_read(f.readline().split()[0]) + self.fst_vt['AeroDyn15']['OLAF']['CircSolvConvCrit'] = float_read(f.readline().split()[0]) + self.fst_vt['AeroDyn15']['OLAF']['CircSolvRelaxation'] = float_read(f.readline().split()[0]) + self.fst_vt['AeroDyn15']['OLAF']['CircSolvMaxIter'] = int_read(f.readline().split()[0]) + self.fst_vt['AeroDyn15']['OLAF']['PrescribedCircFile'] = f.readline().split()[0] + f.readline() + f.readline() + f.readline() + self.fst_vt['AeroDyn15']['OLAF']['nNWPanels'] = int_read(f.readline().split()[0]) + self.fst_vt['AeroDyn15']['OLAF']['nNWPanelsFree'] = int_read(f.readline().split()[0]) + self.fst_vt['AeroDyn15']['OLAF']['nFWPanels'] = int_read(f.readline().split()[0]) + self.fst_vt['AeroDyn15']['OLAF']['nFWPanelsFree'] = int_read(f.readline().split()[0]) + self.fst_vt['AeroDyn15']['OLAF']['FWShedVorticity'] = bool_read(f.readline().split()[0]) + f.readline() + self.fst_vt['AeroDyn15']['OLAF']['DiffusionMethod'] = int_read(f.readline().split()[0]) + self.fst_vt['AeroDyn15']['OLAF']['RegDeterMethod'] = int_read(f.readline().split()[0]) + self.fst_vt['AeroDyn15']['OLAF']['RegFunction'] = int_read(f.readline().split()[0]) + self.fst_vt['AeroDyn15']['OLAF']['WakeRegMethod'] = int_read(f.readline().split()[0]) + self.fst_vt['AeroDyn15']['OLAF']['WakeRegFactor'] = float(f.readline().split()[0]) + self.fst_vt['AeroDyn15']['OLAF']['WingRegFactor'] = float(f.readline().split()[0]) + self.fst_vt['AeroDyn15']['OLAF']['CoreSpreadEddyVisc'] = int(f.readline().split()[0]) + f.readline() + self.fst_vt['AeroDyn15']['OLAF']['TwrShadowOnWake'] = bool_read(f.readline().split()[0]) + self.fst_vt['AeroDyn15']['OLAF']['ShearModel'] = int_read(f.readline().split()[0]) + f.readline() + self.fst_vt['AeroDyn15']['OLAF']['VelocityMethod'] = int_read(f.readline().split()[0]) + self.fst_vt['AeroDyn15']['OLAF']['TreeBranchFactor']= float_read(f.readline().split()[0]) + self.fst_vt['AeroDyn15']['OLAF']['PartPerSegment'] = int(f.readline().split()[0]) + f.readline() + f.readline() + self.fst_vt['AeroDyn15']['OLAF']['WrVTk'] = int(f.readline().split()[0]) + self.fst_vt['AeroDyn15']['OLAF']['nVTKBlades'] = int(f.readline().split()[0]) + self.fst_vt['AeroDyn15']['OLAF']['VTKCoord'] = int_read(f.readline().split()[0]) + self.fst_vt['AeroDyn15']['OLAF']['VTK_fps'] = float_read(f.readline().split()[0]) + self.fst_vt['AeroDyn15']['OLAF']['nGridOut'] = int_read(f.readline().split()[0]) + f.readline() + f.close() + + def read_AeroDyn14(self): + # AeroDyn v14.04 + + ad_file = os.path.join(self.FAST_directory, self.fst_vt['Fst']['AeroFile']) + f = open(ad_file) + # AeroDyn file header (aerodyn) + f.readline() + f.readline() + self.fst_vt['AeroDyn14']['StallMod'] = f.readline().split()[0] + self.fst_vt['AeroDyn14']['UseCm'] = f.readline().split()[0] + self.fst_vt['AeroDyn14']['InfModel'] = f.readline().split()[0] + self.fst_vt['AeroDyn14']['IndModel'] = f.readline().split()[0] + self.fst_vt['AeroDyn14']['AToler'] = float_read(f.readline().split()[0]) + self.fst_vt['AeroDyn14']['TLModel'] = f.readline().split()[0] + self.fst_vt['AeroDyn14']['HLModel'] = f.readline().split()[0] + self.fst_vt['AeroDyn14']['TwrShad'] = int(f.readline().split()[0]) + if self.fst_vt['AeroDyn14']['TwrShad'] > 0: + self.fst_vt['AeroDyn14']['TwrPotent'] = bool_read(f.readline().split()[0]) + self.fst_vt['AeroDyn14']['TwrShadow'] = bool_read(f.readline().split()[0]) + self.fst_vt['AeroDyn14']['TwrFile'] = f.readline().split()[0].replace('"','').replace("'",'') + self.fst_vt['AeroDyn14']['CalcTwrAero'] = bool_read(f.readline().split()[0]) + else: + self.fst_vt['AeroDyn14']['ShadHWid'] = float_read(f.readline().split()[0]) + self.fst_vt['AeroDyn14']['T_Shad_Refpt'] = float_read(f.readline().split()[0]) + self.fst_vt['AeroDyn14']['AirDens'] = float_read(f.readline().split()[0]) + self.fst_vt['AeroDyn14']['KinVisc'] = float_read(f.readline().split()[0]) + self.fst_vt['AeroDyn14']['DTAero'] = float_read(f.readline().split()[0]) + + # AeroDyn Blade Properties (blade_aero) + self.fst_vt['AeroDyn14']['NumFoil'] = int(f.readline().split()[0]) + self.fst_vt['AeroDyn14']['FoilNm'] = [None] * self.fst_vt['AeroDyn14']['NumFoil'] + for i in range(self.fst_vt['AeroDyn14']['NumFoil']): + af_filename = f.readline().split()[0] + af_filename = fix_path(af_filename) + self.fst_vt['AeroDyn14']['FoilNm'][i] = af_filename[1:-1] + + self.fst_vt['AeroDynBlade']['BldNodes'] = int(f.readline().split()[0]) + f.readline() + self.fst_vt['AeroDynBlade']['RNodes'] = [None] * self.fst_vt['AeroDynBlade']['BldNodes'] + self.fst_vt['AeroDynBlade']['AeroTwst'] = [None] * self.fst_vt['AeroDynBlade']['BldNodes'] + self.fst_vt['AeroDynBlade']['DRNodes'] = [None] * self.fst_vt['AeroDynBlade']['BldNodes'] + self.fst_vt['AeroDynBlade']['Chord'] = [None] * self.fst_vt['AeroDynBlade']['BldNodes'] + self.fst_vt['AeroDynBlade']['NFoil'] = [None] * self.fst_vt['AeroDynBlade']['BldNodes'] + self.fst_vt['AeroDynBlade']['PrnElm'] = [None] * self.fst_vt['AeroDynBlade']['BldNodes'] + for i in range(self.fst_vt['AeroDynBlade']['BldNodes']): + data = f.readline().split() + self.fst_vt['AeroDynBlade']['RNodes'][i] = float_read(data[0]) + self.fst_vt['AeroDynBlade']['AeroTwst'][i] = float_read(data[1]) + self.fst_vt['AeroDynBlade']['DRNodes'][i] = float_read(data[2]) + self.fst_vt['AeroDynBlade']['Chord'][i] = float_read(data[3]) + self.fst_vt['AeroDynBlade']['NFoil'][i] = int(data[4]) + self.fst_vt['AeroDynBlade']['PrnElm'][i] = data[5] + + f.close() - def read_AeroDyn15Coord(self): - - self.fst_vt['AeroDyn15']['af_coord'] = [] - self.fst_vt['AeroDyn15']['ac'] = np.zeros(len(self.fst_vt['AeroDyn15']['AFNames'])) + # create airfoil objects + self.fst_vt['AeroDynBlade']['af_data'] = [] + for i in range(self.fst_vt['AeroDyn14']['NumFoil']): + self.fst_vt['AeroDynBlade']['af_data'].append(self.read_AeroDyn14Polar(os.path.join(self.FAST_directory,self.fst_vt['AeroDyn14']['FoilNm'][i]))) - for afi, af_filename in enumerate(self.fst_vt['AeroDyn15']['AFNames']): - self.fst_vt['AeroDyn15']['af_coord'].append({}) - if not (self.fst_vt['AeroDyn15']['af_data'][afi][0]['NumCoords'] == 0 or self.fst_vt['AeroDyn15']['af_data'][afi][0]['NumCoords'] == '0'): - coord_filename = af_filename[0:af_filename.rfind( - os.sep)] + os.sep + self.fst_vt['AeroDyn15']['af_data'][afi][0]['NumCoords'][2:-1] - f = open(coord_filename) - n_coords = int_read(readline_filterComments(f).split()[0]) - x = np.zeros(n_coords) - y = np.zeros(n_coords) - f.readline() - f.readline() - f.readline() - self.fst_vt['AeroDyn15']['ac'][afi] = float(f.readline().split()[0]) - f.readline() - f.readline() - f.readline() - for j in range(n_coords - 1): - x[j], y[j] = f.readline().split() + # tower + if self.fst_vt['AeroDyn14']['TwrShad'] > 0: + self.read_AeroDyn14Tower() - self.fst_vt['AeroDyn15']['af_coord'][afi]['x'] = x - self.fst_vt['AeroDyn15']['af_coord'][afi]['y'] = y + def read_AeroDyn14Tower(self): + # AeroDyn v14.04 Tower - f.close() + ad_tower_file = os.path.join(self.FAST_directory, self.fst_vt['AeroDyn14']['TwrFile']) + f = open(ad_tower_file) - def read_AeroDyn15OLAF(self): - - self.fst_vt['AeroDyn15']['OLAF'] = {} - olaf_filename = os.path.join(self.FAST_directory, self.fst_vt['AeroDyn15']['OLAFInputFileName']) - f = open(olaf_filename) f.readline() f.readline() - f.readline() - self.fst_vt['AeroDyn15']['OLAF']['IntMethod'] = int_read(f.readline().split()[0]) - self.fst_vt['AeroDyn15']['OLAF']['DTfvw'] = float_read(f.readline().split()[0]) - self.fst_vt['AeroDyn15']['OLAF']['FreeWakeStart'] = float_read(f.readline().split()[0]) - self.fst_vt['AeroDyn15']['OLAF']['FullCircStart'] = float_read(f.readline().split()[0]) - f.readline() - self.fst_vt['AeroDyn15']['OLAF']['CircSolvingMethod'] = int_read(f.readline().split()[0]) - self.fst_vt['AeroDyn15']['OLAF']['CircSolvConvCrit'] = float_read(f.readline().split()[0]) - self.fst_vt['AeroDyn15']['OLAF']['CircSolvRelaxation'] = float_read(f.readline().split()[0]) - self.fst_vt['AeroDyn15']['OLAF']['CircSolvMaxIter'] = int_read(f.readline().split()[0]) - self.fst_vt['AeroDyn15']['OLAF']['PrescribedCircFile'] = f.readline().split()[0] - f.readline() + self.fst_vt['AeroDynTower']['NTwrHt'] = int(f.readline().split()[0]) + self.fst_vt['AeroDynTower']['NTwrRe'] = int(f.readline().split()[0]) + self.fst_vt['AeroDynTower']['NTwrCD'] = int(f.readline().split()[0]) + self.fst_vt['AeroDynTower']['Tower_Wake_Constant'] = float_read(f.readline().split()[0]) + f.readline() f.readline() - self.fst_vt['AeroDyn15']['OLAF']['nNWPanel'] = int(f.readline().split()[0]) - self.fst_vt['AeroDyn15']['OLAF']['WakeLength'] = int(f.readline().split()[0]) - self.fst_vt['AeroDyn15']['OLAF']['FreeWakeLength'] = int_read(f.readline().split()[0]) - self.fst_vt['AeroDyn15']['OLAF']['FWShedVorticity'] = float_read(f.readline().split()[0]) + self.fst_vt['AeroDynTower']['TwrHtFr'] = [None]*self.fst_vt['AeroDynTower']['NTwrHt'] + self.fst_vt['AeroDynTower']['TwrWid'] = [None]*self.fst_vt['AeroDynTower']['NTwrHt'] + self.fst_vt['AeroDynTower']['NTwrCDCol'] = [None]*self.fst_vt['AeroDynTower']['NTwrHt'] + for i in range(self.fst_vt['AeroDynTower']['NTwrHt']): + data = [float(val) for val in f.readline().split()] + self.fst_vt['AeroDynTower']['TwrHtFr'][i] = data[0] + self.fst_vt['AeroDynTower']['TwrWid'][i] = data[1] + self.fst_vt['AeroDynTower']['NTwrCDCol'][i] = data[2] + f.readline() - self.fst_vt['AeroDyn15']['OLAF']['DiffusionMethod'] = int_read(f.readline().split()[0]) - self.fst_vt['AeroDyn15']['OLAF']['RegDeterMethod'] = int_read(f.readline().split()[0]) - self.fst_vt['AeroDyn15']['OLAF']['RegFunction'] = int_read(f.readline().split()[0]) - self.fst_vt['AeroDyn15']['OLAF']['WakeRegMethod'] = int_read(f.readline().split()[0]) - self.fst_vt['AeroDyn15']['OLAF']['WakeRegFactor'] = float(f.readline().split()[0]) - self.fst_vt['AeroDyn15']['OLAF']['WingRegFactor'] = float(f.readline().split()[0]) - self.fst_vt['AeroDyn15']['OLAF']['CoreSpreadEddyVisc'] = int(f.readline().split()[0]) f.readline() - self.fst_vt['AeroDyn15']['OLAF']['TwrShadowOnWake'] = bool_read(f.readline().split()[0]) - self.fst_vt['AeroDyn15']['OLAF']['ShearModel'] = int_read(f.readline().split()[0]) + self.fst_vt['AeroDynTower']['TwrRe'] = [None]*self.fst_vt['AeroDynTower']['NTwrRe'] + self.fst_vt['AeroDynTower']['TwrCD'] = np.zeros((self.fst_vt['AeroDynTower']['NTwrRe'], self.fst_vt['AeroDynTower']['NTwrCD'])) + for i in range(self.fst_vt['AeroDynTower']['NTwrRe']): + data = [float(val) for val in f.readline().split()] + self.fst_vt['AeroDynTower']['TwrRe'][i] = data[0] + self.fst_vt['AeroDynTower']['TwrCD'][i,:] = data[1:] + + f.close() + + def read_AeroDyn14Polar(self, aerodynFile): + # AeroDyn v14 Airfoil Polar Input File + + # open aerodyn file + f = open(aerodynFile, 'r') + + airfoil = copy.copy(self.fst_vt['AeroDynPolar']) + + # skip through header + airfoil['description'] = f.readline().rstrip() # remove newline f.readline() - self.fst_vt['AeroDyn15']['OLAF']['VelocityMethod'] = int_read(f.readline().split()[0]) - self.fst_vt['AeroDyn15']['OLAF']['TreeBranchFactor']= float_read(f.readline().split()[0]) - self.fst_vt['AeroDyn15']['OLAF']['PartPerSegment'] = int(f.readline().split()[0]) + airfoil['number_tables'] = int(f.readline().split()[0]) + + IDParam = [float_read(val) for val in f.readline().split()[0:airfoil['number_tables']]] + StallAngle = [float_read(val) for val in f.readline().split()[0:airfoil['number_tables']]] f.readline() f.readline() - self.fst_vt['AeroDyn15']['OLAF']['WrVTk'] = int(f.readline().split()[0]) - self.fst_vt['AeroDyn15']['OLAF']['nVTKBlades'] = int(f.readline().split()[0]) - self.fst_vt['AeroDyn15']['OLAF']['VTKCoord'] = int_read(f.readline().split()[0]) - self.fst_vt['AeroDyn15']['OLAF']['VTK_fps'] = float_read(f.readline().split()[0]) f.readline() + ZeroCn = [float_read(val) for val in f.readline().split()[0:airfoil['number_tables']]] + CnSlope = [float_read(val) for val in f.readline().split()[0:airfoil['number_tables']]] + CnPosStall = [float_read(val) for val in f.readline().split()[0:airfoil['number_tables']]] + CnNegStall = [float_read(val) for val in f.readline().split()[0:airfoil['number_tables']]] + alphaCdMin = [float_read(val) for val in f.readline().split()[0:airfoil['number_tables']]] + CdMin = [float_read(val) for val in f.readline().split()[0:airfoil['number_tables']]] + + data = [] + airfoil['af_tables'] = [] + while True: + line = f.readline() + if 'EOT' in line: + break + line = [float_read(s) for s in line.split()] + if len(line) < 1: + break + data.append(line) + + # loop through tables + for i in range(airfoil['number_tables']): + polar = {} + polar['IDParam'] = IDParam[i] + polar['StallAngle'] = StallAngle[i] + polar['ZeroCn'] = ZeroCn[i] + polar['CnSlope'] = CnSlope[i] + polar['CnPosStall'] = CnPosStall[i] + polar['CnNegStall'] = CnNegStall[i] + polar['alphaCdMin'] = alphaCdMin[i] + polar['CdMin'] = CdMin[i] + + alpha = [] + cl = [] + cd = [] + cm = [] + # read polar information line by line + for datai in data: + if len(datai) == airfoil['number_tables']*3+1: + alpha.append(datai[0]) + cl.append(datai[1 + 3*i]) + cd.append(datai[2 + 3*i]) + cm.append(datai[3 + 3*i]) + elif len(datai) == airfoil['number_tables']*2+1: + alpha.append(datai[0]) + cl.append(datai[1 + 2*i]) + cd.append(datai[2 + 2*i]) + + polar['alpha'] = alpha + polar['cl'] = cl + polar['cd'] = cd + polar['cm'] = cm + airfoil['af_tables'].append(polar) + f.close() + return airfoil def read_ServoDyn(self): # ServoDyn v1.05 Input File @@ -1549,10 +1445,8 @@ def read_DISCON_in(self): else: del self.fst_vt['DISCON_in'] - def read_HydroDyn(self): - # AeroDyn v2.03 + def read_HydroDyn(self, hd_file): - hd_file = os.path.normpath(os.path.join(self.FAST_directory, self.fst_vt['Fst']['HydroFile'])) f = open(hd_file) f.readline() @@ -1913,10 +1807,8 @@ def read_HydroDyn(self): f.close() - def read_SubDyn(self): - # SubDyn v1.01 + def read_SubDyn(self, sd_file): - sd_file = os.path.normpath(os.path.join(self.FAST_directory, self.fst_vt['Fst']['SubFile'])) f = open(sd_file) f.readline() f.readline() @@ -1935,7 +1827,7 @@ def read_SubDyn(self): self.fst_vt['SubDyn']['Nmodes'] = int_read(f.readline().split()[0]) self.fst_vt['SubDyn']['JDampings'] = int_read(f.readline().split()[0]) self.fst_vt['SubDyn']['GuyanDampMod'] = int_read(f.readline().split()[0]) - self.fst_vt['SubDyn']['RayleighDamp'] = [float(m) for m in f.readline().strip().replace(',','').split()[:2]] + self.fst_vt['SubDyn']['RayleighDamp'] = [float(m.replace(',','')) for m in f.readline().split()[:2]] self.fst_vt['SubDyn']['GuyanDampSize'] = int_read(f.readline().split()[0]) self.fst_vt['SubDyn']['GuyanDamp'] = np.array([[float(idx) for idx in f.readline().strip().split()[:6]] for i in range(self.fst_vt['SubDyn']['GuyanDampSize'])]) f.readline() @@ -2069,12 +1961,13 @@ def read_SubDyn(self): self.fst_vt['SubDyn']['YoungE2'][i] = float(ln[1]) self.fst_vt['SubDyn']['ShearG2'][i] = float(ln[2]) self.fst_vt['SubDyn']['MatDens2'][i] = float(ln[3]) - self.fst_vt['SubDyn']['XsecA'][i] = float(ln[4]) - self.fst_vt['SubDyn']['XsecAsx'][i] = float(ln[5]) - self.fst_vt['SubDyn']['XsecAsy'][i] = float(ln[6]) - self.fst_vt['SubDyn']['XsecJxx'][i] = float(ln[7]) - self.fst_vt['SubDyn']['XsecJyy'][i] = float(ln[8]) - self.fst_vt['SubDyn']['XsecJ0'][i] = float(ln[9]) + self.fst_vt['SubDyn']['XsecA'][i] = float(ln[4]) + self.fst_vt['SubDyn']['XsecAsx'][i] = float(ln[5]) + self.fst_vt['SubDyn']['XsecAsy'][i] = float(ln[6]) + self.fst_vt['SubDyn']['XsecJxx'][i] = float(ln[7]) + self.fst_vt['SubDyn']['XsecJyy'][i] = float(ln[8]) + self.fst_vt['SubDyn']['XsecJ0'][i] = float(ln[9]) + # CABLE PROPERTIES f.readline() self.fst_vt['SubDyn']['NCablePropSets'] = int_read(f.readline().split()[0]) self.fst_vt['SubDyn']['CablePropSetID'] = [None]*self.fst_vt['SubDyn']['NCablePropSets'] @@ -2192,14 +2085,12 @@ def read_SubDyn(self): f.close() - def read_MAP(self): + def read_MAP(self, map_file): # MAP++ # TODO: this is likely not robust enough, only tested on the Hywind Spar # additional lines in these tables are likely - map_file = os.path.normpath(os.path.join(self.FAST_directory, self.fst_vt['Fst']['MooringFile'])) - f = open(map_file) f.readline() f.readline() @@ -2243,11 +2134,9 @@ def read_MAP(self): f.readline() f.readline() self.fst_vt['MAP']['Option'] = [str(val) for val in f.readline().strip().split()] + f.close() - - def read_MoorDyn(self): - - moordyn_file = os.path.normpath(os.path.join(self.FAST_directory, self.fst_vt['Fst']['MooringFile'])) + def read_MoorDyn(self, moordyn_file): f = open(moordyn_file) @@ -2339,318 +2228,58 @@ def read_MoorDyn(self): channel_list = channels.split(',') self.set_outlist(self.fst_vt['outlist']['MoorDyn'], channel_list) data = f.readline() - f.close() + f.close() -class InputReader_FAST7(InputReader_Common): - """ FASTv7.02 input file reader """ - def execute(self): + self.read_MainInput() - self.read_AeroDyn_FAST7() - # if self.fst_vt['aerodyn']['wind_file_type'][1] == 'wnd': - # self.WndWindReader(self.fst_vt['aerodyn']['WindFile']) - # else: - # print 'Wind reader for file type .%s not implemented yet.' % self.fst_vt['aerodyn']['wind_file_type'][1] - self.read_ElastoDynBlade() - self.read_ElastoDynTower() - - def read_MainInput(self): - - fst_file = os.path.join(self.FAST_directory, self.FAST_InputFile) - f = open(fst_file) - - # FAST Inputs - f.readline() - f.readline() - self.fst_vt['description'] = f.readline().rstrip() - f.readline() - f.readline() - self.fst_vt['Fst7']['Echo'] = bool_read(f.readline().split()[0]) - self.fst_vt['Fst7']['ADAMSPrep'] = int(f.readline().split()[0]) - self.fst_vt['Fst7']['AnalMode'] = int(f.readline().split()[0]) - self.fst_vt['Fst7']['NumBl'] = int(f.readline().split()[0]) - self.fst_vt['Fst7']['TMax'] = float_read(f.readline().split()[0]) - self.fst_vt['Fst7']['DT'] = float_read(f.readline().split()[0]) - f.readline() - self.fst_vt['Fst7']['YCMode'] = int(f.readline().split()[0]) - self.fst_vt['Fst7']['TYCOn'] = float_read(f.readline().split()[0]) - self.fst_vt['Fst7']['PCMode'] = int(f.readline().split()[0]) - self.fst_vt['Fst7']['TPCOn'] = float_read(f.readline().split()[0]) - self.fst_vt['Fst7']['VSContrl'] = int(f.readline().split()[0]) - self.fst_vt['Fst7']['VS_RtGnSp'] = float_read(f.readline().split()[0]) - self.fst_vt['Fst7']['VS_RtTq'] = float_read(f.readline().split()[0]) - self.fst_vt['Fst7']['VS_Rgn2K'] = float_read(f.readline().split()[0]) - self.fst_vt['Fst7']['VS_SlPc'] = float_read(f.readline().split()[0]) - self.fst_vt['Fst7']['GenModel'] = int(f.readline().split()[0]) - self.fst_vt['Fst7']['GenTiStr'] = bool(f.readline().split()[0]) - self.fst_vt['Fst7']['GenTiStp'] = bool(f.readline().split()[0]) - self.fst_vt['Fst7']['SpdGenOn'] = float_read(f.readline().split()[0]) - self.fst_vt['Fst7']['TimGenOn'] = float_read(f.readline().split()[0]) - self.fst_vt['Fst7']['TimGenOf'] = float_read(f.readline().split()[0]) - self.fst_vt['Fst7']['HSSBrMode'] = int(f.readline().split()[0]) - self.fst_vt['Fst7']['THSSBrDp'] = float_read(f.readline().split()[0]) - self.fst_vt['Fst7']['TiDynBrk'] = float_read(f.readline().split()[0]) - self.fst_vt['Fst7']['TTpBrDp1'] = float_read(f.readline().split()[0]) - self.fst_vt['Fst7']['TTpBrDp2'] = float_read(f.readline().split()[0]) - self.fst_vt['Fst7']['TTpBrDp3'] = float_read(f.readline().split()[0]) - self.fst_vt['Fst7']['TBDepISp1'] = float_read(f.readline().split()[0]) - self.fst_vt['Fst7']['TBDepISp2'] = float_read(f.readline().split()[0]) - self.fst_vt['Fst7']['TBDepISp3'] = float_read(f.readline().split()[0]) - self.fst_vt['Fst7']['TYawManS'] = float_read(f.readline().split()[0]) - self.fst_vt['Fst7']['TYawManE'] = float_read(f.readline().split()[0]) - self.fst_vt['Fst7']['NacYawF'] = float_read(f.readline().split()[0]) - self.fst_vt['Fst7']['TPitManS1'] = float_read(f.readline().split()[0]) - self.fst_vt['Fst7']['TPitManS2'] = float_read(f.readline().split()[0]) - self.fst_vt['Fst7']['TPitManS3'] = float_read(f.readline().split()[0]) - self.fst_vt['Fst7']['TPitManE1'] = float_read(f.readline().split()[0]) - self.fst_vt['Fst7']['TPitManE2'] = float_read(f.readline().split()[0]) - self.fst_vt['Fst7']['TPitManE3'] = float_read(f.readline().split()[0]) - self.fst_vt['Fst7']['BlPitch1'] = float_read(f.readline().split()[0]) - self.fst_vt['Fst7']['BlPitch2'] = float_read(f.readline().split()[0]) - self.fst_vt['Fst7']['BlPitch3'] = float_read(f.readline().split()[0]) - self.fst_vt['Fst7']['B1PitchF1'] = float_read(f.readline().split()[0]) - self.fst_vt['Fst7']['B1PitchF2'] = float_read(f.readline().split()[0]) - self.fst_vt['Fst7']['B1PitchF3'] = float_read(f.readline().split()[0]) - f.readline() - self.fst_vt['Fst7']['Gravity'] = float_read(f.readline().split()[0]) - f.readline() - self.fst_vt['Fst7']['FlapDOF1'] = bool_read(f.readline().split()[0]) - self.fst_vt['Fst7']['FlapDOF2'] = bool_read(f.readline().split()[0]) - self.fst_vt['Fst7']['EdgeDOF'] = bool_read(f.readline().split()[0]) - self.fst_vt['Fst7']['TeetDOF'] = bool_read(f.readline().split()[0]) - self.fst_vt['Fst7']['DrTrDOF'] = bool_read(f.readline().split()[0]) - self.fst_vt['Fst7']['GenDOF'] = bool_read(f.readline().split()[0]) - self.fst_vt['Fst7']['YawDOF'] = bool_read(f.readline().split()[0]) - self.fst_vt['Fst7']['TwFADOF1'] = bool_read(f.readline().split()[0]) - self.fst_vt['Fst7']['TwFADOF2'] = bool_read(f.readline().split()[0]) - self.fst_vt['Fst7']['TwSSDOF1'] = bool_read(f.readline().split()[0]) - self.fst_vt['Fst7']['TwSSDOF2'] = bool_read(f.readline().split()[0]) - self.fst_vt['Fst7']['CompAero'] = bool_read(f.readline().split()[0]) - self.fst_vt['Fst7']['CompNoise'] = bool_read(f.readline().split()[0]) - f.readline() - self.fst_vt['Fst7']['OoPDefl'] = float_read(f.readline().split()[0]) - self.fst_vt['Fst7']['IPDefl'] = float_read(f.readline().split()[0]) - self.fst_vt['Fst7']['TeetDefl'] = float_read(f.readline().split()[0]) - self.fst_vt['Fst7']['Azimuth'] = float_read(f.readline().split()[0]) - self.fst_vt['Fst7']['RotSpeed'] = float_read(f.readline().split()[0]) - self.fst_vt['Fst7']['NacYaw'] = float_read(f.readline().split()[0]) - self.fst_vt['Fst7']['TTDspFA'] = float_read(f.readline().split()[0]) - self.fst_vt['Fst7']['TTDspSS'] = float_read(f.readline().split()[0]) - f.readline() - self.fst_vt['Fst7']['TipRad'] = float_read(f.readline().split()[0]) - self.fst_vt['Fst7']['HubRad'] = float_read(f.readline().split()[0]) - self.fst_vt['Fst7']['PSpnElN'] = int(f.readline().split()[0]) - self.fst_vt['Fst7']['UndSling'] = float_read(f.readline().split()[0]) - self.fst_vt['Fst7']['HubCM'] = float_read(f.readline().split()[0]) - self.fst_vt['Fst7']['OverHang'] = float_read(f.readline().split()[0]) - self.fst_vt['Fst7']['NacCMxn'] = float_read(f.readline().split()[0]) - self.fst_vt['Fst7']['NacCMyn'] = float_read(f.readline().split()[0]) - self.fst_vt['Fst7']['NacCMzn'] = float_read(f.readline().split()[0]) - self.fst_vt['Fst7']['TowerHt'] = float_read(f.readline().split()[0]) - self.fst_vt['Fst7']['Twr2Shft'] = float_read(f.readline().split()[0]) - self.fst_vt['Fst7']['TwrRBHt'] = float_read(f.readline().split()[0]) - self.fst_vt['Fst7']['ShftTilt'] = float_read(f.readline().split()[0]) - self.fst_vt['Fst7']['Delta3'] = float_read(f.readline().split()[0]) - self.fst_vt['Fst7']['PreCone(1)'] = float_read(f.readline().split()[0]) - self.fst_vt['Fst7']['PreCone(2)'] = float_read(f.readline().split()[0]) - self.fst_vt['Fst7']['PreCone(3)'] = float_read(f.readline().split()[0]) - self.fst_vt['Fst7']['AzimB1Up'] = float_read(f.readline().split()[0]) - f.readline() - self.fst_vt['Fst7']['YawBrMass'] = float_read(f.readline().split()[0]) - self.fst_vt['Fst7']['NacMass'] = float_read(f.readline().split()[0]) - self.fst_vt['Fst7']['HubMass'] = float_read(f.readline().split()[0]) - self.fst_vt['Fst7']['TipMass(1)'] = float_read(f.readline().split()[0]) - self.fst_vt['Fst7']['TipMass(2)'] = float_read(f.readline().split()[0]) - self.fst_vt['Fst7']['TipMass(3)'] = float_read(f.readline().split()[0]) - self.fst_vt['Fst7']['NacYIner'] = float_read(f.readline().split()[0]) - self.fst_vt['Fst7']['GenIner'] = float_read(f.readline().split()[0]) - self.fst_vt['Fst7']['HubIner'] = float_read(f.readline().split()[0]) - f.readline() - self.fst_vt['Fst7']['GBoxEff'] = float_read(f.readline().split()[0]) - self.fst_vt['Fst7']['GenEff'] = float_read(f.readline().split()[0]) - self.fst_vt['Fst7']['GBRatio'] = float_read(f.readline().split()[0]) - self.fst_vt['Fst7']['GBRevers'] = bool_read(f.readline().split()[0]) - self.fst_vt['Fst7']['HSSBrTqF'] = float_read(f.readline().split()[0]) - self.fst_vt['Fst7']['HSSBrDT'] = float_read(f.readline().split()[0]) - self.fst_vt['Fst7']['DynBrkFi'] = f.readline().split()[0] - self.fst_vt['Fst7']['DTTorSpr'] = float_read(f.readline().split()[0]) - self.fst_vt['Fst7']['DTTorDmp'] = float_read(f.readline().split()[0]) - f.readline() - self.fst_vt['Fst7']['SIG_SlPc'] = float_read(f.readline().split()[0]) - self.fst_vt['Fst7']['SIG_SySp'] = float_read(f.readline().split()[0]) - self.fst_vt['Fst7']['SIG_RtTq'] = float_read(f.readline().split()[0]) - self.fst_vt['Fst7']['SIG_PORt'] = float_read(f.readline().split()[0]) - f.readline() - self.fst_vt['Fst7']['TEC_Freq'] = float_read(f.readline().split()[0]) - self.fst_vt['Fst7']['TEC_NPol'] = int(f.readline().split()[0]) - self.fst_vt['Fst7']['TEC_SRes'] = float_read(f.readline().split()[0]) - self.fst_vt['Fst7']['TEC_RRes'] = float_read(f.readline().split()[0]) - self.fst_vt['Fst7']['TEC_VLL'] = float_read(f.readline().split()[0]) - self.fst_vt['Fst7']['TEC_SLR'] = float_read(f.readline().split()[0]) - self.fst_vt['Fst7']['TEC_RLR'] = float_read(f.readline().split()[0]) - self.fst_vt['Fst7']['TEC_MR'] = float_read(f.readline().split()[0]) - f.readline() - self.fst_vt['Fst7']['PtfmModel'] = int(f.readline().split()[0]) - self.fst_vt['Fst7']['PtfmFile'] = f.readline().split()[0][1:-1] - f.readline() - self.fst_vt['Fst7']['TwrNodes'] = int(f.readline().split()[0]) - self.fst_vt['Fst7']['TwrFile'] = f.readline().split()[0][1:-1] - f.readline() - self.fst_vt['Fst7']['YawSpr'] = float_read(f.readline().split()[0]) - self.fst_vt['Fst7']['YawDamp'] = float_read(f.readline().split()[0]) - self.fst_vt['Fst7']['YawNeut'] = float_read(f.readline().split()[0]) - f.readline() - self.fst_vt['Fst7']['Furling'] = bool_read(f.readline().split()[0]) - self.fst_vt['Fst7']['FurlFile'] = f.readline().split()[0] - f.readline() - self.fst_vt['Fst7']['TeetMod'] = int(f.readline().split()[0]) - self.fst_vt['Fst7']['TeetDmpP'] = float_read(f.readline().split()[0]) - self.fst_vt['Fst7']['TeetDmp'] = float_read(f.readline().split()[0]) - self.fst_vt['Fst7']['TeetCDmp'] = float_read(f.readline().split()[0]) - self.fst_vt['Fst7']['TeetSStP'] = float_read(f.readline().split()[0]) - self.fst_vt['Fst7']['TeetHStP'] = float_read(f.readline().split()[0]) - self.fst_vt['Fst7']['TeetSSSp'] = float_read(f.readline().split()[0]) - self.fst_vt['Fst7']['TeetHSSp'] = float_read(f.readline().split()[0]) - f.readline() - self.fst_vt['Fst7']['TBDrConN'] = float_read(f.readline().split()[0]) - self.fst_vt['Fst7']['TBDrConD'] = float_read(f.readline().split()[0]) - self.fst_vt['Fst7']['TpBrDT'] = float_read(f.readline().split()[0]) - f.readline() - self.fst_vt['Fst7']['BldFile1'] = f.readline().split()[0][1:-1] # TODO - different blade files - self.fst_vt['Fst7']['BldFile2'] = f.readline().split()[0][1:-1] - self.fst_vt['Fst7']['BldFile3'] = f.readline().split()[0][1:-1] - f.readline() - self.fst_vt['Fst7']['ADFile'] = f.readline().split()[0][1:-1] - f.readline() - self.fst_vt['Fst7']['NoiseFile'] = f.readline().split()[0] - f.readline() - self.fst_vt['Fst7']['ADAMSFile'] = f.readline().split()[0] - f.readline() - self.fst_vt['Fst7']['LinFile'] = f.readline().split()[0] - f.readline() - self.fst_vt['Fst7']['SumPrint'] = bool_read(f.readline().split()[0]) - self.fst_vt['Fst7']['OutFileFmt'] = int(f.readline().split()[0]) - self.fst_vt['Fst7']['TabDelim'] = bool_read(f.readline().split()[0]) - - self.fst_vt['Fst7']['OutFmt'] = f.readline().split()[0] - self.fst_vt['Fst7']['TStart'] = float_read(f.readline().split()[0]) - self.fst_vt['Fst7']['DecFact'] = int(f.readline().split()[0]) - self.fst_vt['Fst7']['SttsTime'] = float_read(f.readline().split()[0]) - self.fst_vt['Fst7']['NcIMUxn'] = float_read(f.readline().split()[0]) - self.fst_vt['Fst7']['NcIMUyn'] = float_read(f.readline().split()[0]) - self.fst_vt['Fst7']['NcIMUzn'] = float_read(f.readline().split()[0]) - self.fst_vt['Fst7']['ShftGagL'] = float_read(f.readline().split()[0]) - self.fst_vt['Fst7']['NTwGages'] = int(f.readline().split()[0]) - twrg = f.readline().split(',') - if self.fst_vt['Fst7']['NTwGages'] != 0: #loop over elements if there are gauges to be added, otherwise assign directly - for i in range(self.fst_vt['Fst7']['NTwGages']): - self.fst_vt['Fst7']['TwrGagNd'].append(twrg[i]) - self.fst_vt['Fst7']['TwrGagNd'][-1] = self.fst_vt['Fst7']['TwrGagNd'][-1][0:2] - else: - self.fst_vt['Fst7']['TwrGagNd'] = twrg - self.fst_vt['Fst7']['TwrGagNd'][-1] = self.fst_vt['Fst7']['TwrGagNd'][-1][0:4] - self.fst_vt['Fst7']['NBlGages'] = int(f.readline().split()[0]) - blg = f.readline().split(',') - if self.fst_vt['Fst7']['NBlGages'] != 0: - for i in range(self.fst_vt['Fst7']['NBlGages']): - self.fst_vt['Fst7']['BldGagNd'].append(blg[i]) - self.fst_vt['Fst7']['BldGagNd'][-1] = self.fst_vt['Fst7']['BldGagNd'][-1][0:2] - else: - self.fst_vt['Fst7']['BldGagNd'] = blg - self.fst_vt['Fst7']['BldGagNd'][-1] = self.fst_vt['Fst7']['BldGagNd'][-1][0:4] - - # Outlist (TODO - detailed categorization) - f.readline() - data = f.readline() - while data.split()[0] != 'END': - channels = data.split('"') - channel_list = channels[1].split(',') - self.set_outlist(self.fst_vt['outlist7'], channel_list) - data = f.readline() - - def read_AeroDyn_FAST7(self): - - ad_file = os.path.join(self.FAST_directory, self.fst_vt['Fst7']['ADFile']) - f = open(ad_file) - - # skip lines and check if nondimensional - f.readline() - self.fst_vt['AeroDyn14']['SysUnits'] = f.readline().split()[0] - self.fst_vt['AeroDyn14']['StallMod'] = f.readline().split()[0] - self.fst_vt['AeroDyn14']['UseCm'] = f.readline().split()[0] - self.fst_vt['AeroDyn14']['InfModel'] = f.readline().split()[0] - self.fst_vt['AeroDyn14']['IndModel'] = f.readline().split()[0] - self.fst_vt['AeroDyn14']['AToler'] = float_read(f.readline().split()[0]) - self.fst_vt['AeroDyn14']['TLModel'] = f.readline().split()[0] - self.fst_vt['AeroDyn14']['HLModel'] = f.readline().split()[0] - self.fst_vt['AeroDyn14']['WindFile'] = os.path.normpath(os.path.join(os.path.split(ad_file)[0], f.readline().split()[0][1:-1])) - self.fst_vt['AeroDyn14']['wind_file_type'] = self.fst_vt['AeroDyn14']['WindFile'].split('.') - self.fst_vt['AeroDyn14']['HH'] = float_read(f.readline().split()[0]) - self.fst_vt['AeroDyn14']['TwrShad'] = float_read(f.readline().split()[0]) - self.fst_vt['AeroDyn14']['ShadHWid'] = float_read(f.readline().split()[0]) - self.fst_vt['AeroDyn14']['T_Shad_Refpt'] = float_read(f.readline().split()[0]) - self.fst_vt['AeroDyn14']['AirDens'] = float_read(f.readline().split()[0]) - self.fst_vt['AeroDyn14']['KinVisc'] = float_read(f.readline().split()[0]) - self.fst_vt['AeroDyn14']['DTAero'] = float_read(f.readline().split()[0]) - - self.fst_vt['AeroDyn14']['NumFoil'] = int(f.readline().split()[0]) - self.fst_vt['AeroDyn14']['FoilNm'] = [None] * self.fst_vt['AeroDyn14']['NumFoil'] - for i in range(self.fst_vt['AeroDyn14']['NumFoil']): - af_filename = f.readline().split()[0] - af_filename = fix_path(af_filename) - self.fst_vt['AeroDyn14']['FoilNm'][i] = af_filename[1:-1] - - self.fst_vt['AeroDynBlade']['BldNodes'] = int(f.readline().split()[0]) - f.readline() - self.fst_vt['AeroDynBlade']['RNodes'] = [None] * self.fst_vt['AeroDynBlade']['BldNodes'] - self.fst_vt['AeroDynBlade']['AeroTwst'] = [None] * self.fst_vt['AeroDynBlade']['BldNodes'] - self.fst_vt['AeroDynBlade']['DRNodes'] = [None] * self.fst_vt['AeroDynBlade']['BldNodes'] - self.fst_vt['AeroDynBlade']['Chord'] = [None] * self.fst_vt['AeroDynBlade']['BldNodes'] - self.fst_vt['AeroDynBlade']['NFoil'] = [None] * self.fst_vt['AeroDynBlade']['BldNodes'] - self.fst_vt['AeroDynBlade']['PrnElm'] = [None] * self.fst_vt['AeroDynBlade']['BldNodes'] - for i in range(self.fst_vt['AeroDynBlade']['BldNodes']): - data = f.readline().split() - self.fst_vt['AeroDynBlade']['RNodes'][i] = float_read(data[0]) - self.fst_vt['AeroDynBlade']['AeroTwst'][i] = float_read(data[1]) - self.fst_vt['AeroDynBlade']['DRNodes'][i] = float_read(data[2]) - self.fst_vt['AeroDynBlade']['Chord'][i] = float_read(data[3]) - self.fst_vt['AeroDynBlade']['NFoil'][i] = int(data[4]) - self.fst_vt['AeroDynBlade']['PrnElm'][i] = data[5] - - f.close() - - # create airfoil objects - self.fst_vt['AeroDynBlade']['af_data'] = [] - for i in range(self.fst_vt['AeroDyn14']['NumFoil']): - self.fst_vt['AeroDynBlade']['af_data'].append(self.read_AeroDyn14Polar(os.path.join(self.FAST_directory,self.fst_vt['AeroDyn14']['FoilNm'][i]))) - + ed_file = os.path.join(self.FAST_directory, self.fst_vt['Fst']['EDFile']) + self.read_ElastoDyn(ed_file) + if not os.path.isabs(self.fst_vt['ElastoDyn']['BldFile1']): + ed_blade_file = os.path.join(os.path.dirname(ed_file), self.fst_vt['ElastoDyn']['BldFile1']) + self.read_ElastoDynBlade(ed_blade_file) + if not os.path.isabs(self.fst_vt['ElastoDyn']['TwrFile']): + ed_tower_file = os.path.join(os.path.dirname(ed_file), self.fst_vt['ElastoDyn']['TwrFile']) + self.read_ElastoDynTower(ed_tower_file) + self.read_InflowWind() + # AeroDyn version selection + if self.fst_vt['Fst']['CompAero'] == 1: + self.read_AeroDyn14() + elif self.fst_vt['Fst']['CompAero'] == 2: + self.read_AeroDyn15() + + if self.fst_vt['Fst']['CompServo'] == 1: + self.read_ServoDyn() + # Would read StCs here + if ROSCO: + self.read_DISCON_in() + hd_file = os.path.normpath(os.path.join(self.FAST_directory, self.fst_vt['Fst']['HydroFile'])) + if os.path.isfile(hd_file): + self.read_HydroDyn(hd_file) + sd_file = os.path.normpath(os.path.join(self.FAST_directory, self.fst_vt['Fst']['SubFile'])) + if os.path.isfile(sd_file): + self.read_SubDyn(sd_file) + if self.fst_vt['Fst']['CompMooring'] == 1: # only MAP++ implemented for mooring models + map_file = os.path.normpath(os.path.join(self.FAST_directory, self.fst_vt['Fst']['MooringFile'])) + if os.path.isfile(map_file): + self.read_MAP(map_file) + if self.fst_vt['Fst']['CompMooring'] == 3: # MoorDyn implimented + moordyn_file = os.path.normpath(os.path.join(self.FAST_directory, self.fst_vt['Fst']['MooringFile'])) + if os.path.isfile(moordyn_file): + self.read_MoorDyn(moordyn_file) + bd_file = os.path.normpath(os.path.join(self.FAST_directory, self.fst_vt['Fst']['BDBldFile(1)'])) + if os.path.isfile(bd_file): + self.read_BeamDyn(bd_file) if __name__=="__main__": - FAST_ver = 'OpenFAST' - read_yaml = False - - if read_yaml: - fast = InputReader_Common(FAST_ver=FAST_ver) - fast.FAST_yamlfile = 'temp/OpenFAST/test.yaml' - fast.read_yaml() - - else: - if FAST_ver.lower() == 'fast7': - fast = InputReader_FAST7(FAST_ver=FAST_ver) - fast.FAST_InputFile = 'Test16.fst' # FAST input file (ext=.fst) - fast.FAST_directory = 'C:/Users/egaertne/WT_Codes/models/FAST_v7.02.00d-bjj/CertTest/' # Path to fst directory files - - elif FAST_ver.lower() == 'fast8': - fast = InputReader_OpenFAST(FAST_ver=FAST_ver) - fast.FAST_InputFile = 'NREL5MW_onshore.fst' # FAST input file (ext=.fst) - fast.FAST_directory = 'C:/Users/egaertne/WT_Codes/models/FAST_v8.16.00a-bjj/ref/5mw_onshore/' # Path to fst directory files - - elif FAST_ver.lower() == 'openfast': - fast = InputReader_OpenFAST(FAST_ver=FAST_ver) - fast.FAST_InputFile = '5MW_OC3Spar_DLL_WTurb_WavesIrr.fst' # FAST input file (ext=.fst) - fast.FAST_directory = 'C:/Users/egaertne/WT_Codes/models/openfast-dev/r-test/glue-codes/openfast/5MW_OC3Spar_DLL_WTurb_WavesIrr' # Path to fst directory files - - fast.execute() + examples_dir = os.path.dirname( os.path.dirname( os.path.dirname( os.path.realpath(__file__) ) ) ) + os.sep + + fast = InputReader_OpenFAST() + fast.FAST_InputFile = 'IEA-15-240-RWT-UMaineSemi.fst' # FAST input file (ext=.fst) + fast.FAST_directory = os.path.join(examples_dir, 'examples', '01_aeroelasticse', + 'OpenFAST_models', 'IEA-15-240-RWT', + 'IEA-15-240-RWT-UMaineSemi') # Path to fst directory files + fast.execute() diff --git a/ROSCO_toolbox/ofTools/fast_io/FAST_vars_out.py b/ROSCO_toolbox/ofTools/fast_io/FAST_vars_out.py index 61ef8dcc..358af810 100644 --- a/ROSCO_toolbox/ofTools/fast_io/FAST_vars_out.py +++ b/ROSCO_toolbox/ofTools/fast_io/FAST_vars_out.py @@ -2543,17 +2543,17 @@ AeroDyn['RtVAvgyh'] = False # (m/s); Rotor-disk-averaged relative wind velocity (y-component); the hub coordinate system AeroDyn['RtVAvgzh'] = False # (m/s); Rotor-disk-averaged relative wind velocity (z-component); the hub coordinate system AeroDyn['RtSkew'] = False # (deg); Rotor inflow-skew angle; -AeroDyn['RtAeroFxh'] = False # (N); Total rotor aerodynamic load (force in x direction); the hub coordinate system -AeroDyn['RtAeroFyh'] = False # (N); Total rotor aerodynamic load (force in y direction); the hub coordinate system -AeroDyn['RtAeroFzh'] = False # (N); Total rotor aerodynamic load (force in z direction); the hub coordinate system -AeroDyn['RtAeroMxh'] = False # (N m); Total rotor aerodynamic load (moment in x direction); the hub coordinate system -AeroDyn['RtAeroMyh'] = False # (N m); Total rotor aerodynamic load (moment in y direction); the hub coordinate system -AeroDyn['RtAeroMzh'] = False # (N m); Total rotor aerodynamic load (moment in z direction); the hub coordinate system -AeroDyn['RtAeroPwr'] = False # (W); Rotor aerodynamic power; +AeroDyn['RtFldFxh'] = False # (N); Total rotor aerodynamic load (force in x direction); the hub coordinate system +AeroDyn['RtFldFyh'] = False # (N); Total rotor aerodynamic load (force in y direction); the hub coordinate system +AeroDyn['RtFldFzh'] = False # (N); Total rotor aerodynamic load (force in z direction); the hub coordinate system +AeroDyn['RtFldMxh'] = False # (N m); Total rotor aerodynamic load (moment in x direction); the hub coordinate system +AeroDyn['RtFldMyh'] = False # (N m); Total rotor aerodynamic load (moment in y direction); the hub coordinate system +AeroDyn['RtFldMzh'] = False # (N m); Total rotor aerodynamic load (moment in z direction); the hub coordinate system +AeroDyn['RtFldPwr'] = False # (W); Rotor aerodynamic power; AeroDyn['RtArea'] = False # (m^2); Rotor swept area; -AeroDyn['RtAeroCp'] = False # (-); Rotor aerodynamic power coefficient; -AeroDyn['RtAeroCq'] = False # (-); Rotor aerodynamic torque coefficient; -AeroDyn['RtAeroCt'] = False # (-); Rotor aerodynamic thrust coefficient; +AeroDyn['RtFldCp'] = False # (-); Rotor aerodynamic power coefficient; +AeroDyn['RtFldCq'] = False # (-); Rotor aerodynamic torque coefficient; +AeroDyn['RtFldCt'] = False # (-); Rotor aerodynamic thrust coefficient; """ InflowWind """ diff --git a/ROSCO_toolbox/ofTools/fast_io/FAST_writer.py b/ROSCO_toolbox/ofTools/fast_io/FAST_writer.py index 8380c686..852b3594 100644 --- a/ROSCO_toolbox/ofTools/fast_io/FAST_writer.py +++ b/ROSCO_toolbox/ofTools/fast_io/FAST_writer.py @@ -4,7 +4,7 @@ import numpy as np from functools import reduce -from ROSCO_toolbox.ofTools.fast_io.FAST_reader import InputReader_Common, InputReader_OpenFAST, InputReader_FAST7 +from ROSCO_toolbox.ofTools.fast_io.FAST_reader import InputReader_OpenFAST from ROSCO_toolbox.ofTools.fast_io.FAST_vars import FstModel from ROSCO_toolbox.utilities import write_rotor_performance, write_DISCON @@ -38,32 +38,16 @@ def int_default_out(val): def get_dict(vartree, branch): return reduce(operator.getitem, branch, vartree) -class InputWriter_Common(object): - """ Methods for writing input files that are (relatively) unchanged across FAST versions.""" +class InputWriter_OpenFAST(object): + """ Methods to write OpenFAST input files.""" - def __init__(self, **kwargs): + def __init__(self): - self.FAST_ver = 'OPENFAST' self.FAST_namingOut = None #Master FAST file self.FAST_runDirectory = None #Output directory - self.fst_vt = FstModel + self.fst_vt = {} self.fst_update = {} - # Optional population class attributes from key word arguments - for (k, w) in kwargs.items(): - try: - setattr(self, k, w) - except: - pass - - super(InputWriter_Common, self).__init__() - - def write_yaml(self): - self.FAST_yamlfile = os.path.join(self.FAST_runDirectory, self.FAST_namingOut+'.yaml') - f = open(self.FAST_yamlfile, "w") - yaml.dump(self.fst_vt, f) - - def update(self, fst_update={}): """ Change fast variables based on the user supplied values """ if fst_update: @@ -102,160 +86,6 @@ def loop_dict(vartree, branch): # set fast variables to update values loop_dict(self.fst_update, []) - - def write_ElastoDynBlade(self): - - self.fst_vt['ElastoDyn']['BldFile1'] = self.FAST_namingOut + '_ElastoDyn_blade.dat' - self.fst_vt['ElastoDyn']['BldFile2'] = self.fst_vt['ElastoDyn']['BldFile1'] - self.fst_vt['ElastoDyn']['BldFile3'] = self.fst_vt['ElastoDyn']['BldFile1'] - blade_file = os.path.join(self.FAST_runDirectory,self.fst_vt['ElastoDyn']['BldFile1']) - f = open(blade_file, 'w') - - f.write('------- ELASTODYN V1.00.* INDIVIDUAL BLADE INPUT FILE --------------------------\n') - f.write('Generated with AeroElasticSE FAST driver\n') - f.write('---------------------- BLADE PARAMETERS ----------------------------------------\n') - f.write('{:<22} {:<11} {:}'.format(self.fst_vt['ElastoDynBlade']['NBlInpSt'], 'NBlInpSt', '- Number of blade input stations (-)\n')) - f.write('{:<22} {:<11} {:}'.format(self.fst_vt['ElastoDynBlade']['BldFlDmp1'], 'BldFlDmp1', '- Blade flap mode #1 structural damping in percent of critical (%)\n')) - f.write('{:<22} {:<11} {:}'.format(self.fst_vt['ElastoDynBlade']['BldFlDmp2'], 'BldFlDmp2', '- Blade flap mode #2 structural damping in percent of critical (%)\n')) - f.write('{:<22} {:<11} {:}'.format(self.fst_vt['ElastoDynBlade']['BldEdDmp1'], 'BldEdDmp1', '- Blade edge mode #1 structural damping in percent of critical (%)\n')) - f.write('---------------------- BLADE ADJUSTMENT FACTORS --------------------------------\n') - f.write('{:<22} {:<11} {:}'.format(self.fst_vt['ElastoDynBlade']['FlStTunr1'], 'FlStTunr1', '- Blade flapwise modal stiffness tuner, 1st mode (-)\n')) - f.write('{:<22} {:<11} {:}'.format(self.fst_vt['ElastoDynBlade']['FlStTunr2'], 'FlStTunr2', '- Blade flapwise modal stiffness tuner, 2nd mode (-)\n')) - f.write('{:<22} {:<11} {:}'.format(self.fst_vt['ElastoDynBlade']['AdjBlMs'], 'AdjBlMs', '- Factor to adjust blade mass density (-)\n')) - f.write('{:<22} {:<11} {:}'.format(self.fst_vt['ElastoDynBlade']['AdjFlSt'], 'AdjFlSt', '- Factor to adjust blade flap stiffness (-)\n')) - f.write('{:<22} {:<11} {:}'.format(self.fst_vt['ElastoDynBlade']['AdjEdSt'], 'AdjEdSt', '- Factor to adjust blade edge stiffness (-)\n')) - f.write('---------------------- DISTRIBUTED BLADE PROPERTIES ----------------------------\n') - f.write(' BlFract PitchAxis StrcTwst BMassDen FlpStff EdgStff\n') - f.write(' (-) (-) (deg) (kg/m) (Nm^2) (Nm^2)\n') - BlFract = self.fst_vt['ElastoDynBlade']['BlFract'] - PitchAxis = self.fst_vt['ElastoDynBlade']['PitchAxis'] - StrcTwst = self.fst_vt['ElastoDynBlade']['StrcTwst'] - BMassDen = self.fst_vt['ElastoDynBlade']['BMassDen'] - FlpStff = self.fst_vt['ElastoDynBlade']['FlpStff'] - EdgStff = self.fst_vt['ElastoDynBlade']['EdgStff'] - for BlFracti, PitchAxisi, StrcTwsti, BMassDeni, FlpStffi, EdgStffi in zip(BlFract, PitchAxis, StrcTwst, BMassDen, FlpStff, EdgStff): - f.write('{: 2.15e} {: 2.15e} {: 2.15e} {: 2.15e} {: 2.15e} {: 2.15e}\n'.format(BlFracti, PitchAxisi, StrcTwsti, BMassDeni, FlpStffi, EdgStffi)) - f.write('---------------------- BLADE MODE SHAPES ---------------------------------------\n') - f.write('{:<22} {:<11} {:}'.format(self.fst_vt['ElastoDynBlade']['BldFl1Sh'][0], 'BldFl1Sh(2)', '- Flap mode 1, coeff of x^2\n')) - f.write('{:<22} {:<11} {:}'.format(self.fst_vt['ElastoDynBlade']['BldFl1Sh'][1], 'BldFl1Sh(3)', '- , coeff of x^3\n')) - f.write('{:<22} {:<11} {:}'.format(self.fst_vt['ElastoDynBlade']['BldFl1Sh'][2], 'BldFl1Sh(4)', '- , coeff of x^4\n')) - f.write('{:<22} {:<11} {:}'.format(self.fst_vt['ElastoDynBlade']['BldFl1Sh'][3], 'BldFl1Sh(5)', '- , coeff of x^5\n')) - f.write('{:<22} {:<11} {:}'.format(self.fst_vt['ElastoDynBlade']['BldFl1Sh'][4], 'BldFl1Sh(6)', '- , coeff of x^6\n')) - f.write('{:<22} {:<11} {:}'.format(self.fst_vt['ElastoDynBlade']['BldFl2Sh'][0], 'BldFl2Sh(2)', '- Flap mode 2, coeff of x^2\n')) - f.write('{:<22} {:<11} {:}'.format(self.fst_vt['ElastoDynBlade']['BldFl2Sh'][1], 'BldFl2Sh(3)', '- , coeff of x^3\n')) - f.write('{:<22} {:<11} {:}'.format(self.fst_vt['ElastoDynBlade']['BldFl2Sh'][2], 'BldFl2Sh(4)', '- , coeff of x^4\n')) - f.write('{:<22} {:<11} {:}'.format(self.fst_vt['ElastoDynBlade']['BldFl2Sh'][3], 'BldFl2Sh(5)', '- , coeff of x^5\n')) - f.write('{:<22} {:<11} {:}'.format(self.fst_vt['ElastoDynBlade']['BldFl2Sh'][4], 'BldFl2Sh(6)', '- , coeff of x^6\n')) - f.write('{:<22} {:<11} {:}'.format(self.fst_vt['ElastoDynBlade']['BldEdgSh'][0], 'BldEdgSh(2)', '- Edge mode 1, coeff of x^2\n')) - f.write('{:<22} {:<11} {:}'.format(self.fst_vt['ElastoDynBlade']['BldEdgSh'][1], 'BldEdgSh(3)', '- , coeff of x^3\n')) - f.write('{:<22} {:<11} {:}'.format(self.fst_vt['ElastoDynBlade']['BldEdgSh'][2], 'BldEdgSh(4)', '- , coeff of x^4\n')) - f.write('{:<22} {:<11} {:}'.format(self.fst_vt['ElastoDynBlade']['BldEdgSh'][3], 'BldEdgSh(5)', '- , coeff of x^5\n')) - f.write('{:<22} {:<11} {:}'.format(self.fst_vt['ElastoDynBlade']['BldEdgSh'][4], 'BldEdgSh(6)', '- , coeff of x^6\n')) - - f.close() - - - def write_ElastoDynTower(self): - - self.fst_vt['ElastoDyn']['TwrFile'] = self.FAST_namingOut + '_ElastoDyn_tower.dat' - tower_file = os.path.join(self.FAST_runDirectory,self.fst_vt['ElastoDyn']['TwrFile']) - f = open(tower_file, 'w') - - f.write('------- ELASTODYN V1.00.* TOWER INPUT FILE -------------------------------------\n') - f.write('Generated with AeroElasticSE FAST driver\n') - f.write('---------------------- TOWER PARAMETERS ----------------------------------------\n') - if self.FAST_ver.lower() == 'fast7': - f.write('---\n') - f.write('{:<22} {:<11} {:}'.format(self.fst_vt['ElastoDynTower']['NTwInpSt'], 'NTwInpSt', '- Number of input stations to specify tower geometry\n')) - if self.FAST_ver.lower() == 'fast7': - f.write('{:}\n'.format(self.fst_vt['ElastoDynTower']['CalcTMode'])) - f.write('{:<22} {:<11} {:}'.format(self.fst_vt['ElastoDynTower']['TwrFADmp1'], 'TwrFADmp(1)', '- Tower 1st fore-aft mode structural damping ratio (%)\n')) - f.write('{:<22} {:<11} {:}'.format(self.fst_vt['ElastoDynTower']['TwrFADmp2'], 'TwrFADmp(2)', '- Tower 2nd fore-aft mode structural damping ratio (%)\n')) - f.write('{:<22} {:<11} {:}'.format(self.fst_vt['ElastoDynTower']['TwrSSDmp1'], 'TwrSSDmp(1)', '- Tower 1st side-to-side mode structural damping ratio (%)\n')) - f.write('{:<22} {:<11} {:}'.format(self.fst_vt['ElastoDynTower']['TwrSSDmp2'], 'TwrSSDmp(2)', '- Tower 2nd side-to-side mode structural damping ratio (%)\n')) - f.write('---------------------- TOWER ADJUSTMUNT FACTORS --------------------------------\n') - f.write('{:<22} {:<11} {:}'.format(self.fst_vt['ElastoDynTower']['FAStTunr1'], 'FAStTunr(1)', '- Tower fore-aft modal stiffness tuner, 1st mode (-)\n')) - f.write('{:<22} {:<11} {:}'.format(self.fst_vt['ElastoDynTower']['FAStTunr2'], 'FAStTunr(2)', '- Tower fore-aft modal stiffness tuner, 2nd mode (-)\n')) - f.write('{:<22} {:<11} {:}'.format(self.fst_vt['ElastoDynTower']['SSStTunr1'], 'SSStTunr(1)', '- Tower side-to-side stiffness tuner, 1st mode (-)\n')) - f.write('{:<22} {:<11} {:}'.format(self.fst_vt['ElastoDynTower']['SSStTunr2'], 'SSStTunr(2)', '- Tower side-to-side stiffness tuner, 2nd mode (-)\n')) - f.write('{:<22} {:<11} {:}'.format(self.fst_vt['ElastoDynTower']['AdjTwMa'], 'AdjTwMa', '- Factor to adjust tower mass density (-)\n')) - f.write('{:<22} {:<11} {:}'.format(self.fst_vt['ElastoDynTower']['AdjFASt'], 'AdjFASt', '- Factor to adjust tower fore-aft stiffness (-)\n')) - f.write('{:<22} {:<11} {:}'.format(self.fst_vt['ElastoDynTower']['AdjSSSt'], 'AdjSSSt', '- Factor to adjust tower side-to-side stiffness (-)\n')) - f.write('---------------------- DISTRIBUTED TOWER PROPERTIES ----------------------------\n') - f.write(' HtFract TMassDen TwFAStif TwSSStif\n') - f.write(' (-) (kg/m) (Nm^2) (Nm^2)\n') - HtFract = self.fst_vt['ElastoDynTower']['HtFract'] - TMassDen = self.fst_vt['ElastoDynTower']['TMassDen'] - TwFAStif = self.fst_vt['ElastoDynTower']['TwFAStif'] - TwSSStif = self.fst_vt['ElastoDynTower']['TwSSStif'] - if self.FAST_ver.lower() == 'fast7': - gs = self.fst_vt['ElastoDynTower']['TwGJStif'] - es = self.fst_vt['ElastoDynTower']['TwEAStif'] - fi = self.fst_vt['ElastoDynTower']['TwFAIner'] - si = self.fst_vt['ElastoDynTower']['TwSSIner'] - fo = self.fst_vt['ElastoDynTower']['TwFAcgOf'] - so = self.fst_vt['ElastoDynTower']['TwSScgOf'] - for a1, a2, a3, a4, a5, a6, a7, a8, a9, a10 in zip(HtFract, TMassDen, TwFAStif, TwSSStif, gs, es, fi, si, fo, so): - f.write('{:.9e}\t{:.9e}\t{:.9e}\t{:.9e}\t{:.9e}\t{:.9e}\t{:.9e}\t{:.9e}\t{:.9e}\t{:.9e}\n'.\ - format(a1, a2, a3, a4, a5, a6, a7, a8, a9, a10)) - else: - for HtFracti, TMassDeni, TwFAStifi, TwSSStifi in zip(HtFract, TMassDen, TwFAStif, TwSSStif): - f.write('{: 2.15e} {: 2.15e} {: 2.15e} {: 2.15e}\n'.format(HtFracti, TMassDeni, TwFAStifi, TwSSStifi)) - f.write('---------------------- TOWER FORE-AFT MODE SHAPES ------------------------------\n') - f.write('{:<22} {:<11} {:}'.format(self.fst_vt['ElastoDynTower']['TwFAM1Sh'][0], 'TwFAM1Sh(2)', '- Mode 1, coefficient of x^2 term\n')) - f.write('{:<22} {:<11} {:}'.format(self.fst_vt['ElastoDynTower']['TwFAM1Sh'][1], 'TwFAM1Sh(3)', '- , coefficient of x^3 term\n')) - f.write('{:<22} {:<11} {:}'.format(self.fst_vt['ElastoDynTower']['TwFAM1Sh'][2], 'TwFAM1Sh(4)', '- , coefficient of x^4 term\n')) - f.write('{:<22} {:<11} {:}'.format(self.fst_vt['ElastoDynTower']['TwFAM1Sh'][3], 'TwFAM1Sh(5)', '- , coefficient of x^5 term\n')) - f.write('{:<22} {:<11} {:}'.format(self.fst_vt['ElastoDynTower']['TwFAM1Sh'][4], 'TwFAM1Sh(6)', '- , coefficient of x^6 term\n')) - f.write('{:<22} {:<11} {:}'.format(self.fst_vt['ElastoDynTower']['TwFAM2Sh'][0], 'TwFAM2Sh(2)', '- Mode 2, coefficient of x^2 term\n')) - f.write('{:<22} {:<11} {:}'.format(self.fst_vt['ElastoDynTower']['TwFAM2Sh'][1], 'TwFAM2Sh(3)', '- , coefficient of x^3 term\n')) - f.write('{:<22} {:<11} {:}'.format(self.fst_vt['ElastoDynTower']['TwFAM2Sh'][2], 'TwFAM2Sh(4)', '- , coefficient of x^4 term\n')) - f.write('{:<22} {:<11} {:}'.format(self.fst_vt['ElastoDynTower']['TwFAM2Sh'][3], 'TwFAM2Sh(5)', '- , coefficient of x^5 term\n')) - f.write('{:<22} {:<11} {:}'.format(self.fst_vt['ElastoDynTower']['TwFAM2Sh'][4], 'TwFAM2Sh(6)', '- , coefficient of x^6 term\n')) - f.write('---------------------- TOWER SIDE-TO-SIDE MODE SHAPES --------------------------\n') - f.write('{:<22} {:<11} {:}'.format(self.fst_vt['ElastoDynTower']['TwSSM1Sh'][0], 'TwSSM1Sh(2)', '- Mode 1, coefficient of x^2 term\n')) - f.write('{:<22} {:<11} {:}'.format(self.fst_vt['ElastoDynTower']['TwSSM1Sh'][1], 'TwSSM1Sh(3)', '- , coefficient of x^3 term\n')) - f.write('{:<22} {:<11} {:}'.format(self.fst_vt['ElastoDynTower']['TwSSM1Sh'][2], 'TwSSM1Sh(4)', '- , coefficient of x^4 term\n')) - f.write('{:<22} {:<11} {:}'.format(self.fst_vt['ElastoDynTower']['TwSSM1Sh'][3], 'TwSSM1Sh(5)', '- , coefficient of x^5 term\n')) - f.write('{:<22} {:<11} {:}'.format(self.fst_vt['ElastoDynTower']['TwSSM1Sh'][4], 'TwSSM1Sh(6)', '- , coefficient of x^6 term\n')) - f.write('{:<22} {:<11} {:}'.format(self.fst_vt['ElastoDynTower']['TwSSM2Sh'][0], 'TwSSM2Sh(2)', '- Mode 2, coefficient of x^2 term\n')) - f.write('{:<22} {:<11} {:}'.format(self.fst_vt['ElastoDynTower']['TwSSM2Sh'][1], 'TwSSM2Sh(3)', '- , coefficient of x^3 term\n')) - f.write('{:<22} {:<11} {:}'.format(self.fst_vt['ElastoDynTower']['TwSSM2Sh'][2], 'TwSSM2Sh(4)', '- , coefficient of x^4 term\n')) - f.write('{:<22} {:<11} {:}'.format(self.fst_vt['ElastoDynTower']['TwSSM2Sh'][3], 'TwSSM2Sh(5)', '- , coefficient of x^5 term\n')) - f.write('{:<22} {:<11} {:}'.format(self.fst_vt['ElastoDynTower']['TwSSM2Sh'][4], 'TwSSM2Sh(6)', '- , coefficient of x^6 term\n')) - - f.close() - - def write_AeroDyn14Polar(self, filename, a_i): - # AeroDyn v14 Airfoil Polar Input File - - f = open(filename, 'w') - f.write('AeroDyn airfoil file, Aerodyn v14.04 formatting\n') - f.write('Generated with AeroElasticSE FAST driver\n') - - f.write('{:9d}\t{:}'.format(self.fst_vt['AeroDynBlade']['af_data'][a_i]['number_tables'], 'Number of airfoil tables in this file\n')) - for i in range(self.fst_vt['AeroDynBlade']['af_data'][a_i]['number_tables']): - param = self.fst_vt['AeroDynBlade']['af_data'][a_i]['af_tables'][i] - f.write('{:9g}\t{:}'.format(i, 'Table ID parameter\n')) - f.write('{: f}\t{:}'.format(param['StallAngle'], 'Stall angle (deg)\n')) - f.write('{: f}\t{:}'.format(0, 'No longer used, enter zero\n')) - f.write('{: f}\t{:}'.format(0, 'No longer used, enter zero\n')) - f.write('{: f}\t{:}'.format(0, 'No longer used, enter zero\n')) - f.write('{: f}\t{:}'.format(param['ZeroCn'], 'Angle of attack for zero Cn for linear Cn curve (deg)\n')) - f.write('{: f}\t{:}'.format(param['CnSlope'], 'Cn slope for zero lift for linear Cn curve (1/rad)\n')) - f.write('{: f}\t{:}'.format(param['CnPosStall'], 'Cn at stall value for positive angle of attack for linear Cn curve\n')) - f.write('{: f}\t{:}'.format(param['CnNegStall'], 'Cn at stall value for negative angle of attack for linear Cn curve\n')) - f.write('{: f}\t{:}'.format(param['alphaCdMin'], 'Angle of attack for minimum CD (deg)\n')) - f.write('{: f}\t{:}'.format(param['CdMin'], 'Minimum CD value\n')) - if param['cm']: - for a, cl, cd, cm in zip(param['alpha'], param['cl'], param['cd'], param['cm']): - f.write('{: 6e} {: 6e} {: 6e} {: 6e}\n'.format(a, cl, cd, cm)) - else: - for a, cl, cd in zip(param['alpha'], param['cl'], param['cd']): - f.write('{: 6e} {: 6e} {: 6e}\n'.format(a, cl, cd)) - - f.close() - def get_outlist(self, vartree_head, channel_list=[]): """ Loop through a list of output channel names, recursively find values set to True in the nested outlist dict """ @@ -312,9 +142,6 @@ def loop_dict(vartree, search_var, val, branch): var = var.replace(' ', '') loop_dict(self.fst_vt['outlist'], var, val, []) - -class InputWriter_OpenFAST(InputWriter_Common): - def execute(self): if not os.path.exists(self.FAST_runDirectory): @@ -330,9 +157,18 @@ def execute(self): elif self.fst_vt['Fst']['CompAero'] == 2: self.write_AeroDyn15() - if 'DISCON_in' in self.fst_vt and ROSCO: - self.write_DISCON_in() - self.write_ServoDyn() + if self.fst_vt['Fst']['CompServo'] == 1: + if 'DISCON_in' in self.fst_vt and ROSCO: + self.write_DISCON_in() + self.write_ServoDyn() + for i_NStC, NStC in enumerate(self.fst_vt['NStC']): + self.write_StC(NStC,self.fst_vt['ServoDyn']['NStCfiles'][i_NStC]) + for i_BStC, BStC in enumerate(self.fst_vt['BStC']): + self.write_StC(BStC,self.fst_vt['ServoDyn']['BStCfiles'][i_BStC]) + for i_TStC, TStC in enumerate(self.fst_vt['TStC']): + self.write_StC(TStC,self.fst_vt['ServoDyn']['TStCfiles'][i_TStC]) + for i_SStC, SStC in enumerate(self.fst_vt['SStC']): + self.write_StC(SStC,self.fst_vt['ServoDyn']['SStCfiles'][i_SStC]) if self.fst_vt['Fst']['CompHydro'] == 1: self.write_HydroDyn() @@ -348,7 +184,6 @@ def execute(self): self.write_MainInput() - def write_MainInput(self): # Main FAST v8.16-v8.17 Input File # Currently no differences between FASTv8.16 and OpenFAST. @@ -434,7 +269,6 @@ def write_MainInput(self): f.close() - def write_ElastoDyn(self): self.fst_vt['Fst']['EDFile'] = self.FAST_namingOut + '_ElastoDyn.dat' @@ -560,9 +394,9 @@ def write_ElastoDyn(self): f.write('{:<22} {:<11} {:}'.format(self.fst_vt['ElastoDyn']['DecFact'], 'DecFact', '- Decimation factor for tabular output {1: output every time step} (-) (currently unused)\n')) f.write('{:<22} {:<11} {:}'.format(self.fst_vt['ElastoDyn']['NTwGages'], 'NTwGages', '- Number of tower nodes that have strain gages for output [0 to 9] (-)\n')) if self.fst_vt['ElastoDyn']['TwrGagNd'] != 0: - f.write('{:<22} {:<11} {:}'.format(', '.join(self.fst_vt['ElastoDyn']['TwrGagNd']), 'TwrGagNd', '- List of tower nodes that have strain gages [1 to TwrNodes] (-) [unused if NTwGages=0]\n')) + f.write('{:<22} {:<11} {:}'.format(', '.join(['%d'%i for i in self.fst_vt['ElastoDyn']['TwrGagNd']]), 'TwrGagNd', '- List of tower nodes that have strain gages [1 to TwrNodes] (-) [unused if NTwGages=0]\n')) else: - f.write('{:<22} {:<11} {:}'.format(0, 'TwrGagNd', '- List of tower nodes that have strain gages [1 to TwrNodes] (-) [unused if NTwGages=0]\n')) + f.write('{:<22} {:<11} {:}'.format('', 'TwrGagNd', '- List of tower nodes that have strain gages [1 to TwrNodes] (-) [unused if NTwGages=0]\n')) f.write('{:<22} {:<11} {:}'.format(self.fst_vt['ElastoDyn']['NBlGages'], 'NBlGages', '- Number of blade nodes that have strain gages for output [0 to 9] (-)\n')) if self.fst_vt['ElastoDyn']['BldGagNd'] != 0: f.write('{:<22} {:<11} {:}'.format(', '.join(['%d'%i for i in self.fst_vt['ElastoDyn']['BldGagNd']]), 'BldGagNd', '- List of blade nodes that have strain gages [1 to BldNodes] (-) [unused if NBlGages=0]\n')) @@ -580,6 +414,112 @@ def write_ElastoDyn(self): f.write('---------------------------------------------------------------------------------------\n') f.close() + def write_ElastoDynBlade(self): + + self.fst_vt['ElastoDyn']['BldFile1'] = self.FAST_namingOut + '_ElastoDyn_blade.dat' + self.fst_vt['ElastoDyn']['BldFile2'] = self.fst_vt['ElastoDyn']['BldFile1'] + self.fst_vt['ElastoDyn']['BldFile3'] = self.fst_vt['ElastoDyn']['BldFile1'] + blade_file = os.path.join(self.FAST_runDirectory,self.fst_vt['ElastoDyn']['BldFile1']) + f = open(blade_file, 'w') + + f.write('------- ELASTODYN V1.00.* INDIVIDUAL BLADE INPUT FILE --------------------------\n') + f.write('Generated with AeroElasticSE FAST driver\n') + f.write('---------------------- BLADE PARAMETERS ----------------------------------------\n') + f.write('{:<22} {:<11} {:}'.format(self.fst_vt['ElastoDynBlade']['NBlInpSt'], 'NBlInpSt', '- Number of blade input stations (-)\n')) + f.write('{:<22} {:<11} {:}'.format(self.fst_vt['ElastoDynBlade']['BldFlDmp1'], 'BldFlDmp1', '- Blade flap mode #1 structural damping in percent of critical (%)\n')) + f.write('{:<22} {:<11} {:}'.format(self.fst_vt['ElastoDynBlade']['BldFlDmp2'], 'BldFlDmp2', '- Blade flap mode #2 structural damping in percent of critical (%)\n')) + f.write('{:<22} {:<11} {:}'.format(self.fst_vt['ElastoDynBlade']['BldEdDmp1'], 'BldEdDmp1', '- Blade edge mode #1 structural damping in percent of critical (%)\n')) + f.write('---------------------- BLADE ADJUSTMENT FACTORS --------------------------------\n') + f.write('{:<22} {:<11} {:}'.format(self.fst_vt['ElastoDynBlade']['FlStTunr1'], 'FlStTunr1', '- Blade flapwise modal stiffness tuner, 1st mode (-)\n')) + f.write('{:<22} {:<11} {:}'.format(self.fst_vt['ElastoDynBlade']['FlStTunr2'], 'FlStTunr2', '- Blade flapwise modal stiffness tuner, 2nd mode (-)\n')) + f.write('{:<22} {:<11} {:}'.format(self.fst_vt['ElastoDynBlade']['AdjBlMs'], 'AdjBlMs', '- Factor to adjust blade mass density (-)\n')) + f.write('{:<22} {:<11} {:}'.format(self.fst_vt['ElastoDynBlade']['AdjFlSt'], 'AdjFlSt', '- Factor to adjust blade flap stiffness (-)\n')) + f.write('{:<22} {:<11} {:}'.format(self.fst_vt['ElastoDynBlade']['AdjEdSt'], 'AdjEdSt', '- Factor to adjust blade edge stiffness (-)\n')) + f.write('---------------------- DISTRIBUTED BLADE PROPERTIES ----------------------------\n') + f.write(' BlFract PitchAxis StrcTwst BMassDen FlpStff EdgStff\n') + f.write(' (-) (-) (deg) (kg/m) (Nm^2) (Nm^2)\n') + BlFract = self.fst_vt['ElastoDynBlade']['BlFract'] + PitchAxis = self.fst_vt['ElastoDynBlade']['PitchAxis'] + StrcTwst = self.fst_vt['ElastoDynBlade']['StrcTwst'] + BMassDen = self.fst_vt['ElastoDynBlade']['BMassDen'] + FlpStff = self.fst_vt['ElastoDynBlade']['FlpStff'] + EdgStff = self.fst_vt['ElastoDynBlade']['EdgStff'] + for BlFracti, PitchAxisi, StrcTwsti, BMassDeni, FlpStffi, EdgStffi in zip(BlFract, PitchAxis, StrcTwst, BMassDen, FlpStff, EdgStff): + f.write('{: 2.15e} {: 2.15e} {: 2.15e} {: 2.15e} {: 2.15e} {: 2.15e}\n'.format(BlFracti, PitchAxisi, StrcTwsti, BMassDeni, FlpStffi, EdgStffi)) + f.write('---------------------- BLADE MODE SHAPES ---------------------------------------\n') + f.write('{:<22} {:<11} {:}'.format(self.fst_vt['ElastoDynBlade']['BldFl1Sh'][0], 'BldFl1Sh(2)', '- Flap mode 1, coeff of x^2\n')) + f.write('{:<22} {:<11} {:}'.format(self.fst_vt['ElastoDynBlade']['BldFl1Sh'][1], 'BldFl1Sh(3)', '- , coeff of x^3\n')) + f.write('{:<22} {:<11} {:}'.format(self.fst_vt['ElastoDynBlade']['BldFl1Sh'][2], 'BldFl1Sh(4)', '- , coeff of x^4\n')) + f.write('{:<22} {:<11} {:}'.format(self.fst_vt['ElastoDynBlade']['BldFl1Sh'][3], 'BldFl1Sh(5)', '- , coeff of x^5\n')) + f.write('{:<22} {:<11} {:}'.format(self.fst_vt['ElastoDynBlade']['BldFl1Sh'][4], 'BldFl1Sh(6)', '- , coeff of x^6\n')) + f.write('{:<22} {:<11} {:}'.format(self.fst_vt['ElastoDynBlade']['BldFl2Sh'][0], 'BldFl2Sh(2)', '- Flap mode 2, coeff of x^2\n')) + f.write('{:<22} {:<11} {:}'.format(self.fst_vt['ElastoDynBlade']['BldFl2Sh'][1], 'BldFl2Sh(3)', '- , coeff of x^3\n')) + f.write('{:<22} {:<11} {:}'.format(self.fst_vt['ElastoDynBlade']['BldFl2Sh'][2], 'BldFl2Sh(4)', '- , coeff of x^4\n')) + f.write('{:<22} {:<11} {:}'.format(self.fst_vt['ElastoDynBlade']['BldFl2Sh'][3], 'BldFl2Sh(5)', '- , coeff of x^5\n')) + f.write('{:<22} {:<11} {:}'.format(self.fst_vt['ElastoDynBlade']['BldFl2Sh'][4], 'BldFl2Sh(6)', '- , coeff of x^6\n')) + f.write('{:<22} {:<11} {:}'.format(self.fst_vt['ElastoDynBlade']['BldEdgSh'][0], 'BldEdgSh(2)', '- Edge mode 1, coeff of x^2\n')) + f.write('{:<22} {:<11} {:}'.format(self.fst_vt['ElastoDynBlade']['BldEdgSh'][1], 'BldEdgSh(3)', '- , coeff of x^3\n')) + f.write('{:<22} {:<11} {:}'.format(self.fst_vt['ElastoDynBlade']['BldEdgSh'][2], 'BldEdgSh(4)', '- , coeff of x^4\n')) + f.write('{:<22} {:<11} {:}'.format(self.fst_vt['ElastoDynBlade']['BldEdgSh'][3], 'BldEdgSh(5)', '- , coeff of x^5\n')) + f.write('{:<22} {:<11} {:}'.format(self.fst_vt['ElastoDynBlade']['BldEdgSh'][4], 'BldEdgSh(6)', '- , coeff of x^6\n')) + + f.close() + + def write_ElastoDynTower(self): + + self.fst_vt['ElastoDyn']['TwrFile'] = self.FAST_namingOut + '_ElastoDyn_tower.dat' + tower_file = os.path.join(self.FAST_runDirectory,self.fst_vt['ElastoDyn']['TwrFile']) + f = open(tower_file, 'w') + + f.write('------- ELASTODYN V1.00.* TOWER INPUT FILE -------------------------------------\n') + f.write('Generated with AeroElasticSE FAST driver\n') + f.write('---------------------- TOWER PARAMETERS ----------------------------------------\n') + f.write('{:<22} {:<11} {:}'.format(self.fst_vt['ElastoDynTower']['NTwInpSt'], 'NTwInpSt', '- Number of input stations to specify tower geometry\n')) + f.write('{:<22} {:<11} {:}'.format(self.fst_vt['ElastoDynTower']['TwrFADmp1'], 'TwrFADmp(1)', '- Tower 1st fore-aft mode structural damping ratio (%)\n')) + f.write('{:<22} {:<11} {:}'.format(self.fst_vt['ElastoDynTower']['TwrFADmp2'], 'TwrFADmp(2)', '- Tower 2nd fore-aft mode structural damping ratio (%)\n')) + f.write('{:<22} {:<11} {:}'.format(self.fst_vt['ElastoDynTower']['TwrSSDmp1'], 'TwrSSDmp(1)', '- Tower 1st side-to-side mode structural damping ratio (%)\n')) + f.write('{:<22} {:<11} {:}'.format(self.fst_vt['ElastoDynTower']['TwrSSDmp2'], 'TwrSSDmp(2)', '- Tower 2nd side-to-side mode structural damping ratio (%)\n')) + f.write('---------------------- TOWER ADJUSTMUNT FACTORS --------------------------------\n') + f.write('{:<22} {:<11} {:}'.format(self.fst_vt['ElastoDynTower']['FAStTunr1'], 'FAStTunr(1)', '- Tower fore-aft modal stiffness tuner, 1st mode (-)\n')) + f.write('{:<22} {:<11} {:}'.format(self.fst_vt['ElastoDynTower']['FAStTunr2'], 'FAStTunr(2)', '- Tower fore-aft modal stiffness tuner, 2nd mode (-)\n')) + f.write('{:<22} {:<11} {:}'.format(self.fst_vt['ElastoDynTower']['SSStTunr1'], 'SSStTunr(1)', '- Tower side-to-side stiffness tuner, 1st mode (-)\n')) + f.write('{:<22} {:<11} {:}'.format(self.fst_vt['ElastoDynTower']['SSStTunr2'], 'SSStTunr(2)', '- Tower side-to-side stiffness tuner, 2nd mode (-)\n')) + f.write('{:<22} {:<11} {:}'.format(self.fst_vt['ElastoDynTower']['AdjTwMa'], 'AdjTwMa', '- Factor to adjust tower mass density (-)\n')) + f.write('{:<22} {:<11} {:}'.format(self.fst_vt['ElastoDynTower']['AdjFASt'], 'AdjFASt', '- Factor to adjust tower fore-aft stiffness (-)\n')) + f.write('{:<22} {:<11} {:}'.format(self.fst_vt['ElastoDynTower']['AdjSSSt'], 'AdjSSSt', '- Factor to adjust tower side-to-side stiffness (-)\n')) + f.write('---------------------- DISTRIBUTED TOWER PROPERTIES ----------------------------\n') + f.write(' HtFract TMassDen TwFAStif TwSSStif\n') + f.write(' (-) (kg/m) (Nm^2) (Nm^2)\n') + HtFract = self.fst_vt['ElastoDynTower']['HtFract'] + TMassDen = self.fst_vt['ElastoDynTower']['TMassDen'] + TwFAStif = self.fst_vt['ElastoDynTower']['TwFAStif'] + TwSSStif = self.fst_vt['ElastoDynTower']['TwSSStif'] + for HtFracti, TMassDeni, TwFAStifi, TwSSStifi in zip(HtFract, TMassDen, TwFAStif, TwSSStif): + f.write('{: 2.15e} {: 2.15e} {: 2.15e} {: 2.15e}\n'.format(HtFracti, TMassDeni, TwFAStifi, TwSSStifi)) + f.write('---------------------- TOWER FORE-AFT MODE SHAPES ------------------------------\n') + f.write('{:<22} {:<11} {:}'.format(self.fst_vt['ElastoDynTower']['TwFAM1Sh'][0], 'TwFAM1Sh(2)', '- Mode 1, coefficient of x^2 term\n')) + f.write('{:<22} {:<11} {:}'.format(self.fst_vt['ElastoDynTower']['TwFAM1Sh'][1], 'TwFAM1Sh(3)', '- , coefficient of x^3 term\n')) + f.write('{:<22} {:<11} {:}'.format(self.fst_vt['ElastoDynTower']['TwFAM1Sh'][2], 'TwFAM1Sh(4)', '- , coefficient of x^4 term\n')) + f.write('{:<22} {:<11} {:}'.format(self.fst_vt['ElastoDynTower']['TwFAM1Sh'][3], 'TwFAM1Sh(5)', '- , coefficient of x^5 term\n')) + f.write('{:<22} {:<11} {:}'.format(self.fst_vt['ElastoDynTower']['TwFAM1Sh'][4], 'TwFAM1Sh(6)', '- , coefficient of x^6 term\n')) + f.write('{:<22} {:<11} {:}'.format(self.fst_vt['ElastoDynTower']['TwFAM2Sh'][0], 'TwFAM2Sh(2)', '- Mode 2, coefficient of x^2 term\n')) + f.write('{:<22} {:<11} {:}'.format(self.fst_vt['ElastoDynTower']['TwFAM2Sh'][1], 'TwFAM2Sh(3)', '- , coefficient of x^3 term\n')) + f.write('{:<22} {:<11} {:}'.format(self.fst_vt['ElastoDynTower']['TwFAM2Sh'][2], 'TwFAM2Sh(4)', '- , coefficient of x^4 term\n')) + f.write('{:<22} {:<11} {:}'.format(self.fst_vt['ElastoDynTower']['TwFAM2Sh'][3], 'TwFAM2Sh(5)', '- , coefficient of x^5 term\n')) + f.write('{:<22} {:<11} {:}'.format(self.fst_vt['ElastoDynTower']['TwFAM2Sh'][4], 'TwFAM2Sh(6)', '- , coefficient of x^6 term\n')) + f.write('---------------------- TOWER SIDE-TO-SIDE MODE SHAPES --------------------------\n') + f.write('{:<22} {:<11} {:}'.format(self.fst_vt['ElastoDynTower']['TwSSM1Sh'][0], 'TwSSM1Sh(2)', '- Mode 1, coefficient of x^2 term\n')) + f.write('{:<22} {:<11} {:}'.format(self.fst_vt['ElastoDynTower']['TwSSM1Sh'][1], 'TwSSM1Sh(3)', '- , coefficient of x^3 term\n')) + f.write('{:<22} {:<11} {:}'.format(self.fst_vt['ElastoDynTower']['TwSSM1Sh'][2], 'TwSSM1Sh(4)', '- , coefficient of x^4 term\n')) + f.write('{:<22} {:<11} {:}'.format(self.fst_vt['ElastoDynTower']['TwSSM1Sh'][3], 'TwSSM1Sh(5)', '- , coefficient of x^5 term\n')) + f.write('{:<22} {:<11} {:}'.format(self.fst_vt['ElastoDynTower']['TwSSM1Sh'][4], 'TwSSM1Sh(6)', '- , coefficient of x^6 term\n')) + f.write('{:<22} {:<11} {:}'.format(self.fst_vt['ElastoDynTower']['TwSSM2Sh'][0], 'TwSSM2Sh(2)', '- Mode 2, coefficient of x^2 term\n')) + f.write('{:<22} {:<11} {:}'.format(self.fst_vt['ElastoDynTower']['TwSSM2Sh'][1], 'TwSSM2Sh(3)', '- , coefficient of x^3 term\n')) + f.write('{:<22} {:<11} {:}'.format(self.fst_vt['ElastoDynTower']['TwSSM2Sh'][2], 'TwSSM2Sh(4)', '- , coefficient of x^4 term\n')) + f.write('{:<22} {:<11} {:}'.format(self.fst_vt['ElastoDynTower']['TwSSM2Sh'][3], 'TwSSM2Sh(5)', '- , coefficient of x^5 term\n')) + f.write('{:<22} {:<11} {:}'.format(self.fst_vt['ElastoDynTower']['TwSSM2Sh'][4], 'TwSSM2Sh(6)', '- , coefficient of x^6 term\n')) + + f.close() def write_BeamDyn(self): self.fst_vt['Fst']['BDBldFile(1)'] = self.FAST_namingOut + '_BeamDyn.dat' @@ -660,8 +600,8 @@ def write_BeamDyn(self): def write_BeamDynBlade(self): # bd_blade_file = self.fst_vt['BeamDyn']['BldFile'] - bd_blade_file = os.path.abspath(os.path.join(self.FAST_runDirectory, self.FAST_namingOut + '_BeamDyn_Blade.dat')) - self.fst_vt['BeamDyn']['BldFile'] = bd_blade_file + self.fst_vt['BeamDyn']['BldFile'] = self.FAST_namingOut + '_BeamDyn_Blade.dat' + bd_blade_file = os.path.abspath(os.path.join(self.FAST_runDirectory, self.fst_vt['BeamDyn']['BldFile'])) f = open(bd_blade_file, 'w') f.write('------- BEAMDYN V1.00.* INDIVIDUAL BLADE INPUT FILE --------------------------\n') @@ -687,7 +627,6 @@ def write_BeamDynBlade(self): f.write('\n') - def write_InflowWind(self): self.fst_vt['Fst']['InflowFile'] = self.FAST_namingOut + '_InflowFile.dat' inflow_file = os.path.join(self.FAST_runDirectory,self.fst_vt['Fst']['InflowFile']) @@ -719,152 +658,43 @@ def write_InflowWind(self): f.write('{!s:<22} {:<11} {:}'.format(self.fst_vt['InflowWind']['TowerFile'], 'TowerFile', '- Have tower file (.twr) (flag)\n')) f.write('================== Parameters for HAWC-format binary files [Only used with WindType = 5] =====================\n') f.write('{:<22} {:<11} {:}'.format('"'+self.fst_vt['InflowWind']['FileName_u']+'"', 'FileName_u', '- name of the file containing the u-component fluctuating wind (.bin)\n')) - f.write('{:<22} {:<11} {:}'.format('"'+self.fst_vt['InflowWind']['FileName_v']+'"', 'FileName_v', '- name of the file containing the v-component fluctuating wind (.bin)\n')) - f.write('{:<22} {:<11} {:}'.format('"'+self.fst_vt['InflowWind']['FileName_w']+'"', 'FileName_w', '- name of the file containing the w-component fluctuating wind (.bin)\n')) - f.write('{:<22} {:<11} {:}'.format(self.fst_vt['InflowWind']['nx'], 'nx', '- number of grids in the x direction (in the 3 files above) (-)\n')) - f.write('{:<22} {:<11} {:}'.format(self.fst_vt['InflowWind']['ny'], 'ny', '- number of grids in the y direction (in the 3 files above) (-)\n')) - f.write('{:<22} {:<11} {:}'.format(self.fst_vt['InflowWind']['nz'], 'nz', '- number of grids in the z direction (in the 3 files above) (-)\n')) - f.write('{:<22} {:<11} {:}'.format(self.fst_vt['InflowWind']['dx'], 'dx', '- distance (in meters) between points in the x direction (m)\n')) - f.write('{:<22} {:<11} {:}'.format(self.fst_vt['InflowWind']['dy'], 'dy', '- distance (in meters) between points in the y direction (m)\n')) - f.write('{:<22} {:<11} {:}'.format(self.fst_vt['InflowWind']['dz'], 'dz', '- distance (in meters) between points in the z direction (m)\n')) - f.write('{:<22} {:<11} {:}'.format(self.fst_vt['InflowWind']['RefHt_Hawc'], 'RefHt_Hawc', '- reference height; the height (in meters) of the vertical center of the grid (m)\n')) - f.write('------------- Scaling parameters for turbulence ---------------------------------------------------------\n') - f.write('{:<22} {:<11} {:}'.format(self.fst_vt['InflowWind']['ScaleMethod'], 'ScaleMethod', '- Turbulence scaling method [0 = none, 1 = direct scaling, 2 = calculate scaling factor based on a desired standard deviation]\n')) - f.write('{:<22} {:<11} {:}'.format(self.fst_vt['InflowWind']['SFx'], 'SFx', '- Turbulence scaling factor for the x direction (-) [ScaleMethod=1]\n')) - f.write('{:<22} {:<11} {:}'.format(self.fst_vt['InflowWind']['SFy'], 'SFy', '- Turbulence scaling factor for the y direction (-) [ScaleMethod=1]\n')) - f.write('{:<22} {:<11} {:}'.format(self.fst_vt['InflowWind']['SFz'], 'SFz', '- Turbulence scaling factor for the z direction (-) [ScaleMethod=1]\n')) - f.write('{:<22} {:<11} {:}'.format(self.fst_vt['InflowWind']['SigmaFx'], 'SigmaFx', '- Turbulence standard deviation to calculate scaling from in x direction (m/s) [ScaleMethod=2]\n')) - f.write('{:<22} {:<11} {:}'.format(self.fst_vt['InflowWind']['SigmaFy'], 'SigmaFy', '- Turbulence standard deviation to calculate scaling from in y direction (m/s) [ScaleMethod=2]\n')) - f.write('{:<22} {:<11} {:}'.format(self.fst_vt['InflowWind']['SigmaFz'], 'SigmaFz', '- Turbulence standard deviation to calculate scaling from in z direction (m/s) [ScaleMethod=2]\n')) - f.write('------------- Mean wind profile parameters (added to HAWC-format files) ---------------------------------\n') - f.write('{:<22} {:<11} {:}'.format(self.fst_vt['InflowWind']['URef'], 'URef', '- Mean u-component wind speed at the reference height (m/s)\n')) - f.write('{:<22} {:<11} {:}'.format(self.fst_vt['InflowWind']['WindProfile'], 'WindProfile', '- Wind profile type (0=constant;1=logarithmic,2=power law)\n')) - f.write('{:<22} {:<11} {:}'.format(self.fst_vt['InflowWind']['PLExp_Hawc'], 'PLExp_Hawc', '- Power law exponent (-) (used for PL wind profile type only)\n')) - f.write('{:<22} {:<11} {:}'.format(self.fst_vt['InflowWind']['Z0'], 'Z0', '- Surface roughness length (m) (used for LG wind profile type only)\n')) - f.write('{:<22} {:<11} {:}'.format(self.fst_vt['InflowWind']['XOffset'], 'XOffset', '- Initial offset in +x direction (shift of wind box) (-)\n')) - f.write('====================== OUTPUT ==================================================\n') - f.write('{!s:<22} {:<11} {:}'.format(self.fst_vt['InflowWind']['SumPrint'], 'SumPrint', '- Print summary data to .IfW.sum (flag)\n')) - f.write('OutList - The next line(s) contains a list of output parameters. See OutListParameters.xlsx for a listing of available output channels, (-)\n') - - outlist = self.get_outlist(self.fst_vt['outlist'], ['InflowWind']) - for channel_list in outlist: - for i in range(len(channel_list)): - f.write('"' + channel_list[i] + '"\n') - - f.write('END of input file (the word "END" must appear in the first 3 columns of this last OutList line)\n') - f.write('---------------------------------------------------------------------------------------\n') - - f.close() - - # def WndWindWriter(self, wndfile): - - # wind_file = os.path.join(self.FAST_runDirectory,wndfile) - # f = open(wind_file, 'w') - - # for i in range(self.fst_vt['wnd_wind']['TimeSteps']): - # f.write('{: 2.15e}\t{: 2.15e}\t{: 2.15e}\t{: 2.15e}\t{: 2.15e}\t{: 2.15e}\t{: 2.15e}\t{: 2.15e}\n'.format(\ - # self.fst_vt['wnd_wind']['Time'][i], self.fst_vt['wnd_wind']['HorSpd'][i], self.fst_vt['wnd_wind']['WindDir'][i],\ - # self.fst_vt['wnd_wind']['VerSpd'][i], self.fst_vt['wnd_wind']['HorShr'][i],\ - # self.fst_vt['wnd_wind']['VerShr'][i], self.fst_vt['wnd_wind']['LnVShr'][i], self.fst_vt['wnd_wind']['GstSpd'][i])) - - # f.close() - - - def write_AeroDyn14(self): - - # ======= Airfoil Files ======== - # make directory for airfoil files - if not os.path.isdir(os.path.join(self.FAST_runDirectory,'AeroData')): - try: - os.mkdir(os.path.join(self.FAST_runDirectory,'AeroData')) - except: - try: - time.sleep(random.random()) - if not os.path.isdir(os.path.join(self.FAST_runDirectory,'AeroData')): - os.mkdir(os.path.join(self.FAST_runDirectory,'AeroData')) - except: - print("Error tring to make '%s'!"%os.path.join(self.FAST_runDirectory,'AeroData')) - - # create write airfoil objects to files - for i in range(self.fst_vt['AeroDyn14']['NumFoil']): - af_name = os.path.join(self.FAST_runDirectory, 'AeroData', 'Airfoil' + str(i) + '.dat') - self.fst_vt['AeroDyn14']['FoilNm'][i] = os.path.join('AeroData', 'Airfoil' + str(i) + '.dat') - self.write_AeroDyn14Polar(af_name, i) - - self.fst_vt['Fst']['AeroFile'] = self.FAST_namingOut + '_AeroDyn14.dat' - ad_file = os.path.join(self.FAST_runDirectory,self.fst_vt['Fst']['AeroFile']) - f = open(ad_file,'w') - - # create Aerodyn Tower - self.write_AeroDyn14Tower() - - # ======= Aerodyn Input File ======== - f.write('AeroDyn v14.04.* INPUT FILE\n\n') - - # f.write('{:}\n'.format(self.fst_vt['aerodyn']['SysUnits'])) - f.write('{:}\n'.format(self.fst_vt['AeroDyn14']['StallMod'])) - - f.write('{:}\n'.format(self.fst_vt['AeroDyn14']['UseCm'])) - f.write('{:}\n'.format(self.fst_vt['AeroDyn14']['InfModel'])) - f.write('{:}\n'.format(self.fst_vt['AeroDyn14']['IndModel'])) - f.write('{: 2.15e}\n'.format(self.fst_vt['AeroDyn14']['AToler'])) - f.write('{:}\n'.format(self.fst_vt['AeroDyn14']['TLModel'])) - f.write('{:}\n'.format(self.fst_vt['AeroDyn14']['HLModel'])) - f.write('{:}\n'.format(self.fst_vt['AeroDyn14']['TwrShad'])) - - f.write('{:}\n'.format(self.fst_vt['AeroDyn14']['TwrPotent'])) - - f.write('{:}\n'.format(self.fst_vt['AeroDyn14']['TwrShadow'])) - f.write('{:}\n'.format(self.fst_vt['AeroDyn14']['TwrFile'])) - f.write('{:}\n'.format(self.fst_vt['AeroDyn14']['CalcTwrAero'])) - - f.write('{: 2.15e}\n'.format(self.fst_vt['AeroDyn14']['AirDens'])) - - f.write('{: 2.15e}\n'.format(self.fst_vt['AeroDyn14']['KinVisc'])) - - f.write('{:2}\n'.format(self.fst_vt['AeroDyn14']['DTAero'])) + f.write('{:<22} {:<11} {:}'.format('"'+self.fst_vt['InflowWind']['FileName_v']+'"', 'FileName_v', '- name of the file containing the v-component fluctuating wind (.bin)\n')) + f.write('{:<22} {:<11} {:}'.format('"'+self.fst_vt['InflowWind']['FileName_w']+'"', 'FileName_w', '- name of the file containing the w-component fluctuating wind (.bin)\n')) + f.write('{:<22} {:<11} {:}'.format(self.fst_vt['InflowWind']['nx'], 'nx', '- number of grids in the x direction (in the 3 files above) (-)\n')) + f.write('{:<22} {:<11} {:}'.format(self.fst_vt['InflowWind']['ny'], 'ny', '- number of grids in the y direction (in the 3 files above) (-)\n')) + f.write('{:<22} {:<11} {:}'.format(self.fst_vt['InflowWind']['nz'], 'nz', '- number of grids in the z direction (in the 3 files above) (-)\n')) + f.write('{:<22} {:<11} {:}'.format(self.fst_vt['InflowWind']['dx'], 'dx', '- distance (in meters) between points in the x direction (m)\n')) + f.write('{:<22} {:<11} {:}'.format(self.fst_vt['InflowWind']['dy'], 'dy', '- distance (in meters) between points in the y direction (m)\n')) + f.write('{:<22} {:<11} {:}'.format(self.fst_vt['InflowWind']['dz'], 'dz', '- distance (in meters) between points in the z direction (m)\n')) + f.write('{:<22} {:<11} {:}'.format(self.fst_vt['InflowWind']['RefHt_Hawc'], 'RefHt_Hawc', '- reference height; the height (in meters) of the vertical center of the grid (m)\n')) + f.write('------------- Scaling parameters for turbulence ---------------------------------------------------------\n') + f.write('{:<22} {:<11} {:}'.format(self.fst_vt['InflowWind']['ScaleMethod'], 'ScaleMethod', '- Turbulence scaling method [0 = none, 1 = direct scaling, 2 = calculate scaling factor based on a desired standard deviation]\n')) + f.write('{:<22} {:<11} {:}'.format(self.fst_vt['InflowWind']['SFx'], 'SFx', '- Turbulence scaling factor for the x direction (-) [ScaleMethod=1]\n')) + f.write('{:<22} {:<11} {:}'.format(self.fst_vt['InflowWind']['SFy'], 'SFy', '- Turbulence scaling factor for the y direction (-) [ScaleMethod=1]\n')) + f.write('{:<22} {:<11} {:}'.format(self.fst_vt['InflowWind']['SFz'], 'SFz', '- Turbulence scaling factor for the z direction (-) [ScaleMethod=1]\n')) + f.write('{:<22} {:<11} {:}'.format(self.fst_vt['InflowWind']['SigmaFx'], 'SigmaFx', '- Turbulence standard deviation to calculate scaling from in x direction (m/s) [ScaleMethod=2]\n')) + f.write('{:<22} {:<11} {:}'.format(self.fst_vt['InflowWind']['SigmaFy'], 'SigmaFy', '- Turbulence standard deviation to calculate scaling from in y direction (m/s) [ScaleMethod=2]\n')) + f.write('{:<22} {:<11} {:}'.format(self.fst_vt['InflowWind']['SigmaFz'], 'SigmaFz', '- Turbulence standard deviation to calculate scaling from in z direction (m/s) [ScaleMethod=2]\n')) + f.write('------------- Mean wind profile parameters (added to HAWC-format files) ---------------------------------\n') + f.write('{:<22} {:<11} {:}'.format(self.fst_vt['InflowWind']['URef'], 'URef', '- Mean u-component wind speed at the reference height (m/s)\n')) + f.write('{:<22} {:<11} {:}'.format(self.fst_vt['InflowWind']['WindProfile'], 'WindProfile', '- Wind profile type (0=constant;1=logarithmic,2=power law)\n')) + f.write('{:<22} {:<11} {:}'.format(self.fst_vt['InflowWind']['PLExp_Hawc'], 'PLExp_Hawc', '- Power law exponent (-) (used for PL wind profile type only)\n')) + f.write('{:<22} {:<11} {:}'.format(self.fst_vt['InflowWind']['Z0'], 'Z0', '- Surface roughness length (m) (used for LG wind profile type only)\n')) + f.write('{:<22} {:<11} {:}'.format(self.fst_vt['InflowWind']['XOffset'], 'XOffset', '- Initial offset in +x direction (shift of wind box) (-)\n')) + f.write('====================== OUTPUT ==================================================\n') + f.write('{!s:<22} {:<11} {:}'.format(self.fst_vt['InflowWind']['SumPrint'], 'SumPrint', '- Print summary data to .IfW.sum (flag)\n')) + f.write('OutList - The next line(s) contains a list of output parameters. See OutListParameters.xlsx for a listing of available output channels, (-)\n') + outlist = self.get_outlist(self.fst_vt['outlist'], ['InflowWind']) + for channel_list in outlist: + for i in range(len(channel_list)): + f.write('"' + channel_list[i] + '"\n') - f.write('{:2}\n'.format(self.fst_vt['AeroDynBlade']['NumFoil'])) - for i in range (self.fst_vt['AeroDynBlade']['NumFoil']): - f.write('"{:}"\n'.format(self.fst_vt['AeroDynBlade']['FoilNm'][i])) - - f.write('{:2}\n'.format(self.fst_vt['AeroDynBlade']['BldNodes'])) - rnodes = self.fst_vt['AeroDynBlade']['RNodes'] - twist = self.fst_vt['AeroDynBlade']['AeroTwst'] - drnodes = self.fst_vt['AeroDynBlade']['DRNodes'] - chord = self.fst_vt['AeroDynBlade']['Chord'] - nfoil = self.fst_vt['AeroDynBlade']['NFoil'] - prnelm = self.fst_vt['AeroDynBlade']['PrnElm'] - f.write('Nodal properties\n') - for r, t, dr, c, a, p in zip(rnodes, twist, drnodes, chord, nfoil, prnelm): - f.write('{: 2.15e}\t{: 2.15e}\t{: 2.15e}\t{: 2.15e}\t{:5}\t{:}\n'.format(r, t, dr, c, a, p)) - - f.close() - - def write_AeroDyn14Tower(self): - # AeroDyn v14.04 Tower - self.fst_vt['AeroDyn14']['TwrFile'] = self.FAST_namingOut + '_AeroDyn14_tower.dat' - filename = os.path.join(self.FAST_runDirectory, self.fst_vt['AeroDyn14']['TwrFile']) - f = open(filename, 'w') + f.write('END of input file (the word "END" must appear in the first 3 columns of this last OutList line)\n') + f.write('---------------------------------------------------------------------------------------\n') - f.write('AeroDyn tower file, Aerodyn v14.04 formatting\n') - f.write('Generated with AeroElasticSE FAST driver\n') - f.write('{:<22d} {:<11} {:}'.format(self.fst_vt['AeroDynTower']['NTwrHt'], 'NTwrHt', '- Number of tower input height stations listed (-)\n')) - f.write('{:<22d} {:<11} {:}'.format(self.fst_vt['AeroDynTower']['NTwrRe'], 'NTwrRe', '- Number of tower Re values (-)\n')) - f.write('{:<22d} {:<11} {:}'.format(self.fst_vt['AeroDynTower']['NTwrCD'], 'NTwrCD', '- Number of tower CD columns (-) Note: For current versions, this MUST be 1\n')) - f.write('{: 2.15e} {:<11} {:}'.format(self.fst_vt['AeroDynTower']['Tower_Wake_Constant'], 'Tower_Wake_Constant', '- Tower wake constant (-) {0.0: full potential flow, 0.1: Bak model}\n')) - f.write('---------------------- DISTRIBUTED TOWER PROPERTIES ----------------------------\n') - f.write('TwrHtFr TwrWid NTwrCDCol\n') - for HtFr, Wid, CDId in zip(self.fst_vt['AeroDynTower']['TwrHtFr'], self.fst_vt['AeroDynTower']['TwrWid'], self.fst_vt['AeroDynTower']['NTwrCDCol']): - f.write('{: 2.15e} {: 2.15e} {:d}\n'.format(HtFr, Wid, int(CDId))) - f.write('---------------------- Re v CD PROPERTIES --------------------------------------\n') - f.write('TwrRe '+ ' '.join(['TwrCD%d'%(i+1) for i in range(self.fst_vt['AeroDynTower']['NTwrCD'])]) +'\n') - for Re, CD in zip(self.fst_vt['AeroDynTower']['TwrRe'], self.fst_vt['AeroDynTower']['TwrCD']): - f.write('% 2.15e' %Re + ' '.join(['% 2.15e'%cdi for cdi in CD]) + '\n') - f.close() - + def write_AeroDyn15(self): # AeroDyn v15.03 @@ -879,6 +709,8 @@ def write_AeroDyn15(self): self.write_AeroDyn15Coord() if self.fst_vt['AeroDyn15']['WakeMod'] == 3: + if self.fst_vt['AeroDyn15']['AFAeroMod'] == 2: + raise Exception('OLAF is called with unsteady airfoil aerodynamics, but OLAF currently only supports AFAeroMod == 1') self.write_OLAF() # Generate AeroDyn v15.03 input file @@ -898,6 +730,7 @@ def write_AeroDyn15(self): f.write('{!s:<22} {:<11} {:}'.format(self.fst_vt['AeroDyn15']['TwrAero'], 'TwrAero', '- Calculate tower aerodynamic loads? (flag)\n')) f.write('{!s:<22} {:<11} {:}'.format(self.fst_vt['AeroDyn15']['FrozenWake'], 'FrozenWake', '- Assume frozen wake during linearization? (flag) [used only when WakeMod=1 and when linearizing]\n')) f.write('{!s:<22} {:<11} {:}'.format(self.fst_vt['AeroDyn15']['CavitCheck'], 'CavitCheck', '- Perform cavitation check? (flag) [AFAeroMod must be 1 when CavitCheck=true]\n')) + f.write('{!s:<22} {:<11} {:}'.format(self.fst_vt['AeroDyn15']['Buoyancy'], 'Buoyancy', '- Include buoyancy effects? (flag)\n')) f.write('{!s:<22} {:<11} {:}'.format(self.fst_vt['AeroDyn15']['CompAA'], 'CompAA', '- Flag to compute AeroAcoustics calculation [only used when WakeMod=1 or 2]\n')) f.write('{!s:<22} {:<11} {:}'.format(self.fst_vt['AeroDyn15']['AA_InputFile'], 'AA_InputFile', '- AeroAcoustics input file [used only when CompAA=true]\n')) f.write('====== Environmental Conditions ===================================================================\n') @@ -906,7 +739,7 @@ def write_AeroDyn15(self): f.write('{:<22} {:<11} {:}'.format(self.fst_vt['AeroDyn15']['SpdSound'], 'SpdSound', '- Speed of sound (m/s)\n')) f.write('{:<22} {:<11} {:}'.format(self.fst_vt['AeroDyn15']['Patm'], 'Patm', '- Atmospheric pressure (Pa) [used only when CavitCheck=True]\n')) f.write('{:<22} {:<11} {:}'.format(self.fst_vt['AeroDyn15']['Pvap'], 'Pvap', '- Vapour pressure of fluid (Pa) [used only when CavitCheck=True]\n')) - f.write('====== Blade-Element/Momentum Theory Options ====================================================== [used only when WakeMod=1]\n') + f.write('====== Blade-Element/Momentum Theory Options ====================================================== [unused when WakeMod=0 or 3]\n') f.write('{:<22d} {:<11} {:}'.format(self.fst_vt['AeroDyn15']['SkewMod'], 'SkewMod', '- Type of skewed-wake correction model (switch) {1=uncoupled, 2=Pitt/Peters, 3=coupled} [unused when WakeMod=0 or 3]\n')) f.write('{!s:<22} {:<11} {:}'.format(self.fst_vt['AeroDyn15']['SkewModFactor'], 'SkewModFactor', '- Constant used in Pitt/Peters skewed wake model {or "default" is 15/32*pi} (-) [used only when SkewMod=2; unused when WakeMod=0 or 3]\n')) f.write('{!s:<22} {:<11} {:}'.format(self.fst_vt['AeroDyn15']['TipLoss'], 'TipLoss', '- Use the Prandtl tip-loss model? (flag) [unused when WakeMod=0 or 3]\n')) @@ -916,8 +749,8 @@ def write_AeroDyn15(self): f.write('{!s:<22} {:<11} {:}'.format(self.fst_vt['AeroDyn15']['TIDrag'], 'TIDrag', '- Include the drag term in the tangential-induction calculation? (flag) [unused when WakeMod=0,3 or TanInd=FALSE]\n')) f.write('{:<22} {:<11} {:}'.format(self.fst_vt['AeroDyn15']['IndToler'], 'IndToler', '- Convergence tolerance for BEMT nonlinear solve residual equation {or "default"} (-) [unused when WakeMod=0 or 3]\n')) f.write('{:<22d} {:<11} {:}'.format(self.fst_vt['AeroDyn15']['MaxIter'], 'MaxIter', '- Maximum number of iteration steps (-) [unused when WakeMod=0]\n')) - f.write('====== Dynamic Blade-Element/Momentum Theory Options ====================================================== [used only when WakeMod=1]\n') - f.write('{:<22d} {:<11} {:}'.format(self.fst_vt['AeroDyn15']['DBEMT_Mod'], 'DBEMT_Mod', '- Type of dynamic BEMT (DBEMT) model {1=constant tau1, 2=time-dependent tau1} (-) [used only when WakeMod=2]\n')) + f.write('====== Dynamic Blade-Element/Momentum Theory Options ====================================================== [used only when WakeMod=2]\n') + f.write('{:<22d} {:<11} {:}'.format(self.fst_vt['AeroDyn15']['DBEMT_Mod'], 'DBEMT_Mod', '- Type of dynamic BEMT (DBEMT) model {1=constant tau1, 2=time-dependent tau1, 3=constant tau1 with continuous formulation} (-) [used only when WakeMod=2]\n')) f.write('{:<22} {:<11} {:}'.format(self.fst_vt['AeroDyn15']['tau1_const'], 'tau1_const', '- Time constant for DBEMT (s) [used only when WakeMod=2 and DBEMT_Mod=1]\n')) f.write('====== OLAF -- cOnvecting LAgrangian Filaments (Free Vortex Wake) Theory Options ================== [used only when WakeMod=3]\n') olaf_file = self.FAST_namingOut + '_OLAF.dat' @@ -925,8 +758,6 @@ def write_AeroDyn15(self): f.write('====== Beddoes-Leishman Unsteady Airfoil Aerodynamics Options ===================================== [used only when AFAeroMod=2]\n') f.write('{:<22d} {:<11} {:}'.format(self.fst_vt['AeroDyn15']['UAMod'], 'UAMod', "- Unsteady Aero Model Switch (switch) {1=Baseline model (Original), 2=Gonzalez's variant (changes in Cn,Cc,Cm), 3=Minnema/Pierce variant (changes in Cc and Cm)} [used only when AFAeroMod=2]\n")) f.write('{!s:<22} {:<11} {:}'.format(self.fst_vt['AeroDyn15']['FLookup'], 'FLookup', "- Flag to indicate whether a lookup for f' will be calculated (TRUE) or whether best-fit exponential equations will be used (FALSE); if FALSE S1-S4 must be provided in airfoil input files (flag) [used only when AFAeroMod=2]\n")) - f.write('{!s:<22} {:<11} {:}'.format(self.fst_vt['AeroDyn15']['UAStartRad'], 'UAStartRad', "- Starting radius for dynamic stall (fraction of rotor radius) [used only when AFAeroMod=2]\n")) - f.write('{!s:<22} {:<11} {:}'.format(self.fst_vt['AeroDyn15']['UAEndRad'], 'UAEndRad', "- Ending radius for dynamic stall (fraction of rotor radius) [used only when AFAeroMod=2]\n")) f.write('====== Airfoil Information =========================================================================\n') f.write('{:<22d} {:<11} {:}'.format(self.fst_vt['AeroDyn15']['AFTabMod'], 'AFTabMod', '- Interpolation method for multiple airfoil tables {1=1D interpolation on AoA (first table only); 2=2D interpolation on AoA and Re; 3=2D interpolation on AoA and UserProp} (-)\n')) f.write('{:<22d} {:<11} {:}'.format(self.fst_vt['AeroDyn15']['InCol_Alfa'], 'InCol_Alfa', '- The column in the airfoil tables that contains the angle of attack (-)\n')) @@ -945,12 +776,21 @@ def write_AeroDyn15(self): f.write('{:<22} {:<11} {:}'.format('"'+self.fst_vt['AeroDyn15']['ADBlFile1']+'"', 'ADBlFile(1)', '- Name of file containing distributed aerodynamic properties for Blade #1 (-)\n')) f.write('{:<22} {:<11} {:}'.format('"'+self.fst_vt['AeroDyn15']['ADBlFile2']+'"', 'ADBlFile(2)', '- Name of file containing distributed aerodynamic properties for Blade #2 (-) [unused if NumBl < 2]\n')) f.write('{:<22} {:<11} {:}'.format('"'+self.fst_vt['AeroDyn15']['ADBlFile3']+'"', 'ADBlFile(3)', '- Name of file containing distributed aerodynamic properties for Blade #3 (-) [unused if NumBl < 3]\n')) - f.write('====== Tower Influence and Aerodynamics ============================================================= [used only when TwrPotent/=0, TwrShadow/=0, or TwrAero=True]\n') - f.write('{:<22d} {:<11} {:}'.format(self.fst_vt['AeroDyn15']['NumTwrNds'], 'NumTwrNds', '- Number of tower nodes used in the analysis (-) [used only when TwrPotent/=0, TwrShadow/=0, or TwrAero=True]\n')) - f.write('TwrElev TwrDiam TwrCd TwrTI (used only with TwrShadow=2)\n') - f.write('(m) (m) (-) (-)\n') - for TwrElev, TwrDiam, TwrCd, TwrTI in zip(self.fst_vt['AeroDyn15']['TwrElev'], self.fst_vt['AeroDyn15']['TwrDiam'], self.fst_vt['AeroDyn15']['TwrCd'], self.fst_vt['AeroDyn15']['TwrTI']): - f.write('{: 2.15e} {: 2.15e} {: 2.15e} {: 2.15e} \n'.format(TwrElev, TwrDiam, TwrCd, TwrTI)) + f.write('====== Hub Properties ============================================================================== [used only when Buoyancy=True]\n') + f.write('{:<22} {:<11} {:}'.format(self.fst_vt['AeroDyn15']['VolHub'], 'VolHub', '- Hub volume (m^3)\n')) + f.write('{:<22} {:<11} {:}'.format(self.fst_vt['AeroDyn15']['HubCenBx'], 'HubCenBx', '- Hub center of buoyancy x direction offset (m)\n')) + f.write('====== Nacelle Properties ========================================================================== [used only when Buoyancy=True]\n') + f.write('{:<22} {:<11} {:}'.format(self.fst_vt['AeroDyn15']['VolNac'], 'VolNac', '- Nacelle volume (m^3)\n')) + f.write('{:<22} {:<11} {:}'.format(', '.join(np.array(self.fst_vt['AeroDyn15']['NacCenB'], dtype=str)), 'NacCenB', '- Position of nacelle center of buoyancy from yaw bearing in nacelle coordinates (m)\n')) + f.write('====== Tail Fin Aerodynamics ========================================================================\n') + f.write('{!s:<22} {:<11} {:}'.format(self.fst_vt['AeroDyn15']['TFinAero'], 'TFinAero', '- Calculate tail fin aerodynamics model (flag)\n')) + f.write('{:<22} {:<11} {:}'.format('"'+self.fst_vt['AeroDyn15']['TFinFile']+'"', 'TFinFile', '- Input file for tail fin aerodynamics [used only when TFinAero=True]\n')) + f.write('====== Tower Influence and Aerodynamics ============================================================ [used only when TwrPotent/=0, TwrShadow/=0, TwrAero=True, or Buoyancy=True]\n') + f.write('{:<22d} {:<11} {:}'.format(self.fst_vt['AeroDyn15']['NumTwrNds'], 'NumTwrNds', '- Number of tower nodes used in the analysis (-) [used only when TwrPotent/=0, TwrShadow/=0, TwrAero=True, or Buoyancy=True]\n')) + f.write('TwrElev TwrDiam TwrCd TwrTI TwrCb !TwrTI used only with TwrShadow=2, TwrCb used only with Buoyancy=True\n') + f.write('(m) (m) (-) (-) (-)\n') + for TwrElev, TwrDiam, TwrCd, TwrTI, TwrCb in zip(self.fst_vt['AeroDyn15']['TwrElev'], self.fst_vt['AeroDyn15']['TwrDiam'], self.fst_vt['AeroDyn15']['TwrCd'], self.fst_vt['AeroDyn15']['TwrTI'], self.fst_vt['AeroDyn15']['TwrCb']): + f.write('{: 2.15e} {: 2.15e} {: 2.15e} {: 2.15e} {: 2.15e} \n'.format(TwrElev, TwrDiam, TwrCd, TwrTI, TwrCb)) f.write('====== Outputs ====================================================================================\n') f.write('{!s:<22} {:<11} {:}'.format(self.fst_vt['AeroDyn15']['SumPrint'], 'SumPrint', '- Generate a summary file listing input options and interpolated properties to ".AD.sum"? (flag)\n')) f.write('{:<22d} {:<11} {:}'.format(self.fst_vt['AeroDyn15']['NBlOuts'], 'NBlOuts', '- Number of blade node outputs [0 - 9] (-)\n')) @@ -1027,7 +867,7 @@ def write_AeroDyn15Polar(self): f.write('! ------------------------------------------------------------------------------\n') f.write('{:<22} {:<11} {:}'.format(self.fst_vt['AeroDyn15']['af_data'][afi][0]['InterpOrd'], 'InterpOrd', '! Interpolation order to use for quasi-steady table lookup {1=linear; 3=cubic spline; "default"} [default=3]\n')) f.write('{:<22} {:<11} {:}'.format(self.fst_vt['AeroDyn15']['af_data'][afi][0]['NonDimArea'], 'NonDimArea', '! The non-dimensional area of the airfoil (area/chord^2) (set to 1.0 if unsure or unneeded)\n')) - if self.fst_vt['AeroDyn15']['af_data'][1][0]['NumCoords'] != '0': + if self.fst_vt['AeroDyn15']['af_data'][afi][0]['NumCoords'] != '0': f.write('@"{:}_AF{:02d}_Coords.txt" {:<11} {:}'.format(self.FAST_namingOut, afi, 'NumCoords', '! The number of coordinates in the airfoil shape file. Set to zero if coordinates not included.\n')) else: f.write('{:<22d} {:<11} {:}'.format(0, 'NumCoords', '! The number of coordinates in the airfoil shape file. Set to zero if coordinates not included.\n')) @@ -1041,8 +881,8 @@ def write_AeroDyn15Polar(self): num_tab = len(self.fst_vt['AeroDyn15']['af_data'][afi]) elif self.fst_vt['AeroDyn15']['AFTabMod'] == 3: # for tab_orig in range(self.fst_vt['AeroDyn15']['af_data'][afi][0]['NumTabs'] - 1): - if len(self.fst_vt['AeroDyn15']['af_data'][afi]) > 1 and \ - self.fst_vt['AeroDyn15']['af_data'][afi][0]['Ctrl'] == self.fst_vt['AeroDyn15']['af_data'][afi][1]['Ctrl']: + if len( self.fst_vt['AeroDyn15']['af_data'][afi]) == 1 or \ + self.fst_vt['AeroDyn15']['af_data'][afi][0]['Ctrl'] == self.fst_vt['AeroDyn15']['af_data'][afi][1]['Ctrl']: num_tab = 1 # assume that all Ctrl angles of the flaps are identical if the first two are -> no flaps! else: num_tab = self.fst_vt['AeroDyn15']['af_data'][afi][0]['NumTabs'] @@ -1166,57 +1006,187 @@ def write_AeroDyn15Coord(self): f.write(' '.join(['{: 2.14e}'.format(val) for val in row])+'\n') f.close() + def write_AeroDyn14(self): + + # ======= Airfoil Files ======== + # make directory for airfoil files + if not os.path.isdir(os.path.join(self.FAST_runDirectory,'AeroData')): + try: + os.mkdir(os.path.join(self.FAST_runDirectory,'AeroData')) + except: + try: + time.sleep(random.random()) + if not os.path.isdir(os.path.join(self.FAST_runDirectory,'AeroData')): + os.mkdir(os.path.join(self.FAST_runDirectory,'AeroData')) + except: + print("Error tring to make '%s'!"%os.path.join(self.FAST_runDirectory,'AeroData')) + + # create write airfoil objects to files + for i in range(self.fst_vt['AeroDyn14']['NumFoil']): + af_name = os.path.join(self.FAST_runDirectory, 'AeroData', 'Airfoil' + str(i) + '.dat') + self.fst_vt['AeroDyn14']['FoilNm'][i] = os.path.join('AeroData', 'Airfoil' + str(i) + '.dat') + self.write_AeroDyn14Polar(af_name, i) + + self.fst_vt['Fst']['AeroFile'] = self.FAST_namingOut + '_AeroDyn14.dat' + ad_file = os.path.join(self.FAST_runDirectory,self.fst_vt['Fst']['AeroFile']) + f = open(ad_file,'w') + + # create Aerodyn Tower + if self.fst_vt['AeroDyn14']['TwrShad'] > 0: + self.write_AeroDyn14Tower() + + # ======= Aerodyn Input File ======== + f.write('AeroDyn v14.04.* INPUT FILE\n\n') + + # f.write('{:}\n'.format(self.fst_vt['aerodyn']['SysUnits'])) + f.write('{:}\n'.format(self.fst_vt['AeroDyn14']['StallMod'])) + + f.write('{:}\n'.format(self.fst_vt['AeroDyn14']['UseCm'])) + f.write('{:}\n'.format(self.fst_vt['AeroDyn14']['InfModel'])) + f.write('{:}\n'.format(self.fst_vt['AeroDyn14']['IndModel'])) + f.write('{: 2.15e}\n'.format(self.fst_vt['AeroDyn14']['AToler'])) + f.write('{:}\n'.format(self.fst_vt['AeroDyn14']['TLModel'])) + f.write('{:}\n'.format(self.fst_vt['AeroDyn14']['HLModel'])) + f.write('{:}\n'.format(self.fst_vt['AeroDyn14']['TwrShad'])) + if self.fst_vt['AeroDyn14']['TwrShad'] > 0: + f.write('{:}\n'.format(self.fst_vt['AeroDyn14']['TwrPotent'])) + f.write('{:}\n'.format(self.fst_vt['AeroDyn14']['TwrShadow'])) + f.write('{:}\n'.format(self.fst_vt['AeroDyn14']['TwrFile'])) + f.write('{:}\n'.format(self.fst_vt['AeroDyn14']['CalcTwrAero'])) + else: + f.write('{: 2.15e}\n'.format(self.fst_vt['AeroDyn14']['ShadHWid'])) + f.write('{: 2.15e}\n'.format(self.fst_vt['AeroDyn14']['T_Shad_Refpt'])) + + f.write('{: 2.15e}\n'.format(self.fst_vt['AeroDyn14']['AirDens'])) + + f.write('{: 2.15e}\n'.format(self.fst_vt['AeroDyn14']['KinVisc'])) + + f.write('{:2}\n'.format(self.fst_vt['AeroDyn14']['DTAero'])) + + + f.write('{:2}\n'.format(self.fst_vt['AeroDyn14']['NumFoil'])) + for i in range (self.fst_vt['AeroDyn14']['NumFoil']): + f.write('"{:}"\n'.format(self.fst_vt['AeroDyn14']['FoilNm'][i])) + + f.write('{:2}\n'.format(self.fst_vt['AeroDynBlade']['BldNodes'])) + rnodes = self.fst_vt['AeroDynBlade']['RNodes'] + twist = self.fst_vt['AeroDynBlade']['AeroTwst'] + drnodes = self.fst_vt['AeroDynBlade']['DRNodes'] + chord = self.fst_vt['AeroDynBlade']['Chord'] + nfoil = self.fst_vt['AeroDynBlade']['NFoil'] + prnelm = self.fst_vt['AeroDynBlade']['PrnElm'] + f.write('Nodal properties\n') + for r, t, dr, c, a, p in zip(rnodes, twist, drnodes, chord, nfoil, prnelm): + f.write('{: 2.15e}\t{: 2.15e}\t{: 2.15e}\t{: 2.15e}\t{:5}\t{:}\n'.format(r, t, dr, c, a, p)) + + f.close() + + def write_AeroDyn14Tower(self): + # AeroDyn v14.04 Tower + self.fst_vt['AeroDyn14']['TwrFile'] = self.FAST_namingOut + '_AeroDyn14_tower.dat' + filename = os.path.join(self.FAST_runDirectory, self.fst_vt['AeroDyn14']['TwrFile']) + f = open(filename, 'w') + + f.write('AeroDyn tower file, Aerodyn v14.04 formatting\n') + f.write('Generated with AeroElasticSE FAST driver\n') + f.write('{:<22d} {:<11} {:}'.format(self.fst_vt['AeroDynTower']['NTwrHt'], 'NTwrHt', '- Number of tower input height stations listed (-)\n')) + f.write('{:<22d} {:<11} {:}'.format(self.fst_vt['AeroDynTower']['NTwrRe'], 'NTwrRe', '- Number of tower Re values (-)\n')) + f.write('{:<22d} {:<11} {:}'.format(self.fst_vt['AeroDynTower']['NTwrCD'], 'NTwrCD', '- Number of tower CD columns (-) Note: For current versions, this MUST be 1\n')) + f.write('{: 2.15e} {:<11} {:}'.format(self.fst_vt['AeroDynTower']['Tower_Wake_Constant'], 'Tower_Wake_Constant', '- Tower wake constant (-) {0.0: full potential flow, 0.1: Bak model}\n')) + f.write('---------------------- DISTRIBUTED TOWER PROPERTIES ----------------------------\n') + f.write('TwrHtFr TwrWid NTwrCDCol\n') + for HtFr, Wid, CDId in zip(self.fst_vt['AeroDynTower']['TwrHtFr'], self.fst_vt['AeroDynTower']['TwrWid'], self.fst_vt['AeroDynTower']['NTwrCDCol']): + f.write('{: 2.15e} {: 2.15e} {:d}\n'.format(HtFr, Wid, int(CDId))) + f.write('---------------------- Re v CD PROPERTIES --------------------------------------\n') + f.write('TwrRe '+ ' '.join(['TwrCD%d'%(i+1) for i in range(self.fst_vt['AeroDynTower']['NTwrCD'])]) +'\n') + for Re, CD in zip(self.fst_vt['AeroDynTower']['TwrRe'], self.fst_vt['AeroDynTower']['TwrCD']): + f.write('% 2.15e' %Re + ' '.join(['% 2.15e'%cdi for cdi in CD]) + '\n') + + f.close() + + def write_AeroDyn14Polar(self, filename, a_i): + # AeroDyn v14 Airfoil Polar Input File + + f = open(filename, 'w') + f.write('AeroDyn airfoil file, Aerodyn v14.04 formatting\n') + f.write('Generated with AeroElasticSE FAST driver\n') + + f.write('{:9d}\t{:}'.format(self.fst_vt['AeroDynBlade']['af_data'][a_i]['number_tables'], 'Number of airfoil tables in this file\n')) + for i in range(self.fst_vt['AeroDynBlade']['af_data'][a_i]['number_tables']): + param = self.fst_vt['AeroDynBlade']['af_data'][a_i]['af_tables'][i] + f.write('{:9g}\t{:}'.format(i, 'Table ID parameter\n')) + f.write('{: f}\t{:}'.format(param['StallAngle'], 'Stall angle (deg)\n')) + f.write('{: f}\t{:}'.format(0, 'No longer used, enter zero\n')) + f.write('{: f}\t{:}'.format(0, 'No longer used, enter zero\n')) + f.write('{: f}\t{:}'.format(0, 'No longer used, enter zero\n')) + f.write('{: f}\t{:}'.format(param['ZeroCn'], 'Angle of attack for zero Cn for linear Cn curve (deg)\n')) + f.write('{: f}\t{:}'.format(param['CnSlope'], 'Cn slope for zero lift for linear Cn curve (1/rad)\n')) + f.write('{: f}\t{:}'.format(param['CnPosStall'], 'Cn at stall value for positive angle of attack for linear Cn curve\n')) + f.write('{: f}\t{:}'.format(param['CnNegStall'], 'Cn at stall value for negative angle of attack for linear Cn curve\n')) + f.write('{: f}\t{:}'.format(param['alphaCdMin'], 'Angle of attack for minimum CD (deg)\n')) + f.write('{: f}\t{:}'.format(param['CdMin'], 'Minimum CD value\n')) + if param['cm']: + for a, cl, cd, cm in zip(param['alpha'], param['cl'], param['cd'], param['cm']): + f.write('{: 6e} {: 6e} {: 6e} {: 6e}\n'.format(a, cl, cd, cm)) + else: + for a, cl, cd in zip(param['alpha'], param['cl'], param['cd']): + f.write('{: 6e} {: 6e} {: 6e}\n'.format(a, cl, cd)) + + f.close() + def write_OLAF(self): olaf_file = os.path.join(self.FAST_runDirectory, self.FAST_namingOut + '_OLAF.dat') f = open(olaf_file, 'w') f.write('--------------------------- OLAF (cOnvecting LAgrangian Filaments) INPUT FILE -----------------\n') - f.write('Free wake input file for the Helix test case\n') + f.write('Generated by WEIS\n') f.write('--------------------------- GENERAL OPTIONS ---------------------------------------------------\n') - f.write('{:<22} {:<11} {:}'.format(self.fst_vt['AeroDyn15']['OLAF']['IntMethod'], 'IntMethod', 'Integration method {5: Forward Euler 1st order, default: 5} (switch)\n')) - f.write('{:<22} {:<11} {:}'.format(self.fst_vt['AeroDyn15']['OLAF']['DTfvw'], 'DTfvw', 'Time interval for wake propagation. {default: dtaero} (s)\n')) - f.write('{:<22} {:<11} {:}'.format(self.fst_vt['AeroDyn15']['OLAF']['FreeWakeStart'], 'FreeWakeStart', 'Time when wake is free. (-) value = always free. {default: 0.0} (s)\n')) - f.write('{:<22} {:<11} {:}'.format(self.fst_vt['AeroDyn15']['OLAF']['FullCircStart'], 'FullCircStart', 'Time at which full circulation is reached. {default: 0.0} (s)\n')) + f.write('{:<22} {:<11} {:}'.format(self.fst_vt['AeroDyn15']['OLAF']['IntMethod'], 'IntMethod', '- Integration method {1: RK4, 5: Forward Euler 1st order, default: 5} (switch)\n')) + f.write('{:<22} {:<11} {:}'.format(self.fst_vt['AeroDyn15']['OLAF']['DTfvw'], 'DTfvw', '- Time interval for wake propagation. {default: dtaero} (s)\n')) + f.write('{:<22} {:<11} {:}'.format(self.fst_vt['AeroDyn15']['OLAF']['FreeWakeStart'], 'FreeWakeStart', '- Time when wake is free. (-) value = always free. {default: 0.0} (s)\n')) + f.write('{:<22} {:<11} {:}'.format(self.fst_vt['AeroDyn15']['OLAF']['FullCircStart'], 'FullCircStart', '- Time at which full circulation is reached. {default: 0.0} (s)\n')) f.write('--------------------------- CIRCULATION SPECIFICATIONS ----------------------------------------\n') - f.write('{:<22} {:<11} {:}'.format(self.fst_vt['AeroDyn15']['OLAF']['CircSolvingMethod'], 'CircSolvingMethod', 'Circulation solving method {1: Cl-Based, 2: No-Flow Through, 3: Prescribed, default: 1 }(switch)\n')) - f.write('{:<22} {:<11} {:}'.format(self.fst_vt['AeroDyn15']['OLAF']['CircSolvConvCrit'], 'CircSolvConvCrit', 'Convergence criteria {default: 0.001} [only if CircSolvingMethod=1] (-)\n')) - f.write('{:<22} {:<11} {:}'.format(self.fst_vt['AeroDyn15']['OLAF']['CircSolvRelaxation'], 'CircSolvRelaxation', 'Relaxation factor {default: 0.1} [only if CircSolvingMethod=1] (-)\n')) - f.write('{:<22} {:<11} {:}'.format(self.fst_vt['AeroDyn15']['OLAF']['CircSolvMaxIter'], 'CircSolvMaxIter', 'Maximum number of iterations for circulation solving {default: 30} (-)\n')) - f.write('{:<22} {:<11} {:}'.format(self.fst_vt['AeroDyn15']['OLAF']['PrescribedCircFile'], 'PrescribedCircFile','File containing prescribed circulation [only if CircSolvingMethod=3] (quoted string)\n')) + f.write('{:<22} {:<11} {:}'.format(self.fst_vt['AeroDyn15']['OLAF']['CircSolvMethod'], 'CircSolvingMethod', '- Circulation solving method {1: Cl-Based, 2: No-Flow Through, 3: Prescribed, default: 1 }(switch)\n')) + f.write('{:<22} {:<11} {:}'.format(self.fst_vt['AeroDyn15']['OLAF']['CircSolvConvCrit'], 'CircSolvConvCrit', ' - Convergence criteria {default: 0.001} [only if CircSolvMethod=1] (-)\n')) + f.write('{:<22} {:<11} {:}'.format(self.fst_vt['AeroDyn15']['OLAF']['CircSolvRelaxation'], 'CircSolvRelaxation', '- Relaxation factor {default: 0.1} [only if CircSolvMethod=1] (-)\n')) + f.write('{:<22} {:<11} {:}'.format(self.fst_vt['AeroDyn15']['OLAF']['CircSolvMaxIter'], 'CircSolvMaxIter', ' - Maximum number of iterations for circulation solving {default: 30} (-)\n')) + f.write('{:<22} {:<11} {:}'.format(self.fst_vt['AeroDyn15']['OLAF']['PrescribedCircFile'], 'PrescribedCircFile','- File containing prescribed circulation [only if CircSolvMethod=3] (quoted string)\n')) f.write('===============================================================================================\n') f.write('--------------------------- WAKE OPTIONS ------------------------------------------------------\n') f.write('------------------- WAKE EXTENT AND DISCRETIZATION --------------------------------------------\n') - f.write('{:<22d} {:<11} {:}'.format(self.fst_vt['AeroDyn15']['OLAF']['nNWPanel'], 'nNWPanel','Number of near-wake panels [integer] (-)\n')) - f.write('{:<22d} {:<11} {:}'.format(self.fst_vt['AeroDyn15']['OLAF']['WakeLength'], 'WakeLength','Total wake distance [integer] (number of time steps)\n')) - f.write('{:<22d} {:<11} {:}'.format(self.fst_vt['AeroDyn15']['OLAF']['FreeWakeLength'], 'FreeWakeLength','Wake length that is free [integer] (number of time steps) {default: WakeLength}\n')) - f.write('{!s:<22} {:<11} {:}'.format(self.fst_vt['AeroDyn15']['OLAF']['FWShedVorticity'], 'FWShedVorticity','Include shed vorticity in the far wake {default: false}\n')) + f.write('{:<22d} {:<11} {:}'.format(self.fst_vt['AeroDyn15']['OLAF']['nNWPanels'], 'nNWPanels','- Number of near-wake panels (-)\n')) + f.write('{:<22d} {:<11} {:}'.format(self.fst_vt['AeroDyn15']['OLAF']['nNWPanelsFree'], 'nNWPanelsFree','- Number of free near-wake panels (-) {default: nNWPanels}\n')) + f.write('{:<22d} {:<11} {:}'.format(self.fst_vt['AeroDyn15']['OLAF']['nFWPanels'], 'nFWPanels','- Number of far-wake panels (-) {default: 0}\n')) + f.write('{:<22d} {:<11} {:}'.format(self.fst_vt['AeroDyn15']['OLAF']['nFWPanelsFree'], 'nFWPanelsFree','- Number of free far-wake panels (-) {default: nFWPanels}\n')) + f.write('{!s:<22} {:<11} {:}'.format(self.fst_vt['AeroDyn15']['OLAF']['FWShedVorticity'], 'FWShedVorticity','- Include shed vorticity in the far wake {default: False}\n')) f.write('------------------- WAKE REGULARIZATIONS AND DIFFUSION -----------------------------------------\n') - f.write('{:<22d} {:<11} {:}'.format(self.fst_vt['AeroDyn15']['OLAF']['DiffusionMethod'], 'DiffusionMethod','Diffusion method to account for viscous effects {0: None, 1: Core Spreading, "default": 0}\n')) - f.write('{:<22d} {:<11} {:}'.format(self.fst_vt['AeroDyn15']['OLAF']['RegDeterMethod'], 'RegDeterMethod','Method to determine the regularization parameters {0: Manual, 1: Optimized, default: 0 }\n')) - f.write('{:<22d} {:<11} {:}'.format(self.fst_vt['AeroDyn15']['OLAF']['RegFunction'], 'RegFunction','Viscous diffusion function {0: None, 1: Rankine, 2: LambOseen, 3: Vatistas, 4: Denominator, "default": 3} (switch)\n')) - f.write('{:<22d} {:<11} {:}'.format(self.fst_vt['AeroDyn15']['OLAF']['WakeRegMethod'], 'WakeRegMethod','Wake regularization method {1: Constant, 2: Stretching, 3: Age, default: 1} (switch)\n')) - f.write('{:<22} {:<11} {:}'.format(self.fst_vt['AeroDyn15']['OLAF']['WakeRegFactor'], 'WakeRegFactor','Wake regularization factor (m)\n')) - f.write('{:<22} {:<11} {:}'.format(self.fst_vt['AeroDyn15']['OLAF']['WingRegFactor'], 'WingRegFactor','Wing regularization factor (m)\n')) - f.write('{:<22} {:<11} {:}'.format(self.fst_vt['AeroDyn15']['OLAF']['CoreSpreadEddyVisc'], 'CoreSpreadEddyVisc','Eddy viscosity in core spreading methods, typical values 1-1000\n')) + f.write('{:<22d} {:<11} {:}'.format(self.fst_vt['AeroDyn15']['OLAF']['DiffusionMethod'], 'DiffusionMethod','- Diffusion method to account for viscous effects {0: None, 1: Core Spreading, "default": 0}\n')) + f.write('{:<22d} {:<11} {:}'.format(self.fst_vt['AeroDyn15']['OLAF']['RegDeterMethod'], 'RegDeterMethod','- Method to determine the regularization parameters {0: Manual, 1: Optimized, 2: Chord, 3: Span, default: 0 }\n')) + f.write('{:<22d} {:<11} {:}'.format(self.fst_vt['AeroDyn15']['OLAF']['RegFunction'], 'RegFunction','- Viscous diffusion function {0: None, 1: Rankine, 2: LambOseen, 3: Vatistas, 4: Denominator, "default": 3} (switch)\n')) + f.write('{:<22d} {:<11} {:}'.format(self.fst_vt['AeroDyn15']['OLAF']['WakeRegMethod'], 'WakeRegMethod','- Wake regularization method {1: Constant, 2: Stretching, 3: Age, default: 3} (switch)\n')) + f.write('{:<22} {:<11} {:}'.format(self.fst_vt['AeroDyn15']['OLAF']['WakeRegFactor'], 'WakeRegFactor','- Wake regularization factor (m)\n')) + f.write('{:<22} {:<11} {:}'.format(self.fst_vt['AeroDyn15']['OLAF']['WingRegFactor'], 'WingRegFactor','- Wing regularization factor (m)\n')) + f.write('{:<22} {:<11} {:}'.format(self.fst_vt['AeroDyn15']['OLAF']['CoreSpreadEddyVisc'], 'CoreSpreadEddyVisc','- Eddy viscosity in core spreading methods, typical values 1-1000\n')) f.write('------------------- WAKE TREATMENT OPTIONS ---------------------------------------------------\n') - f.write('{!s:<22} {:<11} {:}'.format(self.fst_vt['AeroDyn15']['OLAF']['TwrShadowOnWake'], 'TwrShadowOnWake','Include tower flow disturbance effects on wake convection {default:false} [only if TwrPotent or TwrShadow]\n')) - f.write('{:<22d} {:<11} {:}'.format(self.fst_vt['AeroDyn15']['OLAF']['ShearModel'], 'ShearModel','Shear Model {0: No treatment, 1: Mirrored vorticity, default: 0}\n')) + f.write('{!s:<22} {:<11} {:}'.format(self.fst_vt['AeroDyn15']['OLAF']['TwrShadowOnWake'], 'TwrShadowOnWake','- Include tower flow disturbance effects on wake convection {default:false} [only if TwrPotent or TwrShadow]\n')) + f.write('{:<22d} {:<11} {:}'.format(self.fst_vt['AeroDyn15']['OLAF']['ShearModel'], 'ShearModel','- Shear Model {0: No treatment, 1: Mirrored vorticity, default: 0}\n')) f.write('------------------- SPEEDUP OPTIONS -----------------------------------------------------------\n') - f.write('{:<22d} {:<11} {:}'.format(self.fst_vt['AeroDyn15']['OLAF']['VelocityMethod'], 'VelocityMethod','Method to determine the velocity {1:Biot-Savart Segment, 2:Particle tree, default: 1}\n')) - f.write('{:<22} {:<11} {:}'.format(self.fst_vt['AeroDyn15']['OLAF']['TreeBranchFactor'], 'TreeBranchFactor','Branch radius fraction above which a multipole calculation is used {default: 2.0} [only if VelocityMethod=2]\n')) - f.write('{:<22d} {:<11} {:}'.format(self.fst_vt['AeroDyn15']['OLAF']['PartPerSegment'], 'PartPerSegment','Number of particles per segment [only if VelocityMethod=2]\n')) + f.write('{:<22d} {:<11} {:}'.format(self.fst_vt['AeroDyn15']['OLAF']['VelocityMethod'], 'VelocityMethod','- Method to determine the velocity {1:Segment N^2, 2:Particle tree, 3:Particle N^2, 4:Segment tree, default: 2}\n')) + f.write('{:<22} {:<11} {:}'.format(self.fst_vt['AeroDyn15']['OLAF']['TreeBranchFactor'], 'TreeBranchFactor','- Branch radius fraction above which a multipole calculation is used {default: 1.5} [only if VelocityMethod=2,4]\n')) + f.write('{:<22d} {:<11} {:}'.format(self.fst_vt['AeroDyn15']['OLAF']['PartPerSegment'], 'PartPerSegment','- Number of particles per segment {default: 1} [only if VelocityMethod=2,3]\n')) f.write('===============================================================================================\n') f.write('--------------------------- OUTPUT OPTIONS ---------------------------------------------------\n') - f.write('{:<22d} {:<11} {:}'.format(self.fst_vt['AeroDyn15']['OLAF']['WrVTk'], 'WrVTk','Outputs Visualization Toolkit (VTK) (independent of .fst option) {0: NoVTK, 1: Write VTK at each time step} (flag)\n')) - f.write('{:<22d} {:<11} {:}'.format(self.fst_vt['AeroDyn15']['OLAF']['nVTKBlades'], 'nVTKBlades','Number of blades for which VTK files are exported {0: No VTK per blade, n: VTK for blade 1 to n} (-)\n')) - f.write('{:<22d} {:<11} {:}'.format(self.fst_vt['AeroDyn15']['OLAF']['VTKCoord'], 'VTKCoord','Coordinate system used for VTK export. {1: Global, 2: Hub, "default": 1}\n')) - f.write('{:<22} {:<11} {:}'.format(self.fst_vt['AeroDyn15']['OLAF']['VTK_fps'], 'VTK_fps','Frame rate for VTK output (frames per second) {"all" for all glue code timesteps, "default" for all OLAF timesteps} [used only if WrVTK=1]\n')) - f.write('{:<22} {:<11} {:}'.format(self.fst_vt['AeroDyn15']['OLAF']['nGridOut'], 'nGridOut','GB DEBUG 7/8: Number of grid points for VTK output\n')) - f.write('--GridOutHeaders--\n') - f.write('--GridOutUnits--\n') - f.write('1.0 1.0 1.0\n') - f.write('------------------------------------------------------------------------------------------------\n') + f.write('{:<22d} {:<11} {:}'.format(self.fst_vt['AeroDyn15']['OLAF']['WrVTk'], 'WrVTk','- Outputs Visualization Toolkit (VTK) (independent of .fst option) {0: NoVTK, 1: Write VTK at VTK_fps, 2: Write VTK at init and final, default: 0} (flag)\n')) + f.write('{:<22d} {:<11} {:}'.format(self.fst_vt['AeroDyn15']['OLAF']['nVTKBlades'], 'nVTKBlades','- Number of blades for which VTK files are exported {0: No VTK per blade, n: VTK for blade 1 to n, default: 0} (-) \n')) + f.write('{:<22d} {:<11} {:}'.format(self.fst_vt['AeroDyn15']['OLAF']['VTKCoord'], 'VTKCoord','- Coordinate system used for VTK export. {1: Global, 2: Hub, 3: Both, default: 1} \n')) + f.write('{:<22} {:<11} {:}'.format(self.fst_vt['AeroDyn15']['OLAF']['VTK_fps'], 'VTK_fps','- Frame rate for VTK output (frames per second) {"all" for all glue code timesteps, "default" for all OLAF timesteps} [only if WrVTK=1]\n')) + f.write('{:<22} {:<11} {:}'.format(self.fst_vt['AeroDyn15']['OLAF']['nGridOut'], 'nGridOut','- Number of grid outputs\n')) + f.write('GridName GridType TStart TEnd DTGrid XStart XEnd nX YStart YEnd nY ZStart ZEnd nZ\n') + f.write('(-) (-) (s) (s) (s) (m) (m) (-) (m) (m) (-) (m) (m) (-)\n') + f.write('===============================================================================================\n') + f.write('--------------------------- ADVANCED OPTIONS --------------------------------------------------\n') + f.write('===============================================================================================\n') f.close() @@ -1368,8 +1338,8 @@ def write_DISCON_in(self): turbine.Cq_table = self.fst_vt['DISCON_in']['Cq_table'] turbine.pitch_initial_rad = self.fst_vt['DISCON_in']['Cp_pitch_initial_rad'] turbine.TSR_initial = self.fst_vt['DISCON_in']['Cp_TSR_initial'] - turbine.TurbineName = self.fst_vt['description'] - + turbine.TurbineName = 'WEIS Turbine' + # Define DISCON infile paths self.fst_vt['ServoDyn']['DLL_InFile'] = self.FAST_namingOut + '_DISCON.IN' discon_in_file = os.path.join(self.FAST_runDirectory, self.fst_vt['ServoDyn']['DLL_InFile']) @@ -1410,7 +1380,14 @@ def write_HydroDyn(self): f.write('{:<22} {:<11} {:}'.format(self.fst_vt['HydroDyn']['WaveDT'], 'WaveDT', '- Time step for incident wave calculations (sec) [unused when WaveMod=0; 0.1<=WaveDT<=1.0 recommended; determines WaveOmegaMax=Pi/WaveDT in the IFFT]\n')) f.write('{:<22} {:<11} {:}'.format(self.fst_vt['HydroDyn']['WaveHs'], 'WaveHs', '- Significant wave height of incident waves (meters) [used only when WaveMod=1, 2, or 3]\n')) f.write('{:<22} {:<11} {:}'.format(self.fst_vt['HydroDyn']['WaveTp'], 'WaveTp', '- Peak-spectral period of incident waves (sec) [used only when WaveMod=1 or 2]\n')) - f.write('{:<22} {:<11} {:}'.format(self.fst_vt['HydroDyn']['WavePkShp'], 'WavePkShp', '- Peak-shape parameter of incident wave spectrum (-) or DEFAULT (string) [used only when WaveMod=2; use 1.0 for Pierson-Moskowitz]\n')) + if isinstance(self.fst_vt['HydroDyn']['WavePkShp'], float): + if self.fst_vt['HydroDyn']['WavePkShp'] == 0.: + WavePkShp = 'Default' + else: + WavePkShp = self.fst_vt['HydroDyn']['WavePkShp'] + else: + WavePkShp = self.fst_vt['HydroDyn']['WavePkShp'] + f.write('{:<22} {:<11} {:}'.format(WavePkShp, 'WavePkShp', '- Peak-shape parameter of incident wave spectrum (-) or DEFAULT (string) [used only when WaveMod=2; use 1.0 for Pierson-Moskowitz]\n')) f.write('{:<22} {:<11} {:}'.format(self.fst_vt['HydroDyn']['WvLowCOff'], 'WvLowCOff', '- Low cut-off frequency or lower frequency limit of the wave spectrum beyond which the wave spectrum is zeroed (rad/s) [unused when WaveMod=0, 1, or 6]\n')) f.write('{:<22} {:<11} {:}'.format(self.fst_vt['HydroDyn']['WvHiCOff'], 'WvHiCOff', '- High cut-off frequency or upper frequency limit of the wave spectrum beyond which the wave spectrum is zeroed (rad/s) [unused when WaveMod=0, 1, or 6]\n')) f.write('{:<22} {:<11} {:}'.format(self.fst_vt['HydroDyn']['WaveDir'], 'WaveDir', '- Incident wave propagation heading direction (degrees) [unused when WaveMod=0 or 6]\n')) @@ -1419,7 +1396,13 @@ def write_HydroDyn(self): f.write('{:<22d} {:<11} {:}'.format(self.fst_vt['HydroDyn']['WaveNDir'], 'WaveNDir', '- Number of wave directions (-) [only used when WaveMod=2,3, or 4 and WaveDirMod=1; odd number only]\n')) f.write('{:<22} {:<11} {:}'.format(self.fst_vt['HydroDyn']['WaveDirRange'], 'WaveDirRange', '- Range of wave directions (full range: WaveDir +/- 1/2*WaveDirRange) (degrees) [only used when WaveMod=2,3,or 4 and WaveDirMod=1]\n')) f.write('{:<22d} {:<11} {:}'.format(self.fst_vt['HydroDyn']['WaveSeed1'], 'WaveSeed(1)', '- First random seed of incident waves [-2147483648 to 2147483647] (-) [unused when WaveMod=0, 5, or 6]\n')) - f.write('{:<22d} {:<11} {:}'.format(self.fst_vt['HydroDyn']['WaveSeed2'], 'WaveSeed(2)', '- Second random seed of incident waves [-2147483648 to 2147483647] (-) [unused when WaveMod=0, 5, or 6]\n')) + + try: + seed2 = int(self.fst_vt['HydroDyn']['WaveSeed2']) + f.write('{:<22d} {:<11} {:}'.format(self.fst_vt['HydroDyn']['WaveSeed2'], 'WaveSeed(2)', '- Second random seed of incident waves [-2147483648 to 2147483647] (-) [unused when WaveMod=0, 5, or 6]\n')) + except ValueError: + f.write('{!s:<22} {:<11} {:}'.format(self.fst_vt['HydroDyn']['WaveSeed2'], 'WaveSeed(2)', '- Second random seed of incident waves [-2147483648 to 2147483647] (-) [unused when WaveMod=0, 5, or 6] for intrinsic pRNG, or an alternative pRNG: "RanLux"\n')) + f.write('{!s:<22} {:<11} {:}'.format(self.fst_vt['HydroDyn']['WaveNDAmp'], 'WaveNDAmp', '- Flag for normally distributed amplitudes (flag) [only used when WaveMod=2, 3, or 4]\n')) f.write('{:<22} {:<11} {:}'.format('"'+self.fst_vt['HydroDyn']['WvKinFile']+'"', 'WvKinFile', '- Root name of externally generated wave data file(s) (quoted string) [used only when WaveMod=5 or 6]\n')) f.write('{:<22} {:<11} {:}'.format(self.fst_vt['HydroDyn']['NWaveElev'], 'NWaveElev', '- Number of points where the incident wave elevations can be computed (-) [maximum of 9 output locations]\n')) @@ -1517,7 +1500,7 @@ def write_HydroDyn(self): f.write(" ".join(ln) + '\n') f.write('---------------------- MEMBER JOINTS -------------------------------------------\n') f.write('{:<22d} {:<11} {:}'.format(self.fst_vt['HydroDyn']['NJoints'], 'NJoints', '- Number of joints (-) [must be exactly 0 or at least 2]\n')) - f.write(" ".join(['{:^11s}'.format(i) for i in ['JointID', 'Jointxi', 'Jointyi', 'Jointzi', 'JointAxID', 'JointOvrlp']])+' [JointOvrlp= 0: do nothing at joint, 1: eliminate overlaps by calculating super member]\n') + f.write(" ".join(['{:^11s}'.format(i) for i in ['JointID', 'Jointxi', 'Jointyi', 'Jointzi', 'JointAxID', 'JointOvrlp']])+' ! [JointOvrlp= 0: do nothing at joint, 1: eliminate overlaps by calculating super member]\n') f.write(" ".join(['{:^11s}'.format(i) for i in ['(-)', '(m)', '(m)', '(m)', '(-)', '(switch)']])+'\n') for i in range(self.fst_vt['HydroDyn']['NJoints']): ln = [] @@ -1609,7 +1592,7 @@ def write_HydroDyn(self): f.write(" ".join(ln) + '\n') f.write('-------------------- MEMBERS -------------------------------------------------\n') f.write('{:<11d} {:<11} {:}'.format(self.fst_vt['HydroDyn']['NMembers'], 'NMembers', '- Number of members (-)\n')) - f.write(" ".join(['{:^11s}'.format(i) for i in ['MemberID', 'MJointID1', 'MJointID2', 'MPropSetID1', 'MPropSetID2', 'MDivSize', 'MCoefMod', 'PropPot']])+' [MCoefMod=1: use simple coeff table, 2: use depth-based coeff table, 3: use member-based coeff table] [ PropPot/=0 if member is modeled with potential-flow theory]\n') + f.write(" ".join(['{:^11s}'.format(i) for i in ['MemberID', 'MJointID1', 'MJointID2', 'MPropSetID1', 'MPropSetID2', 'MDivSize', 'MCoefMod', 'PropPot']])+' ! [MCoefMod=1: use simple coeff table, 2: use depth-based coeff table, 3: use member-based coeff table] [ PropPot/=0 if member is modeled with potential-flow theory]\n') f.write(" ".join(['{:^11s}'.format(i) for i in ['(-)', '(-)', '(-)', '(-)', '(-)', '(m)', '(switch)', '(flag)']])+'\n') for i in range(self.fst_vt['HydroDyn']['NMembers']): ln = [] @@ -1693,10 +1676,10 @@ def write_SubDyn(self): f.write('{:<22d} {:<11} {:}'.format(self.fst_vt['SubDyn']['Nmodes'], 'Nmodes', '- Number of internal modes to retain (ignored if CBMod=False). If Nmodes=0 --> Guyan Reduction.\n')) JDampings = self.fst_vt['SubDyn']['JDampings'] - if isinstance(JDampings, int): + if isinstance(JDampings, float): f.write('{:<22} {:<11} {:}'.format(self.fst_vt['SubDyn']['JDampings'], 'JDampings', '- Damping Ratios for each retained mode (% of critical) If Nmodes>0, list Nmodes structural damping ratios for each retained mode (% of critical), or a single damping ratio to be applied to all retained modes. (last entered value will be used for all remaining modes).\n')) - else: - f.write('{:<22} {:<11} {:}'.format(", ".join(self.fst_vt['SubDyn']['JDampings']), 'JDampings', '- Damping Ratios for each retained mode (% of critical) If Nmodes>0, list Nmodes structural damping ratios for each retained mode (% of critical), or a single damping ratio to be applied to all retained modes. (last entered value will be used for all remaining modes).\n')) + else: # list of floats + f.write('{:<22} {:<11} {:}'.format(", ".join([f'{d:f}' for d in self.fst_vt['SubDyn']['JDampings']]), 'JDampings', '- Damping Ratios for each retained mode (% of critical) If Nmodes>0, list Nmodes structural damping ratios for each retained mode (% of critical), or a single damping ratio to be applied to all retained modes. (last entered value will be used for all remaining modes).\n')) f.write('{:<22d} {:<11} {:}'.format(self.fst_vt['SubDyn']['GuyanDampMod'], 'GuyanDampMod', '- Guyan damping {0=none, 1=Rayleigh Damping, 2=user specified 6x6 matrix}.\n')) f.write('{:<10}, {:<10} {:<11} {:}'.format(self.fst_vt['SubDyn']['RayleighDamp'][0], self.fst_vt['SubDyn']['RayleighDamp'][1], 'RayleighDamp', '- Mass and stiffness proportional damping coefficients (Rayleigh Damping) [only if GuyanDampMod=1].\n')) f.write('{:<22d} {:<11} {:}'.format(self.fst_vt['SubDyn']['GuyanDampSize'], 'GuyanDampSize', '- Guyan damping matrix (6x6) [only if GuyanDampMod=2].\n')) @@ -1726,7 +1709,7 @@ def write_SubDyn(self): f.write(" ".join(ln) + '\n') f.write('------------------- BASE REACTION JOINTS: 1/0 for Locked/Free DOF @ each Reaction Node ---------------------\n') f.write('{:<22d} {:<11} {:}'.format(self.fst_vt['SubDyn']['NReact'], 'NReact', '- Number of Joints with reaction forces; be sure to remove all rigid motion DOFs of the structure (else det([K])=[0])\n')) - f.write(" ".join(['{:^11s}'.format(i) for i in ['RJointID', 'RctTDXss', 'RctTDYss', 'RctTDZss', 'RctRDXss', 'RctRDYss', 'RctRDZss','SSIfile']])+' [Global Coordinate System]\n') + f.write(" ".join(['{:^11s}'.format(i) for i in ['RJointID', 'RctTDXss', 'RctTDYss', 'RctTDZss', 'RctRDXss', 'RctRDYss', 'RctRDZss','SSIfile']])+' ! [Global Coordinate System]\n') f.write(" ".join(['{:^11s}'.format(i) for i in ['(-)', '(flag)', '(flag)', '(flag)', '(flag)', '(flag)', '(flag)', '(string)']])+'\n') for i in range(self.fst_vt['SubDyn']['NReact']): ln = [] @@ -1741,7 +1724,7 @@ def write_SubDyn(self): f.write(" ".join(ln) + '\n') f.write('------- INTERFACE JOINTS: 1/0 for Locked (to the TP)/Free DOF @each Interface Joint (only Locked-to-TP implemented thus far (=rigid TP)) ---------\n') f.write('{:<22d} {:<11} {:}'.format(self.fst_vt['SubDyn']['NInterf'], 'NInterf', '- Number of interface joints locked to the Transition Piece (TP): be sure to remove all rigid motion dofs\n')) - f.write(" ".join(['{:^11s}'.format(i) for i in ['IJointID', 'ItfTDXss', 'ItfTDYss', 'ItfTDZss', 'ItfRDXss', 'ItfRDYss', 'ItfRDZss']])+' [Global Coordinate System]\n') + f.write(" ".join(['{:^11s}'.format(i) for i in ['IJointID', 'ItfTDXss', 'ItfTDYss', 'ItfTDZss', 'ItfRDXss', 'ItfRDYss', 'ItfRDZss']])+' ! [Global Coordinate System]\n') f.write(" ".join(['{:^11s}'.format(i) for i in ['(-)', '(flag)', '(flag)', '(flag)', '(flag)', '(flag)', '(flag)']])+'\n') for i in range(self.fst_vt['SubDyn']['NInterf']): ln = [] @@ -1864,7 +1847,7 @@ def write_SubDyn(self): f.write('{:<22} {:<11} {:}'.format(self.fst_vt['SubDyn']['OutSFmt'], 'OutSFmt', '- Output format for header strings in the .SD.out file\n')) f.write('------------------------- MEMBER OUTPUT LIST ------------------------------------------\n') f.write('{:<22d} {:<11} {:}'.format(self.fst_vt['SubDyn']['NMOutputs'], 'NMOutputs', '- Number of members whose forces/displacements/velocities/accelerations will be output (-) [Must be <= 9].\n')) - f.write(" ".join(['{:^11s}'.format(i) for i in ['MemberID', 'NOutCnt', 'NodeCnt']])+'[NOutCnt=how many nodes to get output for [< 10]; NodeCnt are local ordinal numbers from the start of the member, and must be >=1 and <= NDiv+1] If NMOutputs=0 leave blank as well.\n') + f.write(" ".join(['{:^11s}'.format(i) for i in ['MemberID', 'NOutCnt', 'NodeCnt']])+' ! [NOutCnt=how many nodes to get output for [< 10]; NodeCnt are local ordinal numbers from the start of the member, and must be >=1 and <= NDiv+1] If NMOutputs=0 leave blank as well.\n') f.write(" ".join(['{:^11s}'.format(i) for i in ['(-)','(-)','(-)']])+'\n') for i in range(self.fst_vt['SubDyn']['NMOutputs']): ln = [] @@ -2010,350 +1993,146 @@ def write_MoorDyn(self): f.write('END\n') f.write('------------------------- need this line --------------------------------------\n') - f.close() - -class InputWriter_FAST7(InputWriter_Common): - - def execute(self): + f.close() - if not os.path.exists(self.FAST_runDirectory): - os.makedirs(self.FAST_runDirectory) - - # self.write_WindWnd() - self.write_ElastoDynBlade() - self.write_ElastoDynTower() - self.write_AeroDyn_FAST7() - - self.write_MainInput() - - def write_MainInput(self): - - self.FAST_InputFileOut = os.path.join(self.FAST_runDirectory, self.FAST_namingOut+'.fst') - ofh = open(self.FAST_InputFileOut, 'w') - - # FAST Inputs - ofh.write('---\n') - ofh.write('---\n') - ofh.write('{:}\n'.format(self.fst_vt['description'])) - ofh.write('---\n') - ofh.write('---\n') - ofh.write('{:}\n'.format(self.fst_vt['Fst7']['Echo'])) - ofh.write('{:3}\n'.format(self.fst_vt['Fst7']['ADAMSPrep'])) - ofh.write('{:3}\n'.format(self.fst_vt['Fst7']['AnalMode'])) - ofh.write('{:3}\n'.format(self.fst_vt['Fst7']['NumBl'])) - ofh.write('{:.9f}\n'.format(self.fst_vt['Fst7']['TMax'])) - ofh.write('{:.9f}\n'.format(self.fst_vt['Fst7']['DT'])) - ofh.write('---\n') - ofh.write('{:3}\n'.format(self.fst_vt['Fst7']['YCMode'])) - ofh.write('{:.9f}\n'.format(self.fst_vt['Fst7']['TYCOn'])) - ofh.write('{:3}\n'.format(self.fst_vt['Fst7']['PCMode'])) - ofh.write('{:.9f}\n'.format(self.fst_vt['Fst7']['TPCOn'])) - ofh.write('{:3}\n'.format(self.fst_vt['Fst7']['VSContrl'])) - ofh.write('{:.9f}\n'.format(self.fst_vt['Fst7']['VS_RtGnSp'])) - ofh.write('{:.9f}\n'.format(self.fst_vt['Fst7']['VS_RtTq'])) - ofh.write('{:.9f}\n'.format(self.fst_vt['Fst7']['VS_Rgn2K'])) - ofh.write('{:.5e}\n'.format(self.fst_vt['Fst7']['VS_SlPc'])) - ofh.write('{:3}\n'.format(self.fst_vt['Fst7']['GenModel'])) - ofh.write('{:}\n'.format(self.fst_vt['Fst7']['GenTiStr'])) - ofh.write('{:}\n'.format(self.fst_vt['Fst7']['GenTiStp'])) - ofh.write('{:.9f}\n'.format(self.fst_vt['Fst7']['SpdGenOn'])) - ofh.write('{:.9f}\n'.format(self.fst_vt['Fst7']['TimGenOn'])) - ofh.write('{:.9f}\n'.format(self.fst_vt['Fst7']['TimGenOf'])) - ofh.write('{:3}\n'.format(self.fst_vt['Fst7']['HSSBrMode'])) - ofh.write('{:.9f}\n'.format(self.fst_vt['Fst7']['THSSBrDp'])) - ofh.write('{:.9f}\n'.format(self.fst_vt['Fst7']['TiDynBrk'])) - ofh.write('{:.9f}\n'.format(self.fst_vt['Fst7']['TTpBrDp1'])) - ofh.write('{:.9f}\n'.format(self.fst_vt['Fst7']['TTpBrDp2'])) - ofh.write('{:.9f}\n'.format(self.fst_vt['Fst7']['TTpBrDp3'])) - ofh.write('{:.9f}\n'.format(self.fst_vt['Fst7']['TBDepISp1'])) - ofh.write('{:.9f}\n'.format(self.fst_vt['Fst7']['TBDepISp2'])) - ofh.write('{:.9f}\n'.format(self.fst_vt['Fst7']['TBDepISp3'])) - ofh.write('{:.9f}\n'.format(self.fst_vt['Fst7']['TYawManS'])) - ofh.write('{:.9f}\n'.format(self.fst_vt['Fst7']['TYawManE'])) - ofh.write('{:.9f}\n'.format(self.fst_vt['Fst7']['NacYawF'])) - ofh.write('{:.9f}\n'.format(self.fst_vt['Fst7']['TPitManS1'])) - ofh.write('{:.9f}\n'.format(self.fst_vt['Fst7']['TPitManS2'])) - ofh.write('{:.9f}\n'.format(self.fst_vt['Fst7']['TPitManS3'])) - ofh.write('{:.9f}\n'.format(self.fst_vt['Fst7']['TPitManE1'])) - ofh.write('{:.9f}\n'.format(self.fst_vt['Fst7']['TPitManE2'])) - ofh.write('{:.9f}\n'.format(self.fst_vt['Fst7']['TPitManE3'])) - ofh.write('{:.9f}\n'.format(self.fst_vt['Fst7']['BlPitch1'])) - ofh.write('{:.9f}\n'.format(self.fst_vt['Fst7']['BlPitch2'])) - ofh.write('{:.9f}\n'.format(self.fst_vt['Fst7']['BlPitch3'])) - ofh.write('{:.9f}\n'.format(self.fst_vt['Fst7']['B1PitchF1'])) - ofh.write('{:.9f}\n'.format(self.fst_vt['Fst7']['B1PitchF2'])) - ofh.write('{:.9f}\n'.format(self.fst_vt['Fst7']['B1PitchF3'])) - ofh.write('---\n') - ofh.write('{:.9f}\n'.format(self.fst_vt['Fst7']['Gravity'])) - ofh.write('---\n') - ofh.write('{:}\n'.format(self.fst_vt['Fst7']['FlapDOF1'])) - ofh.write('{:}\n'.format(self.fst_vt['Fst7']['FlapDOF2'])) - ofh.write('{:}\n'.format(self.fst_vt['Fst7']['EdgeDOF'])) - ofh.write('{:}\n'.format(self.fst_vt['Fst7']['TeetDOF'])) - ofh.write('{:}\n'.format(self.fst_vt['Fst7']['DrTrDOF'])) - ofh.write('{:}\n'.format(self.fst_vt['Fst7']['GenDOF'])) - ofh.write('{:}\n'.format(self.fst_vt['Fst7']['YawDOF'])) - ofh.write('{:}\n'.format(self.fst_vt['Fst7']['TwFADOF1'])) - ofh.write('{:}\n'.format(self.fst_vt['Fst7']['TwFADOF2'])) - ofh.write('{:}\n'.format(self.fst_vt['Fst7']['TwSSDOF1'])) - ofh.write('{:}\n'.format(self.fst_vt['Fst7']['TwSSDOF2'])) - ofh.write('{:}\n'.format(self.fst_vt['Fst7']['CompAero'])) - ofh.write('{:}\n'.format(self.fst_vt['Fst7']['CompNoise'])) - ofh.write('---\n') - ofh.write('{:.9f}\n'.format(self.fst_vt['Fst7']['OoPDefl'])) - ofh.write('{:.9f}\n'.format(self.fst_vt['Fst7']['IPDefl'])) - ofh.write('{:.9f}\n'.format(self.fst_vt['Fst7']['TeetDefl'])) - ofh.write('{:.9f}\n'.format(self.fst_vt['Fst7']['Azimuth'])) - ofh.write('{:.9f}\n'.format(self.fst_vt['Fst7']['RotSpeed'])) - ofh.write('{:.9f}\n'.format(self.fst_vt['Fst7']['NacYaw'])) - ofh.write('{:.9f}\n'.format(self.fst_vt['Fst7']['TTDspFA'])) - ofh.write('{:.9f}\n'.format(self.fst_vt['Fst7']['TTDspSS'])) - ofh.write('---\n') - ofh.write('{:.9f}\n'.format(self.fst_vt['Fst7']['TipRad'])) - ofh.write('{:.9f}\n'.format(self.fst_vt['Fst7']['HubRad'])) - ofh.write('{:3}\n'.format(self.fst_vt['Fst7']['PSpnElN'])) - ofh.write('{:.9f}\n'.format(self.fst_vt['Fst7']['UndSling'])) - ofh.write('{:.9f}\n'.format(self.fst_vt['Fst7']['HubCM'])) - ofh.write('{:.9f}\n'.format(self.fst_vt['Fst7']['OverHang'])) - ofh.write('{:.9f}\n'.format(self.fst_vt['Fst7']['NacCMxn'])) - ofh.write('{:.9f}\n'.format(self.fst_vt['Fst7']['NacCMyn'])) - ofh.write('{:.9f}\n'.format(self.fst_vt['Fst7']['NacCMzn'])) - ofh.write('{:.9f}\n'.format(self.fst_vt['Fst7']['TowerHt'])) - ofh.write('{:.9f}\n'.format(self.fst_vt['Fst7']['Twr2Shft'])) - ofh.write('{:.9f}\n'.format(self.fst_vt['Fst7']['TwrRBHt'])) - ofh.write('{:.9f}\n'.format(self.fst_vt['Fst7']['ShftTilt'])) - ofh.write('{:.9f}\n'.format(self.fst_vt['Fst7']['Delta3'])) - ofh.write('{:.9f}\n'.format(self.fst_vt['Fst7']['PreCone(1)'])) - ofh.write('{:.9f}\n'.format(self.fst_vt['Fst7']['PreCone(2)'])) - ofh.write('{:.9f}\n'.format(self.fst_vt['Fst7']['PreCone(3)'])) - ofh.write('{:.9f}\n'.format(self.fst_vt['Fst7']['AzimB1Up'])) - ofh.write('---\n') - ofh.write('{:.9f}\n'.format(self.fst_vt['Fst7']['YawBrMass'])) - ofh.write('{:.9f}\n'.format(self.fst_vt['Fst7']['NacMass'])) - ofh.write('{:.9f}\n'.format(self.fst_vt['Fst7']['HubMass'])) - ofh.write('{:.9f}\n'.format(self.fst_vt['Fst7']['TipMass(1)'])) - ofh.write('{:.9f}\n'.format(self.fst_vt['Fst7']['TipMass(2)'])) - ofh.write('{:.9f}\n'.format(self.fst_vt['Fst7']['TipMass(3)'])) - ofh.write('{:.9f}\n'.format(self.fst_vt['Fst7']['NacYIner'])) - ofh.write('{:.9f}\n'.format(self.fst_vt['Fst7']['GenIner'])) - ofh.write('{:.9f}\n'.format(self.fst_vt['Fst7']['HubIner'])) - ofh.write('---\n') - ofh.write('{:.9f}\n'.format(self.fst_vt['Fst7']['GBoxEff'])) - ofh.write('{:.9f}\n'.format(self.fst_vt['Fst7']['GenEff'])) - ofh.write('{:.9f}\n'.format(self.fst_vt['Fst7']['GBRatio'])) - ofh.write('{:}\n'.format(self.fst_vt['Fst7']['GBRevers'])) - ofh.write('{:.9f}\n'.format(self.fst_vt['Fst7']['HSSBrTqF'])) - ofh.write('{:.9f}\n'.format(self.fst_vt['Fst7']['HSSBrDT'])) - ofh.write('{:}\n'.format(self.fst_vt['Fst7']['DynBrkFi'])) - ofh.write('{:.9f}\n'.format(self.fst_vt['Fst7']['DTTorSpr'])) - ofh.write('{:.9f}\n'.format(self.fst_vt['Fst7']['DTTorDmp'])) - ofh.write('---\n') - ofh.write('{:.9f}\n'.format(self.fst_vt['Fst7']['SIG_SlPc'])) - ofh.write('{:.9f}\n'.format(self.fst_vt['Fst7']['SIG_SySp'])) - ofh.write('{:.9f}\n'.format(self.fst_vt['Fst7']['SIG_RtTq'])) - ofh.write('{:.9f}\n'.format(self.fst_vt['Fst7']['SIG_PORt'])) - ofh.write('---\n') - ofh.write('{:.9f}\n'.format(self.fst_vt['Fst7']['TEC_Freq'])) - ofh.write('{:5}\n'.format(self.fst_vt['Fst7']['TEC_NPol'])) - ofh.write('{:.9f}\n'.format(self.fst_vt['Fst7']['TEC_SRes'])) - ofh.write('{:.9f}\n'.format(self.fst_vt['Fst7']['TEC_RRes'])) - ofh.write('{:.9f}\n'.format(self.fst_vt['Fst7']['TEC_VLL'])) - ofh.write('{:.9f}\n'.format(self.fst_vt['Fst7']['TEC_SLR'])) - ofh.write('{:.9f}\n'.format(self.fst_vt['Fst7']['TEC_RLR'])) - ofh.write('{:.9f}\n'.format(self.fst_vt['Fst7']['TEC_MR'])) - ofh.write('---\n') - ofh.write('{:3}\n'.format(self.fst_vt['Fst7']['PtfmModel'])) - ofh.write('"{:}"\n'.format(self.fst_vt['Fst7']['PtfmFile'])) - ofh.write('---\n') - ofh.write('{:3}\n'.format(self.fst_vt['Fst7']['TwrNodes'])) - ofh.write('"{:}"\n'.format(self.fst_vt['Fst7']['TwrFile'])) - ofh.write('---\n') - ofh.write('{:.9f}\n'.format(self.fst_vt['Fst7']['YawSpr'])) - ofh.write('{:.9f}\n'.format(self.fst_vt['Fst7']['YawDamp'])) - ofh.write('{:.9f}\n'.format(self.fst_vt['Fst7']['YawNeut'])) - ofh.write('---\n') - ofh.write('{:}\n'.format(self.fst_vt['Fst7']['Furling'])) - ofh.write('{:}\n'.format(self.fst_vt['Fst7']['FurlFile'])) - ofh.write('---\n') - ofh.write('{:}\n'.format(self.fst_vt['Fst7']['TeetMod'])) - ofh.write('{:.9f}\n'.format(self.fst_vt['Fst7']['TeetDmpP'])) - ofh.write('{:.9f}\n'.format(self.fst_vt['Fst7']['TeetDmp'])) - ofh.write('{:.9f}\n'.format(self.fst_vt['Fst7']['TeetCDmp'])) - ofh.write('{:.9f}\n'.format(self.fst_vt['Fst7']['TeetSStP'])) - ofh.write('{:.9f}\n'.format(self.fst_vt['Fst7']['TeetHStP'])) - ofh.write('{:.9f}\n'.format(self.fst_vt['Fst7']['TeetSSSp'])) - ofh.write('{:.9f}\n'.format(self.fst_vt['Fst7']['TeetHSSp'])) - ofh.write('---\n') - ofh.write('{:.9f}\n'.format(self.fst_vt['Fst7']['TBDrConN'])) - ofh.write('{:.9f}\n'.format(self.fst_vt['Fst7']['TBDrConD'])) - ofh.write('{:.9f}\n'.format(self.fst_vt['Fst7']['TpBrDT'])) - ofh.write('---\n') - ofh.write('"{:}"\n'.format(self.fst_vt['Fst7']['BldFile1'])) - ofh.write('"{:}"\n'.format(self.fst_vt['Fst7']['BldFile2'])) - ofh.write('"{:}"\n'.format(self.fst_vt['Fst7']['BldFile3'])) - ofh.write('---\n') - ofh.write('"{:}"\n'.format(self.fst_vt['Fst7']['ADFile'])) - ofh.write('---\n') - ofh.write('{:}\n'.format(self.fst_vt['Fst7']['NoiseFile'])) - ofh.write('---\n') - ofh.write('{:}\n'.format(self.fst_vt['Fst7']['ADAMSFile'])) - ofh.write('---\n') - ofh.write('{:}\n'.format(self.fst_vt['Fst7']['LinFile'])) - ofh.write('---\n') - ofh.write('{:}\n'.format(self.fst_vt['Fst7']['SumPrint'])) - ofh.write('{:}\n'.format(self.fst_vt['Fst7']['OutFileFmt'])) - ofh.write('{:}\n'.format(self.fst_vt['Fst7']['TabDelim'])) - ofh.write('{:}\n'.format(self.fst_vt['Fst7']['OutFmt'])) - ofh.write('{:.9f}\n'.format(self.fst_vt['Fst7']['TStart'])) - ofh.write('{:3}\n'.format(self.fst_vt['Fst7']['DecFact'])) - ofh.write('{:.9f}\n'.format(self.fst_vt['Fst7']['SttsTime'])) - ofh.write('{:.9f}\n'.format(self.fst_vt['Fst7']['NcIMUxn'])) - ofh.write('{:.9f}\n'.format(self.fst_vt['Fst7']['NcIMUyn'])) - ofh.write('{:.9f}\n'.format(self.fst_vt['Fst7']['NcIMUzn'])) - ofh.write('{:.9f}\n'.format(self.fst_vt['Fst7']['ShftGagL'])) - ofh.write('{:3}\n'.format(self.fst_vt['Fst7']['NTwGages'])) - for i in range(self.fst_vt['Fst7']['NTwGages']-1): - ofh.write('{:3}, '.format(self.fst_vt['Fst7']['TwrGagNd'][i])) - ofh.write('{:3}\n'.format(self.fst_vt['Fst7']['TwrGagNd'][-1])) - ofh.write('{:3}\n'.format(self.fst_vt['Fst7']['NBlGages'])) - for i in range(self.fst_vt['Fst7']['NBlGages']-1): - ofh.write('{:3}, '.format(self.fst_vt['Fst7']['BldGagNd'][i])) - ofh.write('{:3}\n'.format(self.fst_vt['Fst7']['BldGagNd'][-1])) - - # Outlist - ofh.write('Outlist\n') - outlist = self.get_outlist(self.fst_vt['outlist7'], ['OutList']) - for channel_list in outlist: - for i in range(len(channel_list)): - f.write('"' + channel_list[i] + '"\n') - ofh.write('END\n') - ofh.close() - ofh.close() - - def write_AeroDyn_FAST7(self): - if not os.path.isdir(os.path.join(self.FAST_runDirectory,'AeroData')): - os.mkdir(os.path.join(self.FAST_runDirectory,'AeroData')) + def write_StC(self,StC_vt,StC_filename): - # create airfoil objects - for i in range(self.fst_vt['AeroDyn14']['NumFoil']): - af_name = os.path.join(self.FAST_runDirectory, 'AeroData', 'Airfoil' + str(i) + '.dat') - self.fst_vt['AeroDyn14']['FoilNm'][i] = os.path.join('AeroData', 'Airfoil' + str(i) + '.dat') - self.write_AeroDyn14Polar(af_name, i) - - self.fst_vt['Fst7']['ADFile'] = self.FAST_namingOut + '_AeroDyn.dat' - ad_file = os.path.join(self.FAST_runDirectory,self.fst_vt['Fst7']['ADFile']) - ofh = open(ad_file,'w') + stc_file = os.path.join(self.FAST_runDirectory, StC_filename) + f = open(stc_file, 'w') - ofh.write('Aerodyn input file for FAST\n') + f.write('------- STRUCTURAL CONTROL (StC) INPUT FILE ----------------------------\n') + f.write('Generated with AeroElasticSE FAST driver within WEIS\n') - ofh.write('{:}\n'.format(self.fst_vt['AeroDyn14']['SysUnits'])) - ofh.write('{:}\n'.format(self.fst_vt['AeroDyn14']['StallMod'])) + f.write('---------------------- SIMULATION CONTROL --------------------------------------\n') + f.write('{!s:<22} {:<11} {:}'.format(StC_vt['Echo'], 'Echo', '- Echo input data to ".SD.ech" (flag)\n')) - ofh.write('{:}\n'.format(self.fst_vt['AeroDyn14']['UseCm'])) - ofh.write('{:}\n'.format(self.fst_vt['AeroDyn14']['InfModel'])) - ofh.write('{:}\n'.format(self.fst_vt['AeroDyn14']['IndModel'])) - ofh.write('{:.3f}\n'.format(self.fst_vt['AeroDyn14']['AToler'])) - ofh.write('{:}\n'.format(self.fst_vt['AeroDyn14']['TLModel'])) - ofh.write('{:}\n'.format(self.fst_vt['AeroDyn14']['HLModel'])) - ofh.write('"{:}"\n'.format(self.fst_vt['AeroDyn14']['WindFile'])) - ofh.write('{:f}\n'.format(self.fst_vt['AeroDyn14']['HH'])) - - ofh.write('{:.1f}\n'.format(self.fst_vt['AeroDyn14']['TwrShad'])) - - ofh.write('{:.1f}\n'.format(self.fst_vt['AeroDyn14']['ShadHWid'])) - - ofh.write('{:.1f}\n'.format(self.fst_vt['AeroDyn14']['T_Shad_Refpt'])) - - ofh.write('{:.3f}\n'.format(self.fst_vt['AeroDyn14']['AirDens'])) - - ofh.write('{:.9f}\n'.format(self.fst_vt['AeroDyn14']['KinVisc'])) - - ofh.write('{:2}\n'.format(self.fst_vt['AeroDyn14']['DTAero'])) + f.write('---------------------- StC DEGREES OF FREEDOM ----------------------------------\n') + f.write('{:<22} {:<11} {:}'.format(StC_vt['StC_DOF_MODE'], 'StC_DOF_MODE', '- DOF mode (switch) {0: No StC or TLCD DOF; 1: StC_X_DOF, StC_Y_DOF, and/or StC_Z_DOF (three independent StC DOFs); 2: StC_XY_DOF (Omni-Directional StC); 3: TLCD; 4: Prescribed force/moment time series}\n')) + f.write('{!s:<22} {:<11} {:}'.format(StC_vt['StC_X_DOF'], 'StC_X_DOF', '- DOF on or off for StC X (flag) [Used only when StC_DOF_MODE=1]\n')) + f.write('{!s:<22} {:<11} {:}'.format(StC_vt['StC_Y_DOF'], 'StC_Y_DOF', '- DOF on or off for StC Y (flag) [Used only when StC_DOF_MODE=1]\n')) + f.write('{!s:<22} {:<11} {:}'.format(StC_vt['StC_Z_DOF'], 'StC_Z_DOF', '- DOF on or off for StC Z (flag) [Used only when StC_DOF_MODE=1]\n')) + f.write('---------------------- StC LOCATION ------------------------------------------- [relative to the reference origin of component attached to]\n') + f.write('{:<22} {:<11} {:}'.format(StC_vt['StC_P_X'], 'StC_P_X', '- At rest X position of StC (m)\n')) + f.write('{:<22} {:<11} {:}'.format(StC_vt['StC_P_Y'], 'StC_P_Y', '- At rest Y position of StC (m)\n')) + f.write('{:<22} {:<11} {:}'.format(StC_vt['StC_P_Z'], 'StC_P_Z', '- At rest Z position of StC (m)\n')) + + f.write('---------------------- StC INITIAL CONDITIONS --------------------------------- [used only when StC_DOF_MODE=1 or 2]\n') + f.write('{:<22} {:<11} {:}'.format(StC_vt['StC_X_DSP'], 'StC_X_DSP', '- StC X initial displacement (m) [relative to at rest position]\n')) + f.write('{:<22} {:<11} {:}'.format(StC_vt['StC_Y_DSP'], 'StC_Y_DSP', '- StC Y initial displacement (m) [relative to at rest position]\n')) + f.write('{:<22} {:<11} {:}'.format(StC_vt['StC_Z_DSP'], 'StC_Z_DSP', '- StC Z initial displacement (m) [relative to at rest position; used only when StC_DOF_MODE=1 and StC_Z_DOF=TRUE]\n')) + f.write('{!s:<22} {:<11} {:}'.format(StC_vt['StC_Z_PreLd'], 'StC_Z_PreLd', '- StC Z pre-load (N) {"gravity" to offset for gravity load; "none" or 0 to turn off} [used only when StC_DOF_MODE=1 and StC_Z_DOF=TRUE]\n')) + + f.write('---------------------- StC CONFIGURATION -------------------------------------- [used only when StC_DOF_MODE=1 or 2]\n') + f.write('{:<22} {:<11} {:}'.format(StC_vt['StC_X_PSP'], 'StC_X_PSP', '- Positive stop position (maximum X mass displacement) (m)\n')) + f.write('{:<22} {:<11} {:}'.format(StC_vt['StC_X_NSP'], 'StC_X_NSP', '- Negative stop position (minimum X mass displacement) (m)\n')) + f.write('{:<22} {:<11} {:}'.format(StC_vt['StC_Y_PSP'], 'StC_Y_PSP', '- Positive stop position (maximum Y mass displacement) (m)\n')) + f.write('{:<22} {:<11} {:}'.format(StC_vt['StC_Y_NSP'], 'StC_Y_NSP', '- Negative stop position (minimum Y mass displacement) (m)\n')) + f.write('{:<22} {:<11} {:}'.format(StC_vt['StC_Z_PSP'], 'StC_Z_PSP', '- Positive stop position (maximum Z mass displacement) (m) [used only when StC_DOF_MODE=1 and StC_Z_DOF=TRUE]\n')) + f.write('{:<22} {:<11} {:}'.format(StC_vt['StC_Z_NSP'], 'StC_Z_NSP', '- Negative stop position (minimum Z mass displacement) (m) [used only when StC_DOF_MODE=1 and StC_Z_DOF=TRUE]\n')) + + f.write('---------------------- StC MASS, STIFFNESS, & DAMPING ------------------------- [used only when StC_DOF_MODE=1 or 2]\n') + f.write('{:<22} {:<11} {:}'.format(StC_vt['StC_X_M'], 'StC_X_M', '- StC X mass (kg) [must equal StC_Y_M for StC_DOF_MODE = 2]\n')) + f.write('{:<22} {:<11} {:}'.format(StC_vt['StC_Y_M'], 'StC_Y_M', '- StC Y mass (kg) [must equal StC_X_M for StC_DOF_MODE = 2]\n')) + f.write('{:<22} {:<11} {:}'.format(StC_vt['StC_Z_M'], 'StC_Z_M', '- StC Z mass (kg) [used only when StC_DOF_MODE=1 and StC_Z_DOF=TRUE]\n')) + f.write('{:<22} {:<11} {:}'.format(StC_vt['StC_XY_M'], 'StC_XY_M', '- StC Z mass (kg) [used only when StC_DOF_MODE=2]\n')) + f.write('{:<22} {:<11} {:}'.format(StC_vt['StC_X_K'], 'StC_X_K', '- StC X stiffness (N/m)\n')) + f.write('{:<22} {:<11} {:}'.format(StC_vt['StC_Y_K'], 'StC_Y_K', '- StC Y stiffness (N/m)\n')) + f.write('{:<22} {:<11} {:}'.format(StC_vt['StC_Z_K'], 'StC_Z_K', '- StC Z stiffness (N/m) [used only when StC_DOF_MODE=1 and StC_Z_DOF=TRUE]\n')) + f.write('{:<22} {:<11} {:}'.format(StC_vt['StC_X_C'], 'StC_X_C', '- StC X damping (N/(m/s))\n')) + f.write('{:<22} {:<11} {:}'.format(StC_vt['StC_Y_C'], 'StC_Y_C', '- StC Y damping (N/(m/s))\n')) + f.write('{:<22} {:<11} {:}'.format(StC_vt['StC_Z_C'], 'StC_Z_C', '- StC Z damping (N/(m/s)) [used only when StC_DOF_MODE=1 and StC_Z_DOF=TRUE]\n')) + f.write('{:<22} {:<11} {:}'.format(StC_vt['StC_X_KS'], 'StC_X_KS', '- Stop spring X stiffness (N/m)\n')) + f.write('{:<22} {:<11} {:}'.format(StC_vt['StC_Y_KS'], 'StC_Y_KS', '- Stop spring Y stiffness (N/m)\n')) + f.write('{:<22} {:<11} {:}'.format(StC_vt['StC_Z_KS'], 'StC_Z_KS', '- Stop spring Z stiffness (N/m) [used only when StC_DOF_MODE=1 and StC_Z_DOF=TRUE]\n')) + f.write('{:<22} {:<11} {:}'.format(StC_vt['StC_X_CS'], 'StC_X_CS', '- Stop spring X damping (N/(m/s))\n')) + f.write('{:<22} {:<11} {:}'.format(StC_vt['StC_Y_CS'], 'StC_Y_CS', '- Stop spring Y damping (N/(m/s))\n')) + f.write('{:<22} {:<11} {:}'.format(StC_vt['StC_Z_CS'], 'StC_Z_CS', '- Stop spring Z damping (N/(m/s)) [used only when StC_DOF_MODE=1 and StC_Z_DOF=TRUE]\n')) + + f.write('---------------------- StC USER-DEFINED SPRING FORCES ------------------------- [used only when StC_DOF_MODE=1 or 2]\n') + f.write('{!s:<22} {:<11} {:}'.format(StC_vt['Use_F_TBL'], 'Use_F_TBL', '- Use spring force from user-defined table (flag)\n')) + f.write('{:<22} {:<11} {:}'.format(StC_vt['NKInpSt'], 'NKInpSt', '- Number of spring force input stations\n')) + + f.write('---------------------- StC SPRING FORCES TABLE -------------------------------- [used only when StC_DOF_MODE=1 or 2]\n') + f.write('X F_X Y F_Y Z F_Z\n') + f.write('(m) (N) (m) (N) (m) (N)\n') + table = StC_vt['SpringForceTable'] + for x, f_x, y, f_y, z, f_z in zip(table['X'],table['F_X'],table['Y'],table['F_Y'],table['Z'],table['F_Z']): + row = [x, f_x, y, f_y, z, f_z] + f.write(' '.join(['{: 2.8e}'.format(val) for val in row])+'\n') + + f.write('---------------------- StructCtrl CONTROL -------------------------------------------- [used only when StC_DOF_MODE=1 or 2]\n') + f.write('{:<22} {:<11} {:}'.format(StC_vt['StC_CMODE'], 'StC_CMODE', '- Control mode (switch) {0:none; 1: Semi-Active Control Mode; 2: Active Control Mode}\n')) + f.write('{:<22} {:<11} {:}'.format(StC_vt['StC_CChan'], 'StC_CChan', '- Control channel group (1:10) for stiffness and damping (StC_[XYZ]_K, StC_[XYZ]_C, and StC_[XYZ]_Brake) (specify additional channels for blade instances of StC active control -- one channel per blade) [used only when StC_DOF_MODE=1 or 2, and StC_CMODE=4 or 5]\n')) + f.write('{:<22} {:<11} {:}'.format(StC_vt['StC_SA_MODE'], 'StC_SA_MODE', '- Semi-Active control mode {1: velocity-based ground hook control; 2: Inverse velocity-based ground hook control; 3: displacement-based ground hook control 4: Phase difference Algorithm with Friction Force 5: Phase difference Algorithm with Damping Force} (-)\n')) + f.write('{:<22} {:<11} {:}'.format(StC_vt['StC_X_C_HIGH'], 'StC_X_C_HIGH', '- StC X high damping for ground hook control\n')) + f.write('{:<22} {:<11} {:}'.format(StC_vt['StC_X_C_LOW'], 'StC_X_C_LOW', '- StC X low damping for ground hook control\n')) + f.write('{:<22} {:<11} {:}'.format(StC_vt['StC_Y_C_HIGH'], 'StC_Y_C_HIGH', '- StC Y high damping for ground hook control\n')) + f.write('{:<22} {:<11} {:}'.format(StC_vt['StC_Y_C_LOW'], 'StC_Y_C_LOW', '- StC Y low damping for ground hook control\n')) + f.write('{:<22} {:<11} {:}'.format(StC_vt['StC_Z_C_HIGH'], 'StC_Z_C_HIGH', '- StC Z high damping for ground hook control [used only when StC_DOF_MODE=1 and StC_Z_DOF=TRUE]\n')) + f.write('{:<22} {:<11} {:}'.format(StC_vt['StC_Z_C_LOW'], 'StC_Z_C_LOW', '- StC Z low damping for ground hook control [used only when StC_DOF_MODE=1 and StC_Z_DOF=TRUE]\n')) + f.write('{:<22} {:<11} {:}'.format(StC_vt['StC_X_C_BRAKE'], 'StC_X_C_BRAKE', '- StC X high damping for braking the StC (Don''t use it now. should be zero)\n')) + f.write('{:<22} {:<11} {:}'.format(StC_vt['StC_Y_C_BRAKE'], 'StC_Y_C_BRAKE', '- StC Y high damping for braking the StC (Don''t use it now. should be zero)\n')) + f.write('{:<22} {:<11} {:}'.format(StC_vt['StC_Z_C_BRAKE'], 'StC_Z_C_BRAKE', '- StC Z high damping for braking the StC (Don''t use it now. should be zero) [used only when StC_DOF_MODE=1 and StC_Z_DOF=TRUE]\n')) + + f.write('---------------------- TLCD --------------------------------------------------- [used only when StC_DOF_MODE=3]\n') + f.write('{:<22} {:<11} {:}'.format(StC_vt['L_X'], 'L_X', '- X TLCD total length (m)\n')) + f.write('{:<22} {:<11} {:}'.format(StC_vt['B_X'], 'B_X', '- X TLCD horizontal length (m)\n')) + f.write('{:<22} {:<11} {:}'.format(StC_vt['area_X'], 'area_X', '- X TLCD cross-sectional area of vertical column (m^2)\n')) + f.write('{:<22} {:<11} {:}'.format(StC_vt['area_ratio_X'], 'area_ratio_X', '- X TLCD cross-sectional area ratio (vertical column area divided by horizontal column area) (-)\n')) + f.write('{:<22} {:<11} {:}'.format(StC_vt['headLossCoeff_X'], 'headLossCoeff_X', '- X TLCD head loss coeff (-)\n')) + f.write('{:<22} {:<11} {:}'.format(StC_vt['rho_X'], 'rho_X', '- X TLCD liquid density (kg/m^3)\n')) + f.write('{:<22} {:<11} {:}'.format(StC_vt['L_Y'], 'L_Y', '- Y TLCD total length (m)\n')) + f.write('{:<22} {:<11} {:}'.format(StC_vt['B_Y'], 'B_Y', '- Y TLCD horizontal length (m)\n')) + f.write('{:<22} {:<11} {:}'.format(StC_vt['area_Y'], 'area_Y', '- Y TLCD cross-sectional area of vertical column (m^2)\n')) + f.write('{:<22} {:<11} {:}'.format(StC_vt['area_ratio_Y'], 'area_ratio_Y', '- Y TLCD cross-sectional area ratio (vertical column area divided by horizontal column area) (-)\n')) + f.write('{:<22} {:<11} {:}'.format(StC_vt['headLossCoeff_Y'], 'headLossCoeff_Y', '- Y TLCD head loss coeff (-)\n')) + f.write('{:<22} {:<11} {:}'.format(StC_vt['rho_Y'], 'rho_Y', '- Y TLCD liquid density (kg/m^3)\n')) + + f.write('---------------------- PRESCRIBED TIME SERIES --------------------------------- [used only when StC_DOF_MODE=4]\n') + f.write('{:<22} {:<11} {:}'.format(StC_vt['PrescribedForcesCoord'], 'PrescribedForcesCoord', '- Prescribed forces are in global or local coordinates (switch) {1: global; 2: local}\n')) + f.write('{!s:<22} {:<11} {:}'.format(StC_vt['PrescribedForcesFile'], 'PrescribedForcesFile', '- Time series force and moment (7 columns of time, FX, FY, FZ, MX, MY, MZ)\n')) + f.write('-------------------------------------------------------------------------------\n') - ofh.write('{:2}\n'.format(self.fst_vt['AeroDyn14']['NumFoil'])) - for i in range (self.fst_vt['AeroDyn14']['NumFoil']): - ofh.write('"{:}"\n'.format(self.fst_vt['AeroDyn14']['FoilNm'][i])) - - ofh.write('{:2}\n'.format(self.fst_vt['AeroDynBlade']['BldNodes'])) - rnodes = self.fst_vt['AeroDynBlade']['RNodes'] - twist = self.fst_vt['AeroDynBlade']['AeroTwst'] - drnodes = self.fst_vt['AeroDynBlade']['DRNodes'] - chord = self.fst_vt['AeroDynBlade']['Chord'] - nfoil = self.fst_vt['AeroDynBlade']['NFoil'] - prnelm = self.fst_vt['AeroDynBlade']['PrnElm'] - ofh.write('Nodal properties\n') - for r, t, dr, c, a, p in zip(rnodes, twist, drnodes, chord, nfoil, prnelm): - ofh.write('{: 2.15e}\t{:.3f}\t{:.4f}\t{:.3f}\t{:5}\t{:}\n'.format(r, t, dr, c, a, p)) - - ofh.close() - - + f.close() if __name__=="__main__": - FAST_ver = 'openfast' - read_yaml = False - fst_update = {} fst_update['Fst', 'TMax'] = 20. fst_update['AeroDyn15', 'TwrAero'] = False + examples_dir = os.path.dirname( os.path.dirname( os.path.dirname( os.path.realpath(__file__) ) ) ) + os.sep - if read_yaml: - fast = InputReader_Common(FAST_ver=FAST_ver) - fast.FAST_yamlfile = 'temp/OpenFAST/test.yaml' - fast.read_yaml() - - if FAST_ver.lower() == 'fast7': - if not read_yaml: - fast = InputReader_FAST7(FAST_ver=FAST_ver) - fast.FAST_InputFile = 'Test16.fst' # FAST input file (ext=.fst) - fast.FAST_directory = 'C:/Users/egaertne/WT_Codes/models/FAST_v7.02.00d-bjj/CertTest/' # Path to fst directory files - fast.execute() - - fastout = InputWriter_FAST7(FAST_ver=FAST_ver) - fastout.fst_vt = fast.fst_vt - fastout.FAST_runDirectory = 'temp/FAST7' - fastout.FAST_namingOut = 'test' - fastout.execute() - - elif FAST_ver.lower() == 'fast8': - if not read_yaml: - fast = InputReader_OpenFAST(FAST_ver=FAST_ver) - fast.FAST_InputFile = 'NREL5MW_onshore.fst' # FAST input file (ext=.fst) - fast.FAST_directory = 'C:/Users/egaertne/WT_Codes/models/FAST_v8.16.00a-bjj/ref/5mw_onshore/' # Path to fst directory files - fast.execute() - - fastout = InputWriter_OpenFAST(FAST_ver=FAST_ver) - fastout.fst_vt = fast.fst_vt - fastout.FAST_runDirectory = 'temp/FAST8' - fastout.FAST_namingOut = 'test' - fastout.execute() - - elif FAST_ver.lower() == 'openfast': - if not read_yaml: - fast = InputReader_OpenFAST(FAST_ver=FAST_ver) - # fast.FAST_InputFile = '5MW_Land_DLL_WTurb.fst' # FAST input file (ext=.fst) - # fast.FAST_directory = 'C:/Users/egaertne/WT_Codes/models/openfast/glue-codes/fast/5MW_Land_DLL_WTurb' # Path to fst directory files - - # fast.FAST_InputFile = "5MW_OC4Jckt_DLL_WTurb_WavesIrr_MGrowth.fst" - # fast.FAST_directory = 'C:/Users/egaertne/WT_Codes/models/openfast-dev/r-test/glue-codes/openfast/5MW_OC4Jckt_DLL_WTurb_WavesIrr_MGrowth' - - fast.FAST_InputFile = '5MW_OC3Spar_DLL_WTurb_WavesIrr.fst' # FAST input file (ext=.fst) - fast.FAST_directory = 'C:/Users/egaertne/WT_Codes/models/openfast-dev/r-test/glue-codes/openfast/5MW_OC3Spar_DLL_WTurb_WavesIrr' # Path to fst directory files - - fast.execute() - - fastout = InputWriter_OpenFAST(FAST_ver=FAST_ver) - fastout.fst_vt = fast.fst_vt - fastout.FAST_runDirectory = 'temp/OpenFAST' - fastout.FAST_namingOut = 'test' - fastout.update(fst_update=fst_update) - fastout.execute() + # Read the model + fast = InputReader_OpenFAST() + fast.FAST_InputFile = 'IEA-15-240-RWT-UMaineSemi.fst' # FAST input file (ext=.fst) + fast.FAST_directory = os.path.join(examples_dir, 'examples', '01_aeroelasticse', + 'OpenFAST_models', 'IEA-15-240-RWT', + 'IEA-15-240-RWT-UMaineSemi') # Path to fst directory files + fast.execute() - fastout.write_yaml() + # Write out the model + fastout = InputWriter_OpenFAST() + fastout.fst_vt = fast.fst_vt + fastout.FAST_runDirectory = 'temp/OpenFAST' + fastout.FAST_namingOut = 'iea15' + fastout.update(fst_update=fst_update) + fastout.execute() + + # import pickle + # with open('fst_vt.pkl','rb') as f: + # fst_vt = pickle.load(f) + + # fastout = InputWriter_OpenFAST() + # fastout.FAST_runDirectory = 'none' + + # fst_vt['TStC'][0]['NKInpSt'] = 2 + + # for i_TStC, TStC in enumerate(fst_vt['TStC']): + # fastout.write_StC(TStC,fst_vt['ServoDyn']['TStCfiles'][i_TStC]) + # print('here') diff --git a/ROSCO_toolbox/tune.py b/ROSCO_toolbox/tune.py index d5f94a25..e4d5392c 100644 --- a/ROSCO_toolbox/tune.py +++ b/ROSCO_toolbox/tune.py @@ -35,7 +35,6 @@ def yaml_to_objs(tuning_yaml): turbine.load_from_fast( path_params['FAST_InputFile'], os.path.join(yaml_dir,path_params['FAST_directory']), - dev_branch=True, rot_source='txt', txt_filename=os.path.join(yaml_dir,path_params['FAST_directory'],path_params['rotor_performance_filename']) ) diff --git a/ROSCO_toolbox/turbine.py b/ROSCO_toolbox/turbine.py index 0d965abc..9aa61932 100644 --- a/ROSCO_toolbox/turbine.py +++ b/ROSCO_toolbox/turbine.py @@ -130,7 +130,13 @@ def load(filename): return turbine # Load data from fast input deck - def load_from_fast(self, FAST_InputFile,FAST_directory, FAST_ver='OpenFAST',dev_branch=True,rot_source=None, txt_filename=None): + def load_from_fast( + self, + FAST_InputFile, + FAST_directory, + rot_source=None, + txt_filename=None + ): """ Load the parameter files directly from a FAST input deck @@ -140,10 +146,6 @@ def load_from_fast(self, FAST_InputFile,FAST_directory, FAST_ver='OpenFAST',dev_ Primary fast model input file (*.fst) FAST_directory: str Directory for primary fast model input file - FAST_ver: string, optional - fast version, usually OpenFAST - dev_branch: bool, optional - dev_branch input to InputReader_OpenFAST, probably True rot_source: str, optional desired source for rotor to get Cp, Ct, Cq tables. Default is to run cc-blade. options: cc-blade - run cc-blade @@ -165,9 +167,14 @@ def load_from_fast(self, FAST_InputFile,FAST_directory, FAST_ver='OpenFAST',dev_ fast.FAST_directory = FAST_directory fast.read_MainInput() - fast.read_ElastoDyn() - + # file + ed_file = os.path.join(fast.FAST_directory, fast.fst_vt['Fst']['EDFile']) + + fast.read_ElastoDyn(ed_file) + ed_blade_file = os.path.join(os.path.dirname(ed_file), fast.fst_vt['ElastoDyn']['BldFile1']) + fast.read_ElastoDynBlade(ed_blade_file) + fast.read_AeroDyn15() fast.read_ServoDyn() @@ -175,7 +182,8 @@ def load_from_fast(self, FAST_InputFile,FAST_directory, FAST_ver='OpenFAST',dev_ if fast.fst_vt['Fst']['CompHydro'] == 1: # SubDyn not yet implimented - fast.read_HydroDyn() + hd_file = os.path.normpath(os.path.join(fast.FAST_directory, fast.fst_vt['Fst']['HydroFile'])) + fast.read_HydroDyn(hd_file) # fast.read_AeroDyn15() # fast.execute() @@ -434,7 +442,7 @@ def generate_rotperf_fast(self, openfast_path, FAST_runDirectory=None, run_BeamD "GenPwr", "GenTq", # AeroDyn15 "RtArea", "RtVAvgxh", "B1N3Clrnc", "B2N3Clrnc", "B3N3Clrnc", - "RtAeroCp", 'RtAeroCq', 'RtAeroCt', 'RtTSR', # NECESSARY + "RtFldCp", 'RtFldCq', 'RtFldCt', 'RtTSR', # NECESSARY # InflowWind "Wind1VelX", ] diff --git a/Test_Cases/BAR_10/BAR_10_AeroDyn15.dat b/Test_Cases/BAR_10/BAR_10_AeroDyn15.dat index 201d9e6d..9f32b605 100644 --- a/Test_Cases/BAR_10/BAR_10_AeroDyn15.dat +++ b/Test_Cases/BAR_10/BAR_10_AeroDyn15.dat @@ -10,6 +10,7 @@ False Echo - Echo the input to ".AD.ech"? (fl True TwrAero - Calculate tower aerodynamic loads? (flag) False FrozenWake - Assume frozen wake during linearization? (flag) [used only when WakeMod=1 and when linearizing] False CavitCheck - Perform cavitation check? (flag) TRUE will turn off unsteady aerodynamics +False Buoyancy - Include buoyancy effects? (flag) False CompAA Flag to compute AeroAcoustics calculation [only used when WakeMod=1 or 2] "AeroAcousticsInput.dat" AA_InputFile - Aeroacoustics input file ====== Environmental Conditions =================================================================== @@ -34,10 +35,8 @@ True TIDrag - Include the drag term in the tangential-ind ====== OLAF -- cOnvecting LAgrangian Filaments (Free Vortex Wake) Theory Options ================== [used only when WakeMod=3] "unused" OLAFInputFileName - Input file for OLAF [used only when WakeMod=3] ====== Beddoes-Leishman Unsteady Airfoil Aerodynamics Options ===================================== [used only when AFAeroMod=2] -3 UAMod Unsteady Aero Model Switch (switch) {1=Baseline model (Original), 2=Gonzalez's variant (changes in Cn,Cc,Cm), 3=Minemma/Pierce variant (changes in Cc and Cm)} [used only when AFAeroMod=2] -True FLookup Flag to indicate whether a lookup for f' will be calculated (TRUE) or whether best-fit exponential equations will be used (FALSE); if FALSE S1-S4 must be provided in airfoil input files (flag) [used only when AFAeroMod=2] -0.0 UAStartRad - Starting radius for dynamic stall (fraction of rotor radius) [used only when AFAeroMod=2] -1.0 UAEndRad - Ending radius for dynamic stall (fraction of rotor radius) [used only when AFAeroMod=2] +3 UAMod - Unsteady Aero Model Switch (switch) {1=Baseline model (Original), 2=Gonzalez's variant (changes in Cn,Cc,Cm), 3=Minnema/Pierce variant (changes in Cc and Cm)} [used only when AFAeroMod=2] +True FLookup - Flag to indicate whether a lookup for f' will be calculated (TRUE) or whether best-fit exponential equations will be used (FALSE); if FALSE S1-S4 must be provided in airfoil input files (flag) [used only when AFAeroMod=2] ====== Airfoil Information ========================================================================= 3 AFTabMod - Interpolation method for multiple airfoil tables {1=1D interpolation on AoA (first table only); 2=2D interpolation on AoA and Re; 3=2D interpolation on AoA and UserProp} (-) 1 InCol_Alfa - The column in the airfoil tables that contains the angle of attack (-) @@ -81,19 +80,28 @@ True UseBlCm - Include aerodynamic pitching moment in calc "BAR_10_AeroDyn15_blade.dat" ADBlFile(1) - Name of file containing distributed aerodynamic properties for Blade #1 (-) "BAR_10_AeroDyn15_blade.dat" ADBlFile(2) - Name of file containing distributed aerodynamic properties for Blade #2 (-) [unused if NumBl < 2] "BAR_10_AeroDyn15_blade.dat" ADBlFile(3) - Name of file containing distributed aerodynamic properties for Blade #3 (-) [unused if NumBl < 3] +====== Hub Properties ============================================================================== [used only when Buoyancy=True] +0.0 VolHub - Hub volume (m^3) +0.0 HubCenBx - Hub center of buoyancy x direction offset (m) +====== Nacelle Properties ========================================================================== [used only when Buoyancy=True] +0.0 VolNac - Nacelle volume (m^3) +0,0,0 NacCenB - Position of nacelle center of buoyancy from yaw bearing in nacelle coordinates (m) +====== Tail fin Aerodynamics ======================================================================== +False TFinAero - Calculate tail fin aerodynamics model (flag) +"unused" TFinFile - Input file for tail fin aerodynamics [used only when TFinAero=True] ====== Tower Influence and Aerodynamics ============================================================= [used only when TwrPotent/=0, TwrShadow=True, or TwrAero=True] 9 NumTwrNds - Number of tower nodes used in the analysis (-) [used only when TwrPotent/=0, TwrShadow=True, or TwrAero=True] -TwrElev TwrDiam TwrCd TwrTI (used only with TwrShadow=2) -(m) (m) (-) (-) - 2.740000000000000e+01 6.000000000000000e+00 1.000000000000000e+00 1.0e-1 - 4.110000000000000e+01 6.000000000000000e+00 1.000000000000000e+00 1.0e-1 - 5.480000000000000e+01 6.000000000000000e+00 1.000000000000000e+00 1.0e-1 - 6.850000000000000e+01 6.000000000000000e+00 1.000000000000000e+00 1.0e-1 - 8.220000000000000e+01 6.000000000000000e+00 1.000000000000000e+00 1.0e-1 - 9.590000000000001e+01 6.000000000000000e+00 1.000000000000000e+00 1.0e-1 - 1.096000000000000e+02 6.000000000000000e+00 1.000000000000000e+00 1.0e-1 - 1.233000000000000e+02 5.890792130000000e+00 1.000000000000000e+00 1.0e-1 - 1.370000000000000e+02 5.530325920000000e+00 1.000000000000000e+00 1.0e-1 +TwrElev TwrDiam TwrCd TwrTI TwrCb !TwrTI used only with TwrShadow=2, TwrCb used only with Buoyancy=True +(m) (m) (-) (-) (-) + 2.740e+01 6.00000e+00 1.0e+00 1.0e-1 0.0 + 4.110e+01 6.00000e+00 1.0e+00 1.0e-1 0.0 + 5.480e+01 6.00000e+00 1.0e+00 1.0e-1 0.0 + 6.850e+01 6.00000e+00 1.0e+00 1.0e-1 0.0 + 8.220e+01 6.00000e+00 1.0e+00 1.0e-1 0.0 + 9.590e+01 6.00000e+00 1.0e+00 1.0e-1 0.0 + 1.096e+02 6.00000e+00 1.0e+00 1.0e-1 0.0 + 1.233e+02 5.89079e+00 1.0e+00 1.0e-1 0.0 + 1.370e+02 5.53032e+00 1.0e+00 1.0e-1 0.0 ====== Tower Influence and Aerodynamics ============================================================= [used only when TwrPotent/=0, TwrShadow=True, or TwrAero=True] True SumPrint - Generate a summary file listing input options and interpolated properties to ".AD.sum"? (flag) 9 NBlOuts - Number of blade node outputs [0 - 9] (-) @@ -101,18 +109,16 @@ True SumPrint - Generate a summary file listing input optio 0 NTwOuts - Number of tower node outputs [0 - 9] (-) 1, 2, 6 TwOutNd - Tower nodes whose values will be output (-) OutList - The next line(s) contains a list of output parameters. See OutListParameters.xlsx for a listing of available output channels, (-) -"RtAeroCp" -"RtAeroCq" -"RtAeroCt" -"RtAeroFxh" -"RtAeroFyh" -"RtAeroFzh" -"RtAeroMxh" -"RtAeroMyh" -"RtAeroMzh" -"RtAeroPwr" +"RtFldFxh" +"RtFldFyh" +"RtFldFzh" +"RtFldMxh" +"RtFldMyh" +"RtFldMzh" +"RtVAvgxh" +"RtFldCp" +"RtFldCt" "RtArea" -"RtSkew" "RtSpeed" "RtTSR" "RtVAvgxh" diff --git a/Test_Cases/IEA-15-240-RWT-UMaineSemi/IEA-15-240-RWT_AeroDyn15.dat b/Test_Cases/IEA-15-240-RWT-UMaineSemi/IEA-15-240-RWT_AeroDyn15.dat index 585bd715..c2602a6f 100644 --- a/Test_Cases/IEA-15-240-RWT-UMaineSemi/IEA-15-240-RWT_AeroDyn15.dat +++ b/Test_Cases/IEA-15-240-RWT-UMaineSemi/IEA-15-240-RWT_AeroDyn15.dat @@ -1,16 +1,17 @@ ------- AERODYN v15.03.* INPUT FILE ------------------------------------------------ IEA 15 MW Offshore Reference Turbine ====== General Options ============================================================================ -False Echo - Echo the input to ".AD.ech"? (flag) -"default" DTAero - Time interval for aerodynamic calculations {or "default"} (s) -1 WakeMod - Type of wake/induction model (switch) {0=none, 1=BEMT, 2=DBEMT, 3=OLAF} [WakeMod cannot be 2 or 3 when linearizing] -2 AFAeroMod - Type of blade airfoil aerodynamics model (switch) {1=steady model, 2=Beddoes-Leishman unsteady model} [AFAeroMod must be 1 when linearizing] -1 TwrPotent - Type tower influence on wind based on potential flow around the tower (switch) {0=none, 1=baseline potential flow, 2=potential flow with Bak correction} -0 TwrShadow - Calculate tower influence on wind based on downstream tower shadow (switch) {0=none, 1=Powles model, 2=Eames model} -True TwrAero - Calculate tower aerodynamic loads? (flag) -False FrozenWake - Assume frozen wake during linearization? (flag) [used only when WakeMod=1 and when linearizing] -False CavitCheck - Perform cavitation check? (flag) [AFAeroMod must be 1 when CavitCheck=true] -False CompAA - Flag to compute AeroAcoustics calculation [used only when WakeMod = 1 or 2] +False Echo - Echo the input to ".AD.ech"? (flag) +"default" DTAero - Time interval for aerodynamic calculations {or "default"} (s) +1 WakeMod - Type of wake/induction model (switch) {0=none, 1=BEMT, 2=DBEMT, 3=OLAF} [WakeMod cannot be 2 or 3 when linearizing] +2 AFAeroMod - Type of blade airfoil aerodynamics model (switch) {1=steady model, 2=Beddoes-Leishman unsteady model} [AFAeroMod must be 1 when linearizing] +1 TwrPotent - Type tower influence on wind based on potential flow around the tower (switch) {0=none, 1=baseline potential flow, 2=potential flow with Bak correction} +1 TwrShadow - Calculate tower influence on wind based on downstream tower shadow (switch) {0=none, 1=Powles model, 2=Eames model} +True TwrAero - Calculate tower aerodynamic loads? (flag) +False FrozenWake - Assume frozen wake during linearization? (flag) [used only when WakeMod=1 and when linearizing] +False CavitCheck - Perform cavitation check? (flag) [AFAeroMod must be 1 when CavitCheck=true] +False Buoyancy - Include buoyancy effects? (flag) +False CompAA - Flag to compute AeroAcoustics calculation [used only when WakeMod = 1 or 2] "AeroAcousticsInput.dat" AA_InputFile - AeroAcoustics input file [used only when CompAA=true] ====== Environmental Conditions =================================================================== "default" AirDens - Air density (kg/m^3) @@ -36,8 +37,6 @@ True TIDrag - Include the drag term in the tangential-ind ====== Beddoes-Leishman Unsteady Airfoil Aerodynamics Options ===================================== [used only when AFAeroMod=2] 3 UAMod - Unsteady Aero Model Switch (switch) {1=Baseline model (Original), 2=Gonzalez's variant (changes in Cn,Cc,Cm), 3=Minnema/Pierce variant (changes in Cc and Cm)} [used only when AFAeroMod=2] True FLookup - Flag to indicate whether a lookup for f' will be calculated (TRUE) or whether best-fit exponential equations will be used (FALSE); if FALSE S1-S4 must be provided in airfoil input files (flag) [used only when AFAeroMod=2] -0.0 UAStartRad - Starting radius for dynamic stall (fraction of rotor radius) [used only when AFAeroMod=2] -1.0 UAEndRad - Ending radius for dynamic stall (fraction of rotor radius) [used only when AFAeroMod=2] ====== Airfoil Information ========================================================================= 1 AFTabMod - Interpolation method for multiple airfoil tables {1=1D interpolation on AoA (first table only); 2=2D interpolation on AoA and Re; 3=2D interpolation on AoA and UserProp} (-) 1 InCol_Alfa - The column in the airfoil tables that contains the angle of attack (-) @@ -101,21 +100,30 @@ True UseBlCm - Include aerodynamic pitching moment in calc "IEA-15-240-RWT_AeroDyn15_blade.dat" ADBlFile(1) - Name of file containing distributed aerodynamic properties for Blade #1 (-) "IEA-15-240-RWT_AeroDyn15_blade.dat" ADBlFile(2) - Name of file containing distributed aerodynamic properties for Blade #2 (-) [unused if NumBl < 2] "IEA-15-240-RWT_AeroDyn15_blade.dat" ADBlFile(3) - Name of file containing distributed aerodynamic properties for Blade #3 (-) [unused if NumBl < 3] -====== Tower Influence and Aerodynamics ============================================================= [used only when TwrPotent/=0, TwrShadow/=0, or TwrAero=True] -11 NumTwrNds - Number of tower nodes used in the analysis (-) [used only when TwrPotent/=0, TwrShadow/=0, or TwrAero=True] -TwrElev TwrDiam TwrCd TwrTI (used only with TwrShadow=2) -(m) (m) (-) (-) - 15. 10. 0.5 0.1 - 28. 10. 0.5 0.1 - 41. 9.926 0.5 0.1 - 54. 9.443 0.5 0.1 - 67. 8.833 0.5 0.1 - 80. 8.151 0.5 0.1 - 93. 7.39 0.5 0.1 - 106. 6.909 0.5 0.1 - 119. 6.748 0.5 0.1 - 132. 6.572 0.5 0.1 - 144.386 6.5 0.5 0.1 +====== Hub Properties ============================================================================== [used only when Buoyancy=True] +0.0 VolHub - Hub volume (m^3) +0.0 HubCenBx - Hub center of buoyancy x direction offset (m) +====== Nacelle Properties ========================================================================== [used only when Buoyancy=True] +0.0 VolNac - Nacelle volume (m^3) +0,0,0 NacCenB - Position of nacelle center of buoyancy from yaw bearing in nacelle coordinates (m) +====== Tail fin Aerodynamics ======================================================================== +False TFinAero - Calculate tail fin aerodynamics model (flag) +"unused" TFinFile - Input file for tail fin aerodynamics [used only when TFinAero=True] +====== Tower Influence and Aerodynamics ============================================================ [used only when TwrPotent/=0, TwrShadow/=0, TwrAero=True, or Buoyancy=True] + 11 NumTwrNds - Number of tower nodes used in the analysis (-) [used only when TwrPotent/=0, TwrShadow/=0, TwrAero=True, or Buoyancy=True] +TwrElev TwrDiam TwrCd TwrTI TwrCb !TwrTI used only with TwrShadow=2, TwrCb used only with Buoyancy=True +(m) (m) (-) (-) (-) + 15. 10. 0.5 0.1 0.0 + 28. 10. 0.5 0.1 0.0 + 41. 9.926 0.5 0.1 0.0 + 54. 9.443 0.5 0.1 0.0 + 67. 8.833 0.5 0.1 0.0 + 80. 8.151 0.5 0.1 0.0 + 93. 7.39 0.5 0.1 0.0 + 106. 6.909 0.5 0.1 0.0 + 119. 6.748 0.5 0.1 0.0 + 132. 6.572 0.5 0.1 0.0 + 144.386 6.5 0.5 0.1 0.0 ====== Outputs ==================================================================================== True SumPrint - Generate a summary file listing input options and interpolated properties to ".AD.sum"? (flag) 9 NBlOuts - Number of blade node outputs [0 - 9] (-) @@ -123,15 +131,15 @@ True SumPrint - Generate a summary file listing input optio 0 NTwOuts - Number of tower node outputs [0 - 9] (-) 1, 2, 3, 4, 5 TwOutNd - Tower nodes whose values will be output (-) OutList - The next line(s) contains a list of output parameters. See OutListParameters.xlsx for a listing of available output channels, (-) -"RtAeroFxh" -"RtAeroFyh" -"RtAeroFzh" -"RtAeroMxh" -"RtAeroMyh" -"RtAeroMzh" +"RtFldFxh" +"RtFldFyh" +"RtFldFzh" +"RtFldMxh" +"RtFldMyh" +"RtFldMzh" "RtVAvgxh" -"RtAeroCp" -"RtAeroCt" +"RtFldCp" +"RtFldCt" "RtArea" "RtSpeed" "RtTSR" diff --git a/Test_Cases/NREL-5MW/NRELOffshrBsline5MW_Onshore_AeroDyn15.dat b/Test_Cases/NREL-5MW/NRELOffshrBsline5MW_Onshore_AeroDyn15.dat index 0983cb2d..b3660b01 100644 --- a/Test_Cases/NREL-5MW/NRELOffshrBsline5MW_Onshore_AeroDyn15.dat +++ b/Test_Cases/NREL-5MW/NRELOffshrBsline5MW_Onshore_AeroDyn15.dat @@ -10,6 +10,7 @@ False Echo - Echo the input to ".AD.ech"? (flag True TwrAero - Calculate tower aerodynamic loads? (flag) False FrozenWake - Assume frozen wake during linearization? (flag) [used only when WakeMod=1 and when linearizing] False CavitCheck - Perform cavitation check? (flag) [AFAeroMod must be 1 when CavitCheck=true] +False Buoyancy - Include buoyancy effects? (flag) False CompAA - Flag to compute AeroAcoustics calculation [only used when WakeMod=1 or 2] "unused" AA_InputFile - Aeroacoustics input file ====== Environmental Conditions =================================================================== @@ -34,10 +35,8 @@ False TIDrag - Include the drag term in the tangential-induc ====== OLAF -- cOnvecting LAgrangian Filaments (Free Vortex Wake) Theory Options ================== [used only when WakeMod=3] "unused" OLAFInputFileName - Input file for OLAF [used only when WakeMod=3] ====== Beddoes-Leishman Unsteady Airfoil Aerodynamics Options ===================================== [used only when AFAeroMod=2] - 3 UAMod - Unsteady Aero Model Switch (switch) {1=Baseline model (Original), 2=Gonzalez's variant (changes in Cn,Cc,Cm), 3=Minnema/Pierce variant (changes in Cc and Cm)} [used only when AFAeroMod=2] -True FLookup - Flag to indicate whether a lookup for f' will be calculated (TRUE) or whether best-fit exponential equations will be used (FALSE); if FALSE S1-S4 must be provided in airfoil input files (flag) [used only when AFAeroMod=2] -0.0 UAStartRad - Starting radius for dynamic stall (fraction of rotor radius) [used only when AFAeroMod=2] -1.0 UAEndRad - Ending radius for dynamic stall (fraction of rotor radius) [used only when AFAeroMod=2] +3 UAMod - Unsteady Aero Model Switch (switch) {1=Baseline model (Original), 2=Gonzalez's variant (changes in Cn,Cc,Cm), 3=Minnema/Pierce variant (changes in Cc and Cm)} [used only when AFAeroMod=2] +True FLookup - Flag to indicate whether a lookup for f' will be calculated (TRUE) or whether best-fit exponential equations will be used (FALSE); if FALSE S1-S4 must be provided in airfoil input files (flag) [used only when AFAeroMod=2] ====== Airfoil Information ========================================================================= 1 AFTabMod - Interpolation method for multiple airfoil tables {1=1D interpolation on AoA (first table only); 2=2D interpolation on AoA and Re; 3=2D interpolation on AoA and UserProp} (-) 1 InCol_Alfa - The column in the airfoil tables that contains the angle of attack (-) @@ -59,22 +58,31 @@ True UseBlCm - Include aerodynamic pitching moment in calcul "NRELOffshrBsline5MW_AeroDyn_blade.dat" ADBlFile(1) - Name of file containing distributed aerodynamic properties for Blade #1 (-) "NRELOffshrBsline5MW_AeroDyn_blade.dat" ADBlFile(2) - Name of file containing distributed aerodynamic properties for Blade #2 (-) [unused if NumBl < 2] "NRELOffshrBsline5MW_AeroDyn_blade.dat" ADBlFile(3) - Name of file containing distributed aerodynamic properties for Blade #3 (-) [unused if NumBl < 3] +====== Hub Properties ============================================================================== [used only when Buoyancy=True] +0.0 VolHub - Hub volume (m^3) +0.0 HubCenBx - Hub center of buoyancy x direction offset (m) +====== Nacelle Properties ========================================================================== [used only when Buoyancy=True] +0.0 VolNac - Nacelle volume (m^3) +0,0,0 NacCenB - Position of nacelle center of buoyancy from yaw bearing in nacelle coordinates (m) +====== Tail fin Aerodynamics ======================================================================== +False TFinAero - Calculate tail fin aerodynamics model (flag) +"unused" TFinFile - Input file for tail fin aerodynamics [used only when TFinAero=True] ====== Tower Influence and Aerodynamics ============================================================= [used only when TwrPotent/=0, TwrShadow=True, or TwrAero=True] 12 NumTwrNds - Number of tower nodes used in the analysis (-) [used only when TwrPotent/=0, TwrShadow=True, or TwrAero=True] -TwrElev TwrDiam TwrCd TwrTI (used only with TwrShadow=2) -(m) (m) (-) (-) -0.0000000E+00 6.0000000E+00 1.0000000E+00 1.000000E-01 -8.5261000E+00 5.7870000E+00 1.0000000E+00 1.000000E-01 -1.7053000E+01 5.5740000E+00 1.0000000E+00 1.000000E-01 -2.5579000E+01 5.3610000E+00 1.0000000E+00 1.000000E-01 -3.4105000E+01 5.1480000E+00 1.0000000E+00 1.000000E-01 -4.2633000E+01 4.9350000E+00 1.0000000E+00 1.000000E-01 -5.1158000E+01 4.7220000E+00 1.0000000E+00 1.000000E-01 -5.9685000E+01 4.5090000E+00 1.0000000E+00 1.000000E-01 -6.8211000E+01 4.2960000E+00 1.0000000E+00 1.000000E-01 -7.6738000E+01 4.0830000E+00 1.0000000E+00 1.000000E-01 -8.5268000E+01 3.8700000E+00 1.0000000E+00 1.000000E-01 -8.7600000E+01 3.8700000E+00 1.0000000E+00 1.000000E-01 +TwrElev TwrDiam TwrCd TwrTI TwrCb !TwrTI used only with TwrShadow=2, TwrCb used only with Buoyancy=True +(m) (m) (-) (-) (-) +0.0000000E+00 6.0000000E+00 1.0000000E+00 1.000000E-01 0.0 +8.5261000E+00 5.7870000E+00 1.0000000E+00 1.000000E-01 0.0 +1.7053000E+01 5.5740000E+00 1.0000000E+00 1.000000E-01 0.0 +2.5579000E+01 5.3610000E+00 1.0000000E+00 1.000000E-01 0.0 +3.4105000E+01 5.1480000E+00 1.0000000E+00 1.000000E-01 0.0 +4.2633000E+01 4.9350000E+00 1.0000000E+00 1.000000E-01 0.0 +5.1158000E+01 4.7220000E+00 1.0000000E+00 1.000000E-01 0.0 +5.9685000E+01 4.5090000E+00 1.0000000E+00 1.000000E-01 0.0 +6.8211000E+01 4.2960000E+00 1.0000000E+00 1.000000E-01 0.0 +7.6738000E+01 4.0830000E+00 1.0000000E+00 1.000000E-01 0.0 +8.5268000E+01 3.8700000E+00 1.0000000E+00 1.000000E-01 0.0 +8.7600000E+01 3.8700000E+00 1.0000000E+00 1.000000E-01 0.0 ====== Outputs ==================================================================================== True SumPrint - Generate a summary file listing input options and interpolated properties to ".AD.sum"? (flag) 0 NBlOuts - Number of blade node outputs [0 - 9] (-) @@ -82,5 +90,17 @@ True SumPrint - Generate a summary file listing input option 0 NTwOuts - Number of tower node outputs [0 - 9] (-) 1, 2, 6 TwOutNd - Tower nodes whose values will be output (-) OutList - The next line(s) contains a list of output parameters. See OutListParameters.xlsx for a listing of available output channels, (-) +"RtFldFxh" +"RtFldFyh" +"RtFldFzh" +"RtFldMxh" +"RtFldMyh" +"RtFldMzh" +"RtVAvgxh" +"RtFldCp" +"RtFldCt" +"RtArea" +"RtSpeed" +"RtTSR" END of input file (the word "END" must appear in the first 3 columns of this last OutList line) --------------------------------------------------------------------------------------- diff --git a/Tune_Cases/tune_ROSCO.py b/Tune_Cases/tune_ROSCO.py deleted file mode 100644 index f0631936..00000000 --- a/Tune_Cases/tune_ROSCO.py +++ /dev/null @@ -1,68 +0,0 @@ -# Controller Tuning Script for NREL-5MW Wind Turbine -# -- Made to run the tools distributed as a part of the ROSCO_Toolbox -import os - -#-------------------------------- LOAD INPUT PARAMETERS ---------------------------------# -# Change this for your turbine -this_dir = os.path.dirname(__file__) -parameter_filename = os.path.join(this_dir,'IEA15MW.yaml') # Name of .yaml input file for the specific turbine - - - - -#--------------------------------------------------------------------------------------------------------------------------------------------------------------------------------# -#--------------------- NOTHING SHOULD NEED TO CHANGE AFTER THIS -----------------------------------------------------------------------------------------------------------------# -#--------------------------------------------------------------------------------------------------------------------------------------------------------------------------------# - - -#------------------------------------- INITIALIZATION ----------------------------------# -# Import python modules -import matplotlib.pyplot as plt -import yaml -# Import ROSCO_toolbox modules -from ROSCO_toolbox import controller as ROSCO_controller -from ROSCO_toolbox import turbine as ROSCO_turbine -from ROSCO_toolbox.utilities import write_rotor_performance, write_DISCON -from ROSCO_toolbox.inputs.validation import load_rosco_yaml - -# Initialize parameter dictionaries -turbine_params = {} -control_params = {} - -# Load input file contents, put them in some dictionaries to keep things cleaner -inps = load_rosco_yaml(parameter_filename) -path_params = inps['path_params'] -turbine_params = inps['turbine_params'] -controller_params = inps['controller_params'] - -#---------------------------------- DO THE FUN STUFF ------------------------------------# -# Initialiize turbine and controller -turbine = ROSCO_turbine.Turbine(turbine_params) - -# Load Turbine, write rotor performance file if it doesn't exist -if os.path.exists(os.path.join(this_dir,path_params['rotor_performance_filename'])): - turbine.load_from_fast(path_params['FAST_InputFile'], \ - os.path.join(this_dir,path_params['FAST_directory']), \ - dev_branch=True,rot_source='txt',txt_filename=path_params['rotor_performance_filename']) -else: - turbine.load_from_fast(path_params['FAST_InputFile'], \ - os.path.join(this_dir,path_params['FAST_directory']), \ - dev_branch=True,rot_source=None, txt_filename=path_params['rotor_performance_filename']) - - write_rotor_performance(turbine,txt_filename=os.path.join(this_dir,path_params['rotor_performance_filename'])) - -# Flap tuning if necessary -if controller_params['Flp_Mode']: - turbine.load_blade_info() - -# Instantiate controller tuning and tune controller -controller = ROSCO_controller.Controller(controller_params) -controller.tune_controller(turbine) - -# Write parameter input file -param_file = 'DISCON.IN' -write_DISCON(turbine,controller,param_file=param_file, txt_filename=os.path.join(this_dir,path_params['rotor_performance_filename'])) - -# Plot rotor performance -turbine.Cp.plot_performance() -plt.show() From 42525a98a136e58b09d9fef65277e187f79fd103 Mon Sep 17 00:00:00 2001 From: dzalkind <65573423+dzalkind@users.noreply.github.com> Date: Thu, 9 Feb 2023 17:18:50 -0700 Subject: [PATCH 027/224] V270 prep (#218) * Allow PA_Mode 1 * Add update_discon_version function * Add update_rosco_discons to testing, add example for updating version * Rename and consolidate examples * Rename to test_examples.py to follow pytest convention * Fix tuning_yaml name in example_19 * Change to pytest for test_examples * Revert "Change to pytest for test_examples" This reverts commit 2f996d98b34a3f15e3f9333c52491f8b0d86a0ec. * Remove dev_branch input, clean up old code, fix reader * Fix load_from_fast in 09 * Update reader/writer/inputs for OpenFAST v3.4.0 * Finish updating inputs for 3.4.0 * Tidy up some more example naming * Fix airfoil reader * Remove remaining dev_branch references * Increment openfast version * Increment version number * Update docs for API changes in 2.7.0 * Fix example paths * Fix ROSCO_walkthrough notebook * Include ROSCO_walkthrough outputs * Update toolbox_input in docs * Allow any numpy * Fix array casting not allowed in new numpy version * Make check of cmake install dir better --- ROSCO/CMakeLists.txt | 10 +++++++--- ROSCO/src/Constants.f90 | 2 +- ROSCO/src/ROSCO_IO.f90 | 2 +- ROSCO/src/ROSCO_Types.f90 | 4 ++-- ROSCO_toolbox/__init__.py | 4 ++-- ROSCO_toolbox/inputs/schema2rst.py | 2 +- ROSCO_toolbox/ofTools/case_gen/CaseGen_General.py | 6 ++---- Test_Cases/BAR_10/BAR_10_DISCON.IN | 2 +- .../IEA-15-240-RWT-UMaineSemi/DISCON-UMaineSemi.IN | 2 +- Test_Cases/NREL-5MW/DISCON.IN | 2 +- docs/source/api_change.rst | 9 ++++++--- docs/source/toolbox_input.rst | 6 +++++- environment.yml | 2 +- setup.py | 4 ++-- 14 files changed, 33 insertions(+), 24 deletions(-) diff --git a/ROSCO/CMakeLists.txt b/ROSCO/CMakeLists.txt index 3a97a216..b69aa02d 100644 --- a/ROSCO/CMakeLists.txt +++ b/ROSCO/CMakeLists.txt @@ -1,5 +1,5 @@ cmake_minimum_required(VERSION 3.6) -project(ROSCO VERSION 2.6.0 LANGUAGES Fortran C) +project(ROSCO VERSION 2.7.0 LANGUAGES Fortran C) set(CMAKE_Fortran_MODULE_DIRECTORY "${CMAKE_BINARY_DIR}/ftnmods") @@ -109,6 +109,10 @@ install(TARGETS discon LIBRARY DESTINATION lib ARCHIVE DESTINATION lib ) -if(CMAKE_INSTALL_PREFIX_INITIALIZED_TO_DEFAULT) + +set(linuxDefault ${CMAKE_INSTALL_PREFIX} STREQUAL "/usr/local") +set(windowsDefault ${CMAKE_INSTALL_PREFIX} STREQUAL "C:\\Program Files (x86)") +if(${linuxDefault} OR ${windowsDefault}) + message("TRUE") set(CMAKE_INSTALL_PREFIX "${CMAKE_SOURCE_DIR}/install") -endif() +endif() \ No newline at end of file diff --git a/ROSCO/src/Constants.f90 b/ROSCO/src/Constants.f90 index d04745ae..0da3ac94 100644 --- a/ROSCO/src/Constants.f90 +++ b/ROSCO/src/Constants.f90 @@ -14,7 +14,7 @@ MODULE Constants USE, INTRINSIC :: ISO_C_Binding - Character(*), PARAMETER :: rosco_version = 'v2.6.0' ! ROSCO version + Character(*), PARAMETER :: rosco_version = 'v2.7.0' ! ROSCO version INTEGER, PARAMETER :: DbKi = C_DOUBLE !< Default kind for double floating-point numbers INTEGER, PARAMETER :: ReKi = C_FLOAT !< Default kind for single floating-point numbers INTEGER, PARAMETER :: IntKi = C_INT !< Default kind for integer numbers diff --git a/ROSCO/src/ROSCO_IO.f90 b/ROSCO/src/ROSCO_IO.f90 index e852105a..d465d512 100644 --- a/ROSCO/src/ROSCO_IO.f90 +++ b/ROSCO/src/ROSCO_IO.f90 @@ -1,5 +1,5 @@ ! ROSCO IO -! This file is automatically generated by write_registry.py using ROSCO v2.6.0 +! This file is automatically generated by write_registry.py using ROSCO v2.7.0 ! For any modification to the registry, please edit the rosco_types.yaml accordingly MODULE ROSCO_IO diff --git a/ROSCO/src/ROSCO_Types.f90 b/ROSCO/src/ROSCO_Types.f90 index ad2b631b..2c4143bc 100644 --- a/ROSCO/src/ROSCO_Types.f90 +++ b/ROSCO/src/ROSCO_Types.f90 @@ -1,5 +1,5 @@ ! ROSCO Registry -! This file is automatically generated by write_registry.py using ROSCO v2.6.0 +! This file is automatically generated by write_registry.py using ROSCO v2.7.0 ! For any modification to the registry, please edit the rosco_types.yaml accordingly MODULE ROSCO_Types @@ -28,7 +28,7 @@ MODULE ROSCO_Types INTEGER(IntKi) :: IPC_ControlMode ! Turn Individual Pitch Control (IPC) for fatigue load reductions (pitch contribution) {0 - off, 1 - 1P reductions, 2 - 1P+2P reductions} REAL(DbKi), DIMENSION(:), ALLOCATABLE :: IPC_Vramp ! Wind speeds for IPC cut-in sigma function [m/s] REAL(DbKi) :: IPC_IntSat ! Integrator saturation (maximum signal amplitude contrbution to pitch from IPC) - INTEGER(IntKi) :: IPC_SatMode ! IPC Saturation method (0 - no saturation, 1 - saturate by PC_MinPit, 2 - saturate by PS_BldPitchMin) + INTEGER(IntKi) :: IPC_SatMode ! IPC Saturation method IPC Saturation method (0 - no saturation (except by PC_MinPit), 1 - saturate by PS_BldPitchMin, 2 - saturate sotfly (full IPC cycle) by PC_MinPit, 3 - saturate softly by PS_BldPitchMin) REAL(DbKi), DIMENSION(:), ALLOCATABLE :: IPC_KP ! Integral gain for the individual pitch controller, [-]. REAL(DbKi), DIMENSION(:), ALLOCATABLE :: IPC_KI ! Integral gain for the individual pitch controller, [-]. REAL(DbKi), DIMENSION(:), ALLOCATABLE :: IPC_aziOffset ! Phase offset added to the azimuth angle for the individual pitch controller, [rad]. diff --git a/ROSCO_toolbox/__init__.py b/ROSCO_toolbox/__init__.py index afbd37e5..092377ed 100644 --- a/ROSCO_toolbox/__init__.py +++ b/ROSCO_toolbox/__init__.py @@ -2,5 +2,5 @@ """Top-level package for ROSCO_toolbox Repo.""" __author__ = """Nikhar J. Abbas and Daniel S. Zalkind""" -__email__ = 'nikhar.abbas@nrel.gov' -__version__ = '2.6.0' +__email__ = 'daniel.zalkind@nrel.gov' +__version__ = '2.7.0' diff --git a/ROSCO_toolbox/inputs/schema2rst.py b/ROSCO_toolbox/inputs/schema2rst.py index a72343f3..e88f63f5 100644 --- a/ROSCO_toolbox/inputs/schema2rst.py +++ b/ROSCO_toolbox/inputs/schema2rst.py @@ -84,7 +84,7 @@ def __init__(self, fname): def write_rst(self): self.f = open(self.fout, "w") self.write_header() - self.write_loop(self.yaml["properties"], 0, self.fname.replace("yaml", "")) + self.write_loop(self.yaml["properties"], 0, 'toolbox_schema') self.f.close() def write_header(self): diff --git a/ROSCO_toolbox/ofTools/case_gen/CaseGen_General.py b/ROSCO_toolbox/ofTools/case_gen/CaseGen_General.py index 87bb7bae..8c46e522 100644 --- a/ROSCO_toolbox/ofTools/case_gen/CaseGen_General.py +++ b/ROSCO_toolbox/ofTools/case_gen/CaseGen_General.py @@ -155,10 +155,8 @@ def CaseGen_General(case_inputs, dir_matrix='', namebase='', save_matrix=True): for g in matrix_group_idx[j]: row_out[g] = change_vals[g][val] matrix_out.append(row_out) - try: - matrix_out = np.asarray(matrix_out, dtype=str) - except: - matrix_out = np.asarray(matrix_out) + + matrix_out = np.asarray(matrix_out, dtype=object) n_cases = np.shape(matrix_out)[0] # case naming diff --git a/Test_Cases/BAR_10/BAR_10_DISCON.IN b/Test_Cases/BAR_10/BAR_10_DISCON.IN index e7f5a1bd..17875c9c 100644 --- a/Test_Cases/BAR_10/BAR_10_DISCON.IN +++ b/Test_Cases/BAR_10/BAR_10_DISCON.IN @@ -1,5 +1,5 @@ ! Controller parameter input file for the BAR_10 wind turbine -! - File written using ROSCO version 2.6.0 controller tuning logic on 01/18/23 +! - File written using ROSCO version 2.7.0 controller tuning logic on 02/06/23 !------- DEBUG ------------------------------------------------------------ 1 ! LoggingLevel - {0: write no debug files, 1: write standard output .dbg-file, 2: LoggingLevel 1 + ROSCO LocalVars (.dbg2) 3: LoggingLevel 2 + complete avrSWAP-array (.dbg3)} diff --git a/Test_Cases/IEA-15-240-RWT-UMaineSemi/DISCON-UMaineSemi.IN b/Test_Cases/IEA-15-240-RWT-UMaineSemi/DISCON-UMaineSemi.IN index 6be782e5..5f55c5ab 100644 --- a/Test_Cases/IEA-15-240-RWT-UMaineSemi/DISCON-UMaineSemi.IN +++ b/Test_Cases/IEA-15-240-RWT-UMaineSemi/DISCON-UMaineSemi.IN @@ -1,5 +1,5 @@ ! Controller parameter input file for the IEA-15-240-RWT-UMaineSemi wind turbine -! - File written using ROSCO version 2.6.0 controller tuning logic on 01/18/23 +! - File written using ROSCO version 2.7.0 controller tuning logic on 02/06/23 !------- DEBUG ------------------------------------------------------------ 2 ! LoggingLevel - {0: write no debug files, 1: write standard output .dbg-file, 2: LoggingLevel 1 + ROSCO LocalVars (.dbg2) 3: LoggingLevel 2 + complete avrSWAP-array (.dbg3)} diff --git a/Test_Cases/NREL-5MW/DISCON.IN b/Test_Cases/NREL-5MW/DISCON.IN index 29b3a8e8..e3c2ae45 100644 --- a/Test_Cases/NREL-5MW/DISCON.IN +++ b/Test_Cases/NREL-5MW/DISCON.IN @@ -1,5 +1,5 @@ ! Controller parameter input file for the NREL-5MW wind turbine -! - File written using ROSCO version 2.6.0 controller tuning logic on 01/18/23 +! - File written using ROSCO version 2.7.0 controller tuning logic on 02/06/23 !------- DEBUG ------------------------------------------------------------ 1 ! LoggingLevel - {0: write no debug files, 1: write standard output .dbg-file, 2: LoggingLevel 1 + ROSCO LocalVars (.dbg2) 3: LoggingLevel 2 + complete avrSWAP-array (.dbg3)} diff --git a/docs/source/api_change.rst b/docs/source/api_change.rst index c126598f..f6ad8a57 100644 --- a/docs/source/api_change.rst +++ b/docs/source/api_change.rst @@ -9,17 +9,20 @@ The changes are tabulated according to the line number, and flag name. The line number corresponds to the resulting line number after all changes are implemented. Thus, be sure to implement each in order so that subsequent line numbers are correct. -2.6.0 to develop +2.6.0 to 2.7.0 ------------------------------- Pitch Faults - Constant pitch actuator offsets (PF_Mode = 1) +IPC Saturation Modes +- Added options for saturating the IPC command with the peak shaving limit ====== ================= ====================================================================================================================================================================================================== -New in ROSCO develop +New in ROSCO 2.7.0 ---------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- Line Input Name Example Value ====== ================= ====================================================================================================================================================================================================== 23 PF_Mode 0 ! PF_Mode - Pitch fault mode {0 - not used, 1 - constant offset on one or more blades} +56 IPC_SatMode 2 ! IPC_SatMode - IPC Saturation method (0 - no saturation (except by PC_MinPit), 1 - saturate by PS_BldPitchMin, 2 - saturate sotfly (full IPC cycle) by PC_MinPit, 3 - saturate softly by PS_BldPitchMin) 139 PF_Section !------- Pitch Actuator Faults --------------------------------------------------------- 140 PF_Offsets 0.00000000 0.00000000 0.00000000 ! PF_Offsets - Constant blade pitch offsets for blades 1-3 [rad] 141 Empty Line @@ -75,7 +78,7 @@ Modified in ROSCO 2.6.0 ---------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- Line Input Name Example Value ====== ================= ====================================================================================================================================================================================================== -97 Y_ErrThresh 4.000000 8.000000 ! Y_ErrThresh - Yaw error threshold/deadband. Turbine begins to yaw when it passes this. If Y_uSwitch is zero, only the first value is used. [deg]. +97 Y_ErrThresh 4.000000 8.000000 ! Y_ErrThresh - Yaw error threshold/deadbands. Turbine begins to yaw when it passes this. If Y_uSwitch is zero, only the second value is used. [deg]. 98 Y_Rate 0.00870 ! Y_Rate - Yaw rate [rad/s] 99 Y_MErrSet 0.00000 ! Y_MErrSet - Integrator saturation (maximum signal amplitude contribution to pitch from yaw-by-IPC), [rad] ====== ================= ====================================================================================================================================================================================================== diff --git a/docs/source/toolbox_input.rst b/docs/source/toolbox_input.rst index 9ac78581..2c11d648 100644 --- a/docs/source/toolbox_input.rst +++ b/docs/source/toolbox_input.rst @@ -9,7 +9,7 @@ ROSCO_Toolbox tuning .yaml Definition of inputs for ROSCO tuning procedure -/Users/dzalkind/Tools/ROSCO/ROSCO_toolbox/inputs/toolbox_schema. +toolbox_schema @@ -697,6 +697,10 @@ These are pass-through parameters for the DISCON.IN file. Use with caution. Integrator saturation (maximum signal amplitude contribution to pitch from IPC) +:code:`IPC_SatMode` : Integer + IPC Saturation method (0 - no saturation, 1 - saturate by + PC_MinPit, 2 - saturate by PS_BldPitchMin) + :code:`IPC_KP` : Array of Floats Proportional gain for the individual pitch controller- first parameter for 1P reductions, second for 2P reductions, [-] diff --git a/environment.yml b/environment.yml index b170dc52..d90d5165 100644 --- a/environment.yml +++ b/environment.yml @@ -4,7 +4,7 @@ channels: dependencies: - matplotlib - - numpy==1.23 + - numpy - pytest - scipy - pyYAML diff --git a/setup.py b/setup.py index ee681647..70fa943f 100644 --- a/setup.py +++ b/setup.py @@ -33,10 +33,10 @@ NAME = 'rosco' DESCRIPTION = 'A reference open source controller toolset for wind turbine applications.' URL = 'https://github.com/NREL/ROSCO' -EMAIL = 'nikhar.abbas@nrel.gov' +EMAIL = 'daniel.zalkind@nrel.gov' AUTHOR = 'NREL, National Wind Technology Center' REQUIRES_PYTHON = '>=3.4' -VERSION = '2.6.0' +VERSION = '2.7.0' # These packages are required for all of the code to be executed. # - Maybe you can get away with older versions... From f5c3c1e5d60595b39f591f70c938b7044da21d43 Mon Sep 17 00:00:00 2001 From: dzalkind Date: Fri, 10 Feb 2023 14:34:48 -0700 Subject: [PATCH 028/224] Add case generation updates --- ROSCO_toolbox/ofTools/case_gen/CaseGen_General.py | 7 +++---- ROSCO_toolbox/ofTools/case_gen/CaseLibrary.py | 2 +- 2 files changed, 4 insertions(+), 5 deletions(-) diff --git a/ROSCO_toolbox/ofTools/case_gen/CaseGen_General.py b/ROSCO_toolbox/ofTools/case_gen/CaseGen_General.py index 87bb7bae..c3ec4df7 100644 --- a/ROSCO_toolbox/ofTools/case_gen/CaseGen_General.py +++ b/ROSCO_toolbox/ofTools/case_gen/CaseGen_General.py @@ -155,10 +155,9 @@ def CaseGen_General(case_inputs, dir_matrix='', namebase='', save_matrix=True): for g in matrix_group_idx[j]: row_out[g] = change_vals[g][val] matrix_out.append(row_out) - try: - matrix_out = np.asarray(matrix_out, dtype=str) - except: - matrix_out = np.asarray(matrix_out) + + matrix_out = np.asarray(matrix_out, dtype=object) + n_cases = np.shape(matrix_out)[0] # case naming diff --git a/ROSCO_toolbox/ofTools/case_gen/CaseLibrary.py b/ROSCO_toolbox/ofTools/case_gen/CaseLibrary.py index a637885e..71d67dbc 100644 --- a/ROSCO_toolbox/ofTools/case_gen/CaseLibrary.py +++ b/ROSCO_toolbox/ofTools/case_gen/CaseLibrary.py @@ -127,7 +127,7 @@ def power_curve(**wind_case_opts): # Constant wind speed, multiple wind speeds, define below # Runtime - T_max = 400. + T_max = wind_case_opts.get('TMax',400.) if 'U' in wind_case_opts: U = wind_case_opts['U'] From a4717839d6c7dfafa50c5567d11959384ae4ee49 Mon Sep 17 00:00:00 2001 From: dzalkind Date: Fri, 10 Feb 2023 14:35:19 -0700 Subject: [PATCH 029/224] Add initial AWC example, needs OF3.4 --- Examples/20_active_wake_control.py | 85 ++++++++++++++++++++++++++++++ Tune_Cases/NREL2p8.yaml | 50 ++++++++++++++++++ 2 files changed, 135 insertions(+) create mode 100644 Examples/20_active_wake_control.py create mode 100644 Tune_Cases/NREL2p8.yaml diff --git a/Examples/20_active_wake_control.py b/Examples/20_active_wake_control.py new file mode 100644 index 00000000..ff5350bf --- /dev/null +++ b/Examples/20_active_wake_control.py @@ -0,0 +1,85 @@ +''' +----------- 20_active_wake_control ------------ +Run openfast with ROSCO and active wake control +----------------------------------------------- + +Set up and run simulation with AWC, check outputs + +''' + +import os, platform +from ROSCO_toolbox.ofTools.case_gen.run_FAST import run_FAST_ROSCO +from ROSCO_toolbox.ofTools.case_gen import CaseLibrary as cl +from ROSCO_toolbox.ofTools.fast_io import output_processing +from ROSCO_toolbox.utilities import read_DISCON, DISCON_dict +import numpy as np + + +#directories +this_dir = os.path.dirname(os.path.abspath(__file__)) +rosco_dir = os.path.dirname(this_dir) +example_out_dir = os.path.join(this_dir,'examples_out') +os.makedirs(example_out_dir,exist_ok=True) + +if platform.system() == 'Windows': + lib_name = os.path.realpath(os.path.join(this_dir, '../ROSCO/build/libdiscon.dll')) +elif platform.system() == 'Darwin': + lib_name = os.path.realpath(os.path.join(this_dir, '../ROSCO/build/libdiscon.dylib')) +else: + lib_name = os.path.realpath(os.path.join(this_dir, '../ROSCO/build/libdiscon.so')) + + +def main(): + + # Input yaml and output directory + parameter_filename = os.path.join(rosco_dir,'Tune_Cases/IEA15MW.yaml') # will be dummy and overwritten with SNL DISCON + run_dir = os.path.join(example_out_dir,'20_active_wake_control') + os.makedirs(run_dir,exist_ok=True) + + # Read all inputs + rosco_vt = read_DISCON('/Users/dzalkind/Tools/ROSCO3/Test_Cases/NREL_2p8_127/NREL-2p8-127_DISCON.IN') + + + + # Apply all discon variables as case inputs + control_base_case = {} + for discon_input in rosco_vt: + control_base_case[('DISCON_in',discon_input)] = {'vals': [rosco_vt[discon_input]], 'group': 0} + + + # simulation set up + r = run_FAST_ROSCO() + r.tuning_yaml = parameter_filename + r.wind_case_fcn = cl.power_curve # single step wind input + r.wind_case_opts = { + 'U': [6], # from 10 to 15 m/s + 'TMax': 100, + } + r.case_inputs = control_base_case + r.case_inputs[("ServoDyn","Ptch_Cntrl")] = {'vals':[1], 'group':0} # Individual pitch control must be enabled in ServoDyn + r.save_dir = run_dir + r.rosco_dir = rosco_dir + + r.run_FAST() + + + print('here') + # # Check pitch offsets + # filenames = [os.path.join(run_dir,'IEA15MW/simp_step/base/IEA15MW_0.outb')] + # fast_out = output_processing.output_processing() + + # # Load and plot + # fastout = fast_out.load_fast_out(filenames) + # offset_2 = fastout[0]['BldPitch2'] - fastout[0]['BldPitch1'] + # offset_3 = fastout[0]['BldPitch3'] - fastout[0]['BldPitch1'] + + # # check that offset (min,max) is very close to prescribed values + # np.testing.assert_almost_equal(offset_2.max(),pitch2_offset,decimal=3) + # np.testing.assert_almost_equal(offset_2.min(),pitch2_offset,decimal=3) + # np.testing.assert_almost_equal(offset_3.max(),pitch3_offset,decimal=3) + # np.testing.assert_almost_equal(offset_3.max(),pitch3_offset,decimal=3) + + + +if __name__=="__main__": + main() \ No newline at end of file diff --git a/Tune_Cases/NREL2p8.yaml b/Tune_Cases/NREL2p8.yaml new file mode 100644 index 00000000..2b39b420 --- /dev/null +++ b/Tune_Cases/NREL2p8.yaml @@ -0,0 +1,50 @@ +--- # ---------------------NREL Generic controller tuning input file ------------------- + # Written for use with ROSCO_Toolbox tuning procedures + # Turbine: NREL 5MW Reference Wind Turbine +# ------------------------------ OpenFAST PATH DEFINITIONS ------------------------------ +path_params: + FAST_InputFile: 'NREL-2p8-127.fst' # Name of *.fst file + FAST_directory: '../Test_Cases/NREL_2p8_127' # Main OpenFAST model directory, where the *.fst lives + # Optional + rotor_performance_filename: 'NREL-2p8-127_Cp_Ct_Cq.txt' # Filename for rotor performance text file (if it has been generated by ccblade already) + +# -------------------------------- TURBINE PARAMETERS ----------------------------------- +turbine_params: + rotor_inertia: 38677040.613 # Rotor inertia [kg m^2], {Available in Elastodyn .sum file} + rated_rotor_speed: 1.26711 # Rated rotor speed [rad/s] + v_min: 3.0 # Cut-in wind speed [m/s] + v_rated: 11.4 # Rated wind speed [m/s] + v_max: 25.0 # Cut-out wind speed [m/s], -- Does not need to be exact (JUST ASSUME FOR NOW) + max_pitch_rate: 0.1745 # Maximum blade pitch rate [rad/s] + max_torque_rate: 1500000. # Maximum torque rate [Nm/s], {~1/4 VS_RtTq/s} + rated_power: 5000000. # Rated Power [W] + bld_edgewise_freq: 6.2831853 # Blade edgewise first natural frequency [rad/s] + bld_flapwise_freq: 0.0 # Blade flapwise first natural frequency [rad/s] + # Optional + # TSR_operational: # None # Desired below-rated operational tip speed ratio (Cp-maximizing TSR is used if not defined) +#------------------------------- CONTROLLER PARAMETERS ---------------------------------- +controller_params: + # Controller flags + LoggingLevel: 1 # {0: write no debug files, 1: write standard output .dbg-file, 2: write standard output .dbg-file and complete avrSWAP-array .dbg2-file + F_LPFType: 1 # {1: first-order low-pass filter, 2: second-order low-pass filter}, [rad/s] (currently filters generator speed and pitch control signals) + F_NotchType: 0 # Notch filter on generator speed and/or tower fore-aft motion (for floating) {0: disable, 1: generator speed, 2: tower-top fore-aft motion, 3: generator speed and tower-top fore-aft motion} + IPC_ControlMode: 0 # Turn Individual Pitch Control (IPC) for fatigue load reductions (pitch contribution) {0: off, 1: 1P reductions, 2: 1P+2P reductions} + VS_ControlMode: 3 # Generator torque control mode in above rated conditions {0: constant torque, 1: constant power, 2: TSR tracking PI control} + PC_ControlMode: 1 # Blade pitch control mode {0: No pitch, fix to fine pitch, 1: active PI blade pitch control} + Y_ControlMode: 0 # Yaw control mode {0: no yaw control, 1: yaw rate control, 2: yaw-by-IPC} + SS_Mode: 1 # Setpoint Smoother mode {0: no setpoint smoothing, 1: introduce setpoint smoothing} + WE_Mode: 2 # Wind speed estimator mode {0: One-second low pass filtered hub height wind speed, 1: Immersion and Invariance Estimator (Ortega et al.)} + PS_Mode: 1 # Pitch saturation mode {0: no pitch saturation, 1: peak shaving, 2: Cp-maximizing pitch saturation, 3: peak shaving and Cp-maximizing pitch saturation} + SD_Mode: 0 # Shutdown mode {0: no shutdown procedure, 1: pitch to max pitch at shutdown} + Fl_Mode: 0 # Floating specific feedback mode {0: no nacelle velocity feedback, 1: nacelle velocity feedback} + Flp_Mode: 0 # Flap control mode {0: no flap control, 1: steady state flap angle, 2: Proportional flap control} + # Controller parameters + zeta_pc: 0.7 # Pitch controller desired damping ratio [-] + omega_pc: 0.6 # Pitch controller desired natural frequency [rad/s] + zeta_vs: 0.7 # Torque controller desired damping ratio [-] + omega_vs: 0.15 # Torque controller desired natural frequency [rad/s] + twr_freq: 0.4499 # Tower natural frequency [rad/s] + ptfm_freq: 0.2325 # Platform natural frequency [rad/s] (OC4Hywind Parameters, here) + # Optional + ps_percent: 0.80 # Percent peak shaving [%, <= 1 ], {default = 80%} + sd_maxpit: 0.4363 # Maximum blade pitch angle to initiate shutdown [rad], {default = bld pitch at v_max} From 80bd691ac684729483393d05792db23a7d0ba2f8 Mon Sep 17 00:00:00 2001 From: dzalkind Date: Fri, 10 Feb 2023 15:23:12 -0700 Subject: [PATCH 030/224] Add AWC_Mode and move AWC into subroutine --- ROSCO/rosco_registry/rosco_types.yaml | 3 ++ ROSCO/src/Controllers.f90 | 77 +++++++++++++++++---------- ROSCO/src/ROSCO_IO.f90 | 11 +++- ROSCO/src/ROSCO_Types.f90 | 1 + ROSCO/src/ReadSetParameters.f90 | 1 + ROSCO_toolbox/utilities.py | 15 ++++++ 6 files changed, 78 insertions(+), 30 deletions(-) diff --git a/ROSCO/rosco_registry/rosco_types.yaml b/ROSCO/rosco_registry/rosco_types.yaml index 6956d9cf..56358a4b 100644 --- a/ROSCO/rosco_registry/rosco_types.yaml +++ b/ROSCO/rosco_registry/rosco_types.yaml @@ -449,6 +449,9 @@ ControlParameters: description: Pitch actuator damping ratio [-, unused if PA_Mode = 1] # Active wake control + AWC_Mode: + <<: *integer + description: Active wake control mode [0 - unused, 1 - SNL method] AWC_NumModes: <<: *integer description: AWC- Number of modes to include [-] diff --git a/ROSCO/src/Controllers.f90 b/ROSCO/src/Controllers.f90 index 079e268b..4671e224 100644 --- a/ROSCO/src/Controllers.f90 +++ b/ROSCO/src/Controllers.f90 @@ -43,14 +43,6 @@ SUBROUTINE PitchControl(avrSWAP, CntrPar, LocalVar, objInst, DebugVar, ErrVar) CHARACTER(*), PARAMETER :: RoutineName = 'PitchControl' ! Local - REAL(DbKi), PARAMETER :: phi1 = 0.0 ! Phase difference from first to second blade - REAL(DbKi), PARAMETER :: phi2 = 2.0/3.0*PI ! Phase difference from first to second blade - REAL(DbKi), PARAMETER :: phi3 = 4.0/3.0*PI ! Phase difference from first to third blade - REAL(DbKi), DIMENSION(3) :: AWC_angle - COMPLEX(DbKi), DIMENSION(3) :: AWC_complexangle - COMPLEX(DbKi) :: complexI = (0.0, 1.0) - INTEGER(IntKi) :: Imode ! Index used for looping through AWC modes - REAL(DbKi) :: clockang ! Clock angle for AWC pitching ! ------- Blade Pitch Controller -------- ! Load PC State @@ -134,28 +126,11 @@ SUBROUTINE PitchControl(avrSWAP, CntrPar, LocalVar, objInst, DebugVar, ErrVar) ENDIF ENDIF - ! Compute the AWC pitch settings - LocalVar%AWC_complexangle = 0.0D0 - - IF (CntrPar%AWC_NumModes > 0) THEN - LocalVar%PC_MinPit = CntrPar%PC_MinPit + ! Active wake control + IF (CntrPar%AWC_Mode > 0) THEN + CALL ActiveWakeControl(CntrPar, LocalVar) ENDIF - DO Imode = 1,CntrPar%AWC_NumModes - clockang = CntrPar%AWC_clockangle(Imode)*PI/180.0_DbKi - AWC_angle(1) = CntrPar%AWC_omega(Imode) * LocalVar%Time - CntrPar%AWC_n(Imode) * (LocalVar%Azimuth + phi1 + clockang) - AWC_angle(2) = CntrPar%AWC_omega(Imode) * LocalVar%Time - CntrPar%AWC_n(Imode) * (LocalVar%Azimuth + phi2 + clockang) - AWC_angle(3) = CntrPar%AWC_omega(Imode) * LocalVar%Time - CntrPar%AWC_n(Imode) * (LocalVar%Azimuth + phi3 + clockang) - ! Add the forcing contribution to LocalVar%AWC_complexangle - DO K = 1,LocalVar%NumBl ! Loop through all blades - LocalVar%AWC_complexangle(K) = LocalVar%AWC_complexangle(K) + CntrPar%AWC_amp(Imode) * EXP(complexI * (AWC_angle(K))) - END DO - END DO - - DO K = 1,LocalVar%NumBl ! Loop through all blades, apply AWC_angle - LocalVar%PitCom(K) = LocalVar%PitCom(K) + REAL(LocalVar%AWC_complexangle(K)) - END DO - ! Place pitch actuator here, so it can be used with or without open-loop DO K = 1,LocalVar%NumBl ! Loop through all blades, add IPC contribution and limit pitch rate IF (CntrPar%PA_Mode > 0) THEN @@ -636,4 +611,50 @@ SUBROUTINE FlapControl(avrSWAP, CntrPar, LocalVar, objInst) RETURN ENDIF END SUBROUTINE FlapControl + +!------------------------------------------------------------------------------------------------------------------------------- + SUBROUTINE ActiveWakeControl(CntrPar, LocalVar) + ! Yaw rate controller + ! AWC_Mode = 0, No active wake control + ! AWC_Mode = 1, SNL active wake control + USE ROSCO_Types, ONLY : ControlParameters, LocalVariables, ObjectInstances + + TYPE(ControlParameters), INTENT(INOUT) :: CntrPar + TYPE(LocalVariables), INTENT(INOUT) :: LocalVar + + ! Local vars + REAL(DbKi), PARAMETER :: phi1 = 0.0 ! Phase difference from first to second blade + REAL(DbKi), PARAMETER :: phi2 = 2.0/3.0*PI ! Phase difference from first to second blade + REAL(DbKi), PARAMETER :: phi3 = 4.0/3.0*PI ! Phase difference from first to third blade + REAL(DbKi), DIMENSION(3) :: AWC_angle + COMPLEX(DbKi), DIMENSION(3) :: AWC_complexangle + COMPLEX(DbKi) :: complexI = (0.0, 1.0) + INTEGER(IntKi) :: Imode, K ! Index used for looping through AWC modes + REAL(DbKi) :: clockang ! Clock angle for AWC pitching + + + ! Compute the AWC pitch settings + LocalVar%AWC_complexangle = 0.0D0 + + IF (CntrPar%AWC_NumModes > 0) THEN + LocalVar%PC_MinPit = CntrPar%PC_MinPit + ENDIF + + DO Imode = 1,CntrPar%AWC_NumModes + clockang = CntrPar%AWC_clockangle(Imode)*PI/180.0_DbKi + AWC_angle(1) = CntrPar%AWC_omega(Imode) * LocalVar%Time - CntrPar%AWC_n(Imode) * (LocalVar%Azimuth + phi1 + clockang) + AWC_angle(2) = CntrPar%AWC_omega(Imode) * LocalVar%Time - CntrPar%AWC_n(Imode) * (LocalVar%Azimuth + phi2 + clockang) + AWC_angle(3) = CntrPar%AWC_omega(Imode) * LocalVar%Time - CntrPar%AWC_n(Imode) * (LocalVar%Azimuth + phi3 + clockang) + ! Add the forcing contribution to LocalVar%AWC_complexangle + DO K = 1,LocalVar%NumBl ! Loop through all blades + LocalVar%AWC_complexangle(K) = LocalVar%AWC_complexangle(K) + CntrPar%AWC_amp(Imode) * EXP(complexI * (AWC_angle(K))) + END DO + END DO + + DO K = 1,LocalVar%NumBl ! Loop through all blades, apply AWC_angle + LocalVar%PitCom(K) = LocalVar%PitCom(K) + REAL(LocalVar%AWC_complexangle(K)) + END DO + + END SUBROUTINE ActiveWakeControl + END MODULE Controllers diff --git a/ROSCO/src/ROSCO_IO.f90 b/ROSCO/src/ROSCO_IO.f90 index d465d512..f0c20c5d 100644 --- a/ROSCO/src/ROSCO_IO.f90 +++ b/ROSCO/src/ROSCO_IO.f90 @@ -131,6 +131,9 @@ SUBROUTINE WriteRestartFile(LocalVar, CntrPar, ErrVar, objInst, RootName, size_a WRITE( Un, IOSTAT=ErrStat) LocalVar%ACC_INFILE_SIZE WRITE( Un, IOSTAT=ErrStat) LocalVar%ACC_INFILE WRITE( Un, IOSTAT=ErrStat) LocalVar%restart + WRITE( Un, IOSTAT=ErrStat) LocalVar%AWC_complexangle(1) + WRITE( Un, IOSTAT=ErrStat) LocalVar%AWC_complexangle(2) + WRITE( Un, IOSTAT=ErrStat) LocalVar%AWC_complexangle(3) WRITE( Un, IOSTAT=ErrStat) LocalVar%WE%om_r WRITE( Un, IOSTAT=ErrStat) LocalVar%WE%v_t WRITE( Un, IOSTAT=ErrStat) LocalVar%WE%v_m @@ -315,6 +318,9 @@ SUBROUTINE ReadRestartFile(avrSWAP, LocalVar, CntrPar, objInst, PerfData, RootNa ALLOCATE(LocalVar%ACC_INFILE(LocalVar%ACC_INFILE_SIZE)) READ( Un, IOSTAT=ErrStat) LocalVar%ACC_INFILE READ( Un, IOSTAT=ErrStat) LocalVar%restart + READ( Un, IOSTAT=ErrStat) LocalVar%AWC_complexangle(1) + READ( Un, IOSTAT=ErrStat) LocalVar%AWC_complexangle(2) + READ( Un, IOSTAT=ErrStat) LocalVar%AWC_complexangle(3) READ( Un, IOSTAT=ErrStat) LocalVar%WE%om_r READ( Un, IOSTAT=ErrStat) LocalVar%WE%v_t READ( Un, IOSTAT=ErrStat) LocalVar%WE%v_m @@ -442,7 +448,7 @@ SUBROUTINE Debug(LocalVar, CntrPar, DebugVar, ErrVar, avrSWAP, RootName, size_av '[rad/s]', '[rad/s]', '[m/s]', '[rad]', '[rad]', & '[N/A]', '[N/A]', '[N/A]', '[N/A]', '[rad/s]', & '[deg]', '[deg]', '[deg]', '[N/A]'] - nLocalVars = 71 + nLocalVars = 72 Allocate(LocalVarOutData(nLocalVars)) Allocate(LocalVarOutStrings(nLocalVars)) LocalVarOutData(1) = LocalVar%iStatus @@ -516,6 +522,7 @@ SUBROUTINE Debug(LocalVar, CntrPar, DebugVar, ErrVar, avrSWAP, RootName, size_av LocalVarOutData(69) = LocalVar%Flp_Angle(1) LocalVarOutData(70) = LocalVar%RootMyb_Last(1) LocalVarOutData(71) = LocalVar%ACC_INFILE_SIZE + LocalVarOutData(72) = LocalVar%AWC_complexangle(1) LocalVarOutStrings = [CHARACTER(15) :: 'iStatus', 'Time', 'DT', 'VS_GenPwr', 'GenSpeed', & 'RotSpeed', 'NacHeading', 'NacVane', 'HorWindV', 'rootMOOP', & 'rootMOOPF', 'BlPitch', 'BlPitchCMeas', 'Azimuth', 'NumBl', & @@ -530,7 +537,7 @@ SUBROUTINE Debug(LocalVar, CntrPar, DebugVar, ErrVar, avrSWAP, RootName, size_av 'VS_SpdErrAr', 'VS_SpdErrBr', 'VS_SpdErr', 'VS_State', 'VS_Rgn3Pitch', & 'WE_Vw', 'WE_Vw_F', 'WE_VwI', 'WE_VwIdot', 'VS_LastGenTrqF', & 'Fl_PitCom', 'NACIMU_FA_AccF', 'FA_AccF', 'Flp_Angle', 'RootMyb_Last', & - 'ACC_INFILE_SIZE'] + 'ACC_INFILE_SIZE', 'AWC_complexangle'] ! Initialize debug file IF ((LocalVar%iStatus == 0) .OR. (LocalVar%iStatus == -9)) THEN ! .TRUE. if we're on the first call to the DLL IF (CntrPar%LoggingLevel > 0) THEN diff --git a/ROSCO/src/ROSCO_Types.f90 b/ROSCO/src/ROSCO_Types.f90 index 5cb04681..6e1621d3 100644 --- a/ROSCO/src/ROSCO_Types.f90 +++ b/ROSCO/src/ROSCO_Types.f90 @@ -114,6 +114,7 @@ MODULE ROSCO_Types INTEGER(IntKi) :: PA_Mode ! Pitch actuator mode {0 - not used, 1 - first order filter, 2 - second order filter} REAL(DbKi) :: PA_CornerFreq ! Pitch actuator bandwidth/cut-off frequency [rad/s] REAL(DbKi) :: PA_Damping ! Pitch actuator damping ratio [-, unused if PA_Mode = 1] + INTEGER(IntKi) :: AWC_Mode ! Active wake control mode [0 - unused, 1 - SNL method] INTEGER(IntKi) :: AWC_NumModes ! AWC- Number of modes to include [-] INTEGER(IntKi), DIMENSION(:), ALLOCATABLE :: AWC_n ! AWC azimuthal mode [-] REAL(DbKi), DIMENSION(:), ALLOCATABLE :: AWC_omega ! AWC frequency [rad/s] diff --git a/ROSCO/src/ReadSetParameters.f90 b/ROSCO/src/ReadSetParameters.f90 index 5750eb5d..d19c9f01 100644 --- a/ROSCO/src/ReadSetParameters.f90 +++ b/ROSCO/src/ReadSetParameters.f90 @@ -264,6 +264,7 @@ SUBROUTINE ReadControlParameterFileSub(CntrPar, zmqVar, accINFILE, accINFILE_siz CALL ParseInput(UnControllerParameters,CurLine,'OL_Mode',accINFILE(1),CntrPar%OL_Mode,ErrVar) CALL ParseInput(UnControllerParameters,CurLine,'PA_Mode',accINFILE(1),CntrPar%PA_Mode,ErrVar) CALL ParseInput(UnControllerParameters,CurLine,'PF_Mode',accINFILE(1),CntrPar%PF_Mode,ErrVar) + CALL ParseInput(UnControllerParameters,CurLine,'AWC_Mode',accINFILE(1),CntrPar%AWC_Mode,ErrVar) CALL ParseInput(UnControllerParameters,CurLine,'Ext_Mode',accINFILE(1),CntrPar%Ext_Mode,ErrVar) CALL ParseInput(UnControllerParameters,CurLine,'ZMQ_Mode',accINFILE(1), CntrPar%ZMQ_Mode,ErrVar) diff --git a/ROSCO_toolbox/utilities.py b/ROSCO_toolbox/utilities.py index 04cf98f3..26c8cb05 100644 --- a/ROSCO_toolbox/utilities.py +++ b/ROSCO_toolbox/utilities.py @@ -84,6 +84,7 @@ def write_DISCON(turbine, controller, param_file='DISCON.IN', txt_filename='Cp_C file.write('{0:<12d} ! OL_Mode - Open loop control mode {{0: no open loop control, 1: open loop control vs. time}}\n'.format(int(rosco_vt['OL_Mode']))) file.write('{0:<12d} ! PA_Mode - Pitch actuator mode {{0 - not used, 1 - first order filter, 2 - second order filter}}\n'.format(int(rosco_vt['PA_Mode']))) file.write('{0:<12d} ! PF_Mode - Pitch fault mode {{0 - not used, 1 - constant offset on one or more blades}}\n'.format(int(rosco_vt['PF_Mode']))) + file.write('{0:<12d} ! AWC_Mode - Active wake control {{0 - not used, 1 - SNL method}}\n'.format(int(rosco_vt['AWC_Mode']))) file.write('{0:<12d} ! Ext_Mode - External control mode {{0 - not used, 1 - call external dynamic library}}\n'.format(int(rosco_vt['Ext_Mode']))) file.write('{0:<12d} ! ZMQ_Mode - Fuse ZeroMQ interface {{0: unused, 1: Yaw Control}}\n'.format(int(rosco_vt['ZMQ_Mode']))) @@ -209,6 +210,13 @@ def write_DISCON(turbine, controller, param_file='DISCON.IN', txt_filename='Cp_C file.write('!------- Pitch Actuator Faults -----------------------------------------------------\n') file.write('{} ! PF_Offsets - Constant blade pitch offsets for blades 1-3 [rad]\n'.format(''.join('{:<10.8f} '.format(rosco_vt['PF_Offsets'][i]) for i in range(3)))) file.write('\n') + file.write('!------- Active Wake Control -----------------------------------------------------\n') + file.write('{0:<12d} ! AWC_NumModes - \n'.format(int(rosco_vt['AWC_NumModes']))) + file.write('{} ! AWC_n - AWC azimuthal number\n'.format(write_array(rosco_vt['AWC_n'],'<4d'))) + file.write('{} ! AWC_omega - AWC frequency [rad/s]\n'.format(write_array(rosco_vt['AWC_omega'],'<6.4f'))) + file.write('{} ! AWC_amp - AWC amplitude [rad]\n'.format(write_array(rosco_vt['AWC_amp'],'<6.4f'))) + file.write('{} ! AWC_clockangle - WC clock angle [deg]\n'.format(write_array(rosco_vt['AWC_clockangle'],'<6.4f'))) + file.write('\n') file.write('!------- External Controller Interface -----------------------------------------------------\n') file.write('"{}" ! DLL_FileName - Name/location of the dynamic library in the Bladed-DLL format\n'.format(rosco_vt['DLL_FileName'])) file.write('"{}" ! DLL_InFile - Name of input file sent to the DLL (-)\n'.format(rosco_vt['DLL_InFile'])) @@ -611,3 +619,10 @@ def list_check(x, return_bool=True): return is_list else: return y + +def write_array(array,format='<.4f'): + + if not hasattr(array,'len'): #not an array + array = [array] + + return ''.join(['{:{}} '.format(item,format) for item in array]) From b102b34d2338b2d1838cfa4df0f35e9cf7d0f309 Mon Sep 17 00:00:00 2001 From: dzalkind Date: Fri, 10 Feb 2023 15:23:36 -0700 Subject: [PATCH 031/224] Update example to point to correct inputs --- Examples/20_active_wake_control.py | 4 ++-- Test_Cases/NREL_2p8_127/NREL-2p8-127_DISCON.IN | 3 ++- 2 files changed, 4 insertions(+), 3 deletions(-) diff --git a/Examples/20_active_wake_control.py b/Examples/20_active_wake_control.py index ff5350bf..3fb1a046 100644 --- a/Examples/20_active_wake_control.py +++ b/Examples/20_active_wake_control.py @@ -32,8 +32,8 @@ def main(): # Input yaml and output directory - parameter_filename = os.path.join(rosco_dir,'Tune_Cases/IEA15MW.yaml') # will be dummy and overwritten with SNL DISCON - run_dir = os.path.join(example_out_dir,'20_active_wake_control') + parameter_filename = os.path.join(rosco_dir,'Tune_Cases/NREL2p8.yaml') # will be dummy and overwritten with SNL DISCON + run_dir = os.path.join(example_out_dir,'20_active_wake_control/setup_2') os.makedirs(run_dir,exist_ok=True) # Read all inputs diff --git a/Test_Cases/NREL_2p8_127/NREL-2p8-127_DISCON.IN b/Test_Cases/NREL_2p8_127/NREL-2p8-127_DISCON.IN index e2bd1347..fc0ef6a1 100644 --- a/Test_Cases/NREL_2p8_127/NREL-2p8-127_DISCON.IN +++ b/Test_Cases/NREL_2p8_127/NREL-2p8-127_DISCON.IN @@ -2,7 +2,7 @@ ! - File written using ROSCO version 2.3.0 controller tuning logic on 07/01/21 !------- 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} +2 ! 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 @@ -21,6 +21,7 @@ 0 ! OL_Mode - Open loop control mode {0: no open loop control, 1: open loop control vs. time} 0 ! PA_Mode - Pitch actuator mode {0 - not used, 1 - first order filter, 2 - second order filter} 0 ! PF_Mode - Pitch fault mode {0 - not used, 1 - constant offset on one or more blades} +1 ! AWC_Mode - Active wake control {0 - not used, 1 - SNL method} 0 ! Ext_Mode - External control mode {0 - not used, 1 - call external dynamic library} 0 ! ZMQ_Mode - Fuse ZeroMQ interface {0: unused, 1: Yaw Control} From 5c5333b12be1de5b4f32eb8a57eac497c3a013a2 Mon Sep 17 00:00:00 2001 From: dzalkind Date: Fri, 10 Feb 2023 15:57:03 -0700 Subject: [PATCH 032/224] Remove LocalVar%PC_MinPit = CntrPar%PC_MinPit, breaking setpoint smoother --- ROSCO/src/Controllers.f90 | 7 ------- 1 file changed, 7 deletions(-) diff --git a/ROSCO/src/Controllers.f90 b/ROSCO/src/Controllers.f90 index 4671e224..f20dd648 100644 --- a/ROSCO/src/Controllers.f90 +++ b/ROSCO/src/Controllers.f90 @@ -160,11 +160,8 @@ SUBROUTINE PitchControl(avrSWAP, CntrPar, LocalVar, objInst, DebugVar, ErrVar) END DO END IF - !WRITE (*,*) 'PITCH ANGLE PRE AWC = ',REAL(LocalVar%PitComAct(1)) - ! Command the pitch demanded from the last ! call to the controller (See Appendix A of Bladed User's Guide): - ! AWC added here as well avrSWAP(42) = LocalVar%PitComAct(1) ! Use the command angles of all blades if using individual pitch avrSWAP(43) = LocalVar%PitComAct(2) ! " avrSWAP(44) = LocalVar%PitComAct(3) ! " @@ -636,10 +633,6 @@ SUBROUTINE ActiveWakeControl(CntrPar, LocalVar) ! Compute the AWC pitch settings LocalVar%AWC_complexangle = 0.0D0 - IF (CntrPar%AWC_NumModes > 0) THEN - LocalVar%PC_MinPit = CntrPar%PC_MinPit - ENDIF - DO Imode = 1,CntrPar%AWC_NumModes clockang = CntrPar%AWC_clockangle(Imode)*PI/180.0_DbKi AWC_angle(1) = CntrPar%AWC_omega(Imode) * LocalVar%Time - CntrPar%AWC_n(Imode) * (LocalVar%Azimuth + phi1 + clockang) From da46fac3110e5c3e03908025c61df95292d84214 Mon Sep 17 00:00:00 2001 From: dzalkind Date: Fri, 10 Feb 2023 15:57:10 -0700 Subject: [PATCH 033/224] Set min pitch for AWC --- Test_Cases/NREL_2p8_127/NREL-2p8-127_DISCON.IN | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Test_Cases/NREL_2p8_127/NREL-2p8-127_DISCON.IN b/Test_Cases/NREL_2p8_127/NREL-2p8-127_DISCON.IN index fc0ef6a1..7f05d65e 100644 --- a/Test_Cases/NREL_2p8_127/NREL-2p8-127_DISCON.IN +++ b/Test_Cases/NREL_2p8_127/NREL-2p8-127_DISCON.IN @@ -45,7 +45,7 @@ 0.0 0.0 0.0 0.0 0.0 0.0 0.0 0.0 0.0 0.0 0.0 0.0 0.0 0.0 0.0 0.0 0.0 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 ! PC_GS_TF - Gain-schedule table: pitch controller tf gains (derivative filter) 1.570000000000 ! PC_MaxPit - Maximum physical pitch limit, [rad]. -0.000000000000 ! PC_MinPit - Minimum physical pitch limit, [rad]. +-0.17453290000 ! PC_MinPit - Minimum physical pitch limit, [rad]. 0.122170000000 ! PC_MaxRat - Maximum pitch rate (in absolute value) in pitch controller, [rad/s]. -0.12217000000 ! PC_MinRat - Minimum pitch rate (in absolute value) in pitch controller, [rad/s]. 122.2879500000 ! PC_RefSpd - Desired (reference) HSS speed for pitch controller, [rad/s]. From cc4080d037a6919aacefaefffccf14175384dfef Mon Sep 17 00:00:00 2001 From: dzalkind Date: Fri, 10 Feb 2023 16:09:33 -0700 Subject: [PATCH 034/224] Tidy up input additions --- ROSCO_toolbox/controller.py | 1 + ROSCO_toolbox/utilities.py | 2 +- 2 files changed, 2 insertions(+), 1 deletion(-) diff --git a/ROSCO_toolbox/controller.py b/ROSCO_toolbox/controller.py index f7cae56a..9771710f 100644 --- a/ROSCO_toolbox/controller.py +++ b/ROSCO_toolbox/controller.py @@ -65,6 +65,7 @@ def __init__(self, controller_params): self.Flp_Mode = controller_params['Flp_Mode'] self.PA_Mode = controller_params['PA_Mode'] self.PF_Mode = controller_params['PF_Mode'] + self.AWC_Mode = controller_params['AWC_Mode'] self.Ext_Mode = controller_params['Ext_Mode'] self.ZMQ_Mode = controller_params['ZMQ_Mode'] diff --git a/ROSCO_toolbox/utilities.py b/ROSCO_toolbox/utilities.py index 26c8cb05..160f92a3 100644 --- a/ROSCO_toolbox/utilities.py +++ b/ROSCO_toolbox/utilities.py @@ -622,7 +622,7 @@ def list_check(x, return_bool=True): def write_array(array,format='<.4f'): - if not hasattr(array,'len'): #not an array + if not hasattr(array,'__len__'): #not an array array = [array] return ''.join(['{:{}} '.format(item,format) for item in array]) From 1201a66722b63eec805a580c2a8c064750840f19 Mon Sep 17 00:00:00 2001 From: dzalkind Date: Fri, 10 Feb 2023 16:09:49 -0700 Subject: [PATCH 035/224] Update other DISCONs --- Test_Cases/BAR_10/BAR_10_DISCON.IN | 10 +++++++++- .../IEA-15-240-RWT-UMaineSemi/DISCON-UMaineSemi.IN | 10 +++++++++- Test_Cases/NREL-5MW/DISCON.IN | 10 +++++++++- 3 files changed, 27 insertions(+), 3 deletions(-) diff --git a/Test_Cases/BAR_10/BAR_10_DISCON.IN b/Test_Cases/BAR_10/BAR_10_DISCON.IN index 17875c9c..3bc20e2d 100644 --- a/Test_Cases/BAR_10/BAR_10_DISCON.IN +++ b/Test_Cases/BAR_10/BAR_10_DISCON.IN @@ -1,5 +1,5 @@ ! Controller parameter input file for the BAR_10 wind turbine -! - File written using ROSCO version 2.7.0 controller tuning logic on 02/06/23 +! - File written using ROSCO version 2.7.0 controller tuning logic on 02/10/23 !------- DEBUG ------------------------------------------------------------ 1 ! LoggingLevel - {0: write no debug files, 1: write standard output .dbg-file, 2: LoggingLevel 1 + ROSCO LocalVars (.dbg2) 3: LoggingLevel 2 + complete avrSWAP-array (.dbg3)} @@ -21,6 +21,7 @@ 0 ! OL_Mode - Open loop control mode {0: no open loop control, 1: open loop control vs. time} 0 ! PA_Mode - Pitch actuator mode {0 - not used, 1 - first order filter, 2 - second order filter} 0 ! PF_Mode - Pitch fault mode {0 - not used, 1 - constant offset on one or more blades} +0 ! AWC_Mode - Active wake control {0 - not used, 1 - SNL method} 0 ! Ext_Mode - External control mode {0 - not used, 1 - call external dynamic library} 0 ! ZMQ_Mode - Fuse ZeroMQ interface {0: unused, 1: Yaw Control} @@ -140,6 +141,13 @@ !------- Pitch Actuator Faults ----------------------------------------------------- 0.00000000 0.00000000 0.00000000 ! PF_Offsets - Constant blade pitch offsets for blades 1-3 [rad] +!------- Active Wake Control ----------------------------------------------------- +1 ! AWC_NumModes - +1 ! AWC_n - AWC azimuthal number +0.3142 ! AWC_omega - AWC frequency [rad/s] +0.0175 ! AWC_amp - AWC amplitude [rad] +0.0000 ! AWC_clockangle - WC clock angle [deg] + !------- External Controller Interface ----------------------------------------------------- "unused" ! DLL_FileName - Name/location of the dynamic library in the Bladed-DLL format "unused" ! DLL_InFile - Name of input file sent to the DLL (-) diff --git a/Test_Cases/IEA-15-240-RWT-UMaineSemi/DISCON-UMaineSemi.IN b/Test_Cases/IEA-15-240-RWT-UMaineSemi/DISCON-UMaineSemi.IN index 5f55c5ab..811c3b2a 100644 --- a/Test_Cases/IEA-15-240-RWT-UMaineSemi/DISCON-UMaineSemi.IN +++ b/Test_Cases/IEA-15-240-RWT-UMaineSemi/DISCON-UMaineSemi.IN @@ -1,5 +1,5 @@ ! Controller parameter input file for the IEA-15-240-RWT-UMaineSemi wind turbine -! - File written using ROSCO version 2.7.0 controller tuning logic on 02/06/23 +! - File written using ROSCO version 2.7.0 controller tuning logic on 02/10/23 !------- DEBUG ------------------------------------------------------------ 2 ! LoggingLevel - {0: write no debug files, 1: write standard output .dbg-file, 2: LoggingLevel 1 + ROSCO LocalVars (.dbg2) 3: LoggingLevel 2 + complete avrSWAP-array (.dbg3)} @@ -21,6 +21,7 @@ 0 ! OL_Mode - Open loop control mode {0: no open loop control, 1: open loop control vs. time} 2 ! PA_Mode - Pitch actuator mode {0 - not used, 1 - first order filter, 2 - second order filter} 0 ! PF_Mode - Pitch fault mode {0 - not used, 1 - constant offset on one or more blades} +0 ! AWC_Mode - Active wake control {0 - not used, 1 - SNL method} 0 ! Ext_Mode - External control mode {0 - not used, 1 - call external dynamic library} 0 ! ZMQ_Mode - Fuse ZeroMQ interface {0: unused, 1: Yaw Control} @@ -140,6 +141,13 @@ !------- Pitch Actuator Faults ----------------------------------------------------- 0.00000000 0.00000000 0.00000000 ! PF_Offsets - Constant blade pitch offsets for blades 1-3 [rad] +!------- Active Wake Control ----------------------------------------------------- +1 ! AWC_NumModes - +1 ! AWC_n - AWC azimuthal number +0.3142 ! AWC_omega - AWC frequency [rad/s] +0.0175 ! AWC_amp - AWC amplitude [rad] +0.0000 ! AWC_clockangle - WC clock angle [deg] + !------- External Controller Interface ----------------------------------------------------- "unused" ! DLL_FileName - Name/location of the dynamic library in the Bladed-DLL format "unused" ! DLL_InFile - Name of input file sent to the DLL (-) diff --git a/Test_Cases/NREL-5MW/DISCON.IN b/Test_Cases/NREL-5MW/DISCON.IN index e3c2ae45..e0d1118d 100644 --- a/Test_Cases/NREL-5MW/DISCON.IN +++ b/Test_Cases/NREL-5MW/DISCON.IN @@ -1,5 +1,5 @@ ! Controller parameter input file for the NREL-5MW wind turbine -! - File written using ROSCO version 2.7.0 controller tuning logic on 02/06/23 +! - File written using ROSCO version 2.7.0 controller tuning logic on 02/10/23 !------- DEBUG ------------------------------------------------------------ 1 ! LoggingLevel - {0: write no debug files, 1: write standard output .dbg-file, 2: LoggingLevel 1 + ROSCO LocalVars (.dbg2) 3: LoggingLevel 2 + complete avrSWAP-array (.dbg3)} @@ -21,6 +21,7 @@ 0 ! OL_Mode - Open loop control mode {0: no open loop control, 1: open loop control vs. time} 0 ! PA_Mode - Pitch actuator mode {0 - not used, 1 - first order filter, 2 - second order filter} 0 ! PF_Mode - Pitch fault mode {0 - not used, 1 - constant offset on one or more blades} +0 ! AWC_Mode - Active wake control {0 - not used, 1 - SNL method} 0 ! Ext_Mode - External control mode {0 - not used, 1 - call external dynamic library} 0 ! ZMQ_Mode - Fuse ZeroMQ interface {0: unused, 1: Yaw Control} @@ -140,6 +141,13 @@ !------- Pitch Actuator Faults ----------------------------------------------------- 0.00000000 0.00000000 0.00000000 ! PF_Offsets - Constant blade pitch offsets for blades 1-3 [rad] +!------- Active Wake Control ----------------------------------------------------- +1 ! AWC_NumModes - +1 ! AWC_n - AWC azimuthal number +0.3142 ! AWC_omega - AWC frequency [rad/s] +0.0175 ! AWC_amp - AWC amplitude [rad] +0.0000 ! AWC_clockangle - WC clock angle [deg] + !------- External Controller Interface ----------------------------------------------------- "unused" ! DLL_FileName - Name/location of the dynamic library in the Bladed-DLL format "unused" ! DLL_InFile - Name of input file sent to the DLL (-) From 1693602fb0297076e582208ed0cf0d1e6936331d Mon Sep 17 00:00:00 2001 From: dzalkind Date: Fri, 10 Feb 2023 16:10:02 -0700 Subject: [PATCH 036/224] Add AWC to toolbox schema --- ROSCO_toolbox/inputs/toolbox_schema.yaml | 44 ++++++++++++++++++++++++ 1 file changed, 44 insertions(+) diff --git a/ROSCO_toolbox/inputs/toolbox_schema.yaml b/ROSCO_toolbox/inputs/toolbox_schema.yaml index 432785df..594e89f5 100644 --- a/ROSCO_toolbox/inputs/toolbox_schema.yaml +++ b/ROSCO_toolbox/inputs/toolbox_schema.yaml @@ -203,6 +203,12 @@ properties: maximum: 1 default: 0 description: Pitch fault mode {0 - not used, 1 - constant offset on one or more blades} + AWC_Mode: + type: number + minimum: 0 + maximum: 1 + default: 0 + description: Active wake control mode {0 - not used, 1 - SNL method} Ext_Mode: type: number minimum: 0 @@ -864,6 +870,44 @@ properties: type: number description: Pitch angle offsets for each blade (array with length of 3) units: rad + AWC_Mode: + type: number + minimum: 0 + maximum: 1 + default: 0 + description: Active wake control mode {0 - not used, 1 - SNL method} + AWC_NumModes: + type: number + description: Number of AWC modes + units: rad + default: 1 + AWC_n: + type: array + items: + type: number + description: AWC azimuthal number + default: [1] + AWC_omega: + type: array + items: + type: number + description: AWC frequency [rad/s] + units: rad/s + default: [0.314159] + AWC_amp: + type: array + items: + type: number + description: AWC amplitude [rad] + units: rad/s + default: [0.017453292] + AWC_clockangle: + type: array + items: + type: number + description: AWC clock angle [deg] + units: rad/s + default: [0] linmodel_tuning: type: object From 2bb01760d9c7f92cde065e305eda1529c2b0072e Mon Sep 17 00:00:00 2001 From: dzalkind Date: Fri, 10 Feb 2023 16:12:22 -0700 Subject: [PATCH 037/224] Tidy example --- Examples/20_active_wake_control.py | 13 ++++++------- 1 file changed, 6 insertions(+), 7 deletions(-) diff --git a/Examples/20_active_wake_control.py b/Examples/20_active_wake_control.py index 3fb1a046..3c0552da 100644 --- a/Examples/20_active_wake_control.py +++ b/Examples/20_active_wake_control.py @@ -32,13 +32,14 @@ def main(): # Input yaml and output directory - parameter_filename = os.path.join(rosco_dir,'Tune_Cases/NREL2p8.yaml') # will be dummy and overwritten with SNL DISCON - run_dir = os.path.join(example_out_dir,'20_active_wake_control/setup_2') + parameter_filename = os.path.join(rosco_dir,'Tune_Cases/NREL2p8.yaml') # will be dummy and overwritten with SNL DISCON params + run_dir = os.path.join(example_out_dir,'20_active_wake_control/setup_4') os.makedirs(run_dir,exist_ok=True) - # Read all inputs - rosco_vt = read_DISCON('/Users/dzalkind/Tools/ROSCO3/Test_Cases/NREL_2p8_127/NREL-2p8-127_DISCON.IN') + # Read all DISCON inputs + rosco_vt = read_DISCON(os.path.join(rosco_dir,'TestCases','NREL_2p8_127/NREL-2p8-127_DISCON.IN')) + # Could change discon parameters here # Apply all discon variables as case inputs @@ -62,9 +63,7 @@ def main(): r.run_FAST() - - print('here') - # # Check pitch offsets + # # Check AWC here # filenames = [os.path.join(run_dir,'IEA15MW/simp_step/base/IEA15MW_0.outb')] # fast_out = output_processing.output_processing() From d93d443215f36837635753d6f5deb14fa1aaa8b4 Mon Sep 17 00:00:00 2001 From: Nate deVelder Date: Tue, 14 Feb 2023 10:14:37 -0700 Subject: [PATCH 038/224] Update AWC example with instructions/theory --- Examples/20_active_wake_control.py | 80 +++++++++++++++++++++++++++++- 1 file changed, 79 insertions(+), 1 deletion(-) diff --git a/Examples/20_active_wake_control.py b/Examples/20_active_wake_control.py index 3c0552da..54d74058 100644 --- a/Examples/20_active_wake_control.py +++ b/Examples/20_active_wake_control.py @@ -5,6 +5,84 @@ Set up and run simulation with AWC, check outputs +Active wake control with blade pitching is implemented in this example with an adaptation into the rotating frame of the mathematical framework from the classical theory for stability of axisymmetric jets [1], which offers flexibility in specifying the forcing strategy. + +The inputs to the controller are: + -AWC_NumModes (-) -> number of forcing modes + -AWC_n (-) -> azimuthal mode number(s) (i.e., the azimuthal mode number relates to the number and direction of the lobes of the wake structure) + -AWC_clockangle (deg) -> clocking angle of forcing mode(s) + -AWC_omega (rad/s) -> frequency(s) of forcing mode(s) + -AWC_amp (rad) -> pitch amplitude(s) of forcing mode(s) + +The latter two inputs may be specified based on the expected inflow while the former three inputs determine the type of active wake control to be used. + +Readers may be familiar with several forcing strategies from literature on active wake control that can be represented as follows: + -collective dynamic induction control: AWC_NumModes = 1, AWC_n = 0, AWC_clockangle = 0 + -helix clockwise: AWC_NumModes = 1, AWC_n = 1, AWC_clockangle = 0 + -helix counter-clockwise: AWC_NumModes = 1, AWC_n = -1, AWC_clockangle = 0 + -up-and-down: AWC_NumModes = 2, AWC_n = -1 1, AWC_clockangle = 0 0 + -side-to-side: AWC_NumModes = 2, AWC_n = -1 1, AWC_clockangle = 90 90 + -other: Higher-order modes or different combinations of the above can also be specified + + Calculation methodology: + For each blade, we compute the total phase angle of blade pitch excursion according to: + AWC_angle(t) = AWC_omega * t - AWC_n * (psi(t) + phi + AWC_clockangle*PI/180) (eq 1) + where t is time + phi(t) is the angular offset of the given blade in the rotor plane relative to blade 1 + psi is the angle of blade 1 in the rotor plane from top-dead center + + Next, the phase angle is converted into the complex pitch amplitude: + AWC_complexangle(t) = AWC_amp * EXP(i * AWC_angle(t)) (eq 2) + where i is the square root of -1 + + Note that if AWC_NumModes>1, then eq 1 and 2 are computed for each additional mode, and AWC_complexangle becomes a summation over all modes for each blade. + + Finally, the real pitch amplitude, theta(t), to be passed to the next step of the controller is calculated: + theta(t) = theta_0(t) + REAL(AWC_complexangle(t)) (eq 3) + where theta_0(t) is the controller's nominal pitch command + + Rearranging for ease of viewing: + Inserting eq 1 into eq 2, and then putting that result into eq 3 gives: + theta(t) = theta_0(t) + REAL(AWC_amp * EXP(i * (AWC_omega * t - AWC_n * (psi(t) + phi + AWC_clockangle*PI/180)))) (eq 4) + + Applying Euler's formula and carrying out the REAL operator: + theta(t) = theta_0(t) + AWC_amp * cos(AWC_omega * t - AWC_n * (psi(t) + phi + AWC_clockangle*PI/180)) (eq 5) + + As an example, we can set parameters to produce the counter-clockwise helix pattern from [2] using AWC_NumModes = 1, AWC_n = -1, and AWC_clockangle = 0: + For blade 1, eq 5 becomes: + theta(t) = theta_0(t) + AWC_amp * cos(AWC_omega * t + psi(t)) (eq 6) + +Note that the inverse multi-blade coordinate (MBC) transformation can also be used to obtain the same result as eq 6. + Beginning with Eq. 3 from [2], we have + + / \ / \ + | theta_1(t) | | theta_0(t) | + | theta_2(t) | = T^-1(psi(t)) * | theta_tilt(t) | (eq 7) + | theta_3(t) | | theta_yaw(t) | + \ / \ / + + where + + / \ + | 1 cos(psi_1(t)) sin(psi_1(t)) | + T^-1(psi(t)) = | 1 cos(psi_2(t)) sin(psi_2(t)) | + | 1 cos(psi_3(t)) sin(psi_3(t)) | + \ / + + Multiplying the first row of the top matrix (and dropping the subscript of blade 1) yields: + theta(t) = theta_0(t) + theta_tilt(t)*cos(psi(t)) + theta_yaw(t)*sin(psi(t)) (eq 8) + + Setting theta_tilt(t) = AWC_amp * cos(AWC_omega * t) and theta_yaw(t) = -AWC_amp * sin(AWC_omega * t) gives: + theta(t) = theta_0(t) + (AWC_amp * cos(AWC_omega * t))*cos(psi(t)) - (AWC_amp * sin(AWC_omega * t))*sin(psi(t)) (eq 9) + + Applying a Ptolemy identity gives: + theta(t) = theta_0(t) + AWC_amp * cos(AWC_omega * t + psi(t)) (eq 10) + which is equivlanet to eq 6 above. + +References: +[1] - Batchelor, G. K., and A. E. Gill. "Analysis of the stability of axisymmetric jets." Journal of fluid mechanics 14.4 (1962): 529-551. +[2] - Frederik, Joeri A., et al. "The helix approach: Using dynamic individual pitch control to enhance wake mixing in wind farms." Wind Energy 23.8 (2020): 1739-1751. + ''' import os, platform @@ -81,4 +159,4 @@ def main(): if __name__=="__main__": - main() \ No newline at end of file + main() From 3c40565ea35888e0fe6038060b6a78dbb77987c8 Mon Sep 17 00:00:00 2001 From: Nate deVelder Date: Tue, 14 Feb 2023 10:16:37 -0700 Subject: [PATCH 039/224] Formatting fixes --- Examples/20_active_wake_control.py | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/Examples/20_active_wake_control.py b/Examples/20_active_wake_control.py index 54d74058..b76232a4 100644 --- a/Examples/20_active_wake_control.py +++ b/Examples/20_active_wake_control.py @@ -55,7 +55,7 @@ Note that the inverse multi-blade coordinate (MBC) transformation can also be used to obtain the same result as eq 6. Beginning with Eq. 3 from [2], we have - / \ / \ + / \ / \ | theta_1(t) | | theta_0(t) | | theta_2(t) | = T^-1(psi(t)) * | theta_tilt(t) | (eq 7) | theta_3(t) | | theta_yaw(t) | @@ -63,11 +63,11 @@ where - / \ + / \ | 1 cos(psi_1(t)) sin(psi_1(t)) | T^-1(psi(t)) = | 1 cos(psi_2(t)) sin(psi_2(t)) | - | 1 cos(psi_3(t)) sin(psi_3(t)) | - \ / + | 1 cos(psi_3(t)) sin(psi_3(t)) | + \ / Multiplying the first row of the top matrix (and dropping the subscript of blade 1) yields: theta(t) = theta_0(t) + theta_tilt(t)*cos(psi(t)) + theta_yaw(t)*sin(psi(t)) (eq 8) From 83022e586d881044db87346551f50afd73a8098f Mon Sep 17 00:00:00 2001 From: dzalkind Date: Wed, 15 Feb 2023 08:57:10 -0700 Subject: [PATCH 040/224] Prep for more modes --- ROSCO/src/Controllers.f90 | 34 +++++++++++++++++++--------------- 1 file changed, 19 insertions(+), 15 deletions(-) diff --git a/ROSCO/src/Controllers.f90 b/ROSCO/src/Controllers.f90 index f20dd648..41720b0d 100644 --- a/ROSCO/src/Controllers.f90 +++ b/ROSCO/src/Controllers.f90 @@ -631,22 +631,26 @@ SUBROUTINE ActiveWakeControl(CntrPar, LocalVar) ! Compute the AWC pitch settings - LocalVar%AWC_complexangle = 0.0D0 - - DO Imode = 1,CntrPar%AWC_NumModes - clockang = CntrPar%AWC_clockangle(Imode)*PI/180.0_DbKi - AWC_angle(1) = CntrPar%AWC_omega(Imode) * LocalVar%Time - CntrPar%AWC_n(Imode) * (LocalVar%Azimuth + phi1 + clockang) - AWC_angle(2) = CntrPar%AWC_omega(Imode) * LocalVar%Time - CntrPar%AWC_n(Imode) * (LocalVar%Azimuth + phi2 + clockang) - AWC_angle(3) = CntrPar%AWC_omega(Imode) * LocalVar%Time - CntrPar%AWC_n(Imode) * (LocalVar%Azimuth + phi3 + clockang) - ! Add the forcing contribution to LocalVar%AWC_complexangle - DO K = 1,LocalVar%NumBl ! Loop through all blades - LocalVar%AWC_complexangle(K) = LocalVar%AWC_complexangle(K) + CntrPar%AWC_amp(Imode) * EXP(complexI * (AWC_angle(K))) - END DO - END DO + IF (CntrPar%AWC_Mode == 1) THEN + + LocalVar%AWC_complexangle = 0.0D0 + + DO Imode = 1,CntrPar%AWC_NumModes + clockang = CntrPar%AWC_clockangle(Imode)*PI/180.0_DbKi + AWC_angle(1) = CntrPar%AWC_omega(Imode) * LocalVar%Time - CntrPar%AWC_n(Imode) * (LocalVar%Azimuth + phi1 + clockang) + AWC_angle(2) = CntrPar%AWC_omega(Imode) * LocalVar%Time - CntrPar%AWC_n(Imode) * (LocalVar%Azimuth + phi2 + clockang) + AWC_angle(3) = CntrPar%AWC_omega(Imode) * LocalVar%Time - CntrPar%AWC_n(Imode) * (LocalVar%Azimuth + phi3 + clockang) + ! Add the forcing contribution to LocalVar%AWC_complexangle + DO K = 1,LocalVar%NumBl ! Loop through all blades + LocalVar%AWC_complexangle(K) = LocalVar%AWC_complexangle(K) + CntrPar%AWC_amp(Imode) * EXP(complexI * (AWC_angle(K))) + END DO + END DO - DO K = 1,LocalVar%NumBl ! Loop through all blades, apply AWC_angle - LocalVar%PitCom(K) = LocalVar%PitCom(K) + REAL(LocalVar%AWC_complexangle(K)) - END DO + DO K = 1,LocalVar%NumBl ! Loop through all blades, apply AWC_angle + LocalVar%PitCom(K) = LocalVar%PitCom(K) + REAL(LocalVar%AWC_complexangle(K)) + END DO + + ENDIF END SUBROUTINE ActiveWakeControl From f6d061f879d55f62f5efc45932b9de47069b4b7a Mon Sep 17 00:00:00 2001 From: kbrown1snl <66843135+kbrown1snl@users.noreply.github.com> Date: Thu, 16 Feb 2023 09:00:51 -0700 Subject: [PATCH 041/224] Update 20_active_wake_control.py --- Examples/20_active_wake_control.py | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/Examples/20_active_wake_control.py b/Examples/20_active_wake_control.py index b76232a4..7390800f 100644 --- a/Examples/20_active_wake_control.py +++ b/Examples/20_active_wake_control.py @@ -18,8 +18,8 @@ Readers may be familiar with several forcing strategies from literature on active wake control that can be represented as follows: -collective dynamic induction control: AWC_NumModes = 1, AWC_n = 0, AWC_clockangle = 0 - -helix clockwise: AWC_NumModes = 1, AWC_n = 1, AWC_clockangle = 0 - -helix counter-clockwise: AWC_NumModes = 1, AWC_n = -1, AWC_clockangle = 0 + -helix clockwise [2]: AWC_NumModes = 1, AWC_n = 1, AWC_clockangle = 0 + -helix counter-clockwise [2]: AWC_NumModes = 1, AWC_n = -1, AWC_clockangle = 0 -up-and-down: AWC_NumModes = 2, AWC_n = -1 1, AWC_clockangle = 0 0 -side-to-side: AWC_NumModes = 2, AWC_n = -1 1, AWC_clockangle = 90 90 -other: Higher-order modes or different combinations of the above can also be specified From 1824f991a7263cf0df46fadbfbc4b41c09fbb6ae Mon Sep 17 00:00:00 2001 From: dzalkind Date: Thu, 16 Feb 2023 15:04:04 -0700 Subject: [PATCH 042/224] Fix units in schema --- ROSCO_toolbox/inputs/toolbox_schema.yaml | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/ROSCO_toolbox/inputs/toolbox_schema.yaml b/ROSCO_toolbox/inputs/toolbox_schema.yaml index 594e89f5..2a851f36 100644 --- a/ROSCO_toolbox/inputs/toolbox_schema.yaml +++ b/ROSCO_toolbox/inputs/toolbox_schema.yaml @@ -899,14 +899,14 @@ properties: items: type: number description: AWC amplitude [rad] - units: rad/s + units: rad default: [0.017453292] AWC_clockangle: type: array items: type: number description: AWC clock angle [deg] - units: rad/s + units: deg default: [0] linmodel_tuning: From de16ecdda411adab263f6e26eefff2320360fa84 Mon Sep 17 00:00:00 2001 From: dzalkind Date: Fri, 17 Feb 2023 14:48:48 -0700 Subject: [PATCH 043/224] Test all AWC cases in example 20 --- Examples/20_active_wake_control.py | 17 ++++++++++------- 1 file changed, 10 insertions(+), 7 deletions(-) diff --git a/Examples/20_active_wake_control.py b/Examples/20_active_wake_control.py index 7390800f..e120bdbc 100644 --- a/Examples/20_active_wake_control.py +++ b/Examples/20_active_wake_control.py @@ -111,21 +111,24 @@ def main(): # Input yaml and output directory parameter_filename = os.path.join(rosco_dir,'Tune_Cases/NREL2p8.yaml') # will be dummy and overwritten with SNL DISCON params - run_dir = os.path.join(example_out_dir,'20_active_wake_control/setup_4') + run_dir = os.path.join(example_out_dir,'20_active_wake_control/all_cases') os.makedirs(run_dir,exist_ok=True) # Read all DISCON inputs - rosco_vt = read_DISCON(os.path.join(rosco_dir,'TestCases','NREL_2p8_127/NREL-2p8-127_DISCON.IN')) - - # Could change discon parameters here - + rosco_vt = read_DISCON(os.path.join(rosco_dir,'Test_Cases','NREL_2p8_127/NREL-2p8-127_DISCON.IN')) # Apply all discon variables as case inputs control_base_case = {} for discon_input in rosco_vt: control_base_case[('DISCON_in',discon_input)] = {'vals': [rosco_vt[discon_input]], 'group': 0} - + # Set up AWC cases defined above + control_base_case[('DISCON_in','AWC_NumModes')] = {'vals': [1,1,1,2,2], 'group': 2} + control_base_case[('DISCON_in','AWC_n')] = {'vals': [[0],[1],[-1],[-1,1], [-1,1]], 'group': 2} + control_base_case[('DISCON_in','AWC_omega')] = {'vals': [[0.3142],[0.3142],[0.3142],[0.3142,0.3142], [0.3142,0.3142]], 'group': 2} + control_base_case[('DISCON_in','AWC_amp')] = {'vals': [[0.0175],[0.0175],[0.0175],[0.0175,0.0175], [0.0175,0.0175]], 'group': 2} + control_base_case[('DISCON_in','AWC_clockangle')] = {'vals': [[0],[0],[0],[0,0], [90,90]], 'group': 2} + # simulation set up r = run_FAST_ROSCO() r.tuning_yaml = parameter_filename @@ -138,7 +141,7 @@ def main(): r.case_inputs[("ServoDyn","Ptch_Cntrl")] = {'vals':[1], 'group':0} # Individual pitch control must be enabled in ServoDyn r.save_dir = run_dir r.rosco_dir = rosco_dir - + r.n_cores = 5 r.run_FAST() # # Check AWC here From de3a6fe443d90504f4a13d10718df9a5a2137a45 Mon Sep 17 00:00:00 2001 From: dzalkind Date: Fri, 17 Feb 2023 14:49:05 -0700 Subject: [PATCH 044/224] Tidy up DISCON file writing --- ROSCO_toolbox/utilities.py | 10 +++++----- 1 file changed, 5 insertions(+), 5 deletions(-) diff --git a/ROSCO_toolbox/utilities.py b/ROSCO_toolbox/utilities.py index 160f92a3..adb4d502 100644 --- a/ROSCO_toolbox/utilities.py +++ b/ROSCO_toolbox/utilities.py @@ -211,11 +211,11 @@ def write_DISCON(turbine, controller, param_file='DISCON.IN', txt_filename='Cp_C file.write('{} ! PF_Offsets - Constant blade pitch offsets for blades 1-3 [rad]\n'.format(''.join('{:<10.8f} '.format(rosco_vt['PF_Offsets'][i]) for i in range(3)))) file.write('\n') file.write('!------- Active Wake Control -----------------------------------------------------\n') - file.write('{0:<12d} ! AWC_NumModes - \n'.format(int(rosco_vt['AWC_NumModes']))) - file.write('{} ! AWC_n - AWC azimuthal number\n'.format(write_array(rosco_vt['AWC_n'],'<4d'))) - file.write('{} ! AWC_omega - AWC frequency [rad/s]\n'.format(write_array(rosco_vt['AWC_omega'],'<6.4f'))) - file.write('{} ! AWC_amp - AWC amplitude [rad]\n'.format(write_array(rosco_vt['AWC_amp'],'<6.4f'))) - file.write('{} ! AWC_clockangle - WC clock angle [deg]\n'.format(write_array(rosco_vt['AWC_clockangle'],'<6.4f'))) + file.write('{0:<12d} ! AWC_NumModes - Number of AWC modes\n'.format(int(rosco_vt['AWC_NumModes']))) + file.write('{} ! AWC_n - AWC azimuthal number, must be an array the size of AWC_NumModes\n'.format(write_array(rosco_vt['AWC_n'],'<4d'))) + file.write('{} ! AWC_omega - AWC frequency, must be an array the size of AWC_NumModes [rad/s]\n'.format(write_array(rosco_vt['AWC_omega'],'<6.4f'))) + file.write('{} ! AWC_amp - AWC amplitude, must be an array the size of AWC_NumModes [rad]\n'.format(write_array(rosco_vt['AWC_amp'],'<6.4f'))) + file.write('{} ! AWC_clockangle - AWC clock angle, must be an array the size of AWC_NumModes [deg]\n'.format(write_array(rosco_vt['AWC_clockangle'],'<6.4f'))) file.write('\n') file.write('!------- External Controller Interface -----------------------------------------------------\n') file.write('"{}" ! DLL_FileName - Name/location of the dynamic library in the Bladed-DLL format\n'.format(rosco_vt['DLL_FileName'])) From 87b3f09c5390d0cc33635987990cf8c1a02bae17 Mon Sep 17 00:00:00 2001 From: dzalkind Date: Fri, 17 Feb 2023 15:17:29 -0700 Subject: [PATCH 045/224] Revert setup directory --- setup.py | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/setup.py b/setup.py index b97495e1..04dbdc7b 100644 --- a/setup.py +++ b/setup.py @@ -52,8 +52,7 @@ # For the CMake Extensions -# this_directory = os.path.abspath(os.path.dirname(__file__)) -this_directory = "/pscratch/ndeveld/awc/ROSCO" +this_directory = os.path.abspath(os.path.dirname(__file__)) class CMakeExtension(Extension): From 46e7168d8b7ea930f801b135d398385cfe622bd8 Mon Sep 17 00:00:00 2001 From: kbrown1snl <66843135+kbrown1snl@users.noreply.github.com> Date: Wed, 22 Feb 2023 13:51:44 -0700 Subject: [PATCH 046/224] Update 20_active_wake_control.py Documentation update: -added type of input, either integer or float -added suggested ranges for input variables (only one of these ranges is a hard rule that might break something if not followed, which is that AWC_NumModes>=0) -added more description of what the azimuthal mode number is Note to Dan: I didn't follow exactly if the units in the code changed between rad and deg - can you check that the units in rows 14-16 are correct? Also, let's have Lawrence review these additions. --- Examples/20_active_wake_control.py | 11 ++++++----- 1 file changed, 6 insertions(+), 5 deletions(-) diff --git a/Examples/20_active_wake_control.py b/Examples/20_active_wake_control.py index e120bdbc..9baa864a 100644 --- a/Examples/20_active_wake_control.py +++ b/Examples/20_active_wake_control.py @@ -8,11 +8,12 @@ Active wake control with blade pitching is implemented in this example with an adaptation into the rotating frame of the mathematical framework from the classical theory for stability of axisymmetric jets [1], which offers flexibility in specifying the forcing strategy. The inputs to the controller are: - -AWC_NumModes (-) -> number of forcing modes - -AWC_n (-) -> azimuthal mode number(s) (i.e., the azimuthal mode number relates to the number and direction of the lobes of the wake structure) - -AWC_clockangle (deg) -> clocking angle of forcing mode(s) - -AWC_omega (rad/s) -> frequency(s) of forcing mode(s) - -AWC_amp (rad) -> pitch amplitude(s) of forcing mode(s) + Name Unit Type Range Description + AWC_NumModes - Integer [0,inf] number of forcing modes + AWC_n - Integer [-inf,inf] azimuthal mode number(s) (i.e., the azimuthal mode number relates to the number and direction of the lobes of the wake structure according to the classical spatio-temporal Fourier decomposition of an arbitrary quantity q, sigma{sigma{q*exp(i*n*theta)*exp(i*omega*time)}}. For the case of a non-time-varying flow (i.e., where omega = 0), the azimuthal mode number specifies the number of cycles of blade pitch oscillation per one rotation around the rotor azimuth.) + AWC_clockangle deg Float [0,360] clocking angle of forcing mode(s) + AWC_omega rad/s Float [0,inf] frequency(s) of forcing mode(s) + AWC_amp rad Float [0,inf] pitch amplitude(s) of forcing mode(s) The latter two inputs may be specified based on the expected inflow while the former three inputs determine the type of active wake control to be used. From 32dc9fd8ac48ef40b0a437c4baac606d81c8b5c5 Mon Sep 17 00:00:00 2001 From: kbrown1snl <66843135+kbrown1snl@users.noreply.github.com> Date: Fri, 24 Feb 2023 11:16:57 -0700 Subject: [PATCH 047/224] Update NREL-2p8-127_DISCON.IN Updating units. --- Test_Cases/NREL_2p8_127/NREL-2p8-127_DISCON.IN | 10 +++++----- 1 file changed, 5 insertions(+), 5 deletions(-) diff --git a/Test_Cases/NREL_2p8_127/NREL-2p8-127_DISCON.IN b/Test_Cases/NREL_2p8_127/NREL-2p8-127_DISCON.IN index 7f05d65e..6617034e 100644 --- a/Test_Cases/NREL_2p8_127/NREL-2p8-127_DISCON.IN +++ b/Test_Cases/NREL_2p8_127/NREL-2p8-127_DISCON.IN @@ -141,11 +141,11 @@ 0.00000000 0.00000000 0.00000000 ! PF_Offsets - Constant blade pitch offsets for blades 1-3 [rad] !------- AWC Modifications ----------------------------------------------------- -1 ! AWC_NumModes -1 ! AWC_n - AWC azimuthal number -0.3141592653 ! AWC_omega - AWC frequency [rad/s] -0.01745329222222222222 ! AWC_amp - AWC amplitude [rad] -0.0 ! AWC_clockangle - AWC clock angle [deg] +1 ! AWC_NumModes - Number of modes +1 ! AWC_n - azimuthal mode number +0.05 ! AWC_freq - frequency [Hz] +1.0 ! AWC_amp - amplitude [deg] +0.0 ! AWC_clockangle - clock angle [deg] !------- External Controller Interface ----------------------------------------------------- "unused" ! DLL_FileName - Name/location of the dynamic library in the Bladed-DLL format From ae5090b5c5b558f75b473ec6550fda494d2cbc29 Mon Sep 17 00:00:00 2001 From: kbrown1snl <66843135+kbrown1snl@users.noreply.github.com> Date: Fri, 24 Feb 2023 11:34:52 -0700 Subject: [PATCH 048/224] Update Controllers.f90 Update units. --- ROSCO/src/Controllers.f90 | 24 ++++++++++++++---------- 1 file changed, 14 insertions(+), 10 deletions(-) diff --git a/ROSCO/src/Controllers.f90 b/ROSCO/src/Controllers.f90 index 41720b0d..07df2c25 100644 --- a/ROSCO/src/Controllers.f90 +++ b/ROSCO/src/Controllers.f90 @@ -611,7 +611,7 @@ END SUBROUTINE FlapControl !------------------------------------------------------------------------------------------------------------------------------- SUBROUTINE ActiveWakeControl(CntrPar, LocalVar) - ! Yaw rate controller + ! Active wake controller ! AWC_Mode = 0, No active wake control ! AWC_Mode = 1, SNL active wake control USE ROSCO_Types, ONLY : ControlParameters, LocalVariables, ObjectInstances @@ -627,7 +627,9 @@ SUBROUTINE ActiveWakeControl(CntrPar, LocalVar) COMPLEX(DbKi), DIMENSION(3) :: AWC_complexangle COMPLEX(DbKi) :: complexI = (0.0, 1.0) INTEGER(IntKi) :: Imode, K ! Index used for looping through AWC modes - REAL(DbKi) :: clockang ! Clock angle for AWC pitching + REAL(DbKi) :: clockang ! Clock angle for AWC pitching in radian + REAL(DbKi) :: omega ! angular frequency for AWC pitching in rad/s + REAL(DbKi) :: amp ! amplitude for AWC pitching in radian ! Compute the AWC pitch settings @@ -636,14 +638,16 @@ SUBROUTINE ActiveWakeControl(CntrPar, LocalVar) LocalVar%AWC_complexangle = 0.0D0 DO Imode = 1,CntrPar%AWC_NumModes - clockang = CntrPar%AWC_clockangle(Imode)*PI/180.0_DbKi - AWC_angle(1) = CntrPar%AWC_omega(Imode) * LocalVar%Time - CntrPar%AWC_n(Imode) * (LocalVar%Azimuth + phi1 + clockang) - AWC_angle(2) = CntrPar%AWC_omega(Imode) * LocalVar%Time - CntrPar%AWC_n(Imode) * (LocalVar%Azimuth + phi2 + clockang) - AWC_angle(3) = CntrPar%AWC_omega(Imode) * LocalVar%Time - CntrPar%AWC_n(Imode) * (LocalVar%Azimuth + phi3 + clockang) - ! Add the forcing contribution to LocalVar%AWC_complexangle - DO K = 1,LocalVar%NumBl ! Loop through all blades - LocalVar%AWC_complexangle(K) = LocalVar%AWC_complexangle(K) + CntrPar%AWC_amp(Imode) * EXP(complexI * (AWC_angle(K))) - END DO + clockang = CntrPar%AWC_clockangle(Imode)*PI/180.0_DbKi + omega = CntrPar%AWC_freq(Imode)*PI*2.0_DbKi + AWC_angle(1) = omega * LocalVar%Time - CntrPar%AWC_n(Imode) * (LocalVar%Azimuth + phi1 + clockang) + AWC_angle(2) = omega * LocalVar%Time - CntrPar%AWC_n(Imode) * (LocalVar%Azimuth + phi2 + clockang) + AWC_angle(3) = omega * LocalVar%Time - CntrPar%AWC_n(Imode) * (LocalVar%Azimuth + phi3 + clockang) + ! Add the forcing contribution to LocalVar%AWC_complexangle + amp = CntrPar%AWC_amp(Imode)*PI/180.0_DbKi + DO K = 1,LocalVar%NumBl ! Loop through all blades + LocalVar%AWC_complexangle(K) = LocalVar%AWC_complexangle(K) + amp * EXP(complexI * (AWC_angle(K))) + END DO END DO DO K = 1,LocalVar%NumBl ! Loop through all blades, apply AWC_angle From 5c878add4e4c8338c0286d5de2815b89fb151853 Mon Sep 17 00:00:00 2001 From: kbrown1snl <66843135+kbrown1snl@users.noreply.github.com> Date: Fri, 24 Feb 2023 11:39:14 -0700 Subject: [PATCH 049/224] Update ROSCO_Types.f90 Update units. --- ROSCO/src/ROSCO_Types.f90 | 10 +++++----- 1 file changed, 5 insertions(+), 5 deletions(-) diff --git a/ROSCO/src/ROSCO_Types.f90 b/ROSCO/src/ROSCO_Types.f90 index 6e1621d3..7e02ded8 100644 --- a/ROSCO/src/ROSCO_Types.f90 +++ b/ROSCO/src/ROSCO_Types.f90 @@ -116,10 +116,10 @@ MODULE ROSCO_Types REAL(DbKi) :: PA_Damping ! Pitch actuator damping ratio [-, unused if PA_Mode = 1] INTEGER(IntKi) :: AWC_Mode ! Active wake control mode [0 - unused, 1 - SNL method] INTEGER(IntKi) :: AWC_NumModes ! AWC- Number of modes to include [-] - INTEGER(IntKi), DIMENSION(:), ALLOCATABLE :: AWC_n ! AWC azimuthal mode [-] - REAL(DbKi), DIMENSION(:), ALLOCATABLE :: AWC_omega ! AWC frequency [rad/s] - REAL(DbKi), DIMENSION(:), ALLOCATABLE :: AWC_amp ! AWC amplitude [deg] - REAL(DbKi), DIMENSION(:), ALLOCATABLE :: AWC_clockangle ! AWC clocking angle [deg] + INTEGER(IntKi), DIMENSION(:), ALLOCATABLE :: AWC_n ! AWC azimuthal mode [-] + REAL(DbKi), DIMENSION(:), ALLOCATABLE :: AWC_freq ! AWC frequency [Hz] + REAL(DbKi), DIMENSION(:), ALLOCATABLE :: AWC_amp ! AWC amplitude [deg] + REAL(DbKi), DIMENSION(:), ALLOCATABLE :: AWC_clockangle ! AWC clocking angle [deg] INTEGER(IntKi) :: PF_Mode ! Pitch actuator fault mode {0 - not used, 1 - offsets on one or more blades} REAL(DbKi), DIMENSION(:), ALLOCATABLE :: PF_Offsets ! Pitch actuator fault offsets for blade 1-3 [rad/s] INTEGER(IntKi) :: Ext_Mode ! External control mode (0 - not used, 1 - call external control library) @@ -345,4 +345,4 @@ MODULE ROSCO_Types REAL(ReKi), DIMENSION(:), ALLOCATABLE :: avrSWAP ! The swap array- used to pass data to and from the DLL controller [see Bladed DLL documentation] END TYPE ExtControlType -END MODULE ROSCO_Types \ No newline at end of file +END MODULE ROSCO_Types From baaa8db069199cb25116a73365ff6d63be5fa065 Mon Sep 17 00:00:00 2001 From: kbrown1snl <66843135+kbrown1snl@users.noreply.github.com> Date: Fri, 24 Feb 2023 11:40:52 -0700 Subject: [PATCH 050/224] Update ReadSetParameters.f90 Update units. --- ROSCO/src/ReadSetParameters.f90 | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ROSCO/src/ReadSetParameters.f90 b/ROSCO/src/ReadSetParameters.f90 index d19c9f01..d8525aa0 100644 --- a/ROSCO/src/ReadSetParameters.f90 +++ b/ROSCO/src/ReadSetParameters.f90 @@ -421,7 +421,7 @@ SUBROUTINE ReadControlParameterFileSub(CntrPar, zmqVar, accINFILE, accINFILE_siz CALL ReadEmptyLine(UnControllerParameters,CurLine) CALL ParseInput(UnControllerParameters,CurLine,'AWC_NumModes', accINFILE(1),CntrPar%AWC_NumModes, ErrVar) CALL ParseAry( UnControllerParameters,CurLine,'AWC_n', CntrPar%AWC_n, CntrPar%AWC_NumModes, accINFILE(1), ErrVar) - CALL ParseAry( UnControllerParameters,CurLine,'AWC_omega', CntrPar%AWC_omega, CntrPar%AWC_NumModes, accINFILE(1), ErrVar) + CALL ParseAry( UnControllerParameters,CurLine,'AWC_freq', CntrPar%AWC_freq, CntrPar%AWC_NumModes, accINFILE(1), ErrVar) CALL ParseAry( UnControllerParameters,CurLine,'AWC_amp', CntrPar%AWC_amp, CntrPar%AWC_NumModes, accINFILE(1), ErrVar) CALL ParseAry( UnControllerParameters,CurLine,'AWC_clockangle',CntrPar%AWC_clockangle,CntrPar%AWC_NumModes, accINFILE(1), ErrVar) CALL ReadEmptyLine(UnControllerParameters,CurLine) From b141c4e044aac365ccb4ec468eb99da9e590a77d Mon Sep 17 00:00:00 2001 From: kbrown1snl <66843135+kbrown1snl@users.noreply.github.com> Date: Fri, 24 Feb 2023 12:08:07 -0700 Subject: [PATCH 051/224] Update 20_active_wake_control.py Update units and documentation. --- Examples/20_active_wake_control.py | 30 ++++++++++++++++-------------- 1 file changed, 16 insertions(+), 14 deletions(-) diff --git a/Examples/20_active_wake_control.py b/Examples/20_active_wake_control.py index 9baa864a..84c7f039 100644 --- a/Examples/20_active_wake_control.py +++ b/Examples/20_active_wake_control.py @@ -5,15 +5,15 @@ Set up and run simulation with AWC, check outputs -Active wake control with blade pitching is implemented in this example with an adaptation into the rotating frame of the mathematical framework from the classical theory for stability of axisymmetric jets [1], which offers flexibility in specifying the forcing strategy. +Active wake control (AWC) with blade pitching is implemented in this example with an adaptation into the rotating frame of the mathematical framework from the classical theory for stability of axisymmetric jets [1], which offers flexibility in specifying the forcing strategy. The inputs to the controller are: Name Unit Type Range Description AWC_NumModes - Integer [0,inf] number of forcing modes AWC_n - Integer [-inf,inf] azimuthal mode number(s) (i.e., the azimuthal mode number relates to the number and direction of the lobes of the wake structure according to the classical spatio-temporal Fourier decomposition of an arbitrary quantity q, sigma{sigma{q*exp(i*n*theta)*exp(i*omega*time)}}. For the case of a non-time-varying flow (i.e., where omega = 0), the azimuthal mode number specifies the number of cycles of blade pitch oscillation per one rotation around the rotor azimuth.) - AWC_clockangle deg Float [0,360] clocking angle of forcing mode(s) - AWC_omega rad/s Float [0,inf] frequency(s) of forcing mode(s) - AWC_amp rad Float [0,inf] pitch amplitude(s) of forcing mode(s) + AWC_clockangle deg Float [0,360] clocking angle(s) of forcing mode(s) + AWC_freq Hz Float [0,inf] frequency(s) of forcing mode(s) + AWC_amp deg Float [0,inf] pitch amplitude(s) of forcing mode(s) (note that AWC_amp specifies the amplitude of each individual mode so that the total amplitude of pitching will be the sum of AWC_amp) The latter two inputs may be specified based on the expected inflow while the former three inputs determine the type of active wake control to be used. @@ -27,13 +27,13 @@ Calculation methodology: For each blade, we compute the total phase angle of blade pitch excursion according to: - AWC_angle(t) = AWC_omega * t - AWC_n * (psi(t) + phi + AWC_clockangle*PI/180) (eq 1) + AWC_angle(t) = 2*Pi*AWC_freq * t - AWC_n * (psi(t) + phi + AWC_clockangle*PI/180) (eq 1) where t is time phi(t) is the angular offset of the given blade in the rotor plane relative to blade 1 psi is the angle of blade 1 in the rotor plane from top-dead center Next, the phase angle is converted into the complex pitch amplitude: - AWC_complexangle(t) = AWC_amp * EXP(i * AWC_angle(t)) (eq 2) + AWC_complexangle(t) = AWC_amp*PI/180 * EXP(i * AWC_angle(t)) (eq 2) where i is the square root of -1 Note that if AWC_NumModes>1, then eq 1 and 2 are computed for each additional mode, and AWC_complexangle becomes a summation over all modes for each blade. @@ -44,14 +44,14 @@ Rearranging for ease of viewing: Inserting eq 1 into eq 2, and then putting that result into eq 3 gives: - theta(t) = theta_0(t) + REAL(AWC_amp * EXP(i * (AWC_omega * t - AWC_n * (psi(t) + phi + AWC_clockangle*PI/180)))) (eq 4) + theta(t) = theta_0(t) + REAL(AWC_amp*PI/180 * EXP(i * (2*Pi*AWC_freq * t - AWC_n * (psi(t) + phi + AWC_clockangle*PI/180)))) (eq 4) Applying Euler's formula and carrying out the REAL operator: - theta(t) = theta_0(t) + AWC_amp * cos(AWC_omega * t - AWC_n * (psi(t) + phi + AWC_clockangle*PI/180)) (eq 5) + theta(t) = theta_0(t) + AWC_amp*PI/180 * cos(2*Pi*AWC_freq * t - AWC_n * (psi(t) + phi + AWC_clockangle*PI/180)) (eq 5) As an example, we can set parameters to produce the counter-clockwise helix pattern from [2] using AWC_NumModes = 1, AWC_n = -1, and AWC_clockangle = 0: For blade 1, eq 5 becomes: - theta(t) = theta_0(t) + AWC_amp * cos(AWC_omega * t + psi(t)) (eq 6) + theta(t) = theta_0(t) + AWC_amp*PI/180 * cos(2*Pi*AWC_freq * t + psi(t)) (eq 6) Note that the inverse multi-blade coordinate (MBC) transformation can also be used to obtain the same result as eq 6. Beginning with Eq. 3 from [2], we have @@ -73,12 +73,14 @@ Multiplying the first row of the top matrix (and dropping the subscript of blade 1) yields: theta(t) = theta_0(t) + theta_tilt(t)*cos(psi(t)) + theta_yaw(t)*sin(psi(t)) (eq 8) - Setting theta_tilt(t) = AWC_amp * cos(AWC_omega * t) and theta_yaw(t) = -AWC_amp * sin(AWC_omega * t) gives: - theta(t) = theta_0(t) + (AWC_amp * cos(AWC_omega * t))*cos(psi(t)) - (AWC_amp * sin(AWC_omega * t))*sin(psi(t)) (eq 9) + Setting theta_tilt(t) = AWC_amp*PI/180 * cos(2*Pi*AWC_freq * t) and theta_yaw(t) = -AWC_amp*PI/180 * sin(2*Pi*AWC_freq * t) gives: + theta(t) = theta_0(t) + (AWC_amp*PI/180 * cos(2*Pi*AWC_freq * t))*cos(psi(t)) - (AWC_amp*PI/180 * sin(2*Pi*AWC_freq * t))*sin(psi(t)) (eq 9) Applying a Ptolemy identity gives: - theta(t) = theta_0(t) + AWC_amp * cos(AWC_omega * t + psi(t)) (eq 10) + theta(t) = theta_0(t) + AWC_amp*PI/180 * cos(2*Pi*AWC_freq * t + psi(t)) (eq 10) which is equivlanet to eq 6 above. + +Implementation note: AWC strategies will be compromised if the AWC pitch command attempts to lower the blade pitch below value PC_MinPit as specified in the DISCON file, so PC_MinPit may need to be reduced by the user. References: [1] - Batchelor, G. K., and A. E. Gill. "Analysis of the stability of axisymmetric jets." Journal of fluid mechanics 14.4 (1962): 529-551. @@ -126,8 +128,8 @@ def main(): # Set up AWC cases defined above control_base_case[('DISCON_in','AWC_NumModes')] = {'vals': [1,1,1,2,2], 'group': 2} control_base_case[('DISCON_in','AWC_n')] = {'vals': [[0],[1],[-1],[-1,1], [-1,1]], 'group': 2} - control_base_case[('DISCON_in','AWC_omega')] = {'vals': [[0.3142],[0.3142],[0.3142],[0.3142,0.3142], [0.3142,0.3142]], 'group': 2} - control_base_case[('DISCON_in','AWC_amp')] = {'vals': [[0.0175],[0.0175],[0.0175],[0.0175,0.0175], [0.0175,0.0175]], 'group': 2} + control_base_case[('DISCON_in','AWC_freq')] = {'vals': [[0.05],[0.05],[0.05],[0.05,0.05], [0.05,0.05]], 'group': 2} + control_base_case[('DISCON_in','AWC_amp')] = {'vals': [[1.0],[1.0],[1.0],[1.0,1.0], [1.0,1.0]], 'group': 2} control_base_case[('DISCON_in','AWC_clockangle')] = {'vals': [[0],[0],[0],[0,0], [90,90]], 'group': 2} # simulation set up From 826ca01fbfe01fbd629640547a9413990420f9bb Mon Sep 17 00:00:00 2001 From: kbrown1snl <66843135+kbrown1snl@users.noreply.github.com> Date: Fri, 24 Feb 2023 12:14:45 -0700 Subject: [PATCH 052/224] Update toolbox_schema.yaml Update units. --- ROSCO_toolbox/inputs/toolbox_schema.yaml | 15 +++++++-------- 1 file changed, 7 insertions(+), 8 deletions(-) diff --git a/ROSCO_toolbox/inputs/toolbox_schema.yaml b/ROSCO_toolbox/inputs/toolbox_schema.yaml index 2a851f36..edee0d2c 100644 --- a/ROSCO_toolbox/inputs/toolbox_schema.yaml +++ b/ROSCO_toolbox/inputs/toolbox_schema.yaml @@ -879,7 +879,6 @@ properties: AWC_NumModes: type: number description: Number of AWC modes - units: rad default: 1 AWC_n: type: array @@ -887,20 +886,20 @@ properties: type: number description: AWC azimuthal number default: [1] - AWC_omega: + AWC_freq: type: array items: type: number - description: AWC frequency [rad/s] - units: rad/s - default: [0.314159] + description: AWC frequency [Hz] + units: Hz + default: [0.05] AWC_amp: type: array items: type: number - description: AWC amplitude [rad] - units: rad - default: [0.017453292] + description: AWC amplitude [deg] + units: deg + default: [1.0] AWC_clockangle: type: array items: From 797e5544e58b4b719ab3178fed879be36cf42376 Mon Sep 17 00:00:00 2001 From: kbrown1snl <66843135+kbrown1snl@users.noreply.github.com> Date: Fri, 24 Feb 2023 12:22:30 -0700 Subject: [PATCH 053/224] Update utilities.py Update AWC descriptions and units. --- ROSCO_toolbox/utilities.py | 10 +++++----- 1 file changed, 5 insertions(+), 5 deletions(-) diff --git a/ROSCO_toolbox/utilities.py b/ROSCO_toolbox/utilities.py index adb4d502..4c92f064 100644 --- a/ROSCO_toolbox/utilities.py +++ b/ROSCO_toolbox/utilities.py @@ -211,11 +211,11 @@ def write_DISCON(turbine, controller, param_file='DISCON.IN', txt_filename='Cp_C file.write('{} ! PF_Offsets - Constant blade pitch offsets for blades 1-3 [rad]\n'.format(''.join('{:<10.8f} '.format(rosco_vt['PF_Offsets'][i]) for i in range(3)))) file.write('\n') file.write('!------- Active Wake Control -----------------------------------------------------\n') - file.write('{0:<12d} ! AWC_NumModes - Number of AWC modes\n'.format(int(rosco_vt['AWC_NumModes']))) - file.write('{} ! AWC_n - AWC azimuthal number, must be an array the size of AWC_NumModes\n'.format(write_array(rosco_vt['AWC_n'],'<4d'))) - file.write('{} ! AWC_omega - AWC frequency, must be an array the size of AWC_NumModes [rad/s]\n'.format(write_array(rosco_vt['AWC_omega'],'<6.4f'))) - file.write('{} ! AWC_amp - AWC amplitude, must be an array the size of AWC_NumModes [rad]\n'.format(write_array(rosco_vt['AWC_amp'],'<6.4f'))) - file.write('{} ! AWC_clockangle - AWC clock angle, must be an array the size of AWC_NumModes [deg]\n'.format(write_array(rosco_vt['AWC_clockangle'],'<6.4f'))) + file.write('{0:<12d} ! AWC_NumModes - number of forcing modes\n'.format(int(rosco_vt['AWC_NumModes']))) + file.write('{} ! AWC_n - azimuthal mode number(s) (i.e., the azimuthal mode number relates to the number and direction of the lobes of the wake structure according to the classical spatio-temporal Fourier decomposition of an arbitrary quantity q, sigma{sigma{q*exp(i*n*theta)*exp(i*omega*time)}}. For the case of a non-time-varying flow (i.e., where omega = 0), the azimuthal mode number specifies the number of cycles of blade pitch oscillation per one rotation around the rotor azimuth.)\n'.format(write_array(rosco_vt['AWC_n'],'<4d'))) + file.write('{} ! AWC_freq - frequency(s) of forcing mode(s) [Hz]\n'.format(write_array(rosco_vt['AWC_omega'],'<6.4f'))) + file.write('{} ! AWC_amp - pitch amplitude(s) of forcing mode(s) (note that AWC_amp specifies the amplitude of each individual mode so that the total amplitude of pitching will be the sum of AWC_amp) [deg]\n'.format(write_array(rosco_vt['AWC_amp'],'<6.4f'))) + file.write('{} ! AWC_clockangle - clocking angle(s) of forcing mode(s) [deg]\n'.format(write_array(rosco_vt['AWC_clockangle'],'<6.4f'))) file.write('\n') file.write('!------- External Controller Interface -----------------------------------------------------\n') file.write('"{}" ! DLL_FileName - Name/location of the dynamic library in the Bladed-DLL format\n'.format(rosco_vt['DLL_FileName'])) From ff0ce39cfa17751dd529683228ab3dde28c32f62 Mon Sep 17 00:00:00 2001 From: kbrown1snl <66843135+kbrown1snl@users.noreply.github.com> Date: Fri, 24 Feb 2023 12:25:29 -0700 Subject: [PATCH 054/224] Update rosco_types.yaml Update AWC units. --- ROSCO/rosco_registry/rosco_types.yaml | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/ROSCO/rosco_registry/rosco_types.yaml b/ROSCO/rosco_registry/rosco_types.yaml index 56358a4b..b22ae86b 100644 --- a/ROSCO/rosco_registry/rosco_types.yaml +++ b/ROSCO/rosco_registry/rosco_types.yaml @@ -459,10 +459,10 @@ ControlParameters: <<: *integer allocatable: True description: AWC azimuthal mode [-] - AWC_omega: + AWC_freq: <<: *real allocatable: True - description: AWC frequency [rad/s] + description: AWC frequency [Hz] AWC_amp: <<: *real allocatable: True From 3bc2185cec3aaeb9c6e745e60adb646bbc5661b0 Mon Sep 17 00:00:00 2001 From: jfrederik-nrel Date: Mon, 27 Feb 2023 16:50:19 -0700 Subject: [PATCH 055/224] Added NREL-developed AWC-implementation --- Examples/20_active_wake_control.py | 220 ++++++++++++++++++ ROSCO/rosco_registry/rosco_types.yaml | 35 +++ ROSCO/rosco_registry/write_registry.py | 27 ++- ROSCO/src/Controllers.f90 | 98 +++++++- ROSCO/src/ROSCO_IO.f90 | 11 +- ROSCO/src/ROSCO_Types.f90 | 7 + ROSCO/src/ReadSetParameters.f90 | 12 +- ROSCO_toolbox/controller.py | 5 +- ROSCO_toolbox/inputs/toolbox_schema.yaml | 44 ++++ ROSCO_toolbox/ofTools/case_gen/CaseLibrary.py | 2 +- .../ofTools/case_gen/runFAST_pywrapper.py | 1 + ROSCO_toolbox/ofTools/fast_io/FAST_reader.py | 4 +- ROSCO_toolbox/utilities.py | 16 ++ Test_Cases/NREL-5MW/DISCON.IN | 7 + setup.py | 4 +- 15 files changed, 467 insertions(+), 26 deletions(-) create mode 100644 Examples/20_active_wake_control.py diff --git a/Examples/20_active_wake_control.py b/Examples/20_active_wake_control.py new file mode 100644 index 00000000..7011b631 --- /dev/null +++ b/Examples/20_active_wake_control.py @@ -0,0 +1,220 @@ +''' +----------- 20_active_wake_control ------------ +Run openfast with ROSCO and active wake control +----------------------------------------------- +Set up and run simulation with AWC, check outputs +Active wake control (AWC) with blade pitching is implemented in this example with an adaptation into the rotating frame of the mathematical framework from the classical theory for stability of axisymmetric jets [1], which offers flexibility in specifying the forcing strategy. + +----------------------------------------------- +AWC_Mode = 1: Sandia National Laboratories (SNL) method: +----------------------------------------------- + +The inputs to the controller are: + Name Unit Type Range Description + AWC_NumModes - Integer [0,inf] number of forcing modes + AWC_n - Integer [-inf,inf] azimuthal mode number(s) (i.e., the azimuthal mode number relates to the number and direction of the lobes of the wake structure according to the classical spatio-temporal Fourier decomposition of an arbitrary quantity q, sigma{sigma{q*exp(i*n*theta)*exp(i*omega*time)}}. For the case of a non-time-varying flow (i.e., where omega = 0), the azimuthal mode number specifies the number of cycles of blade pitch oscillation per one rotation around the rotor azimuth.) + AWC_clockangle deg Float [0,360] clocking angle(s) of forcing mode(s) + AWC_freq Hz Float [0,inf] frequency(s) of forcing mode(s) + AWC_amp deg Float [0,inf] pitch amplitude(s) of forcing mode(s) (note that AWC_amp specifies the amplitude of each individual mode so that the total amplitude of pitching will be the sum of AWC_amp) +The latter two inputs may be specified based on the expected inflow while the former three inputs determine the type of active wake control to be used. +Readers may be familiar with several forcing strategies from literature on active wake control that can be represented as follows: + -collective dynamic induction control: AWC_NumModes = 1, AWC_n = 0, AWC_clockangle = 0 + -helix clockwise [2]: AWC_NumModes = 1, AWC_n = 1, AWC_clockangle = 0 + -helix counter-clockwise [2]: AWC_NumModes = 1, AWC_n = -1, AWC_clockangle = 0 + -up-and-down: AWC_NumModes = 2, AWC_n = -1 1, AWC_clockangle = 0 0 + -side-to-side: AWC_NumModes = 2, AWC_n = -1 1, AWC_clockangle = 90 90 + -other: Higher-order modes or different combinations of the above can also be specified + Calculation methodology: + For each blade, we compute the total phase angle of blade pitch excursion according to: + AWC_angle(t) = 2*Pi*AWC_freq * t - AWC_n * (psi(t) + phi + AWC_clockangle*PI/180) (eq 1) + where t is time + phi(t) is the angular offset of the given blade in the rotor plane relative to blade 1 + psi is the angle of blade 1 in the rotor plane from top-dead center + + Next, the phase angle is converted into the complex pitch amplitude: + AWC_complexangle(t) = AWC_amp*PI/180 * EXP(i * AWC_angle(t)) (eq 2) + where i is the square root of -1 + + Note that if AWC_NumModes>1, then eq 1 and 2 are computed for each additional mode, and AWC_complexangle becomes a summation over all modes for each blade. + Finally, the real pitch amplitude, theta(t), to be passed to the next step of the controller is calculated: + theta(t) = theta_0(t) + REAL(AWC_complexangle(t)) (eq 3) + where theta_0(t) is the controller's nominal pitch command + + Rearranging for ease of viewing: + Inserting eq 1 into eq 2, and then putting that result into eq 3 gives: + theta(t) = theta_0(t) + REAL(AWC_amp*PI/180 * EXP(i * (2*Pi*AWC_freq * t - AWC_n * (psi(t) + phi + AWC_clockangle*PI/180)))) (eq 4) + + Applying Euler's formula and carrying out the REAL operator: + theta(t) = theta_0(t) + AWC_amp*PI/180 * cos(2*Pi*AWC_freq * t - AWC_n * (psi(t) + phi + AWC_clockangle*PI/180)) (eq 5) + As an example, we can set parameters to produce the counter-clockwise helix pattern from [2] using AWC_NumModes = 1, AWC_n = -1, and AWC_clockangle = 0: + For blade 1, eq 5 becomes: + theta(t) = theta_0(t) + AWC_amp*PI/180 * cos(2*Pi*AWC_freq * t + psi(t)) (eq 6) +Note that the inverse multi-blade coordinate (MBC) transformation can also be used to obtain the same result as eq 6. + Beginning with Eq. 3 from [2], we have + / \ / \ + | theta_1(t) | | theta_0(t) | + | theta_2(t) | = T^-1(psi(t)) * | theta_tilt(t) | (eq 7) + | theta_3(t) | | theta_yaw(t) | + \ / \ / + where + / \ + | 1 cos(psi_1(t)) sin(psi_1(t)) | + T^-1(psi(t)) = | 1 cos(psi_2(t)) sin(psi_2(t)) | + | 1 cos(psi_3(t)) sin(psi_3(t)) | + \ / + Multiplying the first row of the top matrix (and dropping the subscript of blade 1) yields: + theta(t) = theta_0(t) + theta_tilt(t)*cos(psi(t)) + theta_yaw(t)*sin(psi(t)) (eq 8) + + Setting theta_tilt(t) = AWC_amp*PI/180 * cos(2*Pi*AWC_freq * t) and theta_yaw(t) = -AWC_amp*PI/180 * sin(2*Pi*AWC_freq * t) gives: + theta(t) = theta_0(t) + (AWC_amp*PI/180 * cos(2*Pi*AWC_freq * t))*cos(psi(t)) - (AWC_amp*PI/180 * sin(2*Pi*AWC_freq * t))*sin(psi(t)) (eq 9) + Applying a Ptolemy identity gives: + theta(t) = theta_0(t) + AWC_amp*PI/180 * cos(2*Pi*AWC_freq * t + psi(t)) (eq 10) + which is equivlanet to eq 6 above. + +----------------------------------------------- +AWC_Mode = 2: National Renewable Energy Laboratory (NREL) implementation: +----------------------------------------------- +The inputs to the controller are: + Name Unit Type Range Description + AWC_NumModes - Integer [1,2] number of modes for tilt and yaw (1: identical settings for tilt and yaw pitch angles, 2: seperate settings for tilt and yaw moments) + AWC_n - Integer [0,1] IPC-AWC enabled (size = AWC_NumModes. 0: collective pitch AWC [UNDER CONSTRUCTION], 1: IPC-AWC) + AWC_clockangle deg Array of Floats [0,360] clocking angle(s) of tilt and yaw pitch angles (size = AWC_NumModes. If size = 1: phase delay of yaw moment w.r.t. tilt moment) + AWC_freq Hz Array of Floats [0,inf] frequency(s) of the tilt and yaw ptich angles, respectively (size = AWC_NumModes. If size = 1, both frequencies are assumed identical) + AWC_amp deg Array of Floats [0,inf] pitch amplitude(s) of tilt and yaw pitch angles (size = AWC_NumModes. If size = 1, both amplitudes are assumed identical) + +Using the inputs mentioned above, the user is able to specify any desired combination of sinusoidal tilt and yaw pitch angles to be tracked by the turbine. +Readers may be familiar with several forcing strategies from literature on active wake control that can be represented as follows: + -collective dynamic induction control: AWC_NumModes = 1, AWC_n = 0 + -helix clockwise [2]: AWC_NumModes = 1, AWC_n = 1, AWC_clockangle = -90 OR AWC_NumModes = 2, AWC_n = 1 1, AWC_clockangle = 0 -90 + -helix counter-clockwise [2]: AWC_NumModes = 1, AWC_n = 1, AWC_clockangle = 90 OR AWC_NumModes = 2, AWC_n = 1 1, AWC_clockangle = 0 90 + -up-and-down: AWC_NumModes = 2, AWC_n = 1 1, AWC_amp = # 0 (where "#" represents the desired amplitude) + -side-to-side: AWC_NumModes = 2, AWC_n = 1 1, AWC_amp = 0 # (where "#" represents the desired amplitude) + -other: different combinations of the above can also be specified + Calculation methodology: + The inputs described above enable the user to specify a desired sinusoidal signal for either the collective pitch (AWC_n = 0) or tilt and yaw pitch + angles (AWC_n = 1). These AWC pitch angles are defined as: + AWC_angle(t) = AWC_amp * sin(2*pi*AWC_freq*t + AWC_clockangle) (eq 1) + + In case of collective pitch AWC, this signal is directly superimposed on the regular pitch control signal. + + In case of IPC-based AWC, the reference tilt and yaw pitch angles theta are transformed to the rotating frame (i.e., pitch angles theta_k(t) for all + individual blades) using the inverse MBC transformation: + / \ / \ + | theta_1(t) | | theta_0(t) | + | theta_2(t) | = T^-1(psi(t)) * | theta_tilt(t) | (eq 2) + | theta_3(t) | | theta_yaw(t) | + \ / \ / + where + theta_tilt(t) = AWC_amp(1) * sin(2*pi*AWC_freq(1)*t + AWC_clockangle(1)) (eq 3) + theta_yaw(t) = AWC_amp(2) * sin(2*pi*AWC_freq(2)*t + AWC_clockangle(2)) (eq 4) + and + / \ + | 1 cos(psi_1(t)) sin(psi_1(t)) | + T^-1(psi(t)) = | 1 cos(psi_2(t)) sin(psi_2(t)) | (eq 5) + | 1 cos(psi_3(t)) sin(psi_3(t)) | + \ / + with psi_k(t) the azimuthal position of blade k at time instant t. Note that if AWC_NumModes = 1, it is assumed that: + AWC_amp(2) = AWC_amp(1) + AWC_freq(2) = AWC_freq(1) + AWC_clockangle(2) = AWC_clockangle(1) + AWC_clockangle(1) = 0 + For more information on this control strategy, the user is referred to [2]. + +----------------------------------------------- + +General Implementation note: AWC strategies will be compromised if the AWC pitch command attempts to lower the blade pitch below value PC_MinPit as specified +in the DISCON file, so PC_MinPit may need to be reduced by the user. + +References: +[1] - Batchelor, G. K., and A. E. Gill. "Analysis of the stability of axisymmetric jets." Journal of fluid mechanics 14.4 (1962): 529-551. +[2] - Frederik, Joeri A., et al. "The helix approach: Using dynamic individual pitch control to enhance wake mixing in wind farms." Wind Energy 23.8 (2020): 1739-1751. +''' + +import os, platform +from ROSCO_toolbox.ofTools.case_gen.run_FAST import run_FAST_ROSCO +from ROSCO_toolbox.ofTools.case_gen import CaseLibrary as cl +from ROSCO_toolbox.ofTools.fast_io import output_processing +from ROSCO_toolbox.utilities import read_DISCON, DISCON_dict +import numpy as np + +# Choose your implementation method +AWC_Mode = 2 # 1 for SNL implementation, 2 for NREL implementation + +#directories +this_dir = os.path.dirname(os.path.abspath(__file__)) +rosco_dir = os.path.dirname(this_dir) +example_out_dir = os.path.join(this_dir,'examples_out') +os.makedirs(example_out_dir,exist_ok=True) + +if platform.system() == 'Windows': + lib_name = os.path.realpath(os.path.join(this_dir, '../ROSCO/build/libdiscon.dll')) +elif platform.system() == 'Darwin': + lib_name = os.path.realpath(os.path.join(this_dir, '../ROSCO/build/libdiscon.dylib')) +else: + lib_name = os.path.realpath(os.path.join(this_dir, '../ROSCO/build/libdiscon.so')) + + +def main(): + + # Input yaml and output directory + parameter_filename = os.path.join(rosco_dir,'Tune_Cases/NREL2p8.yaml') # will be dummy and overwritten with SNL DISCON params + run_dir = os.path.join(example_out_dir,'20_active_wake_control/all_cases') + os.makedirs(run_dir,exist_ok=True) + + # Read all DISCON inputs + rosco_vt = read_DISCON(os.path.join(rosco_dir,'Test_Cases','NREL_2p8_127/NREL-2p8-127_DISCON.IN')) + + # Apply all discon variables as case inputs + control_base_case = {} + for discon_input in rosco_vt: + control_base_case[('DISCON_in',discon_input)] = {'vals': [rosco_vt[discon_input]], 'group': 0} + + # Set up AWC cases defined above + if AWC_Mode == 1: + control_base_case[('DISCON_in','AWC_NumModes')] = {'vals': [1,1,1,2,2], 'group': 2} + control_base_case[('DISCON_in','AWC_n')] = {'vals': [[0],[1],[-1],[-1,1], [-1,1]], 'group': 2} + control_base_case[('DISCON_in','AWC_freq')] = {'vals': [[0.05],[0.05],[0.05],[0.05,0.05], [0.05,0.05]], 'group': 2} + control_base_case[('DISCON_in','AWC_amp')] = {'vals': [[1.0],[1.0],[1.0],[1.0,1.0], [1.0,1.0]], 'group': 2} + control_base_case[('DISCON_in','AWC_clockangle')] = {'vals': [[0],[0],[0],[0,0], [90,90]], 'group': 2} + elif AWC_Mode == 2: + control_base_case[('DISCON_in','AWC_Mode')] = {'vals': [0,2,2,2,2,2], 'group': 2} + control_base_case[('DISCON_in','AWC_NumModes')] = {'vals': [1,1,1,1,2,2], 'group': 2} + control_base_case[('DISCON_in','AWC_n')] = {'vals': [[0],[0],[1],[1],[1,1], [1,1]], 'group': 2} + control_base_case[('DISCON_in','AWC_freq')] = {'vals': [[0],[0.05],[0.05],[0.05],[0.05,0.05], [0.05,0.05]], 'group': 2} + control_base_case[('DISCON_in','AWC_amp')] = {'vals': [[0],[1.0],[1.0],[1.0],[1.0,0.0], [0.0,1.0]], 'group': 2} + control_base_case[('DISCON_in','AWC_clockangle')] = {'vals': [[0],[0],[-90],[90],[0,0], [0,0]], 'group': 2} + + # simulation set up + r = run_FAST_ROSCO() + r.tuning_yaml = parameter_filename + r.wind_case_fcn = cl.power_curve # single step wind input + r.wind_case_opts = { + 'U': [14], # from 10 to 15 m/s + 'TMax': 100, + } + r.case_inputs = control_base_case + r.case_inputs[("ServoDyn","Ptch_Cntrl")] = {'vals':[1], 'group':0} # Individual pitch control must be enabled in ServoDyn + r.save_dir = run_dir + r.rosco_dir = rosco_dir + r.n_cores = 5 + r.run_FAST() + + # # Check AWC here + # filenames = [os.path.join(run_dir,'IEA15MW/simp_step/base/IEA15MW_0.outb')] + # fast_out = output_processing.output_processing() + + # # Load and plot + # fastout = fast_out.load_fast_out(filenames) + # offset_2 = fastout[0]['BldPitch2'] - fastout[0]['BldPitch1'] + # offset_3 = fastout[0]['BldPitch3'] - fastout[0]['BldPitch1'] + + # # check that offset (min,max) is very close to prescribed values + # np.testing.assert_almost_equal(offset_2.max(),pitch2_offset,decimal=3) + # np.testing.assert_almost_equal(offset_2.min(),pitch2_offset,decimal=3) + # np.testing.assert_almost_equal(offset_3.max(),pitch3_offset,decimal=3) + # np.testing.assert_almost_equal(offset_3.max(),pitch3_offset,decimal=3) + + + +if __name__=="__main__": + main() \ No newline at end of file diff --git a/ROSCO/rosco_registry/rosco_types.yaml b/ROSCO/rosco_registry/rosco_types.yaml index 81ad0953..b0d46d61 100644 --- a/ROSCO/rosco_registry/rosco_types.yaml +++ b/ROSCO/rosco_registry/rosco_types.yaml @@ -12,6 +12,13 @@ default_types: size: 0 # Use this if the type IS an array (size:3 --> REAL(8), BldPitch(3)) allocatable: False equals: + complex: &complex + type: complex + description: + dimension: # Use this if a higher-dimensional allocatable array (dimension:(:,:) --> REAL(8), DIMESION(:,:), ALLOCATABLE) + size: 0 # Use this if the type IS an array (size:3 --> REAL(8), BldPitch(3)) + allocatable: False + equals: float: &float type: float description: @@ -441,6 +448,30 @@ ControlParameters: <<: *real description: Pitch actuator damping ratio [-, unused if PA_Mode = 1] + # Active wake control + AWC_Mode: + <<: *integer + description: Active wake control mode [0 - unused, 1 - SNL method, 2 - NREL method] + AWC_NumModes: + <<: *integer + description: AWC- Number of modes to include [-] + AWC_n: + <<: *integer + allocatable: True + description: AWC azimuthal mode [-] + AWC_freq: + <<: *real + allocatable: True + description: AWC frequency [Hz] + AWC_amp: + <<: *real + allocatable: True + description: AWC amplitude [deg] + AWC_clockangle: + <<: *real + allocatable: True + description: AWC clocking angle [deg] + # Pitch actuator error PF_Mode: <<: *integer @@ -921,6 +952,10 @@ LocalVariables: restart: <<: *logical description: Restart flag + AWC_complexangle: + <<: *complex + description: Complex angle for each blade, sum of modes? + size: 3 WE: <<: *derived_type id: WE diff --git a/ROSCO/rosco_registry/write_registry.py b/ROSCO/rosco_registry/write_registry.py index 09c855b3..0368404a 100644 --- a/ROSCO/rosco_registry/write_registry.py +++ b/ROSCO/rosco_registry/write_registry.py @@ -13,12 +13,12 @@ def generate(yfile): def write_types(yfile): ''' Writes ROSCO_types.f90 - -- All additions to the types should be added to rosco_types.yaml! + -- All additions to the types should be added to ! Parameters: ----------- yfile: string - path to rosco_types.yaml + path to ''' reg = load_yaml(yfile) reg.pop('default_types') @@ -27,7 +27,7 @@ def write_types(yfile): # Header file.write('! ROSCO Registry\n') file.write('! This file is automatically generated by write_registry.py using ROSCO v{}\n'.format(ROSCO_toolbox.__version__)) - file.write('! For any modification to the registry, please edit the rosco_types.yaml accordingly\n \n') + file.write('! For any modification to the registry, please edit the accordingly\n \n') file.write('MODULE ROSCO_Types\n') file.write('USE, INTRINSIC :: ISO_C_Binding\n') file.write('USE Constants\n') @@ -50,12 +50,12 @@ def write_types(yfile): def write_roscoio(yfile): ''' Writes ROSCO_IO.f90 - -- All additions to the types should be added to rosco_types.yaml! + -- All additions to the types should be added to ! Parameters: ----------- yfile: string - path to rosco_types.yaml + path to ''' reg = load_yaml(yfile) reg.pop('default_types') @@ -63,7 +63,7 @@ def write_roscoio(yfile): file = open(registry_fname, 'w') file.write('! ROSCO IO\n') file.write('! This file is automatically generated by write_registry.py using ROSCO v{}\n'.format(ROSCO_toolbox.__version__)) - file.write('! For any modification to the registry, please edit the rosco_types.yaml accordingly\n \n') + file.write('! For any modification to the registry, please edit the accordingly\n \n') file.write('MODULE ROSCO_IO\n') file.write(' USE, INTRINSIC :: ISO_C_Binding\n') file.write(' USE ROSCO_Types\n') @@ -163,7 +163,7 @@ def write_roscoio(yfile): file.write(' Close ( Un )\n') file.write(' ENDIF\n') file.write(' ! Read Parameter files\n') - file.write(' CALL ReadControlParameterFileSub(CntrPar, zmqVar, LocalVar%ACC_INFILE, LocalVar%ACC_INFILE_SIZE, ErrVar)\n') + file.write(' CALL (CntrPar, zmqVar, LocalVar%ACC_INFILE, LocalVar%ACC_INFILE_SIZE, ErrVar)\n') file.write(' IF (CntrPar%WE_Mode > 0) THEN\n') file.write(' CALL READCpFile(CntrPar, PerfData, ErrVar)\n') file.write(' ENDIF\n') @@ -237,7 +237,7 @@ def write_roscoio(yfile): # -- Always prints blade(1) for multi-bladed inputss (e.g. BldPitch(1)) lv_strings = [] for lv_idx, localvar in enumerate(reg['LocalVariables']): - if reg['LocalVariables'][localvar]['type'] in ['integer', 'real']: + if reg['LocalVariables'][localvar]['type'] in ['integer', 'real', 'complex']: lv_strings.append(localvar) file.write(' nLocalVars = {}\n'.format(len(lv_strings))) file.write(' Allocate(LocalVarOutData(nLocalVars))\n') @@ -353,6 +353,15 @@ def read_type(param): f90type += ', DIMENSION(:), ALLOCATABLE' elif param['dimension']: f90type += ', DIMENSION{}'.format(param['dimension']) + elif param['type'] == 'complex': + f90type = 'COMPLEX(DbKi)' + if param['allocatable']: + if param['dimension']: + f90type += ', DIMENSION{}, ALLOCATABLE'.format(param['dimension']) + else: + f90type += ', DIMENSION(:), ALLOCATABLE' + elif param['dimension']: + f90type += ', DIMENSION{}'.format(param['dimension']) elif param['type'] == 'float': f90type = 'REAL(ReKi)' if param['allocatable']: @@ -399,6 +408,6 @@ def read_type(param): return f90type if __name__ == '__main__': - fname = os.path.join(os.path.dirname(os.path.abspath(__file__)),'rosco_types.yaml') + fname = os.path.join(os.path.dirname(os.path.abspath(__file__)),'') generate(fname) diff --git a/ROSCO/src/Controllers.f90 b/ROSCO/src/Controllers.f90 index fd7a15f4..78b7f514 100644 --- a/ROSCO/src/Controllers.f90 +++ b/ROSCO/src/Controllers.f90 @@ -42,6 +42,8 @@ SUBROUTINE PitchControl(avrSWAP, CntrPar, LocalVar, objInst, DebugVar, ErrVar) CHARACTER(*), PARAMETER :: RoutineName = 'PitchControl' + ! Local + ! ------- Blade Pitch Controller -------- ! Load PC State IF (LocalVar%PC_State == 1) THEN ! PI BldPitch control @@ -60,7 +62,7 @@ SUBROUTINE PitchControl(avrSWAP, CntrPar, LocalVar, objInst, DebugVar, ErrVar) LocalVar%PC_PitComT = PIController(LocalVar%PC_SpdErr, LocalVar%PC_KP, LocalVar%PC_KI, LocalVar%PC_MinPit, LocalVar%PC_MaxPit, LocalVar%DT, LocalVar%BlPitch(1), LocalVar%piP, LocalVar%restart, objInst%instPI) DebugVar%PC_PICommand = LocalVar%PC_PitComT ! Find individual pitch control contribution - IF ((CntrPar%IPC_ControlMode >= 1) .OR. (CntrPar%Y_ControlMode == 2)) THEN + IF ((CntrPar%IPC_ControlMode >= 1) .OR. ((CntrPar%Y_ControlMode == 2) .OR. (CntrPar%AWC_Mode == 2))) THEN CALL IPC(CntrPar, LocalVar, objInst, DebugVar, ErrVar) ELSE LocalVar%IPC_PitComF = 0.0 ! THIS IS AN ARRAY!! @@ -102,7 +104,7 @@ SUBROUTINE PitchControl(avrSWAP, CntrPar, LocalVar, objInst, DebugVar, ErrVar) ! Combine and saturate all individual pitch commands in software DO K = 1,LocalVar%NumBl ! Loop through all blades, add IPC contribution and limit pitch rate LocalVar%PitCom(K) = LocalVar%PC_PitComT + LocalVar%FA_PitCom(K) - LocalVar%PitCom(K) = saturate(LocalVar%PitCom(K), LocalVar%PC_MinPit, CntrPar%PC_MaxPit) ! Saturate the command using the pitch satauration limits + LocalVar%PitCom(K) = saturate(LocalVar%PitCom(K), LocalVar%PC_MinPit, CntrPar%PC_MaxPit) ! Saturate the command using the pitch saturation limits LocalVar%PitCom(K) = LocalVar%PitCom(K) + LocalVar%IPC_PitComF(K) ! Add IPC ! Hard IPC saturation by peak shaving limit @@ -124,6 +126,11 @@ SUBROUTINE PitchControl(avrSWAP, CntrPar, LocalVar, objInst, DebugVar, ErrVar) ENDIF ENDIF + ! Active wake control + IF (CntrPar%AWC_Mode == 1) THEN + CALL ActiveWakeControl(CntrPar, LocalVar) + ENDIF + ! Place pitch actuator here, so it can be used with or without open-loop DO K = 1,LocalVar%NumBl ! Loop through all blades, add IPC contribution and limit pitch rate IF (CntrPar%PA_Mode > 0) THEN @@ -395,6 +402,9 @@ SUBROUTINE IPC(CntrPar, LocalVar, objInst, DebugVar, ErrVar) REAL(DbKi) :: axisTilt_2P, axisYaw_2P, axisYawF_2P ! Direct axis and quadrature axis outputted by Coleman transform, 1P REAL(DbKi) :: axisYawIPC_1P ! IPC contribution with yaw-by-IPC component REAL(DbKi) :: Y_MErr, Y_MErrF, Y_MErrF_IPC ! Unfiltered and filtered yaw alignment error [rad] + REAL(DbKi) :: AWC_TiltAmp, AWC_YawAmp ! Tilt and yaw amplitude for AWC + REAL(DbKi) :: AWC_TiltAngle, AWC_YawAngle ! Tilt and yaw initial phase angle for AWC + REAL(DbKi) :: AWC_TiltFreq, AWC_YawFreq ! Tilt and yaw frequency for AWC CHARACTER(*), PARAMETER :: RoutineName = 'IPC' @@ -432,7 +442,7 @@ SUBROUTINE IPC(CntrPar, LocalVar, objInst, DebugVar, ErrVar) ENDIF ! Integrate the signal and multiply with the IPC gain - IF ((CntrPar%IPC_ControlMode >= 1) .AND. (CntrPar%Y_ControlMode /= 2)) THEN + IF ((CntrPar%IPC_ControlMode >= 1) .AND. ((CntrPar%Y_ControlMode /= 2) .AND. (CntrPar%AWC_Mode == 0))) THEN ! IPC disabled if AWC is on (add warning?) LocalVar%IPC_axisTilt_1P = PIController(axisTilt_1P, LocalVar%IPC_KP(1), LocalVar%IPC_KI(1), -LocalVar%IPC_IntSat, LocalVar%IPC_IntSat, LocalVar%DT, 0.0_DbKi, LocalVar%piP, LocalVar%restart, objInst%instPI) LocalVar%IPC_axisYaw_1P = PIController(axisYawF_1P, LocalVar%IPC_KP(1), LocalVar%IPC_KI(1), -LocalVar%IPC_IntSat, LocalVar%IPC_IntSat, LocalVar%DT, 0.0_DbKi, LocalVar%piP, LocalVar%restart, objInst%instPI) @@ -440,6 +450,28 @@ SUBROUTINE IPC(CntrPar, LocalVar, objInst, DebugVar, ErrVar) LocalVar%IPC_axisTilt_2P = PIController(axisTilt_2P, LocalVar%IPC_KP(2), LocalVar%IPC_KI(2), -LocalVar%IPC_IntSat, LocalVar%IPC_IntSat, LocalVar%DT, 0.0_DbKi, LocalVar%piP, LocalVar%restart, objInst%instPI) LocalVar%IPC_axisYaw_2P = PIController(axisYawF_2P, LocalVar%IPC_KP(2), LocalVar%IPC_KI(2), -LocalVar%IPC_IntSat, LocalVar%IPC_IntSat, LocalVar%DT, 0.0_DbKi, LocalVar%piP, LocalVar%restart, objInst%instPI) END IF + ! Determine AWC-IPC tilt and yaw moments + ELSEIF ((CntrPar%AWC_Mode == 2) .AND. (CntrPar%AWC_n(1) /= 0)) THEN + IF (CntrPar%AWC_NumModes == 1) THEN + AWC_TiltAmp = CntrPar%AWC_amp(1) + AWC_YawAmp = CntrPar%AWC_amp(1) + AWC_TiltAngle = 0 + AWC_YawAngle = CntrPar%AWC_clockangle(1) + AWC_TiltFreq = CntrPar%AWC_freq(1) + AWC_YawFreq = CntrPar%AWC_freq(1) + ELSE + AWC_TiltAmp = CntrPar%AWC_amp(1) + AWC_YawAmp = CntrPar%AWC_amp(2) + AWC_TiltAngle = CntrPar%AWC_clockangle(1) + AWC_YawAngle = CntrPar%AWC_clockangle(2) + AWC_TiltFreq = CntrPar%AWC_freq(1) + AWC_YawFreq = CntrPar%AWC_freq(2) + END IF + + LocalVar%IPC_axisTilt_1P = PI/180*AWC_TiltAmp*sin(LocalVar%Time*2*PI*AWC_TiltFreq+AWC_TiltAngle*PI/180) + LocalVar%IPC_axisYaw_1P = PI/180*AWC_YawAmp*sin(LocalVar%Time*2*PI*AWC_YawFreq+AWC_YawAngle*PI/180) + LocalVar%IPC_axisTilt_2P = 0.0 + LocalVar%IPC_axisYaw_2P = 0.0 ELSE LocalVar%IPC_axisTilt_1P = 0.0 LocalVar%IPC_axisYaw_1P = 0.0 @@ -469,10 +501,10 @@ SUBROUTINE IPC(CntrPar, LocalVar, objInst, DebugVar, ErrVar) END DO ! debugging - DebugVar%axisTilt_1P = axisTilt_1P - DebugVar%axisYaw_1P = axisYaw_1P - DebugVar%axisTilt_2P = axisTilt_2P - DebugVar%axisYaw_2P = axisYaw_2P + DebugVar%axisTilt_1P = LocalVar%IPC_axisTilt_1P ! axisTilt_1P + DebugVar%axisYaw_1P = LocalVar%IPC_axisYaw_1P ! axisYaw_1P + DebugVar%axisTilt_2P = LocalVar%IPC_axisTilt_2P + DebugVar%axisYaw_2P = LocalVar%IPC_axisYaw_2P @@ -601,4 +633,56 @@ SUBROUTINE FlapControl(avrSWAP, CntrPar, LocalVar, objInst) RETURN ENDIF END SUBROUTINE FlapControl + + +!------------------------------------------------------------------------------------------------------------------------------- + SUBROUTINE ActiveWakeControl(CntrPar, LocalVar) + ! Active wake controller + ! AWC_Mode = 0, No active wake control + ! AWC_Mode = 1, SNL active wake control + ! AWC_Mode = 2, NREL active wake control + USE ROSCO_Types, ONLY : ControlParameters, LocalVariables, ObjectInstances + + TYPE(ControlParameters), INTENT(INOUT) :: CntrPar + TYPE(LocalVariables), INTENT(INOUT) :: LocalVar + + ! Local vars + REAL(DbKi), PARAMETER :: phi1 = 0.0 ! Phase difference from first to first blade + REAL(DbKi), PARAMETER :: phi2 = 2.0/3.0*PI ! Phase difference from first to second blade + REAL(DbKi), PARAMETER :: phi3 = 4.0/3.0*PI ! Phase difference from first to third blade + REAL(DbKi), DIMENSION(3) :: AWC_angle + COMPLEX(DbKi), DIMENSION(3) :: AWC_complexangle + COMPLEX(DbKi) :: complexI = (0.0, 1.0) + INTEGER(IntKi) :: Imode, K ! Index used for looping through AWC modes + REAL(DbKi) :: clockang ! Clock angle for AWC pitching + REAL(DbKi) :: omega ! angular frequency for AWC pitching in rad/s + REAL(DbKi) :: amp ! amplitude for AWC pitching in radian + + + ! Compute the AWC pitch settings + IF (CntrPar%AWC_Mode == 1) THEN + + LocalVar%AWC_complexangle = 0.0D0 + + DO Imode = 1,CntrPar%AWC_NumModes + clockang = CntrPar%AWC_clockangle(Imode)*PI/180.0_DbKi + omega = CntrPar%AWC_freq(Imode)*PI*2.0_DbKi + AWC_angle(1) = omega * LocalVar%Time - CntrPar%AWC_n(Imode) * (LocalVar%Azimuth + phi1 + clockang) + AWC_angle(2) = omega * LocalVar%Time - CntrPar%AWC_n(Imode) * (LocalVar%Azimuth + phi2 + clockang) + AWC_angle(3) = omega * LocalVar%Time - CntrPar%AWC_n(Imode) * (LocalVar%Azimuth + phi3 + clockang) + ! Add the forcing contribution to LocalVar%AWC_complexangle + amp = CntrPar%AWC_amp(Imode)*PI/180.0_DbKi + DO K = 1,LocalVar%NumBl ! Loop through all blades + LocalVar%AWC_complexangle(K) = LocalVar%AWC_complexangle(K) + amp * EXP(complexI * (AWC_angle(K))) + END DO + END DO + + DO K = 1,LocalVar%NumBl ! Loop through all blades, apply AWC_angle + LocalVar%PitCom(K) = LocalVar%PitCom(K) + REAL(LocalVar%AWC_complexangle(K)) + END DO + + ENDIF + + END SUBROUTINE ActiveWakeControl + END MODULE Controllers diff --git a/ROSCO/src/ROSCO_IO.f90 b/ROSCO/src/ROSCO_IO.f90 index d465d512..f0c20c5d 100644 --- a/ROSCO/src/ROSCO_IO.f90 +++ b/ROSCO/src/ROSCO_IO.f90 @@ -131,6 +131,9 @@ SUBROUTINE WriteRestartFile(LocalVar, CntrPar, ErrVar, objInst, RootName, size_a WRITE( Un, IOSTAT=ErrStat) LocalVar%ACC_INFILE_SIZE WRITE( Un, IOSTAT=ErrStat) LocalVar%ACC_INFILE WRITE( Un, IOSTAT=ErrStat) LocalVar%restart + WRITE( Un, IOSTAT=ErrStat) LocalVar%AWC_complexangle(1) + WRITE( Un, IOSTAT=ErrStat) LocalVar%AWC_complexangle(2) + WRITE( Un, IOSTAT=ErrStat) LocalVar%AWC_complexangle(3) WRITE( Un, IOSTAT=ErrStat) LocalVar%WE%om_r WRITE( Un, IOSTAT=ErrStat) LocalVar%WE%v_t WRITE( Un, IOSTAT=ErrStat) LocalVar%WE%v_m @@ -315,6 +318,9 @@ SUBROUTINE ReadRestartFile(avrSWAP, LocalVar, CntrPar, objInst, PerfData, RootNa ALLOCATE(LocalVar%ACC_INFILE(LocalVar%ACC_INFILE_SIZE)) READ( Un, IOSTAT=ErrStat) LocalVar%ACC_INFILE READ( Un, IOSTAT=ErrStat) LocalVar%restart + READ( Un, IOSTAT=ErrStat) LocalVar%AWC_complexangle(1) + READ( Un, IOSTAT=ErrStat) LocalVar%AWC_complexangle(2) + READ( Un, IOSTAT=ErrStat) LocalVar%AWC_complexangle(3) READ( Un, IOSTAT=ErrStat) LocalVar%WE%om_r READ( Un, IOSTAT=ErrStat) LocalVar%WE%v_t READ( Un, IOSTAT=ErrStat) LocalVar%WE%v_m @@ -442,7 +448,7 @@ SUBROUTINE Debug(LocalVar, CntrPar, DebugVar, ErrVar, avrSWAP, RootName, size_av '[rad/s]', '[rad/s]', '[m/s]', '[rad]', '[rad]', & '[N/A]', '[N/A]', '[N/A]', '[N/A]', '[rad/s]', & '[deg]', '[deg]', '[deg]', '[N/A]'] - nLocalVars = 71 + nLocalVars = 72 Allocate(LocalVarOutData(nLocalVars)) Allocate(LocalVarOutStrings(nLocalVars)) LocalVarOutData(1) = LocalVar%iStatus @@ -516,6 +522,7 @@ SUBROUTINE Debug(LocalVar, CntrPar, DebugVar, ErrVar, avrSWAP, RootName, size_av LocalVarOutData(69) = LocalVar%Flp_Angle(1) LocalVarOutData(70) = LocalVar%RootMyb_Last(1) LocalVarOutData(71) = LocalVar%ACC_INFILE_SIZE + LocalVarOutData(72) = LocalVar%AWC_complexangle(1) LocalVarOutStrings = [CHARACTER(15) :: 'iStatus', 'Time', 'DT', 'VS_GenPwr', 'GenSpeed', & 'RotSpeed', 'NacHeading', 'NacVane', 'HorWindV', 'rootMOOP', & 'rootMOOPF', 'BlPitch', 'BlPitchCMeas', 'Azimuth', 'NumBl', & @@ -530,7 +537,7 @@ SUBROUTINE Debug(LocalVar, CntrPar, DebugVar, ErrVar, avrSWAP, RootName, size_av 'VS_SpdErrAr', 'VS_SpdErrBr', 'VS_SpdErr', 'VS_State', 'VS_Rgn3Pitch', & 'WE_Vw', 'WE_Vw_F', 'WE_VwI', 'WE_VwIdot', 'VS_LastGenTrqF', & 'Fl_PitCom', 'NACIMU_FA_AccF', 'FA_AccF', 'Flp_Angle', 'RootMyb_Last', & - 'ACC_INFILE_SIZE'] + 'ACC_INFILE_SIZE', 'AWC_complexangle'] ! Initialize debug file IF ((LocalVar%iStatus == 0) .OR. (LocalVar%iStatus == -9)) THEN ! .TRUE. if we're on the first call to the DLL IF (CntrPar%LoggingLevel > 0) THEN diff --git a/ROSCO/src/ROSCO_Types.f90 b/ROSCO/src/ROSCO_Types.f90 index 2c4143bc..105c0edf 100644 --- a/ROSCO/src/ROSCO_Types.f90 +++ b/ROSCO/src/ROSCO_Types.f90 @@ -114,6 +114,12 @@ MODULE ROSCO_Types INTEGER(IntKi) :: PA_Mode ! Pitch actuator mode {0 - not used, 1 - first order filter, 2 - second order filter} REAL(DbKi) :: PA_CornerFreq ! Pitch actuator bandwidth/cut-off frequency [rad/s] REAL(DbKi) :: PA_Damping ! Pitch actuator damping ratio [-, unused if PA_Mode = 1] + INTEGER(IntKi) :: AWC_Mode ! Active wake control mode [0 - unused, 1 - SNL method] + INTEGER(IntKi) :: AWC_NumModes ! AWC- Number of modes to include [-] + INTEGER(IntKi), DIMENSION(:), ALLOCATABLE :: AWC_n ! AWC azimuthal mode [-] + REAL(DbKi), DIMENSION(:), ALLOCATABLE :: AWC_freq ! AWC frequency [Hz] + REAL(DbKi), DIMENSION(:), ALLOCATABLE :: AWC_amp ! AWC amplitude [deg] + REAL(DbKi), DIMENSION(:), ALLOCATABLE :: AWC_clockangle ! AWC clocking angle [deg] INTEGER(IntKi) :: PF_Mode ! Pitch actuator fault mode {0 - not used, 1 - offsets on one or more blades} REAL(DbKi), DIMENSION(:), ALLOCATABLE :: PF_Offsets ! Pitch actuator fault offsets for blade 1-3 [rad/s] INTEGER(IntKi) :: Ext_Mode ! External control mode (0 - not used, 1 - call external control library) @@ -263,6 +269,7 @@ MODULE ROSCO_Types INTEGER(IntKi) :: ACC_INFILE_SIZE ! Length of parameter input filename CHARACTER, DIMENSION(:), ALLOCATABLE :: ACC_INFILE ! Parameter input filename LOGICAL :: restart ! Restart flag + COMPLEX(DbKi) :: AWC_complexangle(3) ! Complex angle for each blade, sum of modes? TYPE(WE) :: WE ! Wind speed estimator parameters derived type TYPE(FilterParameters) :: FP ! Filter parameters derived type TYPE(piParams) :: piP ! PI parameters derived type diff --git a/ROSCO/src/ReadSetParameters.f90 b/ROSCO/src/ReadSetParameters.f90 index 9ba9e80c..db5f19aa 100644 --- a/ROSCO/src/ReadSetParameters.f90 +++ b/ROSCO/src/ReadSetParameters.f90 @@ -264,6 +264,7 @@ SUBROUTINE ReadControlParameterFileSub(CntrPar, zmqVar, accINFILE, accINFILE_siz CALL ParseInput(UnControllerParameters,CurLine,'OL_Mode',accINFILE(1),CntrPar%OL_Mode,ErrVar) CALL ParseInput(UnControllerParameters,CurLine,'PA_Mode',accINFILE(1),CntrPar%PA_Mode,ErrVar) CALL ParseInput(UnControllerParameters,CurLine,'PF_Mode',accINFILE(1),CntrPar%PF_Mode,ErrVar) + CALL ParseInput(UnControllerParameters,CurLine,'AWC_Mode',accINFILE(1),CntrPar%AWC_Mode,ErrVar) CALL ParseInput(UnControllerParameters,CurLine,'Ext_Mode',accINFILE(1),CntrPar%Ext_Mode,ErrVar) CALL ParseInput(UnControllerParameters,CurLine,'ZMQ_Mode',accINFILE(1), CntrPar%ZMQ_Mode,ErrVar) @@ -415,6 +416,15 @@ SUBROUTINE ReadControlParameterFileSub(CntrPar, zmqVar, accINFILE, accINFILE_siz CALL ReadEmptyLine(UnControllerParameters,CurLine) CALL ParseAry(UnControllerParameters, CurLine,'PF_Offsets', CntrPar%PF_Offsets, 3, accINFILE(1), ErrVar) CALL ReadEmptyLine(UnControllerParameters,CurLine) + + !------------ AWC input ------------ + CALL ReadEmptyLine(UnControllerParameters,CurLine) + CALL ParseInput(UnControllerParameters,CurLine,'AWC_NumModes', accINFILE(1),CntrPar%AWC_NumModes, ErrVar) + CALL ParseAry( UnControllerParameters,CurLine,'AWC_n', CntrPar%AWC_n, CntrPar%AWC_NumModes, accINFILE(1), ErrVar) + CALL ParseAry( UnControllerParameters,CurLine,'AWC_freq', CntrPar%AWC_freq, CntrPar%AWC_NumModes, accINFILE(1), ErrVar) + CALL ParseAry( UnControllerParameters,CurLine,'AWC_amp', CntrPar%AWC_amp, CntrPar%AWC_NumModes, accINFILE(1), ErrVar) + CALL ParseAry( UnControllerParameters,CurLine,'AWC_clockangle',CntrPar%AWC_clockangle,CntrPar%AWC_NumModes, accINFILE(1), ErrVar) + CALL ReadEmptyLine(UnControllerParameters,CurLine) !------------ External control interface ------------ CALL ReadEmptyLine(UnControllerParameters,CurLine) @@ -1047,4 +1057,4 @@ SUBROUTINE CheckInputs(LocalVar, CntrPar, avrSWAP, ErrVar, size_avcMSG) END SUBROUTINE CheckInputs -END MODULE ReadSetParameters +END MODULE ReadSetParameters \ No newline at end of file diff --git a/ROSCO_toolbox/controller.py b/ROSCO_toolbox/controller.py index f7cae56a..d905c1f0 100644 --- a/ROSCO_toolbox/controller.py +++ b/ROSCO_toolbox/controller.py @@ -63,8 +63,9 @@ def __init__(self, controller_params): self.Fl_Mode = controller_params['Fl_Mode'] self.TD_Mode = controller_params['TD_Mode'] self.Flp_Mode = controller_params['Flp_Mode'] - self.PA_Mode = controller_params['PA_Mode'] - self.PF_Mode = controller_params['PF_Mode'] + self.PA_Mode = controller_params['PA_Mode'] + self.PF_Mode = controller_params['PF_Mode'] + self.AWC_Mode = controller_params['AWC_Mode'] self.Ext_Mode = controller_params['Ext_Mode'] self.ZMQ_Mode = controller_params['ZMQ_Mode'] diff --git a/ROSCO_toolbox/inputs/toolbox_schema.yaml b/ROSCO_toolbox/inputs/toolbox_schema.yaml index 432785df..55d2e628 100644 --- a/ROSCO_toolbox/inputs/toolbox_schema.yaml +++ b/ROSCO_toolbox/inputs/toolbox_schema.yaml @@ -203,6 +203,12 @@ properties: maximum: 1 default: 0 description: Pitch fault mode {0 - not used, 1 - constant offset on one or more blades} + AWC_Mode: + type: number + minimum: 0 + maximum: 2 + default: 0 + description: Active wake control mode {0 - not used, 1 - SNL method, 2 - NREL method} Ext_Mode: type: number minimum: 0 @@ -864,6 +870,44 @@ properties: type: number description: Pitch angle offsets for each blade (array with length of 3) units: rad + AWC_Mode: + type: number + minimum: 0 + maximum: 2 + default: 0 + description: Active wake control mode {0 - not used, 1 - SNL method, 2 - NREL method} + AWC_NumModes: + type: number + description: Number of AWC modes (only used in SNL method) + units: rad + default: 1 + AWC_n: + type: array + items: + type: number + description: AWC azimuthal number (only used in SNL method) + default: [1] + AWC_freq: + type: array + items: + type: number + description: AWC frequency [Hz] + units: Hz + default: [0.05] + AWC_amp: + type: array + items: + type: number + description: AWC amplitude [deg] + units: deg + default: [1.0] + AWC_clockangle: + type: array + items: + type: number + description: AWC clock angle [deg] + units: rad/s + default: [0] linmodel_tuning: type: object diff --git a/ROSCO_toolbox/ofTools/case_gen/CaseLibrary.py b/ROSCO_toolbox/ofTools/case_gen/CaseLibrary.py index aa4d1ce4..d1aa7809 100644 --- a/ROSCO_toolbox/ofTools/case_gen/CaseLibrary.py +++ b/ROSCO_toolbox/ofTools/case_gen/CaseLibrary.py @@ -127,7 +127,7 @@ def power_curve(**wind_case_opts): # Constant wind speed, multiple wind speeds, define below # Runtime - T_max = 400. + T_max = wind_case_opts.get('TMax',400.) if 'U' in wind_case_opts: U = wind_case_opts['U'] diff --git a/ROSCO_toolbox/ofTools/case_gen/runFAST_pywrapper.py b/ROSCO_toolbox/ofTools/case_gen/runFAST_pywrapper.py index 886d496b..e347ed7f 100644 --- a/ROSCO_toolbox/ofTools/case_gen/runFAST_pywrapper.py +++ b/ROSCO_toolbox/ofTools/case_gen/runFAST_pywrapper.py @@ -229,6 +229,7 @@ def __init__(self): run_dir = os.path.dirname( os.path.dirname( os.path.dirname( os.path.realpath(__file__) ) ) ) + os.sep self.FAST_exe = os.path.join(run_dir, 'local/bin/openfast') # Path to executable + print(self.FAST_exe) # self.FAST_lib = os.path.join(lib_dir, 'libopenfastlib'+libext) self.FAST_InputFile = None self.FAST_directory = None diff --git a/ROSCO_toolbox/ofTools/fast_io/FAST_reader.py b/ROSCO_toolbox/ofTools/fast_io/FAST_reader.py index 2f809f3b..32baf0d6 100644 --- a/ROSCO_toolbox/ofTools/fast_io/FAST_reader.py +++ b/ROSCO_toolbox/ofTools/fast_io/FAST_reader.py @@ -777,8 +777,8 @@ def read_AeroDyn15(self): f.readline() self.fst_vt['AeroDyn15']['UAMod'] = int(f.readline().split()[0]) self.fst_vt['AeroDyn15']['FLookup'] = bool_read(f.readline().split()[0]) - # self.fst_vt['AeroDyn15']['UAStartRad'] = float_read(f.readline().split()[0]) - # self.fst_vt['AeroDyn15']['UAEndRad'] = float_read(f.readline().split()[0]) + #self.fst_vt['AeroDyn15']['UAStartRad'] = float_read(f.readline().split()[0]) + #self.fst_vt['AeroDyn15']['UAEndRad'] = float_read(f.readline().split()[0]) # Airfoil Information f.readline() diff --git a/ROSCO_toolbox/utilities.py b/ROSCO_toolbox/utilities.py index 04cf98f3..fe83d05a 100644 --- a/ROSCO_toolbox/utilities.py +++ b/ROSCO_toolbox/utilities.py @@ -84,6 +84,7 @@ def write_DISCON(turbine, controller, param_file='DISCON.IN', txt_filename='Cp_C file.write('{0:<12d} ! OL_Mode - Open loop control mode {{0: no open loop control, 1: open loop control vs. time}}\n'.format(int(rosco_vt['OL_Mode']))) file.write('{0:<12d} ! PA_Mode - Pitch actuator mode {{0 - not used, 1 - first order filter, 2 - second order filter}}\n'.format(int(rosco_vt['PA_Mode']))) file.write('{0:<12d} ! PF_Mode - Pitch fault mode {{0 - not used, 1 - constant offset on one or more blades}}\n'.format(int(rosco_vt['PF_Mode']))) + file.write('{0:<12d} ! AWC_Mode - Active wake control {{0 - not used, 1 - SNL method, 2 - NREL method}}\n'.format(int(rosco_vt['AWC_Mode']))) file.write('{0:<12d} ! Ext_Mode - External control mode {{0 - not used, 1 - call external dynamic library}}\n'.format(int(rosco_vt['Ext_Mode']))) file.write('{0:<12d} ! ZMQ_Mode - Fuse ZeroMQ interface {{0: unused, 1: Yaw Control}}\n'.format(int(rosco_vt['ZMQ_Mode']))) @@ -209,6 +210,13 @@ def write_DISCON(turbine, controller, param_file='DISCON.IN', txt_filename='Cp_C file.write('!------- Pitch Actuator Faults -----------------------------------------------------\n') file.write('{} ! PF_Offsets - Constant blade pitch offsets for blades 1-3 [rad]\n'.format(''.join('{:<10.8f} '.format(rosco_vt['PF_Offsets'][i]) for i in range(3)))) file.write('\n') + file.write('!------- Active Wake Control -----------------------------------------------------\n') + file.write('{0:<12d} ! AWC_NumModes - number of forcing modes\n'.format(int(rosco_vt['AWC_NumModes']))) + file.write('{} ! AWC_n - azimuthal mode number(s) (i.e., the azimuthal mode number relates to the number and direction of the lobes of the wake structure according to the classical spatio-temporal Fourier decomposition of an arbitrary quantity q, sigma(sigma(q*exp(i*n*theta)*exp(i*omega*time))). For the case of a non-time-varying flow (i.e., where omega = 0), the azimuthal mode number specifies the number of cycles of blade pitch oscillation per one rotation around the rotor azimuth.)\n'.format(write_array(rosco_vt['AWC_n'],'<4d'))) + file.write('{} ! AWC_freq - frequency(s) of forcing mode(s) [Hz]\n'.format(write_array(rosco_vt['AWC_freq'],'<6.4f'))) + file.write('{} ! AWC_amp - pitch amplitude(s) of forcing mode(s) (note that AWC_amp specifies the amplitude of each individual mode so that the total amplitude of pitching will be the sum of AWC_amp) [deg]\n'.format(write_array(rosco_vt['AWC_amp'],'<6.4f'))) + file.write('{} ! AWC_clockangle - clocking angle(s) of forcing mode(s) [deg]\n'.format(write_array(rosco_vt['AWC_clockangle'],'<6.4f'))) + file.write('\n') file.write('!------- External Controller Interface -----------------------------------------------------\n') file.write('"{}" ! DLL_FileName - Name/location of the dynamic library in the Bladed-DLL format\n'.format(rosco_vt['DLL_FileName'])) file.write('"{}" ! DLL_InFile - Name of input file sent to the DLL (-)\n'.format(rosco_vt['DLL_InFile'])) @@ -410,6 +418,7 @@ def DISCON_dict(turbine, controller, txt_filename=None): DISCON_dict['OL_Mode'] = int(controller.OL_Mode) DISCON_dict['PF_Mode'] = int(controller.PF_Mode) DISCON_dict['PA_Mode'] = int(controller.PA_Mode) + DISCON_dict['AWC_Mode'] = int(controller.AWC_Mode) DISCON_dict['Ext_Mode'] = int(controller.Ext_Mode) DISCON_dict['ZMQ_Mode'] = int(controller.ZMQ_Mode) # ------- FILTERS ------- @@ -611,3 +620,10 @@ def list_check(x, return_bool=True): return is_list else: return y + +def write_array(array,format='<.4f'): + + if not hasattr(array,'__len__'): #not an array + array = [array] + + return ''.join(['{:{}} '.format(item,format) for item in array]) \ No newline at end of file diff --git a/Test_Cases/NREL-5MW/DISCON.IN b/Test_Cases/NREL-5MW/DISCON.IN index e3c2ae45..84b3971c 100644 --- a/Test_Cases/NREL-5MW/DISCON.IN +++ b/Test_Cases/NREL-5MW/DISCON.IN @@ -140,6 +140,13 @@ !------- Pitch Actuator Faults ----------------------------------------------------- 0.00000000 0.00000000 0.00000000 ! PF_Offsets - Constant blade pitch offsets for blades 1-3 [rad] +!------- Active Wake Control ----------------------------------------------------- +1 ! AWC_NumModes - AWC azimuthal mode number(s) (only used in SNL method) +1 ! AWC_n - AWC azimuthal number (only used in SNL method) +0.3142 ! AWC_omega - AWC frequency [rad/s] +0.0175 ! AWC_amp - AWC amplitude [rad] +0.0000 ! AWC_clockangle - WC clock angle [deg] + !------- External Controller Interface ----------------------------------------------------- "unused" ! DLL_FileName - Name/location of the dynamic library in the Bladed-DLL format "unused" ! DLL_InFile - Name of input file sent to the DLL (-) diff --git a/setup.py b/setup.py index 70fa943f..d9eae087 100644 --- a/setup.py +++ b/setup.py @@ -43,10 +43,10 @@ REQUIRED = [ 'matplotlib', 'numpy', - 'pytest', + #'pytest', 'scipy', 'pyYAML', - 'future', + #'future', 'pandas' ] From 687b7603e149ac094a42b3e02818032d3b592fc3 Mon Sep 17 00:00:00 2001 From: jfrederik-nrel Date: Mon, 27 Feb 2023 17:02:28 -0700 Subject: [PATCH 056/224] Undo unintentional changes to wrie_registry.py --- ROSCO/rosco_registry/write_registry.py | 16 ++++++++-------- 1 file changed, 8 insertions(+), 8 deletions(-) diff --git a/ROSCO/rosco_registry/write_registry.py b/ROSCO/rosco_registry/write_registry.py index 0368404a..41f0bea5 100644 --- a/ROSCO/rosco_registry/write_registry.py +++ b/ROSCO/rosco_registry/write_registry.py @@ -13,12 +13,12 @@ def generate(yfile): def write_types(yfile): ''' Writes ROSCO_types.f90 - -- All additions to the types should be added to ! + -- All additions to the types should be added to rosco_types.yaml! Parameters: ----------- yfile: string - path to + path to rosco_types.yaml ''' reg = load_yaml(yfile) reg.pop('default_types') @@ -27,7 +27,7 @@ def write_types(yfile): # Header file.write('! ROSCO Registry\n') file.write('! This file is automatically generated by write_registry.py using ROSCO v{}\n'.format(ROSCO_toolbox.__version__)) - file.write('! For any modification to the registry, please edit the accordingly\n \n') + file.write('! For any modification to the registry, please edit the rosco_types.yaml accordingly\n \n') file.write('MODULE ROSCO_Types\n') file.write('USE, INTRINSIC :: ISO_C_Binding\n') file.write('USE Constants\n') @@ -50,12 +50,12 @@ def write_types(yfile): def write_roscoio(yfile): ''' Writes ROSCO_IO.f90 - -- All additions to the types should be added to ! + -- All additions to the types should be added to rosco_types.yaml! Parameters: ----------- yfile: string - path to + path to rosco_types.yaml ''' reg = load_yaml(yfile) reg.pop('default_types') @@ -63,7 +63,7 @@ def write_roscoio(yfile): file = open(registry_fname, 'w') file.write('! ROSCO IO\n') file.write('! This file is automatically generated by write_registry.py using ROSCO v{}\n'.format(ROSCO_toolbox.__version__)) - file.write('! For any modification to the registry, please edit the accordingly\n \n') + file.write('! For any modification to the registry, please edit the rosco_types.yaml accordingly\n \n') file.write('MODULE ROSCO_IO\n') file.write(' USE, INTRINSIC :: ISO_C_Binding\n') file.write(' USE ROSCO_Types\n') @@ -163,7 +163,7 @@ def write_roscoio(yfile): file.write(' Close ( Un )\n') file.write(' ENDIF\n') file.write(' ! Read Parameter files\n') - file.write(' CALL (CntrPar, zmqVar, LocalVar%ACC_INFILE, LocalVar%ACC_INFILE_SIZE, ErrVar)\n') + file.write(' CALL ReadControlParameterFileSub(CntrPar, zmqVar, LocalVar%ACC_INFILE, LocalVar%ACC_INFILE_SIZE, ErrVar)\n') file.write(' IF (CntrPar%WE_Mode > 0) THEN\n') file.write(' CALL READCpFile(CntrPar, PerfData, ErrVar)\n') file.write(' ENDIF\n') @@ -408,6 +408,6 @@ def read_type(param): return f90type if __name__ == '__main__': - fname = os.path.join(os.path.dirname(os.path.abspath(__file__)),'') + fname = os.path.join(os.path.dirname(os.path.abspath(__file__)),'rosco_types.yaml') generate(fname) From 70d5771c84a47826d332d282267d579ae34617e5 Mon Sep 17 00:00:00 2001 From: dzalkind Date: Tue, 28 Feb 2023 09:49:34 -0700 Subject: [PATCH 057/224] Fix file writing in AWC section --- ROSCO_toolbox/utilities.py | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/ROSCO_toolbox/utilities.py b/ROSCO_toolbox/utilities.py index 4c92f064..28306c20 100644 --- a/ROSCO_toolbox/utilities.py +++ b/ROSCO_toolbox/utilities.py @@ -212,8 +212,8 @@ def write_DISCON(turbine, controller, param_file='DISCON.IN', txt_filename='Cp_C file.write('\n') file.write('!------- Active Wake Control -----------------------------------------------------\n') file.write('{0:<12d} ! AWC_NumModes - number of forcing modes\n'.format(int(rosco_vt['AWC_NumModes']))) - file.write('{} ! AWC_n - azimuthal mode number(s) (i.e., the azimuthal mode number relates to the number and direction of the lobes of the wake structure according to the classical spatio-temporal Fourier decomposition of an arbitrary quantity q, sigma{sigma{q*exp(i*n*theta)*exp(i*omega*time)}}. For the case of a non-time-varying flow (i.e., where omega = 0), the azimuthal mode number specifies the number of cycles of blade pitch oscillation per one rotation around the rotor azimuth.)\n'.format(write_array(rosco_vt['AWC_n'],'<4d'))) - file.write('{} ! AWC_freq - frequency(s) of forcing mode(s) [Hz]\n'.format(write_array(rosco_vt['AWC_omega'],'<6.4f'))) + file.write('{} ! AWC_n - azimuthal mode number(s) (i.e., the number and direction of the lobes of the wake structure)\n'.format(write_array(rosco_vt['AWC_n'],'<4d'))) + file.write('{} ! AWC_freq - frequency(s) of forcing mode(s) [Hz]\n'.format(write_array(rosco_vt['AWC_freq'],'<6.4f'))) file.write('{} ! AWC_amp - pitch amplitude(s) of forcing mode(s) (note that AWC_amp specifies the amplitude of each individual mode so that the total amplitude of pitching will be the sum of AWC_amp) [deg]\n'.format(write_array(rosco_vt['AWC_amp'],'<6.4f'))) file.write('{} ! AWC_clockangle - clocking angle(s) of forcing mode(s) [deg]\n'.format(write_array(rosco_vt['AWC_clockangle'],'<6.4f'))) file.write('\n') From a9ec14e98e1b6d891515a343463337be7bbe1da3 Mon Sep 17 00:00:00 2001 From: dzalkind Date: Tue, 28 Feb 2023 12:07:37 -0700 Subject: [PATCH 058/224] Update all DISCONs --- Test_Cases/BAR_10/BAR_10_DISCON.IN | 12 ++++++------ .../IEA-15-240-RWT-UMaineSemi/DISCON-UMaineSemi.IN | 12 ++++++------ Test_Cases/NREL-5MW/DISCON.IN | 12 ++++++------ 3 files changed, 18 insertions(+), 18 deletions(-) diff --git a/Test_Cases/BAR_10/BAR_10_DISCON.IN b/Test_Cases/BAR_10/BAR_10_DISCON.IN index 3bc20e2d..e7aa6f37 100644 --- a/Test_Cases/BAR_10/BAR_10_DISCON.IN +++ b/Test_Cases/BAR_10/BAR_10_DISCON.IN @@ -1,5 +1,5 @@ ! Controller parameter input file for the BAR_10 wind turbine -! - File written using ROSCO version 2.7.0 controller tuning logic on 02/10/23 +! - File written using ROSCO version 2.7.0 controller tuning logic on 02/28/23 !------- DEBUG ------------------------------------------------------------ 1 ! LoggingLevel - {0: write no debug files, 1: write standard output .dbg-file, 2: LoggingLevel 1 + ROSCO LocalVars (.dbg2) 3: LoggingLevel 2 + complete avrSWAP-array (.dbg3)} @@ -142,11 +142,11 @@ 0.00000000 0.00000000 0.00000000 ! PF_Offsets - Constant blade pitch offsets for blades 1-3 [rad] !------- Active Wake Control ----------------------------------------------------- -1 ! AWC_NumModes - -1 ! AWC_n - AWC azimuthal number -0.3142 ! AWC_omega - AWC frequency [rad/s] -0.0175 ! AWC_amp - AWC amplitude [rad] -0.0000 ! AWC_clockangle - WC clock angle [deg] +1 ! AWC_NumModes - number of forcing modes +1 ! AWC_n - azimuthal mode number(s) (i.e., the number and direction of the lobes of the wake structure) +0.0500 ! AWC_freq - frequency(s) of forcing mode(s) [Hz] +1.0000 ! AWC_amp - pitch amplitude(s) of forcing mode(s) (note that AWC_amp specifies the amplitude of each individual mode so that the total amplitude of pitching will be the sum of AWC_amp) [deg] +0.0000 ! AWC_clockangle - clocking angle(s) of forcing mode(s) [deg] !------- External Controller Interface ----------------------------------------------------- "unused" ! DLL_FileName - Name/location of the dynamic library in the Bladed-DLL format diff --git a/Test_Cases/IEA-15-240-RWT-UMaineSemi/DISCON-UMaineSemi.IN b/Test_Cases/IEA-15-240-RWT-UMaineSemi/DISCON-UMaineSemi.IN index 811c3b2a..159dfb91 100644 --- a/Test_Cases/IEA-15-240-RWT-UMaineSemi/DISCON-UMaineSemi.IN +++ b/Test_Cases/IEA-15-240-RWT-UMaineSemi/DISCON-UMaineSemi.IN @@ -1,5 +1,5 @@ ! Controller parameter input file for the IEA-15-240-RWT-UMaineSemi wind turbine -! - File written using ROSCO version 2.7.0 controller tuning logic on 02/10/23 +! - File written using ROSCO version 2.7.0 controller tuning logic on 02/28/23 !------- DEBUG ------------------------------------------------------------ 2 ! LoggingLevel - {0: write no debug files, 1: write standard output .dbg-file, 2: LoggingLevel 1 + ROSCO LocalVars (.dbg2) 3: LoggingLevel 2 + complete avrSWAP-array (.dbg3)} @@ -142,11 +142,11 @@ 0.00000000 0.00000000 0.00000000 ! PF_Offsets - Constant blade pitch offsets for blades 1-3 [rad] !------- Active Wake Control ----------------------------------------------------- -1 ! AWC_NumModes - -1 ! AWC_n - AWC azimuthal number -0.3142 ! AWC_omega - AWC frequency [rad/s] -0.0175 ! AWC_amp - AWC amplitude [rad] -0.0000 ! AWC_clockangle - WC clock angle [deg] +1 ! AWC_NumModes - number of forcing modes +1 ! AWC_n - azimuthal mode number(s) (i.e., the number and direction of the lobes of the wake structure) +0.0500 ! AWC_freq - frequency(s) of forcing mode(s) [Hz] +1.0000 ! AWC_amp - pitch amplitude(s) of forcing mode(s) (note that AWC_amp specifies the amplitude of each individual mode so that the total amplitude of pitching will be the sum of AWC_amp) [deg] +0.0000 ! AWC_clockangle - clocking angle(s) of forcing mode(s) [deg] !------- External Controller Interface ----------------------------------------------------- "unused" ! DLL_FileName - Name/location of the dynamic library in the Bladed-DLL format diff --git a/Test_Cases/NREL-5MW/DISCON.IN b/Test_Cases/NREL-5MW/DISCON.IN index e0d1118d..d24c9897 100644 --- a/Test_Cases/NREL-5MW/DISCON.IN +++ b/Test_Cases/NREL-5MW/DISCON.IN @@ -1,5 +1,5 @@ ! Controller parameter input file for the NREL-5MW wind turbine -! - File written using ROSCO version 2.7.0 controller tuning logic on 02/10/23 +! - File written using ROSCO version 2.7.0 controller tuning logic on 02/28/23 !------- DEBUG ------------------------------------------------------------ 1 ! LoggingLevel - {0: write no debug files, 1: write standard output .dbg-file, 2: LoggingLevel 1 + ROSCO LocalVars (.dbg2) 3: LoggingLevel 2 + complete avrSWAP-array (.dbg3)} @@ -142,11 +142,11 @@ 0.00000000 0.00000000 0.00000000 ! PF_Offsets - Constant blade pitch offsets for blades 1-3 [rad] !------- Active Wake Control ----------------------------------------------------- -1 ! AWC_NumModes - -1 ! AWC_n - AWC azimuthal number -0.3142 ! AWC_omega - AWC frequency [rad/s] -0.0175 ! AWC_amp - AWC amplitude [rad] -0.0000 ! AWC_clockangle - WC clock angle [deg] +1 ! AWC_NumModes - number of forcing modes +1 ! AWC_n - azimuthal mode number(s) (i.e., the number and direction of the lobes of the wake structure) +0.0500 ! AWC_freq - frequency(s) of forcing mode(s) [Hz] +1.0000 ! AWC_amp - pitch amplitude(s) of forcing mode(s) (note that AWC_amp specifies the amplitude of each individual mode so that the total amplitude of pitching will be the sum of AWC_amp) [deg] +0.0000 ! AWC_clockangle - clocking angle(s) of forcing mode(s) [deg] !------- External Controller Interface ----------------------------------------------------- "unused" ! DLL_FileName - Name/location of the dynamic library in the Bladed-DLL format From 4604ebbeef3adc0e885d4c5152d6465b6b4427b2 Mon Sep 17 00:00:00 2001 From: dzalkind Date: Tue, 28 Feb 2023 12:11:28 -0700 Subject: [PATCH 059/224] Add 20_awc to test_examples --- Examples/test_examples.py | 1 + 1 file changed, 1 insertion(+) diff --git a/Examples/test_examples.py b/Examples/test_examples.py index 89d9e6c9..59bcf0e0 100644 --- a/Examples/test_examples.py +++ b/Examples/test_examples.py @@ -22,6 +22,7 @@ '17_zeromq_interface', '18_pitch_offsets', # NJA: only runs on unix in CI '19_update_discon_version', + '20_active_wake_control', 'update_rosco_discons', ] From b17f350052bed7aed6dae00c2815957ad696d8a8 Mon Sep 17 00:00:00 2001 From: dzalkind Date: Tue, 28 Feb 2023 12:21:29 -0700 Subject: [PATCH 060/224] Add 2.8 to update_discons, regenerate DISCON Should match closely to original DISCON --- .../NREL_2p8_127/NREL-2p8-127_DISCON.IN | 107 +++++++++--------- Test_Cases/update_rosco_discons.py | 3 +- Tune_Cases/NREL2p8.yaml | 15 ++- 3 files changed, 65 insertions(+), 60 deletions(-) diff --git a/Test_Cases/NREL_2p8_127/NREL-2p8-127_DISCON.IN b/Test_Cases/NREL_2p8_127/NREL-2p8-127_DISCON.IN index 6617034e..1f67dac7 100644 --- a/Test_Cases/NREL_2p8_127/NREL-2p8-127_DISCON.IN +++ b/Test_Cases/NREL_2p8_127/NREL-2p8-127_DISCON.IN @@ -1,14 +1,14 @@ -! Controller parameter input file for the WISDEM tuning wind turbine -! - File written using ROSCO version 2.3.0 controller tuning logic on 07/01/21 +! Controller parameter input file for the NREL-2p8-127 wind turbine +! - File written using ROSCO version 2.7.0 controller tuning logic on 02/28/23 !------- DEBUG ------------------------------------------------------------ -2 ! LoggingLevel - {0: write no debug files, 1: write standard output .dbg-file, 2: write standard output .dbg-file and complete avrSWAP-array .dbg2-file} +1 ! LoggingLevel - {0: write no debug files, 1: write standard output .dbg-file, 2: LoggingLevel 1 + ROSCO LocalVars (.dbg2) 3: LoggingLevel 2 + complete avrSWAP-array (.dbg3)} !------- 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 and/or tower fore-aft motion (for floating) {0: disable, 1: generator speed, 2: tower-top fore-aft motion, 3: generator speed and tower-top fore-aft motion} 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} +2 ! VS_ControlMode - Generator torque control mode in above rated conditions {0: constant torque, 1: constant power, 2: TSR tracking PI control with constant torque, 3: TSR tracking PI control with constant power} 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} @@ -21,40 +21,41 @@ 0 ! OL_Mode - Open loop control mode {0: no open loop control, 1: open loop control vs. time} 0 ! PA_Mode - Pitch actuator mode {0 - not used, 1 - first order filter, 2 - second order filter} 0 ! PF_Mode - Pitch fault mode {0 - not used, 1 - constant offset on one or more blades} -1 ! AWC_Mode - Active wake control {0 - not used, 1 - SNL method} +0 ! AWC_Mode - Active wake control {0 - not used, 1 - SNL method} 0 ! Ext_Mode - External control mode {0 - not used, 1 - call external dynamic library} 0 ! ZMQ_Mode - Fuse ZeroMQ interface {0: unused, 1: Yaw Control} !------- FILTERS ---------------------------------------------------------- -2.09625 ! F_LPFCornerFreq - Corner frequency (-3dB point) in the low-pass filters, [rad/s] +2.07080 ! F_LPFCornerFreq - Corner frequency (-3dB point) in the low-pass filters, [rad/s] 0.00000 ! F_LPFDamping - Damping coefficient {used only when F_FilterType = 2} [-] -100.00000 ! F_NotchCornerFreq - Natural frequency of the notch filter, [rad/s] -0.00000 0.25000 ! F_NotchBetaNumDen - Two notch damping values (numerator and denominator, resp) - determines the width and depth of the notch, [-] -0.628320000000 ! F_SSCornerFreq - Corner frequency (-3dB point) in the first order low pass filter for the setpoint smoother, [rad/s]. +0.00000 ! F_NotchCornerFreq - Natural frequency of the notch filter, [rad/s] +0.000000 0.250000 ! F_NotchBetaNumDen - Two notch damping values (numerator and denominator, resp) - determines the width and depth of the notch, [-] +0.62830 ! F_SSCornerFreq - Corner frequency (-3dB point) in the first order low pass filter for the setpoint smoother, [rad/s]. 0.20944 ! F_WECornerFreq - Corner frequency (-3dB point) in the first order low pass filter for the wind speed estimate [rad/s]. 0.17952 ! F_YawErr - Low pass filter corner frequency for yaw controller [rad/s]. -0.20000 1.00000 ! F_FlCornerFreq - Natural frequency and damping in the second order low pass filter of the tower-top fore-aft motion for floating feedback control [rad/s, -]. +0.000000 1.000000 ! F_FlCornerFreq - Natural frequency and damping in the second order low pass filter of the tower-top fore-aft motion for floating feedback control [rad/s, -]. 0.01042 ! F_FlHighPassFreq - Natural frequency of first-order high-pass filter for nacelle fore-aft motion [rad/s]. -1.74957 1.00000 ! F_FlpCornerFreq - Corner frequency and damping in the second order low pass filter of the blade root bending moment for flap control [rad/s, -]. +0.000000 1.000000 ! F_FlpCornerFreq - Corner frequency and damping in the second order low pass filter of the blade root bending moment for flap control [rad/s, -]. !------- BLADE PITCH CONTROL ---------------------------------------------- -29 ! PC_GS_n - Amount of gain-scheduling table entries -0.086568 0.116114 0.139911 0.160483 0.179061 0.196300 0.212523 0.227992 0.242512 0.256650 0.270553 0.283361 0.296184 0.308667 0.320716 0.332616 0.343903 0.355566 0.366454 0.377409 0.387896 0.398463 0.408845 0.419345 0.429098 0.438839 0.448558 0.458211 0.467708 ! PC_GS_angles - Gain-schedule table: pitch angles [rad]. --0.013659 -0.011910 -0.010483 -0.009298 -0.008298 -0.007442 -0.006701 -0.006054 -0.005484 -0.004977 -0.004525 -0.004118 -0.003750 -0.003416 -0.003111 -0.002832 -0.002575 -0.002338 -0.002119 -0.001915 -0.001726 -0.001549 -0.001384 -0.001229 -0.001083 -0.000947 -0.000818 -0.000696 -0.000581 ! PC_GS_KP - Gain-schedule table: pitch controller kp gains [s]. --0.001637 -0.001470 -0.001335 -0.001222 -0.001127 -0.001045 -0.000975 -0.000913 -0.000859 -0.000811 -0.000768 -0.000729 -0.000694 -0.000662 -0.000633 -0.000607 -0.000582 -0.000560 -0.000539 -0.000520 -0.000502 -0.000485 -0.000469 -0.000454 -0.000440 -0.000427 -0.000415 -0.000404 -0.000393 ! 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 ! 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 ! PC_GS_TF - Gain-schedule table: pitch controller tf gains (derivative filter) +30 ! PC_GS_n - Amount of gain-scheduling table entries +0.075990 0.104503 0.127446 0.147544 0.164940 0.181678 0.197073 0.211624 0.225753 0.238993 0.252021 0.264458 0.276515 0.288229 0.299596 0.310932 0.321646 0.332112 0.342584 0.353105 0.363012 0.373072 0.382733 0.392195 0.401619 0.411107 0.420504 0.429096 0.437752 0.446357 ! PC_GS_angles - Gain-schedule table: pitch angles [rad]. +-0.035909 -0.032382 -0.029436 -0.026938 -0.024792 -0.022930 -0.021299 -0.019858 -0.018575 -0.017426 -0.016392 -0.015455 -0.014603 -0.013824 -0.013110 -0.012453 -0.011846 -0.011283 -0.010761 -0.010274 -0.009820 -0.009395 -0.008996 -0.008621 -0.008269 -0.007936 -0.007622 -0.007325 -0.007043 -0.006775 ! PC_GS_KP - Gain-schedule table: pitch controller kp gains [s]. +-0.015528 -0.014136 -0.012973 -0.011987 -0.011140 -0.010405 -0.009760 -0.009191 -0.008685 -0.008232 -0.007823 -0.007453 -0.007117 -0.006810 -0.006528 -0.006268 -0.006028 -0.005806 -0.005600 -0.005408 -0.005229 -0.005061 -0.004904 -0.004756 -0.004616 -0.004485 -0.004361 -0.004244 -0.004132 -0.004027 ! PC_GS_KI - Gain-schedule table: pitch controller ki gains [-]. +0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 ! PC_GS_KD - Gain-schedule table: pitch controller kd gains +0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 ! PC_GS_TF - Gain-schedule table: pitch controller tf gains (derivative filter) 1.570000000000 ! PC_MaxPit - Maximum physical pitch limit, [rad]. --0.17453290000 ! PC_MinPit - Minimum physical pitch limit, [rad]. -0.122170000000 ! PC_MaxRat - Maximum pitch rate (in absolute value) in pitch controller, [rad/s]. --0.12217000000 ! PC_MinRat - Minimum pitch rate (in absolute value) in pitch controller, [rad/s]. -122.2879500000 ! PC_RefSpd - Desired (reference) HSS speed for pitch controller, [rad/s]. +-0.17453000000 ! PC_MinPit - Minimum physical pitch limit, [rad]. +0.174500000000 ! PC_MaxRat - Maximum pitch rate (in absolute value) in pitch controller, [rad/s]. +-0.17450000000 ! PC_MinRat - Minimum pitch rate (in absolute value) in pitch controller, [rad/s]. +122.9096700000 ! PC_RefSpd - Desired (reference) HSS speed for pitch controller, [rad/s]. 0.000000000000 ! PC_FinePit - Record 5: Below-rated pitch angle set-point, [rad] 0.017450000000 ! PC_Switch - Angle above lowest minimum pitch angle for switch, [rad] !------- INDIVIDUAL PITCH CONTROL ----------------------------------------- -0.0 0.0 ! IPC_Vramp - Start and end wind speeds for cut-in ramp function. First entry: IPC inactive, second entry: IPC fully active. [m/s] -0.1 ! IPC_IntSat - Integrator saturation (maximum signal amplitude contribution to pitch from IPC), [rad] +9.120000 11.400000 ! IPC_Vramp - Start and end wind speeds for cut-in ramp function. First entry: IPC inactive, second entry: IPC fully active. [m/s] +2 ! IPC_SatMode - IPC Saturation method (0 - no saturation (except by PC_MinPit), 1 - saturate by PS_BldPitchMin, 2 - saturate sotfly (full IPC cycle) by PC_MinPit, 3 - saturate softly by PS_BldPitchMin) +0.3 ! IPC_IntSat - Integrator saturation (maximum signal amplitude contribution to pitch from IPC), [rad] 0.000e+00 0.000e+00 ! IPC_KP - Proportional gain for the individual pitch controller: first parameter for 1P reductions, second for 2P reductions, [-] 0.000e+00 0.000e+00 ! IPC_KI - Integral gain for the individual pitch controller: first parameter for 1P reductions, second for 2P reductions, [-] 0.000000 0.000000 ! IPC_aziOffset - Phase offset added to the azimuth angle for the individual pitch controller, [rad]. @@ -62,19 +63,19 @@ !------- VS TORQUE CONTROL ------------------------------------------------ 93.94773000000 ! VS_GenEff - Generator efficiency mechanical power -> electrical power, [should match the efficiency defined in the generator properties!], [%] -24371.81831000 ! VS_ArSatTq - Above rated generator torque PI control saturation, [Nm] +24248.54567000 ! VS_ArSatTq - Above rated generator torque PI control saturation, [Nm] 1500000.000000 ! VS_MaxRat - Maximum torque rate (in absolute value) in torque controller, [Nm/s]. -26809.00014000 ! VS_MaxTq - Maximum generator torque in Region 3 (HSS side), [Nm]. -0.000000000000 ! VS_MinTq - Minimum generator (HSS side), [Nm]. -50.78908000000 ! VS_MinOMSpd - Optimal mode minimum speed, cut-in speed towards optimal mode gain path, [rad/s] -2.055580000000 ! VS_Rgn2K - Generator torque constant in Region 2 (HSS side), [Nm/(rad/s)^2] +26673.40024000 ! VS_MaxTq - Maximum generator torque in Region 3 (HSS side), [Nm]. +0.000000000000 ! VS_MinTq - Minimum generator torque (HSS side), [Nm]. +37.81562000000 ! VS_MinOMSpd - Minimum generator speed [rad/s] +1.931170000000 ! VS_Rgn2K - Generator torque constant in Region 2 (HSS side), [Nm/(rad/s)^2] 2800000.000000 ! VS_RtPwr - Wind turbine rated power [W] -24371.81831000 ! VS_RtTq - Rated torque, [Nm]. -122.2879500000 ! VS_RefSpd - Rated generator speed [rad/s] +24248.54567000 ! VS_RtTq - Rated torque, [Nm]. +122.9096700000 ! VS_RefSpd - Rated generator speed [rad/s] 1 ! VS_n - Number of generator PI torque controller gains --585.918650000 ! VS_KP - Proportional gain for generator PI torque controller [-]. (Only used in the transitional 2.5 region if VS_ControlMode =/ 2) --84.3526100000 ! VS_KI - Integral gain for generator PI torque controller [s]. (Only used in the transitional 2.5 region if VS_ControlMode =/ 2) -8.00 ! VS_TSRopt - Power-maximizing region 2 tip-speed-ratio [rad]. +-591.445280000 ! VS_KP - Proportional gain for generator PI torque controller [-]. (Only used in the transitional 2.5 region if VS_ControlMode =/ 2) +-85.3230300000 ! VS_KI - Integral gain for generator PI torque controller [s]. (Only used in the transitional 2.5 region if VS_ControlMode =/ 2) +8.25 ! VS_TSRopt - Power-maximizing region 2 tip-speed-ratio [rad]. !------- SETPOINT SMOOTHER --------------------------------------------- 1.00000 ! SS_VSGain - Variable speed torque controller setpoint smoother gain, [-]. @@ -83,20 +84,20 @@ !------- WIND SPEED ESTIMATOR --------------------------------------------- 63.457 ! WE_BladeRadius - Blade length (distance from hub center to blade tip), [m] 1 ! WE_CP_n - Amount of parameters in the Cp array -0.0 ! WE_CP - Parameters that define the parameterized CP(lambda) function +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], [-] -19841843.18798 ! WE_Jtot - Total drivetrain inertia, including blades, hub and casted generator inertia to LSS, [kg m^2] +66347470.49793 ! 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] -"NREL-2p8-127_Cp_Ct_Cq.txt" ! PerfFileName - File containing rotor performance tables (Cp,Ct,Cq) +"NREL-2p8-127_Cp_Ct_Cq.txt" ! PerfFileName - File containing rotor performance tables (Cp,Ct,Cq) (absolute path or relative to this file) 30 30 ! PerfTableSize - Size of rotor performance tables, first number refers to number of blade pitch angles, second number referse to number of tip-speed ratios -59 ! WE_FOPoles_N - Number of first-order system poles used in EKF -3.00 3.24 3.48 3.72 3.97 4.21 4.45 4.69 4.93 5.17 5.41 5.66 5.90 6.14 6.38 6.62 6.86 7.10 7.34 7.59 7.83 8.07 8.31 8.55 8.79 9.03 9.28 9.52 9.76 10.00 10.52 11.03 11.55 12.07 12.59 13.10 13.62 14.14 14.66 15.17 15.69 16.21 16.72 17.24 17.76 18.28 18.79 19.31 19.83 20.34 20.86 21.38 21.90 22.41 22.93 23.45 23.97 24.48 25.00 ! WE_FOPoles_v - Wind speeds corresponding to first-order system poles [m/s] --0.03755370 -0.04057526 -0.04359682 -0.04661839 -0.04963995 -0.05266151 -0.05568307 -0.05870463 -0.06172620 -0.06474776 -0.06776932 -0.07079088 -0.07381244 -0.07683401 -0.07985557 -0.08287713 -0.08589869 -0.08892026 -0.09194182 -0.09496338 -0.09798494 -0.10100650 -0.10402807 -0.10704963 -0.11007119 -0.11309275 -0.11611431 -0.11913588 -0.12215744 -0.12442309 -0.08151313 -0.09670796 -0.11491145 -0.13526498 -0.15708028 -0.18040671 -0.20314889 -0.22784461 -0.25427479 -0.28079304 -0.30962195 -0.33563012 -0.36680258 -0.39642727 -0.42479673 -0.45403549 -0.48608257 -0.52014667 -0.55456520 -0.58971549 -0.61985547 -0.65379097 -0.69212406 -0.73040974 -0.75941587 -0.79271437 -0.82808748 -0.86351689 -0.90081887 ! WE_FOPoles - First order system poles [1/s] +60 ! WE_FOPoles_N - Number of first-order system poles used in EKF +3.0000 3.2897 3.5793 3.8690 4.1586 4.4483 4.7379 5.0276 5.3172 5.6069 5.8966 6.1862 6.4759 6.7655 7.0552 7.3448 7.6345 7.9241 8.2138 8.5034 8.7931 9.0828 9.3724 9.6621 9.9517 10.2414 10.5310 10.8207 11.1103 11.4000 11.8533 12.3067 12.7600 13.2133 13.6667 14.1200 14.5733 15.0267 15.4800 15.9333 16.3867 16.8400 17.2933 17.7467 18.2000 18.6533 19.1067 19.5600 20.0133 20.4667 20.9200 21.3733 21.8267 22.2800 22.7333 23.1867 23.6400 24.0933 24.5467 25.0000 ! WE_FOPoles_v - Wind speeds corresponding to first-order system poles [m/s] +-0.00983687 -0.01078664 -0.01173641 -0.01268617 -0.01363594 -0.01458571 -0.01553547 -0.01648524 -0.01743501 -0.01838477 -0.01933454 -0.02028431 -0.02123407 -0.02218384 -0.02313361 -0.02408338 -0.02503314 -0.02598291 -0.02693268 -0.02788244 -0.02883221 -0.02978198 -0.03073174 -0.03168151 -0.03117792 -0.02980777 -0.02737033 -0.02372966 -0.01842478 -0.01325506 -0.02209033 -0.02677213 -0.03094759 -0.03700125 -0.04188805 -0.04820630 -0.05390840 -0.06043728 -0.06624359 -0.07295380 -0.07986166 -0.08646363 -0.09412176 -0.10174417 -0.10913837 -0.11728247 -0.12497467 -0.13271621 -0.14189107 -0.15083268 -0.15981675 -0.16948290 -0.17870908 -0.18789884 -0.19750668 -0.20786563 -0.21788705 -0.22660607 -0.23612135 -0.24537696 ! WE_FOPoles - First order system poles [1/s] !------- YAW CONTROL ------------------------------------------------------ -0.00000 ! Y_uSwitch - Wind speed to switch between Y_ErrThresh. If zero, only the first value of Y_ErrThresh is used [m/s] -4.000000 8.000000 ! Y_ErrThresh - Yaw error threshold/deadband. Turbine begins to yaw when it passes this. If Y_uSwitch is zero, only the first value is used. [deg]. +0.00000 ! Y_uSwitch - Wind speed to switch between Y_ErrThresh. If zero, only the second value of Y_ErrThresh is used [m/s] +4.000000 8.000000 ! Y_ErrThresh - Yaw error threshold/deadbands. Turbine begins to yaw when it passes this. If Y_uSwitch is zero, only the second value is used. [deg]. 0.00870 ! Y_Rate - Yaw rate [rad/s] 0.00000 ! Y_MErrSet - Integrator saturation (maximum signal amplitude contribution to pitch from yaw-by-IPC), [rad] 0.00000 ! Y_IPC_IntSat - Integrator saturation (maximum signal amplitude contribution to pitch from yaw-by-IPC), [rad] @@ -104,17 +105,17 @@ 0.00000 ! Y_IPC_KI - Yaw-by-IPC integral controller gain Ki !------- 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 +-1.00000 ! FA_KI - Integral gain for the fore-aft tower damper controller [rad s/m] 0.0 ! FA_HPFCornerFreq - 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] !------- MINIMUM PITCH SATURATION ------------------------------------------- -59 ! PS_BldPitchMin_N - Number of values in minimum blade pitch lookup table (should equal number of values in PS_WindSpeeds and PS_BldPitchMin) -3.0000 3.2414 3.4828 3.7241 3.9655 4.2069 4.4483 4.6897 4.9310 5.1724 5.4138 5.6552 5.8966 6.1379 6.3793 6.6207 6.8621 7.1034 7.3448 7.5862 7.8276 8.0690 8.3103 8.5517 8.7931 9.0345 9.2759 9.5172 9.7586 10.0000 10.5172 11.0345 11.5517 12.0690 12.5862 13.1034 13.6207 14.1379 14.6552 15.1724 15.6897 16.2069 16.7241 17.2414 17.7586 18.2759 18.7931 19.3103 19.8276 20.3448 20.8621 21.3793 21.8966 22.4138 22.9310 23.4483 23.9655 24.4828 25.0000 ! PS_WindSpeeds - Wind speeds corresponding to minimum blade pitch angles [m/s] -0.00000000 0.00000000 0.00000000 0.00000000 0.00000000 0.00000000 0.00000000 0.00000000 0.00000000 0.00000000 0.00000000 0.00000000 0.00000000 0.00000000 0.00000000 0.00000000 0.00000000 0.00000000 0.00000000 0.00000000 0.00000000 0.00000000 0.00763391 0.02582598 0.04121469 0.05415541 0.06572411 0.07607035 0.08541836 0.09383601 0.10711337 0.11980981 0.13230324 0.14429856 0.15620583 0.16769078 0.17903230 0.19036255 0.20094970 0.21164306 0.22225798 0.23236325 0.24250097 0.25268462 0.26261996 0.27261663 0.28234372 0.29204627 0.30171741 0.31126513 0.32058559 0.33032494 0.33977293 0.34883344 0.35807953 0.36776628 0.37731052 0.38609588 0.39489943 ! PS_BldPitchMin - Minimum blade pitch angles [rad] +60 ! PS_BldPitchMin_N - Number of values in minimum blade pitch lookup table (should equal number of values in PS_WindSpeeds and PS_BldPitchMin) +3.0000 3.2897 3.5793 3.8690 4.1586 4.4483 4.7379 5.0276 5.3172 5.6069 5.8966 6.1862 6.4759 6.7655 7.0552 7.3448 7.6345 7.9241 8.2138 8.5034 8.7931 9.0828 9.3724 9.6621 9.9517 10.2414 10.5310 10.8207 11.1103 11.4000 11.8533 12.3067 12.7600 13.2133 13.6667 14.1200 14.5733 15.0267 15.4800 15.9333 16.3867 16.8400 17.2933 17.7467 18.2000 18.6533 19.1067 19.5600 20.0133 20.4667 20.9200 21.3733 21.8267 22.2800 22.7333 23.1867 23.6400 24.0933 24.5467 25.0000 ! PS_WindSpeeds - Wind speeds corresponding to minimum blade pitch angles [m/s] +0.01815283 0.01815283 0.01815283 0.01815283 0.01815283 0.01815283 0.01815283 0.01815283 0.01815283 0.01815283 0.01815283 0.01815283 0.01815283 0.01815283 0.01815283 0.01815283 0.01815283 0.01815283 0.01815283 0.01815283 0.01815283 0.01815283 0.01815283 0.03053884 0.04218924 0.05108100 0.05966213 0.06767357 0.07535561 0.08307338 0.09451116 0.10543602 0.11614542 0.12637321 0.13629489 0.14608659 0.15527593 0.16453742 0.17355159 0.18260256 0.19157236 0.20062149 0.20959308 0.21828530 0.22728389 0.23591357 0.24440042 0.25300395 0.26169197 0.27041514 0.27864678 0.28689031 0.29519526 0.30342802 0.31179547 0.32018758 0.32842343 0.33656456 0.34455345 0.35267496 ! PS_BldPitchMin - Minimum blade pitch angles [rad] !------- SHUTDOWN ----------------------------------------------------------- -0.567710000000 ! SD_MaxPit - Maximum blade pitch angle to initiate shutdown, [rad] +0.436300000000 ! SD_MaxPit - Maximum blade pitch angle to initiate shutdown, [rad] 0.418880000000 ! SD_CornerFreq - Cutoff Frequency for first order low-pass filter for blade pitch angle, [rad/s] !------- Floating ----------------------------------------------------------- @@ -124,7 +125,7 @@ 0.000000000000 ! Flp_Angle - Initial or steady state flap angle [rad] 0.00000000e+00 ! Flp_Kp - Blade root bending moment proportional gain for flap control [s] 0.00000000e+00 ! Flp_Ki - Flap displacement integral gain for flap control [-] -0.000000000000 ! Flp_MaxPit - Maximum (and minimum) flap pitch angle [rad] +0.174500000000 ! Flp_MaxPit - Maximum (and minimum) flap pitch angle [rad] !------- Open Loop Control ----------------------------------------------------- "unused" ! OL_Filename - Input file with open loop timeseries (absolute path or relative to this file) @@ -140,12 +141,12 @@ !------- Pitch Actuator Faults ----------------------------------------------------- 0.00000000 0.00000000 0.00000000 ! PF_Offsets - Constant blade pitch offsets for blades 1-3 [rad] -!------- AWC Modifications ----------------------------------------------------- -1 ! AWC_NumModes - Number of modes -1 ! AWC_n - azimuthal mode number -0.05 ! AWC_freq - frequency [Hz] -1.0 ! AWC_amp - amplitude [deg] -0.0 ! AWC_clockangle - clock angle [deg] +!------- Active Wake Control ----------------------------------------------------- +1 ! AWC_NumModes - number of forcing modes +1 ! AWC_n - azimuthal mode number(s) (i.e., the number and direction of the lobes of the wake structure) +0.0500 ! AWC_freq - frequency(s) of forcing mode(s) [Hz] +1.0000 ! AWC_amp - pitch amplitude(s) of forcing mode(s) (note that AWC_amp specifies the amplitude of each individual mode so that the total amplitude of pitching will be the sum of AWC_amp) [deg] +0.0000 ! AWC_clockangle - clocking angle(s) of forcing mode(s) [deg] !------- External Controller Interface ----------------------------------------------------- "unused" ! DLL_FileName - Name/location of the dynamic library in the Bladed-DLL format diff --git a/Test_Cases/update_rosco_discons.py b/Test_Cases/update_rosco_discons.py index ca08ea31..9a299991 100644 --- a/Test_Cases/update_rosco_discons.py +++ b/Test_Cases/update_rosco_discons.py @@ -12,7 +12,8 @@ map_rel = { 'NREL5MW.yaml': 'NREL-5MW/DISCON.IN', 'IEA15MW.yaml': 'IEA-15-240-RWT-UMaineSemi/DISCON-UMaineSemi.IN', - 'BAR.yaml': 'BAR_10/BAR_10_DISCON.IN' + 'BAR.yaml': 'BAR_10/BAR_10_DISCON.IN', + 'NREL2p8.yaml': 'NREL_2p8_127/NREL-2p8-127_DISCON.IN', } # Directories diff --git a/Tune_Cases/NREL2p8.yaml b/Tune_Cases/NREL2p8.yaml index 2b39b420..0c3bcd04 100644 --- a/Tune_Cases/NREL2p8.yaml +++ b/Tune_Cases/NREL2p8.yaml @@ -10,15 +10,15 @@ path_params: # -------------------------------- TURBINE PARAMETERS ----------------------------------- turbine_params: - rotor_inertia: 38677040.613 # Rotor inertia [kg m^2], {Available in Elastodyn .sum file} + rotor_inertia: 19858184.000 # Rotor inertia [kg m^2], {Available in Elastodyn .sum file} rated_rotor_speed: 1.26711 # Rated rotor speed [rad/s] v_min: 3.0 # Cut-in wind speed [m/s] v_rated: 11.4 # Rated wind speed [m/s] v_max: 25.0 # Cut-out wind speed [m/s], -- Does not need to be exact (JUST ASSUME FOR NOW) max_pitch_rate: 0.1745 # Maximum blade pitch rate [rad/s] max_torque_rate: 1500000. # Maximum torque rate [Nm/s], {~1/4 VS_RtTq/s} - rated_power: 5000000. # Rated Power [W] - bld_edgewise_freq: 6.2831853 # Blade edgewise first natural frequency [rad/s] + rated_power: 2800000. # Rated Power [W] + bld_edgewise_freq: 8.2831853 # Blade edgewise first natural frequency [rad/s] bld_flapwise_freq: 0.0 # Blade flapwise first natural frequency [rad/s] # Optional # TSR_operational: # None # Desired below-rated operational tip speed ratio (Cp-maximizing TSR is used if not defined) @@ -29,7 +29,7 @@ controller_params: F_LPFType: 1 # {1: first-order low-pass filter, 2: second-order low-pass filter}, [rad/s] (currently filters generator speed and pitch control signals) F_NotchType: 0 # Notch filter on generator speed and/or tower fore-aft motion (for floating) {0: disable, 1: generator speed, 2: tower-top fore-aft motion, 3: generator speed and tower-top fore-aft motion} IPC_ControlMode: 0 # Turn Individual Pitch Control (IPC) for fatigue load reductions (pitch contribution) {0: off, 1: 1P reductions, 2: 1P+2P reductions} - VS_ControlMode: 3 # Generator torque control mode in above rated conditions {0: constant torque, 1: constant power, 2: TSR tracking PI control} + VS_ControlMode: 2 # Generator torque control mode in above rated conditions {0: constant torque, 1: constant power, 2: TSR tracking PI control} PC_ControlMode: 1 # Blade pitch control mode {0: No pitch, fix to fine pitch, 1: active PI blade pitch control} Y_ControlMode: 0 # Yaw control mode {0: no yaw control, 1: yaw rate control, 2: yaw-by-IPC} SS_Mode: 1 # Setpoint Smoother mode {0: no setpoint smoothing, 1: introduce setpoint smoothing} @@ -41,10 +41,13 @@ controller_params: # Controller parameters zeta_pc: 0.7 # Pitch controller desired damping ratio [-] omega_pc: 0.6 # Pitch controller desired natural frequency [rad/s] - zeta_vs: 0.7 # Torque controller desired damping ratio [-] - omega_vs: 0.15 # Torque controller desired natural frequency [rad/s] + zeta_vs: 0.465 # Torque controller desired damping ratio [-] + omega_vs: 0.11 # Torque controller desired natural frequency [rad/s] twr_freq: 0.4499 # Tower natural frequency [rad/s] ptfm_freq: 0.2325 # Platform natural frequency [rad/s] (OC4Hywind Parameters, here) # Optional ps_percent: 0.80 # Percent peak shaving [%, <= 1 ], {default = 80%} sd_maxpit: 0.4363 # Maximum blade pitch angle to initiate shutdown [rad], {default = bld pitch at v_max} + DISCON: + PC_MinPit: -0.17453290000 + PC_FinePit: 0.0 From b2fdfbcf93e1cf7d529d4168f9de5e1099e07edb Mon Sep 17 00:00:00 2001 From: dzalkind Date: Tue, 28 Feb 2023 12:33:12 -0700 Subject: [PATCH 061/224] Update AWC_Mode descriptions --- ROSCO_toolbox/utilities.py | 2 +- Test_Cases/BAR_10/BAR_10_DISCON.IN | 2 +- Test_Cases/IEA-15-240-RWT-UMaineSemi/DISCON-UMaineSemi.IN | 2 +- Test_Cases/NREL-5MW/DISCON.IN | 2 +- Test_Cases/NREL_2p8_127/NREL-2p8-127_DISCON.IN | 2 +- 5 files changed, 5 insertions(+), 5 deletions(-) diff --git a/ROSCO_toolbox/utilities.py b/ROSCO_toolbox/utilities.py index 28306c20..e5c62ae7 100644 --- a/ROSCO_toolbox/utilities.py +++ b/ROSCO_toolbox/utilities.py @@ -84,7 +84,7 @@ def write_DISCON(turbine, controller, param_file='DISCON.IN', txt_filename='Cp_C file.write('{0:<12d} ! OL_Mode - Open loop control mode {{0: no open loop control, 1: open loop control vs. time}}\n'.format(int(rosco_vt['OL_Mode']))) file.write('{0:<12d} ! PA_Mode - Pitch actuator mode {{0 - not used, 1 - first order filter, 2 - second order filter}}\n'.format(int(rosco_vt['PA_Mode']))) file.write('{0:<12d} ! PF_Mode - Pitch fault mode {{0 - not used, 1 - constant offset on one or more blades}}\n'.format(int(rosco_vt['PF_Mode']))) - file.write('{0:<12d} ! AWC_Mode - Active wake control {{0 - not used, 1 - SNL method}}\n'.format(int(rosco_vt['AWC_Mode']))) + file.write('{0:<12d} ! AWC_Mode - Active wake control {{0 - not used, 1 - complex number method, 2 - coleman transform method}}\n'.format(int(rosco_vt['AWC_Mode']))) file.write('{0:<12d} ! Ext_Mode - External control mode {{0 - not used, 1 - call external dynamic library}}\n'.format(int(rosco_vt['Ext_Mode']))) file.write('{0:<12d} ! ZMQ_Mode - Fuse ZeroMQ interface {{0: unused, 1: Yaw Control}}\n'.format(int(rosco_vt['ZMQ_Mode']))) diff --git a/Test_Cases/BAR_10/BAR_10_DISCON.IN b/Test_Cases/BAR_10/BAR_10_DISCON.IN index e7aa6f37..50eb68db 100644 --- a/Test_Cases/BAR_10/BAR_10_DISCON.IN +++ b/Test_Cases/BAR_10/BAR_10_DISCON.IN @@ -21,7 +21,7 @@ 0 ! OL_Mode - Open loop control mode {0: no open loop control, 1: open loop control vs. time} 0 ! PA_Mode - Pitch actuator mode {0 - not used, 1 - first order filter, 2 - second order filter} 0 ! PF_Mode - Pitch fault mode {0 - not used, 1 - constant offset on one or more blades} -0 ! AWC_Mode - Active wake control {0 - not used, 1 - SNL method} +0 ! AWC_Mode - Active wake control {0 - not used, 1 - complex number method, 2 - coleman transform method} 0 ! Ext_Mode - External control mode {0 - not used, 1 - call external dynamic library} 0 ! ZMQ_Mode - Fuse ZeroMQ interface {0: unused, 1: Yaw Control} diff --git a/Test_Cases/IEA-15-240-RWT-UMaineSemi/DISCON-UMaineSemi.IN b/Test_Cases/IEA-15-240-RWT-UMaineSemi/DISCON-UMaineSemi.IN index 159dfb91..6ada1874 100644 --- a/Test_Cases/IEA-15-240-RWT-UMaineSemi/DISCON-UMaineSemi.IN +++ b/Test_Cases/IEA-15-240-RWT-UMaineSemi/DISCON-UMaineSemi.IN @@ -21,7 +21,7 @@ 0 ! OL_Mode - Open loop control mode {0: no open loop control, 1: open loop control vs. time} 2 ! PA_Mode - Pitch actuator mode {0 - not used, 1 - first order filter, 2 - second order filter} 0 ! PF_Mode - Pitch fault mode {0 - not used, 1 - constant offset on one or more blades} -0 ! AWC_Mode - Active wake control {0 - not used, 1 - SNL method} +0 ! AWC_Mode - Active wake control {0 - not used, 1 - complex number method, 2 - coleman transform method} 0 ! Ext_Mode - External control mode {0 - not used, 1 - call external dynamic library} 0 ! ZMQ_Mode - Fuse ZeroMQ interface {0: unused, 1: Yaw Control} diff --git a/Test_Cases/NREL-5MW/DISCON.IN b/Test_Cases/NREL-5MW/DISCON.IN index d24c9897..32b1a8fc 100644 --- a/Test_Cases/NREL-5MW/DISCON.IN +++ b/Test_Cases/NREL-5MW/DISCON.IN @@ -21,7 +21,7 @@ 0 ! OL_Mode - Open loop control mode {0: no open loop control, 1: open loop control vs. time} 0 ! PA_Mode - Pitch actuator mode {0 - not used, 1 - first order filter, 2 - second order filter} 0 ! PF_Mode - Pitch fault mode {0 - not used, 1 - constant offset on one or more blades} -0 ! AWC_Mode - Active wake control {0 - not used, 1 - SNL method} +0 ! AWC_Mode - Active wake control {0 - not used, 1 - complex number method, 2 - coleman transform method} 0 ! Ext_Mode - External control mode {0 - not used, 1 - call external dynamic library} 0 ! ZMQ_Mode - Fuse ZeroMQ interface {0: unused, 1: Yaw Control} diff --git a/Test_Cases/NREL_2p8_127/NREL-2p8-127_DISCON.IN b/Test_Cases/NREL_2p8_127/NREL-2p8-127_DISCON.IN index 1f67dac7..3982e80f 100644 --- a/Test_Cases/NREL_2p8_127/NREL-2p8-127_DISCON.IN +++ b/Test_Cases/NREL_2p8_127/NREL-2p8-127_DISCON.IN @@ -21,7 +21,7 @@ 0 ! OL_Mode - Open loop control mode {0: no open loop control, 1: open loop control vs. time} 0 ! PA_Mode - Pitch actuator mode {0 - not used, 1 - first order filter, 2 - second order filter} 0 ! PF_Mode - Pitch fault mode {0 - not used, 1 - constant offset on one or more blades} -0 ! AWC_Mode - Active wake control {0 - not used, 1 - SNL method} +0 ! AWC_Mode - Active wake control {0 - not used, 1 - complex number method, 2 - coleman transform method} 0 ! Ext_Mode - External control mode {0 - not used, 1 - call external dynamic library} 0 ! ZMQ_Mode - Fuse ZeroMQ interface {0: unused, 1: Yaw Control} From e8996003c4615813a2b9b62025d4e082ccabfbae Mon Sep 17 00:00:00 2001 From: jfrederik-nrel Date: Mon, 6 Mar 2023 17:52:49 -0700 Subject: [PATCH 062/224] Updated Coleman Transformation based AWC --- Examples/20_active_wake_control.py | 24 +- ROSCO/src/Controllers.f90 | 76 +++--- Test_Cases/BAR_10/BAR_10_DISCON.IN | 10 +- .../DISCON-UMaineSemi.IN | 10 +- Test_Cases/NREL-5MW/DISCON.IN | 13 +- .../Airfoils/NREL-2p8-127_AF00_Coords.txt | 208 ++++++++++++++ .../Airfoils/NREL-2p8-127_AF01_Coords.txt | 208 ++++++++++++++ .../Airfoils/NREL-2p8-127_AF02_Coords.txt | 208 ++++++++++++++ .../Airfoils/NREL-2p8-127_AF03_Coords.txt | 208 ++++++++++++++ .../Airfoils/NREL-2p8-127_AF04_Coords.txt | 208 ++++++++++++++ .../Airfoils/NREL-2p8-127_AF05_Coords.txt | 208 ++++++++++++++ .../Airfoils/NREL-2p8-127_AF06_Coords.txt | 208 ++++++++++++++ .../Airfoils/NREL-2p8-127_AF07_Coords.txt | 208 ++++++++++++++ .../Airfoils/NREL-2p8-127_AF08_Coords.txt | 208 ++++++++++++++ .../Airfoils/NREL-2p8-127_AF09_Coords.txt | 208 ++++++++++++++ .../Airfoils/NREL-2p8-127_AF10_Coords.txt | 208 ++++++++++++++ .../Airfoils/NREL-2p8-127_AF11_Coords.txt | 208 ++++++++++++++ .../Airfoils/NREL-2p8-127_AF12_Coords.txt | 208 ++++++++++++++ .../Airfoils/NREL-2p8-127_AF13_Coords.txt | 208 ++++++++++++++ .../Airfoils/NREL-2p8-127_AF14_Coords.txt | 208 ++++++++++++++ .../Airfoils/NREL-2p8-127_AF15_Coords.txt | 208 ++++++++++++++ .../Airfoils/NREL-2p8-127_AF16_Coords.txt | 208 ++++++++++++++ .../Airfoils/NREL-2p8-127_AF17_Coords.txt | 208 ++++++++++++++ .../Airfoils/NREL-2p8-127_AF18_Coords.txt | 208 ++++++++++++++ .../Airfoils/NREL-2p8-127_AF19_Coords.txt | 208 ++++++++++++++ .../Airfoils/NREL-2p8-127_AF20_Coords.txt | 208 ++++++++++++++ .../Airfoils/NREL-2p8-127_AF21_Coords.txt | 208 ++++++++++++++ .../Airfoils/NREL-2p8-127_AF22_Coords.txt | 208 ++++++++++++++ .../Airfoils/NREL-2p8-127_AF23_Coords.txt | 208 ++++++++++++++ .../Airfoils/NREL-2p8-127_AF24_Coords.txt | 208 ++++++++++++++ .../Airfoils/NREL-2p8-127_AF25_Coords.txt | 208 ++++++++++++++ .../Airfoils/NREL-2p8-127_AF26_Coords.txt | 208 ++++++++++++++ .../Airfoils/NREL-2p8-127_AF27_Coords.txt | 208 ++++++++++++++ .../Airfoils/NREL-2p8-127_AF28_Coords.txt | 208 ++++++++++++++ .../Airfoils/NREL-2p8-127_AF29_Coords.txt | 208 ++++++++++++++ .../NREL-2p8-127_AeroDyn15_Polar_00.dat | 254 ++++++++++++++++++ .../NREL-2p8-127_AeroDyn15_Polar_01.dat | 254 ++++++++++++++++++ .../NREL-2p8-127_AeroDyn15_Polar_02.dat | 254 ++++++++++++++++++ .../NREL-2p8-127_AeroDyn15_Polar_03.dat | 254 ++++++++++++++++++ .../NREL-2p8-127_AeroDyn15_Polar_04.dat | 254 ++++++++++++++++++ .../NREL-2p8-127_AeroDyn15_Polar_05.dat | 254 ++++++++++++++++++ .../NREL-2p8-127_AeroDyn15_Polar_06.dat | 254 ++++++++++++++++++ .../NREL-2p8-127_AeroDyn15_Polar_07.dat | 254 ++++++++++++++++++ .../NREL-2p8-127_AeroDyn15_Polar_08.dat | 254 ++++++++++++++++++ .../NREL-2p8-127_AeroDyn15_Polar_09.dat | 254 ++++++++++++++++++ .../NREL-2p8-127_AeroDyn15_Polar_10.dat | 254 ++++++++++++++++++ .../NREL-2p8-127_AeroDyn15_Polar_11.dat | 254 ++++++++++++++++++ .../NREL-2p8-127_AeroDyn15_Polar_12.dat | 254 ++++++++++++++++++ .../NREL-2p8-127_AeroDyn15_Polar_13.dat | 254 ++++++++++++++++++ .../NREL-2p8-127_AeroDyn15_Polar_14.dat | 254 ++++++++++++++++++ .../NREL-2p8-127_AeroDyn15_Polar_15.dat | 254 ++++++++++++++++++ .../NREL-2p8-127_AeroDyn15_Polar_16.dat | 254 ++++++++++++++++++ .../NREL-2p8-127_AeroDyn15_Polar_17.dat | 254 ++++++++++++++++++ .../NREL-2p8-127_AeroDyn15_Polar_18.dat | 254 ++++++++++++++++++ .../NREL-2p8-127_AeroDyn15_Polar_19.dat | 254 ++++++++++++++++++ .../NREL-2p8-127_AeroDyn15_Polar_20.dat | 254 ++++++++++++++++++ .../NREL-2p8-127_AeroDyn15_Polar_21.dat | 254 ++++++++++++++++++ .../NREL-2p8-127_AeroDyn15_Polar_22.dat | 254 ++++++++++++++++++ .../NREL-2p8-127_AeroDyn15_Polar_23.dat | 254 ++++++++++++++++++ .../NREL-2p8-127_AeroDyn15_Polar_24.dat | 254 ++++++++++++++++++ .../NREL-2p8-127_AeroDyn15_Polar_25.dat | 254 ++++++++++++++++++ .../NREL-2p8-127_AeroDyn15_Polar_26.dat | 254 ++++++++++++++++++ .../NREL-2p8-127_AeroDyn15_Polar_27.dat | 254 ++++++++++++++++++ .../NREL-2p8-127_AeroDyn15_Polar_28.dat | 254 ++++++++++++++++++ .../NREL-2p8-127_AeroDyn15_Polar_29.dat | 254 ++++++++++++++++++ Test_Cases/NREL_2p8_127/NREL-2.8-127.xlsx | Bin 0 -> 14107 bytes .../NREL_2p8_127/NREL-2.8-127_pitch-speed.csv | 31 +++ Test_Cases/NREL_2p8_127/NREL-2p8-127.fst | 71 +++++ .../NREL_2p8_127/NREL-2p8-127_AeroDyn15.dat | 134 +++++++++ .../NREL-2p8-127_AeroDyn15_blade.dat | 36 +++ .../NREL_2p8_127/NREL-2p8-127_Cp_Ct_Cq.txt | 111 ++++++++ .../NREL_2p8_127/NREL-2p8-127_DISCON.IN | 158 +++++++++++ .../NREL_2p8_127/NREL-2p8-127_ElastoDyn.dat | 210 +++++++++++++++ .../NREL-2p8-127_ElastoDyn_blade.dat | 62 +++++ .../NREL-2p8-127_ElastoDyn_tower.dat | 50 ++++ .../NREL_2p8_127/NREL-2p8-127_InflowFile.dat | 57 ++++ .../NREL_2p8_127/NREL-2p8-127_ServoDyn.dat | 110 ++++++++ Tune_Cases/NREL2p8.yaml | 50 ++++ 78 files changed, 15011 insertions(+), 62 deletions(-) create mode 100644 Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF00_Coords.txt create mode 100644 Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF01_Coords.txt create mode 100644 Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF02_Coords.txt create mode 100644 Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF03_Coords.txt create mode 100644 Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF04_Coords.txt create mode 100644 Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF05_Coords.txt create mode 100644 Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF06_Coords.txt create mode 100644 Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF07_Coords.txt create mode 100644 Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF08_Coords.txt create mode 100644 Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF09_Coords.txt create mode 100644 Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF10_Coords.txt create mode 100644 Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF11_Coords.txt create mode 100644 Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF12_Coords.txt create mode 100644 Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF13_Coords.txt create mode 100644 Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF14_Coords.txt create mode 100644 Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF15_Coords.txt create mode 100644 Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF16_Coords.txt create mode 100644 Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF17_Coords.txt create mode 100644 Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF18_Coords.txt create mode 100644 Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF19_Coords.txt create mode 100644 Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF20_Coords.txt create mode 100644 Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF21_Coords.txt create mode 100644 Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF22_Coords.txt create mode 100644 Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF23_Coords.txt create mode 100644 Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF24_Coords.txt create mode 100644 Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF25_Coords.txt create mode 100644 Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF26_Coords.txt create mode 100644 Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF27_Coords.txt create mode 100644 Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF28_Coords.txt create mode 100644 Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF29_Coords.txt create mode 100644 Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_00.dat create mode 100644 Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_01.dat create mode 100644 Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_02.dat create mode 100644 Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_03.dat create mode 100644 Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_04.dat create mode 100644 Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_05.dat create mode 100644 Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_06.dat create mode 100644 Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_07.dat create mode 100644 Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_08.dat create mode 100644 Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_09.dat create mode 100644 Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_10.dat create mode 100644 Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_11.dat create mode 100644 Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_12.dat create mode 100644 Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_13.dat create mode 100644 Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_14.dat create mode 100644 Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_15.dat create mode 100644 Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_16.dat create mode 100644 Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_17.dat create mode 100644 Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_18.dat create mode 100644 Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_19.dat create mode 100644 Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_20.dat create mode 100644 Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_21.dat create mode 100644 Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_22.dat create mode 100644 Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_23.dat create mode 100644 Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_24.dat create mode 100644 Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_25.dat create mode 100644 Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_26.dat create mode 100644 Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_27.dat create mode 100644 Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_28.dat create mode 100644 Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_29.dat create mode 100644 Test_Cases/NREL_2p8_127/NREL-2.8-127.xlsx create mode 100644 Test_Cases/NREL_2p8_127/NREL-2.8-127_pitch-speed.csv create mode 100644 Test_Cases/NREL_2p8_127/NREL-2p8-127.fst create mode 100644 Test_Cases/NREL_2p8_127/NREL-2p8-127_AeroDyn15.dat create mode 100644 Test_Cases/NREL_2p8_127/NREL-2p8-127_AeroDyn15_blade.dat create mode 100644 Test_Cases/NREL_2p8_127/NREL-2p8-127_Cp_Ct_Cq.txt create mode 100644 Test_Cases/NREL_2p8_127/NREL-2p8-127_DISCON.IN create mode 100644 Test_Cases/NREL_2p8_127/NREL-2p8-127_ElastoDyn.dat create mode 100644 Test_Cases/NREL_2p8_127/NREL-2p8-127_ElastoDyn_blade.dat create mode 100644 Test_Cases/NREL_2p8_127/NREL-2p8-127_ElastoDyn_tower.dat create mode 100644 Test_Cases/NREL_2p8_127/NREL-2p8-127_InflowFile.dat create mode 100644 Test_Cases/NREL_2p8_127/NREL-2p8-127_ServoDyn.dat create mode 100644 Tune_Cases/NREL2p8.yaml diff --git a/Examples/20_active_wake_control.py b/Examples/20_active_wake_control.py index 7011b631..268fe437 100644 --- a/Examples/20_active_wake_control.py +++ b/Examples/20_active_wake_control.py @@ -138,7 +138,7 @@ import numpy as np # Choose your implementation method -AWC_Mode = 2 # 1 for SNL implementation, 2 for NREL implementation +AWC_Mode = 2 # 1 for SNL implementation, 2 for Coleman Transformation implementation #directories this_dir = os.path.dirname(os.path.abspath(__file__)) @@ -171,25 +171,25 @@ def main(): # Set up AWC cases defined above if AWC_Mode == 1: - control_base_case[('DISCON_in','AWC_NumModes')] = {'vals': [1,1,1,2,2], 'group': 2} - control_base_case[('DISCON_in','AWC_n')] = {'vals': [[0],[1],[-1],[-1,1], [-1,1]], 'group': 2} - control_base_case[('DISCON_in','AWC_freq')] = {'vals': [[0.05],[0.05],[0.05],[0.05,0.05], [0.05,0.05]], 'group': 2} - control_base_case[('DISCON_in','AWC_amp')] = {'vals': [[1.0],[1.0],[1.0],[1.0,1.0], [1.0,1.0]], 'group': 2} - control_base_case[('DISCON_in','AWC_clockangle')] = {'vals': [[0],[0],[0],[0,0], [90,90]], 'group': 2} - elif AWC_Mode == 2: - control_base_case[('DISCON_in','AWC_Mode')] = {'vals': [0,2,2,2,2,2], 'group': 2} control_base_case[('DISCON_in','AWC_NumModes')] = {'vals': [1,1,1,1,2,2], 'group': 2} - control_base_case[('DISCON_in','AWC_n')] = {'vals': [[0],[0],[1],[1],[1,1], [1,1]], 'group': 2} + control_base_case[('DISCON_in','AWC_n')] = {'vals': [[0],[0],[1],[-1],[-1,1], [-1,1]], 'group': 2} control_base_case[('DISCON_in','AWC_freq')] = {'vals': [[0],[0.05],[0.05],[0.05],[0.05,0.05], [0.05,0.05]], 'group': 2} - control_base_case[('DISCON_in','AWC_amp')] = {'vals': [[0],[1.0],[1.0],[1.0],[1.0,0.0], [0.0,1.0]], 'group': 2} - control_base_case[('DISCON_in','AWC_clockangle')] = {'vals': [[0],[0],[-90],[90],[0,0], [0,0]], 'group': 2} + control_base_case[('DISCON_in','AWC_amp')] = {'vals': [[0],[1.0],[1.0],[1.0],[0.5,0.5], [0.5,0.5]], 'group': 2} + control_base_case[('DISCON_in','AWC_clockangle')] = {'vals': [[0],[0],[0],[0],[0,0], [90,90]], 'group': 2} + elif AWC_Mode == 2: + control_base_case[('DISCON_in','AWC_Mode')] = {'vals': [0,2,2,2,2,2], 'group': 2} + control_base_case[('DISCON_in','AWC_NumModes')] = {'vals': [1,1,2,2,2,2], 'group': 2} + control_base_case[('DISCON_in','AWC_n')] = {'vals': [[0],[0],[1,1],[1,1],[1,1], [1,1]], 'group': 2} + control_base_case[('DISCON_in','AWC_freq')] = {'vals': [[0],[0.05],[0.05,0.05],[0.05,0.05],[0.05,0.05], [0.05,0.05]], 'group': 2} + control_base_case[('DISCON_in','AWC_amp')] = {'vals': [[0],[1.0],[1.0,1.0],[1.0,1.0],[1.0,0.0], [0.0,1.0]], 'group': 2} + control_base_case[('DISCON_in','AWC_clockangle')] = {'vals': [[0],[0],[0,-90],[0,90],[0,0], [180,180]], 'group': 2} # simulation set up r = run_FAST_ROSCO() r.tuning_yaml = parameter_filename r.wind_case_fcn = cl.power_curve # single step wind input r.wind_case_opts = { - 'U': [14], # from 10 to 15 m/s + 'U': [16], # from 10 to 15 m/s 'TMax': 100, } r.case_inputs = control_base_case diff --git a/ROSCO/src/Controllers.f90 b/ROSCO/src/Controllers.f90 index 78b7f514..71af6792 100644 --- a/ROSCO/src/Controllers.f90 +++ b/ROSCO/src/Controllers.f90 @@ -62,7 +62,7 @@ SUBROUTINE PitchControl(avrSWAP, CntrPar, LocalVar, objInst, DebugVar, ErrVar) LocalVar%PC_PitComT = PIController(LocalVar%PC_SpdErr, LocalVar%PC_KP, LocalVar%PC_KI, LocalVar%PC_MinPit, LocalVar%PC_MaxPit, LocalVar%DT, LocalVar%BlPitch(1), LocalVar%piP, LocalVar%restart, objInst%instPI) DebugVar%PC_PICommand = LocalVar%PC_PitComT ! Find individual pitch control contribution - IF ((CntrPar%IPC_ControlMode >= 1) .OR. ((CntrPar%Y_ControlMode == 2) .OR. (CntrPar%AWC_Mode == 2))) THEN + IF ((CntrPar%IPC_ControlMode >= 1) .OR. (CntrPar%Y_ControlMode == 2)) THEN CALL IPC(CntrPar, LocalVar, objInst, DebugVar, ErrVar) ELSE LocalVar%IPC_PitComF = 0.0 ! THIS IS AN ARRAY!! @@ -127,8 +127,8 @@ SUBROUTINE PitchControl(avrSWAP, CntrPar, LocalVar, objInst, DebugVar, ErrVar) ENDIF ! Active wake control - IF (CntrPar%AWC_Mode == 1) THEN - CALL ActiveWakeControl(CntrPar, LocalVar) + IF (CntrPar%AWC_Mode > 0) THEN + CALL ActiveWakeControl(CntrPar, LocalVar, DebugVar) ENDIF ! Place pitch actuator here, so it can be used with or without open-loop @@ -402,9 +402,9 @@ SUBROUTINE IPC(CntrPar, LocalVar, objInst, DebugVar, ErrVar) REAL(DbKi) :: axisTilt_2P, axisYaw_2P, axisYawF_2P ! Direct axis and quadrature axis outputted by Coleman transform, 1P REAL(DbKi) :: axisYawIPC_1P ! IPC contribution with yaw-by-IPC component REAL(DbKi) :: Y_MErr, Y_MErrF, Y_MErrF_IPC ! Unfiltered and filtered yaw alignment error [rad] - REAL(DbKi) :: AWC_TiltAmp, AWC_YawAmp ! Tilt and yaw amplitude for AWC + REAL(DbKi) :: AWC_YawAmp ! Yaw amplitude for AWC REAL(DbKi) :: AWC_TiltAngle, AWC_YawAngle ! Tilt and yaw initial phase angle for AWC - REAL(DbKi) :: AWC_TiltFreq, AWC_YawFreq ! Tilt and yaw frequency for AWC + REAL(DbKi) :: AWC_YawFreq ! Yaw frequency for AWC CHARACTER(*), PARAMETER :: RoutineName = 'IPC' @@ -450,40 +450,12 @@ SUBROUTINE IPC(CntrPar, LocalVar, objInst, DebugVar, ErrVar) LocalVar%IPC_axisTilt_2P = PIController(axisTilt_2P, LocalVar%IPC_KP(2), LocalVar%IPC_KI(2), -LocalVar%IPC_IntSat, LocalVar%IPC_IntSat, LocalVar%DT, 0.0_DbKi, LocalVar%piP, LocalVar%restart, objInst%instPI) LocalVar%IPC_axisYaw_2P = PIController(axisYawF_2P, LocalVar%IPC_KP(2), LocalVar%IPC_KI(2), -LocalVar%IPC_IntSat, LocalVar%IPC_IntSat, LocalVar%DT, 0.0_DbKi, LocalVar%piP, LocalVar%restart, objInst%instPI) END IF - ! Determine AWC-IPC tilt and yaw moments - ELSEIF ((CntrPar%AWC_Mode == 2) .AND. (CntrPar%AWC_n(1) /= 0)) THEN - IF (CntrPar%AWC_NumModes == 1) THEN - AWC_TiltAmp = CntrPar%AWC_amp(1) - AWC_YawAmp = CntrPar%AWC_amp(1) - AWC_TiltAngle = 0 - AWC_YawAngle = CntrPar%AWC_clockangle(1) - AWC_TiltFreq = CntrPar%AWC_freq(1) - AWC_YawFreq = CntrPar%AWC_freq(1) - ELSE - AWC_TiltAmp = CntrPar%AWC_amp(1) - AWC_YawAmp = CntrPar%AWC_amp(2) - AWC_TiltAngle = CntrPar%AWC_clockangle(1) - AWC_YawAngle = CntrPar%AWC_clockangle(2) - AWC_TiltFreq = CntrPar%AWC_freq(1) - AWC_YawFreq = CntrPar%AWC_freq(2) - END IF - - LocalVar%IPC_axisTilt_1P = PI/180*AWC_TiltAmp*sin(LocalVar%Time*2*PI*AWC_TiltFreq+AWC_TiltAngle*PI/180) - LocalVar%IPC_axisYaw_1P = PI/180*AWC_YawAmp*sin(LocalVar%Time*2*PI*AWC_YawFreq+AWC_YawAngle*PI/180) - LocalVar%IPC_axisTilt_2P = 0.0 - LocalVar%IPC_axisYaw_2P = 0.0 - ELSE - LocalVar%IPC_axisTilt_1P = 0.0 - LocalVar%IPC_axisYaw_1P = 0.0 - LocalVar%IPC_axisTilt_2P = 0.0 - LocalVar%IPC_axisYaw_2P = 0.0 - END IF ! Add the yaw-by-IPC contribution axisYawIPC_1P = LocalVar%IPC_axisYaw_1P + Y_MErrF_IPC ! Pass direct and quadrature axis through the inverse Coleman transform to get the commanded pitch angles - CALL ColemanTransformInverse(LocalVar%IPC_axisTilt_1P, axisYawIPC_1P, LocalVar%Azimuth, NP_1, CntrPar%IPC_aziOffset(1), PitComIPC_1P) + CALL ColemanTransformInverse(LocalVar%IPC_axisTilt_1P, axisYawIPC_1P, LocalVar%Azimuth, CntrPar%AWC_n(1), CntrPar%IPC_aziOffset(1), PitComIPC_1P) CALL ColemanTransformInverse(LocalVar%IPC_axisTilt_2P, LocalVar%IPC_axisYaw_2P, LocalVar%Azimuth, NP_2, CntrPar%IPC_aziOffset(2), PitComIPC_2P) ! Sum nP IPC contributions and store to LocalVar data type @@ -501,8 +473,8 @@ SUBROUTINE IPC(CntrPar, LocalVar, objInst, DebugVar, ErrVar) END DO ! debugging - DebugVar%axisTilt_1P = LocalVar%IPC_axisTilt_1P ! axisTilt_1P - DebugVar%axisYaw_1P = LocalVar%IPC_axisYaw_1P ! axisYaw_1P + DebugVar%axisTilt_1P = axisTilt_1P + DebugVar%axisYaw_1P = axisYaw_1P DebugVar%axisTilt_2P = LocalVar%IPC_axisTilt_2P DebugVar%axisYaw_2P = LocalVar%IPC_axisYaw_2P @@ -636,14 +608,15 @@ END SUBROUTINE FlapControl !------------------------------------------------------------------------------------------------------------------------------- - SUBROUTINE ActiveWakeControl(CntrPar, LocalVar) + SUBROUTINE ActiveWakeControl(CntrPar, LocalVar, DebugVar) ! Active wake controller ! AWC_Mode = 0, No active wake control ! AWC_Mode = 1, SNL active wake control - ! AWC_Mode = 2, NREL active wake control - USE ROSCO_Types, ONLY : ControlParameters, LocalVariables, ObjectInstances + ! AWC_Mode = 2, Coleman Transform-based active wake control + USE ROSCO_Types, ONLY : ControlParameters, LocalVariables, DebugVariables, ObjectInstances TYPE(ControlParameters), INTENT(INOUT) :: CntrPar + TYPE(DebugVariables), INTENT(INOUT) :: DebugVar TYPE(LocalVariables), INTENT(INOUT) :: LocalVar ! Local vars @@ -653,10 +626,11 @@ SUBROUTINE ActiveWakeControl(CntrPar, LocalVar) REAL(DbKi), DIMENSION(3) :: AWC_angle COMPLEX(DbKi), DIMENSION(3) :: AWC_complexangle COMPLEX(DbKi) :: complexI = (0.0, 1.0) - INTEGER(IntKi) :: Imode, K ! Index used for looping through AWC modes + INTEGER(IntKi) :: Imode, K ! Index used for looping through AWC modes, blades REAL(DbKi) :: clockang ! Clock angle for AWC pitching - REAL(DbKi) :: omega ! angular frequency for AWC pitching in rad/s - REAL(DbKi) :: amp ! amplitude for AWC pitching in radian + REAL(DbKi) :: omega ! angular frequency for AWC pitching in Hz + REAL(DbKi) :: amp ! amplitude for AWC pitching in degrees + REAL(DbKi), DIMENSION(2) :: AWC_TiltYaw = [0.0, 0.0] ! AWC Tilt and yaw pitch signal ! Compute the AWC pitch settings @@ -681,6 +655,24 @@ SUBROUTINE ActiveWakeControl(CntrPar, LocalVar) LocalVar%PitCom(K) = LocalVar%PitCom(K) + REAL(LocalVar%AWC_complexangle(K)) END DO + ELSEIF (CntrPar%AWC_Mode == 2) THEN + + DO Imode = 1,CntrPar%AWC_NumModes + DebugVar%axisTilt_1P = AWC_TiltYaw(1) + AWC_TiltYaw = [0.0, 0.0] + AWC_TiltYaw(Imode) = PI/180*CntrPar%AWC_amp(Imode)*cos(LocalVar%Time*2*PI*CntrPar%AWC_freq(Imode) + CntrPar%AWC_clockangle(Imode)*PI/180) + IF (CntrPar%AWC_NumModes == 1) THEN + AWC_TiltYaw(2) = PI/180*CntrPar%AWC_amp(1)*cos(LocalVar%Time*2*PI*CntrPar%AWC_freq(1) + 2*CntrPar%AWC_clockangle(1)*PI/180) + ENDIF + CALL ColemanTransformInverse(AWC_TiltYaw(1), AWC_TiltYaw(2), LocalVar%Azimuth, CntrPar%AWC_n(Imode), 0.0, AWC_angle) + + DO K = 1,LocalVar%NumBl ! Loop through all blades, apply AWC_angle + LocalVar%PitCom(K) = LocalVar%PitCom(K) + AWC_angle(K) + END DO + END DO + DebugVar%axisYaw_1P = AWC_TiltYaw(2) + DebugVar%axisTilt_2P = AWC_angle(1) + ENDIF END SUBROUTINE ActiveWakeControl diff --git a/Test_Cases/BAR_10/BAR_10_DISCON.IN b/Test_Cases/BAR_10/BAR_10_DISCON.IN index 17875c9c..ca5b87ed 100644 --- a/Test_Cases/BAR_10/BAR_10_DISCON.IN +++ b/Test_Cases/BAR_10/BAR_10_DISCON.IN @@ -1,5 +1,5 @@ ! Controller parameter input file for the BAR_10 wind turbine -! - File written using ROSCO version 2.7.0 controller tuning logic on 02/06/23 +! - File written using ROSCO version 2.7.0 controller tuning logic on 03/06/23 !------- DEBUG ------------------------------------------------------------ 1 ! LoggingLevel - {0: write no debug files, 1: write standard output .dbg-file, 2: LoggingLevel 1 + ROSCO LocalVars (.dbg2) 3: LoggingLevel 2 + complete avrSWAP-array (.dbg3)} @@ -21,6 +21,7 @@ 0 ! OL_Mode - Open loop control mode {0: no open loop control, 1: open loop control vs. time} 0 ! PA_Mode - Pitch actuator mode {0 - not used, 1 - first order filter, 2 - second order filter} 0 ! PF_Mode - Pitch fault mode {0 - not used, 1 - constant offset on one or more blades} +0 ! AWC_Mode - Active wake control {0 - not used, 1 - SNL method, 2 - NREL method} 0 ! Ext_Mode - External control mode {0 - not used, 1 - call external dynamic library} 0 ! ZMQ_Mode - Fuse ZeroMQ interface {0: unused, 1: Yaw Control} @@ -140,6 +141,13 @@ !------- Pitch Actuator Faults ----------------------------------------------------- 0.00000000 0.00000000 0.00000000 ! PF_Offsets - Constant blade pitch offsets for blades 1-3 [rad] +!------- Active Wake Control ----------------------------------------------------- +1 ! AWC_NumModes - number of forcing modes +1 ! AWC_n - azimuthal mode number(s) (i.e., the azimuthal mode number relates to the number and direction of the lobes of the wake structure according to the classical spatio-temporal Fourier decomposition of an arbitrary quantity q, sigma(sigma(q*exp(i*n*theta)*exp(i*omega*time))). For the case of a non-time-varying flow (i.e., where omega = 0), the azimuthal mode number specifies the number of cycles of blade pitch oscillation per one rotation around the rotor azimuth.) +0.0500 ! AWC_freq - frequency(s) of forcing mode(s) [Hz] +1.0000 ! AWC_amp - pitch amplitude(s) of forcing mode(s) (note that AWC_amp specifies the amplitude of each individual mode so that the total amplitude of pitching will be the sum of AWC_amp) [deg] +0.0000 ! AWC_clockangle - clocking angle(s) of forcing mode(s) [deg] + !------- External Controller Interface ----------------------------------------------------- "unused" ! DLL_FileName - Name/location of the dynamic library in the Bladed-DLL format "unused" ! DLL_InFile - Name of input file sent to the DLL (-) diff --git a/Test_Cases/IEA-15-240-RWT-UMaineSemi/DISCON-UMaineSemi.IN b/Test_Cases/IEA-15-240-RWT-UMaineSemi/DISCON-UMaineSemi.IN index 5f55c5ab..ccdc4215 100644 --- a/Test_Cases/IEA-15-240-RWT-UMaineSemi/DISCON-UMaineSemi.IN +++ b/Test_Cases/IEA-15-240-RWT-UMaineSemi/DISCON-UMaineSemi.IN @@ -1,5 +1,5 @@ ! Controller parameter input file for the IEA-15-240-RWT-UMaineSemi wind turbine -! - File written using ROSCO version 2.7.0 controller tuning logic on 02/06/23 +! - File written using ROSCO version 2.7.0 controller tuning logic on 03/06/23 !------- DEBUG ------------------------------------------------------------ 2 ! LoggingLevel - {0: write no debug files, 1: write standard output .dbg-file, 2: LoggingLevel 1 + ROSCO LocalVars (.dbg2) 3: LoggingLevel 2 + complete avrSWAP-array (.dbg3)} @@ -21,6 +21,7 @@ 0 ! OL_Mode - Open loop control mode {0: no open loop control, 1: open loop control vs. time} 2 ! PA_Mode - Pitch actuator mode {0 - not used, 1 - first order filter, 2 - second order filter} 0 ! PF_Mode - Pitch fault mode {0 - not used, 1 - constant offset on one or more blades} +0 ! AWC_Mode - Active wake control {0 - not used, 1 - SNL method, 2 - NREL method} 0 ! Ext_Mode - External control mode {0 - not used, 1 - call external dynamic library} 0 ! ZMQ_Mode - Fuse ZeroMQ interface {0: unused, 1: Yaw Control} @@ -140,6 +141,13 @@ !------- Pitch Actuator Faults ----------------------------------------------------- 0.00000000 0.00000000 0.00000000 ! PF_Offsets - Constant blade pitch offsets for blades 1-3 [rad] +!------- Active Wake Control ----------------------------------------------------- +1 ! AWC_NumModes - number of forcing modes +1 ! AWC_n - azimuthal mode number(s) (i.e., the azimuthal mode number relates to the number and direction of the lobes of the wake structure according to the classical spatio-temporal Fourier decomposition of an arbitrary quantity q, sigma(sigma(q*exp(i*n*theta)*exp(i*omega*time))). For the case of a non-time-varying flow (i.e., where omega = 0), the azimuthal mode number specifies the number of cycles of blade pitch oscillation per one rotation around the rotor azimuth.) +0.0500 ! AWC_freq - frequency(s) of forcing mode(s) [Hz] +1.0000 ! AWC_amp - pitch amplitude(s) of forcing mode(s) (note that AWC_amp specifies the amplitude of each individual mode so that the total amplitude of pitching will be the sum of AWC_amp) [deg] +0.0000 ! AWC_clockangle - clocking angle(s) of forcing mode(s) [deg] + !------- External Controller Interface ----------------------------------------------------- "unused" ! DLL_FileName - Name/location of the dynamic library in the Bladed-DLL format "unused" ! DLL_InFile - Name of input file sent to the DLL (-) diff --git a/Test_Cases/NREL-5MW/DISCON.IN b/Test_Cases/NREL-5MW/DISCON.IN index 84b3971c..43ff3097 100644 --- a/Test_Cases/NREL-5MW/DISCON.IN +++ b/Test_Cases/NREL-5MW/DISCON.IN @@ -1,5 +1,5 @@ ! Controller parameter input file for the NREL-5MW wind turbine -! - File written using ROSCO version 2.7.0 controller tuning logic on 02/06/23 +! - File written using ROSCO version 2.7.0 controller tuning logic on 03/06/23 !------- DEBUG ------------------------------------------------------------ 1 ! LoggingLevel - {0: write no debug files, 1: write standard output .dbg-file, 2: LoggingLevel 1 + ROSCO LocalVars (.dbg2) 3: LoggingLevel 2 + complete avrSWAP-array (.dbg3)} @@ -21,6 +21,7 @@ 0 ! OL_Mode - Open loop control mode {0: no open loop control, 1: open loop control vs. time} 0 ! PA_Mode - Pitch actuator mode {0 - not used, 1 - first order filter, 2 - second order filter} 0 ! PF_Mode - Pitch fault mode {0 - not used, 1 - constant offset on one or more blades} +0 ! AWC_Mode - Active wake control {0 - not used, 1 - SNL method, 2 - NREL method} 0 ! Ext_Mode - External control mode {0 - not used, 1 - call external dynamic library} 0 ! ZMQ_Mode - Fuse ZeroMQ interface {0: unused, 1: Yaw Control} @@ -141,11 +142,11 @@ 0.00000000 0.00000000 0.00000000 ! PF_Offsets - Constant blade pitch offsets for blades 1-3 [rad] !------- Active Wake Control ----------------------------------------------------- -1 ! AWC_NumModes - AWC azimuthal mode number(s) (only used in SNL method) -1 ! AWC_n - AWC azimuthal number (only used in SNL method) -0.3142 ! AWC_omega - AWC frequency [rad/s] -0.0175 ! AWC_amp - AWC amplitude [rad] -0.0000 ! AWC_clockangle - WC clock angle [deg] +1 ! AWC_NumModes - number of forcing modes +1 ! AWC_n - azimuthal mode number(s) (i.e., the azimuthal mode number relates to the number and direction of the lobes of the wake structure according to the classical spatio-temporal Fourier decomposition of an arbitrary quantity q, sigma(sigma(q*exp(i*n*theta)*exp(i*omega*time))). For the case of a non-time-varying flow (i.e., where omega = 0), the azimuthal mode number specifies the number of cycles of blade pitch oscillation per one rotation around the rotor azimuth.) +0.0500 ! AWC_freq - frequency(s) of forcing mode(s) [Hz] +1.0000 ! AWC_amp - pitch amplitude(s) of forcing mode(s) (note that AWC_amp specifies the amplitude of each individual mode so that the total amplitude of pitching will be the sum of AWC_amp) [deg] +0.0000 ! AWC_clockangle - clocking angle(s) of forcing mode(s) [deg] !------- External Controller Interface ----------------------------------------------------- "unused" ! DLL_FileName - Name/location of the dynamic library in the Bladed-DLL format diff --git a/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF00_Coords.txt b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF00_Coords.txt new file mode 100644 index 00000000..e9309e03 --- /dev/null +++ b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF00_Coords.txt @@ -0,0 +1,208 @@ + 201 NumCoords ! The number of coordinates in the airfoil shape file (including an extra coordinate for airfoil reference). Set to zero if coordinates not included. +! ......... x-y coordinates are next if NumCoords > 0 ............. +! x-y coordinate of airfoil reference +! x/c y/c + 0.500000 0 +! coordinates of airfoil shape +! interpolation to 200 points +! x/c y/c + 1.00000000000000e+00 1.39471767468535e-15 + 9.99492456366675e-01 -2.24148318097192e-02 + 9.97998442938042e-01 -4.47793322876220e-02 + 9.95467925285309e-01 -6.70365581798988e-02 + 9.91981297584349e-01 -8.91473650534134e-02 + 9.87535715129057e-01 -1.11060278052329e-01 + 9.82077318711035e-01 -1.32710580192188e-01 + 9.75645752125599e-01 -1.54053421230182e-01 + 9.68327814997901e-01 -1.75062933826036e-01 + 9.60169311985103e-01 -1.95709072524484e-01 + 9.51019761347344e-01 -2.15876183412258e-01 + 9.41032965384679e-01 -2.35574562290692e-01 + 9.30228135178293e-01 -2.54760790502087e-01 + 9.18600973249388e-01 -2.73373623585437e-01 + 9.06286773024904e-01 -2.91445285668231e-01 + 8.93185468322794e-01 -3.08852284793353e-01 + 8.79429131687551e-01 -3.25629671028512e-01 + 8.65020010482894e-01 -3.41723774803256e-01 + 8.50001183978561e-01 -3.57112177867390e-01 + 8.34409947013148e-01 -3.71770913166281e-01 + 8.18263641617925e-01 -3.85648552858056e-01 + 8.01628456968450e-01 -3.98748400170390e-01 + 7.84595497003635e-01 -4.11125308634395e-01 + 7.67122879759481e-01 -4.22652791316593e-01 + 7.49310431319132e-01 -4.33396610986265e-01 + 7.31192318835036e-01 -4.43343955969101e-01 + 7.12809122212147e-01 -4.52489087671710e-01 + 6.94192882766294e-01 -4.60805480273623e-01 + 6.75356426213553e-01 -4.68221413716844e-01 + 6.56401839622218e-01 -4.74887730613940e-01 + 6.37339053739694e-01 -4.80732155257960e-01 + 6.18216799132259e-01 -4.85797045327747e-01 + 5.99072127289441e-01 -4.90092245328121e-01 + 5.79920098443495e-01 -4.93529601024917e-01 + 5.60830239179689e-01 -4.96308798320980e-01 + 5.41809841204068e-01 -4.98254021026852e-01 + 5.22902255947823e-01 -4.99468302412137e-01 + 5.04138617740840e-01 -4.99969461095629e-01 + 4.85547896236042e-01 -4.99782528766859e-01 + 4.67157180742230e-01 -4.98932207272937e-01 + 4.48992436485026e-01 -4.97429938215178e-01 + 4.31090922803529e-01 -4.95199601187320e-01 + 4.13451809735344e-01 -4.92443613818918e-01 + 3.96103805194879e-01 -4.89121761104649e-01 + 3.79096627499341e-01 -4.85124024486578e-01 + 3.62407327470865e-01 -4.80659331665282e-01 + 3.46066636516655e-01 -4.75685087833417e-01 + 3.30096115507155e-01 -4.70203747355840e-01 + 3.14480352866339e-01 -4.64314583285520e-01 + 2.99254081643518e-01 -4.57980939909463e-01 + 2.84450426976392e-01 -4.51177575409728e-01 + 2.70052866033160e-01 -4.43988939168408e-01 + 2.56066550501318e-01 -4.36445000343028e-01 + 2.42483923277781e-01 -4.28590357469827e-01 + 2.29353790045290e-01 -4.20376016737305e-01 + 2.16603264062538e-01 -4.11943400950387e-01 + 2.04317853658681e-01 -4.03192627249739e-01 + 1.92459446608375e-01 -3.94201135001427e-01 + 1.81000889336564e-01 -3.85028191464174e-01 + 1.69975424985927e-01 -3.75644842886581e-01 + 1.59391096347033e-01 -3.66066250246720e-01 + 1.49207465402409e-01 -3.56350787229031e-01 + 1.39487797355366e-01 -3.46454046169616e-01 + 1.30120240319336e-01 -3.36494792306467e-01 + 1.21215059211584e-01 -3.26386152642893e-01 + 1.12658598266997e-01 -3.16237746353461e-01 + 1.04576031217800e-01 -3.05961432628231e-01 + 9.68117255237024e-02 -2.95688054408038e-01 + 8.94183192669232e-02 -2.85386126810182e-01 + 8.24692613312736e-02 -2.75012912186705e-01 + 7.58031535914957e-02 -2.64686382950272e-01 + 6.95265332165359e-02 -2.54344021225804e-01 + 6.36014773641337e-02 -2.44016481364265e-01 + 5.79875426758039e-02 -2.33733614688635e-01 + 5.27214572831349e-02 -2.23480055785704e-01 + 4.77407756799443e-02 -2.13293199734344e-01 + 4.30911198450984e-02 -2.03156079856565e-01 + 3.87383767680824e-02 -1.93089031734237e-01 + 3.47120078049050e-02 -1.83082592300236e-01 + 3.09831915833964e-02 -1.73156756176345e-01 + 2.73972939643108e-02 -1.63368018994347e-01 + 2.42148186237083e-02 -1.53628642008223e-01 + 2.11591799216729e-02 -1.44034525093811e-01 + 1.84468268040835e-02 -1.34516182856983e-01 + 1.59138335980001e-02 -1.25130288878497e-01 + 1.36131610235361e-02 -1.15857640369663e-01 + 1.14838295959446e-02 -1.06718459753818e-01 + 9.63946848246122e-03 -9.76879552179587e-02 + 7.95426403181202e-03 -8.87933378901162e-02 + 6.48712578142165e-03 -8.00260463587484e-02 + 5.16242415846458e-03 -7.13984274261874e-02 + 3.96141128417998e-03 -6.29131069298763e-02 + 2.94206395570219e-03 -5.45622661453796e-02 + 2.13806552335743e-03 -4.63439971542207e-02 + 1.44971764281537e-03 -3.82678090225701e-02 + 9.19962693446690e-04 -3.03318166757594e-02 + 5.13539051739693e-04 -2.25365794204782e-02 + 2.28620066730956e-04 -1.48836875697269e-02 + 7.90911911777832e-05 -7.37097402213213e-03 + 0.00000000000000e+00 0.00000000000000e+00 + 7.90677652262213e-05 7.36950623430851e-03 + 2.28464565111448e-04 1.48777524287952e-02 + 5.12873373489222e-04 2.25230881526787e-02 + 9.18597455380868e-04 3.03075781606325e-02 + 1.44666023734530e-03 3.82295855300727e-02 + 2.13316604432083e-03 4.62883932406539e-02 + 2.93360033162344e-03 5.44859437589187e-02 + 3.94803817877652e-03 6.28126278437423e-02 + 5.14351598889891e-03 7.12701576675508e-02 + 6.46190285472730e-03 7.98662577301812e-02 + 7.91902151822289e-03 8.85987369572577e-02 + 9.59444803793060e-03 9.74544221488751e-02 + 1.14235102541198e-02 1.06442996258128e-01 + 1.35337735871235e-02 1.15536956454720e-01 + 1.58224157496375e-02 1.24758221029162e-01 + 1.83235379987219e-02 1.34093489066500e-01 + 2.10204849111940e-02 1.43552196795823e-01 + 2.40367775427033e-02 1.53088940216613e-01 + 2.71877316554608e-02 1.62764372071491e-01 + 3.07399015207509e-02 1.72484170230167e-01 + 3.44190712967375e-02 1.82342411230462e-01 + 3.84042462872392e-02 1.92272935169736e-01 + 4.26949602499204e-02 2.02267606430067e-01 + 4.72829519098945e-02 2.12327253752788e-01 + 5.21982679528133e-02 2.22432953038477e-01 + 5.73926065743804e-02 2.32603305860823e-01 + 6.29241217245761e-02 2.42803072101294e-01 + 6.87643637125652e-02 2.53043124634065e-01 + 7.49396649714102e-02 2.63302631639567e-01 + 8.15067225995126e-02 2.73538864194590e-01 + 8.83465340790937e-02 2.83822725719936e-01 + 9.56069618941523e-02 2.94046380437990e-01 + 1.03242517429104e-01 3.04232736766140e-01 + 1.11181349110592e-01 3.14429033366110e-01 + 1.19600191231908e-01 3.24484491634080e-01 + 1.28332959831487e-01 3.34525491878455e-01 + 1.37529624980321e-01 3.44409800526354e-01 + 1.47054393871766e-01 3.54250702832129e-01 + 1.57068458906247e-01 3.63878030450328e-01 + 1.67434000189824e-01 3.73414748310375e-01 + 1.78267900010996e-01 3.82720355055487e-01 + 1.89470766243389e-01 3.91888095042532e-01 + 2.01116356758227e-01 4.00815766784955e-01 + 2.13142982412971e-01 4.09560128320329e-01 + 2.25647591527817e-01 4.17962490202192e-01 + 2.38508303803600e-01 4.26178518900819e-01 + 2.51815542326035e-01 4.34041451446706e-01 + 2.65513873471791e-01 4.41613730534841e-01 + 2.79625890849574e-01 4.48822548308045e-01 + 2.94122344676086e-01 4.55688297738170e-01 + 3.09025395595222e-01 4.62123018507889e-01 + 3.24322980248437e-01 4.68104987140686e-01 + 3.39961508551486e-01 4.73721797521014e-01 + 3.55970212497486e-01 4.78842188217134e-01 + 3.72330405840910e-01 4.83451204703119e-01 + 3.89018592148974e-01 4.87553971207526e-01 + 4.06028086432003e-01 4.91073750593815e-01 + 4.23330061515063e-01 4.94038626508448e-01 + 4.40892507832343e-01 4.96523552581426e-01 + 4.58722088973087e-01 4.98299627767656e-01 + 4.76781800214759e-01 4.99452452619975e-01 + 4.95047752165150e-01 4.99958293491181e-01 + 5.13494417346180e-01 4.99806115294212e-01 + 5.32095125341593e-01 4.98977641113232e-01 + 5.50821128028667e-01 4.97448239777686e-01 + 5.69628317431665e-01 4.95095914136444e-01 + 5.88509798330163e-01 4.92097041935332e-01 + 6.07423091269127e-01 4.88360764967307e-01 + 6.26315879676062e-01 4.83792644100844e-01 + 6.45179027618201e-01 4.78506342917923e-01 + 6.63949992276556e-01 4.72397468589394e-01 + 6.82596771397553e-01 4.65480454296126e-01 + 7.01105667898352e-01 4.57821533331759e-01 + 7.19390458980571e-01 4.49306560335264e-01 + 7.37449386734799e-01 4.40021763716986e-01 + 7.55233287450602e-01 4.29949280199755e-01 + 7.72675183085231e-01 4.19055842892285e-01 + 7.89810876588208e-01 4.07465502995371e-01 + 8.06484809364324e-01 3.95019026978122e-01 + 8.22749466427636e-01 3.81863671783111e-01 + 8.38549437843995e-01 3.67985948498897e-01 + 8.53822843141276e-01 3.53376712171519e-01 + 8.68482698282576e-01 3.38013117891467e-01 + 8.82527277768971e-01 3.21961416297325e-01 + 8.95954036277289e-01 3.05275366473099e-01 + 9.08757285533517e-01 2.87998251390473e-01 + 9.20757624348661e-01 2.70058949061020e-01 + 9.32077214908394e-01 2.51596702608668e-01 + 9.42611287438903e-01 2.32595879244925e-01 + 9.52349414910574e-01 2.13103474747613e-01 + 9.61237529561560e-01 1.93147648123409e-01 + 9.69168871294468e-01 1.72736199342553e-01 + 9.76326703713309e-01 1.51992962994221e-01 + 9.82585730197106e-01 1.30917869381533e-01 + 9.87884002029843e-01 1.09544033639734e-01 + 9.92202667894419e-01 8.79209963846691e-02 + 9.95599172262122e-01 6.61100082160239e-02 + 9.98052102758341e-01 4.41573284776160e-02 + 9.99507690675012e-01 2.21028728366928e-02 + 1.00000000000000e+00 1.39471767468535e-15 diff --git a/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF01_Coords.txt b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF01_Coords.txt new file mode 100644 index 00000000..c0c8ddad --- /dev/null +++ b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF01_Coords.txt @@ -0,0 +1,208 @@ + 201 NumCoords ! The number of coordinates in the airfoil shape file (including an extra coordinate for airfoil reference). Set to zero if coordinates not included. +! ......... x-y coordinates are next if NumCoords > 0 ............. +! x-y coordinate of airfoil reference +! x/c y/c + 0.489474 0 +! coordinates of airfoil shape +! interpolation to 200 points +! x/c y/c + 1.00000000000000e+00 -3.16421772612390e-03 + 9.99110945270443e-01 -2.47105920697162e-02 + 9.97576994375339e-01 -4.67993845022092e-02 + 9.95459944687624e-01 -6.84337167356077e-02 + 9.91976392334682e-01 -9.00657715770117e-02 + 9.87532357694084e-01 -1.11371691742356e-01 + 9.82073007117098e-01 -1.32004290598503e-01 + 9.75632495177376e-01 -1.51997295578341e-01 + 9.68304625227921e-01 -1.71396793768580e-01 + 9.60134319308372e-01 -1.90350472287492e-01 + 9.50973174570070e-01 -2.10503605813256e-01 + 9.40976075096518e-01 -2.30186416006723e-01 + 9.30161994799789e-01 -2.49354345164969e-01 + 9.18526548050635e-01 -2.67946053746076e-01 + 9.06204685559811e-01 -2.85993589913206e-01 + 8.93096814131007e-01 -3.03374276912405e-01 + 8.79335004439212e-01 -3.20123403157046e-01 + 8.64921830314282e-01 -3.36188237142695e-01 + 8.49900429191050e-01 -3.51546887620593e-01 + 8.34308004668356e-01 -3.66174875302933e-01 + 8.18161715887287e-01 -3.80020141794273e-01 + 8.01527591100297e-01 -3.93086268689914e-01 + 7.84496904773810e-01 -4.04786375894643e-01 + 7.67028251214628e-01 -4.15444728414506e-01 + 7.49221098481114e-01 -4.25443666639427e-01 + 7.31109312546861e-01 -4.34681496122239e-01 + 7.12733221739921e-01 -4.43095560497414e-01 + 6.94124804992610e-01 -4.50716083967267e-01 + 6.75296861217813e-01 -4.57507733373021e-01 + 6.56351220288612e-01 -4.63629797162085e-01 + 6.37297642282493e-01 -4.69021650406962e-01 + 6.18184579076336e-01 -4.73661711191075e-01 + 5.99048824748551e-01 -4.77500682555689e-01 + 5.79905140141725e-01 -4.80476298777868e-01 + 5.60822552266790e-01 -4.82821100897016e-01 + 5.41807779672030e-01 -4.84393609336454e-01 + 5.23137860195204e-01 -4.85340334737817e-01 + 5.04895615780131e-01 -4.85677059437076e-01 + 4.86822413494681e-01 -4.85372268979213e-01 + 4.68943246111643e-01 -4.84434587337354e-01 + 4.51281215228627e-01 -4.82849729526095e-01 + 4.33869791962394e-01 -4.80550261086293e-01 + 4.16708291601139e-01 -4.77756903947675e-01 + 3.99821942290793e-01 -4.74438844863898e-01 + 3.83021226581361e-01 -4.70501187606855e-01 + 3.66510028690683e-01 -4.66117838259083e-01 + 3.50339822528374e-01 -4.61229488062895e-01 + 3.34529434920323e-01 -4.55868065561778e-01 + 3.19060580350289e-01 -4.50137865005078e-01 + 3.03961951611492e-01 -4.44019094016567e-01 + 2.89263477671933e-01 -4.37498086693495e-01 + 2.74954691526094e-01 -4.30627011410182e-01 + 2.61045693322669e-01 -4.23408038064864e-01 + 2.47531081353258e-01 -4.15862808513859e-01 + 2.34454873671549e-01 -4.07946420300901e-01 + 2.21749536060482e-01 -3.99796724707317e-01 + 2.09495761009538e-01 -3.91329723402531e-01 + 1.97654805990354e-01 -3.82623286493885e-01 + 1.86194798835722e-01 -3.73767309376824e-01 + 1.75143832165431e-01 -3.64767492631537e-01 + 1.64510931825440e-01 -3.55619768853155e-01 + 1.54264662143747e-01 -3.46336240294808e-01 + 1.44469444171873e-01 -3.36855727877300e-01 + 1.35016546824907e-01 -3.27295058357275e-01 + 1.26007074796798e-01 -3.17588898325485e-01 + 1.17335095261661e-01 -3.07850346569760e-01 + 1.09122191907664e-01 -2.97988397774553e-01 + 1.01228904610188e-01 -2.88095133738336e-01 + 9.37005857644255e-02 -2.78149751233394e-01 + 8.65952060326960e-02 -2.68149983931702e-01 + 7.97470493709899e-02 -2.58245516255184e-01 + 7.32564041991407e-02 -2.48375945846845e-01 + 6.71103398619902e-02 -2.38520800068324e-01 + 6.12956358739206e-02 -2.28273089593854e-01 + 5.58512861647731e-02 -2.18035625337734e-01 + 5.06986492562267e-02 -2.07863675578317e-01 + 4.58459063482147e-02 -1.97741417265822e-01 + 4.12374651654770e-02 -1.87689118226564e-01 + 3.69363886388660e-02 -1.77695953267912e-01 + 3.29623755477581e-02 -1.67780856055308e-01 + 2.91933599630294e-02 -1.58000033452927e-01 + 2.58326584607911e-02 -1.48266339522027e-01 + 2.25688351721396e-02 -1.39011630549253e-01 + 1.95732992520596e-02 -1.30105462233865e-01 + 1.67610738246130e-02 -1.21314096800611e-01 + 1.42583321073789e-02 -1.12582415338248e-01 + 1.19908166431120e-02 -1.03925933593292e-01 + 9.99928542511028e-03 -9.53469054771868e-02 + 8.12764378342123e-03 -8.68845733614765e-02 + 6.50553857600199e-03 -7.85191937270735e-02 + 5.17572423597908e-03 -7.02483867655549e-02 + 3.97140784027181e-03 -6.20650797672678e-02 + 2.94862431147953e-03 -5.39399963412825e-02 + 2.14055966565164e-03 -4.58470093224122e-02 + 1.45003537340197e-03 -3.78838208911683e-02 + 9.20097460438803e-04 -3.00188642323400e-02 + 5.13569518013506e-04 -2.22872670431334e-02 + 2.24854144698289e-04 -1.47090799938054e-02 + 7.16420419797124e-05 -7.28122005805669e-03 + 0.00000000000000e+00 0.00000000000000e+00 + 8.30667337145912e-05 7.28493907761252e-03 + 2.40621206193159e-04 1.47085612205429e-02 + 5.29850643501296e-04 2.22690666161207e-02 + 9.37552646642290e-04 2.99680567436069e-02 + 1.46364423687516e-03 3.78031462162717e-02 + 2.13415396408500e-03 4.57718293152885e-02 + 2.98505302314019e-03 5.38762991811228e-02 + 4.08049090961046e-03 6.21031222356185e-02 + 5.32348409326103e-03 7.04621026477038e-02 + 6.68540525770168e-03 7.89717384981979e-02 + 8.16349050305524e-03 8.76289039370964e-02 + 9.84115364385886e-03 9.63974146736541e-02 + 1.17664515759166e-02 1.05263924316241e-01 + 1.40318228128144e-02 1.14211150659918e-01 + 1.64404096111178e-02 1.23297936682812e-01 + 1.90063994463009e-02 1.32535275404535e-01 + 2.17243347773833e-02 1.41923218754833e-01 + 2.47531082013638e-02 1.51382020977074e-01 + 2.79876147869340e-02 1.60929925146753e-01 + 3.16880968401645e-02 1.70478068315566e-01 + 3.55350251674146e-02 1.80153130476464e-01 + 3.96263775536540e-02 1.89947425730580e-01 + 4.39456143792258e-02 1.99882812309296e-01 + 4.85239794021445e-02 2.09908181416265e-01 + 5.34534137951630e-02 2.19944265641675e-01 + 5.87462885442388e-02 2.29964197658055e-01 + 6.44270496014028e-02 2.39969754830107e-01 + 7.04097222861749e-02 2.50025763168648e-01 + 7.66631835969947e-02 2.60165429986364e-01 + 8.32549959691082e-02 2.70336561512274e-01 + 9.01101313435420e-02 2.80563309640775e-01 + 9.74049202740261e-02 2.90697579494236e-01 + 1.05114698051431e-01 3.00743368754403e-01 + 1.13145220439572e-01 3.10785648613665e-01 + 1.21630315794086e-01 3.20725544551961e-01 + 1.30390853479517e-01 3.30702112547975e-01 + 1.39590645856004e-01 3.40558753101048e-01 + 1.49124870362037e-01 3.50362123732590e-01 + 1.59154982855993e-01 3.59921913101712e-01 + 1.69544432069570e-01 3.69399060590938e-01 + 1.80386709779081e-01 3.78695988921857e-01 + 1.91579763428791e-01 3.87884300501059e-01 + 2.03215759235826e-01 3.96833543919666e-01 + 2.15253430564785e-01 4.05547214951462e-01 + 2.27772014189445e-01 4.13882927583771e-01 + 2.40642603224139e-01 4.22086896802528e-01 + 2.53939036577503e-01 4.30033802762336e-01 + 2.67609972467099e-01 4.37691285847929e-01 + 2.81557875539761e-01 4.44965913565754e-01 + 2.95881178190567e-01 4.51813642422346e-01 + 3.10595953223466e-01 4.58226822092898e-01 + 3.25692615194284e-01 4.64358752082265e-01 + 3.41122510103875e-01 4.70166093755745e-01 + 3.56906920161226e-01 4.75457819601108e-01 + 3.73028060365530e-01 4.80296533840550e-01 + 3.89466547847528e-01 4.84640854961732e-01 + 4.06216915276230e-01 4.88245022885247e-01 + 4.23329613709593e-01 4.91316221321931e-01 + 4.40890014276592e-01 4.94066031076244e-01 + 4.58716932230117e-01 4.96120177384477e-01 + 4.76773550105776e-01 4.97493108926328e-01 + 4.95036075072470e-01 4.98220076856676e-01 + 5.13479009238266e-01 4.98328313435672e-01 + 5.32075794301084e-01 4.97686119534454e-01 + 5.50797707737235e-01 4.96272617324986e-01 + 5.69600641150388e-01 4.94015215318247e-01 + 5.88477721457098e-01 4.91029243067188e-01 + 6.07386635657425e-01 4.87295372664773e-01 + 6.26275242831597e-01 4.82792184672487e-01 + 6.45134391494005e-01 4.77579799714536e-01 + 6.63901695169446e-01 4.71560607238906e-01 + 6.82545269979229e-01 4.64770350611842e-01 + 7.01051428389662e-01 4.57262911241947e-01 + 7.19334097084216e-01 4.48930414817246e-01 + 7.37391465413848e-01 4.39841141799307e-01 + 7.55174481191430e-01 4.29986432588973e-01 + 7.72616437803403e-01 4.19381365239015e-01 + 7.89753200934423e-01 4.08201692944460e-01 + 8.06429273866882e-01 3.96269530921693e-01 + 8.22696674409171e-01 3.83630606068877e-01 + 8.38499958578817e-01 3.70228814924312e-01 + 8.53777444028247e-01 3.56113546193772e-01 + 8.68442280245945e-01 3.41287951489090e-01 + 8.82492540270293e-01 3.25786277344664e-01 + 8.95925498965556e-01 3.09679894523524e-01 + 9.08735247378820e-01 2.93027554712345e-01 + 9.20742332422719e-01 2.75162884784513e-01 + 9.32068464518384e-01 2.56731572981429e-01 + 9.42608539274729e-01 2.37762434632290e-01 + 9.52774207875208e-01 2.18302108340019e-01 + 9.62859775973639e-01 1.98379401591706e-01 + 9.70800878118612e-01 1.77985574843893e-01 + 9.77526560026023e-01 1.57228723263127e-01 + 9.83348702581913e-01 1.35262496314977e-01 + 9.88287866680976e-01 1.12048580600310e-01 + 9.92312239757846e-01 8.89420954512888e-02 + 9.95598399807970e-01 6.64089965678724e-02 + 9.97884993829918e-01 4.40785443080142e-02 + 9.99371468236542e-01 2.18636293439463e-02 + 1.00000000000000e+00 -1.46513661216579e-04 diff --git a/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF02_Coords.txt b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF02_Coords.txt new file mode 100644 index 00000000..3d277f48 --- /dev/null +++ b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF02_Coords.txt @@ -0,0 +1,208 @@ + 201 NumCoords ! The number of coordinates in the airfoil shape file (including an extra coordinate for airfoil reference). Set to zero if coordinates not included. +! ......... x-y coordinates are next if NumCoords > 0 ............. +! x-y coordinate of airfoil reference +! x/c y/c + 0.405419 0 +! coordinates of airfoil shape +! interpolation to 200 points +! x/c y/c + 1.00000000000000e+00 -1.94964271094086e-02 + 9.96919760277077e-01 -3.64826077995756e-02 + 9.94667087130123e-01 -5.60719522447348e-02 + 9.94761079761680e-01 -7.41287339133444e-02 + 9.91487644632361e-01 -9.30111065602699e-02 + 9.87177265536021e-01 -1.10830801551200e-01 + 9.81618438289038e-01 -1.25618285586318e-01 + 9.74359531938626e-01 -1.37858592038257e-01 + 9.66196197839873e-01 -1.48011073720888e-01 + 9.57084778530041e-01 -1.57244213613537e-01 + 9.47030628319075e-01 -1.76163809587731e-01 + 9.36255994779871e-01 -1.94451554089259e-01 + 9.24755229326704e-01 -2.12084822033116e-01 + 9.12514414231155e-01 -2.28979937705261e-01 + 8.99641900735580e-01 -2.45152777431143e-01 + 8.86071424135137e-01 -2.60541847813049e-01 + 8.71933069994702e-01 -2.75199084385032e-01 + 8.57249287582935e-01 -2.89132205047948e-01 + 8.42064402212172e-01 -3.02348165923965e-01 + 8.26409062460493e-01 -3.14787448920772e-01 + 8.10288808146397e-01 -3.26359904138149e-01 + 7.93758629967803e-01 -3.37091676397995e-01 + 7.76918356342850e-01 -3.44291222218988e-01 + 7.59756850873003e-01 -3.49997131324565e-01 + 7.42348874985586e-01 -3.55640730349542e-01 + 7.24708863089766e-01 -3.60706166782752e-01 + 7.06860528348044e-01 -3.64855413158321e-01 + 6.88831517526942e-01 -3.68409151382566e-01 + 6.70633473983476e-01 -3.71524443372096e-01 + 6.52350564072767e-01 -3.74401784953206e-01 + 6.33982188894777e-01 -3.77065482741049e-01 + 6.15559054509071e-01 -3.79168407766431e-01 + 5.97101918875316e-01 -3.80350473776001e-01 + 5.78607712056559e-01 -3.80687774167715e-01 + 5.60114269360246e-01 -3.80570858605504e-01 + 5.41594988940669e-01 -3.80067548433720e-01 + 5.24491038376215e-01 -3.79537588218947e-01 + 5.09243386421893e-01 -3.78981564014641e-01 + 4.94142523233296e-01 -3.78083193106923e-01 + 4.79201400260462e-01 -3.76755219694438e-01 + 4.64426672033553e-01 -3.74840429494636e-01 + 4.49830052252528e-01 -3.72341501685922e-01 + 4.35411690443212e-01 -3.69564589340833e-01 + 4.21176828920086e-01 -3.66527761938651e-01 + 4.06104752722998e-01 -3.63217644680091e-01 + 3.91187261313758e-01 -3.59606140139742e-01 + 3.76543272121399e-01 -3.55540172858436e-01 + 3.62174951181275e-01 -3.51199859300841e-01 + 3.48051575371203e-01 -3.46733492501332e-01 + 3.34166838440425e-01 -3.42236418543471e-01 + 3.20531094536529e-01 -3.37752409778483e-01 + 3.07166374335585e-01 -3.33138685551140e-01 + 2.94106366929472e-01 -3.28233453302116e-01 + 2.81356553687748e-01 -3.22927037164433e-01 + 2.68929414080849e-01 -3.17210399237509e-01 + 2.56792257622504e-01 -3.11199667576809e-01 + 2.44988366773819e-01 -3.04908147192347e-01 + 2.33487068586780e-01 -2.98398015474454e-01 + 2.22244174627754e-01 -2.91908544458142e-01 + 2.11259238518723e-01 -2.85624154835144e-01 + 2.00540109534862e-01 -2.79445232131323e-01 + 1.90099108400639e-01 -2.73144271821139e-01 + 1.79974500726159e-01 -2.66577875347765e-01 + 1.69915683501289e-01 -2.59834415460592e-01 + 1.60172080930679e-01 -2.52962962830656e-01 + 1.50692746390245e-01 -2.46077778027207e-01 + 1.41572171628772e-01 -2.39083657564268e-01 + 1.32782528972732e-01 -2.31868964518358e-01 + 1.24316300642292e-01 -2.24479019688654e-01 + 1.16125227242430e-01 -2.17115852851904e-01 + 1.08022185325659e-01 -2.10062937367560e-01 + 1.00068510946488e-01 -2.03253136991591e-01 + 9.24181923986685e-02 -1.96403291468797e-01 + 8.52292314707568e-02 -1.87525621188063e-01 + 7.85442356694309e-02 -1.78452955788562e-01 + 7.21826484759061e-02 -1.69371289606163e-01 + 6.59224769279808e-02 -1.60339488949538e-01 + 5.95888908522178e-02 -1.51375335195636e-01 + 5.34570839330547e-02 -1.42381729136260e-01 + 4.78323253460157e-02 -1.33307333331388e-01 + 4.27773110897719e-02 -1.24183705410093e-01 + 3.81406060607182e-02 -1.14969947782298e-01 + 3.34394858942616e-02 -1.07833476412008e-01 + 2.85905771976062e-02 -1.02443290523446e-01 + 2.39758840800528e-02 -9.70665624082339e-02 + 2.00924464828600e-02 -9.14418911635026e-02 + 1.67774266077405e-02 -8.55577600333846e-02 + 1.37085226488790e-02 -7.95717583471716e-02 + 1.06047400652709e-02 -7.35922291670351e-02 + 7.90398428387208e-03 -6.75352052422909e-02 + 6.19892209075347e-03 -6.13137254015921e-02 + 4.74163822479280e-03 -5.48650139398457e-02 + 3.46348797721600e-03 -4.81553931473352e-02 + 2.35439809271567e-03 -4.11318098186878e-02 + 1.48284350464362e-03 -3.41609786643930e-02 + 9.33668904559450e-04 -2.70825630260840e-02 + 5.16784288069033e-04 -2.00607976197347e-02 + 2.03224808289276e-04 -1.32008980839843e-02 + 2.88583219323030e-05 -6.51695336105137e-03 + 0.00000000000000e+00 0.00000000000000e+00 + 1.06034557788935e-04 6.54242344402049e-03 + 3.10442109886626e-04 1.32200621240131e-02 + 6.27358526355077e-04 2.00270586046359e-02 + 1.04642059582819e-03 2.69584070704927e-02 + 1.56119077029123e-03 3.40044020355773e-02 + 2.20965204677518e-03 4.11549554928511e-02 + 3.41098060660727e-03 4.84144618046186e-02 + 5.03360788709283e-03 5.57589214681263e-02 + 6.61245394229265e-03 6.32348735880216e-02 + 8.28994979066480e-03 7.08911179309667e-02 + 9.96034393771960e-03 7.87021820009504e-02 + 1.17636547160994e-02 8.65345063094756e-02 + 1.43612220190213e-02 9.42922806414463e-02 + 1.76430317064128e-02 1.02026805686471e-01 + 2.08737235707927e-02 1.09949354414078e-01 + 2.39097774660482e-02 1.18163715137690e-01 + 2.68277855724522e-02 1.26610148817642e-01 + 3.00184157320084e-02 1.35071752122783e-01 + 3.38529447168762e-02 1.43382634408088e-01 + 3.85374178015213e-02 1.51512804458775e-01 + 4.35193302635381e-02 1.59709865654183e-01 + 4.83524785822808e-02 1.68285035077358e-01 + 5.28925514814938e-02 1.77785241588636e-01 + 5.74509623742945e-02 1.87519752029641e-01 + 6.25207280441538e-02 1.96995257755178e-01 + 6.84864459272233e-02 2.05895125589205e-01 + 7.51749747555155e-02 2.14483369522917e-01 + 8.21424789239981e-02 2.23186204375288e-01 + 8.89480736036874e-02 2.32391482476344e-01 + 9.57168879662020e-02 2.41977056322773e-01 + 1.02682866347355e-01 2.51651269226778e-01 + 1.10220820704945e-01 2.61011250036727e-01 + 1.18407958380338e-01 2.69947451121491e-01 + 1.26881602570982e-01 2.78784626441245e-01 + 1.35660947758076e-01 2.87754998986677e-01 + 1.44539262453658e-01 2.97066755412224e-01 + 1.53710627262191e-01 3.06476813639894e-01 + 1.63224044690801e-01 3.15759213512801e-01 + 1.73217608842146e-01 3.24616725514123e-01 + 1.83592362834056e-01 3.33425258716891e-01 + 1.94325962262670e-01 3.42337881360872e-01 + 2.05324011045863e-01 3.51288753587316e-01 + 2.16730097076787e-01 3.60001663577674e-01 + 2.28586578632938e-01 3.68187843125944e-01 + 2.40883113525511e-01 3.75812546015869e-01 + 2.53496856322201e-01 3.83600826529355e-01 + 2.66426205569999e-01 3.91650072271809e-01 + 2.79648785252606e-01 3.99396772979447e-01 + 2.92654108132638e-01 4.06655149783746e-01 + 3.05982927892807e-01 4.13055764549372e-01 + 3.19616352211114e-01 4.19007565475870e-01 + 3.33559027388770e-01 4.25557700509835e-01 + 3.47790649521039e-01 4.31983019768178e-01 + 3.62286841731615e-01 4.37810261240227e-01 + 3.77034995262049e-01 4.43528144955168e-01 + 3.92039353236568e-01 4.48820541528545e-01 + 4.07301441870269e-01 4.52540541894158e-01 + 4.23279474819674e-01 4.55820048720622e-01 + 4.40634468309514e-01 4.59564402113604e-01 + 4.58216729640812e-01 4.62715547857050e-01 + 4.76002112543622e-01 4.64915551067932e-01 + 4.93972301744354e-01 4.66495076484244e-01 + 5.12102601808104e-01 4.67675381916421e-01 + 5.30374260454303e-01 4.67718175971608e-01 + 5.48760443148615e-01 4.66664714353419e-01 + 5.67217438731546e-01 4.64745135086648e-01 + 5.85739737161608e-01 4.61729462619936e-01 + 6.04297036727046e-01 4.57963754355715e-01 + 6.22849821404431e-01 4.53804771006538e-01 + 6.41387754588488e-01 4.49034662925732e-01 + 6.59860243895401e-01 4.43612634661173e-01 + 6.78243902722125e-01 4.37681519215445e-01 + 6.96525620003880e-01 4.31223433182484e-01 + 7.14630615751572e-01 4.24172943475969e-01 + 7.32553281453510e-01 4.16497772874745e-01 + 7.50252988657587e-01 4.08237425290133e-01 + 7.67683365695193e-01 3.99660004830094e-01 + 7.84884705771043e-01 3.91177827246511e-01 + 8.01707686882478e-01 3.82511987837697e-01 + 8.18171045140217e-01 3.73184018737277e-01 + 8.34218184325793e-01 3.62939454140551e-01 + 8.49803537682218e-01 3.52119100925938e-01 + 8.64853102337230e-01 3.40870213182952e-01 + 8.79352542615986e-01 3.29069212973395e-01 + 8.93288312520579e-01 3.16847374518213e-01 + 9.06641281797077e-01 3.04310322344821e-01 + 9.19235341950085e-01 2.88747970901776e-01 + 9.31163314413939e-01 2.72527797669352e-01 + 9.42304292794809e-01 2.55835364954767e-01 + 9.55213979558356e-01 2.38692901385650e-01 + 9.72177046241266e-01 2.21180379624901e-01 + 9.80174206699236e-01 2.02148008484942e-01 + 9.84417859316093e-01 1.80623200933622e-01 + 9.87730786501502e-01 1.53965422157644e-01 + 9.90607437911417e-01 1.22548669883815e-01 + 9.92941558866010e-01 9.10997252988497e-02 + 9.95524996439665e-01 6.60081316645982e-02 + 9.96925214206640e-01 4.30168042831882e-02 + 9.98589083226293e-01 2.09101531114029e-02 + 1.00000000000000e+00 -1.10918874127508e-04 diff --git a/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF03_Coords.txt b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF03_Coords.txt new file mode 100644 index 00000000..3574f261 --- /dev/null +++ b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF03_Coords.txt @@ -0,0 +1,208 @@ + 201 NumCoords ! The number of coordinates in the airfoil shape file (including an extra coordinate for airfoil reference). Set to zero if coordinates not included. +! ......... x-y coordinates are next if NumCoords > 0 ............. +! x-y coordinate of airfoil reference +! x/c y/c + 0.300072 0 +! coordinates of airfoil shape +! interpolation to 200 points +! x/c y/c + 1.00000000000000e+00 -2.35717905236513e-02 + 9.95894264742224e-01 -3.92526822859504e-02 + 9.92356907783760e-01 -5.58972397758731e-02 + 9.91832649399724e-01 -7.22796935620756e-02 + 9.89065767280758e-01 -8.98751886421859e-02 + 9.85303518885023e-01 -1.06063296906901e-01 + 9.79227294864432e-01 -1.18115211299191e-01 + 9.68317731645526e-01 -1.26727180688080e-01 + 9.56870605029902e-01 -1.32551970200501e-01 + 9.44399782765251e-01 -1.37235805042327e-01 + 9.31376191661979e-01 -1.49921669278151e-01 + 9.18131472990873e-01 -1.62163429513691e-01 + 9.04532462534647e-01 -1.73794296481196e-01 + 8.90513850343901e-01 -1.84548505419301e-01 + 8.76094083221940e-01 -1.94369351614981e-01 + 8.61295443643247e-01 -2.03387259424766e-01 + 8.46228194041534e-01 -2.11697233177751e-01 + 8.30943028446170e-01 -2.19423235960492e-01 + 8.15464579238373e-01 -2.26583810092412e-01 + 7.99805091304501e-01 -2.33034629864386e-01 + 7.83949186991882e-01 -2.38634111936675e-01 + 7.67924901075415e-01 -2.43491491542901e-01 + 7.51827610435101e-01 -2.46922502098554e-01 + 7.35700766231654e-01 -2.49967384402370e-01 + 7.19557581083962e-01 -2.53049973028183e-01 + 7.03374920806515e-01 -2.55675693783315e-01 + 6.87141084317211e-01 -2.57511647636345e-01 + 6.70872708173025e-01 -2.58916159150435e-01 + 6.54584120557027e-01 -2.60070409267096e-01 + 6.38316166451763e-01 -2.61147805145693e-01 + 6.22053812145135e-01 -2.62242468065543e-01 + 6.05795467035195e-01 -2.62984971699304e-01 + 5.89535785963171e-01 -2.62980782780771e-01 + 5.73249959911008e-01 -2.62338277960480e-01 + 5.56924435273058e-01 -2.61412073870956e-01 + 5.40499557828918e-01 -2.60380178738677e-01 + 5.25124338707629e-01 -2.59541047800324e-01 + 5.11278184667223e-01 -2.58859241415762e-01 + 4.97568404605392e-01 -2.58048556490882e-01 + 4.84002314517955e-01 -2.56975419244797e-01 + 4.70578871550198e-01 -2.55452441773426e-01 + 4.57299606722912e-01 -2.53575365177959e-01 + 4.44165059993117e-01 -2.51608626178359e-01 + 4.31171120115011e-01 -2.49565341878899e-01 + 4.17960046660827e-01 -2.47435089625259e-01 + 4.04894573177154e-01 -2.45125131039407e-01 + 3.92025010140446e-01 -2.42462612691433e-01 + 3.79343869682045e-01 -2.39595692647852e-01 + 3.66822492601097e-01 -2.36738334901165e-01 + 3.54437597401984e-01 -2.34084096374542e-01 + 3.42188016976202e-01 -2.31663337492797e-01 + 3.30106565812339e-01 -2.29245864019644e-01 + 3.18228608318416e-01 -2.26607512965020e-01 + 3.06561819529862e-01 -2.23599397180190e-01 + 2.95096087112862e-01 -2.20264450363764e-01 + 2.83822976873035e-01 -2.16705858133672e-01 + 2.72749367112427e-01 -2.12987917599575e-01 + 2.61871015332779e-01 -2.09105223071590e-01 + 2.51166620646972e-01 -2.05257087666955e-01 + 2.40624400846784e-01 -2.01625484971293e-01 + 2.30238432660905e-01 -1.98140713780569e-01 + 2.20026112530791e-01 -1.94584499409339e-01 + 2.09976055390476e-01 -1.90827834894363e-01 + 1.99702136630218e-01 -1.86888650453711e-01 + 1.89635587559752e-01 -1.82831573590219e-01 + 1.79772976644460e-01 -1.78716242047549e-01 + 1.70166626869497e-01 -1.74489311956110e-01 + 1.60857736786573e-01 -1.70006317401921e-01 + 1.51803109355095e-01 -1.65351581130296e-01 + 1.42904673719036e-01 -1.60741881001108e-01 + 1.34016689385335e-01 -1.56400925252111e-01 + 1.25172927433342e-01 -1.52235477594800e-01 + 1.16585145327233e-01 -1.47936269496174e-01 + 1.08455437817872e-01 -1.42606858442656e-01 + 1.00797932241528e-01 -1.36869866343013e-01 + 9.34220406155034e-02 -1.30998286551843e-01 + 8.60634069002927e-02 -1.25203141666258e-01 + 7.85543380199848e-02 -1.19513567026171e-01 + 7.12090438710948e-02 -1.13679449812632e-01 + 6.43781714721257e-02 -1.07497988597386e-01 + 5.81748969271094e-02 -1.00901485941624e-01 + 5.23111625072034e-02 -9.40070595698379e-02 + 4.63848694510659e-02 -8.87274392056592e-02 + 4.02274234777820e-02 -8.49827667220595e-02 + 3.43402499368400e-02 -8.12041215315654e-02 + 2.92122911092120e-02 -7.70335607862094e-02 + 2.46619896023326e-02 -7.24469162604508e-02 + 2.03998728457045e-02 -6.76744757448659e-02 + 1.62083083553108e-02 -6.28569220857654e-02 + 1.24122747710821e-02 -5.78802307117992e-02 + 9.59261999542548e-03 -5.26178555647791e-02 + 7.30477546051285e-03 -4.69809514049654e-02 + 5.24424677887566e-03 -4.11640833368231e-02 + 3.22154066429621e-03 -3.53189852766165e-02 + 1.65180206365193e-03 -2.94779767104117e-02 + 1.00171614777338e-03 -2.35012775997985e-02 + 5.33709082287082e-04 -1.74789869612144e-02 + 1.93102071972421e-04 -1.15157513977575e-02 + 8.83513173800652e-06 -5.67716919165800e-03 + 0.00000000000000e+00 0.00000000000000e+00 + 1.16783719135356e-04 5.69723987547027e-03 + 3.43118960628982e-04 1.15219848562656e-02 + 6.72993148161244e-04 1.74602777849096e-02 + 1.09737183733306e-03 2.34963725200926e-02 + 1.60684348093023e-03 2.96112825450017e-02 + 2.45643493250886e-03 3.57965862211899e-02 + 3.99538452491140e-03 4.20591838228941e-02 + 5.93173609093872e-03 4.83922212075131e-02 + 7.78831860532396e-03 5.48405525131736e-02 + 9.77944638510934e-03 6.14059674486418e-02 + 1.18236157695499e-02 6.80196332226401e-02 + 1.41090606785859e-02 7.45698337168348e-02 + 1.73056541184598e-02 8.10186811443194e-02 + 2.11847229777394e-02 8.74687230723911e-02 + 2.49676864074981e-02 9.40869839667322e-02 + 2.84682042956027e-02 1.00930111245539e-01 + 3.18331846418495e-02 1.07898963211733e-01 + 3.54793253397875e-02 1.14828880543840e-01 + 3.98821847361107e-02 1.21582993745491e-01 + 4.51314595122883e-02 1.28212190706429e-01 + 5.07378731779770e-02 1.34892120261391e-01 + 5.60731260647946e-02 1.41960877640708e-01 + 6.09722950181842e-02 1.50342170540091e-01 + 6.58438293017437e-02 1.58942245558348e-01 + 7.12537393230430e-02 1.67161944148746e-01 + 7.76600623439659e-02 1.74624850622013e-01 + 8.48496220471092e-02 1.81687450473830e-01 + 9.23057704681641e-02 1.88867715176475e-01 + 9.94459240673263e-02 1.96648864845365e-01 + 1.06388932256554e-01 2.04900423667625e-01 + 1.13500915840888e-01 2.13208533649742e-01 + 1.21190173762834e-01 2.21120456132424e-01 + 1.29552662653441e-01 2.28502274929156e-01 + 1.38071878683882e-01 2.35719905821540e-01 + 1.46821747467612e-01 2.43114116431733e-01 + 1.55674346023180e-01 2.50880294859766e-01 + 1.64742508530083e-01 2.58798876919177e-01 + 1.74100620712751e-01 2.66555316753591e-01 + 1.83827637281412e-01 2.73887896215538e-01 + 1.93900930930976e-01 2.81137679364482e-01 + 2.04279807701489e-01 2.88489630315669e-01 + 2.14917904141514e-01 2.95836142276111e-01 + 2.25877633648094e-01 3.02970528418131e-01 + 2.37175240693611e-01 3.09614749723245e-01 + 2.48781997761441e-01 3.15783316315385e-01 + 2.60667851543173e-01 3.22097199193517e-01 + 2.72834283839390e-01 3.28652682218705e-01 + 2.85283064783479e-01 3.34865419367518e-01 + 2.97847251117894e-01 3.40624356479022e-01 + 3.10710643373344e-01 3.45634518095723e-01 + 3.23837985214461e-01 3.50222642863971e-01 + 3.37240583535417e-01 3.55267130987121e-01 + 3.50911402546816e-01 3.60167827153803e-01 + 3.64804696483725e-01 3.64587389850643e-01 + 3.78910279118625e-01 3.69073483105304e-01 + 3.93243450766671e-01 3.73200860402215e-01 + 4.07809010689417e-01 3.75729715812861e-01 + 4.23000375070936e-01 3.77751754255469e-01 + 4.39328786730662e-01 3.80141190316103e-01 + 4.55813610039226e-01 3.82101412277872e-01 + 4.72460251929427e-01 3.83235896264865e-01 + 4.89254536599454e-01 3.83843952964464e-01 + 5.06163834453059e-01 3.84146352307061e-01 + 5.23189394372787e-01 3.83285841342889e-01 + 5.40310058634680e-01 3.81443701603978e-01 + 5.57486522435475e-01 3.79033596004446e-01 + 5.74715352025665e-01 3.75685474236072e-01 + 5.92000372484674e-01 3.71765261705014e-01 + 6.09337554036771e-01 3.67670925407177e-01 + 6.26712711199081e-01 3.63152537787024e-01 + 6.44112689354547e-01 3.58249400169114e-01 + 6.61537902878510e-01 3.53105856660785e-01 + 6.78976015503225e-01 3.47670000178051e-01 + 6.96388219208155e-01 3.41916005228908e-01 + 7.13758174635815e-01 3.35774011869113e-01 + 7.31072071555730e-01 3.29291743909179e-01 + 7.48347054469357e-01 3.22782481179152e-01 + 7.65635234168385e-01 3.16597107059741e-01 + 7.82817938077837e-01 3.10445909406222e-01 + 7.99822649562144e-01 3.03782942002751e-01 + 8.16599499725996e-01 2.96387728717845e-01 + 8.33162654038272e-01 2.88615543528075e-01 + 8.49499238755804e-01 2.80681153424459e-01 + 8.65575980032653e-01 2.72460131547320e-01 + 8.81365101325771e-01 2.64006588773166e-01 + 8.96830625839868e-01 2.55349206752237e-01 + 9.11860293545010e-01 2.45521741551255e-01 + 9.26493285460369e-01 2.35422284498711e-01 + 9.40627758148684e-01 2.25124409413752e-01 + 9.56355816041677e-01 2.14591442921710e-01 + 9.76537617843118e-01 2.04082237971755e-01 + 9.84561014127750e-01 1.89606914519805e-01 + 9.87643053296840e-01 1.67544521992612e-01 + 9.89781643689051e-01 1.41487907300533e-01 + 9.91693019433194e-01 1.13998602352113e-01 + 9.93236086227859e-01 8.40282639292492e-02 + 9.95181038506289e-01 6.17158184066358e-02 + 9.96476028162972e-01 4.13392188133469e-02 + 9.98222919558243e-01 2.12790182529935e-02 + 1.00000000000000e+00 1.60547379486788e-03 diff --git a/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF04_Coords.txt b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF04_Coords.txt new file mode 100644 index 00000000..7c0a13b7 --- /dev/null +++ b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF04_Coords.txt @@ -0,0 +1,208 @@ + 201 NumCoords ! The number of coordinates in the airfoil shape file (including an extra coordinate for airfoil reference). Set to zero if coordinates not included. +! ......... x-y coordinates are next if NumCoords > 0 ............. +! x-y coordinate of airfoil reference +! x/c y/c + 0.250000 0 +! coordinates of airfoil shape +! interpolation to 200 points +! x/c y/c + 1.00000000000000e+00 -2.27521504445117e-02 + 9.95825558916260e-01 -3.85996552852628e-02 + 9.91908351102147e-01 -5.44969196641126e-02 + 9.88416628115054e-01 -7.07599158572808e-02 + 9.85866922904108e-01 -8.82610141031158e-02 + 9.82725730996461e-01 -1.04331474026742e-01 + 9.75943584414250e-01 -1.16192160119479e-01 + 9.60562898886437e-01 -1.24553806205324e-01 + 9.45502094163868e-01 -1.30081821439202e-01 + 9.29689968161834e-01 -1.34454116305964e-01 + 9.13964300425632e-01 -1.38792987259912e-01 + 8.98614488822684e-01 -1.43791084896220e-01 + 8.83335037065323e-01 -1.48845719057247e-01 + 8.67989583131007e-01 -1.53392395893884e-01 + 8.52512977524852e-01 -1.57285196860484e-01 + 8.36980556973450e-01 -1.60814946557067e-01 + 8.21468173261859e-01 -1.64100703909415e-01 + 8.06005351604761e-01 -1.67267075710542e-01 + 7.90569523846495e-01 -1.70238657955313e-01 + 7.75160420278176e-01 -1.72833393586880e-01 + 7.59765591487754e-01 -1.74956177670212e-01 + 7.44400605416898e-01 -1.76801895913143e-01 + 7.29116033776629e-01 -1.78610693133524e-01 + 7.13947989837457e-01 -1.80610582068115e-01 + 6.98879169529179e-01 -1.82683486229382e-01 + 6.83885725014230e-01 -1.84453890742002e-01 + 6.68948266000129e-01 -1.85692240974458e-01 + 6.54077597403275e-01 -1.86675765092582e-01 + 6.39298560836104e-01 -1.87505908577295e-01 + 6.24631617962163e-01 -1.88281679546669e-01 + 6.10073346044509e-01 -1.89102453976540e-01 + 5.95625793495472e-01 -1.89726467074718e-01 + 5.81293508075112e-01 -1.89890541527727e-01 + 5.67078321487802e-01 -1.89672724652735e-01 + 5.52984605219614e-01 -1.89300253242408e-01 + 5.39018740189456e-01 -1.88942147239663e-01 + 5.25163688284825e-01 -1.88679571252767e-01 + 5.11413609207518e-01 -1.88425702489593e-01 + 4.97799177395975e-01 -1.88101973722528e-01 + 4.84327325660904e-01 -1.87580974813977e-01 + 4.70996488304439e-01 -1.86734079403737e-01 + 4.57807499457728e-01 -1.85719999075378e-01 + 4.44760927152842e-01 -1.84696486770858e-01 + 4.31852022455883e-01 -1.83635353168758e-01 + 4.19090901616490e-01 -1.82470445502636e-01 + 4.06491363898788e-01 -1.81170983464115e-01 + 3.94068316367388e-01 -1.79605967544454e-01 + 3.81813043724431e-01 -1.77780857103527e-01 + 3.69699449630328e-01 -1.75956382315867e-01 + 3.57702913407548e-01 -1.74362578401297e-01 + 3.45820758127239e-01 -1.72975266565004e-01 + 3.34085173594801e-01 -1.71599837205798e-01 + 3.22528762317999e-01 -1.70053358838540e-01 + 3.11158458585437e-01 -1.68229483638464e-01 + 2.99960205902575e-01 -1.66205813724721e-01 + 2.88929664556996e-01 -1.64083038925404e-01 + 2.78065429500551e-01 -1.61919157747390e-01 + 2.67372016639914e-01 -1.59640340608867e-01 + 2.56838483482072e-01 -1.57303663087410e-01 + 2.46452895340118e-01 -1.54979944998565e-01 + 2.36204329661831e-01 -1.52707294515853e-01 + 2.26105799104062e-01 -1.50433273332383e-01 + 2.16178334826531e-01 -1.48092285325409e-01 + 2.06440462240654e-01 -1.45637282290730e-01 + 1.96869285515018e-01 -1.43086175320475e-01 + 1.87473435872977e-01 -1.40444127091679e-01 + 1.78262653731453e-01 -1.37710428849814e-01 + 1.69252630220208e-01 -1.34804420084564e-01 + 1.60413244437104e-01 -1.31813387053438e-01 + 1.51703588066681e-01 -1.28882641840022e-01 + 1.43077619868567e-01 -1.26142317505189e-01 + 1.34558223959049e-01 -1.23515015039303e-01 + 1.26236077097364e-01 -1.20786093116937e-01 + 1.18187874855922e-01 -1.17753964310198e-01 + 1.10394900564033e-01 -1.14389083257162e-01 + 1.02776771116232e-01 -1.10926463752281e-01 + 9.52576323187684e-02 -1.07596450900910e-01 + 8.77890248291223e-02 -1.04462641719461e-01 + 8.04931796353551e-02 -1.01301294317992e-01 + 7.35128190911369e-02 -9.78736275580912e-02 + 6.68963895240495e-02 -9.40003856565595e-02 + 6.05009896751561e-02 -8.99475473560910e-02 + 5.41691079982236e-02 -8.60337352895419e-02 + 4.77847233189376e-02 -8.24016920600191e-02 + 4.16000737650022e-02 -7.87323954691971e-02 + 3.58929498807395e-02 -7.46615383996122e-02 + 3.05718156448606e-02 -7.01640817880520e-02 + 2.55841457444921e-02 -6.54750339821926e-02 + 2.08026533112682e-02 -6.07371500023589e-02 + 1.63439586202605e-02 -5.58344930848473e-02 + 1.26739780200523e-02 -5.06379447657982e-02 + 9.64255085974439e-03 -4.50568616338899e-02 + 6.95205676239145e-03 -3.93718854579150e-02 + 4.20584482318000e-03 -3.38153278580581e-02 + 1.88154483510298e-03 -2.82556740113477e-02 + 1.09259224757715e-03 -2.25793808835637e-02 + 5.57027370894427e-04 -1.68301482885243e-02 + 1.92532044605606e-04 -1.11001611628179e-02 + 7.52083255272135e-06 -5.47188430262417e-03 + 0.00000000000000e+00 0.00000000000000e+00 + 1.17486562914811e-04 5.48679985210707e-03 + 3.45293358213107e-04 1.10987098718478e-02 + 6.76028572561267e-04 1.68193159983466e-02 + 1.10074682910982e-03 2.26297904761801e-02 + 1.60992601121548e-03 2.85087154571350e-02 + 2.67599544106549e-03 3.44493853796572e-02 + 4.39289337028668e-03 4.04593247588465e-02 + 6.27509694854768e-03 4.65396355123101e-02 + 8.18501856800657e-03 5.27292560994769e-02 + 1.03189035753580e-02 5.90079710526583e-02 + 1.27370291299606e-02 6.52938850681379e-02 + 1.55557604269686e-02 7.14974882867604e-02 + 1.89758697009180e-02 7.76144942393735e-02 + 2.27125265955629e-02 8.37568225375172e-02 + 2.64205973892604e-02 9.00529677985623e-02 + 3.01282733583995e-02 9.65285394067050e-02 + 3.39926189539913e-02 1.03078210289796e-01 + 3.81573198488582e-02 1.09576659446866e-01 + 4.27861195062449e-02 1.15924379625249e-01 + 4.78311663375292e-02 1.22194138387785e-01 + 5.30764574325103e-02 1.28517196960692e-01 + 5.83111363244493e-02 1.35033938551462e-01 + 6.35760553124462e-02 1.41734309721268e-01 + 6.90274085645503e-02 1.48474163992816e-01 + 7.48336167040122e-02 1.55069663963807e-01 + 8.11611766171277e-02 1.61401120064374e-01 + 8.79191588167710e-02 1.67593332097610e-01 + 9.48826093561019e-02 1.73826214118695e-01 + 1.01844855099363e-01 1.80284855885651e-01 + 1.08870960569728e-01 1.86945163887416e-01 + 1.16112032555569e-01 1.93604681567356e-01 + 1.23730351466839e-01 2.00035948444507e-01 + 1.31824094660795e-01 2.06181698317671e-01 + 1.40296730825128e-01 2.12179485190627e-01 + 1.48993250461499e-01 2.18163657713048e-01 + 1.57819272344995e-01 2.24246096031123e-01 + 1.66852794875010e-01 2.30358166418523e-01 + 1.76155620082319e-01 2.36368608053698e-01 + 1.85787867463952e-01 2.42168413364266e-01 + 1.95750148009566e-01 2.47820613232954e-01 + 2.06011532032752e-01 2.53317180198825e-01 + 2.16542581694721e-01 2.58641479671493e-01 + 2.27367855996913e-01 2.63825228256786e-01 + 2.38481776223131e-01 2.68855474330982e-01 + 2.49861589948929e-01 2.73698630151439e-01 + 2.61511196031386e-01 2.78418546610769e-01 + 2.73444081521194e-01 2.82942196705218e-01 + 2.85666898746156e-01 2.87119018069479e-01 + 2.98200734062047e-01 2.91001132958173e-01 + 3.11032065305424e-01 2.94621877568295e-01 + 3.24124539258925e-01 2.97872294592512e-01 + 3.37489921714358e-01 3.00767227942365e-01 + 3.51122091139916e-01 3.03395484009736e-01 + 3.64973840498426e-01 3.05782280483364e-01 + 3.79035138325125e-01 3.08249753379266e-01 + 3.93322041497236e-01 3.10433221242496e-01 + 4.07839547608925e-01 3.11538517913751e-01 + 4.22602719706730e-01 3.12017813468019e-01 + 4.37571388858179e-01 3.12308843703191e-01 + 4.52705694129202e-01 3.12333639153740e-01 + 4.68022386434649e-01 3.11853160827979e-01 + 4.83493649847560e-01 3.10957551960417e-01 + 4.99066517917555e-01 3.09764580509872e-01 + 5.14753065556197e-01 3.07600736594501e-01 + 5.30536608928272e-01 3.04749547523736e-01 + 5.46385724990049e-01 3.01659366948820e-01 + 5.62295818718890e-01 2.97977515095747e-01 + 5.78294553201899e-01 2.93910589456047e-01 + 5.94402144736603e-01 2.89716319978192e-01 + 6.10601043028817e-01 2.85246570693586e-01 + 6.26909980423233e-01 2.80596756484263e-01 + 6.43345516347184e-01 2.75862073462143e-01 + 6.59894609560225e-01 2.70990265506853e-01 + 6.76549242992279e-01 2.65977472599385e-01 + 6.93285667658481e-01 2.60762532727095e-01 + 7.10113002149428e-01 2.55379870427853e-01 + 7.27101101620968e-01 2.50077155704390e-01 + 7.44309174064674e-01 2.45048240418275e-01 + 7.61658961677203e-01 2.40058424294836e-01 + 7.79018980351826e-01 2.34727092866611e-01 + 7.96358584077290e-01 2.28942034208237e-01 + 8.13753854561790e-01 2.22958342564097e-01 + 8.31270319341910e-01 2.17014377218330e-01 + 8.48885104644356e-01 2.11048726086036e-01 + 8.66584330124259e-01 2.05031932644156e-01 + 8.84350172928721e-01 1.98925268297828e-01 + 9.02193707353903e-01 1.92773917580206e-01 + 9.20157773678337e-01 1.86723259912781e-01 + 9.38246381637406e-01 1.80792430732304e-01 + 9.56399217082597e-01 1.74918496768106e-01 + 9.76798363881330e-01 1.69533670492790e-01 + 9.84828566855567e-01 1.59247090588959e-01 + 9.87839059292136e-01 1.39199540261784e-01 + 9.89905373069722e-01 1.17616603808733e-01 + 9.91757893422502e-01 9.85412138534034e-02 + 9.93252480473954e-01 7.94410871228046e-02 + 9.94743975611726e-01 6.01627278016894e-02 + 9.96445705560557e-01 4.08626126297221e-02 + 9.98198658774545e-01 2.15548416438615e-02 + 1.00000000000000e+00 2.24462872737125e-03 diff --git a/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF05_Coords.txt b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF05_Coords.txt new file mode 100644 index 00000000..e390be98 --- /dev/null +++ b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF05_Coords.txt @@ -0,0 +1,208 @@ + 201 NumCoords ! The number of coordinates in the airfoil shape file (including an extra coordinate for airfoil reference). Set to zero if coordinates not included. +! ......... x-y coordinates are next if NumCoords > 0 ............. +! x-y coordinate of airfoil reference +! x/c y/c + 0.250000 0 +! coordinates of airfoil shape +! interpolation to 200 points +! x/c y/c + 1.00000000000000e+00 -1.79613835013314e-02 + 9.96961558343373e-01 -3.53902489488287e-02 + 9.92023630619313e-01 -4.91929101534255e-02 + 9.84379446083511e-01 -6.00348210114478e-02 + 9.75468141678190e-01 -7.09859658723328e-02 + 9.66631278884337e-01 -8.10763642717688e-02 + 9.55798039282918e-01 -8.89193213483636e-02 + 9.40573198850503e-01 -9.51466796435252e-02 + 9.25558881802059e-01 -9.98612000663832e-02 + 9.10156047961303e-01 -1.03818167988873e-01 + 8.94845249828711e-01 -1.07053770498790e-01 + 8.79788764043181e-01 -1.10793970812780e-01 + 8.64816289515449e-01 -1.14657288651007e-01 + 8.49854909867423e-01 -1.18332319693786e-01 + 8.34868122131193e-01 -1.21755694040649e-01 + 8.19932031659274e-01 -1.25185347068945e-01 + 8.05100969303777e-01 -1.28769954116135e-01 + 7.90321333537330e-01 -1.32315399189505e-01 + 7.75523132904363e-01 -1.35552178535652e-01 + 7.60741767498039e-01 -1.38522987025004e-01 + 7.46023130239504e-01 -1.41378450540013e-01 + 7.31401419294347e-01 -1.44351973608261e-01 + 7.16841539978852e-01 -1.47259170049408e-01 + 7.02302981796658e-01 -1.49894404232336e-01 + 6.87793305289350e-01 -1.52332219473336e-01 + 6.73332858807799e-01 -1.54446440090132e-01 + 6.58925185976507e-01 -1.56177321792256e-01 + 6.44572195057741e-01 -1.57666344545681e-01 + 6.30298458454963e-01 -1.58910640661020e-01 + 6.16114416580374e-01 -1.59951057500702e-01 + 6.02026953030919e-01 -1.60900948878695e-01 + 5.88050398086629e-01 -1.61711857451049e-01 + 5.74189109055960e-01 -1.62294350346538e-01 + 5.60448390812326e-01 -1.62664500132555e-01 + 5.46836999554392e-01 -1.62937231340188e-01 + 5.33367864981090e-01 -1.63248884154172e-01 + 5.19932409233419e-01 -1.63449902911388e-01 + 5.06477442605548e-01 -1.63417485627504e-01 + 4.93144035884787e-01 -1.63328228686621e-01 + 4.79941368474168e-01 -1.63060331436217e-01 + 4.66871737010151e-01 -1.62569827406711e-01 + 4.53934990999079e-01 -1.62070487200764e-01 + 4.41133168558923e-01 -1.61632173585030e-01 + 4.28463654391992e-01 -1.61187532275481e-01 + 4.15933178526276e-01 -1.60548880877149e-01 + 4.03555052687744e-01 -1.59798188531010e-01 + 3.91342756149186e-01 -1.58846604242981e-01 + 3.79289683322135e-01 -1.57540790079054e-01 + 3.67375264219574e-01 -1.56189884356924e-01 + 3.55580233434555e-01 -1.55081224503574e-01 + 3.43903993529589e-01 -1.54105712386970e-01 + 3.32371689603571e-01 -1.53109720354745e-01 + 3.21008399939002e-01 -1.51964778739524e-01 + 3.09818365007830e-01 -1.50611104402699e-01 + 2.98789403182843e-01 -1.49154888767305e-01 + 2.87915260467706e-01 -1.47707797499490e-01 + 2.77192797094198e-01 -1.46295028972452e-01 + 2.66634642137323e-01 -1.44782680901920e-01 + 2.56243230473741e-01 -1.43092118304113e-01 + 2.46011513861498e-01 -1.41179312266907e-01 + 2.35923227561334e-01 -1.39187527359477e-01 + 2.25978716650481e-01 -1.37235092846332e-01 + 2.16205677937271e-01 -1.35310903535781e-01 + 2.06778722942050e-01 -1.33322871209808e-01 + 1.97516042359716e-01 -1.31227497717662e-01 + 1.88427440008692e-01 -1.28991125900883e-01 + 1.79502980110518e-01 -1.26649399614310e-01 + 1.70733325816940e-01 -1.24213566866553e-01 + 1.62098170428490e-01 -1.21762260683871e-01 + 1.53596861253099e-01 -1.19338023194216e-01 + 1.45242024458811e-01 -1.16964714586022e-01 + 1.37059827832412e-01 -1.14553161865558e-01 + 1.29058111671005e-01 -1.12011104818429e-01 + 1.21217330976586e-01 -1.09333580954571e-01 + 1.13490793020045e-01 -1.06582482287198e-01 + 1.05872478787586e-01 -1.03835726838741e-01 + 9.84312049808396e-02 -1.01090373016527e-01 + 9.12178971287871e-02 -9.82756005290104e-02 + 8.42187577306301e-02 -9.53136441369315e-02 + 7.73955759457572e-02 -9.22209615041234e-02 + 7.07054294736601e-02 -8.89789985808886e-02 + 6.41548755011769e-02 -8.56689842703127e-02 + 5.77914057011829e-02 -8.22370633159429e-02 + 5.16081911372133e-02 -7.87250303745277e-02 + 4.56080027670407e-02 -7.51373524837015e-02 + 3.97932691904809e-02 -7.13640514386860e-02 + 3.41289275285710e-02 -6.73803370811387e-02 + 2.88546712589916e-02 -6.31532691299288e-02 + 2.39831240698773e-02 -5.86665495096452e-02 + 1.94527821619992e-02 -5.39591200958821e-02 + 1.53491720497801e-02 -4.90523270599134e-02 + 1.16943357256612e-02 -4.38406284119954e-02 + 8.65365253109135e-03 -3.84459455205228e-02 + 5.92370160379059e-03 -3.30114750896427e-02 + 3.46212829965803e-03 -2.75812253497000e-02 + 1.58454458640205e-03 -2.21027074392882e-02 + 7.35715040582169e-04 -1.65321192119310e-02 + 2.97907005116705e-04 -1.09279875504530e-02 + 5.30676565098627e-05 -5.39101103138609e-03 + 0.00000000000000e+00 0.00000000000000e+00 + 9.16249484271071e-05 5.39472463076042e-03 + 2.97114014867658e-04 1.09125341734703e-02 + 6.07765485359921e-04 1.65347368419011e-02 + 1.01319685944283e-03 2.22398721797630e-02 + 1.57860720361388e-03 2.80048570638302e-02 + 2.85770205402702e-03 3.38268128923488e-02 + 4.60485640943450e-03 3.97136792782237e-02 + 6.36963363495096e-03 4.56791798263678e-02 + 8.27460103313730e-03 5.17469828248211e-02 + 1.04559502964479e-02 5.78621045555090e-02 + 1.30787206403767e-02 6.39307928915866e-02 + 1.62476019915294e-02 6.99136016610049e-02 + 1.97064472281925e-02 7.58656576746356e-02 + 2.32055551437451e-02 8.18956044570781e-02 + 2.67780264071069e-02 8.80520763606948e-02 + 3.05536180174887e-02 9.43034458705317e-02 + 3.46895645314508e-02 1.00552628487572e-01 + 3.91594998227274e-02 1.06753941085293e-01 + 4.38513894815309e-02 1.12886816803394e-01 + 4.86469345513260e-02 1.19031991526595e-01 + 5.35662818491533e-02 1.25246183971636e-01 + 5.86765310389434e-02 1.31515765400035e-01 + 6.41158119407387e-02 1.37430772030919e-01 + 6.98941360883445e-02 1.43254800103538e-01 + 7.59170877123488e-02 1.49053754727573e-01 + 8.21227682881698e-02 1.54888203928039e-01 + 8.85359454387846e-02 1.60747975413262e-01 + 9.51513059583106e-02 1.66598125672197e-01 + 1.01977161405040e-01 1.72421724747484e-01 + 1.09029076244286e-01 1.78602175887026e-01 + 1.16324626112349e-01 1.84952513492490e-01 + 1.23886862179539e-01 1.91028384041450e-01 + 1.31793661272858e-01 1.96904454248269e-01 + 1.40137015144785e-01 2.02603209487098e-01 + 1.48722392856665e-01 2.08131821762515e-01 + 1.57498055037009e-01 2.13566417662387e-01 + 1.66499738307440e-01 2.18924804988545e-01 + 1.75746807567001e-01 2.24209223798866e-01 + 1.85282812844636e-01 2.29419693016131e-01 + 1.95126003842738e-01 2.34424150993428e-01 + 2.05278382458868e-01 2.39064246909332e-01 + 2.15728458898676e-01 2.43395275762812e-01 + 2.26448399402852e-01 2.47609942869563e-01 + 2.37390616140716e-01 2.51915193162418e-01 + 2.48555223136142e-01 2.56240468008173e-01 + 2.59983581489374e-01 2.60218095713622e-01 + 2.71719323509248e-01 2.63616598352372e-01 + 2.83748575426622e-01 2.66632889055311e-01 + 2.96041798832288e-01 2.69453390481384e-01 + 3.08575060192042e-01 2.72409404922417e-01 + 3.21340186072523e-01 2.75012415222477e-01 + 3.34353685398402e-01 2.76492953153595e-01 + 3.47617985877095e-01 2.77530644029356e-01 + 3.61086047806733e-01 2.78478291157024e-01 + 3.74735967198890e-01 2.79421812258223e-01 + 3.88584839416611e-01 2.80075134954841e-01 + 4.02610569745306e-01 2.80158921396025e-01 + 4.16769966222890e-01 2.79426952940989e-01 + 4.31000767416746e-01 2.77780180205803e-01 + 4.45367430099069e-01 2.75892299873811e-01 + 4.59886426162136e-01 2.73764712702610e-01 + 4.74522704612306e-01 2.71235104254327e-01 + 4.89216780464507e-01 2.68272718312492e-01 + 5.03966776199603e-01 2.64447118696879e-01 + 5.18806020666685e-01 2.60200052632834e-01 + 5.33757172542646e-01 2.56033656152525e-01 + 5.48800417061940e-01 2.51670207782890e-01 + 5.63928433117745e-01 2.47052734150705e-01 + 5.79139293361131e-01 2.42196437539003e-01 + 5.94438582209324e-01 2.37156310638374e-01 + 6.09857099330908e-01 2.32081069158076e-01 + 6.25400870520805e-01 2.26991368536271e-01 + 6.41058606965589e-01 2.21852557624183e-01 + 6.56827119257239e-01 2.16670545580237e-01 + 6.72692401163725e-01 2.11435826592181e-01 + 6.88658261530256e-01 2.06153724323127e-01 + 7.04768588597026e-01 2.00939949019601e-01 + 7.21023238876672e-01 1.95698405223399e-01 + 7.37357768356274e-01 1.90224737500501e-01 + 7.53717588941763e-01 1.84447648187462e-01 + 7.70112763502082e-01 1.78479680783297e-01 + 7.86578143910845e-01 1.72394810225689e-01 + 8.03184229023836e-01 1.66738239461448e-01 + 8.19942143394421e-01 1.61342896059017e-01 + 8.36804795974800e-01 1.55942560425342e-01 + 8.53725343344330e-01 1.50402193026770e-01 + 8.70748946763591e-01 1.44842377351049e-01 + 8.87946529574867e-01 1.39474077514211e-01 + 9.05306293149628e-01 1.34235143291426e-01 + 9.22545067587843e-01 1.28920314434417e-01 + 9.40600734347715e-01 1.23754776734464e-01 + 9.53048939484955e-01 1.16864623799960e-01 + 9.63077773676104e-01 1.06395431570647e-01 + 9.72474093255454e-01 9.57868792253965e-02 + 9.81179655916868e-01 8.60931773916215e-02 + 9.88539472463695e-01 7.50338503152747e-02 + 9.93965264664499e-01 5.85418242094117e-02 + 9.96759513501900e-01 4.07113376276323e-02 + 9.98822819206952e-01 2.22334005961241e-02 + 1.00000000000000e+00 3.03882619127306e-03 diff --git a/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF06_Coords.txt b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF06_Coords.txt new file mode 100644 index 00000000..9931444e --- /dev/null +++ b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF06_Coords.txt @@ -0,0 +1,208 @@ + 201 NumCoords ! The number of coordinates in the airfoil shape file (including an extra coordinate for airfoil reference). Set to zero if coordinates not included. +! ......... x-y coordinates are next if NumCoords > 0 ............. +! x-y coordinate of airfoil reference +! x/c y/c + 0.250000 0 +! coordinates of airfoil shape +! interpolation to 200 points +! x/c y/c + 1.00000000000000e+00 -1.13904183263968e-02 + 9.97616112402170e-01 -3.02925242439361e-02 + 9.92090053782966e-01 -4.09226344496437e-02 + 9.78779505574386e-01 -4.46317953566502e-02 + 9.62630848882990e-01 -4.78657079982365e-02 + 9.48002016685502e-01 -5.14602797602320e-02 + 9.33316247673508e-01 -5.51593031128816e-02 + 9.18496232612161e-01 -5.92254605712216e-02 + 9.03703201804367e-01 -6.31663589833213e-02 + 8.88853928485311e-01 -6.68255900117923e-02 + 8.74049386501296e-01 -7.05161511584427e-02 + 8.59334016743915e-01 -7.43874436875609e-02 + 8.44688974778042e-01 -7.83626507822871e-02 + 8.30107202160351e-01 -8.23961121367229e-02 + 8.15594575089335e-01 -8.65047449737667e-02 + 8.01218061118175e-01 -9.08578559827087e-02 + 7.87017154459310e-01 -9.56014747506557e-02 + 7.72867465331189e-01 -1.00310586221221e-01 + 7.58658127516040e-01 -1.04602689055293e-01 + 7.44454533959962e-01 -1.08689082390743e-01 + 7.30359770774575e-01 -1.12881924651599e-01 + 7.16430384005105e-01 -1.17399987158617e-01 + 7.02548411333571e-01 -1.21769749655608e-01 + 6.88587907939929e-01 -1.25508162707915e-01 + 6.74579309967017e-01 -1.28831256546796e-01 + 6.60588643228054e-01 -1.31814109374650e-01 + 6.46644883677572e-01 -1.34518684272535e-01 + 6.32738136446085e-01 -1.36970560657454e-01 + 6.18888539380060e-01 -1.39099781158483e-01 + 6.05094599842353e-01 -1.40925423892468e-01 + 5.91370497948358e-01 -1.42548078837611e-01 + 5.77742681423787e-01 -1.44039268742623e-01 + 5.64210789942644e-01 -1.45418710112677e-01 + 5.50776369602557e-01 -1.46660362777981e-01 + 5.37444968071300e-01 -1.47785036756530e-01 + 5.24218800582908e-01 -1.48883649416298e-01 + 5.11096793180140e-01 -1.49725747746255e-01 + 4.98077600261809e-01 -1.50190862529385e-01 + 4.85165286248710e-01 -1.50548451423256e-01 + 4.72371838173648e-01 -1.50709025323563e-01 + 4.59704855658886e-01 -1.50660182339889e-01 + 4.47162353937939e-01 -1.50610036032676e-01 + 4.34748236821129e-01 -1.50574316591260e-01 + 4.22462962227877e-01 -1.50466331413989e-01 + 4.10307413565604e-01 -1.50120854962051e-01 + 3.98293549815832e-01 -1.49646376138536e-01 + 3.86431947049557e-01 -1.48985011501092e-01 + 3.74719035040848e-01 -1.47937284203969e-01 + 3.63143253860895e-01 -1.46805960127425e-01 + 3.51694487399415e-01 -1.45836094033469e-01 + 3.40375820106151e-01 -1.44917425523182e-01 + 3.29200242436979e-01 -1.43946965381053e-01 + 3.18179373560524e-01 -1.42835461865229e-01 + 3.07312147043483e-01 -1.41563685586535e-01 + 2.96589198655950e-01 -1.40239218363699e-01 + 2.86000302805324e-01 -1.38971039533067e-01 + 2.75538569884689e-01 -1.37776349074027e-01 + 2.65231088919120e-01 -1.36509074431539e-01 + 2.55105124935306e-01 -1.35017464348563e-01 + 2.45163330716385e-01 -1.33182240433968e-01 + 2.35380065561362e-01 -1.31184297306223e-01 + 2.25731797335499e-01 -1.29236565554543e-01 + 2.16212918345480e-01 -1.27375368900912e-01 + 2.06869737828596e-01 -1.25493378403087e-01 + 1.97692792848475e-01 -1.23508013308052e-01 + 1.88692178275185e-01 -1.21356126184016e-01 + 1.79852140135191e-01 -1.19094041300472e-01 + 1.71155287788632e-01 -1.16810198318667e-01 + 1.62583572203815e-01 -1.14572084308225e-01 + 1.54148627233356e-01 -1.12333771605582e-01 + 1.45882282736195e-01 -1.10017484528559e-01 + 1.37813705509852e-01 -1.07521934723333e-01 + 1.29924389454779e-01 -1.04868618458173e-01 + 1.22160459722846e-01 -1.02232244909791e-01 + 1.14462997638161e-01 -9.97769981877239e-02 + 1.06850950889400e-01 -9.74418050455991e-02 + 9.94456540823707e-02 -9.49708378396853e-02 + 9.23374027952569e-02 -9.21230511653797e-02 + 8.54657300321368e-02 -8.89658600035733e-02 + 7.87212757634630e-02 -8.58036899472230e-02 + 7.20187471524862e-02 -8.28315669774048e-02 + 6.54246409525636e-02 -7.99018939763046e-02 + 5.90704249471530e-02 -7.68099610722217e-02 + 5.30035679474469e-02 -7.34323254403719e-02 + 4.71239339609886e-02 -6.99340905790686e-02 + 4.13031360007540e-02 -6.65329912958667e-02 + 3.55234699482794e-02 -6.32184019501613e-02 + 3.01619829327107e-02 -5.96139288290971e-02 + 2.53031775785438e-02 -5.54778043544704e-02 + 2.08048174587776e-02 -5.10511978893060e-02 + 1.65388584263945e-02 -4.65627010925328e-02 + 1.26090766129194e-02 -4.18918267420981e-02 + 9.43378362085923e-03 -3.69337921085883e-02 + 6.78961770854852e-03 -3.16963231219606e-02 + 4.34237637716249e-03 -2.64747404683854e-02 + 1.85598728281019e-03 -2.13060647449452e-02 + 8.70334950751159e-04 -1.60204557614650e-02 + 3.78614157542381e-04 -1.06258278582999e-02 + 8.34360366869797e-05 -5.24793360453415e-03 + 0.00000000000000e+00 0.00000000000000e+00 + 7.67236867486678e-05 5.23517737179421e-03 + 2.69353450923468e-04 1.05899507024689e-02 + 5.68432823980679e-04 1.60424452959359e-02 + 9.62751245980932e-04 2.15677746016270e-02 + 1.56056154959061e-03 2.71408610938964e-02 + 2.93760353810514e-03 3.27643997804523e-02 + 4.68388731306286e-03 3.84466954603457e-02 + 6.39829873698727e-03 4.42192833035362e-02 + 8.30088094239591e-03 5.00830587126182e-02 + 1.04968991067837e-02 5.59331418219662e-02 + 1.31905356506929e-02 6.16590402853706e-02 + 1.64944927228985e-02 6.72926557763616e-02 + 1.99584847680105e-02 7.29780548965268e-02 + 2.33603947254173e-02 7.88193742129969e-02 + 2.68842534255446e-02 8.47441200649158e-02 + 3.06808954672960e-02 9.06322348821772e-02 + 3.49084527320684e-02 9.63920127695594e-02 + 3.94874921561364e-02 1.02093915910307e-01 + 4.41979239135200e-02 1.07851341351126e-01 + 4.88991643814045e-02 1.13771751479133e-01 + 5.37085410028852e-02 1.19785527662613e-01 + 5.87799300044820e-02 1.25738707322743e-01 + 6.42723709032797e-02 1.31439519919589e-01 + 7.01563729259333e-02 1.37001677458821e-01 + 7.62522111785621e-02 1.42563767678454e-01 + 8.24142000324228e-02 1.48247461470601e-01 + 8.87141756594531e-02 1.54005995560218e-01 + 9.52252089668619e-02 1.59738341000206e-01 + 1.02012827165119e-01 1.65362107222581e-01 + 1.09071839770933e-01 1.71005609066199e-01 + 1.16382532480666e-01 1.76625410480436e-01 + 1.23929157304783e-01 1.82119310647882e-01 + 1.31734456855347e-01 1.87537907766897e-01 + 1.39830632988419e-01 1.92818237288258e-01 + 1.48208290383940e-01 1.97881178099860e-01 + 1.56890640982985e-01 2.02754105050709e-01 + 1.65833248340983e-01 2.07492675263682e-01 + 1.74977872658223e-01 2.12167028768671e-01 + 1.84339215056554e-01 2.16828518735710e-01 + 1.93969002461360e-01 2.21262214470146e-01 + 2.03927738995053e-01 2.25232399682506e-01 + 2.14233998923319e-01 2.28819156679255e-01 + 2.24768775871601e-01 2.32298339432912e-01 + 2.35414724132119e-01 2.35983917716678e-01 + 2.46214765126001e-01 2.39788864290029e-01 + 2.57273968847626e-01 2.43131931500378e-01 + 2.68683262153020e-01 2.45701077047944e-01 + 2.80394161446840e-01 2.47884449864113e-01 + 2.92298014116652e-01 2.49928845873406e-01 + 3.04358015522582e-01 2.52310200009780e-01 + 3.16612004841116e-01 2.54366837382113e-01 + 3.29084707645504e-01 2.54944026733475e-01 + 3.41791574758934e-01 2.55013657780952e-01 + 3.54686633087091e-01 2.55077224740846e-01 + 3.67732287456134e-01 2.55080989890258e-01 + 3.80947927549799e-01 2.54809270763009e-01 + 3.94277125966556e-01 2.54299155434133e-01 + 4.07679990408069e-01 2.52964484309584e-01 + 4.21176069905831e-01 2.50460618119005e-01 + 4.34780235148961e-01 2.47779904156950e-01 + 4.48508915785030e-01 2.45032787159418e-01 + 4.62324554197701e-01 2.41951247240081e-01 + 4.76168679634616e-01 2.38443526187009e-01 + 4.90026518395832e-01 2.34310030235241e-01 + 5.03986607097025e-01 2.29965169629546e-01 + 5.18124607276385e-01 2.25794521855877e-01 + 5.32402710892978e-01 2.21622952392128e-01 + 5.46773333755108e-01 2.17288635068298e-01 + 5.61209497775237e-01 2.12697198172799e-01 + 5.75739948251087e-01 2.07963361115272e-01 + 5.90401181915651e-01 2.03229629742975e-01 + 6.05186266686445e-01 1.98479319175866e-01 + 6.20086166342671e-01 1.93692356863453e-01 + 6.35097907187523e-01 1.88871403344983e-01 + 6.50216806205491e-01 1.84017547463539e-01 + 6.65438113197408e-01 1.79123980133843e-01 + 6.80773250934036e-01 1.74228906733020e-01 + 6.96172960729631e-01 1.69180559493466e-01 + 7.11585661998256e-01 1.63830547989403e-01 + 7.27034942498605e-01 1.58268579741071e-01 + 7.42558721683669e-01 1.52649157462292e-01 + 7.58144383438193e-01 1.46939483520203e-01 + 7.73847783484881e-01 1.41394650866481e-01 + 7.89701647082685e-01 1.36067884587493e-01 + 8.05635711733308e-01 1.30738018396962e-01 + 8.21581445293506e-01 1.25220232868624e-01 + 8.37586124515025e-01 1.19666988037264e-01 + 8.53726898147738e-01 1.14318888381174e-01 + 8.69963585585765e-01 1.09065119635605e-01 + 8.86190226070913e-01 1.03619764994052e-01 + 9.02483979686875e-01 9.80682052774082e-02 + 9.18558853276680e-01 9.26538040770285e-02 + 9.34548045768020e-01 8.73262649268327e-02 + 9.50649300724702e-01 8.23994229326946e-02 + 9.66427399966504e-01 7.70749674918775e-02 + 9.80999886673880e-01 6.90076199367232e-02 + 9.92612066213372e-01 5.56165891750792e-02 + 9.96940327203726e-01 4.00048120288691e-02 + 9.99182455606956e-01 2.29517217456512e-02 + 1.00000000000000e+00 4.20817591936930e-03 diff --git a/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF07_Coords.txt b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF07_Coords.txt new file mode 100644 index 00000000..ce777e0d --- /dev/null +++ b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF07_Coords.txt @@ -0,0 +1,208 @@ + 201 NumCoords ! The number of coordinates in the airfoil shape file (including an extra coordinate for airfoil reference). Set to zero if coordinates not included. +! ......... x-y coordinates are next if NumCoords > 0 ............. +! x-y coordinate of airfoil reference +! x/c y/c + 0.250000 0 +! coordinates of airfoil shape +! interpolation to 200 points +! x/c y/c + 1.00000000000000e+00 -7.22169847721207e-03 + 9.93657635607014e-01 -9.80951552444892e-03 + 9.85015925953616e-01 -1.30850106016452e-02 + 9.68838039545111e-01 -1.84611077131393e-02 + 9.50612974422184e-01 -2.33823451641766e-02 + 9.34054843802496e-01 -2.68598144161353e-02 + 9.17904876813281e-01 -2.92032016919475e-02 + 9.02410145568755e-01 -3.25195649501926e-02 + 8.86984531818462e-01 -3.63341125283542e-02 + 8.71653146034245e-01 -4.02779399999799e-02 + 8.56421678685942e-01 -4.44297430955853e-02 + 8.41297341579872e-01 -4.88277542480629e-02 + 8.26299922405764e-01 -5.34725994663518e-02 + 8.11418218122957e-01 -5.83063399795375e-02 + 7.96668059771363e-01 -6.33518858746505e-02 + 7.82093073102221e-01 -6.86691608646314e-02 + 7.67715947269790e-01 -7.43397495082482e-02 + 7.53432129505621e-01 -8.00400824090274e-02 + 7.39140921507287e-01 -8.54783114096485e-02 + 7.24887781938029e-01 -9.07927090242104e-02 + 7.10763647733484e-01 -9.62089130617438e-02 + 6.96813846978418e-01 -1.01849003923843e-01 + 6.82926720247006e-01 -1.07345616986875e-01 + 6.68987494011958e-01 -1.12341932591132e-01 + 6.55015055372256e-01 -1.16974857778111e-01 + 6.41069653036586e-01 -1.21324695308618e-01 + 6.27178381576740e-01 -1.25441039708115e-01 + 6.13325927341839e-01 -1.29300851927610e-01 + 5.99526121249635e-01 -1.32836295356277e-01 + 5.85782516774879e-01 -1.36082768510397e-01 + 5.72099418530029e-01 -1.39062285229702e-01 + 5.58500671454668e-01 -1.41826434136283e-01 + 5.44989585070756e-01 -1.44410477552523e-01 + 5.31572041625452e-01 -1.46801987807261e-01 + 5.18249443006677e-01 -1.48965339749430e-01 + 5.05024114284701e-01 -1.51306014609625e-01 + 4.91903544204855e-01 -1.53396356865900e-01 + 4.78886537168064e-01 -1.55029927452596e-01 + 4.65973152938946e-01 -1.56361009079535e-01 + 4.53179119201583e-01 -1.57373248363793e-01 + 4.40511641089995e-01 -1.58032071375895e-01 + 4.27973254627328e-01 -1.58511320266496e-01 + 4.15569568070292e-01 -1.58830392050982e-01 + 4.03305571015855e-01 -1.58908632350926e-01 + 3.91181433267754e-01 -1.58751137788738e-01 + 3.79208355061609e-01 -1.58402513518675e-01 + 3.67395164279636e-01 -1.57823599361342e-01 + 3.55740722338427e-01 -1.56880132251604e-01 + 3.44238533276691e-01 -1.55825370105009e-01 + 3.32890410142460e-01 -1.54776742866931e-01 + 3.21695626476537e-01 -1.53702620246411e-01 + 3.10660511859208e-01 -1.52547932345675e-01 + 2.99792418198384e-01 -1.51236406478805e-01 + 2.89088689354766e-01 -1.49773471325457e-01 + 2.78543651775726e-01 -1.48236644042898e-01 + 2.68149273917489e-01 -1.46704827592144e-01 + 2.57896406226205e-01 -1.45208435280521e-01 + 2.47810593764685e-01 -1.43640086484094e-01 + 2.37924398764870e-01 -1.41871396589496e-01 + 2.28243375505465e-01 -1.39800943847393e-01 + 2.18746002754731e-01 -1.37561331679565e-01 + 2.09407739643021e-01 -1.35323082679671e-01 + 2.00204632082914e-01 -1.33142628436607e-01 + 1.91097767708039e-01 -1.30937919464830e-01 + 1.82170786872752e-01 -1.28640807136328e-01 + 1.73438864168049e-01 -1.26185420973317e-01 + 1.64887367765774e-01 -1.23622391399294e-01 + 1.56497023195920e-01 -1.21049752796620e-01 + 1.48258982483410e-01 -1.18508626502639e-01 + 1.40184001337527e-01 -1.15939910025142e-01 + 1.32310114080237e-01 -1.13239907331215e-01 + 1.24637510518848e-01 -1.10361154607051e-01 + 1.17138359086711e-01 -1.07372231954189e-01 + 1.09808401127193e-01 -1.04399442414758e-01 + 1.02594618944679e-01 -1.01600341650075e-01 + 9.54864171319728e-02 -9.89295946584694e-02 + 8.85996519559139e-02 -9.61035248577797e-02 + 8.20051916775647e-02 -9.28926032526868e-02 + 7.56369542864789e-02 -8.94141742247751e-02 + 6.94224285943848e-02 -8.59586167133803e-02 + 6.33063696107793e-02 -8.27169512241728e-02 + 5.73252083536456e-02 -7.95397742824449e-02 + 5.15865051316583e-02 -7.61848830062020e-02 + 4.61300367417238e-02 -7.25118010504582e-02 + 4.08738115912319e-02 -6.87276051345213e-02 + 3.57389328883182e-02 -6.50758836466640e-02 + 3.07040311089050e-02 -6.15616444241208e-02 + 2.60327010981162e-02 -5.78249541857669e-02 + 2.18044848917305e-02 -5.36151169153552e-02 + 1.79125721708463e-02 -4.91694235722464e-02 + 1.42640650272980e-02 -4.47148049333326e-02 + 1.09301665102860e-02 -4.01661895085117e-02 + 8.21488787888461e-03 -3.53822053138899e-02 + 5.97345205176603e-03 -3.03209729737249e-02 + 3.91406699176672e-03 -2.52857837799812e-02 + 1.81775566819190e-03 -2.03309654023002e-02 + 9.12160954949108e-04 -1.52977122324043e-02 + 4.02582765125064e-04 -1.01721928519313e-02 + 8.81962189848521e-05 -5.04398886153351e-03 + 0.00000000000000e+00 0.00000000000000e+00 + 7.88481242318804e-05 4.71135299425895e-03 + 2.80754052876520e-04 9.46261288508707e-03 + 6.13006828585368e-04 1.43031715472917e-02 + 1.05300322116593e-03 1.92164339057439e-02 + 1.65902417833529e-03 2.41858280981452e-02 + 2.88604628288041e-03 2.92144066457047e-02 + 4.45666746110958e-03 3.43052576770996e-02 + 6.03753907265340e-03 3.94795983867471e-02 + 7.82960449484624e-03 4.47233966620429e-02 + 9.91655407404961e-03 4.99442035624549e-02 + 1.24284772687387e-02 5.50687705625851e-02 + 1.54763292167825e-02 6.01250554953811e-02 + 1.86843960997679e-02 6.52596352562490e-02 + 2.18962093706069e-02 7.05324271196803e-02 + 2.52784929759404e-02 7.58378592538172e-02 + 2.89300636094216e-02 8.10694276026404e-02 + 3.29484021469950e-02 8.61824529289475e-02 + 3.72852782429899e-02 9.12501336825606e-02 + 4.17870700061248e-02 9.63840447729288e-02 + 4.63496453037568e-02 1.01661284055219e-01 + 5.10435239639925e-02 1.07009882208275e-01 + 5.59875070986280e-02 1.12277397844824e-01 + 6.13148588789216e-02 1.17455631946297e-01 + 6.70010356595760e-02 1.22519800002061e-01 + 7.29051769183183e-02 1.27568059236526e-01 + 7.89112995425554e-02 1.32686684152645e-01 + 8.50741136975359e-02 1.37843119031058e-01 + 9.14578688138890e-02 1.42951013415473e-01 + 9.81151304128743e-02 1.47950651124437e-01 + 1.05022936124011e-01 1.52865251715801e-01 + 1.12182877397443e-01 1.57757291795771e-01 + 1.19585877721620e-01 1.62614046073641e-01 + 1.27214720177563e-01 1.67446356419965e-01 + 1.35051758382265e-01 1.72165225608851e-01 + 1.43176044526092e-01 1.76678814786360e-01 + 1.51634312233503e-01 1.80984672889066e-01 + 1.60356678124586e-01 1.85147263518180e-01 + 1.69269127559869e-01 1.89234816532284e-01 + 1.78381320346887e-01 1.93269420198442e-01 + 1.87736592934877e-01 1.97097647600736e-01 + 1.97403400646351e-01 2.00521431354757e-01 + 2.07414560220724e-01 2.03579949812533e-01 + 2.17637947930063e-01 2.06524316560926e-01 + 2.27957250958957e-01 2.09606621172829e-01 + 2.38424311306026e-01 2.12738917135585e-01 + 2.49140241428875e-01 2.15458447992728e-01 + 2.60193207505178e-01 2.17511148705191e-01 + 2.71533533873424e-01 2.19224005878087e-01 + 2.83047744346193e-01 2.20787015818953e-01 + 2.94701890510800e-01 2.22583472274857e-01 + 3.06540852849821e-01 2.24096763539104e-01 + 3.18587112400968e-01 2.24415002618965e-01 + 3.30855654708830e-01 2.24301491408268e-01 + 3.43310579183658e-01 2.24139847149895e-01 + 3.55916656194316e-01 2.23898337931694e-01 + 3.68688998774519e-01 2.23408427293927e-01 + 3.81572695782548e-01 2.22730323737716e-01 + 3.94527023625166e-01 2.21420378888789e-01 + 4.07577420363382e-01 2.19229578580146e-01 + 4.20747484227582e-01 2.16905927479625e-01 + 4.34048855640024e-01 2.14517519518509e-01 + 4.47450165980170e-01 2.11864556981160e-01 + 4.60905424804169e-01 2.08876051783214e-01 + 4.74402418451617e-01 2.05501088301643e-01 + 4.88022240093813e-01 2.01966908762110e-01 + 5.01834194639075e-01 1.98470477662966e-01 + 5.15805558738129e-01 1.94947715634616e-01 + 5.29888183465374e-01 1.91277769157688e-01 + 5.44052932281682e-01 1.87389757043223e-01 + 5.58325058597065e-01 1.83339503703845e-01 + 5.72736421684721e-01 1.79233707897876e-01 + 5.87278008452787e-01 1.75063217405684e-01 + 6.01942226550589e-01 1.70800025984236e-01 + 6.16726346705862e-01 1.66455074142313e-01 + 6.31625058034417e-01 1.61970282233741e-01 + 6.46632291278635e-01 1.57504594571016e-01 + 6.61751041325077e-01 1.53059152834824e-01 + 6.76936236795835e-01 1.48499192638019e-01 + 6.92147476339639e-01 1.43724258513413e-01 + 7.07422281167433e-01 1.38823871106520e-01 + 7.22793007484622e-01 1.33869944353296e-01 + 7.38235455101973e-01 1.28814615957645e-01 + 7.53788409699974e-01 1.23522467900944e-01 + 7.69480657356214e-01 1.18283395144514e-01 + 7.85257633409310e-01 1.13044577909845e-01 + 8.01060519005720e-01 1.07644700685774e-01 + 8.16924009082326e-01 1.02213067786408e-01 + 8.32899942925333e-01 9.69408719881597e-02 + 8.48952317457811e-01 9.17358463767536e-02 + 8.65002071649512e-01 8.63711864178634e-02 + 8.80969831955332e-01 8.09281767032574e-02 + 8.97584200496906e-01 7.56224024173498e-02 + 9.14568727916341e-01 7.04186437860226e-02 + 9.31904847981603e-01 6.55248665698794e-02 + 9.49305251019172e-01 6.03216786607366e-02 + 9.66164153664091e-01 4.90247665870267e-02 + 9.80884725394935e-01 3.29696041722759e-02 + 9.88910360671404e-01 2.19933114134784e-02 + 9.94960172555627e-01 1.27529106155588e-02 + 1.00000000000000e+00 4.45165609285943e-03 diff --git a/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF08_Coords.txt b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF08_Coords.txt new file mode 100644 index 00000000..478fc66c --- /dev/null +++ b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF08_Coords.txt @@ -0,0 +1,208 @@ + 201 NumCoords ! The number of coordinates in the airfoil shape file (including an extra coordinate for airfoil reference). Set to zero if coordinates not included. +! ......... x-y coordinates are next if NumCoords > 0 ............. +! x-y coordinate of airfoil reference +! x/c y/c + 0.250000 0 +! coordinates of airfoil shape +! interpolation to 200 points +! x/c y/c + 1.00000000000000e+00 -5.11794789304784e-03 + 9.87005763971439e-01 -5.16840068225131e-03 + 9.73038425383534e-01 -5.32849535777342e-03 + 9.56081318146453e-01 -5.65516774424684e-03 + 9.38258725113225e-01 -6.13509187042994e-03 + 9.21098802615238e-01 -7.37719929228484e-03 + 9.04171761208617e-01 -9.67764145296581e-03 + 8.87610187611954e-01 -1.28830910336964e-02 + 8.71194318647985e-01 -1.68426370240972e-02 + 8.54930444958429e-01 -2.12840484397517e-02 + 8.38825194115695e-01 -2.61486444777100e-02 + 8.22890453894495e-01 -3.14203814417820e-02 + 8.07149028562320e-01 -3.70963167232995e-02 + 7.91559160728296e-01 -4.30129343317612e-02 + 7.76134809703913e-01 -4.91784530431020e-02 + 7.60882930217529e-01 -5.55441031998046e-02 + 7.45808391148759e-01 -6.21129397508765e-02 + 7.30872703797860e-01 -6.87753213244312e-02 + 7.16019391262118e-01 -7.53975930760553e-02 + 7.01249601839577e-01 -8.19653842497797e-02 + 6.86602027371248e-01 -8.85381279067066e-02 + 6.72088450727254e-01 -9.51198902776138e-02 + 6.57658826413606e-01 -1.01580704997215e-01 + 6.43273510875851e-01 -1.07825082904111e-01 + 6.28922441703606e-01 -1.13838136909654e-01 + 6.14629543830024e-01 -1.19633865914327e-01 + 6.00402302207097e-01 -1.25204051915514e-01 + 5.86224990574980e-01 -1.30504150242841e-01 + 5.72102688198421e-01 -1.35489694904769e-01 + 5.58056462396552e-01 -1.40219795793820e-01 + 5.44068657963509e-01 -1.44621519921740e-01 + 5.30149292300862e-01 -1.48688195730507e-01 + 5.16309904342871e-01 -1.52448246865224e-01 + 5.02564054060932e-01 -1.55921626814940e-01 + 4.88906214250242e-01 -1.59037421835638e-01 + 4.75341042823127e-01 -1.62423955617231e-01 + 4.61888620093194e-01 -1.65573917902269e-01 + 4.48549276031540e-01 -1.68227765214179e-01 + 4.35323450667154e-01 -1.70397650719714e-01 + 4.22231621477117e-01 -1.72138327387660e-01 + 4.09276701428819e-01 -1.73387571753102e-01 + 3.96470584896236e-01 -1.74281084442316e-01 + 3.83820866691607e-01 -1.74849339228191e-01 + 3.71337084681443e-01 -1.75019751577656e-01 + 3.59023523674681e-01 -1.74968047652900e-01 + 3.46890000105156e-01 -1.74665880146742e-01 + 3.34945069696063e-01 -1.74085229376070e-01 + 3.23189763794252e-01 -1.73173272026349e-01 + 3.11618801432831e-01 -1.72128336356160e-01 + 3.00245771337945e-01 -1.70930259894987e-01 + 2.89061607633421e-01 -1.69632705367369e-01 + 2.78070348777523e-01 -1.68223429598176e-01 + 2.67282084006707e-01 -1.66631651581257e-01 + 2.56695506216341e-01 -1.64880753133419e-01 + 2.46309210866574e-01 -1.63007736992023e-01 + 2.36121268527904e-01 -1.61049692711949e-01 + 2.26122324781829e-01 -1.59049566833247e-01 + 2.16324437766268e-01 -1.56951849123834e-01 + 2.06745907176088e-01 -1.54690861611926e-01 + 1.97389066205685e-01 -1.52226909705892e-01 + 1.88247721921604e-01 -1.49614702715995e-01 + 1.79314005605731e-01 -1.46926220464477e-01 + 1.70566694081349e-01 -1.44223107768427e-01 + 1.61987928073239e-01 -1.41464913845606e-01 + 1.53613637192824e-01 -1.38621916691031e-01 + 1.45465791115612e-01 -1.35641236981406e-01 + 1.37531633873771e-01 -1.32555619747964e-01 + 1.29789500501668e-01 -1.29438714378930e-01 + 1.22244457727610e-01 -1.26295657217261e-01 + 1.14904434138070e-01 -1.23092443693640e-01 + 1.07815146473205e-01 -1.19743795226088e-01 + 1.00932689591638e-01 -1.16291158229989e-01 + 9.42157410411242e-02 -1.12813381113546e-01 + 8.77349155613034e-02 -1.09269854169755e-01 + 8.14482559337302e-02 -1.05747275959770e-01 + 7.53019277572595e-02 -1.02291481938668e-01 + 6.93966080685775e-02 -9.87222833516028e-02 + 6.37676017649456e-02 -9.49332169892506e-02 + 5.83449527155066e-02 -9.10314379469155e-02 + 5.31177088421891e-02 -8.71178387550273e-02 + 4.80761779909361e-02 -8.32564851010753e-02 + 4.32072188935750e-02 -7.94169605594471e-02 + 3.85782245145711e-02 -7.54792072837812e-02 + 3.42154217216861e-02 -7.13768818016279e-02 + 3.00688981057734e-02 -6.72145109220034e-02 + 2.61374641397527e-02 -6.30734442017404e-02 + 2.23928752768931e-02 -5.89691912908124e-02 + 1.89178199388277e-02 -5.47792526393842e-02 + 1.57782895775260e-02 -5.03896663818205e-02 + 1.29264432287037e-02 -4.59030547514804e-02 + 1.03316751650313e-02 -4.14081472593511e-02 + 8.01095482796203e-03 -3.68823744341440e-02 + 6.08150946456878e-03 -3.22776443558319e-02 + 4.52036674400099e-03 -2.75690188527804e-02 + 3.11828349938427e-03 -2.29033385892524e-02 + 1.72653564695298e-03 -1.83027858589327e-02 + 9.36354454312048e-04 -1.37093359958523e-02 + 4.16310542075031e-04 -9.11214382596928e-03 + 9.05200308349797e-05 -4.53311172713394e-03 + 0.00000000000000e+00 0.00000000000000e+00 + 8.23110428241997e-05 3.97993478406906e-03 + 2.98468273940176e-04 7.93603235163689e-03 + 6.81113520909810e-04 1.19732402957132e-02 + 1.19041733235376e-03 1.60895922280325e-02 + 1.80832364157979e-03 2.02825181518579e-02 + 2.76834570722558e-03 2.45519466760042e-02 + 3.99985774071954e-03 2.88929320741292e-02 + 5.33098003226254e-03 3.32996052893721e-02 + 6.90917800997795e-03 3.77505431103084e-02 + 8.77992723995089e-03 4.22046062180702e-02 + 1.09457919494102e-02 4.66556914052094e-02 + 1.35126204924888e-02 5.10795304396620e-02 + 1.62412425116766e-02 5.55670056227592e-02 + 1.90868246244520e-02 6.01139718284135e-02 + 2.21802651667868e-02 6.46464708799812e-02 + 2.55327767469641e-02 6.91387827146383e-02 + 2.91390326059276e-02 7.36166345104199e-02 + 3.30039777104017e-02 7.80809269502797e-02 + 3.70896196513728e-02 8.25444208474574e-02 + 4.13563599588328e-02 8.70143468541920e-02 + 4.57942488220187e-02 9.15057079185578e-02 + 5.04601677621719e-02 9.59562675686702e-02 + 5.54400970779884e-02 1.00346688860753e-01 + 6.07171145906721e-02 1.04660979867235e-01 + 6.62216553378991e-02 1.08935080787161e-01 + 7.18940181674464e-02 1.13200789970514e-01 + 7.77574457722054e-02 1.17447559516479e-01 + 8.38582528706480e-02 1.21612209930337e-01 + 9.02250315657730e-02 1.25670302033989e-01 + 9.68042562433391e-02 1.29880982393018e-01 + 1.03635628099521e-01 1.34244912721725e-01 + 1.10722912321640e-01 1.38498319800975e-01 + 1.18029172437582e-01 1.42690766816319e-01 + 1.25557277062529e-01 1.46757468146931e-01 + 1.33346382566007e-01 1.50646937087769e-01 + 1.41422111706339e-01 1.54348524617411e-01 + 1.49738752822182e-01 1.57926503716025e-01 + 1.58261307252747e-01 1.61412895932014e-01 + 1.67014562834699e-01 1.64759052986503e-01 + 1.75997148265051e-01 1.67949166953076e-01 + 1.85241674734378e-01 1.70882184716457e-01 + 1.94781635865444e-01 1.73518364853247e-01 + 2.04539228304846e-01 1.76027713882885e-01 + 2.14458567307343e-01 1.78522958537949e-01 + 2.24570098428163e-01 1.80925955576210e-01 + 2.34913847146583e-01 1.83050172483361e-01 + 2.45534451193117e-01 1.84760209750302e-01 + 2.56409639618004e-01 1.86197622355102e-01 + 2.67481214281869e-01 1.87445374261523e-01 + 2.78729550445907e-01 1.88701260713293e-01 + 2.90174585689315e-01 1.89727304194648e-01 + 3.01827744802688e-01 1.90098148646786e-01 + 3.13693266853199e-01 1.90148247690122e-01 + 3.25752387770815e-01 1.90049748389473e-01 + 3.37985999295062e-01 1.89850482601187e-01 + 3.50399511022203e-01 1.89420380078704e-01 + 3.62964646417233e-01 1.88761112183883e-01 + 3.75659599317119e-01 1.87699877039682e-01 + 3.88493946311551e-01 1.86138748269845e-01 + 4.01479623369996e-01 1.84435211491590e-01 + 4.14618975626936e-01 1.82594846533824e-01 + 4.27893504473755e-01 1.80517499301112e-01 + 4.41277817165844e-01 1.78160355503343e-01 + 4.54769684184117e-01 1.75569963848603e-01 + 4.68402276532037e-01 1.72797452588699e-01 + 4.82204018250152e-01 1.69896570381480e-01 + 4.96163589481294e-01 1.66904476133250e-01 + 5.10254815759577e-01 1.63749683743645e-01 + 5.24457636672397e-01 1.60385631582868e-01 + 5.38778999812109e-01 1.56819010856189e-01 + 5.53239404956048e-01 1.53135112253065e-01 + 5.67833029385625e-01 1.49336436080728e-01 + 5.82554003323792e-01 1.45391901778675e-01 + 5.97398824215910e-01 1.41321960812472e-01 + 6.12357976569945e-01 1.37030889241381e-01 + 6.27427066223596e-01 1.32799780757966e-01 + 6.42609031829815e-01 1.28608187585689e-01 + 6.57884967455200e-01 1.24319134244053e-01 + 6.73222159445380e-01 1.19854473146893e-01 + 6.88646887911997e-01 1.15297096039949e-01 + 7.04172277874646e-01 1.10673352001207e-01 + 7.19774747820223e-01 1.05929035833374e-01 + 7.35472858003156e-01 1.00901982607120e-01 + 7.51283076871008e-01 9.58585566601091e-02 + 7.67180686513965e-01 9.08137757626553e-02 + 7.83126081044713e-01 8.56561702301634e-02 + 7.99132991302778e-01 8.04660870681737e-02 + 8.15219075008360e-01 7.53413348195255e-02 + 8.31361072829366e-01 7.02307546393778e-02 + 8.47517852331182e-01 6.50201985415269e-02 + 8.63656467507866e-01 5.97821549429307e-02 + 8.80097857298869e-01 5.46370739285706e-02 + 8.96698968133781e-01 4.95450131245877e-02 + 9.13428903265378e-01 4.45899999689061e-02 + 9.30165973653682e-01 3.95022753998810e-02 + 9.46677106385649e-01 3.35856041834030e-02 + 9.62366570300102e-01 2.64891184968628e-02 + 9.75524413777782e-01 1.96392571440591e-02 + 9.87942439431026e-01 1.23546891949117e-02 + 1.00000000000000e+00 4.46208092342662e-03 diff --git a/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF09_Coords.txt b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF09_Coords.txt new file mode 100644 index 00000000..ad8befd3 --- /dev/null +++ b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF09_Coords.txt @@ -0,0 +1,208 @@ + 201 NumCoords ! The number of coordinates in the airfoil shape file (including an extra coordinate for airfoil reference). Set to zero if coordinates not included. +! ......... x-y coordinates are next if NumCoords > 0 ............. +! x-y coordinate of airfoil reference +! x/c y/c + 0.250000 0 +! coordinates of airfoil shape +! interpolation to 200 points +! x/c y/c + 1.00000000000000e+00 -4.48290689425684e-03 + 9.82685147820042e-01 -8.53514315789639e-04 + 9.65074173125769e-01 1.52396515243919e-03 + 9.47131369847641e-01 2.38186310542476e-03 + 9.29079738392991e-01 1.98605407767317e-03 + 9.11136932686656e-01 5.84573053769325e-04 + 8.93331110552002e-01 -1.81559310542060e-03 + 8.75696926836349e-01 -5.03012545181162e-03 + 8.58278441614373e-01 -9.07756072898963e-03 + 8.41065780811555e-01 -1.37558503877734e-02 + 8.24066502389336e-01 -1.89558446797954e-02 + 8.07294332368906e-01 -2.46418157238813e-02 + 7.90771378093859e-01 -3.08020117323259e-02 + 7.74436098064809e-01 -3.72183726376832e-02 + 7.58302300968262e-01 -4.38908526083423e-02 + 7.42347203951615e-01 -5.07231917195430e-02 + 7.26567046543587e-01 -5.76828350641104e-02 + 7.10965565373373e-01 -6.47638335469136e-02 + 6.95519902088750e-01 -7.19078088118299e-02 + 6.80200852515995e-01 -7.90264679400814e-02 + 6.65009538158461e-01 -8.60993846853897e-02 + 6.49932728810378e-01 -9.30770840488921e-02 + 6.34965245124027e-01 -9.99452370375686e-02 + 6.20121473822035e-01 -1.06734816345267e-01 + 6.05369724148523e-01 -1.13358005108072e-01 + 5.90709203181047e-01 -1.19793368271858e-01 + 5.76132232588897e-01 -1.26003318443933e-01 + 5.61623485073142e-01 -1.31936337860336e-01 + 5.47180334826478e-01 -1.37560084850570e-01 + 5.32836011294100e-01 -1.42944693135479e-01 + 5.18557682393933e-01 -1.47974227654401e-01 + 5.04345019178191e-01 -1.52613115006628e-01 + 4.90215407430556e-01 -1.56884809310840e-01 + 4.76188015830545e-01 -1.60825115471635e-01 + 4.62253033665051e-01 -1.64349593909143e-01 + 4.48417515713528e-01 -1.67663331883973e-01 + 4.34710843069829e-01 -1.70667352837079e-01 + 4.21135345763282e-01 -1.73250013095204e-01 + 4.07692539196562e-01 -1.75369441774164e-01 + 3.94406397743186e-01 -1.77099957202116e-01 + 3.81276986557577e-01 -1.78362483813652e-01 + 3.68322783092766e-01 -1.79242115776658e-01 + 3.55553206107463e-01 -1.79749612515479e-01 + 3.42979242027837e-01 -1.79808674233742e-01 + 3.30609148150643e-01 -1.79674534400684e-01 + 3.18449580230503e-01 -1.79275909211052e-01 + 3.06509322655533e-01 -1.78584001099644e-01 + 2.94791175146716e-01 -1.77599602041753e-01 + 2.83289821555050e-01 -1.76476773548797e-01 + 2.72024535692418e-01 -1.75094998486103e-01 + 2.60982410030143e-01 -1.73562091072792e-01 + 2.50165091041909e-01 -1.71897518205597e-01 + 2.39583243413264e-01 -1.70036954342752e-01 + 2.29235853918176e-01 -1.68016721779713e-01 + 2.19124464871966e-01 -1.65842406240233e-01 + 2.09249588884711e-01 -1.63520913043737e-01 + 1.99602392919692e-01 -1.61103792507202e-01 + 1.90186989829693e-01 -1.58574244986568e-01 + 1.81007010664238e-01 -1.55917942725202e-01 + 1.72062553557725e-01 -1.53140009241234e-01 + 1.63359202368110e-01 -1.50235559165085e-01 + 1.54898392347029e-01 -1.47206088517032e-01 + 1.46661235477579e-01 -1.44116632162527e-01 + 1.38647675436818e-01 -1.40957746936569e-01 + 1.30857477642150e-01 -1.37727894684008e-01 + 1.23314150088703e-01 -1.34386012966235e-01 + 1.16005990278055e-01 -1.30951821112718e-01 + 1.08910846474458e-01 -1.27479847786535e-01 + 1.02040340343061e-01 -1.23952846372826e-01 + 9.53986311193279e-02 -1.20357474728516e-01 + 8.90323993394245e-02 -1.16626303852397e-01 + 8.28767305111376e-02 -1.12854160647330e-01 + 7.68844182301344e-02 -1.09120085561990e-01 + 7.11597965516513e-02 -1.05283382260545e-01 + 6.56696750940585e-02 -1.01384532327587e-01 + 6.03433734169027e-02 -9.75228716647275e-02 + 5.52631810751249e-02 -9.35945518645845e-02 + 5.04374628719753e-02 -8.95752445382964e-02 + 4.58017138657216e-02 -8.55532445604049e-02 + 4.13825063739979e-02 -8.15090777857146e-02 + 3.71903771573731e-02 -7.74330944997390e-02 + 3.31831498539127e-02 -7.33695626942466e-02 + 2.94044512619656e-02 -6.92770916723935e-02 + 2.58722600796746e-02 -6.51347604857932e-02 + 2.25572604740764e-02 -6.09795630283635e-02 + 1.94959660050299e-02 -5.67979807916763e-02 + 1.66549185470222e-02 -5.26131319251651e-02 + 1.40190892255552e-02 -4.84378076871468e-02 + 1.16391072588897e-02 -4.42393355742390e-02 + 9.50228788811488e-03 -4.00394598279192e-02 + 7.61750558427819e-03 -3.58461293746517e-02 + 5.96961734277674e-03 -3.16700112648946e-02 + 4.57051426408954e-03 -2.75182493553630e-02 + 3.46220550430262e-03 -2.33803588641517e-02 + 2.49916702260785e-03 -1.93106678103887e-02 + 1.63033961162431e-03 -1.53141667384712e-02 + 9.45407884520976e-04 -1.13883102313619e-02 + 4.21430261701436e-04 -7.52929844595465e-03 + 9.13381590902419e-05 -3.73175381667205e-03 + 0.00000000000000e+00 0.00000000000000e+00 + 8.39329452090013e-05 3.54374461053228e-03 + 3.06764956816802e-04 7.13454764013681e-03 + 7.13012164714768e-04 1.08029006119544e-02 + 1.25477699565490e-03 1.45538137640591e-02 + 1.87824996211846e-03 1.83913428617193e-02 + 2.64208856620242e-03 2.23137326727634e-02 + 3.57895258939452e-03 2.63122664551712e-02 + 4.70335330309463e-03 3.03676984106315e-02 + 6.09496820298392e-03 3.44560592490469e-02 + 7.77012954132717e-03 3.85621978759486e-02 + 9.64425945479125e-03 4.27121086824562e-02 + 1.18165673299811e-02 4.68542778685051e-02 + 1.41500458554206e-02 5.10499179457540e-02 + 1.66757939188311e-02 5.52650509642601e-02 + 1.94944358078314e-02 5.94454470327604e-02 + 2.25601750791306e-02 6.36068555875123e-02 + 2.57991449009508e-02 6.78079383217997e-02 + 2.92507958725958e-02 7.20111307917660e-02 + 3.29560547332662e-02 7.61771155635355e-02 + 3.69223016317185e-02 8.02789497263063e-02 + 4.10868701381863e-02 8.43778345265497e-02 + 4.54636094053712e-02 8.84590735779314e-02 + 5.01015073543740e-02 9.24805126256261e-02 + 5.49864471213822e-02 9.64435890880417e-02 + 6.01030437388835e-02 1.00355103021560e-01 + 6.54365794824045e-02 1.04221338170475e-01 + 7.09866408760679e-02 1.08042054278353e-01 + 7.67848489938729e-02 1.11764924267835e-01 + 8.28419567185367e-02 1.15382031398279e-01 + 8.90827233315631e-02 1.19090347853174e-01 + 9.55745973139600e-02 1.22782565847220e-01 + 1.02331435541202e-01 1.26329878276425e-01 + 1.09301721897512e-01 1.29816008658284e-01 + 1.16503807036038e-01 1.33194917983426e-01 + 1.23946109720764e-01 1.36448961986286e-01 + 1.31637302974835e-01 1.39553652375047e-01 + 1.39550632997968e-01 1.42570826391307e-01 + 1.47682542702398e-01 1.45498302111650e-01 + 1.56069518605229e-01 1.48227377016446e-01 + 1.64675258837698e-01 1.50862919805664e-01 + 1.73503763301154e-01 1.53381044924379e-01 + 1.82588549258338e-01 1.55672292390839e-01 + 1.91896032540898e-01 1.57837375775528e-01 + 2.01419018649528e-01 1.59879697369963e-01 + 2.11170879173786e-01 1.61737676480272e-01 + 2.21142920533604e-01 1.63440457557596e-01 + 2.31344785241530e-01 1.64936734040921e-01 + 2.41776812876277e-01 1.66222595255920e-01 + 2.52425332490408e-01 1.67302947561355e-01 + 2.63282507223669e-01 1.68244340945048e-01 + 2.74348610121382e-01 1.69012303782361e-01 + 2.85626365865730e-01 1.69515492111364e-01 + 2.97112155171042e-01 1.69781263535723e-01 + 3.08800622317762e-01 1.69842332018192e-01 + 3.20686150985499e-01 1.69794894735041e-01 + 3.32766911432096e-01 1.69536965688287e-01 + 3.45035577717233e-01 1.69036525986778e-01 + 3.57485836149525e-01 1.68290434604480e-01 + 3.70115165868763e-01 1.67285953978053e-01 + 3.82926121840238e-01 1.66129716711123e-01 + 3.95913836963527e-01 1.64788643586246e-01 + 4.09070495847257e-01 1.63222025400885e-01 + 4.22386727818900e-01 1.61413466981118e-01 + 4.35868199635534e-01 1.59446587441237e-01 + 4.49510425897221e-01 1.57282538740608e-01 + 4.63310011853810e-01 1.54890791219506e-01 + 4.77272395344154e-01 1.52355017486446e-01 + 4.91388930511577e-01 1.49650569804520e-01 + 5.05646917362174e-01 1.46740875171855e-01 + 5.20039269071302e-01 1.43601845074114e-01 + 5.34577578408399e-01 1.40310816694090e-01 + 5.49258664193118e-01 1.36874027194232e-01 + 5.64078723855862e-01 1.33285076105752e-01 + 5.79033365779676e-01 1.29550827646836e-01 + 5.94111062600388e-01 1.25620789009221e-01 + 6.09309105749297e-01 1.21600186027117e-01 + 6.24630556848364e-01 1.17501437763810e-01 + 6.40076803181406e-01 1.13310521064511e-01 + 6.55621511472488e-01 1.08956689246299e-01 + 6.71282434069662e-01 1.04519499702055e-01 + 6.87058502926135e-01 1.00008908785847e-01 + 7.02927846961763e-01 9.53686490689770e-02 + 7.18895804076489e-01 9.05798419248120e-02 + 7.34971135576913e-01 8.57455415670096e-02 + 7.51152054267092e-01 8.08966931334801e-02 + 7.67413928372726e-01 7.59701046314968e-02 + 7.83757964100345e-01 7.09983525490587e-02 + 8.00181412903085e-01 6.60019195388936e-02 + 8.16674324716874e-01 6.09715410793434e-02 + 8.33223797983461e-01 5.58863227273931e-02 + 8.49836681673719e-01 5.08054192889429e-02 + 8.66528789392319e-01 4.57720870242744e-02 + 8.83272682730090e-01 4.07491338740728e-02 + 9.00052750797641e-01 3.57316517957309e-02 + 9.16852440088815e-01 3.07020031399376e-02 + 9.33648056912371e-01 2.56007231641426e-02 + 9.50397160534152e-01 2.04803293247181e-02 + 9.66974356849030e-01 1.53946239244196e-02 + 9.83503121344171e-01 1.03013893225374e-02 + 1.00000000000000e+00 5.19104209295961e-03 diff --git a/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF10_Coords.txt b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF10_Coords.txt new file mode 100644 index 00000000..2306aabb --- /dev/null +++ b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF10_Coords.txt @@ -0,0 +1,208 @@ + 201 NumCoords ! The number of coordinates in the airfoil shape file (including an extra coordinate for airfoil reference). Set to zero if coordinates not included. +! ......... x-y coordinates are next if NumCoords > 0 ............. +! x-y coordinate of airfoil reference +! x/c y/c + 0.250000 0 +! coordinates of airfoil shape +! interpolation to 200 points +! x/c y/c + 1.00000000000000e+00 -4.86297327722780e-03 + 9.80511984509124e-01 -9.31133134220648e-04 + 9.60815932067473e-01 1.58783899675626e-03 + 9.41263727013327e-01 2.45977643583330e-03 + 9.21908373952958e-01 2.02318714366812e-03 + 9.02633195879556e-01 5.53907693277352e-04 + 8.83548952910911e-01 -1.92622687280061e-03 + 8.64676068654257e-01 -5.23592974327322e-03 + 8.46074367845829e-01 -9.38251493217475e-03 + 8.27741297597062e-01 -1.41772631793085e-02 + 8.09672007216587e-01 -1.94973257087956e-02 + 7.91873336657596e-01 -2.52977908683563e-02 + 7.74367735549103e-01 -3.15620058422089e-02 + 7.57090038050940e-01 -3.80736794610610e-02 + 7.40059721602248e-01 -4.48406933947372e-02 + 7.23230579889469e-01 -5.17449963666943e-02 + 7.06605015919964e-01 -5.87716939723825e-02 + 6.90194826941935e-01 -6.59021942385170e-02 + 6.73996889494706e-01 -7.30893135249750e-02 + 6.57970960213318e-01 -8.02435270068158e-02 + 6.42102769339429e-01 -8.73411845286708e-02 + 6.26367045194948e-01 -9.43282695074803e-02 + 6.10778899846100e-01 -1.01198731702759e-01 + 5.95374122609830e-01 -1.07986550525514e-01 + 5.80108917172105e-01 -1.14593528787722e-01 + 5.64977322759140e-01 -1.21007184170168e-01 + 5.49963599827458e-01 -1.27184493648524e-01 + 5.35054509500322e-01 -1.33078736790999e-01 + 5.20240239002187e-01 -1.38649489081145e-01 + 5.05557788087488e-01 -1.43964284458764e-01 + 4.90970256041941e-01 -1.48911007050803e-01 + 4.76472728677462e-01 -1.53449856278318e-01 + 4.62084942212174e-01 -1.57602665694934e-01 + 4.47828765294808e-01 -1.61403714230558e-01 + 4.33694515609551e-01 -1.64768180098576e-01 + 4.19692014900672e-01 -1.67312421586961e-01 + 4.05855041232298e-01 -1.69438167354179e-01 + 3.92188826102844e-01 -1.71236764964869e-01 + 3.78696783687713e-01 -1.72680366966462e-01 + 3.65404165992181e-01 -1.73828350111621e-01 + 3.52309960259442e-01 -1.74603832845386e-01 + 3.39434352269169e-01 -1.75046402850823e-01 + 3.26788044378576e-01 -1.75133825786606e-01 + 3.14377288520538e-01 -1.74796806544884e-01 + 3.02214001378326e-01 -1.74281937784550e-01 + 2.90296958909308e-01 -1.73520780939566e-01 + 2.78635485836657e-01 -1.72477429763394e-01 + 2.67233529810193e-01 -1.71175577799686e-01 + 2.56083711507059e-01 -1.69740287783202e-01 + 2.45202102031515e-01 -1.68009517278914e-01 + 2.34579105150908e-01 -1.66103858628628e-01 + 2.24212170859206e-01 -1.64059794305773e-01 + 2.14107895836219e-01 -1.61831060401740e-01 + 2.04263429104938e-01 -1.59459845656682e-01 + 1.94681903392709e-01 -1.56932790054656e-01 + 1.85360827376149e-01 -1.54246702766653e-01 + 1.76292980865286e-01 -1.51449979369351e-01 + 1.67482564557179e-01 -1.48544746675442e-01 + 1.58917391100164e-01 -1.45558949901677e-01 + 1.50597215806486e-01 -1.42512007742927e-01 + 1.42535487762553e-01 -1.39364415484843e-01 + 1.34732399664726e-01 -1.36087431797309e-01 + 1.27168245136680e-01 -1.32747266345250e-01 + 1.19842841419690e-01 -1.29351677052803e-01 + 1.12750494865106e-01 -1.25924352574772e-01 + 1.05909796567034e-01 -1.22436413682471e-01 + 9.93094805058807e-02 -1.18882766273095e-01 + 9.29294502220848e-02 -1.15306400616325e-01 + 8.67798712020860e-02 -1.11683261666515e-01 + 8.08601043456327e-02 -1.08010634641524e-01 + 7.52105971387069e-02 -1.04233041725997e-01 + 6.97707736814900e-02 -1.00453870449379e-01 + 6.44954666632857e-02 -9.67461879884846e-02 + 5.94792621751988e-02 -9.29557913115884e-02 + 5.46968806556035e-02 -8.91053349016699e-02 + 5.00889983595891e-02 -8.52955052036599e-02 + 4.57150288715163e-02 -8.14584893545538e-02 + 4.15643801762247e-02 -7.76015601232226e-02 + 3.75882055097653e-02 -7.37928505464360e-02 + 3.38275455149990e-02 -6.99786331700560e-02 + 3.02887595308436e-02 -6.61394551074094e-02 + 2.69209980985916e-02 -6.23365636550792e-02 + 2.37600762514079e-02 -5.85464923862813e-02 + 2.08209273086278e-02 -5.47566143699477e-02 + 1.80843181668748e-02 -5.09866904767273e-02 + 1.55871667540216e-02 -4.72112704231235e-02 + 1.32930091997276e-02 -4.34579786243884e-02 + 1.11671609158122e-02 -3.97587139427468e-02 + 9.24302286361386e-03 -3.60973970879580e-02 + 7.52099695998262e-03 -3.24775010120743e-02 + 6.02824547033773e-03 -2.88913977885378e-02 + 4.73760869802884e-03 -2.53555749353871e-02 + 3.63179948486746e-03 -2.18830234339889e-02 + 2.76343151147194e-03 -1.84654987945057e-02 + 2.02988502957333e-03 -1.51380631574757e-02 + 1.46813569910251e-03 -1.19064518890580e-02 + 8.92625474122533e-04 -8.77454309044243e-03 + 3.99065689084287e-04 -5.74363785175138e-03 + 8.70943828190601e-05 -2.81422588679827e-03 + 0.00000000000000e+00 0.00000000000000e+00 + 8.02187075687612e-05 3.23896444371914e-03 + 2.92360984112174e-04 6.64836967518462e-03 + 6.77158021962086e-04 1.01332887079749e-02 + 1.19066014968889e-03 1.36987991407504e-02 + 1.78076395507241e-03 1.73491673472808e-02 + 2.40903747756074e-03 2.10824160991588e-02 + 3.12276106703853e-03 2.48895553910672e-02 + 4.07783832276212e-03 2.87525459149076e-02 + 5.29086782469029e-03 3.26492458807703e-02 + 6.76340526224963e-03 3.65661596791223e-02 + 8.38018584402884e-03 4.05288053998209e-02 + 1.02253241413783e-02 4.44891365322827e-02 + 1.22248587000671e-02 4.85018949098202e-02 + 1.44438730234543e-02 5.25327300962284e-02 + 1.69548467514969e-02 5.65334970723320e-02 + 1.96931133190989e-02 6.05207316239289e-02 + 2.25638609500651e-02 6.45491498636593e-02 + 2.56161511220727e-02 6.85831866314810e-02 + 2.89202819428702e-02 7.25851847243638e-02 + 3.25062523751746e-02 7.65285938527960e-02 + 3.62951761898641e-02 8.04726459274233e-02 + 4.02846009364239e-02 8.44024704703390e-02 + 4.45007879918332e-02 8.82780700165274e-02 + 4.89247556185767e-02 9.21060334637697e-02 + 5.35723096647886e-02 9.58897521485476e-02 + 5.84592407255586e-02 9.96298721593641e-02 + 6.35713075613679e-02 1.03329002883886e-01 + 6.89278104673831e-02 1.06940810225108e-01 + 7.45312963741614e-02 1.10457519647787e-01 + 8.03023396546418e-02 1.13808960354886e-01 + 8.63179073064753e-02 1.16806322489047e-01 + 9.25972420849028e-02 1.19687016346367e-01 + 9.90811043339423e-02 1.22544358196588e-01 + 1.05787895955984e-01 1.25340806259942e-01 + 1.12724232239356e-01 1.28073095299648e-01 + 1.19892971306548e-01 1.30703114138229e-01 + 1.27273440293726e-01 1.33288917717216e-01 + 1.34877152315313e-01 1.35805891937509e-01 + 1.42744011141429e-01 1.38116832152479e-01 + 1.50823603558752e-01 1.40392690357772e-01 + 1.59107761029883e-01 1.42661149234078e-01 + 1.67629352696633e-01 1.44772172686264e-01 + 1.76377704606620e-01 1.46774529039623e-01 + 1.85370180781539e-01 1.48614215130669e-01 + 1.94612923349638e-01 1.50247989477911e-01 + 2.04074586490007e-01 1.51818931098813e-01 + 2.13747530977158e-01 1.53313183639193e-01 + 2.23645236800479e-01 1.54647357802947e-01 + 2.33775728681758e-01 1.55792644992903e-01 + 2.44138440260482e-01 1.56752241560042e-01 + 2.54726045330669e-01 1.57590263699543e-01 + 2.65537343044850e-01 1.58361624334313e-01 + 2.76567564773377e-01 1.58942652997736e-01 + 2.87817345414617e-01 1.59319971716534e-01 + 2.99290232425583e-01 1.59589784224439e-01 + 3.10982335287392e-01 1.59671340810000e-01 + 3.22895608718648e-01 1.59537343958620e-01 + 3.35033089062765e-01 1.59236217541811e-01 + 3.47389002674619e-01 1.58767154984173e-01 + 3.59961889407242e-01 1.58139657212231e-01 + 3.72743440456310e-01 1.57309327495217e-01 + 3.85733458057802e-01 1.56248726075227e-01 + 3.98930703138098e-01 1.54975303437308e-01 + 4.12345184105345e-01 1.53551512089131e-01 + 4.25954142961272e-01 1.51935725721345e-01 + 4.39739441903326e-01 1.50056917065730e-01 + 4.53714268006763e-01 1.47990332900825e-01 + 4.67878910856137e-01 1.45763613299970e-01 + 4.82224623597588e-01 1.43333415389031e-01 + 4.96738039338005e-01 1.40653686928458e-01 + 5.11425301120766e-01 1.37802798976480e-01 + 5.26284017534203e-01 1.34778098917954e-01 + 5.41313223595069e-01 1.31616771414899e-01 + 5.56506191866471e-01 1.28282935128933e-01 + 5.71853456832878e-01 1.24814251336103e-01 + 5.87352855179168e-01 1.21054902047869e-01 + 6.03005431727672e-01 1.17060565551195e-01 + 6.18822144334829e-01 1.12966378040271e-01 + 6.34781882100071e-01 1.08702844246632e-01 + 6.50899402129147e-01 1.04349818477932e-01 + 6.67165890781568e-01 9.99118836260051e-02 + 6.83560340804585e-01 9.53341953789793e-02 + 7.00082231463252e-01 9.07664656077491e-02 + 7.16736439213004e-01 8.61324826330526e-02 + 7.33532609513889e-01 8.14583044049984e-02 + 7.50453705328182e-01 7.67128793620926e-02 + 7.67496896127474e-01 7.18988453285231e-02 + 7.84651539969057e-01 6.69901347588158e-02 + 8.01917466461742e-01 6.20117979514114e-02 + 8.19294924371077e-01 5.69943186539853e-02 + 8.36792306469474e-01 5.19801638256853e-02 + 8.54409507470158e-01 4.69691610485990e-02 + 8.72138737961771e-01 4.19401147746978e-02 + 8.89967727577875e-01 3.68416407164412e-02 + 9.07923286973654e-01 3.17741055104095e-02 + 9.26040022335196e-01 2.69066169756247e-02 + 9.44348788456134e-01 2.21078957421789e-02 + 9.62867272385349e-01 1.70474154188180e-02 + 9.81428540150012e-01 1.18282222218164e-02 + 1.00000000000000e+00 6.42193222596370e-03 diff --git a/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF11_Coords.txt b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF11_Coords.txt new file mode 100644 index 00000000..cea9e099 --- /dev/null +++ b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF11_Coords.txt @@ -0,0 +1,208 @@ + 201 NumCoords ! The number of coordinates in the airfoil shape file (including an extra coordinate for airfoil reference). Set to zero if coordinates not included. +! ......... x-y coordinates are next if NumCoords > 0 ............. +! x-y coordinate of airfoil reference +! x/c y/c + 0.250000 0 +! coordinates of airfoil shape +! interpolation to 200 points +! x/c y/c + 1.00000000000000e+00 -5.69525046509396e-03 + 9.78806538918783e-01 -1.52333707624982e-03 + 9.57388982524555e-01 1.12180524962487e-03 + 9.36194732688498e-01 2.02641546982668e-03 + 9.15272729634671e-01 1.50711995585143e-03 + 8.94450817639587e-01 -1.31121257641393e-04 + 8.73855886372089e-01 -2.82614463352886e-03 + 8.53513143501759e-01 -6.40839878682634e-03 + 8.33476839211981e-01 -1.08310870429086e-02 + 8.13756218644144e-01 -1.59345264947230e-02 + 7.94338172931301e-01 -2.15617459883902e-02 + 7.75223162367073e-01 -2.76433664245668e-02 + 7.56430809853826e-01 -3.41498879519738e-02 + 7.37902039055167e-01 -4.08770619092354e-02 + 7.19666804126832e-01 -4.78568465131379e-02 + 7.01658130282083e-01 -5.49136484928595e-02 + 6.83899927259984e-01 -6.20881481267653e-02 + 6.66390228117896e-01 -6.93121843337415e-02 + 6.49139979076653e-01 -7.65617633025002e-02 + 6.32111246018286e-01 -8.37529658171195e-02 + 6.15288445442940e-01 -9.08626791271311e-02 + 5.98643467384132e-01 -9.78302135918077e-02 + 5.82199702299186e-01 -1.04659155113551e-01 + 5.65994720552908e-01 -1.11376506607751e-01 + 5.49978071618322e-01 -1.17862982731167e-01 + 5.34153023591067e-01 -1.24136613279468e-01 + 5.18499703066478e-01 -1.30142303625889e-01 + 5.03010433237196e-01 -1.35847983922864e-01 + 4.87668238679784e-01 -1.41188236613217e-01 + 4.72507803295827e-01 -1.46221700598355e-01 + 4.57497896342093e-01 -1.50852564976543e-01 + 4.42633017601021e-01 -1.55032379104410e-01 + 4.27932599332219e-01 -1.58778956843575e-01 + 4.13418848394650e-01 -1.62120173617977e-01 + 3.99086452753069e-01 -1.64971636857931e-01 + 3.84948831136274e-01 -1.67048827443987e-01 + 3.71039880058497e-01 -1.68671738056494e-01 + 3.57369018629051e-01 -1.69925952664825e-01 + 3.43942688850799e-01 -1.70795813632049e-01 + 3.30784793117660e-01 -1.71334788788157e-01 + 3.17893696334626e-01 -1.71490756553470e-01 + 3.05286580000178e-01 -1.71294197311131e-01 + 2.92974406928141e-01 -1.70717197421300e-01 + 2.80951411412875e-01 -1.69737797343376e-01 + 2.69233585663057e-01 -1.68548716430126e-01 + 2.57805947668032e-01 -1.67130702113460e-01 + 2.46678614080578e-01 -1.65444540916611e-01 + 2.35855708755702e-01 -1.63515711588020e-01 + 2.25324636807488e-01 -1.61458171344871e-01 + 2.15089578214410e-01 -1.59139131505499e-01 + 2.05150257762253e-01 -1.56651810005603e-01 + 1.95498465637821e-01 -1.54032321793723e-01 + 1.86133303884814e-01 -1.51267800061800e-01 + 1.77048514682184e-01 -1.48396307898530e-01 + 1.68247904545403e-01 -1.45397772039655e-01 + 1.59721997054468e-01 -1.42280347630919e-01 + 1.51466704551609e-01 -1.39072008137626e-01 + 1.43490819529254e-01 -1.35772826875173e-01 + 1.35761290420028e-01 -1.32454355349041e-01 + 1.28278100435328e-01 -1.29124976897121e-01 + 1.21061925252952e-01 -1.25731442239843e-01 + 1.14106782713019e-01 -1.22244231683582e-01 + 1.07392996712928e-01 -1.18723433818558e-01 + 1.00921587269965e-01 -1.15182636140660e-01 + 9.46841600395731e-02 -1.11678741751433e-01 + 8.86904020175527e-02 -1.08199712602269e-01 + 8.29295937403109e-02 -1.04690677290643e-01 + 7.73855253774526e-02 -1.01182355772936e-01 + 7.20632038828038e-02 -9.76537898724569e-02 + 6.69567872583836e-02 -9.41087513314784e-02 + 6.20974140669556e-02 -9.05039743293917e-02 + 5.74408846245436e-02 -8.69216814878245e-02 + 5.29472035657151e-02 -8.34211011266652e-02 + 4.86830821705248e-02 -7.98783109729412e-02 + 4.46330074510540e-02 -7.63028087621810e-02 + 4.07611793756051e-02 -7.27687863405534e-02 + 3.71009763948847e-02 -6.92364489374634e-02 + 3.36248359360092e-02 -6.57310546071755e-02 + 3.03041413909075e-02 -6.22959704284829e-02 + 2.71879524688719e-02 -5.88684263115360e-02 + 2.42717576545455e-02 -5.54343443189173e-02 + 2.15027525196933e-02 -5.20540051592585e-02 + 1.89137313912481e-02 -4.87090785971533e-02 + 1.65182266978350e-02 -4.53887621601851e-02 + 1.43049162404917e-02 -4.21042791351809e-02 + 1.23028427731255e-02 -3.88313724591694e-02 + 1.04741934250062e-02 -3.55976591947433e-02 + 8.78311115027676e-03 -3.24338519377945e-02 + 7.24533815833448e-03 -2.93330391673238e-02 + 5.86947854914707e-03 -2.62910386079313e-02 + 4.69611128198702e-03 -2.32928044536227e-02 + 3.68981688144507e-03 -2.03556383168934e-02 + 2.82187228866077e-03 -1.74932823095649e-02 + 2.14089095819824e-03 -1.46985911948591e-02 + 1.57630652997499e-03 -1.19942243149679e-02 + 1.18984777333983e-03 -9.38552769920999e-03 + 7.38439523884420e-04 -6.87678063790083e-03 + 3.33591616922490e-04 -4.47097508153630e-03 + 7.46901189097683e-05 -2.17087537934301e-03 + 0.00000000000000e+00 0.00000000000000e+00 + 6.92412634353660e-05 2.74621576665460e-03 + 2.49543457687775e-04 5.67381024680127e-03 + 5.69195748818264e-04 8.67143602234610e-03 + 9.96695834445714e-04 1.17435040095864e-02 + 1.48928310396865e-03 1.48940750374214e-02 + 1.98849119023728e-03 1.81207435789369e-02 + 2.54959257779418e-03 2.14141902325502e-02 + 3.34181357652084e-03 2.47615483193398e-02 + 4.35138049766192e-03 2.81462543893500e-02 + 5.57852652609682e-03 3.15563440839828e-02 + 6.92222649894473e-03 3.50119837686661e-02 + 8.43795113911303e-03 3.84786497098604e-02 + 1.00930905567546e-02 4.19960985164764e-02 + 1.19621589285143e-02 4.55325565150444e-02 + 1.40852578757622e-02 4.90549107074214e-02 + 1.64039291216290e-02 5.25767354668559e-02 + 1.88398593495795e-02 5.61372533386474e-02 + 2.14333380897448e-02 5.97116148591461e-02 + 2.42465708836148e-02 6.32736158904520e-02 + 2.73128417251185e-02 6.68021029337550e-02 + 3.05634247430033e-02 7.03446938508445e-02 + 3.40012367549624e-02 7.38799559097142e-02 + 3.76412740591324e-02 7.73776756177052e-02 + 4.14526743416006e-02 8.08567034039700e-02 + 4.54648935651470e-02 8.43141185886057e-02 + 4.97138325875744e-02 8.77373418115587e-02 + 5.41781481654145e-02 9.11359855290002e-02 + 5.88644478021621e-02 9.44797733214635e-02 + 6.37759842093246e-02 9.77593136724116e-02 + 6.88488483685858e-02 1.00823224034846e-01 + 7.41507917548021e-02 1.03488541051867e-01 + 7.97016770601785e-02 1.06075588555681e-01 + 8.54487989072580e-02 1.08666353687266e-01 + 9.14085009112059e-02 1.11233062570593e-01 + 9.75916624744935e-02 1.13770253357497e-01 + 1.03999187359272e-01 1.16244616416147e-01 + 1.10612131361174e-01 1.18708964579629e-01 + 1.17449024487558e-01 1.21131135964468e-01 + 1.24546888925588e-01 1.23387153002500e-01 + 1.31860808435011e-01 1.25637788779435e-01 + 1.39382107499695e-01 1.27944947022874e-01 + 1.47138451129947e-01 1.30161879268156e-01 + 1.55130130177100e-01 1.32297385813300e-01 + 1.63380895148427e-01 1.34288717996456e-01 + 1.71895347851209e-01 1.36104388754837e-01 + 1.80641095940374e-01 1.37908869745374e-01 + 1.89607443624250e-01 1.39694681869496e-01 + 1.98815192027444e-01 1.41352012545062e-01 + 2.08277829742442e-01 1.42856034753896e-01 + 2.17998788821085e-01 1.44187980224416e-01 + 2.27971555762112e-01 1.45430091516579e-01 + 2.38195302318094e-01 1.46673887296536e-01 + 2.48670661039287e-01 1.47744688351893e-01 + 2.59395614367826e-01 1.48645867466862e-01 + 2.70380513809449e-01 1.49438453642673e-01 + 2.81625107704732e-01 1.50057622177488e-01 + 2.93131175607184e-01 1.50496964150777e-01 + 3.04908162749787e-01 1.50795041350106e-01 + 3.16953693264067e-01 1.50926867573051e-01 + 3.29263945095546e-01 1.50884243661390e-01 + 3.41831054632093e-01 1.50627191696395e-01 + 3.54660098331472e-01 1.50114926580935e-01 + 3.67749572260908e-01 1.49411069482863e-01 + 3.81111124669245e-01 1.48516691724055e-01 + 3.94719101684341e-01 1.47440799158347e-01 + 4.08554267680281e-01 1.46095627806137e-01 + 4.22629583420339e-01 1.44515583307731e-01 + 4.36948565719152e-01 1.42787868414573e-01 + 4.51504717292113e-01 1.40851047954471e-01 + 4.66284547735849e-01 1.38636208645556e-01 + 4.81291098416158e-01 1.36225156460815e-01 + 4.96521243549536e-01 1.33595494775405e-01 + 5.11977506070676e-01 1.30819756217691e-01 + 5.27648084830866e-01 1.27801959456686e-01 + 5.43529232837187e-01 1.24624712255092e-01 + 5.59617766329048e-01 1.21167360031619e-01 + 5.75910930604750e-01 1.17465675967471e-01 + 5.92420943986219e-01 1.13641307775934e-01 + 6.09129433020705e-01 1.09627607546218e-01 + 6.26048292506993e-01 1.05505710212843e-01 + 6.43163878485665e-01 1.01266416248930e-01 + 6.60456216477355e-01 9.68592270720327e-02 + 6.77923642030845e-01 9.24805992427934e-02 + 6.95566193064319e-01 8.80054199530201e-02 + 7.13393826614235e-01 8.34592506694026e-02 + 7.31389719769680e-01 7.88141754388108e-02 + 7.49549904053857e-01 7.40757159847257e-02 + 7.67859592973647e-01 6.92056573065396e-02 + 7.86320983784494e-01 6.42470162878310e-02 + 8.04932658647533e-01 5.92311705291700e-02 + 8.23696980505892e-01 5.41849164919753e-02 + 8.42611206733270e-01 4.91017607941500e-02 + 8.61674584002276e-01 4.39898310628447e-02 + 8.80870637502453e-01 3.87781149653440e-02 + 9.00229080614011e-01 3.35800045674166e-02 + 9.19795776538293e-01 2.86236343997086e-02 + 9.39609936409794e-01 2.37339679553963e-02 + 9.59701477871013e-01 1.84898366266777e-02 + 9.79845921697258e-01 1.30253668628043e-02 + 1.00000000000000e+00 7.30191104279453e-03 diff --git a/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF12_Coords.txt b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF12_Coords.txt new file mode 100644 index 00000000..0559474f --- /dev/null +++ b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF12_Coords.txt @@ -0,0 +1,208 @@ + 201 NumCoords ! The number of coordinates in the airfoil shape file (including an extra coordinate for airfoil reference). Set to zero if coordinates not included. +! ......... x-y coordinates are next if NumCoords > 0 ............. +! x-y coordinate of airfoil reference +! x/c y/c + 0.250000 0 +! coordinates of airfoil shape +! interpolation to 200 points +! x/c y/c + 1.00000000000000e+00 -6.59289903496683e-03 + 9.77462574493223e-01 -2.16354893719578e-03 + 9.54655435704073e-01 6.29155968453326e-04 + 9.32021629665813e-01 1.58147595579106e-03 + 9.09641132745904e-01 9.68321497165801e-04 + 8.87387976484538e-01 -8.61665541778709e-04 + 8.65383162362486e-01 -3.80055493480974e-03 + 8.43662068878266e-01 -7.69211321552455e-03 + 8.22270394573964e-01 -1.24281363324318e-02 + 8.01229047333685e-01 -1.78818932097066e-02 + 7.80519648544988e-01 -2.38576889999194e-02 + 7.60137450727518e-01 -3.02583777838988e-02 + 7.40098281598073e-01 -3.70398802849335e-02 + 7.20352027908950e-01 -4.40116142510090e-02 + 7.00939656244907e-01 -5.12328611067571e-02 + 6.81776953494553e-01 -5.84627261960696e-02 + 6.62912611308619e-01 -6.58049585843197e-02 + 6.44324407874433e-01 -7.31351438149378e-02 + 6.26033587000552e-01 -8.04556049946791e-02 + 6.08009280948661e-01 -8.76887844187042e-02 + 5.90240034355429e-01 -9.48121792091236e-02 + 5.72698730868021e-01 -1.01757526822754e-01 + 5.55411618765222e-01 -1.08539348714150e-01 + 5.38410505295645e-01 -1.15176730540461e-01 + 5.21641137664166e-01 -1.21526455119343e-01 + 5.05120327854410e-01 -1.27641178842136e-01 + 4.88826034147189e-01 -1.33452107654868e-01 + 4.72756829324759e-01 -1.38943797888081e-01 + 4.56889462779481e-01 -1.44022468696136e-01 + 4.41254283784751e-01 -1.48736664468832e-01 + 4.25828763295902e-01 -1.53009077959500e-01 + 4.10608396875106e-01 -1.56781442021245e-01 + 3.95611341439966e-01 -1.60067008778474e-01 + 3.80859198346160e-01 -1.62886386652726e-01 + 3.66352119576184e-01 -1.65155670170054e-01 + 3.52107005040102e-01 -1.66902005730228e-01 + 3.38156214714513e-01 -1.68180087712901e-01 + 3.24513341344794e-01 -1.69002675432013e-01 + 3.11187922762876e-01 -1.69365388971009e-01 + 2.98201656691272e-01 -1.69321104984817e-01 + 2.85552513851790e-01 -1.68850434152112e-01 + 2.73253227372360e-01 -1.67989608645765e-01 + 2.61314584364762e-01 -1.66716467434525e-01 + 2.49717456201525e-01 -1.65067768351444e-01 + 2.38481581724083e-01 -1.63168950410788e-01 + 2.27577633315906e-01 -1.61061577397165e-01 + 2.17016518468669e-01 -1.58704919182658e-01 + 2.06802133386028e-01 -1.56117655460340e-01 + 1.96916073521044e-01 -1.53408634182298e-01 + 1.87348745914297e-01 -1.50498802686717e-01 + 1.78110341897585e-01 -1.47440177216010e-01 + 1.69187136270505e-01 -1.44263475400156e-01 + 1.60570365998313e-01 -1.40988056631572e-01 + 1.52250193619772e-01 -1.37644886570335e-01 + 1.44230669463642e-01 -1.34212542197887e-01 + 1.36494686486109e-01 -1.30715956516135e-01 + 1.29041497441893e-01 -1.27160062404650e-01 + 1.21885590388894e-01 -1.23534314732798e-01 + 1.14973606123809e-01 -1.19946512938672e-01 + 1.08305921585264e-01 -1.16388074461917e-01 + 1.01909359633608e-01 -1.12800979544153e-01 + 9.57707298096185e-02 -1.09166779555742e-01 + 8.98707927414503e-02 -1.05536283052279e-01 + 8.42125339933439e-02 -1.01922663598644e-01 + 7.87856905027138e-02 -9.84078143770367e-02 + 7.35906514404928e-02 -9.49953343228512e-02 + 6.86172317695538e-02 -9.15875578296713e-02 + 6.38533217988130e-02 -8.82040084294520e-02 + 5.92980557795527e-02 -8.48301665574652e-02 + 5.49408872977093e-02 -8.14740098816748e-02 + 5.08036836099950e-02 -7.81032042579184e-02 + 4.68610047073478e-02 -7.47702209343977e-02 + 4.30785112607683e-02 -7.15190729392446e-02 + 3.94919427630735e-02 -6.82684814540532e-02 + 3.60951095929823e-02 -6.50177741480466e-02 + 3.28772361824951e-02 -6.18076334563007e-02 + 2.98476901787584e-02 -5.86203472715078e-02 + 2.69646970034140e-02 -5.54923720162200e-02 + 2.42190323125321e-02 -5.24435068585061e-02 + 2.16645901488774e-02 -4.94116456937637e-02 + 1.92850652097574e-02 -4.63923677020781e-02 + 1.70282894977093e-02 -4.34389302947373e-02 + 1.49260602838669e-02 -4.05334871230597e-02 + 1.29912536138279e-02 -3.76649194227854e-02 + 1.12187903727820e-02 -3.48395240965275e-02 + 9.62813430202066e-03 -3.20378388982212e-02 + 8.18092003399821e-03 -2.92857015336182e-02 + 6.84633398695211e-03 -2.66067373303015e-02 + 5.62450310894219e-03 -2.40002771296278e-02 + 4.52964061799434e-03 -2.14585557295876e-02 + 3.61249392215131e-03 -1.89621107862018e-02 + 2.83156382020768e-03 -1.65274274071386e-02 + 2.15391143043915e-03 -1.41677824378179e-02 + 1.61971733933399e-03 -1.18767840274053e-02 + 1.18249367536328e-03 -9.66762809531005e-03 + 9.00276584579961e-04 -7.54452003683207e-03 + 5.63461991934761e-04 -5.51056387158645e-03 + 2.59288533302532e-04 -3.56890304558222e-03 + 6.06131716837195e-05 -1.72224692907942e-03 + 0.00000000000000e+00 0.00000000000000e+00 + 5.67835389889402e-05 2.23388026035764e-03 + 2.00952097149670e-04 4.61469303956217e-03 + 4.46675038797624e-04 7.05931530631234e-03 + 7.76575926534887e-04 9.57140139412797e-03 + 1.15849680432229e-03 1.21547788698366e-02 + 1.54614500966935e-03 1.48065561530573e-02 + 2.00070260770825e-03 1.75170400276963e-02 + 2.65215356260171e-03 2.02792339598468e-02 + 3.47323279235998e-03 2.30829050644064e-02 + 4.46819146620787e-03 2.59178267189914e-02 + 5.56561856863645e-03 2.87980918982248e-02 + 6.79056284994487e-03 3.17045231575689e-02 + 8.13858873349298e-03 3.46598711622827e-02 + 9.68330745830288e-03 3.76352864715079e-02 + 1.14346994907591e-02 4.06147151377888e-02 + 1.33491940226201e-02 4.36083707829037e-02 + 1.53772074549925e-02 4.66378931168147e-02 + 1.75443628317557e-02 4.96905933565631e-02 + 1.98915287956748e-02 5.27532648459689e-02 + 2.24474950353453e-02 5.58108786203703e-02 + 2.51624414470984e-02 5.88978723678661e-02 + 2.80522645924001e-02 6.19853661991399e-02 + 3.11264629746060e-02 6.50542499375811e-02 + 3.43410667421415e-02 6.81372889799119e-02 + 3.77308203466917e-02 7.12243994705516e-02 + 4.13453068432654e-02 7.42879931829202e-02 + 4.51595000908772e-02 7.73456299876008e-02 + 4.91686920501722e-02 8.03852564794801e-02 + 5.33801809367164e-02 8.33956461149312e-02 + 5.77512987175583e-02 8.62331801696985e-02 + 6.23344808339581e-02 8.87547541886008e-02 + 6.71482925323690e-02 9.12346139217212e-02 + 7.21514064313091e-02 9.37368421170488e-02 + 7.73578208727705e-02 9.62429430485729e-02 + 8.27840233215640e-02 9.87392024812666e-02 + 8.84305455042329e-02 1.01203971113129e-01 + 9.42784521040168e-02 1.03684898058958e-01 + 1.00349482885677e-01 1.06148999300961e-01 + 1.06675746455941e-01 1.08500173174811e-01 + 1.13224681689826e-01 1.10860453971563e-01 + 1.19991569273127e-01 1.13309399912637e-01 + 1.26997678082753e-01 1.15723096597717e-01 + 1.34248487747998e-01 1.18083169460431e-01 + 1.41766455235735e-01 1.20337838546890e-01 + 1.49556942766775e-01 1.22463305444449e-01 + 1.57594884531095e-01 1.24605078711964e-01 + 1.65872323102866e-01 1.26751754125367e-01 + 1.74414303121935e-01 1.28791936379402e-01 + 1.83232973200224e-01 1.30716996095475e-01 + 1.92334031181005e-01 1.32504394318715e-01 + 2.01714845882273e-01 1.34221597554837e-01 + 2.11376563986695e-01 1.35950985429642e-01 + 2.21327073690106e-01 1.37513571507823e-01 + 2.31558674587867e-01 1.38949208546669e-01 + 2.42086808461520e-01 1.40274988342984e-01 + 2.52916621133675e-01 1.41437460216382e-01 + 2.64046135586957e-01 1.42454319791249e-01 + 2.75489341566209e-01 1.43333195335266e-01 + 2.87249360771650e-01 1.44017218149413e-01 + 2.99320864102740e-01 1.44510983023378e-01 + 3.11697880289428e-01 1.44782627217238e-01 + 3.24389216406290e-01 1.44771773129655e-01 + 3.37389885735918e-01 1.44584432506276e-01 + 3.50711947471814e-01 1.44154382165419e-01 + 3.64333063360102e-01 1.43552910023117e-01 + 3.78238232522780e-01 1.42687210105816e-01 + 3.92437161035743e-01 1.41543861735063e-01 + 4.06934048908587e-01 1.40264190680221e-01 + 4.21723746945062e-01 1.38767747462759e-01 + 4.36795000699457e-01 1.36967177057565e-01 + 4.52149019127696e-01 1.34947664351219e-01 + 4.67781452534759e-01 1.32666334029277e-01 + 4.83698128848859e-01 1.30225012111576e-01 + 4.99881720532700e-01 1.27468428284761e-01 + 5.16334894694303e-01 1.24505686672269e-01 + 5.33052962546645e-01 1.21341841759092e-01 + 5.50029162636473e-01 1.17972273560778e-01 + 5.67273658847011e-01 1.14454109134925e-01 + 5.84769489731911e-01 1.10723931887335e-01 + 6.02525985564944e-01 1.06864330068656e-01 + 6.20526328831323e-01 1.02850463209321e-01 + 6.38751539751037e-01 9.86367644668299e-02 + 6.57200727073522e-01 9.44111760430084e-02 + 6.75869233343243e-01 9.00585516397063e-02 + 6.94763003002744e-01 8.56060946859686e-02 + 7.13862552225269e-01 8.10172115726413e-02 + 7.33163934294235e-01 7.63128882283146e-02 + 7.52650023865557e-01 7.14576086673483e-02 + 7.72322163431510e-01 6.65036673628003e-02 + 7.92171758296376e-01 6.14635847757860e-02 + 8.12193610513406e-01 5.63508957281089e-02 + 8.32382188739325e-01 5.11679507532475e-02 + 8.52739781790815e-01 4.59537194411629e-02 + 8.73243502309430e-01 4.06300736331539e-02 + 8.93910339588305e-01 3.52818185648098e-02 + 9.14779694269379e-01 3.01276312748428e-02 + 9.35880709193391e-01 2.50231519126587e-02 + 9.57228053275711e-01 1.95608523563538e-02 + 9.78615505631340e-01 1.38731920021658e-02 + 1.00000000000000e+00 7.91978608447872e-03 diff --git a/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF13_Coords.txt b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF13_Coords.txt new file mode 100644 index 00000000..1e2d3601 --- /dev/null +++ b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF13_Coords.txt @@ -0,0 +1,208 @@ + 201 NumCoords ! The number of coordinates in the airfoil shape file (including an extra coordinate for airfoil reference). Set to zero if coordinates not included. +! ......... x-y coordinates are next if NumCoords > 0 ............. +! x-y coordinate of airfoil reference +! x/c y/c + 0.250000 0 +! coordinates of airfoil shape +! interpolation to 200 points +! x/c y/c + 1.00000000000000e+00 -7.43253554058350e-03 + 9.76403943349399e-01 -2.76411676761089e-03 + 9.52484559548605e-01 1.70901095140179e-04 + 9.28638752659537e-01 1.17264141488701e-03 + 9.04989311213425e-01 4.70169949588895e-04 + 8.81494872571301e-01 -1.54228412257468e-03 + 8.58261823976117e-01 -4.71323858688598e-03 + 8.35336988680772e-01 -8.89913342673737e-03 + 8.12757098532986e-01 -1.39333287845482e-02 + 7.90553516827622e-01 -1.97204508402206e-02 + 7.68704378080380e-01 -2.60279549350672e-02 + 7.47200735959936e-01 -3.27322719971618e-02 + 7.26054587908095e-01 -3.97754488388574e-02 + 7.05225114492986e-01 -4.69799082848601e-02 + 6.84763435154875e-01 -5.44309327674479e-02 + 6.64571290619340e-01 -6.18254862513697e-02 + 6.44721094918900e-01 -6.93273346207594e-02 + 6.25169625290117e-01 -7.67585322065482e-02 + 6.05945813175358e-01 -8.41464455288096e-02 + 5.87027171152179e-01 -9.14195705532406e-02 + 5.68408265127836e-01 -9.85559847621229e-02 + 5.50064494090816e-01 -1.05480219170930e-01 + 5.32022391078534e-01 -1.12217201602923e-01 + 5.14305379706589e-01 -1.18778483581882e-01 + 4.96856985375564e-01 -1.24998074174480e-01 + 4.79708052221339e-01 -1.30961580748527e-01 + 4.62835414864543e-01 -1.36587172753257e-01 + 4.46243569969428e-01 -1.41875228138195e-01 + 4.29903985709251e-01 -1.46704975300093e-01 + 4.13842250877566e-01 -1.51115352601705e-01 + 3.98044961478621e-01 -1.55046661039126e-01 + 3.82509179271707e-01 -1.58431291993384e-01 + 3.67251501006871e-01 -1.61278156599173e-01 + 3.52292583349217e-01 -1.63600947933904e-01 + 3.37637965766980e-01 -1.65316224048267e-01 + 3.23307637097987e-01 -1.66752310164544e-01 + 3.09331872759859e-01 -1.67700911633119e-01 + 2.95728021634658e-01 -1.68102591062499e-01 + 2.82508440825120e-01 -1.67965908456118e-01 + 2.69692479373679e-01 -1.67345872254253e-01 + 2.57277849131547e-01 -1.66258775918654e-01 + 2.45272663136680e-01 -1.64751212632708e-01 + 2.33687365765199e-01 -1.62810360546622e-01 + 2.22490214641063e-01 -1.60532132121801e-01 + 2.11704186735648e-01 -1.57971495180763e-01 + 2.01286775160185e-01 -1.55229506262782e-01 + 1.91249599793888e-01 -1.52264499706685e-01 + 1.81596180932401e-01 -1.49084933070302e-01 + 1.72302626179722e-01 -1.45794670174339e-01 + 1.63346132459904e-01 -1.42374113100026e-01 + 1.54746809674797e-01 -1.38830155258698e-01 + 1.46486022194054e-01 -1.35188632600945e-01 + 1.38547760953462e-01 -1.31493700970626e-01 + 1.30918888826124e-01 -1.27769213465648e-01 + 1.23603494162898e-01 -1.23994562827742e-01 + 1.16577318947649e-01 -1.20210273993055e-01 + 1.09842714794822e-01 -1.16401422895844e-01 + 1.03419770202037e-01 -1.12543409822447e-01 + 9.72370562742986e-02 -1.08770274872843e-01 + 9.12953749434174e-02 -1.05058596046523e-01 + 8.56266337766400e-02 -1.01348959545830e-01 + 8.02107080494107e-02 -9.76386287937753e-02 + 7.50289238576886e-02 -9.39674688861899e-02 + 7.00863608932403e-02 -9.03441792141839e-02 + 6.53714233337561e-02 -8.68604994148313e-02 + 6.08759530256630e-02 -8.35323692737949e-02 + 5.65902415275960e-02 -8.02398098638649e-02 + 5.25059651925724e-02 -7.69927063770997e-02 + 4.86166628447913e-02 -7.37837554314917e-02 + 4.49077582947745e-02 -7.06237618527845e-02 + 4.13927777039596e-02 -6.74897039413312e-02 + 3.80641981810206e-02 -6.44036061372499e-02 + 3.48929832724408e-02 -6.13951848582158e-02 + 3.18856459672562e-02 -5.84268249770528e-02 + 2.90442132262908e-02 -5.54899494869964e-02 + 2.63811004580753e-02 -5.25920709101139e-02 + 2.38848880530692e-02 -4.97328732122965e-02 + 2.15021569942004e-02 -4.69560380557319e-02 + 1.92408086204874e-02 -4.42606273044788e-02 + 1.71577483979552e-02 -4.15892362716984e-02 + 1.52256501903280e-02 -3.89479589361177e-02 + 1.33940150325620e-02 -3.63811619058724e-02 + 1.16945968480858e-02 -3.38694685065991e-02 + 1.01399947277134e-02 -3.14005699954941e-02 + 8.73005199067174e-03 -2.89778491430780e-02 + 7.47487782179956e-03 -2.65876880354154e-02 + 6.33594551826867e-03 -2.42535714842850e-02 + 5.28961501167165e-03 -2.19902421680995e-02 + 4.32280168968960e-03 -1.98014211395919e-02 + 3.45367866450521e-03 -1.76778349381210e-02 + 2.74078600109631e-03 -1.55973088719527e-02 + 2.13806582939436e-03 -1.35749028237675e-02 + 1.61183106799287e-03 -1.16229600944032e-02 + 1.19278741801813e-03 -9.73562172682337e-03 + 8.52780015436871e-04 -7.91879592506294e-03 + 6.34492750095705e-04 -6.17534236909210e-03 + 3.96951815978446e-04 -4.50663935247869e-03 + 1.88581057949551e-04 -2.91531619917444e-03 + 4.72174234786785e-05 -1.40304801253723e-03 + 0.00000000000000e+00 0.00000000000000e+00 + 4.49286575851582e-05 1.76091109368109e-03 + 1.54712126205946e-04 3.62140154224627e-03 + 3.30083241230729e-04 5.53978075065709e-03 + 5.67107864039499e-04 7.51898308153193e-03 + 8.43717618992945e-04 9.56261412743599e-03 + 1.13820712865826e-03 1.16673197751854e-02 + 1.51620497309045e-03 1.38230510834726e-02 + 2.05010390234215e-03 1.60283976006057e-02 + 2.70761333894050e-03 1.82791506633120e-02 + 3.49886357702170e-03 2.05667372944473e-02 + 4.38563597305350e-03 2.28994709759180e-02 + 5.36480583545219e-03 2.52727779283164e-02 + 6.45176350756975e-03 2.76932258096428e-02 + 7.71493839934877e-03 3.01347479048045e-02 + 9.13811424494260e-03 3.25975238107331e-02 + 1.06948081659682e-02 3.50885690282112e-02 + 1.23665030939463e-02 3.76127912846818e-02 + 1.41631103789096e-02 4.01690740091098e-02 + 1.61006676743100e-02 4.27565790645424e-02 + 1.82006253144294e-02 4.53661056474953e-02 + 2.04339011456132e-02 4.80195490755358e-02 + 2.28313083356356e-02 5.06809426782037e-02 + 2.53998275561691e-02 5.33417422932120e-02 + 2.80831554197667e-02 5.60479549242059e-02 + 3.09172689371117e-02 5.87826801739081e-02 + 3.39613669672685e-02 6.15040472448373e-02 + 3.71885488983873e-02 6.42371788378289e-02 + 4.05844892078012e-02 6.69873627303355e-02 + 4.41615443337093e-02 6.97416261506273e-02 + 4.78986121512040e-02 7.24009578305107e-02 + 5.18317438541022e-02 7.48725582194455e-02 + 5.59775247308777e-02 7.73346153272878e-02 + 6.03069307314000e-02 7.98322938773953e-02 + 6.48317249020550e-02 8.23552542934740e-02 + 6.95740177949655e-02 8.48797840519584e-02 + 7.45346746264872e-02 8.73976434260533e-02 + 7.96940411568568e-02 8.99518601786404e-02 + 8.50751411244750e-02 9.25115521139639e-02 + 9.07047952097347e-02 9.50119363718962e-02 + 9.65644778591387e-02 9.75280567202470e-02 + 1.02654922362443e-01 1.00141176068606e-01 + 1.08991128382069e-01 1.02759655535384e-01 + 1.15580811141506e-01 1.05350177915118e-01 + 1.22442015345549e-01 1.07879078703890e-01 + 1.29581761141198e-01 1.10327867455967e-01 + 1.36985125957807e-01 1.12805201120027e-01 + 1.44649070157922e-01 1.15294515341388e-01 + 1.52601162527081e-01 1.17695162751273e-01 + 1.60849467906986e-01 1.20016136499640e-01 + 1.69400994120977e-01 1.22239166511633e-01 + 1.78257906944928e-01 1.24404435861666e-01 + 1.87423810521919e-01 1.26566367432406e-01 + 1.96913917030033e-01 1.28565322487382e-01 + 2.06714122721902e-01 1.30480002121111e-01 + 2.16843733267671e-01 1.32284460248505e-01 + 2.27313503043412e-01 1.33932897606815e-01 + 2.38116555091135e-01 1.35466082264203e-01 + 2.49270187442578e-01 1.36855347383195e-01 + 2.60783364777495e-01 1.38015044037685e-01 + 2.72649760913212e-01 1.38972898742601e-01 + 2.84865722003232e-01 1.39703902024797e-01 + 2.97442765366165e-01 1.40129901393810e-01 + 3.10371404770489e-01 1.40389901175565e-01 + 3.23663550383385e-01 1.40356686531760e-01 + 3.37302478141465e-01 1.40159944002643e-01 + 3.51279258331868e-01 1.39708203283014e-01 + 3.65599383240653e-01 1.38942103586727e-01 + 3.80266593353821e-01 1.38048333465819e-01 + 3.95276573569828e-01 1.36930305581693e-01 + 4.10621082225397e-01 1.35488514837408e-01 + 4.26300213083275e-01 1.33810605435263e-01 + 4.42308306311055e-01 1.31836152808260e-01 + 4.58654091580520e-01 1.29693294983505e-01 + 4.75315068619854e-01 1.27173492402662e-01 + 4.92299980112839e-01 1.24408547660075e-01 + 5.09602575838928e-01 1.21522453981813e-01 + 5.27212395134502e-01 1.18468930195838e-01 + 5.45136348862968e-01 1.15242151997318e-01 + 5.63358188082521e-01 1.11781777741663e-01 + 5.81885057318307e-01 1.08171778668078e-01 + 6.00697978768359e-01 1.04372430246799e-01 + 6.19778853163952e-01 1.00342858722927e-01 + 6.39128296470107e-01 9.62399740334075e-02 + 6.58737479416311e-01 9.19824964120890e-02 + 6.78606901768962e-01 8.76000132289643e-02 + 6.98713465939465e-01 8.30431156104294e-02 + 7.19053735025290e-01 7.83520462505258e-02 + 7.39609238737388e-01 7.34999974962512e-02 + 7.60379187011757e-01 6.85439537095766e-02 + 7.81346186916718e-01 6.34710892603186e-02 + 8.02497578082114e-01 5.82840033620211e-02 + 8.23825251477110e-01 5.29994283777580e-02 + 8.45332549847506e-01 4.76847762917876e-02 + 8.66989872326120e-01 4.22607936796464e-02 + 8.88796133601469e-01 3.67689289229451e-02 + 9.10777419149797e-01 3.13903865017990e-02 + 9.32946008475891e-01 2.60399205588807e-02 + 9.55291210260545e-01 2.03661935434009e-02 + 9.77655302958250e-01 1.44867409656004e-02 + 1.00000000000000e+00 8.36305924051618e-03 diff --git a/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF14_Coords.txt b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF14_Coords.txt new file mode 100644 index 00000000..21ac9bc9 --- /dev/null +++ b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF14_Coords.txt @@ -0,0 +1,208 @@ + 201 NumCoords ! The number of coordinates in the airfoil shape file (including an extra coordinate for airfoil reference). Set to zero if coordinates not included. +! ......... x-y coordinates are next if NumCoords > 0 ............. +! x-y coordinate of airfoil reference +! x/c y/c + 0.250000 0 +! coordinates of airfoil shape +! interpolation to 200 points +! x/c y/c + 1.00000000000000e+00 -8.14836236062521e-03 + 9.75605454220754e-01 -3.27870018079412e-03 + 9.50836784314451e-01 -2.20900988818551e-04 + 9.26031070036306e-01 8.25225422744434e-04 + 9.01354150415546e-01 4.63723364948677e-05 + 8.76856729032888e-01 -2.12212287818620e-03 + 8.52628325860033e-01 -5.49153345932107e-03 + 8.28726407818510e-01 -9.92913740060339e-03 + 8.05179636734850e-01 -1.52183220368432e-02 + 7.82028005324449e-01 -2.12905294714742e-02 + 7.59247407101620e-01 -2.78817020291902e-02 + 7.36825672022388e-01 -3.48456742332678e-02 + 7.14771415904034e-01 -4.21126282820779e-02 + 6.93052137845832e-01 -4.95161086094975e-02 + 6.71727481343893e-01 -5.71636330448956e-02 + 6.50688318620596e-01 -6.46990238340603e-02 + 6.30027418222565e-01 -7.23373717103563e-02 + 6.09682760834827e-01 -7.98549524801710e-02 + 5.89688828203817e-01 -8.73005491504785e-02 + 5.70031102500545e-01 -9.46078346312720e-02 + 5.50710313744022e-01 -1.01755382714016e-01 + 5.31704773200269e-01 -1.08661561649762e-01 + 5.13040076772302e-01 -1.15360198522277e-01 + 4.94731072648672e-01 -1.21856401857074e-01 + 4.76720063365871e-01 -1.27964705191137e-01 + 4.59050447577727e-01 -1.33798894725046e-01 + 4.41698554665827e-01 -1.39265991429221e-01 + 4.24673935956588e-01 -1.44379903497306e-01 + 4.07943877996459e-01 -1.48996777520091e-01 + 3.91529590322889e-01 -1.53147337031555e-01 + 3.75425881926708e-01 -1.56786941146897e-01 + 3.59631453908511e-01 -1.59839992659012e-01 + 3.44161400760639e-01 -1.62311690399160e-01 + 3.29035392588028e-01 -1.64209813619226e-01 + 3.14263667203509e-01 -1.65451316764320e-01 + 2.99868746495612e-01 -1.66506903639003e-01 + 2.85878821421829e-01 -1.67028933600720e-01 + 2.72314348501668e-01 -1.66931590818852e-01 + 2.59190034344532e-01 -1.66240903049082e-01 + 2.46523097896223e-01 -1.65015711658322e-01 + 2.34311085993631e-01 -1.63309762544107e-01 + 2.22557973039563e-01 -1.61179016172101e-01 + 2.11273825191574e-01 -1.58619367104621e-01 + 2.00416162834866e-01 -1.55781295522583e-01 + 1.90010573443506e-01 -1.52649361562255e-01 + 1.80003508496110e-01 -1.49375875213019e-01 + 1.70407177602816e-01 -1.45918068123790e-01 + 1.61224702358730e-01 -1.42273052042672e-01 + 1.52427517023986e-01 -1.38535454147255e-01 + 1.43981471299467e-01 -1.34741684356880e-01 + 1.35915137076383e-01 -1.30853570083458e-01 + 1.28205843380849e-01 -1.26896454867671e-01 + 1.20831500156688e-01 -1.22926515095291e-01 + 1.13776200252657e-01 -1.18962260383654e-01 + 1.07043970465416e-01 -1.14984403533098e-01 + 1.00604490983182e-01 -1.11043538945192e-01 + 9.44627247382671e-02 -1.07112169597954e-01 + 8.86436371027153e-02 -1.03150305327463e-01 + 8.30609551236505e-02 -9.93048193507565e-02 + 7.77158685764800e-02 -9.55452265219299e-02 + 7.26442623777319e-02 -9.18109492601984e-02 + 6.78200455328382e-02 -8.81164194990571e-02 + 6.32251003858072e-02 -8.44890217245990e-02 + 5.88664059457334e-02 -8.09291839835693e-02 + 5.47314426912757e-02 -7.75147830298754e-02 + 5.08048887650857e-02 -7.42689802432870e-02 + 4.70774277960059e-02 -7.10840961776320e-02 + 4.35439177679982e-02 -6.79622663696009e-02 + 4.01931090877671e-02 -6.49028866719955e-02 + 3.70071961558051e-02 -6.19186097345931e-02 + 3.39928055580254e-02 -5.89938489520709e-02 + 3.11577683019826e-02 -5.61235560760588e-02 + 2.84775442869274e-02 -5.33253098749644e-02 + 2.59337722860059e-02 -5.06003306707210e-02 + 2.35351879537169e-02 -4.79341414523893e-02 + 2.13137371577664e-02 -4.53052669924546e-02 + 1.92412232739687e-02 -4.27265135238339e-02 + 1.72551808149047e-02 -4.02460777005286e-02 + 1.53775125192213e-02 -3.78461069409167e-02 + 1.36669286314092e-02 -3.54751904767474e-02 + 1.20867763486272e-02 -3.31490567840202e-02 + 1.05884996763417e-02 -3.09033988993154e-02 + 9.20425453765281e-03 -2.87165660887120e-02 + 7.94657176624660e-03 -2.65748008857490e-02 + 6.81901031712526e-03 -2.44798541378323e-02 + 5.82356366307817e-03 -2.24237272913497e-02 + 4.92174384636360e-03 -2.04275731539013e-02 + 4.09719664088157e-03 -1.84975012786712e-02 + 3.32633841273745e-03 -1.66402354620686e-02 + 2.63006056419046e-03 -1.48461343785805e-02 + 2.07265379541992e-03 -1.30914265545919e-02 + 1.60475669651842e-03 -1.13896387204853e-02 + 1.19362491575511e-03 -9.75207784151342e-03 + 8.61158304775857e-04 -8.17325143675256e-03 + 5.92658871339785e-04 -6.65366840829812e-03 + 4.11941085518658e-04 -5.19491140252507e-03 + 2.54556569896829e-04 -3.79658841465355e-03 + 1.28113832478964e-04 -2.46056989256330e-03 + 3.57617220409199e-05 -1.18717030094207e-03 + 0.00000000000000e+00 0.00000000000000e+00 + 3.47906660476153e-05 1.35864880901149e-03 + 1.15168885058535e-04 2.77417290109050e-03 + 2.30376916315236e-04 4.24252249803400e-03 + 3.87976131495443e-04 5.76601626174964e-03 + 5.74526506204122e-04 7.34806995808761e-03 + 7.95654255520616e-04 8.98493392763457e-03 + 1.12021971636174e-03 1.06662550219730e-02 + 1.56154664930487e-03 1.23953998641279e-02 + 2.08683544746350e-03 1.41733115513416e-02 + 2.71224085851922e-03 1.59928312616081e-02 + 3.43035954718513e-03 1.78573300023999e-02 + 4.21435009067654e-03 1.97747226754239e-02 + 5.09317032805970e-03 2.17377376445490e-02 + 6.12872222137403e-03 2.37226879106243e-02 + 7.28358292664935e-03 2.57436355827732e-02 + 8.54729910157088e-03 2.78048612104546e-02 + 9.92972828959359e-03 2.98969637573703e-02 + 1.14264946100910e-02 3.20287229123090e-02 + 1.30302058764849e-02 3.42098777797921e-02 + 1.47545509310666e-02 3.64362116507928e-02 + 1.65895142682137e-02 3.87188939282128e-02 + 1.85799091430884e-02 4.10158975075125e-02 + 2.07318790579148e-02 4.33277140117620e-02 + 2.29786410496385e-02 4.57116743283601e-02 + 2.53553835037421e-02 4.81450487278177e-02 + 2.79278776797602e-02 5.05737523231150e-02 + 3.06684104757498e-02 5.30293753541954e-02 + 3.35549896302923e-02 5.55320353345598e-02 + 3.66048832549710e-02 5.80672661628428e-02 + 3.98160878278975e-02 6.05922518843348e-02 + 4.32097657635900e-02 6.30632131339738e-02 + 4.68004477364611e-02 6.55508747412392e-02 + 5.05703468888338e-02 6.80833115592091e-02 + 5.45293129960311e-02 7.06568325856674e-02 + 5.87044042125043e-02 7.32381347585862e-02 + 6.30971043353738e-02 7.58315677252795e-02 + 6.76867916036615e-02 7.84763490181517e-02 + 7.24967292572105e-02 8.11447924400529e-02 + 7.75489190519818e-02 8.38012218025252e-02 + 8.28379430912991e-02 8.64755853792752e-02 + 8.83700160522555e-02 8.92311260118967e-02 + 9.41546877815251e-02 9.20147089552618e-02 + 1.00200275044183e-01 9.47925250920637e-02 + 1.06519506627458e-01 9.75499482587641e-02 + 1.13121273553931e-01 1.00272215404985e-01 + 1.20000865270765e-01 1.03022793377647e-01 + 1.27160568795956e-01 1.05784624380971e-01 + 1.34629377330607e-01 1.08475019956957e-01 + 1.42410501436542e-01 1.11115501827654e-01 + 1.50511658880668e-01 1.13695222223560e-01 + 1.58939652295794e-01 1.16224524312285e-01 + 1.67700467710513e-01 1.18723937489766e-01 + 1.76815783980035e-01 1.21067625942295e-01 + 1.86265538652919e-01 1.23365512977448e-01 + 1.96071866452217e-01 1.25554708540608e-01 + 2.06250547051562e-01 1.27593275787970e-01 + 2.16789870603760e-01 1.29541754711146e-01 + 2.27709471480002e-01 1.31337948456032e-01 + 2.39023607624358e-01 1.32877774715532e-01 + 2.50725312099806e-01 1.34211878219550e-01 + 2.62813163393733e-01 1.35317273908679e-01 + 2.75300589304416e-01 1.36105292149500e-01 + 2.88173680979742e-01 1.36733482190757e-01 + 3.01443959248928e-01 1.37027602201975e-01 + 3.15100693572125e-01 1.37162360722735e-01 + 3.29141136015704e-01 1.37051985111160e-01 + 3.43566633885766e-01 1.36597826483452e-01 + 3.58379996607331e-01 1.36020493099717e-01 + 3.73577404766437e-01 1.35212892447741e-01 + 3.89153622315017e-01 1.34072142153192e-01 + 4.05108094120761e-01 1.32686673560345e-01 + 4.21433969423481e-01 1.30984053441620e-01 + 4.38142341403862e-01 1.29118324458878e-01 + 4.55206328011914e-01 1.26836633577195e-01 + 4.72639853963158e-01 1.24300133080523e-01 + 4.90435271070256e-01 1.21679117794261e-01 + 5.08579010309887e-01 1.18895867110872e-01 + 5.27074571229468e-01 1.15918274965440e-01 + 5.45906008138401e-01 1.12688629331682e-01 + 5.65078719861412e-01 1.09292084145262e-01 + 5.84572298052518e-01 1.05676186408607e-01 + 6.04369364403524e-01 1.01804075775369e-01 + 6.24472197888980e-01 9.77950051523939e-02 + 6.44868545310258e-01 9.36084798785348e-02 + 6.65553461692358e-01 8.92765243340495e-02 + 6.86500234562328e-01 8.47365603510263e-02 + 7.07706100172094e-01 8.00475004561028e-02 + 7.29151865146187e-01 7.51929614727690e-02 + 7.50834276036418e-01 7.02319315014268e-02 + 7.72727461247450e-01 6.51263205099363e-02 + 7.94812249063048e-01 5.98701925922095e-02 + 8.17078362972243e-01 5.44954720205527e-02 + 8.39529154287222e-01 4.90934541266714e-02 + 8.62128984506176e-01 4.35866611147249e-02 + 8.84858418262504e-01 3.79716307048406e-02 + 9.07728679674592e-01 3.23837149939797e-02 + 9.30734095888120e-01 2.68027303925987e-02 + 9.53837027134021e-01 2.09467195741978e-02 + 9.76936319972422e-01 1.49132298932001e-02 + 1.00000000000000e+00 8.66710884250080e-03 diff --git a/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF15_Coords.txt b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF15_Coords.txt new file mode 100644 index 00000000..670d0c5a --- /dev/null +++ b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF15_Coords.txt @@ -0,0 +1,208 @@ + 201 NumCoords ! The number of coordinates in the airfoil shape file (including an extra coordinate for airfoil reference). Set to zero if coordinates not included. +! ......... x-y coordinates are next if NumCoords > 0 ............. +! x-y coordinate of airfoil reference +! x/c y/c + 0.250000 0 +! coordinates of airfoil shape +! interpolation to 200 points +! x/c y/c + 1.00000000000000e+00 -8.57879977773810e-03 + 9.75180222150308e-01 -3.03879904135747e-03 + 9.49954708363444e-01 -1.26002872729501e-04 + 9.24617663626292e-01 6.10122226095701e-04 + 8.99362589909934e-01 -2.13375521927681e-04 + 8.74301657857705e-01 -2.47307597608542e-03 + 8.49512831893362e-01 -5.95848312946069e-03 + 8.25060132654372e-01 -1.05432097366251e-02 + 8.00967349009157e-01 -1.59814342852104e-02 + 7.77279396459348e-01 -2.22202726470426e-02 + 7.53971146353458e-01 -2.89772479518455e-02 + 7.31028686926424e-01 -3.60929872413459e-02 + 7.08458616265561e-01 -4.34907379085029e-02 + 6.86233439551971e-01 -5.10105449101421e-02 + 6.64417721038235e-01 -5.87729225500483e-02 + 6.42896424356607e-01 -6.63906320145616e-02 + 6.21774241465352e-01 -7.41087631455492e-02 + 6.00977841522425e-01 -8.16768344389446e-02 + 5.80544552788493e-01 -8.91561467273735e-02 + 5.60464827414216e-01 -9.64833988179528e-02 + 5.40743392390515e-01 -1.03637454592294e-01 + 5.21360556780428e-01 -1.10533080197566e-01 + 5.02340910284044e-01 -1.17209304289204e-01 + 4.83693742857298e-01 -1.23667469493609e-01 + 4.65360905225594e-01 -1.29710726001548e-01 + 4.47393349439378e-01 -1.35469330395386e-01 + 4.29767286515700e-01 -1.40843787417424e-01 + 4.12495217820767e-01 -1.45855913618906e-01 + 3.95542115741603e-01 -1.50348364394606e-01 + 3.78926510481714e-01 -1.54347061753637e-01 + 3.62648170482185e-01 -1.57816166203811e-01 + 3.46706871509637e-01 -1.60675411249642e-01 + 3.31116764742986e-01 -1.62927825900264e-01 + 3.15896874263702e-01 -1.64577732807176e-01 + 3.01060219418983e-01 -1.65542318105973e-01 + 2.86630760513041e-01 -1.66019067198897e-01 + 2.72635352957487e-01 -1.65852810272617e-01 + 2.59096229086319e-01 -1.65053656791642e-01 + 2.46029444917578e-01 -1.63674484017382e-01 + 2.33450927162206e-01 -1.61779021413358e-01 + 2.21358148093932e-01 -1.59458179997197e-01 + 2.09752590238530e-01 -1.56768645463127e-01 + 1.98644065634366e-01 -1.53708652225252e-01 + 1.87983838111383e-01 -1.50468466633829e-01 + 1.77798959359292e-01 -1.46968929468240e-01 + 1.68029515979667e-01 -1.43391369897358e-01 + 1.58688054711323e-01 -1.39690800395147e-01 + 1.49777434120809e-01 -1.35854606762879e-01 + 1.41266364582040e-01 -1.31957036662395e-01 + 1.33114043882986e-01 -1.28072240442312e-01 + 1.25353982091811e-01 -1.24123605323377e-01 + 1.17961213252232e-01 -1.20147065379440e-01 + 1.10910137898332e-01 -1.16185429245801e-01 + 1.04183249914720e-01 -1.12256793878014e-01 + 9.77845035922472e-02 -1.08341834070059e-01 + 9.16800568181114e-02 -1.04487577173595e-01 + 8.58763837804680e-02 -1.00669929174109e-01 + 8.04013343441990e-02 -9.68347298049542e-02 + 7.51601956348723e-02 -9.31177415424908e-02 + 7.01543935952098e-02 -8.94997948476300e-02 + 6.54219938355571e-02 -8.59156686036492e-02 + 6.09334040261291e-02 -8.23945222782936e-02 + 5.66708598548473e-02 -7.89496641080547e-02 + 5.26424925924951e-02 -7.55684130212430e-02 + 4.88353267109018e-02 -7.22706692662718e-02 + 4.52299098002129e-02 -6.90769445598798e-02 + 4.18171486326621e-02 -6.59585470797291e-02 + 3.85937390562270e-02 -6.29132740880722e-02 + 3.55456313710721e-02 -5.99446421848028e-02 + 3.26532165695984e-02 -5.70661627728155e-02 + 2.99191791468483e-02 -5.42663897359114e-02 + 2.73603366698335e-02 -5.15240489459803e-02 + 2.49547621710270e-02 -4.88496591224952e-02 + 2.26696019923393e-02 -4.62677203676052e-02 + 2.05173895362584e-02 -4.37606410408951e-02 + 1.85413689047946e-02 -4.12897613211990e-02 + 1.67039255897644e-02 -3.88748760932536e-02 + 1.49376604499564e-02 -3.65661749206043e-02 + 1.32724098833742e-02 -3.43362370571288e-02 + 1.17676398242478e-02 -3.21379214236623e-02 + 1.03812841619170e-02 -2.99928372995567e-02 + 9.06612278982865e-03 -2.79311924288680e-02 + 7.85471709046639e-03 -2.59296320464281e-02 + 6.75962346486767e-03 -2.39733845222929e-02 + 5.78638085277238e-03 -2.20635808604033e-02 + 4.93219411743517e-03 -2.01957483008656e-02 + 4.15866656660073e-03 -1.83895524002002e-02 + 3.45414954175195e-03 -1.66456540575484e-02 + 2.78923310544400e-03 -1.49722402872741e-02 + 2.18613805623396e-03 -1.33598127496920e-02 + 1.71216161569515e-03 -1.17839473069557e-02 + 1.31624248102220e-03 -1.02571525116732e-02 + 9.66801840458578e-04 -8.79003718291119e-03 + 6.80319528299336e-04 -7.37728839044000e-03 + 4.49100581451274e-04 -6.01658261674601e-03 + 2.83701305712447e-04 -4.70870707990412e-03 + 1.71327286198412e-04 -3.45212068865394e-03 + 9.27710524239121e-05 -2.24812638028363e-03 + 2.90659238934096e-05 -1.09605843814913e-03 + 0.00000000000000e+00 0.00000000000000e+00 + 2.88650625107761e-05 1.11148823849564e-03 + 9.20560654498922e-05 2.26693180022457e-03 + 1.72099085901139e-04 3.47224142051019e-03 + 2.83274561762190e-04 4.72937588738418e-03 + 4.17185695243679e-04 6.04164001396517e-03 + 5.97882203243190e-04 7.40505294611765e-03 + 8.95891727887411e-04 8.80908372794426e-03 + 1.28619996129368e-03 1.02598911578957e-02 + 1.73718091964475e-03 1.17614295105485e-02 + 2.26889766516844e-03 1.33073665302488e-02 + 2.89290184609361e-03 1.48981843737658e-02 + 3.56863592046535e-03 1.65490975122241e-02 + 4.33167262281806e-03 1.82447453137629e-02 + 5.23928473841845e-03 1.99628317108720e-02 + 6.24211877712485e-03 2.17255330691366e-02 + 7.33964056226407e-03 2.35355313731346e-02 + 8.55899423724526e-03 2.53750621882832e-02 + 9.88712266524690e-03 2.72586895159738e-02 + 1.13020867063170e-02 2.92023348035768e-02 + 1.28124619939745e-02 3.12046945194575e-02 + 1.44198946335000e-02 3.32706688249579e-02 + 1.61778638266544e-02 3.53546883232132e-02 + 1.80925347692918e-02 3.74625260070275e-02 + 2.00910255479398e-02 3.96581315151937e-02 + 2.22073480805733e-02 4.19153679037419e-02 + 2.45104741518688e-02 4.41730112135886e-02 + 2.69725227219957e-02 4.64664319277826e-02 + 2.95672369905170e-02 4.88244154637241e-02 + 3.23149834672359e-02 5.12316228766112e-02 + 3.52251763885414e-02 5.36850922615401e-02 + 3.83099350602331e-02 5.61720264031417e-02 + 4.15824489104227e-02 5.86905077324653e-02 + 4.50317770709382e-02 6.12582681605947e-02 + 4.86666503586395e-02 6.38753760166677e-02 + 5.25170727043328e-02 6.65025186818970e-02 + 5.65850189187534e-02 6.91518398462091e-02 + 6.08491647683366e-02 7.18603850558563e-02 + 6.53325801131270e-02 7.46028792309043e-02 + 7.00543348142427e-02 7.73615611579748e-02 + 7.50171013293054e-02 8.01381142978750e-02 + 8.02306159895163e-02 8.29454075566739e-02 + 8.57012088705319e-02 8.57724141117260e-02 + 9.14370395472359e-02 8.86083733592826e-02 + 9.74471306573141e-02 9.14506955541571e-02 + 1.03741642665461e-01 9.42869115799166e-02 + 1.10322431016719e-01 9.71366683959768e-02 + 1.17195331455295e-01 9.99963817208149e-02 + 1.24389884664589e-01 1.02804765589993e-01 + 1.31905935056049e-01 1.05580086008781e-01 + 1.39751456026638e-01 1.08317196263952e-01 + 1.47936168023821e-01 1.11006216128796e-01 + 1.56467558128623e-01 1.13642271424664e-01 + 1.65371163914618e-01 1.16141616432774e-01 + 1.74623252652850e-01 1.18621015919461e-01 + 1.84247428093051e-01 1.20997142483866e-01 + 1.94262496093302e-01 1.23226242267470e-01 + 2.04653672488981e-01 1.25380363541681e-01 + 2.15441765864240e-01 1.27378959185081e-01 + 2.26644243180055e-01 1.29123968217828e-01 + 2.38253845273158e-01 1.30674870254090e-01 + 2.50270552701415e-01 1.31999307783067e-01 + 2.62708751790901e-01 1.33015597369151e-01 + 2.75551725512235e-01 1.33872159509066e-01 + 2.88810665433822e-01 1.34378959676908e-01 + 3.02478807217932e-01 1.34723171413855e-01 + 3.16557400521368e-01 1.34828318979527e-01 + 3.31045159681679e-01 1.34573337077908e-01 + 3.45944140981529e-01 1.34191735267806e-01 + 3.61250730235273e-01 1.33577791174796e-01 + 3.76961614806380e-01 1.32641039909018e-01 + 3.93075978637921e-01 1.31467341415961e-01 + 4.09586247490783e-01 1.29983874522969e-01 + 4.26504850189084e-01 1.28372193187690e-01 + 4.43802359792042e-01 1.26353263881723e-01 + 4.61495724587332e-01 1.24138877363526e-01 + 4.79576454948711e-01 1.21758646632159e-01 + 4.98029186432348e-01 1.19133369177162e-01 + 5.16855180283856e-01 1.16301424988927e-01 + 5.36038549215196e-01 1.13206639039446e-01 + 5.55583719652262e-01 1.09934856544340e-01 + 5.75469608979237e-01 1.06426184782536e-01 + 5.95679247848144e-01 1.02646109224194e-01 + 6.16216032509872e-01 9.86875548679134e-02 + 6.37065764297449e-01 9.45384567802663e-02 + 6.58220009598337e-01 9.02324184327279e-02 + 6.79649739397516e-01 8.56983061171984e-02 + 7.01352675498130e-01 8.10067998035236e-02 + 7.23309367720016e-01 7.61487654794268e-02 + 7.45514874390413e-01 7.11835831183337e-02 + 7.67937997489119e-01 6.60570021231055e-02 + 7.90555709099499e-01 6.07584149955232e-02 + 8.13356480155146e-01 5.53297489402000e-02 + 8.36343320325429e-01 4.98760881816722e-02 + 8.59476947043660e-01 4.43220559191783e-02 + 8.82726076021484e-01 3.86348982394945e-02 + 9.06091895800112e-01 3.29178055135213e-02 + 9.29556869258233e-01 2.71942568107446e-02 + 9.53065562517705e-01 2.12312867691710e-02 + 9.76555746470235e-01 1.51116304681152e-02 + 1.00000000000000e+00 8.80279316603190e-03 diff --git a/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF16_Coords.txt b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF16_Coords.txt new file mode 100644 index 00000000..c1f50c91 --- /dev/null +++ b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF16_Coords.txt @@ -0,0 +1,208 @@ + 201 NumCoords ! The number of coordinates in the airfoil shape file (including an extra coordinate for airfoil reference). Set to zero if coordinates not included. +! ......... x-y coordinates are next if NumCoords > 0 ............. +! x-y coordinate of airfoil reference +! x/c y/c + 0.250000 0 +! coordinates of airfoil shape +! interpolation to 200 points +! x/c y/c + 1.00000000000000e+00 -7.93823528916634e-03 + 9.75306611523266e-01 -3.07804362808370e-03 + 9.50254896398834e-01 2.12362996603380e-05 + 9.25086956564820e-01 1.10034879293892e-03 + 8.99988535976524e-01 4.37422920277549e-04 + 8.75072599857149e-01 -1.69228312874642e-03 + 8.50417485943084e-01 -5.02575124436309e-03 + 8.26088106219083e-01 -9.48963995265479e-03 + 8.02111382252523e-01 -1.48157088586162e-02 + 7.78533224241522e-01 -2.09559594834436e-02 + 7.55333131164625e-01 -2.76360667094703e-02 + 7.32498770899621e-01 -3.46931927585546e-02 + 7.10037524800713e-01 -4.20512954807589e-02 + 6.87921684496055e-01 -4.95447286109428e-02 + 6.66209179710118e-01 -5.72757010622818e-02 + 6.44793205529505e-01 -6.48779142100834e-02 + 6.23770247083330e-01 -7.25767710634749e-02 + 6.03070773283972e-01 -8.01314038494710e-02 + 5.82725782097447e-01 -8.75866260531345e-02 + 5.62727405516286e-01 -9.48842528629214e-02 + 5.43080423918886e-01 -1.02003644748097e-01 + 5.23763733755852e-01 -1.08853301029009e-01 + 5.04803219809205e-01 -1.15477844917736e-01 + 4.86206982188546e-01 -1.21874673443526e-01 + 4.67921007083763e-01 -1.27856568331733e-01 + 4.49992820623389e-01 -1.33542654805615e-01 + 4.32401794865636e-01 -1.38840810792771e-01 + 4.15160522435188e-01 -1.43774009354166e-01 + 3.98236888852800e-01 -1.48190991673080e-01 + 3.81648251477225e-01 -1.52112731931741e-01 + 3.65396878028470e-01 -1.55516473547203e-01 + 3.49482408564341e-01 -1.58321238170515e-01 + 3.33919160469124e-01 -1.60534240376794e-01 + 3.18725408829206e-01 -1.62165537784395e-01 + 3.03913049141917e-01 -1.63131873998207e-01 + 2.89504737395872e-01 -1.62983765163967e-01 + 2.75525761184225e-01 -1.62070670020849e-01 + 2.61996790164123e-01 -1.60600815773790e-01 + 2.48932908441187e-01 -1.58650156209932e-01 + 2.36348800371720e-01 -1.56288718478177e-01 + 2.24242074483076e-01 -1.53625685704211e-01 + 2.12614132311826e-01 -1.50704613076576e-01 + 2.01474116266847e-01 -1.47515164268461e-01 + 1.90775946871820e-01 -1.44259340711770e-01 + 1.80545164370369e-01 -1.40816254075015e-01 + 1.70726148932411e-01 -1.37356122795043e-01 + 1.61329495142793e-01 -1.33838435774938e-01 + 1.52357448812365e-01 -1.30248116217731e-01 + 1.43781676609354e-01 -1.26622879278557e-01 + 1.35562251699688e-01 -1.23048941083730e-01 + 1.27731865989209e-01 -1.19425293871551e-01 + 1.20263781459649e-01 -1.15816680044401e-01 + 1.13136940952170e-01 -1.12220007869416e-01 + 1.06332983042845e-01 -1.08662489701008e-01 + 9.98554576560956e-02 -1.05123339035014e-01 + 9.36729639947835e-02 -1.01629914852298e-01 + 8.77889829403561e-02 -9.81820383630434e-02 + 8.22313494306295e-02 -9.47155808667247e-02 + 7.69114078116147e-02 -9.13308647018588e-02 + 7.18269333109061e-02 -8.80418761209455e-02 + 6.70154064102991e-02 -8.47739827365595e-02 + 6.24469306153174e-02 -8.15646647777206e-02 + 5.81057659587854e-02 -7.84140549690817e-02 + 5.40009405345228e-02 -7.52947049856435e-02 + 5.01151207789006e-02 -7.21659059076321e-02 + 4.64322700792648e-02 -6.90335942126407e-02 + 4.29462331812666e-02 -6.59671142994205e-02 + 3.96515804572136e-02 -6.29681996718810e-02 + 3.65329345743545e-02 -6.00437178811974e-02 + 3.35738970738148e-02 -5.72025031652544e-02 + 3.07754335365257e-02 -5.44358564951100e-02 + 2.81537659173496e-02 -5.17226337871633e-02 + 2.56886770890630e-02 -4.90717427799052e-02 + 2.33482991143229e-02 -4.65080355566962e-02 + 2.11432730232991e-02 -4.40159414301263e-02 + 1.91121471256101e-02 -4.15606205415437e-02 + 1.72228999311958e-02 -3.91575871889248e-02 + 1.54064395993220e-02 -3.68520424585129e-02 + 1.36928020357784e-02 -3.46229069295389e-02 + 1.21373998162167e-02 -3.24269429373621e-02 + 1.07044618156111e-02 -3.02820978142858e-02 + 9.34868730826734e-03 -2.82170700487391e-02 + 8.09806623056062e-03 -2.62111289422148e-02 + 6.96372181943001e-03 -2.42506526569285e-02 + 5.96056834155680e-03 -2.23318948971137e-02 + 5.06965708895582e-03 -2.04584451649110e-02 + 4.26820207826318e-03 -1.86422076010040e-02 + 3.54215279838966e-03 -1.68853270402674e-02 + 2.85815863780286e-03 -1.51976459649791e-02 + 2.24323664486902e-03 -1.35681174800671e-02 + 1.75728174742475e-03 -1.19752101824980e-02 + 1.34793914004162e-03 -1.04318177524506e-02 + 9.90510266959983e-04 -8.94698512072236e-03 + 6.97578703019438e-04 -7.51579339168028e-03 + 4.64357280248315e-04 -6.13612031461294e-03 + 2.88591972559368e-04 -4.81032939412014e-03 + 1.72652071928442e-04 -3.53504260318557e-03 + 9.21726822772373e-05 -2.31236956248856e-03 + 2.89749158143047e-05 -1.14152595228739e-03 + 0.00000000000000e+00 0.00000000000000e+00 + 2.89846382908482e-05 1.09904377509191e-03 + 9.25460105131971e-05 2.26825426701565e-03 + 1.77372928637046e-04 3.48749114259613e-03 + 2.94928045666597e-04 4.75871421546040e-03 + 4.43018528169673e-04 6.08403094200768e-03 + 6.38312963887756e-04 7.46056696755252e-03 + 9.47163065524872e-04 8.87928204628239e-03 + 1.36292248354851e-03 1.03385546497900e-02 + 1.83694236418441e-03 1.18499779537360e-02 + 2.40074018468558e-03 1.34014033663973e-02 + 3.05594814662641e-03 1.49976678162017e-02 + 3.77032037989221e-03 1.66497807270228e-02 + 4.57488786576987e-03 1.83443029444178e-02 + 5.51906408703589e-03 2.00632619669774e-02 + 6.56072342496301e-03 2.18246212199481e-02 + 7.69623508636216e-03 2.36337857570079e-02 + 8.95571256166709e-03 2.54702712422116e-02 + 1.03262325097732e-02 2.73482935706184e-02 + 1.17850925399475e-02 2.92850723449938e-02 + 1.33375184491728e-02 3.12822963331383e-02 + 1.49920040237809e-02 3.33377667408644e-02 + 1.67963509381930e-02 3.54114606810732e-02 + 1.87564987080519e-02 3.75086023081501e-02 + 2.08048274019325e-02 3.96894126704762e-02 + 2.29716484700822e-02 4.19312226540401e-02 + 2.53216431358212e-02 4.41765315953156e-02 + 2.78298220840403e-02 4.64577629177545e-02 + 3.04725601623169e-02 4.88011066487437e-02 + 3.32695085116736e-02 5.11918075676120e-02 + 3.62304186897929e-02 5.36280031772383e-02 + 3.93644755511771e-02 5.61022315336534e-02 + 4.26868496705988e-02 5.86057232062309e-02 + 4.61876578605174e-02 6.11553846039597e-02 + 4.98741851089849e-02 6.37532547016415e-02 + 5.37745202719990e-02 6.63631960936247e-02 + 5.78890274684652e-02 6.90003260469755e-02 + 6.22045848623571e-02 7.16867591984326e-02 + 6.67395204425100e-02 7.44058004604966e-02 + 7.15094552811985e-02 7.71467339233253e-02 + 7.65211067667525e-02 7.99024876975873e-02 + 8.17838450454122e-02 8.26301768788084e-02 + 8.73028349577319e-02 8.53481713528125e-02 + 9.30858323711997e-02 8.80783750999101e-02 + 9.91416946670507e-02 9.08176986892974e-02 + 1.05480595351981e-01 9.35548293971554e-02 + 1.12106860649107e-01 9.62797051576990e-02 + 1.19024136382428e-01 9.90174394136982e-02 + 1.26260042330622e-01 1.01725417281737e-01 + 1.33816269566989e-01 1.04399273374098e-01 + 1.41700663462267e-01 1.07033756577881e-01 + 1.49922921245669e-01 1.09617507912382e-01 + 1.58490745848084e-01 1.12140288851728e-01 + 1.67427226610566e-01 1.14558206235614e-01 + 1.76710282027346e-01 1.16962741891360e-01 + 1.86363310666109e-01 1.19272582161213e-01 + 1.96405140293252e-01 1.21436031107907e-01 + 2.06821300548881e-01 1.23525479904894e-01 + 2.17631928576255e-01 1.25464812094116e-01 + 2.28852962522468e-01 1.27193749895941e-01 + 2.40477755282815e-01 1.28758039445176e-01 + 2.52507693678930e-01 1.30101102154715e-01 + 2.64955599100463e-01 1.31171639589549e-01 + 2.77806279246518e-01 1.32075007668201e-01 + 2.91070185192249e-01 1.32646573696457e-01 + 3.04740840328737e-01 1.33041903853136e-01 + 3.18819477395129e-01 1.33195283275007e-01 + 3.33304350362167e-01 1.32986169941820e-01 + 3.48197166977535e-01 1.32632958624357e-01 + 3.63493940108890e-01 1.32044025079949e-01 + 3.79191584895447e-01 1.31162317872549e-01 + 3.95288926848852e-01 1.30062172860921e-01 + 4.11778548872039e-01 1.28686018034213e-01 + 4.28672318266481e-01 1.27234783277367e-01 + 4.45941423639317e-01 1.25432754513171e-01 + 4.63601280756515e-01 1.23542253443373e-01 + 4.81644473880432e-01 1.21300435261224e-01 + 5.00056154441041e-01 1.18664422872359e-01 + 5.18836063389421e-01 1.15815814392759e-01 + 5.37969499408613e-01 1.12707530577688e-01 + 5.57460349222905e-01 1.09422776572642e-01 + 5.77288515939648e-01 1.05906885195990e-01 + 5.97436626517306e-01 1.02120358117792e-01 + 6.17906665003925e-01 9.81468229100023e-02 + 6.38686205928774e-01 9.39865902403502e-02 + 6.59766571546815e-01 8.96723879840407e-02 + 6.81119084918578e-01 8.51320545501444e-02 + 7.02741779443877e-01 8.04384800208977e-02 + 7.24615479257981e-01 7.55830551158126e-02 + 7.46734371501449e-01 7.06203776437117e-02 + 7.69068303705288e-01 6.55004145708381e-02 + 7.91594648342087e-01 6.02131883818753e-02 + 8.14301397875068e-01 5.47976161070736e-02 + 8.37189869304468e-01 4.93502115779818e-02 + 8.60223965891098e-01 4.38110631161306e-02 + 8.83371421758982e-01 3.81398145030035e-02 + 9.06633371381850e-01 3.24408481950457e-02 + 9.29989733000046e-01 2.67257978266275e-02 + 9.53387742290786e-01 2.07144753192261e-02 + 9.76768638918538e-01 1.45035303709754e-02 + 1.00000000000000e+00 8.08144847432573e-03 diff --git a/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF17_Coords.txt b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF17_Coords.txt new file mode 100644 index 00000000..e8398cd3 --- /dev/null +++ b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF17_Coords.txt @@ -0,0 +1,208 @@ + 201 NumCoords ! The number of coordinates in the airfoil shape file (including an extra coordinate for airfoil reference). Set to zero if coordinates not included. +! ......... x-y coordinates are next if NumCoords > 0 ............. +! x-y coordinate of airfoil reference +! x/c y/c + 0.250000 0 +! coordinates of airfoil shape +! interpolation to 200 points +! x/c y/c + 1.00000000000000e+00 -5.45301418050398e-03 + 9.75817754636844e-01 -1.07014594571340e-03 + 9.51454474857096e-01 1.91024365189180e-03 + 9.26967643090702e-01 3.00968706555777e-03 + 9.02511079251701e-01 2.94654327425755e-03 + 8.78192574605997e-01 1.33458056758987e-03 + 8.54093368263713e-01 -1.40182384869508e-03 + 8.30280803054358e-01 -5.36722915654211e-03 + 8.06793858998891e-01 -1.02284409757101e-02 + 7.83681486977920e-01 -1.59512159380425e-02 + 7.60940204843493e-01 -2.22950822168370e-02 + 7.38563657479683e-01 -2.90867632401626e-02 + 7.16562339357988e-01 -3.62524846703740e-02 + 6.94907137649732e-01 -4.36064241543176e-02 + 6.73631134029173e-01 -5.11811692579687e-02 + 6.52658302378040e-01 -5.86920124341470e-02 + 6.32053668313489e-01 -6.62866061150648e-02 + 6.11762998595842e-01 -7.37633434906679e-02 + 5.91793833227140e-01 -8.11048412074493e-02 + 5.72143812615339e-01 -8.82708930236720e-02 + 5.52817394328116e-01 -9.52421061177968e-02 + 5.33788045856372e-01 -1.01905267173908e-01 + 5.15086541349180e-01 -1.08323876177549e-01 + 4.96717352144744e-01 -1.14481204108679e-01 + 4.78641616276281e-01 -1.20227783933246e-01 + 4.60893396881899e-01 -1.25639100003988e-01 + 4.43463621570381e-01 -1.30651726403441e-01 + 4.26364855167011e-01 -1.35291421458868e-01 + 4.09575905165181e-01 -1.39432097972120e-01 + 3.93110179140291e-01 -1.43077401925812e-01 + 3.76978460385483e-01 -1.46251273376598e-01 + 3.61179752938969e-01 -1.48871519397112e-01 + 3.45729101934949e-01 -1.50960869674387e-01 + 3.30642129005544e-01 -1.52550649026425e-01 + 3.15926278476078e-01 -1.53556648571138e-01 + 3.01599265716078e-01 -1.53406493492377e-01 + 2.87680819991451e-01 -1.52565505829207e-01 + 2.74185684558165e-01 -1.51262467818296e-01 + 2.61125227450442e-01 -1.49553952675144e-01 + 2.48509753994654e-01 -1.47518928364719e-01 + 2.36337378313774e-01 -1.45239165168132e-01 + 2.24609516585392e-01 -1.42744892161473e-01 + 2.13332897224055e-01 -1.40016001929494e-01 + 2.02471916601662e-01 -1.37246042052315e-01 + 1.92046415499529e-01 -1.34302336350696e-01 + 1.82017241046991e-01 -1.31316990852076e-01 + 1.72387811926573e-01 -1.28277098407418e-01 + 1.63158168703259e-01 -1.25175025059640e-01 + 1.54311116670428e-01 -1.22008726981644e-01 + 1.45810745366912e-01 -1.18882519862654e-01 + 1.37686151480707e-01 -1.15678943069290e-01 + 1.29904396960524e-01 -1.12501052056401e-01 + 1.22461453799045e-01 -1.09296875694661e-01 + 1.15336029025638e-01 -1.06110381969955e-01 + 1.08530206086421e-01 -1.02923068284723e-01 + 1.02021937517086e-01 -9.97477261452737e-02 + 9.58035794795516e-02 -9.66087731597880e-02 + 8.99025563208008e-02 -9.34345462961179e-02 + 8.42533694191495e-02 -9.03001520357529e-02 + 7.88404210406804e-02 -8.72478321301334e-02 + 7.36987958956943e-02 -8.41967679007426e-02 + 6.87979160132652e-02 -8.11907184984598e-02 + 6.41293950735861e-02 -7.82219427896279e-02 + 5.97053948052580e-02 -7.52557475365361e-02 + 5.54927030145125e-02 -7.23200756561499e-02 + 5.14882701745751e-02 -6.94055630007988e-02 + 4.76966523729130e-02 -6.65204388093482e-02 + 4.41044276154980e-02 -6.36813418052842e-02 + 4.06917094514561e-02 -6.09068675236080e-02 + 3.74540490762733e-02 -5.81886656057259e-02 + 3.43866063044132e-02 -5.55275845558965e-02 + 3.15023235573427e-02 -5.29049733067924e-02 + 2.87869138658892e-02 -5.03247145633268e-02 + 2.62138854996644e-02 -4.78100517604238e-02 + 2.37865060486491e-02 -4.53531589485433e-02 + 2.15247839409282e-02 -4.29352820557746e-02 + 1.94182671926051e-02 -4.05554813845574e-02 + 1.73965234398919e-02 -3.82405266496950e-02 + 1.54853588645235e-02 -3.59936663761455e-02 + 1.37247140912916e-02 -3.37853520929274e-02 + 1.21016771194090e-02 -3.16194081025936e-02 + 1.05781206388565e-02 -2.95197185049363e-02 + 9.16563324054632e-03 -2.74753790222862e-02 + 7.87017740303867e-03 -2.54771064952531e-02 + 6.73874368242485e-03 -2.35033804471445e-02 + 5.69708622898664e-03 -2.15868085403806e-02 + 4.77713369380707e-03 -1.97111181309851e-02 + 3.95637742176391e-03 -1.78845743446675e-02 + 3.18867965744800e-03 -1.61229116929551e-02 + 2.51755355177319e-03 -1.44093804163539e-02 + 1.97561081401136e-03 -1.27330821562174e-02 + 1.50680513040740e-03 -1.11084517063373e-02 + 1.11087123697807e-03 -9.53891013699422e-03 + 7.87187928013208e-04 -8.02095919047579e-03 + 5.40440313749341e-04 -6.55353655736207e-03 + 3.24451588791395e-04 -5.14486804718090e-03 + 1.88916042874488e-04 -3.78501062412031e-03 + 9.46340362822307e-05 -2.47910069070381e-03 + 2.95523038007147e-05 -1.22605370486567e-03 + 0.00000000000000e+00 0.00000000000000e+00 + 3.01481344622130e-05 1.17505317893727e-03 + 9.71702652511514e-05 2.42646619372459e-03 + 2.03793338171215e-04 3.72885439165868e-03 + 3.50357301196391e-04 5.08422545353897e-03 + 5.56726492329121e-04 6.49032410794411e-03 + 8.10159355539692e-04 7.94834859081885e-03 + 1.16155592002565e-03 9.45472898904353e-03 + 1.67637488199947e-03 1.09790644306452e-02 + 2.24350076193863e-03 1.25604990644086e-02 + 2.93581026563085e-03 1.41655243002384e-02 + 3.71628942355257e-03 1.58152478828471e-02 + 4.58474262640831e-03 1.75044149307111e-02 + 5.55488305863393e-03 1.92276009432552e-02 + 6.64802371618967e-03 2.09824655006495e-02 + 7.84988650655681e-03 2.27705789972541e-02 + 9.14426750365521e-03 2.46074952599354e-02 + 1.05699641486623e-02 2.64638140414759e-02 + 1.21156298219846e-02 2.83517697847890e-02 + 1.37576162529760e-02 3.02925689186482e-02 + 1.54895733386299e-02 3.22984799032679e-02 + 1.73435567726879e-02 3.43421258897796e-02 + 1.93455202749544e-02 3.64041907098984e-02 + 2.15005396192731e-02 3.84872450496868e-02 + 2.37609732142698e-02 4.06370705630654e-02 + 2.61438022753388e-02 4.28440907355414e-02 + 2.86976791253163e-02 4.50652887339507e-02 + 3.14081825116334e-02 4.73218530627499e-02 + 3.42618133903517e-02 4.96294249787890e-02 + 3.72752122579656e-02 5.19754897747939e-02 + 4.04579457665667e-02 5.43568206182997e-02 + 4.38096061596044e-02 5.67814925288692e-02 + 4.73527794655686e-02 5.92252949852968e-02 + 5.10805893305958e-02 6.17034102753216e-02 + 5.49951734742978e-02 6.42246281779437e-02 + 5.91172562090566e-02 6.67651820406855e-02 + 6.34412452148952e-02 6.93500711466022e-02 + 6.79840941864798e-02 7.19471001376835e-02 + 7.27468469458395e-02 7.45705996505986e-02 + 7.77328868720285e-02 7.72333440704537e-02 + 8.29626933019556e-02 7.98998610400721e-02 + 8.84438437146468e-02 8.25516267432993e-02 + 9.41776411888755e-02 8.52039636550780e-02 + 1.00170421380160e-01 8.78676504969935e-02 + 1.06430934474038e-01 9.05393436776120e-02 + 1.12969233548496e-01 9.32086710673799e-02 + 1.19797828219200e-01 9.58462247530667e-02 + 1.26911894255357e-01 9.84958150865328e-02 + 1.34331983632213e-01 1.01128226770770e-01 + 1.42066987117710e-01 1.03723117625941e-01 + 1.50124262102595e-01 1.06274763475707e-01 + 1.58513048529723e-01 1.08770852235264e-01 + 1.67241646522678e-01 1.11196896421823e-01 + 1.76323718493828e-01 1.13540445285679e-01 + 1.85743681389525e-01 1.15873278276396e-01 + 1.95524016824630e-01 1.18115770052045e-01 + 2.05683255342811e-01 1.20208699038275e-01 + 2.16208468120044e-01 1.22224461173209e-01 + 2.27117207800504e-01 1.24090288616604e-01 + 2.38419423158324e-01 1.25782649954125e-01 + 2.50110734150605e-01 1.27336011108803e-01 + 2.62197488700551e-01 1.28669969942400e-01 + 2.74686682065653e-01 1.29764427838693e-01 + 2.87569054903857e-01 1.30681368424973e-01 + 3.00852399367078e-01 1.31283757276969e-01 + 3.14530771437150e-01 1.31692707165930e-01 + 3.28604824690067e-01 1.31851460992892e-01 + 3.43071468150563e-01 1.31640913718290e-01 + 3.57931242815408e-01 1.31256435294713e-01 + 3.73178779264493e-01 1.30614578750586e-01 + 3.88811577543217e-01 1.29697152615801e-01 + 4.04827176697756e-01 1.28553939360805e-01 + 4.21218824620110e-01 1.27145088813715e-01 + 4.37996175755373e-01 1.25658971878768e-01 + 4.55132979373076e-01 1.23843182272296e-01 + 4.72638679585242e-01 1.21926903878881e-01 + 4.90509890590074e-01 1.19631762561332e-01 + 5.08733867924661e-01 1.16939647488128e-01 + 5.27305087603049e-01 1.14015126381095e-01 + 5.46213184288326e-01 1.10843992328087e-01 + 5.65460187911138e-01 1.07498826395060e-01 + 5.85029675577305e-01 1.03944942811554e-01 + 6.04902749493555e-01 1.00126044902967e-01 + 6.25076084848418e-01 9.60954974978452e-02 + 6.45543971739222e-01 9.18933165314899e-02 + 6.66297289512585e-01 8.75484886184110e-02 + 6.87308946494649e-01 8.29877474141992e-02 + 7.08578048914644e-01 7.82894566836472e-02 + 7.30086443256557e-01 7.34459663833689e-02 + 7.51825357054199e-01 6.84945162374382e-02 + 7.73769138587997e-01 6.34023849460844e-02 + 7.95897100069124e-01 5.81625974308282e-02 + 8.18195637696294e-01 5.28018830946166e-02 + 8.40659948231990e-01 4.73841857178122e-02 + 8.63266034014869e-01 4.19041191703725e-02 + 8.85979573720097e-01 3.62991883120328e-02 + 9.08802830149653e-01 3.06806974342369e-02 + 9.31707972602122e-01 2.50135348041367e-02 + 9.54654320230810e-01 1.88471626322655e-02 + 9.77590603702380e-01 1.23214474808323e-02 + 1.00000000000000e+00 5.52162384629112e-03 diff --git a/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF18_Coords.txt b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF18_Coords.txt new file mode 100644 index 00000000..87813ee7 --- /dev/null +++ b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF18_Coords.txt @@ -0,0 +1,208 @@ + 201 NumCoords ! The number of coordinates in the airfoil shape file (including an extra coordinate for airfoil reference). Set to zero if coordinates not included. +! ......... x-y coordinates are next if NumCoords > 0 ............. +! x-y coordinate of airfoil reference +! x/c y/c + 0.250000 0 +! coordinates of airfoil shape +! interpolation to 200 points +! x/c y/c + 1.00000000000000e+00 -2.37767599414968e-03 + 9.76446819562239e-01 1.18667276573974e-03 + 9.52930798636692e-01 3.80478847156908e-03 + 9.29282208028914e-01 5.37628501132393e-03 + 9.05615578666939e-01 6.07272680933467e-03 + 8.82032334216335e-01 5.18874855240369e-03 + 8.58617284514100e-01 3.26660678111755e-03 + 8.35440764035589e-01 2.67187094232616e-05 + 8.12556593166433e-01 -4.15650599841566e-03 + 7.90017464961696e-01 -9.25945431510779e-03 + 7.67840842437519e-01 -1.50885188225015e-02 + 7.46027726392422e-01 -2.14593261524176e-02 + 7.24592442618031e-01 -2.82974871754426e-02 + 7.03504149817637e-01 -3.53964569024539e-02 + 6.82765349116846e-01 -4.26998988823194e-02 + 6.62337893926518e-01 -5.00271216489902e-02 + 6.42248092575011e-01 -5.74239730292741e-02 + 6.22460538916900e-01 -6.47395984745764e-02 + 6.02953903187687e-01 -7.18789103015881e-02 + 5.83732605013996e-01 -7.88228152136706e-02 + 5.64800704679662e-01 -8.55519158464723e-02 + 5.46124988243235e-01 -9.19284463008494e-02 + 5.27742247208307e-01 -9.80364414989111e-02 + 5.09652486976343e-01 -1.03841306232240e-01 + 4.91835492986616e-01 -1.09243363075515e-01 + 4.74308759446067e-01 -1.14261681915081e-01 + 4.57077435404333e-01 -1.18870892627075e-01 + 4.40154051473917e-01 -1.23098817274973e-01 + 4.23530856843343e-01 -1.26854027870635e-01 + 4.07216398081170e-01 -1.30119328171116e-01 + 3.91231938614656e-01 -1.32976005720577e-01 + 3.75575699731328e-01 -1.35342726415398e-01 + 3.60263622208770e-01 -1.37261172568907e-01 + 3.45308062067250e-01 -1.38788502251440e-01 + 3.30710985565161e-01 -1.39841337156737e-01 + 3.16484027641533e-01 -1.40100625734666e-01 + 3.02640076917013e-01 -1.39862266369132e-01 + 2.89186583012941e-01 -1.39252768782004e-01 + 2.76130340586499e-01 -1.38286107582322e-01 + 2.63476265682543e-01 -1.37049216008764e-01 + 2.51223094661652e-01 -1.35572490644241e-01 + 2.39372261720154e-01 -1.33875529784685e-01 + 2.27927524364597e-01 -1.31931209492906e-01 + 2.16866171615739e-01 -1.29910205264487e-01 + 2.06201029914413e-01 -1.27692002391941e-01 + 1.95913212312204e-01 -1.25358568326782e-01 + 1.85997306093273e-01 -1.22934748923442e-01 + 1.76450637821784e-01 -1.20426052562665e-01 + 1.67269721120968e-01 -1.17795029832047e-01 + 1.58423588488400e-01 -1.15164333199127e-01 + 1.49936911969762e-01 -1.12408754691065e-01 + 1.41769123119841e-01 -1.09669875291307e-01 + 1.33937151744594e-01 -1.06851502319845e-01 + 1.26416097012572e-01 -1.04016679034228e-01 + 1.19206237571905e-01 -1.01151657303313e-01 + 1.12297037125044e-01 -9.82587192113124e-02 + 1.05667160617742e-01 -9.53856625792421e-02 + 9.93435270819619e-02 -9.24557770413018e-02 + 9.32891373053101e-02 -8.95249953967126e-02 + 8.74719354214747e-02 -8.66600851213458e-02 + 8.19240576596432e-02 -8.37764095161515e-02 + 7.66140873543626e-02 -8.09233249988340e-02 + 7.15426883354032e-02 -7.80879536266522e-02 + 6.67258789024077e-02 -7.52313564677441e-02 + 6.21109049974624e-02 -7.24930414546405e-02 + 5.77107003282204e-02 -6.98465745441758e-02 + 5.35430034534783e-02 -6.71846452282005e-02 + 4.95845561568290e-02 -6.45422361158792e-02 + 4.58099226060605e-02 -6.19523763970443e-02 + 4.22293604618921e-02 -5.93855665933846e-02 + 3.88308843695516e-02 -5.68544053787320e-02 + 3.56234006217278e-02 -5.43433098462299e-02 + 3.25999205074709e-02 -5.18499783811972e-02 + 2.97405688058144e-02 -4.93956746514801e-02 + 2.70395385980955e-02 -4.69821041730334e-02 + 2.44940212404595e-02 -4.46103096861655e-02 + 2.21201103864747e-02 -4.22591015257432e-02 + 1.98580479062668e-02 -3.99325658782353e-02 + 1.77168686887470e-02 -3.76638917235478e-02 + 1.57157807032474e-02 -3.54403779106754e-02 + 1.38676651671849e-02 -3.32484674991874e-02 + 1.21441938253155e-02 -3.11061195104619e-02 + 1.05378361076491e-02 -2.90145230640159e-02 + 9.04844929893957e-03 -2.69697346212576e-02 + 7.75683497330708e-03 -2.49283589829342e-02 + 6.52980280782892e-03 -2.29587165235158e-02 + 5.45989916249106e-03 -2.10098573697542e-02 + 4.51688987743758e-03 -1.90975789024075e-02 + 3.64156821001467e-03 -1.72448669660278e-02 + 2.89517955356030e-03 -1.54279532736546e-02 + 2.27709187814676e-03 -1.36490255771574e-02 + 1.72915425508911e-03 -1.19244153221547e-02 + 1.27964769399565e-03 -1.02506222817353e-02 + 9.12717177077437e-04 -8.62589658032073e-03 + 6.43670432858475e-04 -7.05048038051019e-03 + 3.75496964177492e-04 -5.53981424307094e-03 + 2.12451593354277e-04 -4.07587556179559e-03 + 9.85747212878459e-05 -2.66752580611053e-03 + 3.05204163981267e-05 -1.31331094969237e-03 + 0.00000000000000e+00 0.00000000000000e+00 + 3.15800516939920e-05 1.28536935659477e-03 + 1.02861345468154e-04 2.63794919245206e-03 + 2.36308992810849e-04 4.04267190102204e-03 + 4.18574204776478e-04 5.50160407333578e-03 + 6.96667127526426e-04 7.00712121949262e-03 + 1.02165107805804e-03 8.56543372145463e-03 + 1.42540966556040e-03 1.01797040162715e-02 + 2.06214142058454e-03 1.17841124321626e-02 + 2.74385305341704e-03 1.34517101595850e-02 + 3.59432216104703e-03 1.51227008126668e-02 + 4.52897284835177e-03 1.68382166645950e-02 + 5.58705383071816e-03 1.85729863183344e-02 + 6.76096524288088e-03 2.03314489250025e-02 + 8.03743675144860e-03 2.21305025010730e-02 + 9.43646227409209e-03 2.39515425026592e-02 + 1.09263641031346e-02 2.58226128735423e-02 + 1.25566270365459e-02 2.77033405353925e-02 + 1.43178449292754e-02 2.96035213537207e-02 + 1.61852054142408e-02 3.15492683526132e-02 + 1.81381119035080e-02 3.35658704424136e-02 + 2.02376177807679e-02 3.55949640883938e-02 + 2.24827884412515e-02 3.76427169254937e-02 + 2.48776366499191e-02 3.97084340106233e-02 + 2.73991082013164e-02 4.18201264039935e-02 + 3.00477787622335e-02 4.39843306813997e-02 + 3.28525738533268e-02 4.61758552907474e-02 + 3.58120783592458e-02 4.84020618976064e-02 + 3.89252554594669e-02 5.06656093643179e-02 + 4.22050404438107e-02 5.29567403882480e-02 + 4.56607724006619e-02 5.52705490464994e-02 + 4.92802379264876e-02 5.76342317329541e-02 + 5.30951492645608e-02 6.00045745431363e-02 + 5.71023305776689e-02 6.23946378850674e-02 + 6.12975848311221e-02 6.48215197669438e-02 + 6.56925727776909e-02 6.72766782487322e-02 + 7.02743714952992e-02 6.97972744317459e-02 + 7.50969486986961e-02 7.22842735310359e-02 + 8.01400765487782e-02 7.47901896085021e-02 + 8.53920774693246e-02 7.73567066055900e-02 + 9.08903676568554e-02 7.99133996484751e-02 + 9.66403183510142e-02 8.24936560307861e-02 + 1.02638479952074e-01 8.50997650283062e-02 + 1.08889440257636e-01 8.77162219327400e-02 + 1.15401817527268e-01 9.03394906080130e-02 + 1.22185516627081e-01 9.29598512750285e-02 + 1.29263118491494e-01 9.55337809970597e-02 + 1.36619374775123e-01 9.81184385458023e-02 + 1.44266139092389e-01 1.00694502173312e-01 + 1.52221162890854e-01 1.03229848289691e-01 + 1.60491203003249e-01 1.05718276956696e-01 + 1.69084936589124e-01 1.08146601356303e-01 + 1.78011398738398e-01 1.10496847084347e-01 + 1.87272650122097e-01 1.12780737463291e-01 + 1.96861105345526e-01 1.15054643125002e-01 + 2.06798117527740e-01 1.17240543617190e-01 + 2.17101851419760e-01 1.19273158884218e-01 + 2.27761275369060e-01 1.21224134069861e-01 + 2.38790761271252e-01 1.23023413411139e-01 + 2.50192886766329e-01 1.24678047176873e-01 + 2.61966061889217e-01 1.26213824812832e-01 + 2.74122740201456e-01 1.27530811823120e-01 + 2.86662746727198e-01 1.28636005140460e-01 + 2.99584123829558e-01 1.29553120390120e-01 + 3.12891391317914e-01 1.30171094917509e-01 + 3.26579260634688e-01 1.30578353143042e-01 + 3.40647672578538e-01 1.30725411590738e-01 + 3.55091880946261e-01 1.30496104164832e-01 + 3.69910990811779e-01 1.30058415062081e-01 + 3.85097931570468e-01 1.29333718130797e-01 + 4.00650923113019e-01 1.28339370562823e-01 + 4.16565921229797e-01 1.27096432683427e-01 + 4.32836992216272e-01 1.25581769969023e-01 + 4.49471067150447e-01 1.23948898925125e-01 + 4.66445046714551e-01 1.21982635824263e-01 + 4.83761025693294e-01 1.19827800217627e-01 + 5.01420577935565e-01 1.17377223728947e-01 + 5.19413548507589e-01 1.14623284584942e-01 + 5.37727933854121e-01 1.11613572571558e-01 + 5.56358704938187e-01 1.08373804583437e-01 + 5.75305606530518e-01 1.04960916116859e-01 + 5.94556737334723e-01 1.01364726003763e-01 + 6.14091323042302e-01 9.75131887392979e-02 + 6.33899505217000e-01 9.34229607669790e-02 + 6.53983838820148e-01 8.91779646388802e-02 + 6.74334658110115e-01 8.48016108581404e-02 + 6.94926822402831e-01 8.02237288972718e-02 + 7.15760758260989e-01 7.55262386365138e-02 + 7.36819570375329e-01 7.07027052448581e-02 + 7.58090843885297e-01 6.57693336437398e-02 + 7.79554466153280e-01 6.07141783168916e-02 + 8.01192136630880e-01 5.55343914786427e-02 + 8.22988286990664e-01 5.02420511779286e-02 + 8.44930581805388e-01 4.48622679286764e-02 + 8.67009913774751e-01 3.94519467741740e-02 + 8.89189431928600e-01 3.39266635119004e-02 + 9.11472787704912e-01 2.84011627846064e-02 + 9.33822613763039e-01 2.27894520303026e-02 + 9.56213100416208e-01 1.64551756972167e-02 + 9.78602197523542e-01 9.57262213328838e-03 + 1.00000000000000e+00 2.38801343162379e-03 diff --git a/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF19_Coords.txt b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF19_Coords.txt new file mode 100644 index 00000000..ffdbb0d3 --- /dev/null +++ b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF19_Coords.txt @@ -0,0 +1,208 @@ + 201 NumCoords ! The number of coordinates in the airfoil shape file (including an extra coordinate for airfoil reference). Set to zero if coordinates not included. +! ......... x-y coordinates are next if NumCoords > 0 ............. +! x-y coordinate of airfoil reference +! x/c y/c + 0.250000 0 +! coordinates of airfoil shape +! interpolation to 200 points +! x/c y/c + 1.00000000000000e+00 -3.68399389995869e-04 + 9.76857008771838e-01 2.66731162732446e-03 + 9.53893452982560e-01 5.08228579069216e-03 + 9.30791447416205e-01 6.92341917618193e-03 + 9.07639904153749e-01 8.15655615709104e-03 + 8.84536094791801e-01 7.92264904224889e-03 + 8.61567157501965e-01 6.68493011849853e-03 + 8.38805377497580e-01 4.13452337383163e-03 + 8.16314251999226e-01 5.97915678772836e-04 + 7.94148914190988e-01 -3.89604633156816e-03 + 7.72340484630481e-01 -9.19436001700492e-03 + 7.50894760627057e-01 -1.51087969475548e-02 + 7.29828566229855e-01 -2.15579885729289e-02 + 7.09109933074187e-01 -2.83298125964794e-02 + 6.88721421877958e-01 -3.53036886233563e-02 + 6.68649585846097e-01 -4.23737071775973e-02 + 6.48895487241817e-01 -4.95075181376893e-02 + 6.29435996348719e-01 -5.65920614554448e-02 + 6.10230958530276e-01 -6.34793436033746e-02 + 5.91289213882662e-01 -7.01620809295741e-02 + 5.72614563636092e-01 -7.66179006666135e-02 + 5.54169437142293e-01 -8.26972170912674e-02 + 5.35994549591891e-01 -8.84922462055237e-02 + 5.18086994319589e-01 -9.39558134124888e-02 + 5.00438716025881e-01 -9.90271375426639e-02 + 4.83056404950572e-01 -1.03683276789266e-01 + 4.65954483401666e-01 -1.07928967059445e-01 + 4.49145459682817e-01 -1.11790741247148e-01 + 4.32630347798518e-01 -1.15206880360019e-01 + 4.16414524640443e-01 -1.18147531896552e-01 + 4.00526087330994e-01 -1.20731141532653e-01 + 3.84962746755882e-01 -1.22881481336833e-01 + 3.69741027707524e-01 -1.24652317902417e-01 + 3.54871156825438e-01 -1.26116996793257e-01 + 3.40351528329817e-01 -1.27196549851457e-01 + 3.26189812343215e-01 -1.27831505011485e-01 + 3.12394436962796e-01 -1.28135125466097e-01 + 2.98968095909353e-01 -1.28135971204913e-01 + 2.85914601715587e-01 -1.27815225606007e-01 + 2.73235356281731e-01 -1.27263263044964e-01 + 2.60929501705741e-01 -1.26470643765030e-01 + 2.48998483933274e-01 -1.25450275622875e-01 + 2.37444123255251e-01 -1.24173437692176e-01 + 2.26252115496294e-01 -1.22785796310441e-01 + 2.15430713313732e-01 -1.21185221143952e-01 + 2.04974244392958e-01 -1.19412349992892e-01 + 1.94871537400587e-01 -1.17520737121037e-01 + 1.85118149204518e-01 -1.15527561249974e-01 + 1.75719532106264e-01 -1.13369650618129e-01 + 1.66647941717989e-01 -1.11180617405335e-01 + 1.57925164945130e-01 -1.08833224985739e-01 + 1.49505657854053e-01 -1.06498338398972e-01 + 1.41420016040231e-01 -1.04044619127328e-01 + 1.33640986123984e-01 -1.01549904565748e-01 + 1.26167669913614e-01 -9.90049839819346e-02 + 1.18997037103723e-01 -9.64015758401574e-02 + 1.12098825120963e-01 -9.38093390294696e-02 + 1.05499623500676e-01 -9.11479135507931e-02 + 9.91810164066800e-02 -8.84508376192239e-02 + 9.31002162531755e-02 -8.58102997394773e-02 + 8.72874366774390e-02 -8.31377449587737e-02 + 8.17107141333520e-02 -8.04892138256785e-02 + 7.63766137075373e-02 -7.78449994839546e-02 + 7.13036684223055e-02 -7.51579825759147e-02 + 6.64263817165701e-02 -7.26018598042667e-02 + 6.17681093546461e-02 -7.01301752855594e-02 + 5.73551856813564e-02 -6.76137828225569e-02 + 5.31579386553926e-02 -6.50996263715978e-02 + 4.91473139049403e-02 -6.26301467575107e-02 + 4.53431586149581e-02 -6.01620539688450e-02 + 4.17288283387378e-02 -5.77156085161925e-02 + 3.83105975635588e-02 -5.52772281229456e-02 + 3.50862364938885e-02 -5.28405786158374e-02 + 3.20401842818251e-02 -5.04256327322228e-02 + 2.91607168682362e-02 -4.80403110926350e-02 + 2.64301474681941e-02 -4.56985651824556e-02 + 2.38818791314998e-02 -4.33660011061808e-02 + 2.14869187314351e-02 -4.10319139878904e-02 + 1.92210251217201e-02 -3.87490158345328e-02 + 1.70866204440822e-02 -3.65155909889459e-02 + 1.51088856667703e-02 -3.43067488660566e-02 + 1.32677571342121e-02 -3.21365849699287e-02 + 1.15452964783661e-02 -3.00141740624550e-02 + 9.93785550135011e-03 -2.79390543678102e-02 + 8.53733963199581e-03 -2.58535670157040e-02 + 7.18971942545551e-03 -2.38493192760235e-02 + 6.01408812501931e-03 -2.18527495788709e-02 + 4.98035831239796e-03 -1.98845668008135e-02 + 4.02595523871816e-03 -1.79724851036912e-02 + 3.21872354864114e-03 -1.60881596868680e-02 + 2.53699895316356e-03 -1.42423112550335e-02 + 1.92596838800982e-03 -1.24525079880165e-02 + 1.42958340648342e-03 -1.07107365453782e-02 + 1.02402066973875e-03 -9.01638710474725e-03 + 7.29515457680132e-04 -7.37055242509973e-03 + 4.22134415351005e-04 -5.79337753090592e-03 + 2.34596295265449e-04 -4.26157143671717e-03 + 1.02904903665998e-04 -2.78642458580164e-03 + 3.16491042877115e-05 -1.36624202526467e-03 + 0.00000000000000e+00 0.00000000000000e+00 + 3.25137502262144e-05 1.36126836315680e-03 + 1.06572281496749e-04 2.77981521878749e-03 + 2.57511209208200e-04 4.25126635289481e-03 + 4.63055841935316e-04 5.77772676962173e-03 + 7.87917070457592e-04 7.34807091678409e-03 + 1.15955675201046e-03 8.97177740531396e-03 + 1.59745861466139e-03 1.06563985806526e-02 + 2.31368504535807e-03 1.23130195245482e-02 + 3.07011367084607e-03 1.40368009141934e-02 + 4.02371261501702e-03 1.57508050961990e-02 + 5.05889266777718e-03 1.75092215738978e-02 + 6.24062268199277e-03 1.92737269450562e-02 + 7.54740536677814e-03 2.10551920713005e-02 + 8.94341992064346e-03 2.28830596185717e-02 + 1.04710077300238e-02 2.47255697363701e-02 + 1.20884012253117e-02 2.66189106966348e-02 + 1.38520540216189e-02 2.85155544569944e-02 + 1.57538252832241e-02 3.04237067797815e-02 + 1.77681435802238e-02 3.23726800924697e-02 + 1.98651227360326e-02 3.43962534435927e-02 + 2.21247244203388e-02 3.64158580641648e-02 + 2.45284811789666e-02 3.84542786038096e-02 + 2.70797126293869e-02 4.05086907274035e-02 + 2.97713970613449e-02 4.25955179697784e-02 + 3.25934127100249e-02 4.47318036374387e-02 + 3.55618220018821e-02 4.69039793632072e-02 + 3.86836906268538e-02 4.91103908591560e-02 + 4.19661079042882e-02 5.13452316640530e-02 + 4.54195931002610e-02 5.36005424735060e-02 + 4.90533369175556e-02 5.58703224938828e-02 + 5.28474279411799e-02 5.81942364368840e-02 + 5.68395292704747e-02 6.05166790176710e-02 + 6.10288780337881e-02 6.28493270475509e-02 + 6.54071465451169e-02 6.52146960136306e-02 + 6.99800855562079e-02 6.76141714293276e-02 + 7.47299921393616e-02 7.00928446530985e-02 + 7.97349694380070e-02 7.25080974627385e-02 + 8.49609191753247e-02 7.49373418732565e-02 + 9.03863431014392e-02 7.74411126435351e-02 + 9.60597012920897e-02 7.99261936987175e-02 + 1.01984926382490e-01 8.24310363129346e-02 + 1.08155469732798e-01 8.49653756451838e-02 + 1.14574779429234e-01 8.75131666717048e-02 + 1.21251387707475e-01 9.00699473431387e-02 + 1.28195102790333e-01 9.26263962880819e-02 + 1.35435072734491e-01 9.51218497619305e-02 + 1.42949252027610e-01 9.76304862957753e-02 + 1.50743822415266e-01 1.00143225443294e-01 + 1.58842313055751e-01 1.02614343572487e-01 + 1.67251089180853e-01 1.05037311736569e-01 + 1.75978460980627e-01 1.07398386544002e-01 + 1.85033942788463e-01 1.09676903953931e-01 + 1.94412030223010e-01 1.11906753065792e-01 + 2.04110352857490e-01 1.14127897662318e-01 + 2.14149527961947e-01 1.16265117747636e-01 + 2.24547481767990e-01 1.18248683868967e-01 + 2.35294419696161e-01 1.20148148534840e-01 + 2.46402639597428e-01 1.21897385397864e-01 + 2.57869912676765e-01 1.23526834665610e-01 + 2.69696468272276e-01 1.25053947368743e-01 + 2.81898741199044e-01 1.26364975026619e-01 + 2.94471881045941e-01 1.27487690783284e-01 + 3.07418691339119e-01 1.28414307575311e-01 + 3.20741558118385e-01 1.29056641751163e-01 + 3.34435620226968e-01 1.29474248027250e-01 + 3.48500353688656e-01 1.29624393334326e-01 + 3.62929932989329e-01 1.29396296126059e-01 + 3.77722526892471e-01 1.28930828553253e-01 + 3.92869955516012e-01 1.28156113952553e-01 + 4.08370908134265e-01 1.27114694902152e-01 + 4.24220308156953e-01 1.25806236875891e-01 + 4.40412755529192e-01 1.24220713149001e-01 + 4.56953405525328e-01 1.22475796836960e-01 + 4.73821213743432e-01 1.20395388434913e-01 + 4.91013482752600e-01 1.18050411789495e-01 + 5.08535020400488e-01 1.15490643648704e-01 + 5.26377360286358e-01 1.12710340482628e-01 + 5.44524273775329e-01 1.09660985096774e-01 + 5.62974211427790e-01 1.06393299108221e-01 + 5.81725427948974e-01 1.02949051041186e-01 + 6.00768970403698e-01 9.93338710397741e-02 + 6.20082840879561e-01 9.54749572480719e-02 + 6.39652920613148e-01 9.13660653707297e-02 + 6.59487153767914e-01 8.71101696164325e-02 + 6.79575519171002e-01 8.27251675441617e-02 + 6.99894148304263e-01 7.81515132973927e-02 + 7.20444328669405e-01 7.34673024705215e-02 + 7.41209985385736e-01 6.86669596077010e-02 + 7.62176328526465e-01 6.37536068656100e-02 + 7.83326857277745e-01 5.87278224664763e-02 + 8.04644827719480e-01 5.35902846761059e-02 + 8.26113390531774e-01 4.83441901136536e-02 + 8.47715298834171e-01 4.29917435480749e-02 + 8.69451154762037e-01 3.76211700207279e-02 + 8.91282457860132e-01 3.21440170875230e-02 + 9.13213765042928e-01 2.66674634778728e-02 + 9.35201490491600e-01 2.10851818173222e-02 + 9.57229521434730e-01 1.46843783125432e-02 + 9.79261819214701e-01 7.64883901865307e-03 + 1.00000000000000e+00 3.48671814865888e-04 diff --git a/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF20_Coords.txt b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF20_Coords.txt new file mode 100644 index 00000000..8e86a6c9 --- /dev/null +++ b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF20_Coords.txt @@ -0,0 +1,208 @@ + 201 NumCoords ! The number of coordinates in the airfoil shape file (including an extra coordinate for airfoil reference). Set to zero if coordinates not included. +! ......... x-y coordinates are next if NumCoords > 0 ............. +! x-y coordinate of airfoil reference +! x/c y/c + 0.250000 0 +! coordinates of airfoil shape +! interpolation to 200 points +! x/c y/c + 1.00000000000000e+00 -1.16970450232154e-05 + 9.76925950475657e-01 2.89849629928081e-03 + 9.54056302293072e-01 5.27987438372875e-03 + 9.31048128850624e-01 7.19864995910977e-03 + 9.07985124166376e-01 8.59432633354728e-03 + 8.84963341017396e-01 8.76245996738773e-03 + 8.62070108500804e-01 7.89821744156301e-03 + 8.39377957233181e-01 5.82757272129634e-03 + 8.16952105741759e-01 2.74131006023888e-03 + 7.94848134812973e-01 -1.31047187114084e-03 + 7.73099762468629e-01 -6.19594038201392e-03 + 7.51713796559463e-01 -1.17316935887704e-02 + 7.30707465507159e-01 -1.78243181962159e-02 + 7.10048880246723e-01 -2.42736757420121e-02 + 6.89717065485909e-01 -3.09377224920066e-02 + 6.69703185975444e-01 -3.77351051006435e-02 + 6.50003630817286e-01 -4.46004260244532e-02 + 6.30597616366455e-01 -5.14349380887498e-02 + 6.11441818070351e-01 -5.80781149510869e-02 + 5.92545822192135e-01 -6.45215136200802e-02 + 5.73913326684091e-01 -7.07373461559128e-02 + 5.55506287086248e-01 -7.65813023757692e-02 + 5.37365867311171e-01 -8.21381752489661e-02 + 5.19488675136997e-01 -8.73572229383648e-02 + 5.01868935197649e-01 -9.21948826265366e-02 + 4.84511382435821e-01 -9.66125856407465e-02 + 4.67432104979211e-01 -1.00628904032081e-01 + 4.50643532673488e-01 -1.04265668268842e-01 + 4.34148314472208e-01 -1.07478023174613e-01 + 4.17951273380630e-01 -1.10235646319524e-01 + 4.02081583043242e-01 -1.12662589853757e-01 + 3.86536904904201e-01 -1.14691181363898e-01 + 3.71333778363175e-01 -1.16376698317397e-01 + 3.56481987324237e-01 -1.17794019293702e-01 + 3.41979279301955e-01 -1.18871441512321e-01 + 3.27832555060862e-01 -1.19600488549061e-01 + 3.14049364730407e-01 -1.20059113518256e-01 + 3.00631508155208e-01 -1.20254220188729e-01 + 2.87582216544618e-01 -1.20159958866052e-01 + 2.74902221193761e-01 -1.19865036371322e-01 + 2.62590720444375e-01 -1.19348842067133e-01 + 2.50649124402496e-01 -1.18621135823199e-01 + 2.39078845345792e-01 -1.17656533028436e-01 + 2.27867184439070e-01 -1.16582394562078e-01 + 2.17021456811297e-01 -1.15308380050123e-01 + 2.06538387308884e-01 -1.13853615562753e-01 + 1.96405791960340e-01 -1.12282176086080e-01 + 1.86618882329224e-01 -1.10617167094150e-01 + 1.77184649555781e-01 -1.08781185951076e-01 + 1.68076082704334e-01 -1.06908773866295e-01 + 1.59314215217802e-01 -1.04873638045081e-01 + 1.50852862448295e-01 -1.02861593237538e-01 + 1.42724842088730e-01 -1.00718365786054e-01 + 1.34902608040035e-01 -9.85287421796948e-02 + 1.27384992592018e-01 -9.62861825827909e-02 + 1.20170299874457e-01 -9.39710611432170e-02 + 1.13226789857415e-01 -9.16709983326127e-02 + 1.06580720474888e-01 -8.93032875865484e-02 + 1.00217178769272e-01 -8.68749312381822e-02 + 9.40916537592124e-02 -8.45028367434999e-02 + 8.82337163668553e-02 -8.20944117938331e-02 + 8.26115051483221e-02 -7.97126340550203e-02 + 7.72312330966435e-02 -7.73288341051596e-02 + 7.21130677350178e-02 -7.48833638768388e-02 + 6.71894736753951e-02 -7.24763209375136e-02 + 6.24856412277135e-02 -7.00416636170101e-02 + 5.80294161668677e-02 -6.75572914548322e-02 + 5.37899973283964e-02 -6.50720675769313e-02 + 4.97376985419173e-02 -6.26297954371682e-02 + 4.58940560730263e-02 -6.01849905424522e-02 + 4.22416037500420e-02 -5.77591819336826e-02 + 3.87861465552347e-02 -5.53392550403537e-02 + 3.55262959996525e-02 -5.29181938435960e-02 + 3.24472582872532e-02 -5.05155931301242e-02 + 2.95362641509762e-02 -4.81404755119313e-02 + 2.67729953169852e-02 -4.58090684459152e-02 + 2.41939083904648e-02 -4.34848129849921e-02 + 2.18141572031663e-02 -4.11543813853988e-02 + 1.95673854713824e-02 -3.88737506338495e-02 + 1.74477564779088e-02 -3.66431614312941e-02 + 1.54752345352323e-02 -3.44358303125963e-02 + 1.36342551938651e-02 -3.22650844102067e-02 + 1.19084234941661e-02 -3.01413804853732e-02 + 1.02942941011661e-02 -2.80648529097022e-02 + 8.86743811777817e-03 -2.59756933328882e-02 + 7.49856900534070e-03 -2.39690434637317e-02 + 6.29098663294263e-03 -2.19677989083217e-02 + 5.22308841935517e-03 -1.99933475331875e-02 + 4.24008866088351e-03 -1.80740827427679e-02 + 3.40280642281631e-03 -1.61810689964114e-02 + 2.68688998868729e-03 -1.43265021403969e-02 + 2.04591034039661e-03 -1.25280222785356e-02 + 1.52162287314027e-03 -1.07769333035290e-02 + 1.09208473544427e-03 -9.07280332309622e-03 + 7.75103994536751e-04 -7.41691607941299e-03 + 4.52353374589913e-04 -5.83014500820004e-03 + 2.49723979775574e-04 -4.28843531366952e-03 + 1.06661955669598e-04 -2.80345353766615e-03 + 3.27195725030880e-05 -1.37348955310638e-03 + 0.00000000000000e+00 0.00000000000000e+00 + 3.26413884329373e-05 1.37318323731147e-03 + 1.07225011317394e-04 2.80153107572479e-03 + 2.61262892040196e-04 4.28285015690166e-03 + 4.70931448264386e-04 5.81923659176159e-03 + 8.04058189317705e-04 7.39899934408296e-03 + 1.18395464357889e-03 9.03211811477640e-03 + 1.62790475131778e-03 1.07268695231018e-02 + 2.35805156291858e-03 1.23907220018351e-02 + 3.12729867551767e-03 1.41221855611746e-02 + 4.09811443518625e-03 1.58417552692127e-02 + 5.15013525889198e-03 1.76056029553215e-02 + 6.35251451470470e-03 1.93733209765600e-02 + 7.68136628992783e-03 2.11568889489349e-02 + 9.09705641338774e-03 2.29878091550079e-02 + 1.06457219627370e-02 2.48321471768241e-02 + 1.22840569946196e-02 2.67273324555485e-02 + 1.40693975554630e-02 2.86248786440320e-02 + 1.59938671904845e-02 3.05326851588142e-02 + 1.80320179344073e-02 3.24804018390111e-02 + 2.01525184247463e-02 3.45030950602257e-02 + 2.24382250539517e-02 3.65190950131922e-02 + 2.48676010790424e-02 3.85540869978262e-02 + 2.74438995195706e-02 4.06048186992883e-02 + 3.01630613080321e-02 4.26855478409807e-02 + 3.30131439394830e-02 4.48150556811931e-02 + 3.60078117153417e-02 4.69819958893802e-02 + 3.91555926213345e-02 4.91831364532758e-02 + 4.24650818770967e-02 5.14111490804253e-02 + 4.59463399533206e-02 5.36584113782445e-02 + 4.96085019195341e-02 5.59187875417100e-02 + 5.34304029583731e-02 5.82339756158755e-02 + 5.74506053673470e-02 6.05464382961678e-02 + 6.16688433559805e-02 6.28675145510649e-02 + 6.60761101690652e-02 6.52205906481849e-02 + 7.06771229650270e-02 6.76087786085493e-02 + 7.54534564656442e-02 7.00783385211843e-02 + 8.04871181124642e-02 7.24796963744080e-02 + 8.57417937708899e-02 7.48942120614805e-02 + 9.11943707542743e-02 7.73854695174959e-02 + 9.68950720892806e-02 7.98566713262581e-02 + 1.02847573387230e-01 8.22876079010535e-02 + 1.09044858215908e-01 8.47210179791181e-02 + 1.15490222891971e-01 8.71750070246340e-02 + 1.22192184613505e-01 8.96434844224979e-02 + 1.29160511286559e-01 9.21174420433711e-02 + 1.36425397154230e-01 9.45156825723323e-02 + 1.43963785764342e-01 9.69333711278718e-02 + 1.51780847657248e-01 9.93726343552587e-02 + 1.59901053759045e-01 1.01772022005663e-01 + 1.68330718517798e-01 1.04124856132688e-01 + 1.77078093160315e-01 1.06417242140794e-01 + 1.86152768336554e-01 1.08626721316434e-01 + 1.95547957086479e-01 1.10808018380726e-01 + 2.05262344651788e-01 1.12982949744755e-01 + 2.15316288411784e-01 1.15080703683943e-01 + 2.25727640430810e-01 1.17028842247463e-01 + 2.36486953294469e-01 1.18893468221244e-01 + 2.47606103597236e-01 1.20613966312300e-01 + 2.59082067962401e-01 1.22236590592394e-01 + 2.70915428466803e-01 1.23770388922269e-01 + 2.83123302721779e-01 1.25093790952213e-01 + 2.95700040272605e-01 1.26248167564620e-01 + 3.08649339579229e-01 1.27202204411106e-01 + 3.21973207911371e-01 1.27886002490200e-01 + 3.35666915940575e-01 1.28336009455904e-01 + 3.49729856148137e-01 1.28515938919406e-01 + 3.64156044605897e-01 1.28322082434802e-01 + 3.78943465936109e-01 1.27872557734258e-01 + 3.94083763263825e-01 1.27105654197604e-01 + 4.09575696342703e-01 1.26076864381629e-01 + 4.25414011369775e-01 1.24776753517338e-01 + 4.41593423933488e-01 1.23203803654028e-01 + 4.58118698550793e-01 1.21453065442532e-01 + 4.74969289264106e-01 1.19379481227578e-01 + 4.92141581296370e-01 1.17024136753557e-01 + 5.09640928459442e-01 1.14468473774205e-01 + 5.27459181191729e-01 1.11706370002499e-01 + 5.45579400762510e-01 1.08675938318902e-01 + 5.64000646601103e-01 1.05430671339811e-01 + 5.82720846933108e-01 1.02001576810010e-01 + 6.01731586141294e-01 9.83969151548686e-02 + 6.21010755973352e-01 9.45591973944104e-02 + 6.40543478738464e-01 9.04796724759952e-02 + 6.60338537645302e-01 8.62499884007561e-02 + 6.80385825453853e-01 8.18833516289867e-02 + 7.00661796733097e-01 7.73360839181257e-02 + 7.21167806331622e-01 7.26753969763489e-02 + 7.41887916488567e-01 6.78960039061239e-02 + 7.62806892564257e-01 6.29998067215964e-02 + 7.83908861634844e-01 5.79878832722068e-02 + 8.05177351436274e-01 5.28629172742288e-02 + 8.26595261100184e-01 4.76276642630319e-02 + 8.48144449629654e-01 4.22843337759070e-02 + 8.69827140629476e-01 3.69111819966000e-02 + 8.91604637206406e-01 3.14360883953754e-02 + 9.13481489167149e-01 2.59485561418769e-02 + 9.35413129302637e-01 2.03601258502341e-02 + 9.57385180896840e-01 1.40200210251241e-02 + 9.79362661611973e-01 7.10265085432084e-03 + 1.00000000000000e+00 -1.07577592503420e-05 diff --git a/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF21_Coords.txt b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF21_Coords.txt new file mode 100644 index 00000000..388e7950 --- /dev/null +++ b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF21_Coords.txt @@ -0,0 +1,208 @@ + 201 NumCoords ! The number of coordinates in the airfoil shape file (including an extra coordinate for airfoil reference). Set to zero if coordinates not included. +! ......... x-y coordinates are next if NumCoords > 0 ............. +! x-y coordinate of airfoil reference +! x/c y/c + 0.250000 0 +! coordinates of airfoil shape +! interpolation to 200 points +! x/c y/c + 1.00000000000000e+00 -2.84740725711342e-05 + 9.76865338872185e-01 2.85428304137865e-03 + 9.53929219800446e-01 5.24327408174464e-03 + 9.30868587354945e-01 7.20751732930949e-03 + 9.07757786371386e-01 8.68022664963385e-03 + 8.84685981963589e-01 9.16779767337892e-03 + 8.61737273650503e-01 8.59878745573448e-03 + 8.38982716451081e-01 6.97032631101525e-03 + 8.16487465310072e-01 4.27790070293695e-03 + 7.94307280144394e-01 5.98958387499667e-04 + 7.72478209244049e-01 -3.92421216988763e-03 + 7.51009294443888e-01 -9.11447969158894e-03 + 7.29917171589636e-01 -1.48652160246661e-02 + 7.09173987466613e-01 -2.09915209310793e-02 + 6.88759055777041e-01 -2.73426738600162e-02 + 6.68666517410726e-01 -3.38483930358717e-02 + 6.48890300856279e-01 -4.04237940323079e-02 + 6.29411879426884e-01 -4.69774888101651e-02 + 6.10190624345359e-01 -5.33527496658855e-02 + 5.91235514841636e-01 -5.95364517406264e-02 + 5.72549427006805e-01 -6.54947690043992e-02 + 5.54098681203993e-01 -7.10990749251103e-02 + 5.35920827161821e-01 -7.64189417500869e-02 + 5.18012958869965e-01 -8.14046707993908e-02 + 5.00370906490186e-01 -8.60216565775983e-02 + 4.82998993642838e-01 -9.02272377996711e-02 + 4.65913482233682e-01 -9.40474533539546e-02 + 4.49125729712078e-01 -9.74967264248575e-02 + 4.32639419880572e-01 -1.00542965307158e-01 + 4.16459539589475e-01 -1.03161374243716e-01 + 4.00613215473433e-01 -1.05466420900906e-01 + 3.85098707684728e-01 -1.07402177176065e-01 + 3.69931266330609e-01 -1.09020571824359e-01 + 3.55119768331056e-01 -1.10391209715929e-01 + 3.40661821755905e-01 -1.11451999694907e-01 + 3.26563430473896e-01 -1.12194090288857e-01 + 3.12830956759217e-01 -1.12692769163857e-01 + 2.99465542002860e-01 -1.12952761784846e-01 + 2.86469704616211e-01 -1.12949992221423e-01 + 2.73843543674708e-01 -1.12766407873851e-01 + 2.61586025508254e-01 -1.12380265536283e-01 + 2.49698014015215e-01 -1.11799275824114e-01 + 2.38180021002129e-01 -1.11005012677545e-01 + 2.27020875450809e-01 -1.10103654156307e-01 + 2.16226137874301e-01 -1.09019236030612e-01 + 2.05793116599237e-01 -1.07760935076377e-01 + 1.95709833948425e-01 -1.06391330139806e-01 + 1.85971073779880e-01 -1.04935019609158e-01 + 1.76583031796272e-01 -1.03315378553033e-01 + 1.67520981485238e-01 -1.01654758321660e-01 + 1.58802515906259e-01 -9.98409591053214e-02 + 1.50385000970262e-01 -9.80499859448751e-02 + 1.42298158727063e-01 -9.61306196719593e-02 + 1.34516269147850e-01 -9.41634136087469e-02 + 1.27037305703638e-01 -9.21442045117529e-02 + 1.19859512781939e-01 -9.00492381147093e-02 + 1.12952800949352e-01 -8.79682875564088e-02 + 1.06339499636755e-01 -8.58264580885655e-02 + 1.00007414389900e-01 -8.36143627290609e-02 + 9.39147764330701e-02 -8.14516604635932e-02 + 8.80868393032252e-02 -7.92537536059723e-02 + 8.24946159428780e-02 -7.70801723815972e-02 + 7.71274250919293e-02 -7.49012538073132e-02 + 7.20190535116052e-02 -7.26564811445412e-02 + 6.71057079852937e-02 -7.03934414720974e-02 + 6.24118140095744e-02 -6.80431207723954e-02 + 5.79644757418812e-02 -6.56460890316721e-02 + 5.37333540900433e-02 -6.32481286299431e-02 + 4.96893756299879e-02 -6.08884959776765e-02 + 4.58534457561426e-02 -5.85255201649711e-02 + 4.22083319889390e-02 -5.61793213837462e-02 + 3.87596121937182e-02 -5.38383821901660e-02 + 3.55057922281837e-02 -5.14962236665323e-02 + 3.24322743559543e-02 -4.91703134749231e-02 + 2.95264783129621e-02 -4.68695823371802e-02 + 2.67683318695932e-02 -4.46098816905116e-02 + 2.41934701367245e-02 -4.23573844305122e-02 + 2.18548607049960e-02 -4.00989773901928e-02 + 1.96524338700715e-02 -3.78875178579182e-02 + 1.75755260431319e-02 -3.57232070150690e-02 + 1.56358377059865e-02 -3.35811088781324e-02 + 1.38207984844720e-02 -3.14734077737011e-02 + 1.21180061661380e-02 -2.94102107211683e-02 + 1.05254874189780e-02 -2.73912953793136e-02 + 9.09360929036987e-03 -2.53625298476404e-02 + 7.72181822309867e-03 -2.34101512080760e-02 + 6.49763138245874e-03 -2.14641052056444e-02 + 5.40871842169344e-03 -1.95429445805207e-02 + 4.40961919998241e-03 -1.76727016085954e-02 + 3.55040219006997e-03 -1.58276863888619e-02 + 2.80808183134115e-03 -1.40194239937278e-02 + 2.14649703528823e-03 -1.22634144788593e-02 + 1.59920737776881e-03 -1.05527195276620e-02 + 1.14930375044154e-03 -8.88654178716626e-03 + 8.10231534512569e-04 -7.26673074294147e-03 + 4.78895883677518e-04 -5.71256790934727e-03 + 2.63639401109400e-04 -4.20252872193405e-03 + 1.11557989496940e-04 -2.74745794723513e-03 + 3.44756369415605e-05 -1.34604561592499e-03 + 0.00000000000000e+00 0.00000000000000e+00 + 3.20816693922806e-05 1.34573179197360e-03 + 1.07094538044363e-04 2.74581135191723e-03 + 2.61023002477552e-04 4.19787122797409e-03 + 4.70744609715971e-04 5.70378084563639e-03 + 8.02668778110153e-04 7.25269694625556e-03 + 1.18211679499553e-03 8.85342213515878e-03 + 1.62613136894154e-03 1.05133892427942e-02 + 2.35095850098151e-03 1.21472955138763e-02 + 3.11291707163376e-03 1.38451043913963e-02 + 4.06681615370234e-03 1.55343607101053e-02 + 5.10318321837548e-03 1.72662509388141e-02 + 6.28537915014080e-03 1.90038719565046e-02 + 7.59081076018542e-03 2.07586526711072e-02 + 8.98284133346192e-03 2.25595390649685e-02 + 1.05048772029216e-02 2.43750659231944e-02 + 1.21173705320911e-02 2.62396209517460e-02 + 1.38724687721741e-02 2.81092919141236e-02 + 1.57628531446385e-02 2.99916503138032e-02 + 1.77668024925910e-02 3.19129888938685e-02 + 1.98560304119069e-02 3.39051089397272e-02 + 2.21065209505667e-02 3.58935725801445e-02 + 2.44975644102754e-02 3.79031615747998e-02 + 2.70332347408878e-02 3.99299291146165e-02 + 2.97109628466766e-02 4.19867024992787e-02 + 3.25200587654925e-02 4.40903080891470e-02 + 3.54726867654753e-02 4.62315479726106e-02 + 3.85766530005811e-02 4.84076241040826e-02 + 4.18413693987001e-02 5.06110330462258e-02 + 4.52764942398936e-02 5.28343865988492e-02 + 4.88907425761762e-02 5.50724163659514e-02 + 5.26646691476036e-02 5.73640816538310e-02 + 5.66345029639527e-02 5.96558451069643e-02 + 6.08009395375298e-02 6.19577340085226e-02 + 6.51558010698599e-02 6.42917617552471e-02 + 6.97040980071108e-02 6.66604081412036e-02 + 7.44292782322818e-02 6.91063981945018e-02 + 7.94075911539318e-02 7.14919169255233e-02 + 8.46064336120551e-02 7.38912356977943e-02 + 9.00046646171667e-02 7.63634375717562e-02 + 9.56495329755105e-02 7.88186816028507e-02 + 1.01544707534728e-01 8.12061081549737e-02 + 1.07684393957011e-01 8.35823621854077e-02 + 1.14072629815357e-01 8.59820974163730e-02 + 1.20717936678019e-01 8.83984296232361e-02 + 1.27629750106332e-01 9.08236951338500e-02 + 1.34836465041941e-01 9.31733181108972e-02 + 1.42317922535003e-01 9.55435716133629e-02 + 1.50079297300981e-01 9.79421782603361e-02 + 1.58143784516036e-01 1.00304899967289e-01 + 1.66517972957835e-01 1.02624809036553e-01 + 1.75210207161683e-01 1.04888579553756e-01 + 1.84229946037827e-01 1.07074677598208e-01 + 1.93571360679093e-01 1.09243451986783e-01 + 2.03234945574175e-01 1.11402415125159e-01 + 2.13239205546370e-01 1.13491436907172e-01 + 2.23601537222704e-01 1.15440504439587e-01 + 2.34314315339563e-01 1.17306503096526e-01 + 2.45388676682413e-01 1.19037311828905e-01 + 2.56822498877269e-01 1.20681072953816e-01 + 2.68616771371790e-01 1.22241825144540e-01 + 2.80788220103666e-01 1.23601558631169e-01 + 2.93331680600211e-01 1.24805212165338e-01 + 3.06251511490344e-01 1.25807926970102e-01 + 3.19549745336724e-01 1.26554338608240e-01 + 3.33222453479109e-01 1.27061326118213e-01 + 3.47269018943833e-01 1.27298091243991e-01 + 3.61683948293755e-01 1.27170458380383e-01 + 3.76464979016090e-01 1.26770572192297e-01 + 3.91604054165987e-01 1.26048320133488e-01 + 4.07099743027696e-01 1.25063728629558e-01 + 4.22946891110087e-01 1.23804897872974e-01 + 4.39140508807244e-01 1.22276792353123e-01 + 4.55684294155409e-01 1.20554509111602e-01 + 4.72559601516541e-01 1.18524015966612e-01 + 4.89761912975334e-01 1.16207419090395e-01 + 5.07296139266516e-01 1.13684964275664e-01 + 5.25154357085284e-01 1.10950890395180e-01 + 5.43320252389640e-01 1.07950681161174e-01 + 5.61792716627316e-01 1.04735757711390e-01 + 5.80568803339265e-01 1.01328525940682e-01 + 5.99640262789189e-01 9.77381351876646e-02 + 6.18986539924185e-01 9.39237635066851e-02 + 6.38592769146560e-01 8.98769749368346e-02 + 6.58465976460566e-01 8.56827556065770e-02 + 6.78595728050462e-01 8.13433005574353e-02 + 6.98959863838616e-01 7.68298671125305e-02 + 7.19558497677296e-01 7.21964039086358e-02 + 7.40375559459272e-01 6.74380995266311e-02 + 7.61395509952232e-01 6.25588162368450e-02 + 7.82602242599360e-01 5.75571816126900e-02 + 8.03979199523738e-01 5.24376017015890e-02 + 8.25508947220265e-01 4.72044836666912e-02 + 8.47173082201993e-01 4.18658829372147e-02 + 8.68972243269945e-01 3.64790803343795e-02 + 8.90869140608345e-01 3.09938752249591e-02 + 9.12865896627548e-01 2.54780934053288e-02 + 9.34919781152421e-01 1.98727453143736e-02 + 9.57016514682770e-01 1.36303405789984e-02 + 9.79120888238619e-01 6.90832082291697e-03 + 1.00000000000000e+00 3.57170593908316e-05 diff --git a/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF22_Coords.txt b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF22_Coords.txt new file mode 100644 index 00000000..ee67f764 --- /dev/null +++ b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF22_Coords.txt @@ -0,0 +1,208 @@ + 201 NumCoords ! The number of coordinates in the airfoil shape file (including an extra coordinate for airfoil reference). Set to zero if coordinates not included. +! ......... x-y coordinates are next if NumCoords > 0 ............. +! x-y coordinate of airfoil reference +! x/c y/c + 0.250000 0 +! coordinates of airfoil shape +! interpolation to 200 points +! x/c y/c + 1.00000000000000e+00 -1.37905772906987e-04 + 9.76725991935908e-01 2.75905550847849e-03 + 9.53631351611733e-01 5.18607754339260e-03 + 9.30439467907717e-01 7.21116637405844e-03 + 9.07208132179710e-01 8.76441631458846e-03 + 8.84013496158046e-01 9.51161259804528e-03 + 8.60933319861523e-01 9.19547841137385e-03 + 8.38035712490432e-01 7.96595476402018e-03 + 8.15385168895348e-01 5.62847327150540e-03 + 7.93037657818789e-01 2.28558101061580e-03 + 7.71032949299981e-01 -1.90093741181228e-03 + 7.49384114270963e-01 -6.76049461633643e-03 + 7.28106510273087e-01 -1.21725858076415e-02 + 7.07180107191085e-01 -1.79684774976327e-02 + 6.86585882704839e-01 -2.39949416112886e-02 + 6.66322327664117e-01 -3.01870419451860e-02 + 6.46380042253330e-01 -3.64467876017566e-02 + 6.26744157329858e-01 -4.26868759536930e-02 + 6.07380274045402e-01 -4.87646156436792e-02 + 5.88295958690534e-01 -5.46605390281692e-02 + 5.69492521413567e-01 -6.03344111379996e-02 + 5.50944917753757e-01 -6.56813210738157e-02 + 5.32683529719922e-01 -7.07499443242120e-02 + 5.14706548079326e-01 -7.54948621351449e-02 + 4.97012214427392e-01 -7.98856360729547e-02 + 4.79604661938784e-01 -8.38829246167327e-02 + 4.62499971271577e-01 -8.75164861473946e-02 + 4.45707439025159e-01 -9.07910364185073e-02 + 4.29232251749769e-01 -9.36853302638665e-02 + 4.13079887518895e-01 -9.61843197334282e-02 + 3.97273156999330e-01 -9.83823772625506e-02 + 3.81811499955324e-01 -1.00238171273862e-01 + 3.66707654879754e-01 -1.01796983957391e-01 + 3.51968873020320e-01 -1.03118493586559e-01 + 3.37592692843044e-01 -1.04152291381984e-01 + 3.23583613955391e-01 -1.04892228070397e-01 + 3.09945962441104e-01 -1.05403595252986e-01 + 2.96679877893668e-01 -1.05689666745533e-01 + 2.83786673843868e-01 -1.05732022868329e-01 + 2.71265428998315e-01 -1.05601326789481e-01 + 2.59114641005256e-01 -1.05279433841182e-01 + 2.47334122817983e-01 -1.04772898258849e-01 + 2.35922762413987e-01 -1.04073450080798e-01 + 2.24871859339431e-01 -1.03261410015675e-01 + 2.14183854398850e-01 -1.02280347491613e-01 + 2.03856443420195e-01 -1.01137855951245e-01 + 1.93878365466042e-01 -9.98859412460872e-02 + 1.84243680326433e-01 -9.85473584321357e-02 + 1.74956557366324e-01 -9.70603160684741e-02 + 1.65996483607503e-01 -9.55230954068784e-02 + 1.57374597017771e-01 -9.38510527263059e-02 + 1.49055367342827e-01 -9.21872601100961e-02 + 1.41061804544547e-01 -9.04086149008263e-02 + 1.33371830662132e-01 -8.85813343893779e-02 + 1.25981833168783e-01 -8.67037376102544e-02 + 1.18889524396252e-01 -8.47556746420726e-02 + 1.12068484997073e-01 -8.28134777714908e-02 + 1.05533508673527e-01 -8.08202882655789e-02 + 9.92765954754487e-02 -7.87616970055698e-02 + 9.32618460232315e-02 -7.67377034670206e-02 + 8.75063188947793e-02 -7.46839878289475e-02 + 8.19865845292902e-02 -7.26460887111042e-02 + 7.66696758964058e-02 -7.06018837113606e-02 + 7.16044906719353e-02 -6.85025449105124e-02 + 6.67363367619081e-02 -6.63816283727544e-02 + 6.20862671655154e-02 -6.41837626120213e-02 + 5.76781158267178e-02 -6.19465872092337e-02 + 5.34835811930607e-02 -5.97092958338184e-02 + 4.94762917876905e-02 -5.75018783824138e-02 + 4.56743711349976e-02 -5.52907634791866e-02 + 4.20616172369434e-02 -5.30929364276299e-02 + 3.86426064710656e-02 -5.08998396737268e-02 + 3.54153788093397e-02 -4.87062512082961e-02 + 3.23662010540160e-02 -4.65256202361847e-02 + 2.94833263627923e-02 -4.43663553536911e-02 + 2.67477674550665e-02 -4.22428674968400e-02 + 2.41915370057616e-02 -4.01273164512632e-02 + 2.18857573818062e-02 -3.80078237337925e-02 + 1.97179884024849e-02 -3.59301627477569e-02 + 1.76757845498892e-02 -3.38938481159999e-02 + 1.57641027306169e-02 -3.18781262584388e-02 + 1.39724593422236e-02 -2.98931987545935e-02 + 1.22918968479213e-02 -2.79480618328304e-02 + 1.07221372201749e-02 -2.60416137215328e-02 + 9.28872160500910e-03 -2.41314304207875e-02 + 7.91630048953282e-03 -2.22853322080103e-02 + 6.67953167608040e-03 -2.04480781470025e-02 + 5.57389618300349e-03 -1.86324963909326e-02 + 4.56332093730877e-03 -1.68598162507488e-02 + 3.68524480226045e-03 -1.51108431623255e-02 + 2.91938579202685e-03 -1.33953381237321e-02 + 2.24116079129066e-03 -1.17246173969605e-02 + 1.67248583161617e-03 -1.00953735229212e-02 + 1.20324454848532e-03 -8.50604304796152e-03 + 8.41606529174913e-04 -6.95951603892573e-03 + 5.04718335749302e-04 -5.47175146445821e-03 + 2.77648316387901e-04 -4.02638290581776e-03 + 1.17748797893260e-04 -2.63253995295761e-03 + 3.69468292642352e-05 -1.28969548263411e-03 + 0.00000000000000e+00 0.00000000000000e+00 + 3.09535021918612e-05 1.28936436929246e-03 + 1.06637401949987e-04 2.63142100210815e-03 + 2.59964572072159e-04 4.02351019908418e-03 + 4.69920111426106e-04 5.46706336175963e-03 + 7.96541452526313e-04 6.95306199333623e-03 + 1.17401205379525e-03 8.48786363886347e-03 + 1.61831089593917e-03 1.00770346353190e-02 + 2.32333874774940e-03 1.16504559884271e-02 + 3.06712959817167e-03 1.32804282822632e-02 + 3.98276803748560e-03 1.49090049113570e-02 + 4.98344743343845e-03 1.65770603791945e-02 + 6.11996090735756e-03 1.82551557640217e-02 + 7.37297343445192e-03 1.99533035573824e-02 + 8.71286539087883e-03 2.16948370578646e-02 + 1.01765501551493e-02 2.34537701968742e-02 + 1.17322670694759e-02 2.52581891303742e-02 + 1.34217992141067e-02 2.70733747583812e-02 + 1.52388298301360e-02 2.89063564237294e-02 + 1.71688461558914e-02 3.07767937542747e-02 + 1.91899331878790e-02 3.27097377805680e-02 + 2.13638093661363e-02 3.46457797783486e-02 + 2.36723297656305e-02 3.66070405437775e-02 + 2.61211854117630e-02 3.85883561887161e-02 + 2.87097811699761e-02 4.06004475067315e-02 + 3.14304301249726e-02 4.26557978654197e-02 + 3.42931270832587e-02 4.47486944963130e-02 + 3.73038188445460e-02 4.68776749211300e-02 + 4.04730361230994e-02 4.90353694174481e-02 + 4.38097981156242e-02 5.12147401773910e-02 + 4.73220204778543e-02 5.34122475810596e-02 + 5.09939923040230e-02 5.56608916859612e-02 + 5.48571252255563e-02 5.79155152658394e-02 + 5.89138291139096e-02 6.01837002893103e-02 + 6.31577497344129e-02 6.24845191863370e-02 + 6.75947899647940e-02 6.48186842922515e-02 + 7.22122652229698e-02 6.72216823767386e-02 + 7.70740114758716e-02 6.95807319849553e-02 + 8.21553322345438e-02 7.19550902719777e-02 + 8.74394236745447e-02 7.43941379373109e-02 + 9.29672017196781e-02 7.68226772209049e-02 + 9.87424021686052e-02 7.91978116359561e-02 + 1.04761752867740e-01 8.15667320414124e-02 + 1.11030780081871e-01 8.39572315421679e-02 + 1.17558018563720e-01 8.63625746301939e-02 + 1.24352270186846e-01 8.87774608495421e-02 + 1.31438105054613e-01 9.11321173164249e-02 + 1.38801313550205e-01 9.35029309525731e-02 + 1.46447393656373e-01 9.58971156573319e-02 + 1.54396766312990e-01 9.82613258248415e-02 + 1.62656569565700e-01 1.00588261686332e-01 + 1.71235347766832e-01 1.02865843879122e-01 + 1.80142279870852e-01 1.05076149462146e-01 + 1.89373799652761e-01 1.07269345993908e-01 + 1.98933590722142e-01 1.09443191127768e-01 + 2.08836636556623e-01 1.11554276573076e-01 + 2.19099471288483e-01 1.13540075332887e-01 + 2.29717904676441e-01 1.15442617819263e-01 + 2.40701766215834e-01 1.17220973164961e-01 + 2.52050933191971e-01 1.18911560197852e-01 + 2.63767077262110e-01 1.20517086973916e-01 + 2.75865949946677e-01 1.21934154882854e-01 + 2.88343581116220e-01 1.23201688742876e-01 + 3.01205334203085e-01 1.24270880831573e-01 + 3.14453408998862e-01 1.25097439258154e-01 + 3.28085392677879e-01 1.25681829879209e-01 + 3.42100675917614e-01 1.25997636647737e-01 + 3.56494768423971e-01 1.25962526629538e-01 + 3.71264984512598e-01 1.25638758942093e-01 + 3.86403905621335e-01 1.24988484201363e-01 + 4.01909708696471e-01 1.24068994185517e-01 + 4.17777487590764e-01 1.22870793211783e-01 + 4.34002789914367e-01 1.21403723025625e-01 + 4.50587361686721e-01 1.19722425477543e-01 + 4.67516097146081e-01 1.17745691253289e-01 + 4.84783008098729e-01 1.15478338348871e-01 + 5.02391973551338e-01 1.12996226374276e-01 + 5.20335411416213e-01 1.10293881931109e-01 + 5.38598443680468e-01 1.07327040011182e-01 + 5.57179445389403e-01 1.04143490655964e-01 + 5.76073870986909e-01 1.00758354775127e-01 + 5.95273625837750e-01 9.71818954906031e-02 + 6.14761209512960e-01 9.33892639430016e-02 + 6.34522016454894e-01 8.93721485884786e-02 + 6.54559394245177e-01 8.52121018071187e-02 + 6.74862300856641e-01 8.08992604208061e-02 + 6.95411169374383e-01 7.64180821116692e-02 + 7.16203679512635e-01 7.18100281693020e-02 + 7.37223461079002e-01 6.70709646616096e-02 + 7.58454521150695e-01 6.22070114365566e-02 + 7.79880103179641e-01 5.72143218232588e-02 + 8.01483398149160e-01 5.20988678810583e-02 + 8.23246404130259e-01 4.68667510151217e-02 + 8.45150485874660e-01 4.15319681044740e-02 + 8.67192695150624e-01 3.61314252690582e-02 + 8.89338539461505e-01 3.06353825258196e-02 + 9.11585423298854e-01 2.50909095333333e-02 + 9.33894494503434e-01 1.94679731415527e-02 + 9.56251121560769e-01 1.33384432495636e-02 + 9.78619325570430e-01 6.83697775457594e-03 + 1.00000000000000e+00 2.05198748460235e-04 diff --git a/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF23_Coords.txt b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF23_Coords.txt new file mode 100644 index 00000000..b7ccee65 --- /dev/null +++ b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF23_Coords.txt @@ -0,0 +1,208 @@ + 201 NumCoords ! The number of coordinates in the airfoil shape file (including an extra coordinate for airfoil reference). Set to zero if coordinates not included. +! ......... x-y coordinates are next if NumCoords > 0 ............. +! x-y coordinate of airfoil reference +! x/c y/c + 0.250000 0 +! coordinates of airfoil shape +! interpolation to 200 points +! x/c y/c + 1.00000000000000e+00 -3.89631805446465e-04 + 9.76523223440909e-01 2.57752479218257e-03 + 9.53190468875220e-01 5.08428616099728e-03 + 9.29793700110228e-01 7.19463079459903e-03 + 9.06373069230989e-01 8.83683936265999e-03 + 8.82989474321167e-01 9.75643931673717e-03 + 8.59712867174704e-01 9.61496203663975e-03 + 8.36607653336429e-01 8.67096288412905e-03 + 8.13736696364153e-01 6.61459865723342e-03 + 7.91156003915796e-01 3.56436965978782e-03 + 7.68908626920759e-01 -3.19229213119966e-04 + 7.47012054504006e-01 -4.87284377280892e-03 + 7.25479893786865e-01 -9.96177887707548e-03 + 7.04301598747634e-01 -1.54349458980302e-02 + 6.83461873027533e-01 -2.11434442792537e-02 + 6.62962284386421e-01 -2.70203050251467e-02 + 6.42791629284883e-01 -3.29619235742479e-02 + 6.22938362223096e-01 -3.88812963489969e-02 + 6.03377191897424e-01 -4.46577924076831e-02 + 5.84113605921901e-01 -5.02638611712951e-02 + 5.65147058057943e-01 -5.56526737727627e-02 + 5.46463242401931e-01 -6.07476183166026e-02 + 5.28083600651341e-01 -6.55730561886808e-02 + 5.10007892084025e-01 -7.00900567751652e-02 + 4.92236196987507e-01 -7.42679957358169e-02 + 4.74773357090323e-01 -7.80766311425804e-02 + 4.57634431292357e-01 -8.15460818492506e-02 + 4.40826245471248e-01 -8.46702707193481e-02 + 4.24355029015101e-01 -8.74363864527718e-02 + 4.08227124292632e-01 -8.98419112116650e-02 + 3.92459570866590e-01 -9.19539503766752e-02 + 3.77053268096062e-01 -9.37469616449339e-02 + 3.62017890326388e-01 -9.52572816145339e-02 + 3.47358922971653e-01 -9.65314596619472e-02 + 3.33074130797390e-01 -9.75316311345544e-02 + 3.19166552441191e-01 -9.82568017865109e-02 + 3.05638457789601e-01 -9.87570424765259e-02 + 2.92489196946871e-01 -9.90352109981780e-02 + 2.79718896446607e-01 -9.90816142636686e-02 + 2.67325715523272e-01 -9.89532661236331e-02 + 2.55307554299133e-01 -9.86395210813088e-02 + 2.43662963759620e-01 -9.81468679323721e-02 + 2.32389051593200e-01 -9.74790188542946e-02 + 2.21479352444559e-01 -9.66892453470001e-02 + 2.10932960713701e-01 -9.57430626738486e-02 + 2.00746891023561e-01 -9.46523604003965e-02 + 1.90911241857401e-01 -9.34530543544128e-02 + 1.81419357741535e-01 -9.21641429584474e-02 + 1.72272201518936e-01 -9.07467422355202e-02 + 1.63454036160759e-01 -8.92690930011261e-02 + 1.54968504898213e-01 -8.76805069244906e-02 + 1.46789032362938e-01 -8.60792825829244e-02 + 1.38929389926432e-01 -8.43836334579841e-02 + 1.31372073509835e-01 -8.26402323580097e-02 + 1.24111669738838e-01 -8.08497501671892e-02 + 1.17144601558583e-01 -7.89996633722882e-02 + 1.10449627383806e-01 -7.71449373419936e-02 + 1.04032527949034e-01 -7.52514037061188e-02 + 9.78887241867816e-02 -7.33057936883226e-02 + 9.19902897469441e-02 -7.13774864507213e-02 + 8.63446174524882e-02 -6.94278850804577e-02 + 8.09349931912135e-02 -6.74837749535468e-02 + 7.57176279736417e-02 -6.55345654926341e-02 + 7.07422636872318e-02 -6.35487599075303e-02 + 6.59681013466920e-02 -6.15577280140700e-02 + 6.14091796784638e-02 -5.95276219887417e-02 + 5.70825310884753e-02 -5.74696232341217e-02 + 5.29640917916176e-02 -5.54139826908802e-02 + 4.90331099431885e-02 -5.33787557780121e-02 + 4.53019232083321e-02 -5.13412852201466e-02 + 4.17564728311483e-02 -4.93141304770355e-02 + 3.83992522495016e-02 -4.72921118209637e-02 + 3.52273324651378e-02 -4.52718650652909e-02 + 3.22287783868937e-02 -4.32621299402485e-02 + 2.93935765607861e-02 -4.12701495319455e-02 + 2.67049962322860e-02 -3.93074868211488e-02 + 2.41875159700224e-02 -3.73546300420540e-02 + 2.19051355335849e-02 -3.54024649802942e-02 + 1.97596598780863e-02 -3.34865723449696e-02 + 1.77404917592603e-02 -3.16046902103228e-02 + 1.58480959117786e-02 -2.97420661384396e-02 + 1.40731937772208e-02 -2.79068578544306e-02 + 1.24092192372854e-02 -2.61060448917434e-02 + 1.08572800374988e-02 -2.43371683353192e-02 + 9.42416939885715e-03 -2.25730887258294e-02 + 8.05945666798942e-03 -2.08575096912792e-02 + 6.81900211726789e-03 -1.91549248355902e-02 + 5.70427188596224e-03 -1.74708678303986e-02 + 4.68929550551071e-03 -1.58203951766527e-02 + 3.79718481534846e-03 -1.41925025018919e-02 + 3.01254414274189e-03 -1.25940941416061e-02 + 2.32306506044275e-03 -1.10313592778986e-02 + 1.73616370284593e-03 -9.50573827422768e-03 + 1.25001115654578e-03 -8.01464961151014e-03 + 8.66582941084615e-04 -6.56215809631841e-03 + 5.27892943221305e-04 -5.15982819826281e-03 + 2.90620181051750e-04 -3.79793930383067e-03 + 1.24304967749036e-04 -2.48335242246912e-03 + 3.96737576866571e-05 -1.21650060438702e-03 + 0.00000000000000e+00 0.00000000000000e+00 + 2.95189184277812e-05 1.21614429607452e-03 + 1.05767060451514e-04 2.48286216056600e-03 + 2.57762778152470e-04 3.79720959162143e-03 + 4.68204860110995e-04 5.16008910759149e-03 + 7.83797140932723e-04 6.56497526010459e-03 + 1.15715502367995e-03 8.01500849124157e-03 + 1.60204509969143e-03 9.51313492711731e-03 + 2.26838290451738e-03 1.10094565184360e-02 + 2.98389530162135e-03 1.25531639212653e-02 + 3.84468300573088e-03 1.41052049491652e-02 + 4.79382432709198e-03 1.56929490788932e-02 + 5.86480251491728e-03 1.72970451450205e-02 + 7.04339712537743e-03 1.89252483507722e-02 + 8.31036366558127e-03 2.05930697348407e-02 + 9.69288686144440e-03 2.22822382309425e-02 + 1.11694244157683e-02 2.40125728679872e-02 + 1.27687195678609e-02 2.57610052570714e-02 + 1.44855480622724e-02 2.75340521574697e-02 + 1.63141117762223e-02 2.93431371358707e-02 + 1.82409459730255e-02 3.12044757360750e-02 + 2.03090129151232e-02 3.30784440112194e-02 + 2.25047656211822e-02 3.49825288350549e-02 + 2.48358954405978e-02 3.69102907266350e-02 + 2.73027851057594e-02 3.88709280586456e-02 + 2.99022786432083e-02 4.08708020979388e-02 + 3.26428835363264e-02 4.29073735254742e-02 + 3.55275801260422e-02 4.49815642845116e-02 + 3.85675366725734e-02 4.70868993056664e-02 + 4.17712151330545e-02 4.92166052451779e-02 + 4.51455848984656e-02 5.13693116705787e-02 + 4.86800832975236e-02 5.35697871829730e-02 + 5.23998258242555e-02 5.57840039693155e-02 + 5.63090699963194e-02 5.80167300546564e-02 + 6.04040077958621e-02 6.02830393557848e-02 + 6.46921254503434e-02 6.25806625362446e-02 + 6.91657933196187e-02 6.49357139206047e-02 + 7.38718601029010e-02 6.72692279831682e-02 + 7.87963189404003e-02 6.96202880139496e-02 + 8.39284216127343e-02 7.20249986111878e-02 + 8.93005278379212e-02 7.44277079926884e-02 + 9.49165785178080e-02 7.68080305069524e-02 + 1.00776596462740e-01 7.91941589367465e-02 + 1.06887992955234e-01 8.15979852235107e-02 + 1.13259326028114e-01 8.40133348371362e-02 + 1.19898645623439e-01 8.64376453292622e-02 + 1.26825363129969e-01 8.88246082279034e-02 + 1.34032996617006e-01 9.12209273262398e-02 + 1.41527923866446e-01 9.36300218950618e-02 + 1.49326736108375e-01 9.60160327660242e-02 + 1.57437264377705e-01 9.83712642438628e-02 + 1.65868324600152e-01 1.00685218752554e-01 + 1.74628718266615e-01 1.02944937223580e-01 + 1.83718250107745e-01 1.05182085806860e-01 + 1.93143977808745e-01 1.07387673596204e-01 + 2.02916723675256e-01 1.09537420256945e-01 + 2.13052007685298e-01 1.11578803647391e-01 + 2.23549653724373e-01 1.13536674601117e-01 + 2.34418102657221e-01 1.15382216081547e-01 + 2.45660047881914e-01 1.17132423550172e-01 + 2.57277821794247e-01 1.18790833197830e-01 + 2.69285661481619e-01 1.20274563173763e-01 + 2.81681435328113e-01 1.21610792504416e-01 + 2.94471299405458e-01 1.22753207590004e-01 + 3.07657839217654e-01 1.23665554126748e-01 + 3.21240423603742e-01 1.24335192568048e-01 + 3.35218492732312e-01 1.24739126354752e-01 + 3.49588853515411e-01 1.24807697648437e-01 + 3.64348393745959e-01 1.24573091480070e-01 + 3.79490557018895e-01 1.24009550543367e-01 + 3.95013008833302e-01 1.23166425873097e-01 + 4.10911230551784e-01 1.22040125894596e-01 + 4.27181368064296e-01 1.20643690185419e-01 + 4.43822979334143e-01 1.19012214211741e-01 + 4.60825027599087e-01 1.17096430824897e-01 + 4.78180176231373e-01 1.14887296599190e-01 + 4.95890785853081e-01 1.12452966207322e-01 + 5.13949537326196e-01 1.09787047252637e-01 + 5.32343642071341e-01 1.06859196176221e-01 + 5.51070553747742e-01 1.03710967331665e-01 + 5.70123937401839e-01 1.00351455565678e-01 + 5.89495628773574e-01 9.67909361070087e-02 + 6.09171898570426e-01 9.30211098562286e-02 + 6.29138822745811e-01 8.90355090111987e-02 + 6.49394868003684e-01 8.49035724050775e-02 + 6.69928293397831e-01 8.06107601158379e-02 + 6.90722533013325e-01 7.61534793554206e-02 + 7.11772271356487e-01 7.15640092699005e-02 + 7.33060707027799e-01 6.68388174833136e-02 + 7.54571508751324e-01 6.19858692115997e-02 + 7.76286826841553e-01 5.69994231785712e-02 + 7.98189415948090e-01 5.18865779509044e-02 + 8.20260703237170e-01 4.66547433653687e-02 + 8.42482201370411e-01 4.13224819490564e-02 + 8.64845816185461e-01 3.59114363001708e-02 + 8.87320554539452e-01 3.04068317544367e-02 + 9.09898081718863e-01 2.48403197190891e-02 + 9.32544737844051e-01 1.92037035893727e-02 + 9.55244628007707e-01 1.31962135682704e-02 + 9.77960328149588e-01 6.92447736867692e-03 + 1.00000000000000e+00 5.33569410323788e-04 diff --git a/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF24_Coords.txt b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF24_Coords.txt new file mode 100644 index 00000000..dee2a673 --- /dev/null +++ b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF24_Coords.txt @@ -0,0 +1,208 @@ + 201 NumCoords ! The number of coordinates in the airfoil shape file (including an extra coordinate for airfoil reference). Set to zero if coordinates not included. +! ......... x-y coordinates are next if NumCoords > 0 ............. +! x-y coordinate of airfoil reference +! x/c y/c + 0.250000 0 +! coordinates of airfoil shape +! interpolation to 200 points +! x/c y/c + 1.00000000000000e+00 -7.50291333776672e-04 + 9.76298896194702e-01 2.32889115261073e-03 + 9.52696096636841e-01 4.94521028450639e-03 + 9.29060312605788e-01 7.15692894407718e-03 + 9.05417910316586e-01 8.89067899641578e-03 + 8.81816184123139e-01 9.89569835581813e-03 + 8.58317705959904e-01 9.84322267766306e-03 + 8.34983301808537e-01 9.04823588658875e-03 + 8.11873434560873e-01 7.18374392840931e-03 + 7.89043919534343e-01 4.37297375841967e-03 + 7.66539540795448e-01 7.44223479357781e-04 + 7.44381391909662e-01 -3.54660860602751e-03 + 7.22581240917263e-01 -8.35156649411918e-03 + 7.01137346622867e-01 -1.35373495193734e-02 + 6.80039693873756e-01 -1.89641771354476e-02 + 6.59290364533785e-01 -2.45571754348028e-02 + 6.38878859868852e-01 -3.02132879449722e-02 + 6.18795535800661e-01 -3.58428941592947e-02 + 5.99025214360609e-01 -4.13502377144402e-02 + 5.79571063345178e-01 -4.66989833430834e-02 + 5.60430857912260e-01 -5.18361266758138e-02 + 5.41600549487872e-01 -5.67126894278324e-02 + 5.23093012388221e-01 -6.13292557711388e-02 + 5.04909716783247e-01 -6.56538953621398e-02 + 4.87051293227111e-01 -6.96530548678958e-02 + 4.69524243044734e-01 -7.33080529423055e-02 + 4.52341821294675e-01 -7.66472468360973e-02 + 4.35508589614116e-01 -7.96544207222355e-02 + 4.19030914862448e-01 -8.23226920725703e-02 + 4.02916228417393e-01 -8.46623466695113e-02 + 3.87175637539370e-01 -8.67119738820041e-02 + 3.71811428132166e-01 -8.84606569575440e-02 + 3.56830409304917e-01 -8.99353602919689e-02 + 3.42236645717252e-01 -9.11689881156119e-02 + 3.28028443529475e-01 -9.21352973252990e-02 + 3.14207871794200e-01 -9.28394446226089e-02 + 3.00775731152437e-01 -9.33148765751533e-02 + 2.87731091983130e-01 -9.35649492324365e-02 + 2.75073270707374e-01 -9.35897732815692e-02 + 2.62799911559184e-01 -9.34332051784304e-02 + 2.50908328649408e-01 -9.30938200207195e-02 + 2.39395914296969e-01 -9.25789080830780e-02 + 2.28258324217990e-01 -9.19038525166016e-02 + 2.17490357613613e-01 -9.10978135960199e-02 + 2.07088466750961e-01 -9.01469095785202e-02 + 1.97047806459751e-01 -8.90697005309464e-02 + 1.87360260340612e-01 -8.78852780089872e-02 + 1.78018682210870e-01 -8.66086122363040e-02 + 1.69020258315682e-01 -8.52244126115397e-02 + 1.60353331264926e-01 -8.37720812851559e-02 + 1.52014939197557e-01 -8.22330718969560e-02 + 1.43987185788990e-01 -8.06620558758565e-02 + 1.36274091000982e-01 -7.90182608959080e-02 + 1.28862566102960e-01 -7.73292710854366e-02 + 1.21745655831401e-01 -7.55977296970018e-02 + 1.14917898957625e-01 -7.38189265766767e-02 + 1.08363637615901e-01 -7.20267149673762e-02 + 1.02080415985040e-01 -7.02081908521227e-02 + 9.60650562136330e-02 -6.83524876726988e-02 + 9.02979483004230e-02 -6.64992618936153e-02 + 8.47777986078614e-02 -6.46338463331624e-02 + 7.94941040279597e-02 -6.27654801484029e-02 + 7.44102991938022e-02 -6.08945434432346e-02 + 6.95582747844778e-02 -5.90057327945389e-02 + 6.49131793283190e-02 -5.71216563862163e-02 + 6.04794197269670e-02 -5.52290978859873e-02 + 5.62646886835696e-02 -5.33218521504249e-02 + 5.22507416096869e-02 -5.14208493808622e-02 + 4.84245433996503e-02 -4.95323182851412e-02 + 4.47904867206598e-02 -4.76449015546858e-02 + 4.13374558635882e-02 -4.57663829252569e-02 + 3.80650840253715e-02 -4.38944940923365e-02 + 3.49691116419480e-02 -4.20279518522186e-02 + 3.20400727373755e-02 -4.01712967041496e-02 + 2.92703341033774e-02 -3.83301218257238e-02 + 2.66462635908786e-02 -3.65121714900467e-02 + 2.41819941212201e-02 -3.47068073590117e-02 + 2.19143199986438e-02 -3.29088330701643e-02 + 1.97796258019261e-02 -3.11426553752093e-02 + 1.77718675728929e-02 -2.94033561455842e-02 + 1.58892791802320e-02 -2.76827467855728e-02 + 1.41231129715086e-02 -2.59874713046408e-02 + 1.24680257561555e-02 -2.43219224431366e-02 + 1.09259070704779e-02 -2.26820710355976e-02 + 9.49343298356482e-03 -2.10561306903018e-02 + 8.14503768413817e-03 -1.94635072722990e-02 + 6.90999917273266e-03 -1.78889094607232e-02 + 5.79390475471148e-03 -1.63307209071248e-02 + 4.78106804114271e-03 -1.47978940894094e-02 + 3.88016584757143e-03 -1.32873649605637e-02 + 3.08233798054177e-03 -1.18026200908121e-02 + 2.38686534170238e-03 -1.03450301564476e-02 + 1.78599805341179e-03 -8.92081233071476e-03 + 1.28652156378685e-03 -7.52634471004791e-03 + 8.83996769448488e-04 -6.16669016705767e-03 + 5.46612029292912e-04 -4.84894257335285e-03 + 3.01376049559927e-04 -3.56996967423148e-03 + 1.30154076571712e-04 -2.33432457843823e-03 + 4.21374163304318e-05 -1.14334359217422e-03 + 0.00000000000000e+00 0.00000000000000e+00 + 2.81157574964881e-05 1.14295937760577e-03 + 1.04621923266427e-04 2.33440626401102e-03 + 2.54739066947636e-04 3.57120735782472e-03 + 4.65849257103884e-04 4.85377645755166e-03 + 7.66296706792806e-04 6.17820210329396e-03 + 1.13400710680486e-03 7.54436835218198e-03 + 1.57970905045129e-03 8.95240763421855e-03 + 2.19446599887451e-03 1.03731283301651e-02 + 2.87705684559474e-03 1.18324568030195e-02 + 3.67789371859726e-03 1.33102740954264e-02 + 4.57036584246313e-03 1.48203416608747e-02 + 5.56967498060080e-03 1.63537813005310e-02 + 6.66759090523285e-03 1.79156766085822e-02 + 7.85649334745409e-03 1.95131911485843e-02 + 9.15255477687989e-03 2.11363600124788e-02 + 1.05445488424763e-02 2.27966579112874e-02 + 1.20486064407746e-02 2.44823719840950e-02 + 1.36603871932619e-02 2.61996974106957e-02 + 1.53821576127598e-02 2.79522040521000e-02 + 1.72090722971723e-02 2.97472094765997e-02 + 1.91651219523706e-02 3.15651260035317e-02 + 2.12426156558742e-02 3.34176370326924e-02 + 2.34511443758688e-02 3.52973320141773e-02 + 2.57904895361023e-02 3.72130957307203e-02 + 2.82626509750913e-02 3.91646919322919e-02 + 3.08759739857624e-02 4.11514060005145e-02 + 3.36299253040576e-02 4.31771896078588e-02 + 3.65354985842998e-02 4.52371794325495e-02 + 3.96008704268746e-02 4.73246766888027e-02 + 4.28321561070921e-02 4.94404029988426e-02 + 4.62242346874908e-02 5.16004112773017e-02 + 4.97958902647260e-02 5.37820404238713e-02 + 5.35528496536011e-02 5.59876066111493e-02 + 5.74940264314054e-02 5.82280097517281e-02 + 6.16289114941267e-02 6.04973177565880e-02 + 6.59549586653717e-02 6.28123067599801e-02 + 7.05011791699481e-02 6.51291026479873e-02 + 7.52646676807933e-02 6.74659569979716e-02 + 8.02411483868892e-02 6.98450349458632e-02 + 8.54541005536459e-02 7.22307435968477e-02 + 9.09077876598320e-02 7.46202759272474e-02 + 9.66055445093218e-02 7.70252439848328e-02 + 1.02556617968726e-01 7.94445037398437e-02 + 1.08769595464231e-01 8.18723919264446e-02 + 1.15251846243329e-01 8.43087989893419e-02 + 1.22017436032429e-01 8.67299569776199e-02 + 1.29067606508560e-01 8.91543819424277e-02 + 1.36410072520413e-01 9.15812636222036e-02 + 1.44057372467977e-01 9.39916412991629e-02 + 1.52018009642350e-01 9.63774884768607e-02 + 1.60301083370340e-01 9.87298228910894e-02 + 1.68915004119298e-01 1.01040503878498e-01 + 1.77863375679202e-01 1.03322385460583e-01 + 1.87155863329685e-01 1.05561389941643e-01 + 1.96799541214523e-01 1.07750710152026e-01 + 2.06809021346131e-01 1.09847473640509e-01 + 2.17187694050625e-01 1.11860752579225e-01 + 2.27942920264959e-01 1.13772677888835e-01 + 2.39080425704280e-01 1.15580120940451e-01 + 2.50602978823008e-01 1.17288028936626e-01 + 2.62523055501980e-01 1.18833856236034e-01 + 2.74840647475125e-01 1.20232024719622e-01 + 2.87562192937226e-01 1.21441226349321e-01 + 3.00690830602118e-01 1.22430852727519e-01 + 3.14227523639263e-01 1.23178402093805e-01 + 3.28171801048535e-01 1.23663484726724e-01 + 3.42521760498053e-01 1.23828016318311e-01 + 3.57273986043832e-01 1.23678074838371e-01 + 3.72422815778781e-01 1.23198599341217e-01 + 3.87965402200350e-01 1.22429097089126e-01 + 4.03897678601998e-01 1.21373131778580e-01 + 4.20216289788358e-01 1.20045527577897e-01 + 4.36918952632428e-01 1.18464558254558e-01 + 4.53998170716250e-01 1.16608654175239e-01 + 4.71445818375774e-01 1.14459171027755e-01 + 4.89262561234794e-01 1.12074715982259e-01 + 5.07441163553935e-01 1.09446574254448e-01 + 5.25971148178741e-01 1.06560361311888e-01 + 5.44848798428680e-01 1.03449434794008e-01 + 5.64066277235567e-01 1.00118102629513e-01 + 5.83615080942241e-01 9.65751507526858e-02 + 6.03485053765207e-01 9.28288280428212e-02 + 6.23663294928140e-01 8.88766391764726e-02 + 6.44143290404599e-01 8.47640847275778e-02 + 6.64912691365091e-01 8.04820587812154e-02 + 6.85957565742361e-01 7.60375257877561e-02 + 7.07269770163650e-01 7.14578896712954e-02 + 7.28832031023755e-01 6.67399716333503e-02 + 7.50627928640914e-01 6.18927779581912e-02 + 7.72638273090132e-01 5.69095365551616e-02 + 7.94845273313031e-01 5.17979358377091e-02 + 8.17229952512696e-01 4.65661010560639e-02 + 8.39774418012758e-01 4.12350839199444e-02 + 8.62464948057395e-01 3.58183297895103e-02 + 8.85273913513708e-01 3.03089834179839e-02 + 9.08187630633643e-01 2.47304583972593e-02 + 9.31177783406441e-01 1.90863321564750e-02 + 9.54226411846771e-01 1.31957781659379e-02 + 9.77294204499900e-01 7.13558621173920e-03 + 1.00000000000000e+00 9.69484227912823e-04 diff --git a/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF25_Coords.txt b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF25_Coords.txt new file mode 100644 index 00000000..f5baf458 --- /dev/null +++ b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF25_Coords.txt @@ -0,0 +1,208 @@ + 201 NumCoords ! The number of coordinates in the airfoil shape file (including an extra coordinate for airfoil reference). Set to zero if coordinates not included. +! ......... x-y coordinates are next if NumCoords > 0 ............. +! x-y coordinate of airfoil reference +! x/c y/c + 0.250000 0 +! coordinates of airfoil shape +! interpolation to 200 points +! x/c y/c + 1.00000000000000e+00 -1.09250671868000e-03 + 9.76115586099618e-01 2.09600510332978e-03 + 9.52288294552172e-01 4.81417885933177e-03 + 9.28450060797343e-01 7.11490117592222e-03 + 9.04619297601449e-01 8.92329765774539e-03 + 8.80834074284664e-01 9.95340950185301e-03 + 8.57151659839586e-01 9.92756319875484e-03 + 8.33630254563209e-01 9.17783270101517e-03 + 8.10328015134571e-01 7.42012067290446e-03 + 7.87300463622396e-01 4.77516783787571e-03 + 7.64592703953390e-01 1.32624859090481e-03 + 7.42228033108644e-01 -2.77682728463799e-03 + 7.20216772646893e-01 -7.37607048945225e-03 + 6.98563400687629e-01 -1.23524458090196e-02 + 6.77262887692173e-01 -1.75755523866722e-02 + 6.56316064999009e-01 -2.29614286738159e-02 + 6.35714570806867e-01 -2.84102836191219e-02 + 6.15449288352083e-01 -3.38290876998397e-02 + 5.95513325480546e-01 -3.91424755035297e-02 + 5.75907942700664e-01 -4.43068439562326e-02 + 5.56629760363534e-01 -4.92645154005323e-02 + 5.37682173510500e-01 -5.39873548651573e-02 + 5.19071820661838e-01 -5.84578413099440e-02 + 5.00801555954315e-01 -6.26495762564164e-02 + 4.82871601768206e-01 -6.65256315806630e-02 + 4.65290321806567e-01 -7.00771541943242e-02 + 4.48069107802193e-01 -7.33303008744292e-02 + 4.31210942377935e-01 -7.62613694929760e-02 + 4.14721717256527e-01 -7.88670112627226e-02 + 3.98609830485640e-01 -8.11674486204708e-02 + 3.82881803238740e-01 -8.31789010896421e-02 + 3.67540922501510e-01 -8.49011792837672e-02 + 3.52591959359744e-01 -8.63538669976877e-02 + 3.38038125513927e-01 -8.75591661511401e-02 + 3.23878337769632e-01 -8.84993826488772e-02 + 3.10114246734585e-01 -8.91848244796117e-02 + 2.96745918134662e-01 -8.96356484654719e-02 + 2.83772536979569e-01 -8.98560569285609e-02 + 2.71193048529533e-01 -8.98541970412896e-02 + 2.59004966514683e-01 -8.96641882545778e-02 + 2.47205169565799e-01 -8.92924468430343e-02 + 2.35790240472659e-01 -8.87473051941079e-02 + 2.24754947680772e-01 -8.80529555951448e-02 + 2.14094425301211e-01 -8.72214656839783e-02 + 2.03803579375793e-01 -8.62541002544239e-02 + 1.93875405543264e-01 -8.51751516327919e-02 + 1.84303408655320e-01 -8.39908637540001e-02 + 1.75080215317279e-01 -8.27132159406177e-02 + 1.66199793240435e-01 -8.13445725448274e-02 + 1.57653122663062e-01 -7.99033042566852e-02 + 1.49432819276280e-01 -7.83940014030634e-02 + 1.41527369025976e-01 -7.68397516570057e-02 + 1.33933094840571e-01 -7.52295246442809e-02 + 1.26640143243466e-01 -7.35770567956669e-02 + 1.19640559393263e-01 -7.18863418890472e-02 + 1.12927077813054e-01 -7.01581195662533e-02 + 1.06488519837237e-01 -6.84113181275732e-02 + 1.00316701895756e-01 -6.66480482070258e-02 + 9.44082133574360e-02 -6.48587314973944e-02 + 8.87499483874507e-02 -6.30623827083626e-02 + 8.33346753623294e-02 -6.12610269188888e-02 + 7.81562621654159e-02 -5.94517874653428e-02 + 7.31951432238743e-02 -5.76424972836634e-02 + 6.84577626403403e-02 -5.58286777757905e-02 + 6.39326342358596e-02 -5.40173864513933e-02 + 5.96152121769926e-02 -5.22094494493164e-02 + 5.55045079578264e-02 -5.03979483760663e-02 + 5.15876859053906e-02 -4.85965280700871e-02 + 4.78588835860377e-02 -4.68025488097465e-02 + 4.43151088293809e-02 -4.50134393598166e-02 + 4.09479814741917e-02 -4.32331507155101e-02 + 3.77544761371438e-02 -4.14613164257821e-02 + 3.47290964996220e-02 -3.96983685901773e-02 + 3.18646716164714e-02 -3.79460007064151e-02 + 2.91557807064150e-02 -3.62082493349325e-02 + 2.65916717593254e-02 -3.44893521422311e-02 + 2.41768614668749e-02 -3.27857249071581e-02 + 2.19169363744281e-02 -3.10958697248329e-02 + 1.97853574099944e-02 -2.94351217148795e-02 + 1.77809502328637e-02 -2.77959928991413e-02 + 1.59012923654057e-02 -2.61756147968822e-02 + 1.41377791124355e-02 -2.45798265623274e-02 + 1.24854340081653e-02 -2.30107015135764e-02 + 1.09463949529226e-02 -2.14628875680232e-02 + 9.51420326071247e-03 -1.99362443503988e-02 + 8.18367131774184e-03 -1.84317002704562e-02 + 6.95781355369571e-03 -1.69495477016988e-02 + 5.84461757031922e-03 -1.54828594722959e-02 + 4.83675987451319e-03 -1.40360192911298e-02 + 3.93148210889690e-03 -1.26118037509212e-02 + 3.12597705524147e-03 -1.12107577936507e-02 + 2.42827959498203e-03 -9.83080813631348e-03 + 1.81848159181735e-03 -8.48180028772974e-03 + 1.31026857339993e-03 -7.15931186006862e-03 + 8.94028566689473e-04 -5.86904696569661e-03 + 5.59139659541858e-04 -4.61467241237522e-03 + 3.08713803920484e-04 -3.39799797587375e-03 + 1.34284352600275e-04 -2.22180755581035e-03 + 4.38766782931077e-05 -1.08808364043886e-03 + 0.00000000000000e+00 0.00000000000000e+00 + 2.70754963215136e-05 1.08767660334744e-03 + 1.03580808069746e-04 2.22228516879441e-03 + 2.51928419550096e-04 3.40061010146026e-03 + 4.63659613080425e-04 4.62272156443479e-03 + 7.50030014672317e-04 5.88676081458818e-03 + 1.11249110649511e-03 7.19012596240712e-03 + 1.55894767722491e-03 8.53069940774572e-03 + 2.12648113335517e-03 9.89524770439861e-03 + 2.78122395867452e-03 1.12920178518460e-02 + 3.53349472781731e-03 1.27152234032320e-02 + 4.37986080892483e-03 1.41682764668305e-02 + 5.32108740225112e-03 1.56504595401408e-02 + 6.35403104634295e-03 1.71645723270603e-02 + 7.48065465647005e-03 1.87111343722309e-02 + 8.70798790603196e-03 2.02868357356723e-02 + 1.00326625323290e-02 2.18967960271385e-02 + 1.14615517896570e-02 2.35376948845036e-02 + 1.29908498121995e-02 2.52156066282122e-02 + 1.46285017870635e-02 2.69284106702504e-02 + 1.63762840007771e-02 2.86766604856462e-02 + 1.82437127611806e-02 3.04560704781735e-02 + 2.02283271437812e-02 3.22731904280343e-02 + 2.23410892379826e-02 3.41200707129672e-02 + 2.45803161096591e-02 3.60061322399834e-02 + 2.69523034357121e-02 3.79258490183542e-02 + 2.94661214249216e-02 3.98790227559557e-02 + 3.21182316854737e-02 4.18723073706309e-02 + 3.49189765158157e-02 4.39025161395751e-02 + 3.78764907558025e-02 4.59628851663624e-02 + 4.09963031658456e-02 4.80556676923546e-02 + 4.42775927892050e-02 5.01900205707697e-02 + 4.77343365858657e-02 5.23520241988731e-02 + 5.13731297355052e-02 5.45423734775189e-02 + 5.51950546654045e-02 5.67687018233320e-02 + 5.92113866358186e-02 5.90218736527301e-02 + 6.34234392442166e-02 6.13116302117422e-02 + 6.78462003333466e-02 6.36214314140050e-02 + 7.24854173464343e-02 6.59533657552206e-02 + 7.73419721841157e-02 6.83186401819959e-02 + 8.24324258544088e-02 7.06971481688955e-02 + 8.77613607346135e-02 7.30926428047549e-02 + 9.33346253668055e-02 7.55076582271502e-02 + 9.91628221387800e-02 7.79350885797270e-02 + 1.05254564598752e-01 8.03695380742510e-02 + 1.11616753158002e-01 8.28125781644698e-02 + 1.18259294307182e-01 8.52558088653510e-02 + 1.25189263783572e-01 8.76985152086404e-02 + 1.32415679289748e-01 9.01369747472587e-02 + 1.39947873838956e-01 9.25638030881446e-02 + 1.47794845481183e-01 9.49707607832480e-02 + 1.55965915271520e-01 9.73499622034032e-02 + 1.64469189511735e-01 9.96967278841057e-02 + 1.73311416702080e-01 1.02010530578746e-01 + 1.82503742461270e-01 1.04273623478212e-01 + 1.92050672615684e-01 1.06491541481398e-01 + 2.01966200947807e-01 1.08628345168654e-01 + 2.12256126598972e-01 1.10681929211142e-01 + 2.22927191842667e-01 1.12642214263348e-01 + 2.33987552164155e-01 1.14491142152048e-01 + 2.45440161850974e-01 1.16234688095526e-01 + 2.57296008031495e-01 1.17825202458106e-01 + 2.69556869203747e-01 1.19267427279133e-01 + 2.82229070262522e-01 1.20524379694892e-01 + 2.95316275100028e-01 1.21569011458766e-01 + 3.08820531899773e-01 1.22372406982529e-01 + 3.22741461950530e-01 1.22915930928339e-01 + 3.37078134209340e-01 1.23149875849477e-01 + 3.51826981727722e-01 1.23062131822088e-01 + 3.66983039246985e-01 1.22645337613189e-01 + 3.82543070599223e-01 1.21930860322884e-01 + 3.98503391798556e-01 1.20928153680211e-01 + 4.14860961126985e-01 1.19652845240075e-01 + 4.31612326060530e-01 1.18111343121154e-01 + 4.48752327492312e-01 1.16301638158787e-01 + 4.66272601249854e-01 1.14199654104434e-01 + 4.84172419107913e-01 1.11855636518184e-01 + 5.02444493519843e-01 1.09258193501888e-01 + 5.21080236029992e-01 1.06406605973784e-01 + 5.40074886324364e-01 1.03326688418026e-01 + 5.59419655929053e-01 1.00019465978113e-01 + 5.79105612175721e-01 9.64916235087976e-02 + 5.99125173361441e-01 9.27647911198193e-02 + 6.19466430557399e-01 8.88409323564860e-02 + 6.40119041978738e-01 8.47390121899819e-02 + 6.61070257644903e-01 8.04603243420791e-02 + 6.82307901055849e-01 7.60197144231869e-02 + 7.03821798847536e-01 7.14430901975401e-02 + 7.25594294352276e-01 6.67273876453086e-02 + 7.47609060933277e-01 6.18819437827459e-02 + 7.69845737824426e-01 5.68996656088332e-02 + 7.92286051630428e-01 5.17884210392101e-02 + 8.14910827049322e-01 4.65565586752961e-02 + 8.37702906504111e-01 4.12259060670082e-02 + 8.60644007466582e-01 3.58073758391948e-02 + 8.83708956400804e-01 3.02965383060978e-02 + 9.06880276867715e-01 2.47142694962048e-02 + 9.30133788123677e-01 1.90677931913939e-02 + 9.53449456906722e-01 1.32665027689235e-02 + 9.76786262644257e-01 7.36258542738043e-03 + 1.00000000000000e+00 1.36768088735877e-03 diff --git a/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF26_Coords.txt b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF26_Coords.txt new file mode 100644 index 00000000..cf7fc7ad --- /dev/null +++ b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF26_Coords.txt @@ -0,0 +1,208 @@ + 201 NumCoords ! The number of coordinates in the airfoil shape file (including an extra coordinate for airfoil reference). Set to zero if coordinates not included. +! ......... x-y coordinates are next if NumCoords > 0 ............. +! x-y coordinate of airfoil reference +! x/c y/c + 0.250000 0 +! coordinates of airfoil shape +! interpolation to 200 points +! x/c y/c + 1.00000000000000e+00 -1.24163918250367e-03 + 9.76041165887563e-01 1.99488268803741e-03 + 9.52121914098850e-01 4.75706252222044e-03 + 9.28199957236603e-01 7.09542956274019e-03 + 9.04291190262318e-01 8.93443745793852e-03 + 8.80430343444036e-01 9.96657729426452e-03 + 8.56672689113696e-01 9.94290435584814e-03 + 8.33075425877888e-01 9.19689625764953e-03 + 8.09695700165266e-01 7.47347691185626e-03 + 7.86588885771507e-01 4.89111440127801e-03 + 7.63799981052509e-01 1.51070336812985e-03 + 7.41353018207342e-01 -2.52044512396319e-03 + 7.19257743648676e-01 -7.04038680187796e-03 + 6.97520950922480e-01 -1.19358851549070e-02 + 6.76139778430185e-01 -1.70807096849569e-02 + 6.55114191085606e-01 -2.23867022793893e-02 + 6.34437029834687e-01 -2.77559055040500e-02 + 6.14099171583599e-01 -3.30936716419077e-02 + 5.94097092702040e-01 -3.83329090713677e-02 + 5.74431276878783e-01 -4.34270288627529e-02 + 5.55097922205893e-01 -4.83165117769746e-02 + 5.36103244219295e-01 -5.29813461185869e-02 + 5.17451514118577e-01 -5.73969020907143e-02 + 4.99146144876149e-01 -6.15389789381977e-02 + 4.81187008959400e-01 -6.53691205567300e-02 + 4.63583334863196e-01 -6.88825029007271e-02 + 4.46345674250821e-01 -7.21042694778078e-02 + 4.29476426936704e-01 -7.50078286995993e-02 + 4.12981165598887e-01 -7.75910433182066e-02 + 3.96868697220895e-01 -7.98780646047934e-02 + 3.81143737274277e-01 -8.18762285984978e-02 + 3.65809950832190e-01 -8.35894755418217e-02 + 3.50871346715946e-01 -8.50344502846749e-02 + 3.36330856482784e-01 -8.62291005970239e-02 + 3.22187680974826e-01 -8.71590314211491e-02 + 3.08443381198299e-01 -8.78366569779970e-02 + 2.95097824515779e-01 -8.82768172546241e-02 + 2.82150316172696e-01 -8.84841421890272e-02 + 2.69599713195053e-01 -8.84700415928376e-02 + 2.57443538674293e-01 -8.82648900755557e-02 + 2.45678503760535e-01 -8.78783328013873e-02 + 2.34300892069519e-01 -8.73191978590562e-02 + 2.23305176083759e-01 -8.66151143715721e-02 + 2.12686475906400e-01 -8.57717042278548e-02 + 2.02439201431732e-01 -8.47960575058360e-02 + 1.92555334399891e-01 -8.37147804336106e-02 + 1.83029072759030e-01 -8.25291243560209e-02 + 1.73852988185549e-01 -8.12499391500962e-02 + 1.65019713285519e-01 -7.98863532611348e-02 + 1.56521149653515e-01 -7.84487425858802e-02 + 1.48348326905127e-01 -7.69504193661685e-02 + 1.40492169632055e-01 -7.54025801721342e-02 + 1.32945934195466e-01 -7.38053647018080e-02 + 1.25701000521494e-01 -7.21672889164535e-02 + 1.18749063872964e-01 -7.04928479452887e-02 + 1.12082069469409e-01 -6.87847420009533e-02 + 1.05690639166719e-01 -6.70564170338887e-02 + 9.95644793751720e-02 -6.53155594973088e-02 + 9.36997891046597e-02 -6.35528503057422e-02 + 8.80860404700645e-02 -6.17798179936638e-02 + 8.27138402760154e-02 -6.00046280095742e-02 + 7.75786796919451e-02 -5.82199952095701e-02 + 7.26702775903076e-02 -5.64364109081874e-02 + 6.79824154250675e-02 -5.46532131450536e-02 + 6.35091047142614e-02 -5.28689233118743e-02 + 5.92419326453291e-02 -5.10893765254210e-02 + 5.51761610142073e-02 -4.93108527891892e-02 + 5.13012904354392e-02 -4.75441103336549e-02 + 4.76145565870374e-02 -4.57830799218584e-02 + 4.41097775457074e-02 -4.40286611417737e-02 + 4.07797547228364e-02 -4.22832639538696e-02 + 3.76203144073222e-02 -4.05471915450099e-02 + 3.46254260858043e-02 -3.88215755752492e-02 + 3.17889101119942e-02 -3.71070792104368e-02 + 2.91063013242030e-02 -3.54070623086104e-02 + 2.65680917385227e-02 -3.37242560099722e-02 + 2.41746444824902e-02 -3.20578976536326e-02 + 2.19171444247013e-02 -3.04080975483655e-02 + 1.97858149698125e-02 -2.87865206302891e-02 + 1.77816785975911e-02 -2.71845498672619e-02 + 1.59022597396959e-02 -2.56014672844354e-02 + 1.41389646872167e-02 -2.40428780632352e-02 + 1.24868469400250e-02 -2.25098697316461e-02 + 1.09480652882895e-02 -2.09965445874096e-02 + 9.51590058520777e-03 -1.95072970846173e-02 + 8.19359579424781e-03 -1.80358499675050e-02 + 6.97242094431141e-03 -1.65886214694131e-02 + 5.86117299541770e-03 -1.51566425360256e-02 + 4.85595721623195e-03 -1.37425320553921e-02 + 3.94940941742267e-03 -1.23512986917568e-02 + 3.14133805635955e-03 -1.09822611963997e-02 + 2.44321685058300e-03 -9.63205407941857e-03 + 1.83022786901874e-03 -8.31193681735096e-03 + 1.31884419349740e-03 -7.01717270777278e-03 + 8.97352130663886e-04 -5.75368875832799e-03 + 5.63740815773768e-04 -4.52380901007206e-03 + 3.11436976892490e-04 -3.33125476138120e-03 + 1.35836193808489e-04 -2.17811670838639e-03 + 4.45280502729537e-05 -1.06661993857544e-03 + 0.00000000000000e+00 0.00000000000000e+00 + 2.66760054509128e-05 1.06620363196370e-03 + 1.03135511949883e-04 2.17873971903504e-03 + 2.50714385917578e-04 3.33437480200911e-03 + 4.62713811117844e-04 4.53305150068868e-03 + 7.43003875184307e-04 5.77372654297466e-03 + 1.10319761909825e-03 7.05282637820245e-03 + 1.54998013794877e-03 8.36733050300788e-03 + 2.09725226970234e-03 9.71027755670584e-03 + 2.74048621866142e-03 1.10830229161061e-02 + 3.47313095950444e-03 1.24853542942127e-02 + 4.30082217565610e-03 1.39166476275545e-02 + 5.21857196014794e-03 1.53794131710022e-02 + 6.22534316879645e-03 1.68755017759930e-02 + 7.32700741881788e-03 1.84027736911195e-02 + 8.52685165419718e-03 1.99605923185556e-02 + 9.82457508956703e-03 2.15515967524936e-02 + 1.12235177290181e-02 2.31756834085188e-02 + 1.27200503919435e-02 2.48389080154999e-02 + 1.43242279905998e-02 2.65369959399126e-02 + 1.60404245440130e-02 2.82678634249202e-02 + 1.78725008542331e-02 3.00332073110525e-02 + 1.98202147599872e-02 3.18374092114472e-02 + 2.18950460972363e-02 3.36723552878899e-02 + 2.40945084991586e-02 3.55478542511501e-02 + 2.64266594338935e-02 3.74562543671355e-02 + 2.89010475331631e-02 3.93973576550753e-02 + 3.15128856164724e-02 4.13789637240956e-02 + 3.42721423161374e-02 4.33986437239279e-02 + 3.71869766220148e-02 4.54495802606190e-02 + 4.02627031087678e-02 4.75346101784617e-02 + 4.35002150116920e-02 4.96601391986086e-02 + 4.69116164095437e-02 5.18156791609964e-02 + 5.05037836700218e-02 5.40013488484752e-02 + 5.42786678950318e-02 5.62234865342880e-02 + 5.82483001631071e-02 5.84716108883904e-02 + 6.24154978875846e-02 6.07527350834376e-02 + 6.67896743600186e-02 6.30611281243319e-02 + 7.13799999231155e-02 6.53925012153297e-02 + 7.61894222215938e-02 6.77537053720447e-02 + 8.12317662654453e-02 7.01307269242542e-02 + 8.65117557737097e-02 7.25279882775677e-02 + 9.20362184425747e-02 7.49454680746529e-02 + 9.78162759593724e-02 7.73748306064237e-02 + 1.03860552928939e-01 7.98107486389235e-02 + 1.10175778191298e-01 8.22554075072582e-02 + 1.16770214549517e-01 8.47058953467228e-02 + 1.23653203755665e-01 8.71546056154831e-02 + 1.30834337594950e-01 8.95968004923253e-02 + 1.38321670606146e-01 9.20292431191944e-02 + 1.46124389981669e-01 9.44436195002828e-02 + 1.54251904677806e-01 9.68324582790219e-02 + 1.62712200809751e-01 9.91923751629681e-02 + 1.71513312218537e-01 1.01517930059788e-01 + 1.80666845834493e-01 1.03789912148757e-01 + 1.90176370985942e-01 1.06018468666417e-01 + 2.00055657032727e-01 1.08170258618851e-01 + 2.10311372495842e-01 1.10238994003200e-01 + 2.20950065131051e-01 1.12217532980930e-01 + 2.31980866532305e-01 1.14082146312415e-01 + 2.43406769821147e-01 1.15839163095632e-01 + 2.55238147077280e-01 1.17446579677784e-01 + 2.67477513281741e-01 1.18905422327083e-01 + 2.80131073498889e-01 1.20180419750751e-01 + 2.93202720534022e-01 1.21245816208447e-01 + 3.06694896295832e-01 1.22070353231193e-01 + 3.20607263770737e-01 1.22636054133308e-01 + 3.34939268318345e-01 1.22896410171916e-01 + 3.49687302556342e-01 1.22832514196396e-01 + 3.64846676687070e-01 1.22439952772840e-01 + 3.80414003309436e-01 1.21746813551104e-01 + 3.96385756696833e-01 1.20764922463268e-01 + 4.12759002166226e-01 1.19510124555119e-01 + 4.29529884389691e-01 1.17984334619021e-01 + 4.46694073835668e-01 1.16192944649426e-01 + 4.64243196738119e-01 1.14110111055027e-01 + 4.82175957113290e-01 1.11782567369759e-01 + 5.00485020623298e-01 1.09197665297171e-01 + 5.19162565566196e-01 1.06360394677582e-01 + 5.38203389191021e-01 1.03293317692501e-01 + 5.57598376049888e-01 9.99962209759983e-02 + 5.77338386735964e-01 9.64747451695822e-02 + 5.97416810267783e-01 9.27560007851153e-02 + 6.17822173815498e-01 8.88440305009192e-02 + 6.38542633624223e-01 8.47454500445900e-02 + 6.59565297378976e-01 8.04670393872135e-02 + 6.80878616121945e-01 7.60267543210821e-02 + 7.02471652655181e-01 7.14503788937509e-02 + 7.24326595397154e-01 6.67348588383987e-02 + 7.46427190977622e-01 6.18895589890343e-02 + 7.68752587046382e-01 5.69073596180092e-02 + 7.91284306570890e-01 5.17961434205325e-02 + 8.14003121917812e-01 4.65642776255388e-02 + 8.36892227450033e-01 4.12336544355374e-02 + 8.59931497183523e-01 3.58149763309393e-02 + 8.83096691520270e-01 3.03040139923268e-02 + 9.06368918443855e-01 2.47214332231998e-02 + 9.29725626335315e-01 1.90747607002302e-02 + 9.53145857383183e-01 1.33087425250220e-02 + 9.76587861324942e-01 7.46542536535991e-03 + 1.00000000000000e+00 1.53835660395088e-03 diff --git a/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF27_Coords.txt b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF27_Coords.txt new file mode 100644 index 00000000..a8559b09 --- /dev/null +++ b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF27_Coords.txt @@ -0,0 +1,208 @@ + 201 NumCoords ! The number of coordinates in the airfoil shape file (including an extra coordinate for airfoil reference). Set to zero if coordinates not included. +! ......... x-y coordinates are next if NumCoords > 0 ............. +! x-y coordinate of airfoil reference +! x/c y/c + 0.250000 0 +! coordinates of airfoil shape +! interpolation to 200 points +! x/c y/c + 1.00000000000000e+00 -1.24164223325347e-03 + 9.76041164392396e-01 1.99488062082566e-03 + 9.52121910751731e-01 4.75706135335948e-03 + 9.28199952199219e-01 7.09542915865422e-03 + 9.04291183649571e-01 8.93443767118390e-03 + 8.80430335305919e-01 9.96657750751068e-03 + 8.56672679460919e-01 9.94290456909515e-03 + 8.33075414701384e-01 9.19689647089799e-03 + 8.09695687435274e-01 7.47347776900502e-03 + 7.86588871455130e-01 4.89111649401108e-03 + 7.63799965113471e-01 1.51070681640460e-03 + 7.41353000623285e-01 -2.52044025059049e-03 + 7.19257724385752e-01 -7.04038035491660e-03 + 6.97520929992240e-01 -1.19358771025367e-02 + 6.76139755888505e-01 -1.70807000809784e-02 + 6.55114166969036e-01 -2.23866910906930e-02 + 6.34437004205735e-01 -2.77558927368869e-02 + 6.14099144503465e-01 -3.30936572688430e-02 + 5.94097064299627e-01 -3.83328932311329e-02 + 5.74431247267374e-01 -4.34270116338703e-02 + 5.55097891490535e-01 -4.83164932012163e-02 + 5.36103212560625e-01 -5.29813263991864e-02 + 5.17451481630547e-01 -5.73968812892901e-02 + 4.99146111683925e-01 -6.15389571602501e-02 + 4.81186975180132e-01 -6.53690978763222e-02 + 4.63583300631990e-01 -6.88824794729917e-02 + 4.46345639685456e-01 -7.21042454369658e-02 + 4.29476392143564e-01 -7.50078041225779e-02 + 4.12981130677270e-01 -7.75910183051978e-02 + 3.96868662278405e-01 -7.98780393343755e-02 + 3.81143702382537e-01 -8.18762030718283e-02 + 3.65809916070270e-01 -8.35894498418953e-02 + 3.50871312147949e-01 -8.50344244357429e-02 + 3.36330822167539e-01 -8.62290745383426e-02 + 3.22187646977060e-01 -8.71590051574009e-02 + 3.08443347581371e-01 -8.78366305562361e-02 + 2.95097791339595e-01 -8.82767906155356e-02 + 2.82150283499973e-01 -8.84841152823162e-02 + 2.69599681087069e-01 -8.84700144337475e-02 + 2.57443507192848e-01 -8.82648626051867e-02 + 2.45678472964112e-01 -8.78783050259134e-02 + 2.34300862010750e-01 -8.73191697949781e-02 + 2.23305146809674e-01 -8.66150861037270e-02 + 2.12686447462944e-01 -8.57716757140843e-02 + 2.02439173855586e-01 -8.47960288193625e-02 + 1.92555307706631e-01 -8.37147516939257e-02 + 1.83029046978344e-01 -8.25290955835651e-02 + 1.73852963346223e-01 -8.12499103431124e-02 + 1.65019689389359e-01 -7.98863245514951e-02 + 1.56521126720043e-01 -7.84487139477401e-02 + 1.48348304923117e-01 -7.69503909453266e-02 + 1.40492148638460e-01 -7.54025518805833e-02 + 1.32945914165942e-01 -7.38053366709304e-02 + 1.25700981456047e-01 -7.21672611749456e-02 + 1.18749045764871e-01 -7.04928205316870e-02 + 1.12082052295785e-01 -6.87847149917338e-02 + 1.05690622940757e-01 -6.70563903986223e-02 + 9.95644640688240e-02 -6.53155333147837e-02 + 9.36997746804533e-02 -6.35528246583057e-02 + 8.80860269419856e-02 -6.17797928182627e-02 + 8.27138276159543e-02 -6.00046033630738e-02 + 7.75786679035966e-02 -5.82199710630611e-02 + 7.26702668766427e-02 -5.64363872841197e-02 + 6.79824057221827e-02 -5.46531901393429e-02 + 6.35090960690899e-02 -5.28689008362057e-02 + 5.92419250258708e-02 -5.10893545882387e-02 + 5.51761543119222e-02 -4.93108314830338e-02 + 5.13012845894761e-02 -4.75440896934531e-02 + 4.76145515997845e-02 -4.57830599145488e-02 + 4.41097733544431e-02 -4.40286418035125e-02 + 4.07797512889574e-02 -4.22832452899324e-02 + 3.76203116687853e-02 -4.05471735735779e-02 + 3.46254239696624e-02 -3.88215583285753e-02 + 3.17889085655347e-02 -3.71070627007449e-02 + 2.91063003142196e-02 -3.54070465342894e-02 + 2.65680912572024e-02 -3.37242409387003e-02 + 2.41746444372365e-02 -3.20578833095496e-02 + 2.19171444247057e-02 -3.04080839884921e-02 + 1.97858149698170e-02 -2.87865078379770e-02 + 1.77816785975956e-02 -2.71845378027204e-02 + 1.59022597397006e-02 -2.56014559510294e-02 + 1.41389646872214e-02 -2.40428674601252e-02 + 1.24868469400299e-02 -2.25098598379508e-02 + 1.09480652882944e-02 -2.09965353712404e-02 + 9.51590058521273e-03 -1.95072886041607e-02 + 8.19359596476239e-03 -1.80358421377615e-02 + 6.97242121388991e-03 -1.65886143273830e-02 + 5.86117330807756e-03 -1.51566360782969e-02 + 4.85595758514205e-03 -1.37425262435773e-02 + 3.94940976333073e-03 -1.23512935315688e-02 + 3.14133835342164e-03 -1.09822566687452e-02 + 2.44321714150649e-03 -9.63205013980954e-03 + 1.83022809796061e-03 -8.31193344939125e-03 + 1.31884436057794e-03 -7.01716988880847e-03 + 8.97352193736273e-04 -5.75368646998309e-03 + 5.63740905842356e-04 -4.52380720725293e-03 + 3.11437030347409e-04 -3.33125343689109e-03 + 1.35836224347021e-04 -2.17811584123553e-03 + 4.45280630750671e-05 -1.06661951254253e-03 + 0.00000000000000e+00 0.00000000000000e+00 + 2.66759975469128e-05 1.06620320574453e-03 + 1.03135502882502e-04 2.17873885472331e-03 + 2.50714361136359e-04 3.33437348745562e-03 + 4.62713791811825e-04 4.53304972124580e-03 + 7.43003731765193e-04 5.77372430028259e-03 + 1.10319742939756e-03 7.05282365458086e-03 + 1.54997995490141e-03 8.36732726269284e-03 + 2.09725167376054e-03 9.71027388884010e-03 + 2.74048539040992e-03 1.10830187729024e-02 + 3.47312973743479e-03 1.24853497385656e-02 + 4.30082057862358e-03 1.39166426421534e-02 + 5.21856989199968e-03 1.53794078029284e-02 + 6.22534057591764e-03 1.68754960531490e-02 + 7.32700432621982e-03 1.84027675881834e-02 + 8.52684801153103e-03 1.99605858637636e-02 + 9.82457090745577e-03 2.15515899247781e-02 + 1.12235129483028e-02 2.31756762504219e-02 + 1.27200449567995e-02 2.48389005693531e-02 + 1.43242218865420e-02 2.65369882056060e-02 + 1.60404178082626e-02 2.82678553499417e-02 + 1.78724934115684e-02 3.00331989618528e-02 + 1.98202065802740e-02 3.18374006104675e-02 + 2.18950371605342e-02 3.36723464545640e-02 + 2.40944987682683e-02 3.55478452136134e-02 + 2.64266489071067e-02 3.74562451109318e-02 + 2.89010362193680e-02 3.93973481646352e-02 + 3.15128734993139e-02 4.13789540071277e-02 + 3.42721293711695e-02 4.33986338037802e-02 + 3.71869628254960e-02 4.54495701594197e-02 + 4.02626884327817e-02 4.75345999298599e-02 + 4.35001994625931e-02 4.96601287812404e-02 + 4.69115999564798e-02 5.18156686218105e-02 + 5.05037662874084e-02 5.40013382232845e-02 + 5.42786495746735e-02 5.62234758330505e-02 + 5.82482809121614e-02 5.84716000937855e-02 + 6.24154777430842e-02 6.07527241240193e-02 + 6.67896532476333e-02 6.30611171442784e-02 + 7.13799778368031e-02 6.53924902316809e-02 + 7.61893991966636e-02 6.77536943148228e-02 + 8.12317422826271e-02 7.01307158448530e-02 + 8.65117308166364e-02 7.25279772295263e-02 + 9.20361925143298e-02 7.49454570665521e-02 + 9.78162490733068e-02 7.73748196288702e-02 + 1.03860525098628e-01 7.98107376836716e-02 + 1.10175749426971e-01 8.22553965780306e-02 + 1.16770184828620e-01 8.47058845532950e-02 + 1.23653173100621e-01 8.71545949342700e-02 + 1.30834306039958e-01 8.95967898803351e-02 + 1.38321638159842e-01 9.20292326136635e-02 + 1.46124356656426e-01 9.44436091370127e-02 + 1.54251870487751e-01 9.68324481019705e-02 + 1.62712165766615e-01 9.91923652415109e-02 + 1.71513276359922e-01 1.01517920367561e-01 + 1.80666809206519e-01 1.03789902629961e-01 + 1.90176333616483e-01 1.06018459355824e-01 + 2.00055618945293e-01 1.08170249602257e-01 + 2.10311333730825e-01 1.10238985284240e-01 + 2.20950025725240e-01 1.12217524621099e-01 + 2.31980826542045e-01 1.14082138261491e-01 + 2.43406729303366e-01 1.15839155310084e-01 + 2.55238106076494e-01 1.17446572225308e-01 + 2.67477471857320e-01 1.18905415201973e-01 + 2.80131031707401e-01 1.20180412981259e-01 + 2.93202678436719e-01 1.21245809848125e-01 + 3.06694853961626e-01 1.22070347287731e-01 + 3.20607221269401e-01 1.22636048627399e-01 + 3.34939225727116e-01 1.22896405187495e-01 + 3.49687259951759e-01 1.22832509683795e-01 + 3.64846634151165e-01 1.22439948740756e-01 + 3.80413960921238e-01 1.21746809942571e-01 + 3.96385714538567e-01 1.20764919268824e-01 + 4.12758960322157e-01 1.19510121769152e-01 + 4.29529842936380e-01 1.17984332147218e-01 + 4.46694032865700e-01 1.16192942543521e-01 + 4.64243156344356e-01 1.14110109333428e-01 + 4.82175917377177e-01 1.11782565979692e-01 + 5.00484981625201e-01 1.09197664159710e-01 + 5.19162527401886e-01 1.06360393829411e-01 + 5.38203351947280e-01 1.03293317103930e-01 + 5.57598339807246e-01 9.99962205928791e-02 + 5.77338351570623e-01 9.64747449157602e-02 + 5.97416776275050e-01 9.27560006949552e-02 + 6.17822141099620e-01 8.88440306520127e-02 + 6.38542602259551e-01 8.47454502578335e-02 + 6.59565267437110e-01 8.04670396004571e-02 + 6.80878587686638e-01 7.60267545343259e-02 + 7.02471625795160e-01 7.14503791069948e-02 + 7.24326570178040e-01 6.67348590516426e-02 + 7.46427167466697e-01 6.18895592022783e-02 + 7.68752565300964e-01 5.69073598312532e-02 + 7.91284286644164e-01 5.17961436337766e-02 + 8.14003103862062e-01 4.65642778387828e-02 + 8.36892211324902e-01 4.12336546487814e-02 + 8.59931483011660e-01 3.58149765441833e-02 + 8.83096679342750e-01 3.03040142055707e-02 + 9.06368908273977e-01 2.47214334364437e-02 + 9.29725618218844e-01 1.90747609134739e-02 + 9.53145851346865e-01 1.33087434425404e-02 + 9.76587857380671e-01 7.46542748662253e-03 + 1.00000000000000e+00 1.53836008119114e-03 diff --git a/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF28_Coords.txt b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF28_Coords.txt new file mode 100644 index 00000000..a8559b09 --- /dev/null +++ b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF28_Coords.txt @@ -0,0 +1,208 @@ + 201 NumCoords ! The number of coordinates in the airfoil shape file (including an extra coordinate for airfoil reference). Set to zero if coordinates not included. +! ......... x-y coordinates are next if NumCoords > 0 ............. +! x-y coordinate of airfoil reference +! x/c y/c + 0.250000 0 +! coordinates of airfoil shape +! interpolation to 200 points +! x/c y/c + 1.00000000000000e+00 -1.24164223325347e-03 + 9.76041164392396e-01 1.99488062082566e-03 + 9.52121910751731e-01 4.75706135335948e-03 + 9.28199952199219e-01 7.09542915865422e-03 + 9.04291183649571e-01 8.93443767118390e-03 + 8.80430335305919e-01 9.96657750751068e-03 + 8.56672679460919e-01 9.94290456909515e-03 + 8.33075414701384e-01 9.19689647089799e-03 + 8.09695687435274e-01 7.47347776900502e-03 + 7.86588871455130e-01 4.89111649401108e-03 + 7.63799965113471e-01 1.51070681640460e-03 + 7.41353000623285e-01 -2.52044025059049e-03 + 7.19257724385752e-01 -7.04038035491660e-03 + 6.97520929992240e-01 -1.19358771025367e-02 + 6.76139755888505e-01 -1.70807000809784e-02 + 6.55114166969036e-01 -2.23866910906930e-02 + 6.34437004205735e-01 -2.77558927368869e-02 + 6.14099144503465e-01 -3.30936572688430e-02 + 5.94097064299627e-01 -3.83328932311329e-02 + 5.74431247267374e-01 -4.34270116338703e-02 + 5.55097891490535e-01 -4.83164932012163e-02 + 5.36103212560625e-01 -5.29813263991864e-02 + 5.17451481630547e-01 -5.73968812892901e-02 + 4.99146111683925e-01 -6.15389571602501e-02 + 4.81186975180132e-01 -6.53690978763222e-02 + 4.63583300631990e-01 -6.88824794729917e-02 + 4.46345639685456e-01 -7.21042454369658e-02 + 4.29476392143564e-01 -7.50078041225779e-02 + 4.12981130677270e-01 -7.75910183051978e-02 + 3.96868662278405e-01 -7.98780393343755e-02 + 3.81143702382537e-01 -8.18762030718283e-02 + 3.65809916070270e-01 -8.35894498418953e-02 + 3.50871312147949e-01 -8.50344244357429e-02 + 3.36330822167539e-01 -8.62290745383426e-02 + 3.22187646977060e-01 -8.71590051574009e-02 + 3.08443347581371e-01 -8.78366305562361e-02 + 2.95097791339595e-01 -8.82767906155356e-02 + 2.82150283499973e-01 -8.84841152823162e-02 + 2.69599681087069e-01 -8.84700144337475e-02 + 2.57443507192848e-01 -8.82648626051867e-02 + 2.45678472964112e-01 -8.78783050259134e-02 + 2.34300862010750e-01 -8.73191697949781e-02 + 2.23305146809674e-01 -8.66150861037270e-02 + 2.12686447462944e-01 -8.57716757140843e-02 + 2.02439173855586e-01 -8.47960288193625e-02 + 1.92555307706631e-01 -8.37147516939257e-02 + 1.83029046978344e-01 -8.25290955835651e-02 + 1.73852963346223e-01 -8.12499103431124e-02 + 1.65019689389359e-01 -7.98863245514951e-02 + 1.56521126720043e-01 -7.84487139477401e-02 + 1.48348304923117e-01 -7.69503909453266e-02 + 1.40492148638460e-01 -7.54025518805833e-02 + 1.32945914165942e-01 -7.38053366709304e-02 + 1.25700981456047e-01 -7.21672611749456e-02 + 1.18749045764871e-01 -7.04928205316870e-02 + 1.12082052295785e-01 -6.87847149917338e-02 + 1.05690622940757e-01 -6.70563903986223e-02 + 9.95644640688240e-02 -6.53155333147837e-02 + 9.36997746804533e-02 -6.35528246583057e-02 + 8.80860269419856e-02 -6.17797928182627e-02 + 8.27138276159543e-02 -6.00046033630738e-02 + 7.75786679035966e-02 -5.82199710630611e-02 + 7.26702668766427e-02 -5.64363872841197e-02 + 6.79824057221827e-02 -5.46531901393429e-02 + 6.35090960690899e-02 -5.28689008362057e-02 + 5.92419250258708e-02 -5.10893545882387e-02 + 5.51761543119222e-02 -4.93108314830338e-02 + 5.13012845894761e-02 -4.75440896934531e-02 + 4.76145515997845e-02 -4.57830599145488e-02 + 4.41097733544431e-02 -4.40286418035125e-02 + 4.07797512889574e-02 -4.22832452899324e-02 + 3.76203116687853e-02 -4.05471735735779e-02 + 3.46254239696624e-02 -3.88215583285753e-02 + 3.17889085655347e-02 -3.71070627007449e-02 + 2.91063003142196e-02 -3.54070465342894e-02 + 2.65680912572024e-02 -3.37242409387003e-02 + 2.41746444372365e-02 -3.20578833095496e-02 + 2.19171444247057e-02 -3.04080839884921e-02 + 1.97858149698170e-02 -2.87865078379770e-02 + 1.77816785975956e-02 -2.71845378027204e-02 + 1.59022597397006e-02 -2.56014559510294e-02 + 1.41389646872214e-02 -2.40428674601252e-02 + 1.24868469400299e-02 -2.25098598379508e-02 + 1.09480652882944e-02 -2.09965353712404e-02 + 9.51590058521273e-03 -1.95072886041607e-02 + 8.19359596476239e-03 -1.80358421377615e-02 + 6.97242121388991e-03 -1.65886143273830e-02 + 5.86117330807756e-03 -1.51566360782969e-02 + 4.85595758514205e-03 -1.37425262435773e-02 + 3.94940976333073e-03 -1.23512935315688e-02 + 3.14133835342164e-03 -1.09822566687452e-02 + 2.44321714150649e-03 -9.63205013980954e-03 + 1.83022809796061e-03 -8.31193344939125e-03 + 1.31884436057794e-03 -7.01716988880847e-03 + 8.97352193736273e-04 -5.75368646998309e-03 + 5.63740905842356e-04 -4.52380720725293e-03 + 3.11437030347409e-04 -3.33125343689109e-03 + 1.35836224347021e-04 -2.17811584123553e-03 + 4.45280630750671e-05 -1.06661951254253e-03 + 0.00000000000000e+00 0.00000000000000e+00 + 2.66759975469128e-05 1.06620320574453e-03 + 1.03135502882502e-04 2.17873885472331e-03 + 2.50714361136359e-04 3.33437348745562e-03 + 4.62713791811825e-04 4.53304972124580e-03 + 7.43003731765193e-04 5.77372430028259e-03 + 1.10319742939756e-03 7.05282365458086e-03 + 1.54997995490141e-03 8.36732726269284e-03 + 2.09725167376054e-03 9.71027388884010e-03 + 2.74048539040992e-03 1.10830187729024e-02 + 3.47312973743479e-03 1.24853497385656e-02 + 4.30082057862358e-03 1.39166426421534e-02 + 5.21856989199968e-03 1.53794078029284e-02 + 6.22534057591764e-03 1.68754960531490e-02 + 7.32700432621982e-03 1.84027675881834e-02 + 8.52684801153103e-03 1.99605858637636e-02 + 9.82457090745577e-03 2.15515899247781e-02 + 1.12235129483028e-02 2.31756762504219e-02 + 1.27200449567995e-02 2.48389005693531e-02 + 1.43242218865420e-02 2.65369882056060e-02 + 1.60404178082626e-02 2.82678553499417e-02 + 1.78724934115684e-02 3.00331989618528e-02 + 1.98202065802740e-02 3.18374006104675e-02 + 2.18950371605342e-02 3.36723464545640e-02 + 2.40944987682683e-02 3.55478452136134e-02 + 2.64266489071067e-02 3.74562451109318e-02 + 2.89010362193680e-02 3.93973481646352e-02 + 3.15128734993139e-02 4.13789540071277e-02 + 3.42721293711695e-02 4.33986338037802e-02 + 3.71869628254960e-02 4.54495701594197e-02 + 4.02626884327817e-02 4.75345999298599e-02 + 4.35001994625931e-02 4.96601287812404e-02 + 4.69115999564798e-02 5.18156686218105e-02 + 5.05037662874084e-02 5.40013382232845e-02 + 5.42786495746735e-02 5.62234758330505e-02 + 5.82482809121614e-02 5.84716000937855e-02 + 6.24154777430842e-02 6.07527241240193e-02 + 6.67896532476333e-02 6.30611171442784e-02 + 7.13799778368031e-02 6.53924902316809e-02 + 7.61893991966636e-02 6.77536943148228e-02 + 8.12317422826271e-02 7.01307158448530e-02 + 8.65117308166364e-02 7.25279772295263e-02 + 9.20361925143298e-02 7.49454570665521e-02 + 9.78162490733068e-02 7.73748196288702e-02 + 1.03860525098628e-01 7.98107376836716e-02 + 1.10175749426971e-01 8.22553965780306e-02 + 1.16770184828620e-01 8.47058845532950e-02 + 1.23653173100621e-01 8.71545949342700e-02 + 1.30834306039958e-01 8.95967898803351e-02 + 1.38321638159842e-01 9.20292326136635e-02 + 1.46124356656426e-01 9.44436091370127e-02 + 1.54251870487751e-01 9.68324481019705e-02 + 1.62712165766615e-01 9.91923652415109e-02 + 1.71513276359922e-01 1.01517920367561e-01 + 1.80666809206519e-01 1.03789902629961e-01 + 1.90176333616483e-01 1.06018459355824e-01 + 2.00055618945293e-01 1.08170249602257e-01 + 2.10311333730825e-01 1.10238985284240e-01 + 2.20950025725240e-01 1.12217524621099e-01 + 2.31980826542045e-01 1.14082138261491e-01 + 2.43406729303366e-01 1.15839155310084e-01 + 2.55238106076494e-01 1.17446572225308e-01 + 2.67477471857320e-01 1.18905415201973e-01 + 2.80131031707401e-01 1.20180412981259e-01 + 2.93202678436719e-01 1.21245809848125e-01 + 3.06694853961626e-01 1.22070347287731e-01 + 3.20607221269401e-01 1.22636048627399e-01 + 3.34939225727116e-01 1.22896405187495e-01 + 3.49687259951759e-01 1.22832509683795e-01 + 3.64846634151165e-01 1.22439948740756e-01 + 3.80413960921238e-01 1.21746809942571e-01 + 3.96385714538567e-01 1.20764919268824e-01 + 4.12758960322157e-01 1.19510121769152e-01 + 4.29529842936380e-01 1.17984332147218e-01 + 4.46694032865700e-01 1.16192942543521e-01 + 4.64243156344356e-01 1.14110109333428e-01 + 4.82175917377177e-01 1.11782565979692e-01 + 5.00484981625201e-01 1.09197664159710e-01 + 5.19162527401886e-01 1.06360393829411e-01 + 5.38203351947280e-01 1.03293317103930e-01 + 5.57598339807246e-01 9.99962205928791e-02 + 5.77338351570623e-01 9.64747449157602e-02 + 5.97416776275050e-01 9.27560006949552e-02 + 6.17822141099620e-01 8.88440306520127e-02 + 6.38542602259551e-01 8.47454502578335e-02 + 6.59565267437110e-01 8.04670396004571e-02 + 6.80878587686638e-01 7.60267545343259e-02 + 7.02471625795160e-01 7.14503791069948e-02 + 7.24326570178040e-01 6.67348590516426e-02 + 7.46427167466697e-01 6.18895592022783e-02 + 7.68752565300964e-01 5.69073598312532e-02 + 7.91284286644164e-01 5.17961436337766e-02 + 8.14003103862062e-01 4.65642778387828e-02 + 8.36892211324902e-01 4.12336546487814e-02 + 8.59931483011660e-01 3.58149765441833e-02 + 8.83096679342750e-01 3.03040142055707e-02 + 9.06368908273977e-01 2.47214334364437e-02 + 9.29725618218844e-01 1.90747609134739e-02 + 9.53145851346865e-01 1.33087434425404e-02 + 9.76587857380671e-01 7.46542748662253e-03 + 1.00000000000000e+00 1.53836008119114e-03 diff --git a/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF29_Coords.txt b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF29_Coords.txt new file mode 100644 index 00000000..a8559b09 --- /dev/null +++ b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF29_Coords.txt @@ -0,0 +1,208 @@ + 201 NumCoords ! The number of coordinates in the airfoil shape file (including an extra coordinate for airfoil reference). Set to zero if coordinates not included. +! ......... x-y coordinates are next if NumCoords > 0 ............. +! x-y coordinate of airfoil reference +! x/c y/c + 0.250000 0 +! coordinates of airfoil shape +! interpolation to 200 points +! x/c y/c + 1.00000000000000e+00 -1.24164223325347e-03 + 9.76041164392396e-01 1.99488062082566e-03 + 9.52121910751731e-01 4.75706135335948e-03 + 9.28199952199219e-01 7.09542915865422e-03 + 9.04291183649571e-01 8.93443767118390e-03 + 8.80430335305919e-01 9.96657750751068e-03 + 8.56672679460919e-01 9.94290456909515e-03 + 8.33075414701384e-01 9.19689647089799e-03 + 8.09695687435274e-01 7.47347776900502e-03 + 7.86588871455130e-01 4.89111649401108e-03 + 7.63799965113471e-01 1.51070681640460e-03 + 7.41353000623285e-01 -2.52044025059049e-03 + 7.19257724385752e-01 -7.04038035491660e-03 + 6.97520929992240e-01 -1.19358771025367e-02 + 6.76139755888505e-01 -1.70807000809784e-02 + 6.55114166969036e-01 -2.23866910906930e-02 + 6.34437004205735e-01 -2.77558927368869e-02 + 6.14099144503465e-01 -3.30936572688430e-02 + 5.94097064299627e-01 -3.83328932311329e-02 + 5.74431247267374e-01 -4.34270116338703e-02 + 5.55097891490535e-01 -4.83164932012163e-02 + 5.36103212560625e-01 -5.29813263991864e-02 + 5.17451481630547e-01 -5.73968812892901e-02 + 4.99146111683925e-01 -6.15389571602501e-02 + 4.81186975180132e-01 -6.53690978763222e-02 + 4.63583300631990e-01 -6.88824794729917e-02 + 4.46345639685456e-01 -7.21042454369658e-02 + 4.29476392143564e-01 -7.50078041225779e-02 + 4.12981130677270e-01 -7.75910183051978e-02 + 3.96868662278405e-01 -7.98780393343755e-02 + 3.81143702382537e-01 -8.18762030718283e-02 + 3.65809916070270e-01 -8.35894498418953e-02 + 3.50871312147949e-01 -8.50344244357429e-02 + 3.36330822167539e-01 -8.62290745383426e-02 + 3.22187646977060e-01 -8.71590051574009e-02 + 3.08443347581371e-01 -8.78366305562361e-02 + 2.95097791339595e-01 -8.82767906155356e-02 + 2.82150283499973e-01 -8.84841152823162e-02 + 2.69599681087069e-01 -8.84700144337475e-02 + 2.57443507192848e-01 -8.82648626051867e-02 + 2.45678472964112e-01 -8.78783050259134e-02 + 2.34300862010750e-01 -8.73191697949781e-02 + 2.23305146809674e-01 -8.66150861037270e-02 + 2.12686447462944e-01 -8.57716757140843e-02 + 2.02439173855586e-01 -8.47960288193625e-02 + 1.92555307706631e-01 -8.37147516939257e-02 + 1.83029046978344e-01 -8.25290955835651e-02 + 1.73852963346223e-01 -8.12499103431124e-02 + 1.65019689389359e-01 -7.98863245514951e-02 + 1.56521126720043e-01 -7.84487139477401e-02 + 1.48348304923117e-01 -7.69503909453266e-02 + 1.40492148638460e-01 -7.54025518805833e-02 + 1.32945914165942e-01 -7.38053366709304e-02 + 1.25700981456047e-01 -7.21672611749456e-02 + 1.18749045764871e-01 -7.04928205316870e-02 + 1.12082052295785e-01 -6.87847149917338e-02 + 1.05690622940757e-01 -6.70563903986223e-02 + 9.95644640688240e-02 -6.53155333147837e-02 + 9.36997746804533e-02 -6.35528246583057e-02 + 8.80860269419856e-02 -6.17797928182627e-02 + 8.27138276159543e-02 -6.00046033630738e-02 + 7.75786679035966e-02 -5.82199710630611e-02 + 7.26702668766427e-02 -5.64363872841197e-02 + 6.79824057221827e-02 -5.46531901393429e-02 + 6.35090960690899e-02 -5.28689008362057e-02 + 5.92419250258708e-02 -5.10893545882387e-02 + 5.51761543119222e-02 -4.93108314830338e-02 + 5.13012845894761e-02 -4.75440896934531e-02 + 4.76145515997845e-02 -4.57830599145488e-02 + 4.41097733544431e-02 -4.40286418035125e-02 + 4.07797512889574e-02 -4.22832452899324e-02 + 3.76203116687853e-02 -4.05471735735779e-02 + 3.46254239696624e-02 -3.88215583285753e-02 + 3.17889085655347e-02 -3.71070627007449e-02 + 2.91063003142196e-02 -3.54070465342894e-02 + 2.65680912572024e-02 -3.37242409387003e-02 + 2.41746444372365e-02 -3.20578833095496e-02 + 2.19171444247057e-02 -3.04080839884921e-02 + 1.97858149698170e-02 -2.87865078379770e-02 + 1.77816785975956e-02 -2.71845378027204e-02 + 1.59022597397006e-02 -2.56014559510294e-02 + 1.41389646872214e-02 -2.40428674601252e-02 + 1.24868469400299e-02 -2.25098598379508e-02 + 1.09480652882944e-02 -2.09965353712404e-02 + 9.51590058521273e-03 -1.95072886041607e-02 + 8.19359596476239e-03 -1.80358421377615e-02 + 6.97242121388991e-03 -1.65886143273830e-02 + 5.86117330807756e-03 -1.51566360782969e-02 + 4.85595758514205e-03 -1.37425262435773e-02 + 3.94940976333073e-03 -1.23512935315688e-02 + 3.14133835342164e-03 -1.09822566687452e-02 + 2.44321714150649e-03 -9.63205013980954e-03 + 1.83022809796061e-03 -8.31193344939125e-03 + 1.31884436057794e-03 -7.01716988880847e-03 + 8.97352193736273e-04 -5.75368646998309e-03 + 5.63740905842356e-04 -4.52380720725293e-03 + 3.11437030347409e-04 -3.33125343689109e-03 + 1.35836224347021e-04 -2.17811584123553e-03 + 4.45280630750671e-05 -1.06661951254253e-03 + 0.00000000000000e+00 0.00000000000000e+00 + 2.66759975469128e-05 1.06620320574453e-03 + 1.03135502882502e-04 2.17873885472331e-03 + 2.50714361136359e-04 3.33437348745562e-03 + 4.62713791811825e-04 4.53304972124580e-03 + 7.43003731765193e-04 5.77372430028259e-03 + 1.10319742939756e-03 7.05282365458086e-03 + 1.54997995490141e-03 8.36732726269284e-03 + 2.09725167376054e-03 9.71027388884010e-03 + 2.74048539040992e-03 1.10830187729024e-02 + 3.47312973743479e-03 1.24853497385656e-02 + 4.30082057862358e-03 1.39166426421534e-02 + 5.21856989199968e-03 1.53794078029284e-02 + 6.22534057591764e-03 1.68754960531490e-02 + 7.32700432621982e-03 1.84027675881834e-02 + 8.52684801153103e-03 1.99605858637636e-02 + 9.82457090745577e-03 2.15515899247781e-02 + 1.12235129483028e-02 2.31756762504219e-02 + 1.27200449567995e-02 2.48389005693531e-02 + 1.43242218865420e-02 2.65369882056060e-02 + 1.60404178082626e-02 2.82678553499417e-02 + 1.78724934115684e-02 3.00331989618528e-02 + 1.98202065802740e-02 3.18374006104675e-02 + 2.18950371605342e-02 3.36723464545640e-02 + 2.40944987682683e-02 3.55478452136134e-02 + 2.64266489071067e-02 3.74562451109318e-02 + 2.89010362193680e-02 3.93973481646352e-02 + 3.15128734993139e-02 4.13789540071277e-02 + 3.42721293711695e-02 4.33986338037802e-02 + 3.71869628254960e-02 4.54495701594197e-02 + 4.02626884327817e-02 4.75345999298599e-02 + 4.35001994625931e-02 4.96601287812404e-02 + 4.69115999564798e-02 5.18156686218105e-02 + 5.05037662874084e-02 5.40013382232845e-02 + 5.42786495746735e-02 5.62234758330505e-02 + 5.82482809121614e-02 5.84716000937855e-02 + 6.24154777430842e-02 6.07527241240193e-02 + 6.67896532476333e-02 6.30611171442784e-02 + 7.13799778368031e-02 6.53924902316809e-02 + 7.61893991966636e-02 6.77536943148228e-02 + 8.12317422826271e-02 7.01307158448530e-02 + 8.65117308166364e-02 7.25279772295263e-02 + 9.20361925143298e-02 7.49454570665521e-02 + 9.78162490733068e-02 7.73748196288702e-02 + 1.03860525098628e-01 7.98107376836716e-02 + 1.10175749426971e-01 8.22553965780306e-02 + 1.16770184828620e-01 8.47058845532950e-02 + 1.23653173100621e-01 8.71545949342700e-02 + 1.30834306039958e-01 8.95967898803351e-02 + 1.38321638159842e-01 9.20292326136635e-02 + 1.46124356656426e-01 9.44436091370127e-02 + 1.54251870487751e-01 9.68324481019705e-02 + 1.62712165766615e-01 9.91923652415109e-02 + 1.71513276359922e-01 1.01517920367561e-01 + 1.80666809206519e-01 1.03789902629961e-01 + 1.90176333616483e-01 1.06018459355824e-01 + 2.00055618945293e-01 1.08170249602257e-01 + 2.10311333730825e-01 1.10238985284240e-01 + 2.20950025725240e-01 1.12217524621099e-01 + 2.31980826542045e-01 1.14082138261491e-01 + 2.43406729303366e-01 1.15839155310084e-01 + 2.55238106076494e-01 1.17446572225308e-01 + 2.67477471857320e-01 1.18905415201973e-01 + 2.80131031707401e-01 1.20180412981259e-01 + 2.93202678436719e-01 1.21245809848125e-01 + 3.06694853961626e-01 1.22070347287731e-01 + 3.20607221269401e-01 1.22636048627399e-01 + 3.34939225727116e-01 1.22896405187495e-01 + 3.49687259951759e-01 1.22832509683795e-01 + 3.64846634151165e-01 1.22439948740756e-01 + 3.80413960921238e-01 1.21746809942571e-01 + 3.96385714538567e-01 1.20764919268824e-01 + 4.12758960322157e-01 1.19510121769152e-01 + 4.29529842936380e-01 1.17984332147218e-01 + 4.46694032865700e-01 1.16192942543521e-01 + 4.64243156344356e-01 1.14110109333428e-01 + 4.82175917377177e-01 1.11782565979692e-01 + 5.00484981625201e-01 1.09197664159710e-01 + 5.19162527401886e-01 1.06360393829411e-01 + 5.38203351947280e-01 1.03293317103930e-01 + 5.57598339807246e-01 9.99962205928791e-02 + 5.77338351570623e-01 9.64747449157602e-02 + 5.97416776275050e-01 9.27560006949552e-02 + 6.17822141099620e-01 8.88440306520127e-02 + 6.38542602259551e-01 8.47454502578335e-02 + 6.59565267437110e-01 8.04670396004571e-02 + 6.80878587686638e-01 7.60267545343259e-02 + 7.02471625795160e-01 7.14503791069948e-02 + 7.24326570178040e-01 6.67348590516426e-02 + 7.46427167466697e-01 6.18895592022783e-02 + 7.68752565300964e-01 5.69073598312532e-02 + 7.91284286644164e-01 5.17961436337766e-02 + 8.14003103862062e-01 4.65642778387828e-02 + 8.36892211324902e-01 4.12336546487814e-02 + 8.59931483011660e-01 3.58149765441833e-02 + 8.83096679342750e-01 3.03040142055707e-02 + 9.06368908273977e-01 2.47214334364437e-02 + 9.29725618218844e-01 1.90747609134739e-02 + 9.53145851346865e-01 1.33087434425404e-02 + 9.76587857380671e-01 7.46542748662253e-03 + 1.00000000000000e+00 1.53836008119114e-03 diff --git a/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_00.dat b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_00.dat new file mode 100644 index 00000000..b23ba71d --- /dev/null +++ b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_00.dat @@ -0,0 +1,254 @@ +! ------------ AirfoilInfo v1.01.x Input File ---------------------------------- +! AeroElasticSE FAST driver +! line +! line +! ------------------------------------------------------------------------------ +DEFAULT InterpOrd ! Interpolation order to use for quasi-steady table lookup {1=linear; 3=cubic spline; "default"} [default=3] +1 NonDimArea ! The non-dimensional area of the airfoil (area/chord^2) (set to 1.0 if unsure or unneeded) +@"NREL-2p8-127_AF00_Coords.txt" NumCoords ! The number of coordinates in the airfoil shape file. Set to zero if coordinates not included. +AF00_BL.txt BL_file ! The file name including the boundary layer characteristics of the profile. Ignored if the aeroacoustic module is not called. +1 NumTabs ! Number of airfoil tables in this file. Each table must have lines for Re and Ctrl. +! ------------------------------------------------------------------------------ +! data for table 1 +! ------------------------------------------------------------------------------ +6.000000 Re ! Reynolds number in millions +0 Ctrl ! Control setting (must be 0 for current AirfoilInfo) +True InclUAdata ! Is unsteady aerodynamics data included in this table? If TRUE, then include 30 UA coefficients below this line +!........................................ +0.000000 alpha0 ! 0-lift angle of attack, depends on airfoil. +0.000000 alpha1 ! Angle of attack at f=0.7, (approximately the stall angle) for AOA>alpha0. (deg) +0.000000 alpha2 ! Angle of attack at f=0.7, (approximately the stall angle) for AOA1] +0.000000 S2 ! Constant in the f curve best-fit for AOA> alpha1; by definition it depends on the airfoil. [ignored if UAMod<>1] +0.000000 S3 ! Constant in the f curve best-fit for alpha2<=AOA< alpha0; by definition it depends on the airfoil. [ignored if UAMod<>1] +0.000000 S4 ! Constant in the f curve best-fit for AOA< alpha2; by definition it depends on the airfoil. [ignored if UAMod<>1] +0.000000 Cn1 ! Critical value of C0n at leading edge separation. It should be extracted from airfoil data at a given Mach and Reynolds number. It can be calculated from the static value of Cn at either the break in the pitching moment or the loss of chord force at the onset of stall. It is close to the condition of maximum lift of the airfoil at low Mach numbers. +0.000000 Cn2 ! As Cn1 for negative AOAs. +Default St_sh ! Strouhal's shedding frequency constant. [default = 0.19] +0.000000 Cd0 ! 2D drag coefficient value at 0-lift. +0.000000 Cm0 ! 2D pitching moment coefficient about 1/4-chord location, at 0-lift, positive if nose up. [If the aerodynamics coefficients table does not include a column for Cm, this needs to be set to 0.0] +0.000000 k0 ! Constant in the \hat(x)_cp curve best-fit; = (\hat(x)_AC-0.25). [ignored if UAMod<>1] +0.000000 k1 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k2 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k3 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k1_hat ! Constant in the expression of Cc due to leading edge vortex effects. [ignored if UAMod<>1] +Default x_cp_bar ! Constant in the expression of \hat(x)_cp^v. [ignored if UAMod<>1, default = 0.2] +Default UACutout ! Angle of attack above which unsteady aerodynamics are disabled (deg). [Specifying the string "Default" sets UACutout to 45 degrees] +Default filtCutOff ! Cut-off frequency (-3 dB corner frequency) for low-pass filtering the AoA input to UA, as well as the 1st and 2nd derivatives (Hz) [default = 20] +!........................................ +! Table of aerodynamics coefficients +200 NumAlf ! Number of data lines in the following table +! Alpha Cl Cd Cm +! (deg) (-) (-) (-) +-1.80000000000000e+02 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-1.77000000000000e+02 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-1.74000000000000e+02 0.00000000000000e+00 5.00000000000000e-01 -2.77555756156289e-17 +-1.71000000000000e+02 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-1.68000000000000e+02 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-1.65000000000000e+02 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-1.62000000000000e+02 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-1.59000000000000e+02 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-1.56000000000000e+02 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-1.53000000000000e+02 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-1.50000000000000e+02 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-1.47000000000000e+02 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-1.44000000000000e+02 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-1.41000000000000e+02 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-1.38000000000000e+02 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-1.35000000000000e+02 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-1.32000000000000e+02 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-1.29000000000000e+02 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-1.26000000000000e+02 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-1.23000000000000e+02 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-1.20000000000000e+02 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-1.17000000000000e+02 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-1.14000000000000e+02 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-1.11000000000000e+02 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-1.08000000000000e+02 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-1.05000000000000e+02 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-1.02000000000000e+02 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-9.90000000000000e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-9.60000000000000e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-9.30000000000000e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-9.00000000000000e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-8.70000000000000e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-8.40000000000000e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-8.10000000000000e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-7.80000000000000e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-7.50000000000000e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-7.20000000000000e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-6.90000000000000e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-6.60000000000000e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-6.30000000000000e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-6.00000000000000e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-5.70000000000000e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-5.40000000000000e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-5.10000000000000e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-4.80000000000000e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-4.50000000000000e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-4.20000000000000e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-3.90000000000000e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-3.60000000000000e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-3.30000000000000e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-3.00000000000000e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-2.93939393939394e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-2.87878787878788e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-2.81818181818182e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-2.75757575757576e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-2.69696969696970e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-2.63636363636364e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-2.57575757575758e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-2.51515151515151e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-2.45454545454545e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-2.39393939393939e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-2.33333333333333e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-2.27272727272727e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-2.21212121212121e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-2.15151515151515e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-2.09090909090909e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-2.03030303030303e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-1.96969696969697e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-1.90909090909091e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-1.84848484848485e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-1.78787878787879e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-1.72727272727273e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-1.66666666666667e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-1.60606060606061e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-1.54545454545455e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-1.48484848484848e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-1.42424242424242e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-1.36363636363636e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-1.30303030303030e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-1.24242424242424e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-1.18181818181818e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-1.12121212121212e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-1.06060606060606e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-1.00000000000000e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-9.39393939393939e+00 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-8.78787878787879e+00 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-8.18181818181818e+00 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-7.57575757575758e+00 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-6.96969696969697e+00 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-6.36363636363636e+00 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-5.75757575757576e+00 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-5.15151515151515e+00 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-4.54545454545454e+00 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-3.93939393939394e+00 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-3.33333333333333e+00 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-2.72727272727273e+00 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-2.12121212121212e+00 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-1.51515151515152e+00 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-9.09090909090912e-01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-3.03030303030302e-01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 3.03030303030302e-01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 9.09090909090912e-01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 1.51515151515152e+00 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 2.12121212121212e+00 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 2.72727272727273e+00 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 3.33333333333333e+00 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 3.93939393939394e+00 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 4.54545454545455e+00 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 5.15151515151515e+00 1.11022302462516e-16 5.00000000000000e-01 0.00000000000000e+00 + 5.75757575757576e+00 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 6.36363636363637e+00 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 6.96969696969697e+00 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 7.57575757575757e+00 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 8.18181818181818e+00 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 8.78787878787879e+00 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 9.39393939393939e+00 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 1.00000000000000e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 1.06060606060606e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 1.12121212121212e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 1.18181818181818e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 1.24242424242424e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 1.30303030303030e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 1.36363636363636e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 1.42424242424242e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 1.48484848484848e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 1.54545454545455e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 1.60606060606061e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 1.66666666666667e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 1.72727272727273e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 1.78787878787879e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 1.84848484848485e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 1.90909090909091e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 1.96969696969697e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 2.03030303030303e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 2.09090909090909e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 2.15151515151515e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 2.21212121212121e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 2.27272727272727e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 2.33333333333333e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 2.39393939393939e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 2.45454545454545e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 2.51515151515151e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 2.57575757575758e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 2.63636363636364e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 2.69696969696970e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 2.75757575757576e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 2.81818181818182e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 2.87878787878788e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 2.93939393939394e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 3.00000000000000e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 3.30000000000000e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 3.60000000000000e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 3.90000000000000e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 4.20000000000000e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 4.50000000000000e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 4.80000000000000e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 5.10000000000000e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 5.40000000000000e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 5.70000000000000e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 6.00000000000000e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 6.30000000000000e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 6.60000000000000e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 6.90000000000000e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 7.20000000000000e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 7.50000000000000e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 7.80000000000000e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 8.10000000000000e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 8.40000000000000e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 8.70000000000000e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 9.00000000000000e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 9.30000000000000e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 9.60000000000000e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 9.90000000000000e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 1.02000000000000e+02 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 1.05000000000000e+02 2.77555756156289e-17 5.00000000000000e-01 0.00000000000000e+00 + 1.08000000000000e+02 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 1.11000000000000e+02 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 1.14000000000000e+02 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 1.17000000000000e+02 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 1.20000000000000e+02 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 1.23000000000000e+02 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 1.26000000000000e+02 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 1.29000000000000e+02 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 1.32000000000000e+02 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 1.35000000000000e+02 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 1.38000000000000e+02 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 1.41000000000000e+02 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 1.44000000000000e+02 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 1.47000000000000e+02 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 1.50000000000000e+02 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 1.53000000000000e+02 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 1.56000000000000e+02 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 1.59000000000000e+02 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 1.62000000000000e+02 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 1.65000000000000e+02 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 1.68000000000000e+02 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 1.71000000000000e+02 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 1.74000000000000e+02 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 1.77000000000000e+02 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 1.80000000000000e+02 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 diff --git a/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_01.dat b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_01.dat new file mode 100644 index 00000000..b197c637 --- /dev/null +++ b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_01.dat @@ -0,0 +1,254 @@ +! ------------ AirfoilInfo v1.01.x Input File ---------------------------------- +! AeroElasticSE FAST driver +! line +! line +! ------------------------------------------------------------------------------ +DEFAULT InterpOrd ! Interpolation order to use for quasi-steady table lookup {1=linear; 3=cubic spline; "default"} [default=3] +1 NonDimArea ! The non-dimensional area of the airfoil (area/chord^2) (set to 1.0 if unsure or unneeded) +@"NREL-2p8-127_AF01_Coords.txt" NumCoords ! The number of coordinates in the airfoil shape file. Set to zero if coordinates not included. +AF01_BL.txt BL_file ! The file name including the boundary layer characteristics of the profile. Ignored if the aeroacoustic module is not called. +1 NumTabs ! Number of airfoil tables in this file. Each table must have lines for Re and Ctrl. +! ------------------------------------------------------------------------------ +! data for table 1 +! ------------------------------------------------------------------------------ +6.000000 Re ! Reynolds number in millions +0 Ctrl ! Control setting (must be 0 for current AirfoilInfo) +True InclUAdata ! Is unsteady aerodynamics data included in this table? If TRUE, then include 30 UA coefficients below this line +!........................................ +0.000000 alpha0 ! 0-lift angle of attack, depends on airfoil. +0.000000 alpha1 ! Angle of attack at f=0.7, (approximately the stall angle) for AOA>alpha0. (deg) +0.000000 alpha2 ! Angle of attack at f=0.7, (approximately the stall angle) for AOA1] +0.000000 S2 ! Constant in the f curve best-fit for AOA> alpha1; by definition it depends on the airfoil. [ignored if UAMod<>1] +0.000000 S3 ! Constant in the f curve best-fit for alpha2<=AOA< alpha0; by definition it depends on the airfoil. [ignored if UAMod<>1] +0.000000 S4 ! Constant in the f curve best-fit for AOA< alpha2; by definition it depends on the airfoil. [ignored if UAMod<>1] +0.000000 Cn1 ! Critical value of C0n at leading edge separation. It should be extracted from airfoil data at a given Mach and Reynolds number. It can be calculated from the static value of Cn at either the break in the pitching moment or the loss of chord force at the onset of stall. It is close to the condition of maximum lift of the airfoil at low Mach numbers. +0.000000 Cn2 ! As Cn1 for negative AOAs. +Default St_sh ! Strouhal's shedding frequency constant. [default = 0.19] +0.000000 Cd0 ! 2D drag coefficient value at 0-lift. +0.000000 Cm0 ! 2D pitching moment coefficient about 1/4-chord location, at 0-lift, positive if nose up. [If the aerodynamics coefficients table does not include a column for Cm, this needs to be set to 0.0] +0.000000 k0 ! Constant in the \hat(x)_cp curve best-fit; = (\hat(x)_AC-0.25). [ignored if UAMod<>1] +0.000000 k1 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k2 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k3 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k1_hat ! Constant in the expression of Cc due to leading edge vortex effects. [ignored if UAMod<>1] +Default x_cp_bar ! Constant in the expression of \hat(x)_cp^v. [ignored if UAMod<>1, default = 0.2] +Default UACutout ! Angle of attack above which unsteady aerodynamics are disabled (deg). [Specifying the string "Default" sets UACutout to 45 degrees] +Default filtCutOff ! Cut-off frequency (-3 dB corner frequency) for low-pass filtering the AoA input to UA, as well as the 1st and 2nd derivatives (Hz) [default = 20] +!........................................ +! Table of aerodynamics coefficients +200 NumAlf ! Number of data lines in the following table +! Alpha Cl Cd Cm +! (deg) (-) (-) (-) +-1.80000000000000e+02 0.00000000000000e+00 4.98298540333591e-01 0.00000000000000e+00 +-1.77000000000000e+02 6.22917411225319e-03 4.99373778033698e-01 7.76775909182493e-03 +-1.74000000000000e+02 1.25154154596942e-02 4.99419482735902e-01 1.56066808333025e-02 +-1.71000000000000e+02 1.87731622461588e-02 4.99461965511715e-01 2.34100699534240e-02 +-1.68000000000000e+02 2.34094297732302e-02 4.99530448606310e-01 2.52436698228222e-02 +-1.65000000000000e+02 2.72360674222744e-02 4.99608171404762e-01 2.40924447430971e-02 +-1.62000000000000e+02 3.10637475603965e-02 4.99680051763820e-01 2.29412064713014e-02 +-1.59000000000000e+02 3.36494201711338e-02 4.99754234730512e-01 2.21517716457378e-02 +-1.56000000000000e+02 3.37510782194723e-02 4.99836914626034e-01 2.20859314734659e-02 +-1.53000000000000e+02 3.38548418745498e-02 4.99908331389323e-01 2.20200907982144e-02 +-1.50000000000000e+02 3.39610598736408e-02 4.99965130046894e-01 2.19542509808981e-02 +-1.47000000000000e+02 3.40022351252792e-02 5.01549605455131e-01 2.23645223424130e-02 +-1.44000000000000e+02 3.40443360294749e-02 5.07633704084372e-01 2.27747952710201e-02 +-1.41000000000000e+02 3.40874558144093e-02 5.13717849193324e-01 2.31850713339235e-02 +-1.38000000000000e+02 3.36790582106382e-02 5.20009950681803e-01 2.35945800253753e-02 +-1.35000000000000e+02 3.30448480367859e-02 5.26406029938182e-01 2.40037050326582e-02 +-1.32000000000000e+02 3.24110462717851e-02 5.32802182487933e-01 2.44128347281493e-02 +-1.29000000000000e+02 3.14966524820477e-02 5.39025691193689e-01 2.47587684454421e-02 +-1.26000000000000e+02 3.00203897774573e-02 5.44903911391262e-01 2.49783099065228e-02 +-1.23000000000000e+02 2.85442923527018e-02 5.47997043443126e-01 2.51978496904198e-02 +-1.20000000000000e+02 2.70683874187890e-02 5.50390438255170e-01 2.54173886357562e-02 +-1.17000000000000e+02 2.48208058238953e-02 5.51842311486022e-01 2.53547661804404e-02 +-1.14000000000000e+02 2.25732865469572e-02 5.53294177329843e-01 2.52921434125441e-02 +-1.11000000000000e+02 2.03258601363591e-02 5.54746032082366e-01 2.52295211230444e-02 +-1.08000000000000e+02 1.77044555792872e-02 5.55339410798165e-01 2.49510697467495e-02 +-1.05000000000000e+02 1.48960397658858e-02 5.55503544958830e-01 2.45647021836766e-02 +-1.02000000000000e+02 1.20876828091304e-02 5.55667677238678e-01 2.41783390479984e-02 +-9.90000000000000e+01 9.19392120485563e-03 5.55336597556942e-01 2.36900749881812e-02 +-9.60000000000000e+01 6.12926766887735e-03 5.54015072501802e-01 2.29980046662208e-02 +-9.30000000000000e+01 3.06463754512461e-03 5.52693557542367e-01 2.23059396312876e-02 +-9.00000000000000e+01 1.91272727247280e-08 5.51372047630695e-01 2.15841433608613e-02 +-8.70000000000000e+01 -3.06463440848635e-03 5.52693556189802e-01 2.16338466189352e-02 +-8.40000000000000e+01 -6.12927623833141e-03 5.54015076197080e-01 2.16677916947745e-02 +-8.10000000000000e+01 -9.19389465618328e-03 5.55336586108752e-01 2.16947509086332e-02 +-7.80000000000000e+01 -1.20876692076357e-02 5.55667678033613e-01 2.14919425433851e-02 +-7.50000000000000e+01 -1.48960583459338e-02 5.55503543872940e-01 2.11742464233755e-02 +-7.20000000000000e+01 -1.77044419776618e-02 5.55339411593092e-01 2.08565539438687e-02 +-6.90000000000000e+01 -2.03258406672883e-02 5.54746044659799e-01 2.04334687101240e-02 +-6.60000000000000e+01 -2.25732928313413e-02 5.53294173270158e-01 1.97995893374298e-02 +-6.30000000000000e+01 -2.48208206936227e-02 5.51842301880517e-01 1.91657099647355e-02 +-6.00000000000000e+01 -2.70683971825928e-02 5.50390422420595e-01 1.85318284698429e-02 +-5.70000000000000e+01 -2.85443021178706e-02 5.47997027608551e-01 1.76503617476530e-02 +-5.40000000000000e+01 -3.00203995438562e-02 5.44903872501265e-01 1.67688916585075e-02 +-5.10000000000000e+01 -3.14966622493741e-02 5.39025652303692e-01 1.58874148353996e-02 +-4.80000000000000e+01 -3.24110456233041e-02 5.32802189034552e-01 1.48845508415255e-02 +-4.50000000000000e+01 -3.30448401226552e-02 5.26406109778172e-01 1.38209952131320e-02 +-4.20000000000000e+01 -3.36790575613502e-02 5.20009957227964e-01 1.27574273972622e-02 +-3.90000000000000e+01 -3.40874557757088e-02 5.13717843800706e-01 1.16502587670957e-02 +-3.60000000000000e+01 -3.40443359103789e-02 5.07633687072646e-01 1.04558679399742e-02 +-3.30000000000000e+01 -3.40022354063646e-02 5.01549646541201e-01 9.26149992360155e-03 +-3.00000000000000e+01 -3.39610593176495e-02 4.99965129704843e-01 8.06710800308781e-03 +-2.93939393939394e+01 -3.39393842149473e-02 4.99955039870966e-01 7.77133972459921e-03 +-2.87878787878788e+01 -3.39178226626962e-02 4.99944209186026e-01 7.47170990628286e-03 +-2.81818181818182e+01 -3.38963709780943e-02 4.99932679692807e-01 7.17234251862615e-03 +-2.75757575757576e+01 -3.38750252088939e-02 4.99920490061147e-01 6.87323704771576e-03 +-2.69696969696970e+01 -3.38537822279900e-02 4.99907676487852e-01 6.57440256765985e-03 +-2.63636363636364e+01 -3.38326389844070e-02 4.99894272577114e-01 6.27584744506084e-03 +-2.57575757575758e+01 -3.38115926180026e-02 4.99880309637533e-01 5.97758105595668e-03 +-2.51515151515151e+01 -3.37906402717716e-02 4.99865816763762e-01 5.67961122622956e-03 +-2.45454545454545e+01 -3.37697787305793e-02 4.99850820740502e-01 5.38193913346827e-03 +-2.39393939393939e+01 -3.37490052565293e-02 4.99835346782305e-01 5.08457126751900e-03 +-2.33333333333333e+01 -3.37283172206986e-02 4.99819418446624e-01 4.78751430822279e-03 +-2.27272727272727e+01 -3.37077120977687e-02 4.99803057767734e-01 4.49077513241954e-03 +-2.21212121212121e+01 -3.36871874609726e-02 4.99786285377891e-01 4.19436082126422e-03 +-2.15151515151515e+01 -3.36667405096286e-02 4.99769120219361e-01 3.89827188626708e-03 +-2.09090909090909e+01 -3.36463693546679e-02 4.99751580718914e-01 3.60252094397359e-03 +-2.03030303030303e+01 -3.36260719547005e-02 4.99733684020483e-01 3.30711743419011e-03 +-1.96969696969697e+01 -3.29941770005342e-02 4.99715928910410e-01 2.97198266169500e-03 +-1.90909090909091e+01 -3.17509544740198e-02 4.99698118180787e-01 2.59700694849448e-03 +-1.84848484848485e+01 -3.05081921751880e-02 4.99679692312574e-01 2.22228885632221e-03 +-1.78787878787879e+01 -2.92658434632383e-02 4.99660638867322e-01 1.84786105360303e-03 +-1.72727272727273e+01 -2.80238734929002e-02 4.99640945159408e-01 1.47377573016103e-03 +-1.66666666666667e+01 -2.67823588448486e-02 4.99620599927312e-01 1.10014144572659e-03 +-1.60606060606061e+01 -2.55413203393379e-02 4.99599590742328e-01 7.27083418764568e-04 +-1.54545454545455e+01 -2.43008440419113e-02 4.99577905993521e-01 3.54797120669601e-04 +-1.48484848484848e+01 -2.30608787869031e-02 4.99555531346250e-01 4.21684305218460e-05 +-1.42424242424242e+01 -2.18214069842467e-02 4.99532452564366e-01 2.71911216522822e-05 +-1.36363636363636e+01 -2.05833091301585e-02 4.99508671393742e-01 1.42264537010822e-05 +-1.30303030303030e+01 -1.93442785240345e-02 4.99484131275150e-01 4.31295864732214e-06 +-1.24242424242424e+01 -1.81074797005703e-02 4.99458875874706e-01 -1.61041962405105e-04 +-1.18181818181818e+01 -1.68699463185017e-02 4.99432832875225e-01 -7.83817617224051e-04 +-1.12121212121212e+01 -1.56337784253251e-02 4.99406027440083e-01 -1.40654332027136e-03 +-1.06060606060606e+01 -1.43985688202720e-02 4.99052692242324e-01 -2.02931540870597e-03 +-1.00000000000000e+01 -1.31630022724158e-02 4.97993704507194e-01 -2.65204851654948e-03 +-9.39393939393939e+00 -1.11477228175490e-02 4.96487069320693e-01 -2.55646323442072e-03 +-8.78787878787879e+00 -9.13290842766007e-03 4.94977661180442e-01 -2.46147157009362e-03 +-8.18181818181818e+00 -7.12154268363285e-03 4.93467019568035e-01 -2.36566761577865e-03 +-7.57575757575758e+00 -5.11266117893152e-03 4.91954998300813e-01 -2.26283387170764e-03 +-6.96969696969697e+00 -3.10698824489412e-03 4.90440242965021e-01 -2.08181170391097e-03 +-6.36363636363636e+00 -1.10309834514044e-03 4.88921311313049e-01 -1.89874522974860e-03 +-5.75757575757576e+00 -3.00747474205360e-04 4.87401751405469e-01 -1.71567088819378e-03 +-5.15151515151515e+00 -2.21631176101127e-04 4.85879616962190e-01 -1.53403240787112e-03 +-4.54545454545454e+00 -1.49616631477367e-04 4.84353891592103e-01 -1.35030844364575e-03 +-3.93939393939394e+00 -8.68897616353509e-05 4.82825709613375e-01 -1.16711649919569e-03 +-3.33333333333333e+00 -3.06390387180330e-05 4.81485638756053e-01 -1.06097220254243e-03 +-2.72727272727273e+00 2.49883470329266e-03 4.81081167821070e-01 -1.11471300781816e-03 +-2.12121212121212e+00 9.70229526683138e-03 4.81205260595194e-01 -1.25146797918653e-03 +-1.51515151515152e+00 1.69064135086061e-02 4.81329323131111e-01 -1.47373619873665e-03 +-9.09090909090912e-01 2.15687752025109e-02 4.81450361624086e-01 -1.68081905636486e-03 +-3.03030303030302e-01 2.42404595537528e-02 4.81560887996981e-01 -1.90313415400156e-03 + 3.03030303030302e-01 2.69131749150450e-02 4.81684879937810e-01 -2.12376124690789e-03 + 9.09090909090912e-01 2.95856638229001e-02 4.81808857865227e-01 -2.33301661078614e-03 + 1.51515151515152e+00 3.22398936101882e-02 4.81929840079279e-01 -2.55120165338738e-03 + 2.12121212121212e+00 3.66675784640552e-02 4.81924986740543e-01 -2.77391835793390e-03 + 2.72727272727273e+00 4.19698427928253e-02 4.81879454613869e-01 -2.98510710550669e-03 + 3.33333333333333e+00 4.72717179522425e-02 4.81833922593971e-01 -3.18573614963958e-03 + 3.93939393939394e+00 5.25753326357400e-02 4.81775728360497e-01 -3.38638186200821e-03 + 4.54545454545455e+00 5.78765746006633e-02 4.81728632143155e-01 -3.59889201718914e-03 + 5.15151515151515e+00 6.31803800322498e-02 4.81680617938285e-01 -3.79953830438974e-03 + 5.75757575757576e+00 6.78668119866628e-02 4.81626107889307e-01 -4.03804041841606e-03 + 6.36363636363637e+00 7.15042486961224e-02 4.81584603835809e-01 -4.34980617905866e-03 + 6.96969696969697e+00 7.49998526302299e-02 4.81530576563388e-01 -4.66507085142508e-03 + 7.57575757575757e+00 7.85534281259633e-02 4.81489207644286e-01 -4.96022383060956e-03 + 8.18181818181818e+00 8.27222397693518e-02 4.81442706653469e-01 -5.12210053319802e-03 + 8.78787878787879e+00 8.59673537796770e-02 4.81485608223198e-01 -5.30026887591891e-03 + 9.39393939393939e+00 8.63938854494780e-02 4.81734888790963e-01 -5.58390579608546e-03 + 1.00000000000000e+01 8.61476310716953e-02 4.82033636040847e-01 -5.89351913489291e-03 + 1.06060606060606e+01 1.14640664678628e-02 4.86367761950627e-01 -4.32401101558585e-03 + 1.12121212121212e+01 1.77109990487445e-03 4.90977291638818e-01 -5.52690415533776e-05 + 1.18181818181818e+01 1.63608094150530e-03 4.94596563237555e-01 -4.71568484033090e-05 + 1.24242424242424e+01 5.38023265894621e-02 4.97637007791052e-01 -7.01427597271410e-05 + 1.30303030303030e+01 7.07102583465799e-02 4.99408388908304e-01 -2.78511851302713e-04 + 1.36363636363636e+01 6.81632004936948e-02 4.99466710089213e-01 -3.41458399817878e-04 + 1.42424242424242e+01 6.49592840496404e-02 4.99515392758744e-01 -3.60890382699212e-04 + 1.48484848484848e+01 6.00226087507924e-02 4.99558582755279e-01 -3.80502489146672e-04 + 1.54545454545455e+01 5.42932388358678e-02 4.99595173447000e-01 -3.60569709918067e-04 + 1.60606060606061e+01 4.89399852015463e-02 4.99626659734195e-01 -3.74707069218248e-04 + 1.66666666666667e+01 4.90264804982352e-02 4.99643029856566e-01 -8.14570485140793e-04 + 1.72727272727273e+01 4.89767434358854e-02 4.99658738397009e-01 -1.29542584308036e-03 + 1.78787878787879e+01 4.87601917929942e-02 4.99673710331708e-01 -1.82640692279492e-03 + 1.84848484848485e+01 4.85448822816922e-02 4.99688486075466e-01 -2.35860501303099e-03 + 1.90909090909091e+01 4.83300562227171e-02 4.99703072863703e-01 -2.89167774847090e-03 + 1.96969696969697e+01 4.81154623433704e-02 4.99717479015725e-01 -3.42523467641370e-03 + 2.03030303030303e+01 4.80233231913679e-02 4.99733684020482e-01 -3.86916331990858e-03 + 2.09090909090909e+01 4.80535318777004e-02 4.99751580718914e-01 -4.22318641357654e-03 + 2.15151515151515e+01 4.80838465710918e-02 4.99769120219361e-01 -4.57757988364418e-03 + 2.21212121212121e+01 4.81142702027946e-02 4.99786285377891e-01 -4.93233346765168e-03 + 2.27272727272727e+01 4.81448054735174e-02 4.99803057767734e-01 -5.28743306710894e-03 + 2.33333333333333e+01 4.81754564360106e-02 4.99819418446624e-01 -5.64287905507360e-03 + 2.39393939393939e+01 4.82062265821584e-02 4.99835346782305e-01 -5.99866390348971e-03 + 2.45454545454545e+01 4.82371195457987e-02 4.99850820740502e-01 -6.35478030087519e-03 + 2.51515151515151e+01 4.82681391100110e-02 4.99865816763762e-01 -6.71122114458926e-03 + 2.57575757575758e+01 4.82992892148572e-02 4.99880309637533e-01 -7.06797953342872e-03 + 2.63636363636364e+01 4.83305745045125e-02 4.99894272577114e-01 -7.42505490046007e-03 + 2.69696969696970e+01 4.83619990851020e-02 4.99907676487852e-01 -7.78243869417755e-03 + 2.75757575757576e+01 4.83935670617676e-02 4.99920490061147e-01 -8.14012048538783e-03 + 2.81818181818182e+01 4.84252828173819e-02 4.99932679692807e-01 -8.49809103217069e-03 + 2.87878787878788e+01 4.84571508417891e-02 4.99944209186026e-01 -8.85634022554155e-03 + 2.93939393939394e+01 4.84891768440017e-02 4.99955039870966e-01 -9.21486940940596e-03 + 3.00000000000000e+01 4.85213661255990e-02 4.99965129704843e-01 -9.57367290978077e-03 + 3.30000000000000e+01 4.85783850925221e-02 5.01549646541201e-01 -1.08893308683242e-02 + 3.60000000000000e+01 4.86367279082047e-02 5.07633687072646e-01 -1.21830696545693e-02 + 3.90000000000000e+01 4.86965308414856e-02 5.13717843800706e-01 -1.34715855024972e-02 + 4.20000000000000e+01 4.81074542024269e-02 5.20009957227964e-01 -1.45755410030633e-02 + 4.50000000000000e+01 4.71938349445183e-02 5.26406109778172e-01 -1.55872262614513e-02 + 4.80000000000000e+01 4.62807992978572e-02 5.32802189034552e-01 -1.65988999268877e-02 + 5.10000000000000e+01 4.49696537236258e-02 5.39025652303692e-01 -1.75196039279897e-02 + 5.40000000000000e+01 4.28613244897533e-02 5.44903872501265e-01 -1.82583627521897e-02 + 5.70000000000000e+01 4.07532301242102e-02 5.47997027608551e-01 -1.89971159327085e-02 + 6.00000000000000e+01 3.86454092273193e-02 5.50390422420595e-01 -1.97358662914081e-02 + 6.30000000000000e+01 3.54441639493027e-02 5.51842301880517e-01 -2.01991699310181e-02 + 6.60000000000000e+01 3.22429963032422e-02 5.53294173270158e-01 -2.06624712096125e-02 + 6.90000000000000e+01 2.90419479592744e-02 5.54746044659799e-01 -2.11257724882070e-02 + 7.20000000000000e+01 2.52997639160426e-02 5.55339411593092e-01 -2.14026262276280e-02 + 7.50000000000000e+01 2.12869899032544e-02 5.55503543872940e-01 -2.15862600142917e-02 + 7.80000000000000e+01 1.72742065965976e-02 5.55667678033613e-01 -2.17698959052524e-02 + 8.10000000000000e+01 1.31391516042592e-02 5.55336586108752e-01 -2.18644734045035e-02 + 8.40000000000000e+01 8.75945317316178e-03 5.54015076197080e-01 -2.17809402678169e-02 + 8.70000000000000e+01 4.37972128358576e-03 5.52693556189802e-01 -2.16904207186265e-02 + 9.00000000000000e+01 -1.91272727377706e-08 5.51372047630695e-01 -2.15841433608613e-02 + 9.30000000000000e+01 -3.06463754512461e-03 5.52693557542367e-01 -2.23059396312876e-02 + 9.60000000000000e+01 -6.12926766887736e-03 5.54015072501802e-01 -2.29980046662208e-02 + 9.90000000000000e+01 -9.19392120485563e-03 5.55336597556942e-01 -2.36900749881812e-02 + 1.02000000000000e+02 -1.20876828091304e-02 5.55667677238678e-01 -2.41783390479984e-02 + 1.05000000000000e+02 -1.48960397658858e-02 5.55503544958831e-01 -2.45647021836766e-02 + 1.08000000000000e+02 -1.77044555792872e-02 5.55339410798165e-01 -2.49510697467495e-02 + 1.11000000000000e+02 -2.03258601363591e-02 5.54746032082366e-01 -2.52295211230444e-02 + 1.14000000000000e+02 -2.25732865469573e-02 5.53294177329843e-01 -2.52921434125440e-02 + 1.17000000000000e+02 -2.48208058238953e-02 5.51842311486022e-01 -2.53547661804404e-02 + 1.20000000000000e+02 -2.70683874187890e-02 5.50390438255170e-01 -2.54173886357562e-02 + 1.23000000000000e+02 -2.85442923527018e-02 5.47997043443125e-01 -2.51978496904198e-02 + 1.26000000000000e+02 -3.00203897774573e-02 5.44903911391262e-01 -2.49783099065228e-02 + 1.29000000000000e+02 -3.14966524820477e-02 5.39025691193689e-01 -2.47587684454421e-02 + 1.32000000000000e+02 -3.24110462717851e-02 5.32802182487933e-01 -2.44128347281493e-02 + 1.35000000000000e+02 -3.30448480367859e-02 5.26406029938182e-01 -2.40037050326582e-02 + 1.38000000000000e+02 -3.36790582106382e-02 5.20009950681803e-01 -2.35945800253753e-02 + 1.41000000000000e+02 -3.40874558144093e-02 5.13717849193324e-01 -2.31850713339234e-02 + 1.44000000000000e+02 -3.40443360294749e-02 5.07633704084372e-01 -2.27747952710201e-02 + 1.47000000000000e+02 -3.40022351252792e-02 5.01549605455131e-01 -2.23645223424130e-02 + 1.50000000000000e+02 -3.39610598736408e-02 4.99965130046894e-01 -2.19542509808981e-02 + 1.53000000000000e+02 -3.38548418745498e-02 4.99908331389323e-01 -2.20200907982144e-02 + 1.56000000000000e+02 -3.37510782194723e-02 4.99836914626034e-01 -2.20859314734659e-02 + 1.59000000000000e+02 -3.36494201711338e-02 4.99754234730512e-01 -2.21517716457378e-02 + 1.62000000000000e+02 -3.10637475603964e-02 4.99680051763820e-01 -2.42417639918563e-02 + 1.65000000000000e+02 -2.72360674222744e-02 4.99608171404762e-01 -2.73438495435689e-02 + 1.68000000000000e+02 -2.34094297732302e-02 4.99530448606310e-01 -3.04458995483989e-02 + 1.71000000000000e+02 -1.87731622461588e-02 4.99461965511715e-01 -2.92625874417800e-02 + 1.74000000000000e+02 -1.25154154596942e-02 4.99419482735902e-01 -1.95083510416281e-02 + 1.77000000000000e+02 -6.22917411225319e-03 4.99373778033698e-01 -9.70969886478117e-03 + 1.80000000000000e+02 0.00000000000000e+00 4.98298540333591e-01 0.00000000000000e+00 diff --git a/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_02.dat b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_02.dat new file mode 100644 index 00000000..3b06888a --- /dev/null +++ b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_02.dat @@ -0,0 +1,254 @@ +! ------------ AirfoilInfo v1.01.x Input File ---------------------------------- +! AeroElasticSE FAST driver +! line +! line +! ------------------------------------------------------------------------------ +DEFAULT InterpOrd ! Interpolation order to use for quasi-steady table lookup {1=linear; 3=cubic spline; "default"} [default=3] +1 NonDimArea ! The non-dimensional area of the airfoil (area/chord^2) (set to 1.0 if unsure or unneeded) +@"NREL-2p8-127_AF02_Coords.txt" NumCoords ! The number of coordinates in the airfoil shape file. Set to zero if coordinates not included. +AF02_BL.txt BL_file ! The file name including the boundary layer characteristics of the profile. Ignored if the aeroacoustic module is not called. +1 NumTabs ! Number of airfoil tables in this file. Each table must have lines for Re and Ctrl. +! ------------------------------------------------------------------------------ +! data for table 1 +! ------------------------------------------------------------------------------ +6.000000 Re ! Reynolds number in millions +0 Ctrl ! Control setting (must be 0 for current AirfoilInfo) +True InclUAdata ! Is unsteady aerodynamics data included in this table? If TRUE, then include 30 UA coefficients below this line +!........................................ +0.000000 alpha0 ! 0-lift angle of attack, depends on airfoil. +0.000000 alpha1 ! Angle of attack at f=0.7, (approximately the stall angle) for AOA>alpha0. (deg) +0.000000 alpha2 ! Angle of attack at f=0.7, (approximately the stall angle) for AOA1] +0.000000 S2 ! Constant in the f curve best-fit for AOA> alpha1; by definition it depends on the airfoil. [ignored if UAMod<>1] +0.000000 S3 ! Constant in the f curve best-fit for alpha2<=AOA< alpha0; by definition it depends on the airfoil. [ignored if UAMod<>1] +0.000000 S4 ! Constant in the f curve best-fit for AOA< alpha2; by definition it depends on the airfoil. [ignored if UAMod<>1] +0.000000 Cn1 ! Critical value of C0n at leading edge separation. It should be extracted from airfoil data at a given Mach and Reynolds number. It can be calculated from the static value of Cn at either the break in the pitching moment or the loss of chord force at the onset of stall. It is close to the condition of maximum lift of the airfoil at low Mach numbers. +0.000000 Cn2 ! As Cn1 for negative AOAs. +Default St_sh ! Strouhal's shedding frequency constant. [default = 0.19] +0.000000 Cd0 ! 2D drag coefficient value at 0-lift. +0.000000 Cm0 ! 2D pitching moment coefficient about 1/4-chord location, at 0-lift, positive if nose up. [If the aerodynamics coefficients table does not include a column for Cm, this needs to be set to 0.0] +0.000000 k0 ! Constant in the \hat(x)_cp curve best-fit; = (\hat(x)_AC-0.25). [ignored if UAMod<>1] +0.000000 k1 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k2 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k3 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k1_hat ! Constant in the expression of Cc due to leading edge vortex effects. [ignored if UAMod<>1] +Default x_cp_bar ! Constant in the expression of \hat(x)_cp^v. [ignored if UAMod<>1, default = 0.2] +Default UACutout ! Angle of attack above which unsteady aerodynamics are disabled (deg). [Specifying the string "Default" sets UACutout to 45 degrees] +Default filtCutOff ! Cut-off frequency (-3 dB corner frequency) for low-pass filtering the AoA input to UA, as well as the 1st and 2nd derivatives (Hz) [default = 20] +!........................................ +! Table of aerodynamics coefficients +200 NumAlf ! Number of data lines in the following table +! Alpha Cl Cd Cm +! (deg) (-) (-) (-) +-1.80000000000000e+02 0.00000000000000e+00 4.43994184250602e-01 0.00000000000000e+00 +-1.77000000000000e+02 5.28218858836285e-02 4.51778947168691e-01 6.31301215186523e-02 +-1.74000000000000e+02 1.06127688082721e-01 4.54846200132976e-01 1.26838596030369e-01 +-1.71000000000000e+02 1.59191863314727e-01 4.57721687001980e-01 1.90258289868333e-01 +-1.68000000000000e+02 1.97447618139026e-01 4.62593607482116e-01 2.03998727898909e-01 +-1.65000000000000e+02 2.28363691552126e-01 4.68241882193770e-01 1.92900117855920e-01 +-1.62000000000000e+02 2.59339036364168e-01 4.73545480231159e-01 1.81801380632199e-01 +-1.59000000000000e+02 2.79820337838342e-01 4.79170658239085e-01 1.73519743179148e-01 +-1.56000000000000e+02 2.79311457907633e-01 4.85668590966138e-01 1.70872209970165e-01 +-1.53000000000000e+02 2.78926753637668e-01 4.91502040321387e-01 1.68224656535610e-01 +-1.50000000000000e+02 2.78686833504982e-01 4.96473066155593e-01 1.65577105058638e-01 +-1.47000000000000e+02 2.78482617289417e-01 5.10449666953889e-01 1.68109661007669e-01 +-1.44000000000000e+02 2.78333002128108e-01 5.51477403517201e-01 1.70642226630173e-01 +-1.41000000000000e+02 2.78243478183707e-01 5.92505453513528e-01 1.73174811600312e-01 +-1.38000000000000e+02 2.74638204421170e-01 6.34935844279750e-01 1.76256259812944e-01 +-1.35000000000000e+02 2.69271830313825e-01 6.78067402586119e-01 1.79612138533394e-01 +-1.32000000000000e+02 2.63929918544127e-01 7.21199455141732e-01 1.82968055709224e-01 +-1.29000000000000e+02 2.56353341244360e-01 7.63167294790495e-01 1.86036517826043e-01 +-1.26000000000000e+02 2.44267095501969e-01 8.02806703094638e-01 1.88530068460767e-01 +-1.23000000000000e+02 2.32190027809931e-01 8.30095142617392e-01 1.91023600046048e-01 +-1.20000000000000e+02 2.20124030074996e-01 8.54280447094884e-01 1.93517122106963e-01 +-1.17000000000000e+02 2.01822771772063e-01 8.71322712892104e-01 1.94226310566758e-01 +-1.14000000000000e+02 1.83524830303930e-01 8.88364899623064e-01 1.94935492828237e-01 +-1.11000000000000e+02 1.65231494534441e-01 9.05406956162956e-01 1.95644669672032e-01 +-1.08000000000000e+02 1.43911689592217e-01 9.15698197853296e-01 1.94815640807175e-01 +-1.05000000000000e+02 1.21077486266499e-01 9.22613980715162e-01 1.93217497375608e-01 +-1.02000000000000e+02 9.82451183513876e-02 9.29529684328913e-01 1.91619372257204e-01 +-9.90000000000000e+01 7.47225598413416e-02 9.32477260333714e-01 1.89218782642220e-01 +-9.60000000000000e+01 4.98149331461973e-02 9.27488409240135e-01 1.85213229275117e-01 +-9.30000000000000e+01 2.49074967312809e-02 9.22499596258566e-01 1.81207706508184e-01 +-9.00000000000000e+01 1.55454756347091e-07 9.17510802332658e-01 1.75447976882559e-01 +-8.70000000000000e+01 -2.49074712386065e-02 9.22499591152534e-01 1.75821854055456e-01 +-8.40000000000000e+01 -4.98150027934706e-02 9.27488423190074e-01 1.75265803096445e-01 +-8.10000000000000e+01 -7.47223440699950e-02 9.32477217115983e-01 1.74297623848041e-01 +-7.80000000000000e+01 -9.82450077740596e-02 9.29529717823434e-01 1.71657379233808e-01 +-7.50000000000000e+01 -1.21077637330475e-01 9.22613934961229e-01 1.68181073081051e-01 +-7.20000000000000e+01 -1.43911579000158e-01 9.15698231347477e-01 1.64704806763536e-01 +-6.90000000000000e+01 -1.65231336083193e-01 9.05407103798478e-01 1.60521039551036e-01 +-6.60000000000000e+01 -1.83524881462789e-01 8.88364851969969e-01 1.54922212612248e-01 +-6.30000000000000e+01 -2.01822892842596e-01 8.71322600141459e-01 1.49323385673460e-01 +-6.00000000000000e+01 -2.20124109861353e-01 8.54280287086177e-01 1.43724546113009e-01 +-5.70000000000000e+01 -2.32190107676827e-01 8.30094982608685e-01 1.36653206413885e-01 +-5.40000000000000e+01 -2.44267175435753e-01 8.02806440842389e-01 1.29581839704227e-01 +-5.10000000000000e+01 -2.56353421232862e-01 7.63167032538246e-01 1.22510418973089e-01 +-4.80000000000000e+01 -2.63929913090152e-01 7.21199499288443e-01 1.14843085027639e-01 +-4.50000000000000e+01 -2.69271763474185e-01 6.78067940982074e-01 1.06877804052201e-01 +-4.20000000000000e+01 -2.74638198917296e-01 6.34935888423376e-01 9.89124318011671e-02 +-3.90000000000000e+01 -2.78243478234639e-01 5.92505417148744e-01 9.07777362760891e-02 +-3.60000000000000e+01 -2.78333002465160e-01 5.51477288799700e-01 8.23042410827366e-02 +-3.30000000000000e+01 -2.78482616088909e-01 5.10449944015222e-01 7.38309077181307e-02 +-3.00000000000000e+01 -2.78686834724237e-01 4.96473034437446e-01 6.53574058853759e-02 +-2.93939393939394e+01 -2.78722484884278e-01 4.95550482915159e-01 6.31590888898999e-02 +-2.87878787878788e+01 -2.78764834228033e-01 4.94584223091226e-01 6.07329510056277e-02 +-2.81818181818182e+01 -2.78813665479675e-01 4.93576735381485e-01 5.83222958533192e-02 +-2.75757575757576e+01 -2.78868771825416e-01 4.92530294643563e-01 5.59273989519316e-02 +-2.69696969696970e+01 -2.78929953713021e-01 4.91447040145689e-01 5.35486208968168e-02 +-2.63636363636364e+01 -2.78997019845282e-01 4.90328957261459e-01 5.11863242110430e-02 +-2.57575757575758e+01 -2.79069786417323e-01 4.89177896868326e-01 4.88408872710036e-02 +-2.51515151515151e+01 -2.79148077344780e-01 4.87995577350176e-01 4.65126844314689e-02 +-2.45454545454545e+01 -2.79231725535284e-01 4.86783573310055e-01 4.42020473048908e-02 +-2.39393939393939e+01 -2.79320569460013e-01 4.85543372341575e-01 4.19093587754535e-02 +-2.33333333333333e+01 -2.79414454019281e-01 4.84276364273540e-01 3.96350129365467e-02 +-2.27272727272727e+01 -2.79513230225828e-01 4.82983849071519e-01 3.73794155039853e-02 +-2.21212121212121e+01 -2.79616754906648e-01 4.81667043985251e-01 3.51429842476471e-02 +-2.15151515151515e+01 -2.79724892952109e-01 4.80327059059195e-01 3.29260988660576e-02 +-2.09090909090909e+01 -2.79837510321443e-01 4.78964987050167e-01 3.07292415847816e-02 +-2.03030303030303e+01 -2.79954479045127e-01 4.77581841281423e-01 2.85528819253764e-02 +-1.96969696969697e+01 -2.75171456546404e-01 4.76241678491924e-01 2.59885541142665e-02 +-1.90909090909091e+01 -2.65502607041286e-01 4.74932861964715e-01 2.30296767768801e-02 +-1.84848484848485e+01 -2.55857808543395e-01 4.73587766414009e-01 2.00850651071971e-02 +-1.78787878787879e+01 -2.46237593082487e-01 4.72205644697461e-01 1.71576346825735e-02 +-1.72727272727273e+01 -2.36642641160737e-01 4.70785737308274e-01 1.42512880441333e-02 +-1.66666666666667e+01 -2.27074552079369e-01 4.69327391673071e-01 1.13715515436610e-02 +-1.60606060606061e+01 -2.17534554179683e-01 4.67829874530176e-01 8.52581274757511e-03 +-1.54545454545455e+01 -2.08024441493220e-01 4.66292514169838e-01 5.72461577042921e-03 +-1.48484848484848e+01 -1.98545026218225e-01 4.64714449362364e-01 3.24301314993957e-03 +-1.42424242424242e+01 -1.89097459745549e-01 4.63094831340957e-01 2.15754331667197e-03 +-1.36363636363636e+01 -1.79689119603896e-01 4.61433905636119e-01 1.19082104448867e-03 +-1.30303030303030e+01 -1.70305930436414e-01 4.59727952028918e-01 4.04096803450701e-04 +-1.24242424242424e+01 -1.60970739714131e-01 4.57980061533300e-01 -1.08597634782590e-03 +-1.18181818181818e+01 -1.51665423337775e-01 4.56185474694515e-01 -5.28562481853854e-03 +-1.12121212121212e+01 -1.42405828637851e-01 4.54346018736465e-01 -9.48493644261989e-03 +-1.06060606060606e+01 -1.33190990892009e-01 4.51015638941563e-01 -1.36845608636440e-02 +-1.00000000000000e+01 -1.24014684903561e-01 4.44510346744821e-01 -1.78839224215030e-02 +-9.39393939393939e+00 -1.08436489679061e-01 4.35608923797464e-01 -1.72393490814751e-02 +-8.78787878787879e+00 -9.29541316307449e-02 4.26594514374539e-01 -1.65987787657685e-02 +-8.18181818181818e+00 -7.76026887758120e-02 4.17469560995041e-01 -1.59527308236021e-02 +-7.57575757575758e+00 -6.23970752419446e-02 4.08227566266090e-01 -1.52754905468310e-02 +-6.96969696969697e+00 -4.73685296749869e-02 3.98853223979206e-01 -1.42539284761816e-02 +-6.36363636363636e+00 -3.25421758356058e-02 3.89329220025460e-01 -1.32208969139180e-02 +-5.75757575757576e+00 -2.32883547306756e-02 3.79669167553607e-01 -1.21878209564984e-02 +-5.15151515151515e+00 -1.75463818719779e-02 3.69851724588186e-01 -1.11628011971168e-02 +-4.54545454545454e+00 -1.22231690324848e-02 3.59859373530705e-01 -1.01275683268214e-02 +-3.93939393939394e+00 -7.44825163485882e-03 3.49689752142525e-01 -9.09398161623545e-03 +-3.33333333333333e+00 -2.91658839268368e-03 3.40624828035861e-01 -8.49251566568143e-03 +-2.72727272727273e+00 1.68507347052569e-02 3.37851584545355e-01 -9.05855564667579e-03 +-2.12121212121212e+00 6.54268180916555e-02 3.38696970690453e-01 -1.01724248228530e-02 +-1.51515151515152e+00 1.14007336489887e-01 3.39540888251967e-01 -1.18440226132878e-02 +-9.09090909090912e-01 1.51313727007511e-01 3.40364324377504e-01 -1.33594433207991e-02 +-3.03030303030302e-01 1.79793106660581e-01 3.41119901467205e-01 -1.49439775633901e-02 + 3.03030303030302e-01 2.08277227321411e-01 3.41959802485552e-01 -1.65190153005760e-02 + 9.09090909090912e-01 2.36761120877396e-01 3.42798375876233e-01 -1.80436696564668e-02 + 1.51515151515152e+00 2.62099120009543e-01 3.43615726098759e-01 -1.96089791867871e-02 + 2.12121212121212e+00 2.98214942887010e-01 3.43590036955630e-01 -2.12433569551258e-02 + 2.72727272727273e+00 3.41265305298494e-01 3.43282612273994e-01 -2.28522580646574e-02 + 3.33333333333333e+00 3.84321941282732e-01 3.42975023524515e-01 -2.44142825317703e-02 + 3.93939393939394e+00 4.27399321163861e-01 3.42588020332646e-01 -2.59764367716794e-02 + 4.54545454545455e+00 4.70462749288264e-01 3.42270335299019e-01 -2.75887619844635e-02 + 5.15151515151515e+00 5.13550609798191e-01 3.41947566135864e-01 -2.91509206998043e-02 + 5.75757575757576e+00 5.51690452105184e-01 3.41583432622427e-01 -3.09254291087337e-02 + 6.36363636363637e+00 5.81502121097488e-01 3.41302193452691e-01 -3.30991045572195e-02 + 6.96969696969697e+00 6.10301560112658e-01 3.40942615842003e-01 -3.52998315891569e-02 + 7.57575757575757e+00 6.39640830053245e-01 3.40662394282476e-01 -3.74120160931164e-02 + 8.18181818181818e+00 6.73716922359672e-01 3.40349350542629e-01 -3.89332211349433e-02 + 8.78787878787879e+00 7.00575005999923e-01 3.40649231227702e-01 -4.05874368999055e-02 + 9.39393939393939e+00 7.05980518760212e-01 3.42347265627704e-01 -4.28334247556514e-02 + 1.00000000000000e+01 7.06877424431301e-01 3.44374177297010e-01 -4.52251156741810e-02 + 1.06060606060606e+01 2.24043543681458e-01 3.72918111447314e-01 -3.53747047936440e-02 + 1.12121212121212e+01 1.40264660669456e-01 4.01951061572017e-01 -4.64618913321433e-03 + 1.18181818181818e+01 1.31385056875955e-01 4.23992085353333e-01 -4.07850695907500e-03 + 1.24242424242424e+01 4.46038012430764e-01 4.42283118524471e-01 -5.50420221929163e-03 + 1.30303030303030e+01 5.55998373281915e-01 4.54419475361305e-01 -7.26003568693194e-03 + 1.36363636363636e+01 5.44188127636130e-01 4.58360923643072e-01 -7.86408309600584e-03 + 1.42424242424242e+01 5.27942944540329e-01 4.61684804811602e-01 -8.24435657376023e-03 + 1.48484848484848e+01 4.89688648561149e-01 4.64663565131384e-01 -8.63252791099281e-03 + 1.54545454545455e+01 4.48737588342535e-01 4.67211594818839e-01 -8.81024773998454e-03 + 1.60606060606061e+01 4.12943834077636e-01 4.69433759746416e-01 -9.21685653350780e-03 + 1.66666666666667e+01 4.12507412476758e-01 4.70665756115078e-01 -1.23356902066896e-02 + 1.72727272727273e+01 4.11140315107920e-01 4.71853296753582e-01 -1.57410394707879e-02 + 1.78787878787879e+01 4.08617622571655e-01 4.72990750025282e-01 -1.94979904601476e-02 + 1.84848484848485e+01 4.06114881343676e-01 4.74116453453578e-01 -2.33119670538974e-02 + 1.90909090909091e+01 4.03627419358201e-01 4.75230998047512e-01 -2.71766217490092e-02 + 1.96969696969697e+01 4.01154151508036e-01 4.76335071600720e-01 -3.10855411393017e-02 + 2.03030303030303e+01 3.99841450263120e-01 4.77581841281423e-01 -3.43354943821136e-02 + 2.09090909090909e+01 3.99682666388390e-01 4.78964987050167e-01 -3.69103854071785e-02 + 2.15151515151515e+01 3.99530136656685e-01 4.80327059059195e-01 -3.95071276844189e-02 + 2.21212121212121e+01 3.99384045127721e-01 4.81667043985251e-01 -4.21252206930270e-02 + 2.27272727272727e+01 3.99244584495002e-01 4.82983849071519e-01 -4.47641473640253e-02 + 2.33333333333333e+01 3.99111949378307e-01 4.84276364273540e-01 -4.74235100634337e-02 + 2.39393939393939e+01 3.98986345789788e-01 4.85543372341575e-01 -5.01028646553693e-02 + 2.45454545454545e+01 3.98867988116513e-01 4.86783573310055e-01 -5.28017797812506e-02 + 2.51515151515151e+01 3.98757099550410e-01 4.87995577350176e-01 -5.55198364035922e-02 + 2.57575757575758e+01 3.98653912544980e-01 4.89177896868326e-01 -5.82566273692076e-02 + 2.63636363636364e+01 3.98558667733390e-01 4.90328957261459e-01 -6.10118045012879e-02 + 2.69696969696970e+01 3.98471618483357e-01 4.91447040145689e-01 -6.37849681601756e-02 + 2.75757575757576e+01 3.98393029231929e-01 4.92530294643563e-01 -6.65757129024393e-02 + 2.81818181818182e+01 3.98323175239888e-01 4.93576735381485e-01 -6.93836508624560e-02 + 2.87878787878788e+01 3.98262343636652e-01 4.94584223091226e-01 -7.22083954498178e-02 + 2.93939393939394e+01 3.98210832316413e-01 4.95550482915159e-01 -7.50496587540483e-02 + 3.00000000000000e+01 3.98168954058675e-01 4.96473034437446e-01 -7.79071060247789e-02 + 3.30000000000000e+01 3.97861629624178e-01 5.10449944015222e-01 -8.85000759993798e-02 + 3.60000000000000e+01 3.97632504408999e-01 5.51477288799700e-01 -9.78012526556367e-02 + 3.90000000000000e+01 3.97489452250910e-01 5.92505417148744e-01 -1.06793009320285e-01 + 4.20000000000000e+01 3.92296355524120e-01 6.34935888423376e-01 -1.14716558885029e-01 + 4.50000000000000e+01 3.84572561868948e-01 6.78067940982074e-01 -1.22106077030729e-01 + 4.80000000000000e+01 3.76882670622963e-01 7.21199499288443e-01 -1.29495510499575e-01 + 5.10000000000000e+01 3.66020533668567e-01 7.63167032538246e-01 -1.36361479578265e-01 + 5.40000000000000e+01 3.48758349336931e-01 8.02806440842389e-01 -1.42180486224307e-01 + 5.70000000000000e+01 3.31509203268269e-01 8.30094982608685e-01 -1.47999448416575e-01 + 6.00000000000000e+01 3.14275781966473e-01 8.54280287086177e-01 -1.53818388382123e-01 + 6.30000000000000e+01 2.88206454299320e-01 8.71322600141459e-01 -1.57969229855332e-01 + 6.60000000000000e+01 2.62142183925970e-01 8.88364851969969e-01 -1.62120057030290e-01 + 6.90000000000000e+01 2.36084952068339e-01 9.05407103798478e-01 -1.66270884205247e-01 + 7.20000000000000e+01 2.05649772307401e-01 9.15698231347478e-01 -1.69225081057529e-01 + 7.50000000000000e+01 1.73023749638975e-01 9.22613934961229e-01 -1.71580987245091e-01 + 7.80000000000000e+01 1.40399517677831e-01 9.29529717823434e-01 -1.73936920429460e-01 + 8.10000000000000e+01 1.06786972533886e-01 9.32477217115983e-01 -1.75676992294215e-01 + 8.40000000000000e+01 7.11914675762680e-02 9.27488423190074e-01 -1.76185384031098e-01 + 8.70000000000000e+01 3.55956906886392e-02 9.22499591152534e-01 -1.76281636984940e-01 + 9.00000000000000e+01 -1.55454756453089e-07 9.17510802332658e-01 -1.75447976882559e-01 + 9.30000000000000e+01 -2.49074967312808e-02 9.22499596258566e-01 -1.81207706508184e-01 + 9.60000000000000e+01 -4.98149331461974e-02 9.27488409240135e-01 -1.85213229275117e-01 + 9.90000000000000e+01 -7.47225598413417e-02 9.32477260333714e-01 -1.89218782642220e-01 + 1.02000000000000e+02 -9.82451183513876e-02 9.29529684328913e-01 -1.91619372257204e-01 + 1.05000000000000e+02 -1.21077486266499e-01 9.22613980715162e-01 -1.93217497375608e-01 + 1.08000000000000e+02 -1.43911689592217e-01 9.15698197853296e-01 -1.94815640807175e-01 + 1.11000000000000e+02 -1.65231494534441e-01 9.05406956162956e-01 -1.95644669672032e-01 + 1.14000000000000e+02 -1.83524830303930e-01 8.88364899623064e-01 -1.94935492828237e-01 + 1.17000000000000e+02 -2.01822771772063e-01 8.71322712892104e-01 -1.94226310566758e-01 + 1.20000000000000e+02 -2.20124030074997e-01 8.54280447094884e-01 -1.93517122106963e-01 + 1.23000000000000e+02 -2.32190027809931e-01 8.30095142617392e-01 -1.91023600046048e-01 + 1.26000000000000e+02 -2.44267095501969e-01 8.02806703094638e-01 -1.88530068460767e-01 + 1.29000000000000e+02 -2.56353341244360e-01 7.63167294790494e-01 -1.86036517826043e-01 + 1.32000000000000e+02 -2.63929918544127e-01 7.21199455141732e-01 -1.82968055709224e-01 + 1.35000000000000e+02 -2.69271830313825e-01 6.78067402586119e-01 -1.79612138533394e-01 + 1.38000000000000e+02 -2.74638204421170e-01 6.34935844279749e-01 -1.76256259812944e-01 + 1.41000000000000e+02 -2.78243478183707e-01 5.92505453513527e-01 -1.73174811600312e-01 + 1.44000000000000e+02 -2.78333002128108e-01 5.51477403517201e-01 -1.70642226630173e-01 + 1.47000000000000e+02 -2.78482617289417e-01 5.10449666953889e-01 -1.68109661007669e-01 + 1.50000000000000e+02 -2.78686833504982e-01 4.96473066155593e-01 -1.65577105058638e-01 + 1.53000000000000e+02 -2.78926753637668e-01 4.91502040321387e-01 -1.68224656535610e-01 + 1.56000000000000e+02 -2.79311457907633e-01 4.85668590966138e-01 -1.70872209970165e-01 + 1.59000000000000e+02 -2.79820337838342e-01 4.79170658239085e-01 -1.73519743179148e-01 + 1.62000000000000e+02 -2.59339036364167e-01 4.73545480231159e-01 -1.92371270010081e-01 + 1.65000000000000e+02 -2.28363691552126e-01 4.68241882193770e-01 -2.19324930692370e-01 + 1.68000000000000e+02 -1.97447618139026e-01 4.62593607482116e-01 -2.46278282511930e-01 + 1.71000000000000e+02 -1.59191863314727e-01 4.57721687001980e-01 -2.37822862335416e-01 + 1.74000000000000e+02 -1.06127688082721e-01 4.54846200132976e-01 -1.58548245037961e-01 + 1.77000000000000e+02 -5.28218858836285e-02 4.51778947168691e-01 -7.89126518983154e-02 + 1.80000000000000e+02 0.00000000000000e+00 4.43994184250602e-01 0.00000000000000e+00 diff --git a/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_03.dat b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_03.dat new file mode 100644 index 00000000..1c63fe2f --- /dev/null +++ b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_03.dat @@ -0,0 +1,254 @@ +! ------------ AirfoilInfo v1.01.x Input File ---------------------------------- +! AeroElasticSE FAST driver +! line +! line +! ------------------------------------------------------------------------------ +DEFAULT InterpOrd ! Interpolation order to use for quasi-steady table lookup {1=linear; 3=cubic spline; "default"} [default=3] +1 NonDimArea ! The non-dimensional area of the airfoil (area/chord^2) (set to 1.0 if unsure or unneeded) +@"NREL-2p8-127_AF03_Coords.txt" NumCoords ! The number of coordinates in the airfoil shape file. Set to zero if coordinates not included. +AF03_BL.txt BL_file ! The file name including the boundary layer characteristics of the profile. Ignored if the aeroacoustic module is not called. +1 NumTabs ! Number of airfoil tables in this file. Each table must have lines for Re and Ctrl. +! ------------------------------------------------------------------------------ +! data for table 1 +! ------------------------------------------------------------------------------ +6.000000 Re ! Reynolds number in millions +0 Ctrl ! Control setting (must be 0 for current AirfoilInfo) +True InclUAdata ! Is unsteady aerodynamics data included in this table? If TRUE, then include 30 UA coefficients below this line +!........................................ +0.000000 alpha0 ! 0-lift angle of attack, depends on airfoil. +0.000000 alpha1 ! Angle of attack at f=0.7, (approximately the stall angle) for AOA>alpha0. (deg) +0.000000 alpha2 ! Angle of attack at f=0.7, (approximately the stall angle) for AOA1] +0.000000 S2 ! Constant in the f curve best-fit for AOA> alpha1; by definition it depends on the airfoil. [ignored if UAMod<>1] +0.000000 S3 ! Constant in the f curve best-fit for alpha2<=AOA< alpha0; by definition it depends on the airfoil. [ignored if UAMod<>1] +0.000000 S4 ! Constant in the f curve best-fit for AOA< alpha2; by definition it depends on the airfoil. [ignored if UAMod<>1] +0.000000 Cn1 ! Critical value of C0n at leading edge separation. It should be extracted from airfoil data at a given Mach and Reynolds number. It can be calculated from the static value of Cn at either the break in the pitching moment or the loss of chord force at the onset of stall. It is close to the condition of maximum lift of the airfoil at low Mach numbers. +0.000000 Cn2 ! As Cn1 for negative AOAs. +Default St_sh ! Strouhal's shedding frequency constant. [default = 0.19] +0.000000 Cd0 ! 2D drag coefficient value at 0-lift. +0.000000 Cm0 ! 2D pitching moment coefficient about 1/4-chord location, at 0-lift, positive if nose up. [If the aerodynamics coefficients table does not include a column for Cm, this needs to be set to 0.0] +0.000000 k0 ! Constant in the \hat(x)_cp curve best-fit; = (\hat(x)_AC-0.25). [ignored if UAMod<>1] +0.000000 k1 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k2 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k3 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k1_hat ! Constant in the expression of Cc due to leading edge vortex effects. [ignored if UAMod<>1] +Default x_cp_bar ! Constant in the expression of \hat(x)_cp^v. [ignored if UAMod<>1, default = 0.2] +Default UACutout ! Angle of attack above which unsteady aerodynamics are disabled (deg). [Specifying the string "Default" sets UACutout to 45 degrees] +Default filtCutOff ! Cut-off frequency (-3 dB corner frequency) for low-pass filtering the AoA input to UA, as well as the 1st and 2nd derivatives (Hz) [default = 20] +!........................................ +! Table of aerodynamics coefficients +200 NumAlf ! Number of data lines in the following table +! Alpha Cl Cd Cm +! (deg) (-) (-) (-) +-1.80000000000000e+02 0.00000000000000e+00 2.86667939639823e-01 0.00000000000000e+00 +-1.77000000000000e+02 1.03993393584518e-01 2.98099548900633e-01 1.09870530503698e-01 +-1.74000000000000e+02 2.08939500216179e-01 3.07632373564454e-01 2.20747616176905e-01 +-1.71000000000000e+02 3.13409902357768e-01 3.16774623015665e-01 3.31122113148220e-01 +-1.68000000000000e+02 3.85054442612432e-01 3.34234373573580e-01 3.53101024359159e-01 +-1.65000000000000e+02 4.40412121695890e-01 3.55419527359135e-01 3.30883174396667e-01 +-1.62000000000000e+02 4.95885499788614e-01 3.75931646834106e-01 3.08665069836311e-01 +-1.59000000000000e+02 5.30626275353240e-01 3.98846265744607e-01 2.91144350600985e-01 +-1.56000000000000e+02 5.23897762918947e-01 4.27014220182996e-01 2.83018243112307e-01 +-1.53000000000000e+02 5.17411720704259e-01 4.53884562381070e-01 2.74892073545017e-01 +-1.50000000000000e+02 5.11208424965791e-01 4.79070665595520e-01 2.66765899031848e-01 +-1.47000000000000e+02 5.07722631231294e-01 5.14614980861448e-01 2.69838067335530e-01 +-1.44000000000000e+02 5.04343461108966e-01 5.71996674202226e-01 2.72910247373812e-01 +-1.41000000000000e+02 5.01081625048703e-01 6.29378805912717e-01 2.75982450882136e-01 +-1.38000000000000e+02 4.92453728624275e-01 6.88722261711689e-01 2.80934437546522e-01 +-1.35000000000000e+02 4.81136499725427e-01 7.49046375576140e-01 2.86826311975596e-01 +-1.32000000000000e+02 4.69867035979492e-01 8.09371180701211e-01 2.92718253920303e-01 +-1.29000000000000e+02 4.54938482726295e-01 8.68067709113985e-01 2.98486582390899e-01 +-1.26000000000000e+02 4.32612975232015e-01 9.23507676366582e-01 3.04007683325731e-01 +-1.23000000000000e+02 4.10305382623877e-01 9.74580839620112e-01 3.09528742082194e-01 +-1.20000000000000e+02 3.88019404664959e-01 1.02455678086533e+00 3.15049779750259e-01 +-1.17000000000000e+02 3.55328226413339e-01 1.06294869915767e+00 3.18312911803281e-01 +-1.14000000000000e+02 3.22643517723842e-01 1.10134044814828e+00 3.21576026976400e-01 +-1.11000000000000e+02 2.89967780617592e-01 1.13973190385125e+00 3.24839117221471e-01 +-1.08000000000000e+02 2.52261395940272e-01 1.16675109608688e+00 3.25784702971782e-01 +-1.05000000000000e+02 2.12037421291888e-01 1.18808406999478e+00 3.25571518828366e-01 +-1.02000000000000e+02 1.71816981097322e-01 1.20941679944765e+00 3.25358337127833e-01 +-9.90000000000000e+01 1.30505705696886e-01 1.22393767216320e+00 3.23791373077473e-01 +-9.60000000000000e+01 8.70036173585535e-02 1.22483453634678e+00 3.19516785688025e-01 +-9.30000000000000e+01 4.35018613516539e-02 1.22573139367882e+00 3.15242230954016e-01 +-9.00000000000000e+01 2.71507463396801e-07 1.22662824758516e+00 3.07541711312162e-01 +-8.70000000000000e+01 -4.35018168277582e-02 1.22573139459675e+00 3.06500259153458e-01 +-8.40000000000000e+01 -8.70037390000840e-02 1.22483453383895e+00 3.03642638678455e-01 +-8.10000000000000e+01 -1.30505328844274e-01 1.22393767993261e+00 2.99980148628166e-01 +-7.80000000000000e+01 -1.71816786310515e-01 1.20941690276751e+00 2.93732912001213e-01 +-7.50000000000000e+01 -2.12037687400372e-01 1.18808392885856e+00 2.86193257479784e-01 +-7.20000000000000e+01 -2.52261201124482e-01 1.16675119940570e+00 2.78653689355799e-01 +-6.90000000000000e+01 -2.89967497594430e-01 1.13973223643685e+00 2.70131045852760e-01 +-6.60000000000000e+01 -3.22643609105459e-01 1.10134034079787e+00 2.59642171088866e-01 +-6.30000000000000e+01 -3.55328442677626e-01 1.06294844515890e+00 2.49153296324973e-01 +-6.00000000000000e+01 -3.88019552026475e-01 1.02455645022712e+00 2.38664407299212e-01 +-5.70000000000000e+01 -4.10305530142687e-01 9.74580508981902e-01 2.26511664589643e-01 +-5.40000000000000e+01 -4.32613122881359e-01 9.23507309578663e-01 2.14358875460006e-01 +-5.10000000000000e+01 -4.54938630482502e-01 8.68067342326065e-01 2.02205993489526e-01 +-4.80000000000000e+01 -4.69867024471485e-01 8.09371242445124e-01 1.89666602848052e-01 +-4.50000000000000e+01 -4.81136358743375e-01 7.49047128580672e-01 1.76933964082825e-01 +-4.20000000000000e+01 -4.92453717018877e-01 6.88722323451287e-01 1.64201179411986e-01 +-3.90000000000000e+01 -5.01081627884301e-01 6.29378755052664e-01 1.51481884585662e-01 +-3.60000000000000e+01 -5.04343470398699e-01 5.71996513757487e-01 1.38789326350142e-01 +-3.30000000000000e+01 -5.07722608040306e-01 5.14615368361460e-01 1.26097010519998e-01 +-3.00000000000000e+01 -5.11208459117473e-01 4.79070493417508e-01 1.13404444471583e-01 +-2.93939393939394e+01 -5.12436596980431e-01 4.74141998928450e-01 1.10133084143430e-01 +-2.87878787878788e+01 -5.13677818293272e-01 4.69128142491057e-01 1.06416791520792e-01 +-2.81818181818182e+01 -5.14931698718120e-01 4.64033768336758e-01 1.02730736544464e-01 +-2.75757575757576e+01 -5.16197857581441e-01 4.58863256541541e-01 9.90754777938710e-02 +-2.69696969696970e+01 -5.17475891884770e-01 4.53620820905796e-01 9.54517077990795e-02 +-2.63636363636364e+01 -5.18765418068804e-01 4.48310365722169e-01 9.18601257810618e-02 +-2.57575757575758e+01 -5.20066063887109e-01 4.42935541572834e-01 8.83014589939624e-02 +-2.51515151515151e+01 -5.21377478812960e-01 4.37499722355814e-01 8.47764326963560e-02 +-2.45454545454545e+01 -5.22699356428834e-01 4.32005929515122e-01 8.12857120895547e-02 +-2.39393939393939e+01 -5.24031381270285e-01 4.26457068308669e-01 7.78300449431755e-02 +-2.33333333333333e+01 -5.25373250428924e-01 4.20855853060512e-01 7.44102009183187e-02 +-2.27272727272727e+01 -5.26724672933875e-01 4.15204822592555e-01 7.10269723745852e-02 +-2.21212121212121e+01 -5.28085369169450e-01 4.09506354183381e-01 6.76811752130597e-02 +-2.15151515151515e+01 -5.29455101817919e-01 4.03762544083001e-01 6.43735744019926e-02 +-2.09090909090909e+01 -5.30833589187798e-01 3.97975580174912e-01 6.11050941602448e-02 +-2.03030303030303e+01 -5.32220574716406e-01 3.92147459389974e-01 5.78766456029426e-02 +-1.96969696969697e+01 -5.25041853310013e-01 3.86734130344610e-01 5.36740381794206e-02 +-1.90909090909091e+01 -5.09325030771277e-01 3.81712847911617e-01 4.84844307653104e-02 +-1.84848484848485e+01 -4.93655025441404e-01 3.76620832907035e-01 4.33226553930925e-02 +-1.78787878787879e+01 -4.78033039651211e-01 3.71456499045297e-01 3.81944365371004e-02 +-1.72727272727273e+01 -4.62460538476065e-01 3.66218257085999e-01 3.31074211396244e-02 +-1.66666666666667e+01 -4.46940500203995e-01 3.60904945553023e-01 2.80723751195183e-02 +-1.60606060606061e+01 -4.31475323775307e-01 3.55515132392443e-01 2.31037263323430e-02 +-1.54545454545455e+01 -4.16068349642614e-01 3.50047632879528e-01 1.82220369706882e-02 +-1.48484848484848e+01 -4.00721354508913e-01 3.44500616736217e-01 1.35484980910323e-02 +-1.42424242424242e+01 -3.85436695885767e-01 3.38872341578923e-01 9.50016605244364e-03 +-1.36363636363636e+01 -3.70224538567261e-01 3.33164648622073e-01 5.68381330007907e-03 +-1.30303030303030e+01 -3.55069373476952e-01 3.27366609646139e-01 2.21886814225965e-03 +-1.24242424242424e+01 -3.39999733693878e-01 3.21489179943910e-01 -1.51885448689381e-03 +-1.18181818181818e+01 -3.24995626539620e-01 3.15518354985586e-01 -7.39251364704825e-03 +-1.12121212121212e+01 -3.10077560762327e-01 3.09460976947365e-01 -1.32657016910330e-02 +-1.06060606060606e+01 -2.95245474304323e-01 3.02802644980894e-01 -1.91393272151166e-02 +-1.00000000000000e+01 -2.80494800381428e-01 2.94941318686088e-01 -2.50125850968491e-02 +-9.39393939393939e+00 -2.53378368416910e-01 2.85498339501372e-01 -2.41110800948355e-02 +-8.78787878787879e+00 -2.26455617318188e-01 2.75839796452712e-01 -2.32151737520043e-02 +-8.18181818181818e+00 -1.99780347135765e-01 2.65960153502913e-01 -2.23116063606220e-02 +-7.57575757575758e+00 -1.73389839145603e-01 2.55848927836634e-01 -2.13969572586265e-02 +-6.96969696969697e+00 -1.47345183372831e-01 2.45482961997361e-01 -2.03679525995866e-02 +-6.36363636363636e+00 -1.21705108097721e-01 2.34834463036821e-01 -1.93275559307849e-02 +-5.75757575757576e+00 -9.84583488516512e-02 2.23910273504550e-01 -1.82871145503072e-02 +-5.15151515151515e+00 -7.69804748827422e-02 2.12678155631259e-01 -1.72546758160953e-02 +-4.54545454545454e+00 -5.63182850040337e-02 2.01106147724455e-01 -1.62156816231646e-02 +-3.93939393939394e+00 -3.67302227953779e-02 1.89186489694562e-01 -1.51750925589128e-02 +-3.33333333333333e+00 -1.62909510485965e-02 1.78416547415723e-01 -1.45633390580307e-02 +-2.72727272727273e+00 2.35675611773452e-02 1.75058203392890e-01 -1.57637846300459e-02 +-2.12121212121212e+00 9.15064277602737e-02 1.76056082872914e-01 -1.78244951342892e-02 +-1.51515151515152e+00 1.59451497183287e-01 1.77051126032286e-01 -2.03910649409379e-02 +-9.09090909090912e-01 2.23403602833365e-01 1.78026120925083e-01 -2.27493568922369e-02 +-3.03030303030302e-01 2.84237891949164e-01 1.78938378727225e-01 -2.51368568675113e-02 + 3.03030303030302e-01 3.45074372567327e-01 1.79925592577568e-01 -2.75148616917628e-02 + 9.09090909090912e-01 4.05913145027735e-01 1.80910163063640e-01 -2.98751951472708e-02 + 1.51515151515152e+00 4.60391564367498e-01 1.81869640777608e-01 -3.22531226669864e-02 + 2.12121212121212e+00 5.26159436695712e-01 1.81867217039864e-01 -3.48049504623527e-02 + 2.72727272727273e+00 6.00837730272748e-01 1.81506752812675e-01 -3.74260524663783e-02 + 3.33333333333333e+00 6.75529949068352e-01 1.81145950978939e-01 -4.00304350025881e-02 + 3.93939393939394e+00 7.50255901253955e-01 1.80716836967219e-01 -4.26350339105715e-02 + 4.54545454545455e+00 8.24966195051160e-01 1.80347288666951e-01 -4.52499112015484e-02 + 5.15151515151515e+00 8.99712588876260e-01 1.79976785308154e-01 -4.78545175714740e-02 + 5.75757575757576e+00 9.67968657716851e-01 1.79568694884216e-01 -5.06699455716737e-02 + 6.36363636363637e+00 1.02536319902264e+00 1.79238042626890e-01 -5.38531921907918e-02 + 6.96969696969697e+00 1.08152198541483e+00 1.78841802101979e-01 -5.70812124887872e-02 + 7.57575757575757e+00 1.13835718017464e+00 1.78513776681022e-01 -6.02799006382464e-02 + 8.18181818181818e+00 1.20034525413988e+00 1.78155584214918e-01 -6.32698190171098e-02 + 8.78787878787879e+00 1.25229031916550e+00 1.78543028590070e-01 -6.64922350787756e-02 + 9.39393939393939e+00 1.27694825197027e+00 1.80574010062172e-01 -7.03025346844773e-02 + 1.00000000000000e+01 1.29634873488058e+00 1.82986102023255e-01 -7.42574649964911e-02 + 1.06060606060606e+01 7.61428140940585e-01 2.15852259319746e-01 -6.42507106934242e-02 + 1.12121212121212e+01 6.15718379411708e-01 2.48106113414377e-01 -2.23104303837720e-02 + 1.18181818181818e+01 5.89645960609568e-01 2.71990713431963e-01 -2.03506593942910e-02 + 1.24242424242424e+01 8.40078452027123e-01 2.92157538787909e-01 -2.37998425692650e-02 + 1.30303030303030e+01 9.36540372696081e-01 3.08975183148329e-01 -2.65133219580019e-02 + 1.36363636363636e+01 9.30793183702627e-01 3.21455925212482e-01 -2.79339590650596e-02 + 1.42424242424242e+01 9.21535598013246e-01 3.32263191328175e-01 -2.92269843086423e-02 + 1.48484848484848e+01 8.79920211959341e-01 3.42195165358544e-01 -3.05512733483560e-02 + 1.54545454545455e+01 8.39112171194525e-01 3.50890504854493e-01 -3.17289039382959e-02 + 1.60606060606061e+01 8.05866011124999e-01 3.58713280531263e-01 -3.32426789378008e-02 + 1.66666666666667e+01 8.00847317731894e-01 3.63662607459754e-01 -3.82620408096336e-02 + 1.72727272727273e+01 7.94727809634000e-01 3.68473291646017e-01 -4.36253357634993e-02 + 1.78787878787879e+01 7.87227516277651e-01 3.73122818099744e-01 -4.94117560810391e-02 + 1.84848484848485e+01 7.79760973975816e-01 3.77747724480973e-01 -5.53090732287109e-02 + 1.90909090909091e+01 7.72322946522647e-01 3.82350733174758e-01 -6.13053346702226e-02 + 1.96969696969697e+01 7.64912514438728e-01 3.86935069316851e-01 -6.73885480064952e-02 + 2.03030303030303e+01 7.60227909567809e-01 3.92147459389974e-01 -7.23552962067858e-02 + 2.09090909090909e+01 7.58256171990743e-01 3.97975580174912e-01 -7.61741534254430e-02 + 2.15151515151515e+01 7.56296648702810e-01 4.03762544083001e-01 -8.00356859572341e-02 + 2.21212121212121e+01 7.54349708693408e-01 4.09506354183381e-01 -8.39389232226646e-02 + 2.27272727272727e+01 7.52415756848464e-01 4.15204822592555e-01 -8.78828761836009e-02 + 2.33333333333333e+01 7.50495135179352e-01 4.20855853060512e-01 -9.18667405374683e-02 + 2.39393939393939e+01 7.48588246026085e-01 4.26457068308669e-01 -9.58896488905942e-02 + 2.45454545454545e+01 7.46695508084816e-01 4.32005929515122e-01 -9.99507588032690e-02 + 2.51515151515151e+01 7.44817357247520e-01 4.37499722355814e-01 -1.04049251898781e-01 + 2.57575757575758e+01 7.42954247493942e-01 4.42935541572834e-01 -1.08184333010354e-01 + 2.63636363636364e+01 7.41106620219380e-01 4.48310365722169e-01 -1.12355301356762e-01 + 2.69696969696970e+01 7.39274979765670e-01 4.53620820905796e-01 -1.16561383374543e-01 + 2.75757575757576e+01 7.37459861618629e-01 4.58863256541540e-01 -1.20801801101431e-01 + 2.81818181818182e+01 7.35661817641651e-01 4.64033768336758e-01 -1.25075807437783e-01 + 2.87878787878788e+01 7.33881427635071e-01 4.69128142491057e-01 -1.29382661238589e-01 + 2.93939393939394e+01 7.32119240063399e-01 4.74141998928450e-01 -1.33721775955579e-01 + 3.00000000000000e+01 7.30375865782397e-01 4.79070493417508e-01 -1.38092497824076e-01 + 3.30000000000000e+01 7.25362478438806e-01 5.14615368361460e-01 -1.54403266201777e-01 + 3.60000000000000e+01 7.20501914137933e-01 5.71996513757487e-01 -1.68191263513666e-01 + 3.90000000000000e+01 7.15809365515503e-01 6.29378755052664e-01 -1.81374882567390e-01 + 4.20000000000000e+01 7.03433185279059e-01 6.88722323451288e-01 -1.93418520707176e-01 + 4.50000000000000e+01 6.87204092577322e-01 7.49047128580672e-01 -2.04892279627535e-01 + 4.80000000000000e+01 6.71041224113679e-01 8.09371242445124e-01 -2.16365907069522e-01 + 5.10000000000000e+01 6.49672046103066e-01 8.68067342326066e-01 -2.27288040920096e-01 + 5.40000000000000e+01 6.17781812255886e-01 9.23507309578663e-01 -2.37107152133572e-01 + 5.70000000000000e+01 5.85917028103372e-01 9.74580508981902e-01 -2.46926188334836e-01 + 6.00000000000000e+01 5.54082947327309e-01 1.02455645022712e+00 -2.56745187030279e-01 + 6.30000000000000e+01 5.07474214362050e-01 1.06294844515890e+00 -2.64611277891633e-01 + 6.60000000000000e+01 4.60875379522342e-01 1.10134034079787e+00 -2.72477352013468e-01 + 6.90000000000000e+01 4.14290290845089e-01 1.13973223643685e+00 -2.80343426135302e-01 + 7.20000000000000e+01 3.60455499151900e-01 1.16675119940570e+00 -2.86657663083315e-01 + 7.50000000000000e+01 3.02992179274825e-01 1.18808392885856e+00 -2.92196013212590e-01 + 7.80000000000000e+01 2.45532428311787e-01 1.20941690276751e+00 -2.97734426806946e-01 + 8.10000000000000e+01 1.86507133137001e-01 1.22393767993261e+00 -3.02380776716557e-01 + 8.40000000000000e+01 1.24338355198263e-01 1.22483453383895e+00 -3.05243060833536e-01 + 8.70000000000000e+01 6.21691023243765e-02 1.22573139459675e+00 -3.07300455628019e-01 + 9.00000000000000e+01 -2.71507463581614e-07 1.22662824758516e+00 -3.07541711312162e-01 + 9.30000000000000e+01 -4.35018613516539e-02 1.22573139367882e+00 -3.15242230954016e-01 + 9.60000000000000e+01 -8.70036173585537e-02 1.22483453634678e+00 -3.19516785688025e-01 + 9.90000000000000e+01 -1.30505705696887e-01 1.22393767216320e+00 -3.23791373077473e-01 + 1.02000000000000e+02 -1.71816981097322e-01 1.20941679944765e+00 -3.25358337127833e-01 + 1.05000000000000e+02 -2.12037421291888e-01 1.18808406999478e+00 -3.25571518828366e-01 + 1.08000000000000e+02 -2.52261395940272e-01 1.16675109608688e+00 -3.25784702971782e-01 + 1.11000000000000e+02 -2.89967780617593e-01 1.13973190385125e+00 -3.24839117221471e-01 + 1.14000000000000e+02 -3.22643517723843e-01 1.10134044814828e+00 -3.21576026976400e-01 + 1.17000000000000e+02 -3.55328226413339e-01 1.06294869915767e+00 -3.18312911803281e-01 + 1.20000000000000e+02 -3.88019404664959e-01 1.02455678086533e+00 -3.15049779750259e-01 + 1.23000000000000e+02 -4.10305382623878e-01 9.74580839620111e-01 -3.09528742082193e-01 + 1.26000000000000e+02 -4.32612975232015e-01 9.23507676366582e-01 -3.04007683325731e-01 + 1.29000000000000e+02 -4.54938482726295e-01 8.68067709113984e-01 -2.98486582390899e-01 + 1.32000000000000e+02 -4.69867035979492e-01 8.09371180701210e-01 -2.92718253920303e-01 + 1.35000000000000e+02 -4.81136499725427e-01 7.49046375576140e-01 -2.86826311975596e-01 + 1.38000000000000e+02 -4.92453728624275e-01 6.88722261711688e-01 -2.80934437546522e-01 + 1.41000000000000e+02 -5.01081625048703e-01 6.29378805912717e-01 -2.75982450882136e-01 + 1.44000000000000e+02 -5.04343461108966e-01 5.71996674202226e-01 -2.72910247373812e-01 + 1.47000000000000e+02 -5.07722631231294e-01 5.14614980861448e-01 -2.69838067335530e-01 + 1.50000000000000e+02 -5.11208424965791e-01 4.79070665595519e-01 -2.66765899031848e-01 + 1.53000000000000e+02 -5.17411720704259e-01 4.53884562381070e-01 -2.74892073545017e-01 + 1.56000000000000e+02 -5.23897762918947e-01 4.27014220182996e-01 -2.83018243112307e-01 + 1.59000000000000e+02 -5.30626275353240e-01 3.98846265744607e-01 -2.91144350600985e-01 + 1.62000000000000e+02 -4.95885499788614e-01 3.75931646834106e-01 -3.27060715613266e-01 + 1.65000000000000e+02 -4.40412121695890e-01 3.55419527359135e-01 -3.76872444414846e-01 + 1.68000000000000e+02 -3.85054442612432e-01 3.34234373573580e-01 -4.26683602422472e-01 + 1.71000000000000e+02 -3.13409902357768e-01 3.16774623015665e-01 -4.13902641435275e-01 + 1.74000000000000e+02 -2.08939500216179e-01 3.07632373564454e-01 -2.75934520221132e-01 + 1.77000000000000e+02 -1.03993393584518e-01 2.98099548900633e-01 -1.37338163129622e-01 + 1.80000000000000e+02 0.00000000000000e+00 2.86667939639823e-01 0.00000000000000e+00 diff --git a/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_04.dat b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_04.dat new file mode 100644 index 00000000..abbe8560 --- /dev/null +++ b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_04.dat @@ -0,0 +1,254 @@ +! ------------ AirfoilInfo v1.01.x Input File ---------------------------------- +! AeroElasticSE FAST driver +! line +! line +! ------------------------------------------------------------------------------ +DEFAULT InterpOrd ! Interpolation order to use for quasi-steady table lookup {1=linear; 3=cubic spline; "default"} [default=3] +1 NonDimArea ! The non-dimensional area of the airfoil (area/chord^2) (set to 1.0 if unsure or unneeded) +@"NREL-2p8-127_AF04_Coords.txt" NumCoords ! The number of coordinates in the airfoil shape file. Set to zero if coordinates not included. +AF04_BL.txt BL_file ! The file name including the boundary layer characteristics of the profile. Ignored if the aeroacoustic module is not called. +1 NumTabs ! Number of airfoil tables in this file. Each table must have lines for Re and Ctrl. +! ------------------------------------------------------------------------------ +! data for table 1 +! ------------------------------------------------------------------------------ +6.000000 Re ! Reynolds number in millions +0 Ctrl ! Control setting (must be 0 for current AirfoilInfo) +True InclUAdata ! Is unsteady aerodynamics data included in this table? If TRUE, then include 30 UA coefficients below this line +!........................................ +0.000000 alpha0 ! 0-lift angle of attack, depends on airfoil. +0.000000 alpha1 ! Angle of attack at f=0.7, (approximately the stall angle) for AOA>alpha0. (deg) +0.000000 alpha2 ! Angle of attack at f=0.7, (approximately the stall angle) for AOA1] +0.000000 S2 ! Constant in the f curve best-fit for AOA> alpha1; by definition it depends on the airfoil. [ignored if UAMod<>1] +0.000000 S3 ! Constant in the f curve best-fit for alpha2<=AOA< alpha0; by definition it depends on the airfoil. [ignored if UAMod<>1] +0.000000 S4 ! Constant in the f curve best-fit for AOA< alpha2; by definition it depends on the airfoil. [ignored if UAMod<>1] +0.000000 Cn1 ! Critical value of C0n at leading edge separation. It should be extracted from airfoil data at a given Mach and Reynolds number. It can be calculated from the static value of Cn at either the break in the pitching moment or the loss of chord force at the onset of stall. It is close to the condition of maximum lift of the airfoil at low Mach numbers. +0.000000 Cn2 ! As Cn1 for negative AOAs. +Default St_sh ! Strouhal's shedding frequency constant. [default = 0.19] +0.000000 Cd0 ! 2D drag coefficient value at 0-lift. +0.000000 Cm0 ! 2D pitching moment coefficient about 1/4-chord location, at 0-lift, positive if nose up. [If the aerodynamics coefficients table does not include a column for Cm, this needs to be set to 0.0] +0.000000 k0 ! Constant in the \hat(x)_cp curve best-fit; = (\hat(x)_AC-0.25). [ignored if UAMod<>1] +0.000000 k1 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k2 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k3 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k1_hat ! Constant in the expression of Cc due to leading edge vortex effects. [ignored if UAMod<>1] +Default x_cp_bar ! Constant in the expression of \hat(x)_cp^v. [ignored if UAMod<>1, default = 0.2] +Default UACutout ! Angle of attack above which unsteady aerodynamics are disabled (deg). [Specifying the string "Default" sets UACutout to 45 degrees] +Default filtCutOff ! Cut-off frequency (-3 dB corner frequency) for low-pass filtering the AoA input to UA, as well as the 1st and 2nd derivatives (Hz) [default = 20] +!........................................ +! Table of aerodynamics coefficients +200 NumAlf ! Number of data lines in the following table +! Alpha Cl Cd Cm +! (deg) (-) (-) (-) +-1.80000000000000e+02 0.00000000000000e+00 1.52890685398725e-01 0.00000000000000e+00 +-1.77000000000000e+02 1.31704479748411e-01 1.63763723652671e-01 1.19452717008645e-01 +-1.74000000000000e+02 2.64615541683425e-01 1.74744683765139e-01 2.39999774321882e-01 +-1.71000000000000e+02 3.96924138305795e-01 1.85683483417484e-01 3.60000410445527e-01 +-1.68000000000000e+02 4.83692709572010e-01 2.10410090026251e-01 3.83359490424043e-01 +-1.65000000000000e+02 5.47678400067375e-01 2.42039936419247e-01 3.58398920279377e-01 +-1.62000000000000e+02 6.11661936785840e-01 2.73684904094820e-01 3.33438064107582e-01 +-1.59000000000000e+02 6.49147890945894e-01 3.10889487497261e-01 3.13527249627107e-01 +-1.56000000000000e+02 6.33627994109589e-01 3.59203284556557e-01 3.03716295849012e-01 +-1.53000000000000e+02 6.18102771363694e-01 4.07545900233725e-01 2.93905168850931e-01 +-1.50000000000000e+02 6.02571440780362e-01 4.55925647601040e-01 2.84093898343018e-01 +-1.47000000000000e+02 5.93851743225456e-01 5.14758887292997e-01 2.87063352917468e-01 +-1.44000000000000e+02 5.85129730070885e-01 5.73263830376554e-01 2.90032783400607e-01 +-1.41000000000000e+02 5.76405140982154e-01 6.31769220410934e-01 2.93002194449487e-01 +-1.38000000000000e+02 5.62958434932229e-01 6.92274906461514e-01 2.98271914144742e-01 +-1.35000000000000e+02 5.47150816004827e-01 7.53780736462377e-01 3.04691792390807e-01 +-1.32000000000000e+02 5.31341994964165e-01 8.15287271265272e-01 3.11111734292256e-01 +-1.29000000000000e+02 5.11898674393990e-01 8.75134136992628e-01 3.17501821606841e-01 +-1.26000000000000e+02 4.85188015388141e-01 9.31661656684178e-01 3.23832218317126e-01 +-1.23000000000000e+02 4.58477182925037e-01 9.88188744534565e-01 3.30162566296010e-01 +-1.20000000000000e+02 4.31765994733252e-01 1.04471561647244e+00 3.36492889647229e-01 +-1.17000000000000e+02 3.94568156643264e-01 1.08888387091091e+00 3.40603620297433e-01 +-1.14000000000000e+02 3.57370304957649e-01 1.13305193246859e+00 3.44714328600463e-01 +-1.11000000000000e+02 3.20172552298473e-01 1.17721965661140e+00 3.48825002561235e-01 +-1.08000000000000e+02 2.77962126266291e-01 1.20912806034645e+00 3.50515840614408e-01 +-1.05000000000000e+02 2.33245372677999e-01 1.23490671052890e+00 3.50996730156169e-01 +-1.02000000000000e+02 1.88529066354869e-01 1.26068506531321e+00 3.51477592241862e-01 +-9.90000000000000e+01 1.42846269453300e-01 1.27908367222767e+00 3.50498451065250e-01 +-9.60000000000000e+01 9.52306422330625e-02 1.28272246374676e+00 3.46599247549748e-01 +-9.30000000000000e+01 4.76153787695439e-02 1.28636122746753e+00 3.42699970222382e-01 +-9.00000000000000e+01 2.97181093101284e-07 1.28999997728939e+00 3.38877476679819e-01 +-8.70000000000000e+01 -4.76153300354876e-02 1.28636123119179e+00 3.34288189245273e-01 +-8.40000000000000e+01 -9.52307753769642e-02 1.28272245357189e+00 3.29739597523247e-01 +-8.10000000000000e+01 -1.42845856965667e-01 1.27908370375002e+00 3.25207993177059e-01 +-7.80000000000000e+01 -1.88528849782130e-01 1.26068519016437e+00 3.17955441758359e-01 +-7.50000000000000e+01 -2.33245668518482e-01 1.23490653998066e+00 3.09344032062908e-01 +-7.20000000000000e+01 -2.77961909696404e-01 1.20912818519635e+00 3.00732721046221e-01 +-6.90000000000000e+01 -3.20172230052935e-01 1.17722003923687e+00 2.91121626468145e-01 +-6.60000000000000e+01 -3.57370408969930e-01 1.13305180896654e+00 2.79510882896335e-01 +-6.30000000000000e+01 -3.94568402742750e-01 1.08888357869621e+00 2.67900139324525e-01 +-6.00000000000000e+01 -4.31766171454802e-01 1.04471524249362e+00 2.56289382389432e-01 +-5.70000000000000e+01 -4.58477359643245e-01 9.88188370555741e-01 2.43119604599202e-01 +-5.40000000000000e+01 -4.85188192105633e-01 9.31661282701068e-01 2.29949776504115e-01 +-5.10000000000000e+01 -5.11898851109208e-01 8.75133763009519e-01 2.16779847798548e-01 +-4.80000000000000e+01 -5.31341959036239e-01 8.15287334218715e-01 2.03370614403917e-01 +-4.50000000000000e+01 -5.47150557766459e-01 7.53781504217852e-01 1.89841732510719e-01 +-4.20000000000000e+01 -5.62958388264277e-01 6.92274969410558e-01 1.76312695587616e-01 +-3.90000000000000e+01 -5.76405141219782e-01 6.31769168555292e-01 1.62884018923624e-01 +-3.60000000000000e+01 -5.85129736228324e-01 5.73263666791100e-01 1.49655804982024e-01 +-3.30000000000000e+01 -5.93851682613004e-01 5.14759282378343e-01 1.36427843675875e-01 +-3.00000000000000e+01 -6.02571527674987e-01 4.55925302880350e-01 1.23199622280574e-01 +-2.93939393939394e+01 -6.05709742968724e-01 4.46148292728679e-01 1.20183218217587e-01 +-2.87878787878788e+01 -6.08847690581429e-01 4.36373153786693e-01 1.17176335932680e-01 +-2.81818181818182e+01 -6.11985380005597e-01 4.26599779864539e-01 1.14168793413229e-01 +-2.75757575757576e+01 -6.15122858980615e-01 4.16827876718823e-01 1.11160516192624e-01 +-2.69696969696970e+01 -6.18260109619839e-01 4.07057465245291e-01 1.08151524224604e-01 +-2.63636363636364e+01 -6.21397122656834e-01 3.97288544820632e-01 1.05141828538283e-01 +-2.57575757575758e+01 -6.24533844014296e-01 3.87521148707597e-01 1.02131448274330e-01 +-2.51515151515151e+01 -6.27670245374249e-01 3.77755259564324e-01 9.91203848845818e-02 +-2.45454545454545e+01 -6.30806424352339e-01 3.67990641254345e-01 9.61085707127930e-02 +-2.39393939393939e+01 -6.33942376901069e-01 3.58227230091829e-01 9.30959891641372e-02 +-2.33333333333333e+01 -6.37078020453462e-01 3.48464966576383e-01 9.00826225283333e-02 +-2.27272727272727e+01 -6.40213455369502e-01 3.38703795054776e-01 8.70684539419758e-02 +-2.21212121212121e+01 -6.43348687727384e-01 3.28943663414953e-01 8.40534654418665e-02 +-2.15151515151515e+01 -6.46483666873065e-01 3.19184299164519e-01 8.10375681805418e-02 +-2.09090909090909e+01 -6.49618442068989e-01 3.09425824234104e-01 7.80207956612929e-02 +-2.03030303030303e+01 -6.52753032833882e-01 2.99668251498965e-01 7.50031458623772e-02 +-1.96969696969697e+01 -6.46281639088916e-01 2.90949411270925e-01 7.04968593518714e-02 +-1.90909090909091e+01 -6.30204218160431e-01 2.83269742867490e-01 6.45023032212650e-02 +-1.84848484848485e+01 -6.14126582290594e-01 2.75592004359402e-01 5.85074349929442e-02 +-1.78787878787879e+01 -5.98047856789765e-01 2.67915828822348e-01 5.25118142631482e-02 +-1.72727272727273e+01 -5.81967302635588e-01 2.60240916364328e-01 4.65150110129194e-02 +-1.66666666666667e+01 -5.65885606263078e-01 2.52567649498003e-01 4.05170693283586e-02 +-1.60606060606061e+01 -5.49802714208954e-01 2.44896059615267e-01 3.45176730639480e-02 +-1.54545454545455e+01 -5.33719399306242e-01 2.37226574370814e-01 2.85166866132808e-02 +-1.48484848484848e+01 -5.17634634029050e-01 2.29558765259197e-01 2.25131018007247e-02 +-1.42424242424242e+01 -5.01547801579493e-01 2.21892402675115e-01 1.65057329856289e-02 +-1.36363636363636e+01 -4.85463674091492e-01 2.14231747747893e-01 1.04934903363307e-02 +-1.30303030303030e+01 -4.69370079236432e-01 2.06565470271126e-01 4.47314506258597e-03 +-1.24242424242424e+01 -4.53283193318206e-01 1.98908867060531e-01 -1.54613211877309e-03 +-1.18181818181818e+01 -4.37187366788929e-01 1.91247369015575e-01 -7.53424241146752e-03 +-1.12121212121212e+01 -4.21093768204950e-01 1.83591167142366e-01 -1.35218680172613e-02 +-1.06060606060606e+01 -4.04998617109735e-01 1.75937905154481e-01 -1.95099338612331e-02 +-1.00000000000000e+01 -3.88896565106125e-01 1.68281357120578e-01 -2.54976171334784e-02 +-9.39393939393939e+00 -3.56980581536747e-01 1.60570608546530e-01 -2.45787021969936e-02 +-8.78787878787879e+00 -3.25052844156906e-01 1.52859809151608e-01 -2.36654666080170e-02 +-8.18181818181818e+00 -2.93123808227596e-01 1.45152920413788e-01 -2.27443554637733e-02 +-7.57575757575758e+00 -2.61189540733289e-01 1.37458302486576e-01 -2.18232254306519e-02 +-6.96969696969697e+00 -2.29253315550365e-01 1.29770338259547e-01 -2.09121948405043e-02 +-6.36363636363636e+00 -1.97299114478799e-01 1.22078681072535e-01 -1.99910067472643e-02 +-5.75757575757576e+00 -1.65337094409309e-01 1.14401642642313e-01 -1.90688307982063e-02 +-5.15151515151515e+00 -1.33363372258401e-01 1.06731125985166e-01 -1.81553134789971e-02 +-4.54545454545454e+00 -1.01365853608070e-01 9.90577635911853e-02 -1.72377886839538e-02 +-3.93939393939394e+00 -6.93567841681647e-02 9.14006376859695e-02 -1.63172897943185e-02 +-3.33333333333333e+00 -3.31807555093951e-02 8.46570826009648e-02 -1.57731499131537e-02 +-2.72727272727273e+00 2.39727377628819e-02 8.25273948895898e-02 -1.71381638240559e-02 +-2.12121212121212e+00 9.32486327068270e-02 8.31141750981614e-02 -1.96272564550678e-02 +-1.51515151515152e+00 1.62528583105757e-01 8.37008175454388e-02 -2.21076923365064e-02 +-9.09090909090912e-01 2.31797235397626e-01 8.42859193789413e-02 -2.45940451844470e-02 +-3.03030303030302e-01 3.01068246865505e-01 8.48656437169153e-02 -2.70868281606804e-02 + 3.03030303030302e-01 3.70338484450812e-01 8.54523328928443e-02 -2.95712433598367e-02 + 9.09090909090912e-01 4.39610300212106e-01 8.60391036829737e-02 -3.20559148731745e-02 + 1.51515151515152e+00 5.09192579530866e-01 8.66138848674114e-02 -3.45449324288621e-02 + 2.12121212121212e+00 5.86406064228343e-01 8.66581954835795e-02 -3.72379475609113e-02 + 2.72727272727273e+00 6.67209757832241e-01 8.64425327187755e-02 -4.00378706815080e-02 + 3.33333333333333e+00 7.48006310769884e-01 8.62268646743108e-02 -4.28376526659724e-02 + 3.93939393939394e+00 8.28814559558240e-01 8.60123335176102e-02 -4.56376672559721e-02 + 4.54545454545455e+00 9.09607713918266e-01 8.57976670724705e-02 -4.84274348252293e-02 + 5.15151515151515e+00 9.90415750809011e-01 8.55913123524140e-02 -5.12274574370195e-02 + 5.75757575757576e+00 1.06840447148798e+00 8.53816156813169e-02 -5.42125455584405e-02 + 6.36363636363637e+00 1.14160400255878e+00 8.51849910150180e-02 -5.75066351634233e-02 + 6.96969696969697e+00 1.21413721717018e+00 8.49944037839137e-02 -6.08487619763315e-02 + 7.57575757575757e+00 1.28664609286845e+00 8.48025295082906e-02 -6.41936917237977e-02 + 8.18181818181818e+00 1.35907367282053e+00 8.46074089108589e-02 -6.75395926025836e-02 + 8.78787878787879e+00 1.42498875451348e+00 8.48939582739108e-02 -7.11385484353892e-02 + 9.39393939393939e+00 1.47790044040096e+00 8.61562125019175e-02 -7.52537462367865e-02 + 1.00000000000000e+01 1.52761951021426e+00 8.76527806305783e-02 -7.94958935415669e-02 + 1.06060606060606e+01 1.21037111221097e+00 1.08368637158632e-01 -7.47780360782507e-02 + 1.12121212121212e+01 1.06745252059869e+00 1.30650270554887e-01 -4.13744293556483e-02 + 1.18181818181818e+01 1.04047682231151e+00 1.48602204458626e-01 -3.87322662567038e-02 + 1.24242424242424e+01 1.02050139325215e+00 1.65510670067403e-01 -4.07401587716326e-02 + 1.30303030303030e+01 1.00956882423978e+00 1.81609086020050e-01 -4.27814866733380e-02 + 1.36363636363636e+01 1.00743778578338e+00 1.96445539032532e-01 -4.48202992152467e-02 + 1.42424242424242e+01 1.00757475615447e+00 2.09842058498476e-01 -4.68758763258071e-02 + 1.48484848484848e+01 1.00899715128062e+00 2.22621760789065e-01 -4.89826947132140e-02 + 1.54545454545455e+01 1.01148957933609e+00 2.34179209308161e-01 -5.10542451445077e-02 + 1.60606060606061e+01 1.01288900592554e+00 2.45010338785109e-01 -5.35062027787723e-02 + 1.66666666666667e+01 1.00195252813289e+00 2.52941797110189e-01 -5.94879954798757e-02 + 1.72727272727273e+01 9.90372353173637e-01 2.60712604214289e-01 -6.56606862514200e-02 + 1.78787878787879e+01 9.78006308087524e-01 2.68286875927460e-01 -7.20666332697287e-02 + 1.84848484848485e+01 9.65644506690629e-01 2.75856403296140e-01 -7.84749075877025e-02 + 1.90909090909091e+01 9.53284332352213e-01 2.83426080329155e-01 -8.48813171286689e-02 + 1.96969696969697e+01 9.40924882807228e-01 2.91001781071828e-01 -9.12808153392477e-02 + 2.03030303030303e+01 9.32508485341658e-01 2.99668251498965e-01 -9.63197520692682e-02 + 2.09090909090909e+01 9.28035612370247e-01 3.09425824234104e-01 -9.99987465351088e-02 + 2.15151515151515e+01 9.23562474293211e-01 3.19184299164519e-01 -1.03676821203003e-01 + 2.21212121212121e+01 9.19089043051198e-01 3.28943663414953e-01 -1.07353977654978e-01 + 2.27272727272727e+01 9.14615247866511e-01 3.38703795054776e-01 -1.11030178126034e-01 + 2.33333333333333e+01 9.10141161527127e-01 3.48464966576383e-01 -1.14705513496165e-01 + 2.39393939393939e+01 9.05666775287466e-01 3.58227230091829e-01 -1.18380002566973e-01 + 2.45454545454545e+01 9.01191945397226e-01 3.67990641254345e-01 -1.22053668013310e-01 + 2.51515151515151e+01 8.96716790059191e-01 3.77755259564324e-01 -1.25726522238022e-01 + 2.57575757575758e+01 8.92241315022274e-01 3.87521148707597e-01 -1.29398582102913e-01 + 2.63636363636364e+01 8.87765380758913e-01 3.97288544820632e-01 -1.33069928789038e-01 + 2.69696969696970e+01 8.83289027675016e-01 4.07057465245291e-01 -1.36740556769150e-01 + 2.75757575757576e+01 8.78812332951360e-01 4.16827876718823e-01 -1.40410439162852e-01 + 2.81818181818182e+01 8.74335309658910e-01 4.26599779864539e-01 -1.44079560303650e-01 + 2.87878787878788e+01 8.69857983172985e-01 4.36373153786694e-01 -1.47747893479490e-01 + 2.93939393939394e+01 8.65380285398246e-01 4.46148292728679e-01 -1.51415526599333e-01 + 3.00000000000000e+01 8.60902202671727e-01 4.55925302880350e-01 -1.55082474171227e-01 + 3.30000000000000e+01 8.48397959434636e-01 5.14759282378343e-01 -1.68663399184894e-01 + 3.60000000000000e+01 8.35890707575628e-01 5.73263666791100e-01 -1.82298027595826e-01 + 3.90000000000000e+01 8.23379662232036e-01 6.31769168555292e-01 -1.95945868274559e-01 + 4.20000000000000e+01 8.04154954731604e-01 6.92274969410558e-01 -2.08554266597334e-01 + 4.50000000000000e+01 7.81573458480718e-01 7.53781504217852e-01 -2.20643060705334e-01 + 4.80000000000000e+01 7.58990915560083e-01 8.15287334218715e-01 -2.32731716287242e-01 + 5.10000000000000e+01 7.31215839592101e-01 8.75133763009519e-01 -2.44320755354886e-01 + 5.40000000000000e+01 6.93057699659601e-01 9.31661282701068e-01 -2.54910529274792e-01 + 5.70000000000000e+01 6.54899314951571e-01 9.88188370555741e-01 -2.65500222295077e-01 + 6.00000000000000e+01 6.16740425757725e-01 1.04471524249362e+00 -2.76089874865860e-01 + 6.30000000000000e+01 5.63629556606820e-01 1.08888357869621e+00 -2.84820525032635e-01 + 6.60000000000000e+01 5.10518346428343e-01 1.13305180896654e+00 -2.93551159264809e-01 + 6.90000000000000e+01 4.57406844501805e-01 1.17722003923687e+00 -3.02281793496983e-01 + 7.20000000000000e+01 3.97127599293486e-01 1.20912818519635e+00 -3.09472835540815e-01 + 7.50000000000000e+01 3.33264710335960e-01 1.23490653998066e+00 -3.15894113007981e-01 + 7.80000000000000e+01 2.69400999928860e-01 1.26068519016437e+00 -3.22315464057870e-01 + 8.10000000000000e+01 2.04142652815547e-01 1.27908370375002e+00 -3.27816939705399e-01 + 8.40000000000000e+01 1.36095393510895e-01 1.28272245357189e+00 -3.31478728044814e-01 + 8.70000000000000e+01 6.80476143629091e-02 1.28636123119179e+00 -3.35157787608892e-01 + 9.00000000000000e+01 -2.97181093302924e-07 1.28999997728939e+00 -3.38875766435868e-01 + 9.30000000000000e+01 -4.76153787695439e-02 1.28636122746753e+00 -3.42699882733940e-01 + 9.60000000000000e+01 -9.52306422330627e-02 1.28272246374676e+00 -3.46597404225314e-01 + 9.90000000000000e+01 -1.42846269453301e-01 1.27908367222767e+00 -3.50494955491782e-01 + 1.02000000000000e+02 -1.88529066354869e-01 1.26068506531321e+00 -3.51472552278717e-01 + 1.05000000000000e+02 -2.33245372677999e-01 1.23490671052890e+00 -3.50990203444848e-01 + 1.08000000000000e+02 -2.77962126266291e-01 1.20912806034645e+00 -3.50507849083669e-01 + 1.11000000000000e+02 -3.20172552298473e-01 1.17721965661140e+00 -3.48815656358806e-01 + 1.14000000000000e+02 -3.57370304957649e-01 1.13305193246859e+00 -3.44703823754748e-01 + 1.17000000000000e+02 -3.94568156643264e-01 1.08888387091091e+00 -3.40591959738759e-01 + 1.20000000000000e+02 -4.31765994733252e-01 1.04471561647244e+00 -3.36480075676600e-01 + 1.23000000000000e+02 -4.58477182925037e-01 9.88188744534564e-01 -3.30149032834181e-01 + 1.26000000000000e+02 -4.85188015388141e-01 9.31661656684178e-01 -3.23817965809434e-01 + 1.29000000000000e+02 -5.11898674393990e-01 8.75134136992627e-01 -3.17486850418223e-01 + 1.32000000000000e+02 -5.31341994964165e-01 8.15287271265271e-01 -3.11096424528303e-01 + 1.35000000000000e+02 -5.47150816004827e-01 7.53780736462377e-01 -3.04676343460043e-01 + 1.38000000000000e+02 -5.62958434932230e-01 6.92274906461514e-01 -2.98256335959350e-01 + 1.41000000000000e+02 -5.76405140982154e-01 6.31769220410933e-01 -2.92986730247466e-01 + 1.44000000000000e+02 -5.85129730070885e-01 5.73263830376554e-01 -2.90017937448097e-01 + 1.47000000000000e+02 -5.93851743225456e-01 5.14758887292997e-01 -2.87049167328765e-01 + 1.50000000000000e+02 -6.02571440780362e-01 4.55925647601039e-01 -2.84080408549046e-01 + 1.53000000000000e+02 -6.18102771363694e-01 4.07545900233725e-01 -2.93893652756478e-01 + 1.56000000000000e+02 -6.33627994109589e-01 3.59203284556557e-01 -3.03706889264038e-01 + 1.59000000000000e+02 -6.49147890945894e-01 3.10889487497261e-01 -3.13520050804901e-01 + 1.62000000000000e+02 -6.11662753189298e-01 2.73684904094820e-01 -3.53432900875577e-01 + 1.65000000000000e+02 -5.47687466921444e-01 2.42039936419247e-01 -4.08395849769896e-01 + 1.68000000000000e+02 -4.83692709572010e-01 2.10410090026251e-01 -4.63358168842291e-01 + 1.71000000000000e+02 -3.96924138305795e-01 1.85683483417484e-01 -4.50000513056908e-01 + 1.74000000000000e+02 -2.64615541683425e-01 1.74744683765139e-01 -2.99999717902353e-01 + 1.77000000000000e+02 -1.31704479748411e-01 1.63763723652671e-01 -1.49315896260807e-01 + 1.80000000000000e+02 0.00000000000000e+00 1.52890685398725e-01 0.00000000000000e+00 diff --git a/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_05.dat b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_05.dat new file mode 100644 index 00000000..28ca6bdb --- /dev/null +++ b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_05.dat @@ -0,0 +1,254 @@ +! ------------ AirfoilInfo v1.01.x Input File ---------------------------------- +! AeroElasticSE FAST driver +! line +! line +! ------------------------------------------------------------------------------ +DEFAULT InterpOrd ! Interpolation order to use for quasi-steady table lookup {1=linear; 3=cubic spline; "default"} [default=3] +1 NonDimArea ! The non-dimensional area of the airfoil (area/chord^2) (set to 1.0 if unsure or unneeded) +@"NREL-2p8-127_AF05_Coords.txt" NumCoords ! The number of coordinates in the airfoil shape file. Set to zero if coordinates not included. +AF05_BL.txt BL_file ! The file name including the boundary layer characteristics of the profile. Ignored if the aeroacoustic module is not called. +1 NumTabs ! Number of airfoil tables in this file. Each table must have lines for Re and Ctrl. +! ------------------------------------------------------------------------------ +! data for table 1 +! ------------------------------------------------------------------------------ +6.000000 Re ! Reynolds number in millions +0 Ctrl ! Control setting (must be 0 for current AirfoilInfo) +True InclUAdata ! Is unsteady aerodynamics data included in this table? If TRUE, then include 30 UA coefficients below this line +!........................................ +-2.550758 alpha0 ! 0-lift angle of attack, depends on airfoil. +11.972792 alpha1 ! Angle of attack at f=0.7, (approximately the stall angle) for AOA>alpha0. (deg) +-3.390653 alpha2 ! Angle of attack at f=0.7, (approximately the stall angle) for AOA1] +0.000000 S2 ! Constant in the f curve best-fit for AOA> alpha1; by definition it depends on the airfoil. [ignored if UAMod<>1] +0.000000 S3 ! Constant in the f curve best-fit for alpha2<=AOA< alpha0; by definition it depends on the airfoil. [ignored if UAMod<>1] +0.000000 S4 ! Constant in the f curve best-fit for AOA< alpha2; by definition it depends on the airfoil. [ignored if UAMod<>1] +1.577585 Cn1 ! Critical value of C0n at leading edge separation. It should be extracted from airfoil data at a given Mach and Reynolds number. It can be calculated from the static value of Cn at either the break in the pitching moment or the loss of chord force at the onset of stall. It is close to the condition of maximum lift of the airfoil at low Mach numbers. +-0.698181 Cn2 ! As Cn1 for negative AOAs. +Default St_sh ! Strouhal's shedding frequency constant. [default = 0.19] +0.047738 Cd0 ! 2D drag coefficient value at 0-lift. +-0.017884 Cm0 ! 2D pitching moment coefficient about 1/4-chord location, at 0-lift, positive if nose up. [If the aerodynamics coefficients table does not include a column for Cm, this needs to be set to 0.0] +0.000000 k0 ! Constant in the \hat(x)_cp curve best-fit; = (\hat(x)_AC-0.25). [ignored if UAMod<>1] +0.000000 k1 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k2 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k3 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k1_hat ! Constant in the expression of Cc due to leading edge vortex effects. [ignored if UAMod<>1] +Default x_cp_bar ! Constant in the expression of \hat(x)_cp^v. [ignored if UAMod<>1, default = 0.2] +Default UACutout ! Angle of attack above which unsteady aerodynamics are disabled (deg). [Specifying the string "Default" sets UACutout to 45 degrees] +Default filtCutOff ! Cut-off frequency (-3 dB corner frequency) for low-pass filtering the AoA input to UA, as well as the 1st and 2nd derivatives (Hz) [default = 20] +!........................................ +! Table of aerodynamics coefficients +200 NumAlf ! Number of data lines in the following table +! Alpha Cl Cd Cm +! (deg) (-) (-) (-) +-1.80000000000000e+02 0.00000000000000e+00 5.30927947138125e-02 0.00000000000000e+00 +-1.77000000000000e+02 1.43244990746609e-01 5.69851238094485e-02 1.19452717008645e-01 +-1.74000000000000e+02 2.87802289582396e-01 6.09656699428337e-02 2.39999774321882e-01 +-1.71000000000000e+02 4.31704332512692e-01 6.49763275693468e-02 3.60000410445527e-01 +-1.68000000000000e+02 5.23499707930916e-01 8.50931388592694e-02 3.82638556679456e-01 +-1.65000000000000e+02 5.83384432077198e-01 1.13322899941877e-01 3.56596594332269e-01 +-1.62000000000000e+02 6.43053795138515e-01 1.41646320077994e-01 3.30554333566108e-01 +-1.59000000000000e+02 6.78451069490567e-01 1.78095963395456e-01 3.09470086171798e-01 +-1.56000000000000e+02 6.58893043506451e-01 2.30735614552766e-01 2.98273249714432e-01 +-1.53000000000000e+02 6.39361023231318e-01 2.83555584049004e-01 2.87022407877401e-01 +-1.50000000000000e+02 6.19863301663139e-01 3.36609283159026e-01 2.75697034623494e-01 +-1.47000000000000e+02 6.09009472068249e-01 4.01283048649868e-01 2.78062585683198e-01 +-1.44000000000000e+02 5.98171151079133e-01 4.63879476339314e-01 2.80408703728939e-01 +-1.41000000000000e+02 5.87351226752077e-01 5.26476382236643e-01 2.82731729240854e-01 +-1.38000000000000e+02 5.72330730353409e-01 5.91679697265480e-01 2.87760801862453e-01 +-1.35000000000000e+02 5.55209533057542e-01 6.58186211572688e-01 2.94147772624518e-01 +-1.32000000000000e+02 5.38097371011921e-01 7.24693487985318e-01 3.00529378672850e-01 +-1.29000000000000e+02 5.17511317766740e-01 7.89812599804369e-01 3.07049734636571e-01 +-1.26000000000000e+02 4.89961725795433e-01 8.52155375838165e-01 3.13857858392341e-01 +-1.23000000000000e+02 4.62416171597766e-01 9.14497675605232e-01 3.20665726887359e-01 +-1.20000000000000e+02 4.34875524108853e-01 9.76839737247837e-01 3.27473323520141e-01 +-1.17000000000000e+02 3.97141252418688e-01 1.02744833950730e+00 3.32448774893895e-01 +-1.14000000000000e+02 3.59408610235184e-01 1.07805672550782e+00 3.37422939191108e-01 +-1.11000000000000e+02 3.21678367338784e-01 1.12866472489365e+00 3.42395452802871e-01 +-1.08000000000000e+02 2.79088060479540e-01 1.16729127063990e+00 3.45105968655180e-01 +-1.05000000000000e+02 2.34067147859934e-01 1.19992699833297e+00 3.46678811680518e-01 +-1.02000000000000e+02 1.89047548243342e-01 1.23256235205249e+00 3.48239595384036e-01 +-9.90000000000000e+01 1.43131704344168e-01 1.25788743783553e+00 3.48340383273987e-01 +-9.60000000000000e+01 9.54209316759962e-02 1.26859167109942e+00 3.45525190946857e-01 +-9.30000000000000e+01 4.77105235832516e-02 1.27929582258901e+00 3.42653176080977e-01 +-9.00000000000000e+01 2.97774918887840e-07 1.28999993319219e+00 3.41171513503408e-01 +-8.70000000000000e+01 -4.77104747518152e-02 1.27929583354468e+00 3.34817796856754e-01 +-8.40000000000000e+01 -9.54210650859458e-02 1.26859164116800e+00 3.29193185522394e-01 +-8.10000000000000e+01 -1.43131291032302e-01 1.25788753056483e+00 3.23300885206925e-01 +-7.80000000000000e+01 -1.89047330204813e-01 1.23256251011385e+00 3.14255422250019e-01 +-7.50000000000000e+01 -2.34067445710414e-01 1.19992678241918e+00 3.04545364776568e-01 +-7.20000000000000e+01 -2.79087842435176e-01 1.16729142869966e+00 2.94835418571366e-01 +-6.90000000000000e+01 -3.21678040492873e-01 1.12866516331131e+00 2.84308787573372e-01 +-6.60000000000000e+01 -3.59408715740005e-01 1.07805658399745e+00 2.72148720112555e-01 +-6.30000000000000e+01 -3.97141502062332e-01 1.02744800468359e+00 2.59988652651739e-01 +-6.00000000000000e+01 -4.34875706297759e-01 9.76839324796023e-01 2.47828577510345e-01 +-5.70000000000000e+01 -4.62416353822370e-01 9.14497263153418e-01 2.34772451636168e-01 +-5.40000000000000e+01 -4.89961908050355e-01 8.52154963381625e-01 2.21716275891253e-01 +-5.10000000000000e+01 -5.17511500044336e-01 7.89812187347829e-01 2.08660000404101e-01 +-4.80000000000000e+01 -5.38086518717761e-01 7.24693556057142e-01 1.95844288146640e-01 +-4.50000000000000e+01 -5.55175897952576e-01 6.58187041749934e-01 1.83148853637833e-01 +-4.20000000000000e+01 -5.72313983328070e-01 5.91679765332548e-01 1.70453273649745e-01 +-3.90000000000000e+01 -5.87347123075626e-01 5.26476326754529e-01 1.58085355571838e-01 +-3.60000000000000e+01 -5.98161176797901e-01 4.63879301313675e-01 1.46372520769741e-01 +-3.30000000000000e+01 -6.09008454841632e-01 4.01283471365111e-01 1.34659909662040e-01 +-3.00000000000000e+01 -6.19863411384585e-01 3.36608903265194e-01 1.22947070166372e-01 +-2.93939393939394e+01 -6.23846756639890e-01 3.25869060451884e-01 1.20313440786885e-01 +-2.87878787878788e+01 -6.27838778995726e-01 3.15141051259396e-01 1.17614452112613e-01 +-2.81818181818182e+01 -6.31839641876821e-01 3.04424204137947e-01 1.14912699050432e-01 +-2.75757575757576e+01 -6.35836270597920e-01 2.93717682812228e-01 1.12207880384010e-01 +-2.69696969696970e+01 -6.39833911454526e-01 2.83021034017517e-01 1.09499798315900e-01 +-2.63636363636364e+01 -6.43837810956875e-01 2.72333814688203e-01 1.06788280516258e-01 +-2.57575757575758e+01 -6.47833727204863e-01 2.61655649661799e-01 1.04073092351849e-01 +-2.51515151515151e+01 -6.51811878050700e-01 2.50986136645096e-01 1.01353965974111e-01 +-2.45454545454545e+01 -6.55792402610431e-01 2.40324660439802e-01 9.86307582663180e-02 +-2.39393939393939e+01 -6.59769329462643e-01 2.29670818293622e-01 9.59032541531653e-02 +-2.33333333333333e+01 -6.63693753618085e-01 2.19024233923185e-01 9.31708867916564e-02 +-2.27272727272727e+01 -6.67617282194909e-01 2.08384555374766e-01 9.04338238763716e-02 +-2.21212121212121e+01 -6.71539925846911e-01 1.97751453089189e-01 8.76919095450044e-02 +-2.15151515151515e+01 -6.75391364530441e-01 1.87124374677434e-01 8.49442500011879e-02 +-2.09090909090909e+01 -6.79225055311131e-01 1.76503213160456e-01 8.21911480032724e-02 +-2.03030303030303e+01 -6.83058586454578e-01 1.65887757170172e-01 7.94326338508051e-02 +-1.96969696969697e+01 -6.77179366626525e-01 1.57936143099498e-01 7.50259515023840e-02 +-1.90909090909091e+01 -6.61588812956316e-01 1.52651370129665e-01 6.89730817674315e-02 +-1.84848484848485e+01 -6.45998974297365e-01 1.47376694007528e-01 6.29169683694159e-02 +-1.78787878787879e+01 -6.30407947197086e-01 1.42112026219737e-01 5.68565081215708e-02 +-1.72727272727273e+01 -6.14814081267429e-01 1.36857330079429e-01 5.07903974899203e-02 +-1.66666666666667e+01 -5.99217230522637e-01 1.31613040740835e-01 4.47175106901892e-02 +-1.60606060606061e+01 -5.83616581541072e-01 1.26379356727811e-01 3.86359166779271e-02 +-1.54545454545455e+01 -5.68012174444683e-01 1.21156750685727e-01 3.25431989869031e-02 +-1.48484848484848e+01 -5.52402341156080e-01 1.15945116537827e-01 2.64350024320926e-02 +-1.42424242424242e+01 -5.36785838629193e-01 1.10744490215081e-01 2.03050549247369e-02 +-1.36363636363636e+01 -5.21164946554597e-01 1.05556831744732e-01 1.41441663106941e-02 +-1.30303030303030e+01 -5.05532268418259e-01 1.00377944456418e-01 7.93532744678689e-03 +-1.24242424242424e+01 -4.89896163495659e-01 9.52139797533199e-02 1.73252780437516e-03 +-1.18181818181818e+01 -4.74247226456870e-01 9.00595351969602e-02 -4.26939729837575e-03 +-1.12121212121212e+01 -4.58591426990099e-01 8.49188835204796e-02 -1.02684318086498e-02 +-1.06060606060606e+01 -4.42925008308680e-01 7.97910287467256e-02 -1.62647493676347e-02 +-1.00000000000000e+01 -4.27245419806289e-01 7.46743204034461e-02 -2.22564315863916e-02 +-9.39393939393939e+00 -3.94450071012984e-01 7.15761244145179e-02 -2.16020013916610e-02 +-8.78787878787879e+00 -3.61709763635419e-01 6.85053420395361e-02 -2.09365369698145e-02 +-8.18181818181818e+00 -3.29004774877055e-01 6.54609123314964e-02 -2.02303412864217e-02 +-7.57575757575758e+00 -2.96719457325792e-01 6.35194996651035e-02 -1.95537154607737e-02 +-6.96969696969697e+00 -2.64607645997063e-01 6.22646687778469e-02 -1.89056408818654e-02 +-6.36363636363636e+00 -2.32580527152297e-01 6.06079991204510e-02 -1.81689497551464e-02 +-5.75757575757576e+00 -2.00633174166183e-01 5.86072762325081e-02 -1.69119223172787e-02 +-5.15151515151515e+00 -1.68866114677660e-01 5.62255812194239e-02 -1.65526782796882e-02 +-4.54545454545454e+00 -1.37461932635248e-01 5.36929428917852e-02 -1.61977017355170e-02 +-3.93939393939394e+00 -1.06758451318221e-01 5.10791375965595e-02 -1.58364616756710e-02 +-3.33333333333333e+00 -7.62685548653199e-02 4.84672024181126e-02 -1.56131840112851e-02 +-2.72727272727273e+00 -2.30465602521035e-02 4.76318232912975e-02 -1.71370109715407e-02 +-2.12121212121212e+00 5.60835187551921e-02 4.79951799533595e-02 -1.97007210491168e-02 +-1.51515151515152e+00 1.33973262951602e-01 4.82654676882718e-02 -2.19439082938550e-02 +-9.09090909090912e-01 2.11028087723967e-01 4.85254853369285e-02 -2.42243917401695e-02 +-3.03030303030302e-01 2.87261368924859e-01 4.88198593001318e-02 -2.64441305820696e-02 + 3.03030303030302e-01 3.62683470094018e-01 4.90303436956597e-02 -2.86606885206110e-02 + 9.09090909090912e-01 4.37199562095510e-01 4.92283898912697e-02 -3.09291436006373e-02 + 1.51515151515152e+00 5.13610653178412e-01 4.93813249350217e-02 -3.31627344995039e-02 + 2.12121212121212e+00 5.93819523225117e-01 4.94346635643130e-02 -3.56399268252573e-02 + 2.72727272727273e+00 6.74386743494600e-01 4.93129308208056e-02 -3.83078247443938e-02 + 3.33333333333333e+00 7.54945044010580e-01 4.91755144944948e-02 -4.10234230183793e-02 + 3.93939393939394e+00 8.35509088091445e-01 4.91056624497743e-02 -4.37392469039279e-02 + 4.54545454545455e+00 9.16064316845785e-01 4.89398733238135e-02 -4.63880027667541e-02 + 5.15151515151515e+00 9.96625787614405e-01 4.87886086060796e-02 -4.91038344328945e-02 + 5.75757575757576e+00 1.07656301546343e+00 4.86681788543757e-02 -5.18876441202431e-02 + 6.36363636363637e+00 1.15542943443492e+00 4.84580270970572e-02 -5.47393555777829e-02 + 6.96969696969697e+00 1.23410923793262e+00 4.83167054847680e-02 -5.76374031069491e-02 + 7.57575757575757e+00 1.31245193672788e+00 4.80332030687119e-02 -6.06302767966048e-02 + 8.18181818181818e+00 1.38759943761324e+00 4.77434147182263e-02 -6.42287509236700e-02 + 8.78787878787879e+00 1.45873318731176e+00 4.76208649517908e-02 -6.80810236266958e-02 + 9.39393939393939e+00 1.52667302662998e+00 4.74125681417122e-02 -7.21235138863210e-02 + 1.00000000000000e+01 1.59364179899341e+00 4.69592426109806e-02 -7.62125968301386e-02 + 1.06060606060606e+01 1.53266180129203e+00 5.17795621500542e-02 -7.64122517246057e-02 + 1.12121212121212e+01 1.50662714460046e+00 5.81185911119093e-02 -6.22473445320763e-02 + 1.18181818181818e+01 1.52196088499542e+00 6.47040938908333e-02 -6.38501972207365e-02 + 1.24242424242424e+01 1.06125737520671e+00 7.27011070641862e-02 -5.06632430902114e-02 + 1.30303030303030e+01 9.86623647198398e-01 7.99581638241099e-02 -5.02161054006635e-02 + 1.36363636363636e+01 9.95413895615537e-01 8.64252489342137e-02 -5.25392814360008e-02 + 1.42424242424242e+01 1.00924723452713e+00 9.21833608579365e-02 -5.50345279620461e-02 + 1.48484848484848e+01 1.02661321711400e+00 9.75776888323979e-02 -5.76003393676277e-02 + 1.54545454545455e+01 1.05138532349845e+00 1.02292972150637e-01 -6.01726803278759e-02 + 1.60606060606061e+01 1.07964132412529e+00 1.07181768900225e-01 -6.30677892912717e-02 + 1.66666666666667e+01 1.06432412273203e+00 1.15493817389282e-01 -6.88775293421371e-02 + 1.72727272727273e+01 1.04867809191367e+00 1.23747525118351e-01 -7.47996579324639e-02 + 1.78787878787879e+01 1.03269240545081e+00 1.31928776633279e-01 -8.08557118437613e-02 + 1.84848484848485e+01 1.01640007994456e+00 1.40110699660449e-01 -8.69627224737571e-02 + 1.90909090909091e+01 1.00063944099394e+00 1.48295486938811e-01 -9.30638334648102e-02 + 1.96969696969697e+01 9.85938420719178e-01 1.56485775705632e-01 -9.91101057357213e-02 + 2.03030303030303e+01 9.75860062476632e-01 1.65887757170172e-01 -1.03774527782874e-01 + 2.09090909090909e+01 9.70385523569138e-01 1.76503213160456e-01 -1.07066137517572e-01 + 2.15151515151515e+01 9.64910741287637e-01 1.87124374677434e-01 -1.10360436221179e-01 + 2.21212121212121e+01 9.59410539374443e-01 1.97751453089189e-01 -1.13658562031653e-01 + 2.27272727272727e+01 9.53808409121640e-01 2.08384555374766e-01 -1.16963451063534e-01 + 2.33333333333333e+01 9.48205009566551e-01 2.19024233923185e-01 -1.20268180130586e-01 + 2.39393939393939e+01 9.42600325574261e-01 2.29670818293622e-01 -1.23572752917098e-01 + 2.45454545454545e+01 9.36920460742092e-01 2.40324660439802e-01 -1.26879595000076e-01 + 2.51515151515151e+01 9.31235454127077e-01 2.50986136645096e-01 -1.30185781900636e-01 + 2.57575757575758e+01 9.25553857527951e-01 2.61655649661799e-01 -1.33491111669471e-01 + 2.63636363636364e+01 9.19846852026574e-01 2.72333814688203e-01 -1.36796376983463e-01 + 2.69696969696970e+01 9.14128444983841e-01 2.83021034017517e-01 -1.40101150711351e-01 + 2.75757575757576e+01 9.08419019689508e-01 2.93717682812228e-01 -1.43405050790712e-01 + 2.81818181818182e+01 9.02711061316296e-01 3.04424204137947e-01 -1.46708310397499e-01 + 2.87878787878788e+01 8.96997060076054e-01 3.15141051259396e-01 -1.50011073235030e-01 + 2.93939393939394e+01 8.91295747727463e-01 3.25869060451884e-01 -1.53313276996418e-01 + 3.00000000000000e+01 8.85606890090034e-01 3.36608903265194e-01 -1.56615109400843e-01 + 3.30000000000000e+01 8.70046621612218e-01 4.01283471365112e-01 -1.68896662349608e-01 + 3.60000000000000e+01 8.54497762357662e-01 4.63879301313675e-01 -1.80807931817999e-01 + 3.90000000000000e+01 8.38996891272377e-01 5.26476326754529e-01 -1.92637317529328e-01 + 4.20000000000000e+01 8.17522301694096e-01 5.91679765332548e-01 -2.03957651916238e-01 + 4.50000000000000e+01 7.93066546402043e-01 6.58187041749934e-01 -2.15023567058536e-01 + 4.80000000000000e+01 7.68679932146205e-01 7.24693556057142e-01 -2.26089355395965e-01 + 5.10000000000000e+01 7.39303717872206e-01 7.89812187347829e-01 -2.36920708472379e-01 + 5.40000000000000e+01 6.99944452555873e-01 8.52154963381625e-01 -2.47283175955455e-01 + 5.70000000000000e+01 6.60590914392139e-01 9.14497263153418e-01 -2.57645564275396e-01 + 6.00000000000000e+01 6.21244336348351e-01 9.76839324796023e-01 -2.68007913014073e-01 + 6.30000000000000e+01 5.67342239658887e-01 1.02744800468359e+00 -2.77212112250156e-01 + 6.60000000000000e+01 5.13442407001332e-01 1.07805658399745e+00 -2.86416301559060e-01 + 6.90000000000000e+01 4.59545925192930e-01 1.12866516331131e+00 -2.95620490867964e-01 + 7.20000000000000e+01 3.98720080252567e-01 1.16729142869966e+00 -3.03676557424305e-01 + 7.50000000000000e+01 3.34428749413491e-01 1.19992678241918e+00 -3.11158586107968e-01 + 7.80000000000000e+01 2.70137761942138e-01 1.23256251011385e+00 -3.18640700529719e-01 + 8.10000000000000e+01 2.04550434150108e-01 1.25788753056483e+00 -3.25335532450249e-01 + 8.40000000000000e+01 1.36367248239496e-01 1.26859164116800e+00 -3.30455853712348e-01 + 8.70000000000000e+01 6.81835415395329e-02 1.27929583354468e+00 -3.35467708982822e-01 + 9.00000000000000e+01 -2.97774919089685e-07 1.28999993319219e+00 -3.40233119894460e-01 + 9.30000000000000e+01 -4.77105235832516e-02 1.27929582258901e+00 -3.42605172055241e-01 + 9.60000000000000e+01 -9.54209316759964e-02 1.26859167109942e+00 -3.44513777418663e-01 + 9.90000000000000e+01 -1.43131704344168e-01 1.25788743783553e+00 -3.46422397362864e-01 + 1.02000000000000e+02 -1.89047548243342e-01 1.23256235205249e+00 -3.45474218431042e-01 + 1.05000000000000e+02 -2.34067147859934e-01 1.19992699833297e+00 -3.43097670996285e-01 + 1.08000000000000e+02 -2.79088060479540e-01 1.16729127063990e+00 -3.40721096328304e-01 + 1.11000000000000e+02 -3.21678367338785e-01 1.12866472489365e+00 -3.37267285780153e-01 + 1.14000000000000e+02 -3.59408610235184e-01 1.07805672550782e+00 -3.31659036281393e-01 + 1.17000000000000e+02 -3.97141252418688e-01 1.02744833950730e+00 -3.26050743938977e-01 + 1.20000000000000e+02 -4.34875524108853e-01 9.76839737247837e-01 -3.20442427056780e-01 + 1.23000000000000e+02 -4.62416171597766e-01 9.14497675605232e-01 -3.13240052857952e-01 + 1.26000000000000e+02 -4.89961725795433e-01 8.52155375838165e-01 -3.06037651148621e-01 + 1.29000000000000e+02 -5.17511317766740e-01 7.89812599804369e-01 -2.98835194416227e-01 + 1.32000000000000e+02 -5.38097371011921e-01 7.24693487985317e-01 -2.92129065581036e-01 + 1.35000000000000e+02 -5.55209533057542e-01 6.58186211572688e-01 -2.85671100106641e-01 + 1.38000000000000e+02 -5.72330730353409e-01 5.91679697265480e-01 -2.79213208633931e-01 + 1.41000000000000e+02 -5.87351226752077e-01 5.26476382236642e-01 -2.74246677538335e-01 + 1.44000000000000e+02 -5.98171151079133e-01 4.63879476339314e-01 -2.72262879298565e-01 + 1.47000000000000e+02 -6.09009472068249e-01 4.01283048649868e-01 -2.70279096213984e-01 + 1.50000000000000e+02 -6.19863301663139e-01 3.36609283159026e-01 -2.68295320706727e-01 + 1.53000000000000e+02 -6.39361023231318e-01 2.83555584049004e-01 -2.80703642982803e-01 + 1.56000000000000e+02 -6.58893043506451e-01 2.30735614552766e-01 -2.93111951398230e-01 + 1.59000000000000e+02 -6.78451069490567e-01 1.78095963395456e-01 -3.05520165022309e-01 + 1.62000000000000e+02 -6.43501747482713e-01 1.41646320077994e-01 -3.47725013460614e-01 + 1.65000000000000e+02 -5.88359323471862e-01 1.13322899941877e-01 -4.04828431301629e-01 + 1.68000000000000e+02 -5.23499707930916e-01 8.50931388592694e-02 -4.61931194793028e-01 + 1.71000000000000e+02 -4.31704332512692e-01 6.49763275693468e-02 -4.50000513056908e-01 + 1.74000000000000e+02 -2.87802289582396e-01 6.09656699428337e-02 -2.99999717902353e-01 + 1.77000000000000e+02 -1.43244990746609e-01 5.69851238094485e-02 -1.49315896260807e-01 + 1.80000000000000e+02 0.00000000000000e+00 5.30927947138125e-02 0.00000000000000e+00 diff --git a/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_06.dat b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_06.dat new file mode 100644 index 00000000..28b7cb05 --- /dev/null +++ b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_06.dat @@ -0,0 +1,254 @@ +! ------------ AirfoilInfo v1.01.x Input File ---------------------------------- +! AeroElasticSE FAST driver +! line +! line +! ------------------------------------------------------------------------------ +DEFAULT InterpOrd ! Interpolation order to use for quasi-steady table lookup {1=linear; 3=cubic spline; "default"} [default=3] +1 NonDimArea ! The non-dimensional area of the airfoil (area/chord^2) (set to 1.0 if unsure or unneeded) +@"NREL-2p8-127_AF06_Coords.txt" NumCoords ! The number of coordinates in the airfoil shape file. Set to zero if coordinates not included. +AF06_BL.txt BL_file ! The file name including the boundary layer characteristics of the profile. Ignored if the aeroacoustic module is not called. +1 NumTabs ! Number of airfoil tables in this file. Each table must have lines for Re and Ctrl. +! ------------------------------------------------------------------------------ +! data for table 1 +! ------------------------------------------------------------------------------ +6.000000 Re ! Reynolds number in millions +0 Ctrl ! Control setting (must be 0 for current AirfoilInfo) +True InclUAdata ! Is unsteady aerodynamics data included in this table? If TRUE, then include 30 UA coefficients below this line +!........................................ +0.000000 alpha0 ! 0-lift angle of attack, depends on airfoil. +0.000000 alpha1 ! Angle of attack at f=0.7, (approximately the stall angle) for AOA>alpha0. (deg) +0.000000 alpha2 ! Angle of attack at f=0.7, (approximately the stall angle) for AOA1] +0.000000 S2 ! Constant in the f curve best-fit for AOA> alpha1; by definition it depends on the airfoil. [ignored if UAMod<>1] +0.000000 S3 ! Constant in the f curve best-fit for alpha2<=AOA< alpha0; by definition it depends on the airfoil. [ignored if UAMod<>1] +0.000000 S4 ! Constant in the f curve best-fit for AOA< alpha2; by definition it depends on the airfoil. [ignored if UAMod<>1] +0.000000 Cn1 ! Critical value of C0n at leading edge separation. It should be extracted from airfoil data at a given Mach and Reynolds number. It can be calculated from the static value of Cn at either the break in the pitching moment or the loss of chord force at the onset of stall. It is close to the condition of maximum lift of the airfoil at low Mach numbers. +0.000000 Cn2 ! As Cn1 for negative AOAs. +Default St_sh ! Strouhal's shedding frequency constant. [default = 0.19] +0.000000 Cd0 ! 2D drag coefficient value at 0-lift. +0.000000 Cm0 ! 2D pitching moment coefficient about 1/4-chord location, at 0-lift, positive if nose up. [If the aerodynamics coefficients table does not include a column for Cm, this needs to be set to 0.0] +0.000000 k0 ! Constant in the \hat(x)_cp curve best-fit; = (\hat(x)_AC-0.25). [ignored if UAMod<>1] +0.000000 k1 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k2 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k3 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k1_hat ! Constant in the expression of Cc due to leading edge vortex effects. [ignored if UAMod<>1] +Default x_cp_bar ! Constant in the expression of \hat(x)_cp^v. [ignored if UAMod<>1, default = 0.2] +Default UACutout ! Angle of attack above which unsteady aerodynamics are disabled (deg). [Specifying the string "Default" sets UACutout to 45 degrees] +Default filtCutOff ! Cut-off frequency (-3 dB corner frequency) for low-pass filtering the AoA input to UA, as well as the 1st and 2nd derivatives (Hz) [default = 20] +!........................................ +! Table of aerodynamics coefficients +200 NumAlf ! Number of data lines in the following table +! Alpha Cl Cd Cm +! (deg) (-) (-) (-) +-1.80000000000000e+02 0.00000000000000e+00 1.04451467064788e-02 0.00000000000000e+00 +-1.77000000000000e+02 1.47157007613739e-01 1.04872308588687e-02 1.19452717008645e-01 +-1.74000000000000e+02 2.95662162415483e-01 1.05303966409131e-02 2.39999774321882e-01 +-1.71000000000000e+02 4.43494166290477e-01 1.05740045222718e-02 3.60000410445527e-01 +-1.68000000000000e+02 5.36848745324298e-01 2.74506298830325e-02 3.81279166438973e-01 +-1.65000000000000e+02 6.01560063853722e-01 5.27443629674667e-02 3.53198134597150e-01 +-1.62000000000000e+02 6.66223778858103e-01 7.80396220376046e-02 3.25116780970332e-01 +-1.59000000000000e+02 7.02316612456853e-01 1.12504063201209e-01 3.01860860228524e-01 +-1.56000000000000e+02 6.79726083437648e-01 1.65305735070101e-01 2.88248798735499e-01 +-1.53000000000000e+02 6.57149315796707e-01 2.18110193131311e-01 2.74623662647778e-01 +-1.50000000000000e+02 6.34589659449874e-01 2.70917973756332e-01 2.60980583690885e-01 +-1.47000000000000e+02 6.22060969336252e-01 3.35899150571673e-01 2.62488656920504e-01 +-1.44000000000000e+02 6.09539332292595e-01 4.00853059956420e-01 2.63992059057429e-01 +-1.41000000000000e+02 5.97025743089158e-01 4.65807465559123e-01 2.65489913378387e-01 +-1.38000000000000e+02 5.80704075775906e-01 5.33717517969207e-01 2.70296859813583e-01 +-1.35000000000000e+02 5.62478076348152e-01 6.03105387787129e-01 2.76759519512185e-01 +-1.32000000000000e+02 5.44255597967036e-01 6.72494052728241e-01 2.83220945160593e-01 +-1.29000000000000e+02 5.22678505700544e-01 7.40650991852422e-01 2.90064291270315e-01 +-1.26000000000000e+02 4.94385901691070e-01 8.06344473485986e-01 2.97673949948684e-01 +-1.23000000000000e+02 4.66094993647798e-01 8.72037453255156e-01 3.05283501600632e-01 +-1.20000000000000e+02 4.37806027109449e-01 9.37730182101509e-01 3.12892965044744e-01 +-1.17000000000000e+02 3.99577421117098e-01 9.92049662822417e-01 3.19211276900007e-01 +-1.14000000000000e+02 3.61349504390741e-01 1.04636891381409e+00 3.25529257918674e-01 +-1.11000000000000e+02 3.23122662358267e-01 1.10068774984251e+00 3.31846802734848e-01 +-1.08000000000000e+02 2.80173308571465e-01 1.14318523690795e+00 3.36136841670906e-01 +-1.05000000000000e+02 2.34862463623927e-01 1.17977195947738e+00 3.39411510930403e-01 +-1.02000000000000e+02 1.89552426493172e-01 1.21635826279871e+00 3.42683246088910e-01 +-9.90000000000000e+01 1.43411370176115e-01 1.24567433198225e+00 3.44537199174708e-01 +-9.60000000000000e+01 9.56073752226676e-02 1.26044961797812e+00 3.43556506874831e-01 +-9.30000000000000e+01 4.78037454869307e-02 1.27522479109913e+00 3.42562148033031e-01 +-9.00000000000000e+01 2.98356743247137e-07 1.28999990778373e+00 3.41794286215052e-01 +-8.70000000000000e+01 -4.78036965600822e-02 1.27522480622146e+00 3.34958722226529e-01 +-8.40000000000000e+01 -9.56075088932874e-02 1.26044957666313e+00 3.28241304934322e-01 +-8.10000000000000e+01 -1.43410956056677e-01 1.24567445997852e+00 3.21434171665192e-01 +-7.80000000000000e+01 -1.89552207046124e-01 1.21635843999553e+00 3.12123499707622e-01 +-7.50000000000000e+01 -2.34862763393904e-01 1.17977171742431e+00 3.01780409905885e-01 +-7.20000000000000e+01 -2.80173089123731e-01 1.14318541410297e+00 2.91437438626359e-01 +-6.90000000000000e+01 -3.23122331202990e-01 1.10068822040718e+00 2.80383282644346e-01 +-6.60000000000000e+01 -3.61349611282076e-01 1.04636876192745e+00 2.67906699019381e-01 +-6.30000000000000e+01 -3.99577674034013e-01 9.92049303447725e-01 2.55430115394417e-01 +-6.00000000000000e+01 -4.37806214260738e-01 9.37729747481855e-01 2.42953527363207e-01 +-5.70000000000000e+01 -4.66095180812632e-01 8.72037018635503e-01 2.29962886841547e-01 +-5.40000000000000e+01 -4.94386088868899e-01 8.06344038861353e-01 2.16972196699283e-01 +-5.10000000000000e+01 -5.22678692887195e-01 7.40650557227788e-01 2.03981407315058e-01 +-4.80000000000000e+01 -5.44252972972638e-01 6.72494123749236e-01 1.91507677333331e-01 +-4.50000000000000e+01 -5.62469809216957e-01 6.03106253931314e-01 1.79292468742977e-01 +-4.20000000000000e+01 -5.80700032781224e-01 5.33717588985239e-01 1.67077120176337e-01 +-3.90000000000000e+01 -5.97024764718039e-01 4.65807407987464e-01 1.55320402968213e-01 +-3.60000000000000e+01 -6.09536960661095e-01 4.00852878339035e-01 1.44480717872626e-01 +-3.30000000000000e+01 -6.22060657674661e-01 3.35899589207050e-01 1.33641239795822e-01 +-3.00000000000000e+01 -6.34589785519217e-01 2.70917595996388e-01 1.22801551597028e-01 +-2.93939393939394e+01 -6.39157128083239e-01 2.60249253715867e-01 1.20443684761723e-01 +-2.87878787878788e+01 -6.43726970234920e-01 2.49581068160403e-01 1.18056074979326e-01 +-2.81818181818182e+01 -6.48299337915072e-01 2.38913030435958e-01 1.15668753051161e-01 +-2.75757575757576e+01 -6.52871145565939e-01 2.28244918383301e-01 1.13281631608806e-01 +-2.69696969696970e+01 -6.57443601591947e-01 2.17576846610789e-01 1.10894703470960e-01 +-2.63636363636364e+01 -6.62017925284925e-01 2.06908899722581e-01 1.08507963151374e-01 +-2.57575757575758e+01 -6.66590638057245e-01 1.96241193383532e-01 1.06121395705389e-01 +-2.51515151515151e+01 -6.71159355283587e-01 1.85573782554301e-01 1.03734968840955e-01 +-2.45454545454545e+01 -6.75728973211485e-01 1.74906478164995e-01 1.01348641226412e-01 +-2.39393939393939e+01 -6.80298045453838e-01 1.64239274881544e-01 9.89623846880801e-02 +-2.33333333333333e+01 -6.84854798199331e-01 1.53572167720432e-01 9.65760871231664e-02 +-2.27272727272727e+01 -6.89411636551734e-01 1.42905152020367e-01 9.41898138397285e-02 +-2.21212121212121e+01 -6.93968554262710e-01 1.32238223416651e-01 9.18035530549137e-02 +-2.15151515151515e+01 -6.98508709947078e-01 1.21571133361270e-01 8.94170767131999e-02 +-2.09090909090909e+01 -7.03044892648499e-01 1.10904061345980e-01 8.70305146317220e-02 +-2.03030303030303e+01 -7.07581304739425e-01 1.00237064894968e-01 8.46439121010197e-02 +-1.96969696969697e+01 -7.02434146497075e-01 9.30822479646328e-02 8.04176563008526e-02 +-1.90909090909091e+01 -6.87605029081401e-01 8.94394535867222e-02 7.43518989818734e-02 +-1.84848484848485e+01 -6.72778074386064e-01 8.57969669339951e-02 6.82864549586822e-02 +-1.78787878787879e+01 -6.57952316652420e-01 8.21546025938098e-02 6.22210099648385e-02 +-1.72727272727273e+01 -6.43126950262024e-01 7.85122065549102e-02 5.61553003431422e-02 +-1.66666666666667e+01 -6.28302519055304e-01 7.48699483442050e-02 5.00895983301152e-02 +-1.60606060606061e+01 -6.13478902955351e-01 7.12278305909537e-02 4.40238940514546e-02 +-1.54545454545455e+01 -5.98656762623450e-01 6.75860437894719e-02 3.79584834371826e-02 +-1.48484848484848e+01 -5.83835116087009e-01 6.39443715968832e-02 3.18929726477928e-02 +-1.42424242424242e+01 -5.69013374770912e-01 6.03026916613097e-02 2.58271029097552e-02 +-1.36363636363636e+01 -5.54192788419233e-01 5.66613031319075e-02 1.97612536677373e-02 +-1.30303030303030e+01 -5.39371304159858e-01 5.30198014190618e-02 1.36946491482892e-02 +-1.24242424242424e+01 -5.24551543111039e-01 4.93787366739739e-02 7.62887531626830e-03 +-1.18181818181818e+01 -5.09730889357631e-01 4.57375886003972e-02 1.56582884204670e-03 +-1.12121212121212e+01 -4.94911816881562e-01 4.20969074071858e-02 -4.49615178689840e-03 +-1.06060606060606e+01 -4.80091928606605e-01 3.84561282662129e-02 -1.05578228942103e-02 +-1.00000000000000e+01 -4.65272615271009e-01 3.48157175645994e-02 -1.66180951849822e-02 +-9.39393939393939e+00 -4.33015231009942e-01 3.42187656030196e-02 -1.65076215545108e-02 +-8.78787878787879e+00 -4.00776603293592e-01 3.36221501328585e-02 -1.63940097647302e-02 +-8.18181818181818e+00 -3.68550425214672e-01 3.30196417584014e-02 -1.62766322067477e-02 +-7.57575757575758e+00 -3.36434279469676e-01 3.26768333428082e-02 -1.61640703650675e-02 +-6.96969696969697e+00 -3.04375048369348e-01 3.24942948584592e-02 -1.60544597500587e-02 +-6.36363636363636e+00 -2.72349727408693e-01 3.22072522033381e-02 -1.59243774119394e-02 +-5.75757575757576e+00 -2.40358355463915e-01 3.18276476040425e-02 -1.56691283801087e-02 +-5.15151515151515e+00 -2.08432296047144e-01 3.13466648471733e-02 -1.56292523082999e-02 +-4.54545454545454e+00 -1.76609965524745e-01 3.08120593078346e-02 -1.55984117030112e-02 +-3.93939393939394e+00 -1.44997595632154e-01 3.02529210905892e-02 -1.55594122431336e-02 +-3.33333333333333e+00 -1.13863635347939e-01 2.96208324027153e-02 -1.55210128993654e-02 +-2.72727272727273e+00 -5.99893192871201e-02 2.93065185564550e-02 -1.71363467068633e-02 +-2.12121212121212e+00 2.27564888093693e-02 2.93538954238316e-02 -1.97749354532020e-02 +-1.51515151515152e+00 1.05200007924397e-01 2.93787983393214e-02 -2.18495371988307e-02 +-9.09090909090912e-01 1.87443112873824e-01 2.94162855389729e-02 -2.40114002927046e-02 +-3.03030303030302e-01 2.69492451080518e-01 2.95149670076408e-02 -2.60738132222027e-02 + 3.03030303030302e-01 3.51341217387514e-01 2.95252389442168e-02 -2.81360338847481e-02 + 9.09090909090912e-01 4.32977146923541e-01 2.95324300033464e-02 -3.02799067329311e-02 + 1.51515151515152e+00 5.14818629228781e-01 2.95320187044063e-02 -3.23663227732926e-02 + 2.12121212121212e+00 5.95875970346463e-01 2.96220237683965e-02 -3.47191596720360e-02 + 2.72727272727273e+00 6.76364098276864e-01 2.96076377124260e-02 -3.73109856941127e-02 + 3.33333333333333e+00 7.56846420931681e-01 2.95894663968510e-02 -3.99780779670709e-02 + 3.93939393939394e+00 8.37335412739111e-01 2.96601655289752e-02 -4.26453918217197e-02 + 4.54545454545455e+00 9.17819291031016e-01 2.96450963882609e-02 -4.52128978330237e-02 + 5.15151515151515e+00 9.98308476294268e-01 2.96479816058189e-02 -4.78802193292873e-02 + 5.75757575757576e+00 1.07878507397145e+00 2.96910810658735e-02 -5.05480539440911e-02 + 6.36363636363637e+00 1.15925721789623e+00 2.96540309894699e-02 -5.31448705442736e-02 + 6.96969696969697e+00 1.23972406223336e+00 2.97108111966689e-02 -5.57870430345416e-02 + 7.57575757575757e+00 1.31979653762893e+00 2.96607700932776e-02 -5.85770647543249e-02 + 8.18181818181818e+00 1.39574347837112e+00 2.96344899473148e-02 -6.23210696280249e-02 + 8.78787878787879e+00 1.46845278922940e+00 2.96855555923576e-02 -6.63193015468805e-02 + 9.39393939393939e+00 1.54113668312882e+00 2.96488360635837e-02 -7.03198982848751e-02 + 1.00000000000000e+01 1.61380661140144e+00 2.95365970912785e-02 -7.43207867311127e-02 + 1.06060606060606e+01 1.66835969927735e+00 2.93338363207452e-02 -7.80346111337379e-02 + 1.12121212121212e+01 1.70692741182872e+00 2.93798828283306e-02 -8.05927498314898e-02 + 1.18181818181818e+01 1.74587632218544e+00 3.01307604443737e-02 -8.45839669704818e-02 + 1.24242424242424e+01 1.09782720012007e+00 3.33105797425031e-02 -6.18259975113200e-02 + 1.30303030303030e+01 9.73402814155888e-01 3.56492113840093e-02 -5.87718757586572e-02 + 1.36363636363636e+01 9.88485823361229e-01 3.73441347002030e-02 -6.12633502425757e-02 + 1.42424242424242e+01 1.01090647828627e+00 3.86537299612605e-02 -6.40712596029900e-02 + 1.48484848484848e+01 1.04282842508625e+00 3.96717899749230e-02 -6.69529521512987e-02 + 1.54545454545455e+01 1.08269042899909e+00 4.02778502988878e-02 -7.00292393429914e-02 + 1.60606060606061e+01 1.12069441651250e+00 4.15211136336744e-02 -7.34124817337401e-02 + 1.66666666666667e+01 1.10428631804948e+00 4.97349677981258e-02 -7.89834353690655e-02 + 1.72727272727273e+01 1.08784286827117e+00 5.79481890360755e-02 -8.45666402360810e-02 + 1.78787878787879e+01 1.07137007227413e+00 6.61606214571691e-02 -9.01640784321922e-02 + 1.84848484848485e+01 1.05482456124854e+00 7.43726955221486e-02 -9.57806291561119e-02 + 1.90909090909091e+01 1.03840773749638e+00 8.25847845613570e-02 -1.01399088671180e-01 + 1.96969696969697e+01 1.02224607479530e+00 9.07973366722597e-02 -1.07003526290174e-01 + 2.03030303030303e+01 1.01092702064250e+00 1.00237064894968e-01 -1.11264195300182e-01 + 2.09090909090909e+01 1.00444584016781e+00 1.10904061345980e-01 -1.14182224296970e-01 + 2.15151515151515e+01 9.97964986040765e-01 1.21571133361270e-01 -1.17102244903151e-01 + 2.21212121212121e+01 9.91478442890709e-01 1.32238223416651e-01 -1.20024488822164e-01 + 2.27272727272727e+01 9.84967906725073e-01 1.42905152020367e-01 -1.22949596706990e-01 + 2.33333333333333e+01 9.78457485279851e-01 1.53572167720432e-01 -1.25875923784615e-01 + 2.39393939393939e+01 9.71947187592677e-01 1.64239274881544e-01 -1.28803443608322e-01 + 2.45454545454545e+01 9.65419250819274e-01 1.74906478164995e-01 -1.31732713112496e-01 + 2.51515151515151e+01 9.58890536835396e-01 1.85573782554301e-01 -1.34663003015135e-01 + 2.57575757575758e+01 9.52363117111773e-01 1.96241193383532e-01 -1.37594239679627e-01 + 2.63636363636364e+01 9.45829985373321e-01 2.06908899722581e-01 -1.40526626180439e-01 + 2.69696969696970e+01 9.39294556254110e-01 2.17576846610789e-01 -1.43460023904971e-01 + 2.75757575757576e+01 9.32761808370637e-01 2.28244918383301e-01 -1.46394293444329e-01 + 2.81818181818182e+01 9.26229995246710e-01 2.38913030435957e-01 -1.49329450107358e-01 + 2.87878787878788e+01 9.19697387107103e-01 2.49581068160403e-01 -1.52265482124334e-01 + 2.93939393939394e+01 9.13168404913080e-01 2.60249253715867e-01 -1.55202396247522e-01 + 3.00000000000000e+01 9.06643011580764e-01 2.70917595996388e-01 -1.58140217032240e-01 + 3.30000000000000e+01 8.88688675426252e-01 3.35899589207050e-01 -1.69129145388514e-01 + 3.60000000000000e+01 8.70742215903117e-01 4.00852878339035e-01 -1.79949350188385e-01 + 3.90000000000000e+01 8.52812326157355e-01 4.65807407987464e-01 -1.90730956251902e-01 + 4.20000000000000e+01 8.29505265359302e-01 5.33717588985240e-01 -2.01309118189523e-01 + 4.50000000000000e+01 8.03510457214686e-01 6.03106253931314e-01 -2.11785658405499e-01 + 4.80000000000000e+01 7.77534592624486e-01 6.72494123749237e-01 -2.22262078570281e-01 + 5.10000000000000e+01 7.46744805516537e-01 7.40650557227789e-01 -2.32656858855358e-01 + 5.40000000000000e+01 7.06322608215230e-01 8.06344038861353e-01 -2.42888354132579e-01 + 5.70000000000000e+01 6.65902819356557e-01 8.72037018635503e-01 -2.53119771247217e-01 + 6.00000000000000e+01 6.25485786688918e-01 9.37729747481856e-01 -2.63351149280861e-01 + 6.30000000000000e+01 5.70855611235508e-01 9.92049303447725e-01 -2.72828203817710e-01 + 6.60000000000000e+01 5.16226204482826e-01 1.04636876192745e+00 -2.82305251888810e-01 + 6.90000000000000e+01 4.61598036952559e-01 1.10068822040718e+00 -2.91782299959910e-01 + 7.20000000000000e+01 4.00255485500037e-01 1.14318541410298e+00 -3.00336786931006e-01 + 7.50000000000000e+01 3.35555531395701e-01 1.17977171742431e+00 -3.08430012238153e-01 + 7.80000000000000e+01 2.70855228914286e-01 1.21635843999553e+00 -3.16523330287215e-01 + 8.10000000000000e+01 2.04949941366059e-01 1.24567445997852e+00 -3.23905764836268e-01 + 8.40000000000000e+01 1.36633587012766e-01 1.26044957666313e+00 -3.29866481455659e-01 + 8.70000000000000e+01 6.83167107824974e-02 1.27522480622146e+00 -3.35775778267908e-01 + 9.00000000000000e+01 -2.98356743449189e-07 1.28999990778373e+00 -3.41568552350958e-01 + 9.30000000000000e+01 -4.78037454869307e-02 1.27522479109913e+00 -3.42550600496776e-01 + 9.60000000000000e+01 -9.56073752226678e-02 1.26044961797812e+00 -3.43313207813819e-01 + 9.90000000000000e+01 -1.43411370176115e-01 1.24567433198225e+00 -3.44075820956797e-01 + 1.02000000000000e+02 -1.89552426493172e-01 1.21635826279871e+00 -3.42018024992642e-01 + 1.05000000000000e+02 -2.34862463623927e-01 1.17977195947738e+00 -3.38550055015947e-01 + 1.08000000000000e+02 -2.80173308571465e-01 1.14318523690795e+00 -3.35082045299249e-01 + 1.11000000000000e+02 -3.23122662358267e-01 1.10068774984251e+00 -3.30613204224884e-01 + 1.14000000000000e+02 -3.61349504390742e-01 1.04636891381409e+00 -3.24142730917994e-01 + 1.17000000000000e+02 -3.99577421117098e-01 9.92049662822417e-01 -3.17672208180576e-01 + 1.20000000000000e+02 -4.37806027109449e-01 9.37730182101508e-01 -3.11201658314193e-01 + 1.23000000000000e+02 -4.66094993647798e-01 8.72037453255156e-01 -3.03497229746074e-01 + 1.26000000000000e+02 -4.94385901691070e-01 8.06344473485986e-01 -2.95792771749784e-01 + 1.29000000000000e+02 -5.22678505700545e-01 7.40650991852421e-01 -2.88088254894948e-01 + 1.32000000000000e+02 -5.44255597967036e-01 6.72494052728240e-01 -2.81200220471366e-01 + 1.35000000000000e+02 -5.62478076348152e-01 6.03105387787129e-01 -2.74720426295997e-01 + 1.38000000000000e+02 -5.80704075775906e-01 5.33717517969206e-01 -2.68240706372448e-01 + 1.41000000000000e+02 -5.97025743089158e-01 4.65807465559123e-01 -2.63448804520033e-01 + 1.44000000000000e+02 -6.09539332292595e-01 4.00853059956420e-01 -2.62032552505631e-01 + 1.47000000000000e+02 -6.22060969336252e-01 3.35899150571673e-01 -2.60616311310659e-01 + 1.50000000000000e+02 -6.34589659449874e-01 2.70917973756332e-01 -2.59200075525210e-01 + 1.53000000000000e+02 -6.57149315796707e-01 2.18110193131311e-01 -2.73103661656341e-01 + 1.56000000000000e+02 -6.79726083437648e-01 1.65305735070101e-01 -2.87007230377031e-01 + 1.59000000000000e+02 -7.02316612456853e-01 1.12504063201209e-01 -3.00910692883565e-01 + 1.62000000000000e+02 -6.66331535360941e-01 7.80396220376046e-02 -3.44436173003965e-01 + 1.65000000000000e+02 -6.02756791375368e-01 5.27443629674667e-02 -4.02772912450035e-01 + 1.68000000000000e+02 -5.36848745324298e-01 2.74506298830325e-02 -4.61108983413823e-01 + 1.71000000000000e+02 -4.43494166290477e-01 1.05740045222718e-02 -4.50000513056908e-01 + 1.74000000000000e+02 -2.95662162415483e-01 1.05303966409131e-02 -2.99999717902353e-01 + 1.77000000000000e+02 -1.47157007613739e-01 1.04872308588687e-02 -1.49315896260807e-01 + 1.80000000000000e+02 0.00000000000000e+00 1.04451467064788e-02 0.00000000000000e+00 diff --git a/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_07.dat b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_07.dat new file mode 100644 index 00000000..d854bfa0 --- /dev/null +++ b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_07.dat @@ -0,0 +1,254 @@ +! ------------ AirfoilInfo v1.01.x Input File ---------------------------------- +! AeroElasticSE FAST driver +! line +! line +! ------------------------------------------------------------------------------ +DEFAULT InterpOrd ! Interpolation order to use for quasi-steady table lookup {1=linear; 3=cubic spline; "default"} [default=3] +1 NonDimArea ! The non-dimensional area of the airfoil (area/chord^2) (set to 1.0 if unsure or unneeded) +@"NREL-2p8-127_AF07_Coords.txt" NumCoords ! The number of coordinates in the airfoil shape file. Set to zero if coordinates not included. +AF07_BL.txt BL_file ! The file name including the boundary layer characteristics of the profile. Ignored if the aeroacoustic module is not called. +1 NumTabs ! Number of airfoil tables in this file. Each table must have lines for Re and Ctrl. +! ------------------------------------------------------------------------------ +! data for table 1 +! ------------------------------------------------------------------------------ +6.000000 Re ! Reynolds number in millions +0 Ctrl ! Control setting (must be 0 for current AirfoilInfo) +True InclUAdata ! Is unsteady aerodynamics data included in this table? If TRUE, then include 30 UA coefficients below this line +!........................................ +-2.175483 alpha0 ! 0-lift angle of attack, depends on airfoil. +12.034907 alpha1 ! Angle of attack at f=0.7, (approximately the stall angle) for AOA>alpha0. (deg) +-4.017330 alpha2 ! Angle of attack at f=0.7, (approximately the stall angle) for AOA1] +0.000000 S2 ! Constant in the f curve best-fit for AOA> alpha1; by definition it depends on the airfoil. [ignored if UAMod<>1] +0.000000 S3 ! Constant in the f curve best-fit for alpha2<=AOA< alpha0; by definition it depends on the airfoil. [ignored if UAMod<>1] +0.000000 S4 ! Constant in the f curve best-fit for AOA< alpha2; by definition it depends on the airfoil. [ignored if UAMod<>1] +1.598379 Cn1 ! Critical value of C0n at leading edge separation. It should be extracted from airfoil data at a given Mach and Reynolds number. It can be calculated from the static value of Cn at either the break in the pitching moment or the loss of chord force at the onset of stall. It is close to the condition of maximum lift of the airfoil at low Mach numbers. +-0.740046 Cn2 ! As Cn1 for negative AOAs. +Default St_sh ! Strouhal's shedding frequency constant. [default = 0.19] +0.019639 Cd0 ! 2D drag coefficient value at 0-lift. +-0.026025 Cm0 ! 2D pitching moment coefficient about 1/4-chord location, at 0-lift, positive if nose up. [If the aerodynamics coefficients table does not include a column for Cm, this needs to be set to 0.0] +0.000000 k0 ! Constant in the \hat(x)_cp curve best-fit; = (\hat(x)_AC-0.25). [ignored if UAMod<>1] +0.000000 k1 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k2 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k3 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k1_hat ! Constant in the expression of Cc due to leading edge vortex effects. [ignored if UAMod<>1] +Default x_cp_bar ! Constant in the expression of \hat(x)_cp^v. [ignored if UAMod<>1, default = 0.2] +Default UACutout ! Angle of attack above which unsteady aerodynamics are disabled (deg). [Specifying the string "Default" sets UACutout to 45 degrees] +Default filtCutOff ! Cut-off frequency (-3 dB corner frequency) for low-pass filtering the AoA input to UA, as well as the 1st and 2nd derivatives (Hz) [default = 20] +!........................................ +! Table of aerodynamics coefficients +200 NumAlf ! Number of data lines in the following table +! Alpha Cl Cd Cm +! (deg) (-) (-) (-) +-1.80000000000000e+02 0.00000000000000e+00 2.33914127688100e-02 0.00000000000000e+00 +-1.77000000000000e+02 1.43031527763221e-01 2.33914127688100e-02 1.19163615697548e-01 +-1.74000000000000e+02 2.87990892106934e-01 2.66846196171584e-02 2.39999774321882e-01 +-1.71000000000000e+02 4.31987088278764e-01 3.65643482753360e-02 3.60000410445527e-01 +-1.68000000000000e+02 5.31545849874829e-01 5.84098652013656e-02 3.64532897060852e-01 +-1.65000000000000e+02 6.11268538666348e-01 8.62381366029380e-02 3.11332656605488e-01 +-1.62000000000000e+02 6.94600133989169e-01 1.14066726893083e-01 2.58131725599959e-01 +-1.59000000000000e+02 7.40824462046985e-01 1.50632267952715e-01 2.21242462675373e-01 +-1.56000000000000e+02 7.16139659509821e-01 2.04671414989218e-01 2.16831447428975e-01 +-1.53000000000000e+02 6.91423868529968e-01 2.58710851852227e-01 2.12177598920349e-01 +-1.50000000000000e+02 6.66670110194854e-01 3.12750462408367e-01 2.07242736249593e-01 +-1.47000000000000e+02 6.52900940317335e-01 3.79139090101126e-01 2.11698220689362e-01 +-1.44000000000000e+02 6.39116027015019e-01 4.45527909875772e-01 2.16157774411608e-01 +-1.41000000000000e+02 6.25312980734950e-01 5.11917113827909e-01 2.20622202461720e-01 +-1.38000000000000e+02 6.07728072005134e-01 5.81216719268110e-01 2.27857968655088e-01 +-1.35000000000000e+02 5.88252908821619e-01 6.51971519548278e-01 2.36476173369762e-01 +-1.32000000000000e+02 5.68769160282536e-01 7.22726946114877e-01 2.45092460374068e-01 +-1.29000000000000e+02 5.45846532434262e-01 7.92131150298341e-01 2.54083304617287e-01 +-1.26000000000000e+02 5.16059865398949e-01 8.58832903295187e-01 2.63823977750305e-01 +-1.23000000000000e+02 4.86270063393777e-01 9.25534146724964e-01 2.73560128804467e-01 +-1.20000000000000e+02 4.56476301826173e-01 9.92235135380730e-01 2.83291214803044e-01 +-1.17000000000000e+02 4.16489600596796e-01 1.04694876887339e+00 2.91917422175410e-01 +-1.14000000000000e+02 3.76501801901982e-01 1.10166216993032e+00 3.00538465312235e-01 +-1.11000000000000e+02 3.36512597958186e-01 1.15637515301294e+00 3.09153340377474e-01 +-1.08000000000000e+02 2.91693025082505e-01 1.19874087754264e+00 3.15840388222425e-01 +-1.05000000000000e+02 2.44458666678294e-01 1.23493287877690e+00 3.21561919471006e-01 +-1.02000000000000e+02 1.97224219276773e-01 1.27112446528618e+00 3.27278150969725e-01 +-9.90000000000000e+01 1.49160540417765e-01 1.29974121708087e+00 3.31577776566796e-01 +-9.60000000000000e+01 9.94402497296759e-02 1.31320797134044e+00 3.33053601420033e-01 +-9.30000000000000e+01 4.97202158283082e-02 1.32667462272159e+00 3.34536430978363e-01 +-9.00000000000000e+01 3.10317978578370e-07 1.34014122266447e+00 3.35516468539213e-01 +-8.70000000000000e+01 -4.97201649399637e-02 1.32667463650466e+00 3.30914309585675e-01 +-8.40000000000000e+01 -9.94403887586856e-02 1.31320793368439e+00 3.25875044063013e-01 +-8.10000000000000e+01 -1.49160109697721e-01 1.29974133374151e+00 3.20684674998472e-01 +-7.80000000000000e+01 -1.97223990505980e-01 1.27112464057129e+00 3.14068969100332e-01 +-7.50000000000000e+01 -2.44458979176423e-01 1.23493263933526e+00 3.06188477394521e-01 +-7.20000000000000e+01 -2.91692796320390e-01 1.19874105282597e+00 2.98307891491871e-01 +-6.90000000000000e+01 -3.36512251521935e-01 1.15637562699211e+00 2.89561021929827e-01 +-6.60000000000000e+01 -3.76501913717355e-01 1.10166201694156e+00 2.79081514110173e-01 +-6.30000000000000e+01 -4.16489865150498e-01 1.04694840689101e+00 2.68601883289040e-01 +-6.00000000000000e+01 -4.56476498955521e-01 9.92234694090483e-01 2.58122183245595e-01 +-5.70000000000000e+01 -4.86270260493495e-01 9.25533705434717e-01 2.46741658278199e-01 +-5.40000000000000e+01 -5.16060062475956e-01 8.58832461999884e-01 2.35361028339939e-01 +-5.10000000000000e+01 -5.45846729491953e-01 7.92130709003037e-01 2.23980188458352e-01 +-4.80000000000000e+01 -5.69289853059557e-01 7.22744238735752e-01 2.13008982600553e-01 +-4.50000000000000e+01 -5.89557703094231e-01 6.52015452980456e-01 2.02242587171249e-01 +-4.20000000000000e+01 -6.08251798068365e-01 5.81234011749336e-01 1.91868319013648e-01 +-3.90000000000000e+01 -6.25416926876934e-01 5.11597466281429e-01 1.81968105360702e-01 +-3.60000000000000e+01 -6.39316913259601e-01 4.44496914459934e-01 1.73264272171102e-01 +-3.30000000000000e+01 -6.52916432542900e-01 3.78198211323207e-01 1.65338571395536e-01 +-3.00000000000000e+01 -6.66670235178609e-01 3.12750067745499e-01 1.58271579799568e-01 +-2.93939393939394e+01 -6.71047367933391e-01 3.01438712775986e-01 1.57020885663939e-01 +-2.87878787878788e+01 -6.75419095195018e-01 2.90127357806473e-01 1.55835649782268e-01 +-2.81818181818182e+01 -6.79785363067838e-01 2.78816002836960e-01 1.54649678410992e-01 +-2.75757575757576e+01 -6.84281237628547e-01 2.67629852848922e-01 1.53624988893004e-01 +-2.69696969696970e+01 -6.88830733728478e-01 2.56497366741980e-01 1.52669124180276e-01 +-2.63636363636364e+01 -6.93376184149147e-01 2.45364880635039e-01 1.51712730581928e-01 +-2.57575757575758e+01 -6.98037897852729e-01 2.34311621831173e-01 1.50875935757439e-01 +-2.51515151515151e+01 -7.02877385944567e-01 2.23377185516994e-01 1.50218827286969e-01 +-2.45454545454545e+01 -7.07714903614937e-01 2.12442749202814e-01 1.49561371313348e-01 +-2.39393939393939e+01 -7.12595164217054e-01 2.01529837369162e-01 1.48943431555047e-01 +-2.33333333333333e+01 -7.17876308107891e-01 1.90810650027497e-01 1.48683703309005e-01 +-2.27272727272727e+01 -7.23157231061198e-01 1.80091462685832e-01 1.48423779056222e-01 +-2.21212121212121e+01 -7.28437947560357e-01 1.69372275344166e-01 1.48163680826540e-01 +-2.15151515151515e+01 -7.31713351978921e-01 1.58838231776999e-01 1.48337985994225e-01 +-2.09090909090909e+01 -7.34245840474427e-01 1.48350486062725e-01 1.48620871862006e-01 +-2.03030303030303e+01 -7.38065551990425e-01 1.37862740348452e-01 1.48903686939429e-01 +-1.96969696969697e+01 -7.32808819200495e-01 1.29918930302428e-01 1.44712603991306e-01 +-1.90909090909091e+01 -7.18361958000880e-01 1.24518912013222e-01 1.36047824693694e-01 +-1.84848484848485e+01 -7.04189587691779e-01 1.19119156714805e-01 1.27383320623159e-01 +-1.78787878787879e+01 -6.90170520790039e-01 1.13719385941933e-01 1.18718587275407e-01 +-1.72727272727273e+01 -6.76245095637824e-01 1.08319367652727e-01 1.10053115983160e-01 +-1.66666666666667e+01 -6.62381424994436e-01 1.02255720988610e-01 1.01387526517949e-01 +-1.60606060606061e+01 -6.48560316531438e-01 9.61448175238969e-02 9.27217646524863e-02 +-1.54545454545455e+01 -6.34969522120538e-01 9.03872009230254e-02 8.40561496211227e-02 +-1.48484848484848e+01 -6.21508539218862e-01 8.48230957038706e-02 7.53901059090511e-02 +-1.42424242424242e+01 -6.08408366025162e-01 7.96630711027307e-02 6.67232674713552e-02 +-1.36363636363636e+01 -5.95447218953895e-01 7.45632229779760e-02 5.80562179472338e-02 +-1.30303030303030e+01 -5.82646323386179e-01 6.95101444417735e-02 4.93879760859292e-02 +-1.24242424242424e+01 -5.70051253619176e-01 6.44104289730139e-02 4.07195611654372e-02 +-1.18181818181818e+01 -5.57661981483822e-01 5.92219660335435e-02 3.20496569255294e-02 +-1.12121212121212e+01 -5.45521148334811e-01 5.38126013913541e-02 2.33792067297271e-02 +-1.06060606060606e+01 -5.33770601268997e-01 4.82803386350898e-02 1.47062382307926e-02 +-1.00000000000000e+01 -5.22536282520595e-01 4.27091715581483e-02 6.03175191196416e-03 +-9.39393939393939e+00 -4.98663010113629e-01 3.97762979408636e-02 1.46216346791845e-03 +-8.78787878787879e+00 -4.74896579071385e-01 3.69498939396144e-02 -3.11443204072278e-03 +-8.18181818181818e+00 -4.50184735644143e-01 3.36609587046423e-02 -7.71668568938825e-03 +-7.57575757575758e+00 -4.16320862490726e-01 3.11984229016655e-02 -1.02342715344042e-02 +-6.96969696969697e+00 -3.78533908672691e-01 2.88846280067247e-02 -1.18586821223915e-02 +-6.36363636363636e+00 -3.41308425879108e-01 2.66987274834274e-02 -1.37039177713602e-02 +-5.75757575757576e+00 -3.03292128777548e-01 2.47793566352644e-02 -1.57278639083592e-02 +-5.15151515151515e+00 -2.63917787982752e-01 2.33543465327187e-02 -1.65422055989149e-02 +-4.54545454545454e+00 -2.22824817551322e-01 2.20950859887883e-02 -1.76054229676369e-02 +-3.93939393939394e+00 -1.80668798888092e-01 2.09756580073103e-02 -1.88443435684976e-02 +-3.33333333333333e+00 -1.34176568044395e-01 2.04804489661257e-02 -2.02207166542285e-02 +-2.72727272727273e+00 -7.19453798936780e-02 2.00079017312406e-02 -2.28911294526880e-02 +-2.12121212121212e+00 7.07606911784324e-03 1.96027557312253e-02 -2.63328024672574e-02 +-1.51515151515152e+00 8.73289871843104e-02 1.94248148430849e-02 -2.91753660865235e-02 +-9.09090909090912e-01 1.68214610603894e-01 1.93209749444206e-02 -3.21126237712362e-02 +-3.03030303030302e-01 2.49847575674565e-01 1.93085263731067e-02 -3.50069460021776e-02 + 3.03030303030302e-01 3.32076661864978e-01 1.92708245709109e-02 -3.78355127682451e-02 + 9.09090909090912e-01 4.14967913083368e-01 1.92564396323649e-02 -4.06506905185218e-02 + 1.51515151515152e+00 4.97503403994561e-01 1.93240509371219e-02 -4.34545183162005e-02 + 2.12121212121212e+00 5.78017026165593e-01 1.94699699516029e-02 -4.63887820732702e-02 + 2.72727272727273e+00 6.57982538458257e-01 1.95636992876711e-02 -4.91776418225647e-02 + 3.33333333333333e+00 7.37634840577441e-01 1.96859030314327e-02 -5.19181781483109e-02 + 3.93939393939394e+00 8.17042150325575e-01 1.99153209631174e-02 -5.45755311911616e-02 + 4.54545454545455e+00 8.95773550489732e-01 2.01574613792028e-02 -5.71758300930519e-02 + 5.15151515151515e+00 9.74202606524190e-01 2.04147221937826e-02 -5.98020954890244e-02 + 5.75757575757576e+00 1.05192610299832e+00 2.06935862917398e-02 -6.22831373010045e-02 + 6.36363636363637e+00 1.12864853703975e+00 2.09894711710230e-02 -6.45992855497388e-02 + 6.96969696969697e+00 1.20469677736454e+00 2.13767147820252e-02 -6.68719079346452e-02 + 7.57575757575757e+00 1.27852391355893e+00 2.18254003510820e-02 -6.92881289021872e-02 + 8.18181818181818e+00 1.34843619913274e+00 2.23379405478464e-02 -7.23998694538348e-02 + 8.78787878787879e+00 1.41389258501910e+00 2.29917029483263e-02 -7.57224146801624e-02 + 9.39393939393939e+00 1.47693105199554e+00 2.42669452043504e-02 -7.90940633281295e-02 + 1.00000000000000e+01 1.53866152751405e+00 2.58158538548453e-02 -8.24968128995006e-02 + 1.06060606060606e+01 1.58175634209111e+00 2.78715872133015e-02 -8.63366627353863e-02 + 1.12121212121212e+01 1.60853428444793e+00 2.99227788852005e-02 -9.25178530036142e-02 + 1.18181818181818e+01 1.62618116680780e+00 3.25599114107023e-02 -9.61254605123986e-02 + 1.24242424242424e+01 1.17081115183266e+00 3.76946916781032e-02 -7.96133950050748e-02 + 1.30303030303030e+01 1.07057266006274e+00 4.25731273306023e-02 -7.63714447703372e-02 + 1.36363636363636e+01 1.07323785139661e+00 4.76558461605604e-02 -7.83786809582152e-02 + 1.42424242424242e+01 1.08209790208772e+00 5.26403136632421e-02 -8.07401047567165e-02 + 1.48484848484848e+01 1.10354986974947e+00 5.77455347083801e-02 -8.32982121847380e-02 + 1.54545454545455e+01 1.13090095347719e+00 6.28922160620656e-02 -8.70718045668990e-02 + 1.60606060606061e+01 1.15290331847775e+00 6.85681445746570e-02 -9.13408073485258e-02 + 1.66666666666667e+01 1.13888783926795e+00 7.88844991137046e-02 -9.76066740175176e-02 + 1.72727272727273e+01 1.12569869109310e+00 8.91882738787458e-02 -1.03672038183508e-01 + 1.78787878787879e+01 1.11348996181680e+00 9.94766732049302e-02 -1.09493916588364e-01 + 1.84848484848485e+01 1.10412272552069e+00 1.09722110128521e-01 -1.14392819645911e-01 + 1.90909090909091e+01 1.09417618957362e+00 1.19712328172831e-01 -1.19171119055800e-01 + 1.96969696969697e+01 1.07815671838533e+00 1.28316705476137e-01 -1.24569996191147e-01 + 2.03030303030303e+01 1.06590918336347e+00 1.37862740348452e-01 -1.28927442015208e-01 + 2.09090909090909e+01 1.05744457824252e+00 1.48350486062725e-01 -1.32240940695518e-01 + 2.15151515151515e+01 1.04897922606013e+00 1.58838231776999e-01 -1.35550005581577e-01 + 2.21212121212121e+01 1.04069744082963e+00 1.69372275344167e-01 -1.38809930873424e-01 + 2.27272727272727e+01 1.03315254333471e+00 1.80091462685832e-01 -1.41886753748031e-01 + 2.33333333333333e+01 1.02560734768900e+00 1.90810650027497e-01 -1.44960808190677e-01 + 2.39393939393939e+01 1.01806183295191e+00 2.01529837369162e-01 -1.48032154260591e-01 + 2.45454545454545e+01 1.01108909354267e+00 2.12442749202814e-01 -1.50974394253646e-01 + 2.51515151515151e+01 1.00417741009351e+00 2.23377185516994e-01 -1.53900389859026e-01 + 2.57575757575758e+01 9.97262895226883e-01 2.34311621831173e-01 -1.56824213640932e-01 + 2.63636363636364e+01 9.90602272243490e-01 2.45364880635039e-01 -1.59691865247193e-01 + 2.69696969696970e+01 9.84107677556836e-01 2.56497366741980e-01 -1.62521495117230e-01 + 2.75757575757576e+01 9.77607274768511e-01 2.67629852848922e-01 -1.65349122555614e-01 + 2.81818181818182e+01 9.71183535418784e-01 2.78816002836960e-01 -1.68157082819057e-01 + 2.87878787878788e+01 9.64945123677017e-01 2.90127357806473e-01 -1.70921894375263e-01 + 2.93939393939394e+01 9.58698873686608e-01 3.01438712775986e-01 -1.73684689615452e-01 + 3.00000000000000e+01 9.52444862477794e-01 3.12750067745499e-01 -1.76445418513927e-01 + 3.30000000000000e+01 9.32757112804349e-01 3.78198211323207e-01 -1.87615870546037e-01 + 3.60000000000000e+01 9.13290569721045e-01 4.44496914459934e-01 -1.99008415557536e-01 + 3.90000000000000e+01 8.93393781094339e-01 5.11597466281430e-01 -2.09904410150492e-01 + 4.20000000000000e+01 8.68886648478033e-01 5.81234011749336e-01 -2.20659088173443e-01 + 4.50000000000000e+01 8.42222962046853e-01 6.52015452980456e-01 -2.31358509305899e-01 + 4.80000000000000e+01 8.13311107256429e-01 7.22744238735752e-01 -2.42008926938194e-01 + 5.10000000000000e+01 7.79848244960539e-01 7.92130709003037e-01 -2.52553412425687e-01 + 5.40000000000000e+01 7.37292615749320e-01 8.58832461999884e-01 -2.62871600790229e-01 + 5.70000000000000e+01 6.94732715144264e-01 9.25533705434717e-01 -2.73198801942233e-01 + 6.00000000000000e+01 6.52167283863280e-01 9.92234694090484e-01 -2.83534193702832e-01 + 6.30000000000000e+01 5.95021513422317e-01 1.04694840689101e+00 -2.92939646889504e-01 + 6.60000000000000e+01 5.37873671092777e-01 1.10166201694156e+00 -3.02353620386315e-01 + 6.90000000000000e+01 4.80723120327637e-01 1.15637562699211e+00 -3.11775458141060e-01 + 7.20000000000000e+01 4.16702853573743e-01 1.19874105282597e+00 -3.20152624301910e-01 + 7.50000000000000e+01 3.49248630212311e-01 1.23493263933526e+00 -3.28012827849872e-01 + 7.80000000000000e+01 2.81792775389929e-01 1.27112464057129e+00 -3.35882005640500e-01 + 8.10000000000000e+01 2.13139309353073e-01 1.29974133374152e+00 -3.42992209540911e-01 + 8.40000000000000e+01 1.42093279928522e-01 1.31320793368439e+00 -3.48577487448998e-01 + 8.70000000000000e+01 7.10465847027829e-02 1.32667463650466e+00 -3.54286237278487e-01 + 9.00000000000000e+01 -3.10317978790605e-07 1.34014122266447e+00 -3.60261329275921e-01 + 9.30000000000000e+01 -4.97202158283082e-02 1.32667462272159e+00 -3.60939509181810e-01 + 9.60000000000000e+01 -9.94402497296761e-02 1.31320797134044e+00 -3.62101276854683e-01 + 9.90000000000000e+01 -1.49160540417765e-01 1.29974121708087e+00 -3.63263116762426e-01 + 1.02000000000000e+02 -1.97224219276773e-01 1.27112446528618e+00 -3.61500175595017e-01 + 1.05000000000000e+02 -2.44458666678294e-01 1.23493287877690e+00 -3.58275028210518e-01 + 1.08000000000000e+02 -2.91693025082505e-01 1.19874087754264e+00 -3.55049870683841e-01 + 1.11000000000000e+02 -3.36512597958186e-01 1.15637515301294e+00 -3.50765979419127e-01 + 1.14000000000000e+02 -3.76501801901982e-01 1.10166216993032e+00 -3.44364638786946e-01 + 1.17000000000000e+02 -4.16489600596796e-01 1.04694876887339e+00 -3.37963575060275e-01 + 1.20000000000000e+02 -4.56476301826173e-01 9.92235135380730e-01 -3.31562852852576e-01 + 1.23000000000000e+02 -4.86270063393777e-01 9.25534146724963e-01 -3.23780752167797e-01 + 1.26000000000000e+02 -5.16059865398949e-01 8.58832903295187e-01 -3.15999386352538e-01 + 1.29000000000000e+02 -5.45846532434262e-01 7.92131150298340e-01 -3.08218654603481e-01 + 1.32000000000000e+02 -5.68769160282536e-01 7.22726946114877e-01 -3.01185530669448e-01 + 1.35000000000000e+02 -5.88252908821619e-01 6.51971519548278e-01 -2.94527284921154e-01 + 1.38000000000000e+02 -6.07728072005134e-01 5.81216719268109e-01 -2.87870702883092e-01 + 1.41000000000000e+02 -6.25312980734950e-01 5.11917113827908e-01 -2.82904694585223e-01 + 1.44000000000000e+02 -6.39116027015019e-01 4.45527909875772e-01 -2.81319615496767e-01 + 1.47000000000000e+02 -6.52900940317335e-01 3.79139090101126e-01 -2.79738043324018e-01 + 1.50000000000000e+02 -6.66670110194854e-01 3.12750462408366e-01 -2.78159839410523e-01 + 1.53000000000000e+02 -6.91423868529968e-01 2.58710851852227e-01 -2.92436611808699e-01 + 1.56000000000000e+02 -7.16139659509821e-01 2.04671414989218e-01 -3.06713727094434e-01 + 1.59000000000000e+02 -7.40824462046985e-01 1.50632267952715e-01 -3.20991093106481e-01 + 1.62000000000000e+02 -6.92523326346939e-01 1.14218878924218e-01 -3.60600316892406e-01 + 1.65000000000000e+02 -6.04090178045220e-01 8.66185179666223e-02 -4.12875574153840e-01 + 1.68000000000000e+02 -5.25703495579730e-01 5.90182887830723e-02 -4.65150066961505e-01 + 1.71000000000000e+02 -4.24060615670435e-01 3.72487259247374e-02 -4.50000513056908e-01 + 1.74000000000000e+02 -2.82706583196469e-01 2.71407679330614e-02 -2.99999717902353e-01 + 1.77000000000000e+02 -1.40374735896749e-01 2.36166297084173e-02 -1.48954519621935e-01 + 1.80000000000000e+02 0.00000000000000e+00 2.33914127688100e-02 0.00000000000000e+00 diff --git a/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_08.dat b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_08.dat new file mode 100644 index 00000000..d72fa625 --- /dev/null +++ b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_08.dat @@ -0,0 +1,254 @@ +! ------------ AirfoilInfo v1.01.x Input File ---------------------------------- +! AeroElasticSE FAST driver +! line +! line +! ------------------------------------------------------------------------------ +DEFAULT InterpOrd ! Interpolation order to use for quasi-steady table lookup {1=linear; 3=cubic spline; "default"} [default=3] +1 NonDimArea ! The non-dimensional area of the airfoil (area/chord^2) (set to 1.0 if unsure or unneeded) +@"NREL-2p8-127_AF08_Coords.txt" NumCoords ! The number of coordinates in the airfoil shape file. Set to zero if coordinates not included. +AF08_BL.txt BL_file ! The file name including the boundary layer characteristics of the profile. Ignored if the aeroacoustic module is not called. +1 NumTabs ! Number of airfoil tables in this file. Each table must have lines for Re and Ctrl. +! ------------------------------------------------------------------------------ +! data for table 1 +! ------------------------------------------------------------------------------ +6.000000 Re ! Reynolds number in millions +0 Ctrl ! Control setting (must be 0 for current AirfoilInfo) +True InclUAdata ! Is unsteady aerodynamics data included in this table? If TRUE, then include 30 UA coefficients below this line +!........................................ +-2.094045 alpha0 ! 0-lift angle of attack, depends on airfoil. +11.810318 alpha1 ! Angle of attack at f=0.7, (approximately the stall angle) for AOA>alpha0. (deg) +-5.789318 alpha2 ! Angle of attack at f=0.7, (approximately the stall angle) for AOA1] +0.000000 S2 ! Constant in the f curve best-fit for AOA> alpha1; by definition it depends on the airfoil. [ignored if UAMod<>1] +0.000000 S3 ! Constant in the f curve best-fit for alpha2<=AOA< alpha0; by definition it depends on the airfoil. [ignored if UAMod<>1] +0.000000 S4 ! Constant in the f curve best-fit for AOA< alpha2; by definition it depends on the airfoil. [ignored if UAMod<>1] +1.434702 Cn1 ! Critical value of C0n at leading edge separation. It should be extracted from airfoil data at a given Mach and Reynolds number. It can be calculated from the static value of Cn at either the break in the pitching moment or the loss of chord force at the onset of stall. It is close to the condition of maximum lift of the airfoil at low Mach numbers. +-0.791051 Cn2 ! As Cn1 for negative AOAs. +Default St_sh ! Strouhal's shedding frequency constant. [default = 0.19] +0.013400 Cd0 ! 2D drag coefficient value at 0-lift. +-0.038790 Cm0 ! 2D pitching moment coefficient about 1/4-chord location, at 0-lift, positive if nose up. [If the aerodynamics coefficients table does not include a column for Cm, this needs to be set to 0.0] +0.000000 k0 ! Constant in the \hat(x)_cp curve best-fit; = (\hat(x)_AC-0.25). [ignored if UAMod<>1] +0.000000 k1 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k2 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k3 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k1_hat ! Constant in the expression of Cc due to leading edge vortex effects. [ignored if UAMod<>1] +Default x_cp_bar ! Constant in the expression of \hat(x)_cp^v. [ignored if UAMod<>1, default = 0.2] +Default UACutout ! Angle of attack above which unsteady aerodynamics are disabled (deg). [Specifying the string "Default" sets UACutout to 45 degrees] +Default filtCutOff ! Cut-off frequency (-3 dB corner frequency) for low-pass filtering the AoA input to UA, as well as the 1st and 2nd derivatives (Hz) [default = 20] +!........................................ +! Table of aerodynamics coefficients +200 NumAlf ! Number of data lines in the following table +! Alpha Cl Cd Cm +! (deg) (-) (-) (-) +-1.80000000000000e+02 0.00000000000000e+00 4.36560269351644e-02 0.00000000000000e+00 +-1.77000000000000e+02 1.35439946882412e-01 4.36560269351644e-02 1.18726131869253e-01 +-1.74000000000000e+02 2.73681807554892e-01 5.19326935053434e-02 2.39999774321882e-01 +-1.71000000000000e+02 4.10523187830625e-01 7.67629649316860e-02 3.60000410445527e-01 +-1.68000000000000e+02 5.20540196449849e-01 1.06183060966195e-01 3.39345685302513e-01 +-1.65000000000000e+02 6.17416589309490e-01 1.37898015734769e-01 2.48364921181521e-01 +-1.62000000000000e+02 7.20366694799217e-01 1.69613333930037e-01 1.57382975358883e-01 +-1.59000000000000e+02 7.79902956443025e-01 2.09395231609251e-01 1.00198616429354e-01 +-1.56000000000000e+02 7.54094985201384e-01 2.65310015371530e-01 1.10341134086108e-01 +-1.53000000000000e+02 7.28273002358664e-01 3.21224917158275e-01 1.20030838658758e-01 +-1.50000000000000e+02 7.02433949228043e-01 3.77139907333099e-01 1.29188534097997e-01 +-1.47000000000000e+02 6.88056994571163e-01 4.45660752601736e-01 1.38937062638940e-01 +-1.44000000000000e+02 6.73672820323352e-01 5.14181705032495e-01 1.48679864311782e-01 +-1.41000000000000e+02 6.59280196399078e-01 5.82702871795152e-01 1.58415928945197e-01 +-1.38000000000000e+02 6.40870225785841e-01 6.54060157601795e-01 1.69647719764598e-01 +-1.35000000000000e+02 6.20451890084054e-01 7.26835497177056e-01 1.81625021280610e-01 +-1.32000000000000e+02 6.00029188829974e-01 7.99611206996042e-01 1.93595285306556e-01 +-1.29000000000000e+02 5.75956737945601e-01 8.70852261041323e-01 2.05770654480656e-01 +-1.26000000000000e+02 5.44590931294051e-01 9.39023996253647e-01 2.18364183904311e-01 +-1.23000000000000e+02 5.13223602126577e-01 1.00719521066899e+00 2.30949738818684e-01 +-1.20000000000000e+02 4.81854438801891e-01 1.07536616469559e+00 2.43526390646390e-01 +-1.17000000000000e+02 4.39681481271308e-01 1.13061446591332e+00 2.54956685887127e-01 +-1.14000000000000e+02 3.97508111898989e-01 1.18586253082399e+00 2.66377239042142e-01 +-1.11000000000000e+02 3.55334297402172e-01 1.24111017367587e+00 2.77786058750497e-01 +-1.08000000000000e+02 3.08037893527830e-01 1.28321205725494e+00 2.87281519675595e-01 +-1.05000000000000e+02 2.58180351390511e-01 1.31874096109859e+00 2.95813196403833e-01 +-1.02000000000000e+02 2.08323097887283e-01 1.35426945781572e+00 3.04327743613626e-01 +-9.90000000000000e+01 1.57576203402918e-01 1.38176151510008e+00 3.11395522027348e-01 +-9.60000000000000e+01 1.05050834785785e-01 1.39318034541842e+00 3.15588655906570e-01 +-9.30000000000000e+01 5.25255582791447e-02 1.40459908850334e+00 3.19756596609520e-01 +-9.00000000000000e+01 3.27826917023240e-07 1.41601778797233e+00 3.23659461316635e-01 +-8.70000000000000e+01 -5.25255045195490e-02 1.40459910019038e+00 3.22945034933183e-01 +-8.40000000000000e+01 -1.05050981658418e-01 1.39318031348883e+00 3.21791611743605e-01 +-8.10000000000000e+01 -1.57575748382869e-01 1.38176161401983e+00 3.20129918962609e-01 +-7.80000000000000e+01 -2.08322856414832e-01 1.35426962988931e+00 3.17048455458342e-01 +-7.50000000000000e+01 -2.58180681242367e-01 1.31874072604392e+00 3.12905041046394e-01 +-7.20000000000000e+01 -3.08037652060678e-01 1.28321222932679e+00 3.08761210418793e-01 +-6.90000000000000e+01 -3.55333932045767e-01 1.24111065228680e+00 3.03514635390291e-01 +-6.60000000000000e+01 -3.97508229824454e-01 1.18586237634021e+00 2.96062481257706e-01 +-6.30000000000000e+01 -4.39681760287162e-01 1.13061410039362e+00 2.88610017991116e-01 +-6.00000000000000e+01 -4.81854646345531e-01 1.07536571368012e+00 2.81157387364500e-01 +-5.70000000000000e+01 -5.13223809656928e-01 1.00719475965353e+00 2.72212286505312e-01 +-5.40000000000000e+01 -5.44591138813060e-01 9.39023545233018e-01 2.63266996912069e-01 +-5.10000000000000e+01 -5.75956945455947e-01 8.70851810020693e-01 2.54321329847841e-01 +-4.80000000000000e+01 -6.01326324662319e-01 7.99654560229442e-01 2.45618131252866e-01 +-4.50000000000000e+01 -6.23695970153485e-01 7.26944601773029e-01 2.37036162995707e-01 +-4.20000000000000e+01 -6.42168713793076e-01 6.54103510491734e-01 2.29439922053861e-01 +-3.90000000000000e+01 -6.59537045517161e-01 5.81899603350932e-01 2.22338894134465e-01 +-3.60000000000000e+01 -6.74166998306598e-01 5.11590826220192e-01 2.16852610379598e-01 +-3.30000000000000e+01 -6.88095062911521e-01 4.43295420850299e-01 2.13321658336198e-01 +-3.00000000000000e+01 -7.02434061164880e-01 3.77139487001304e-01 2.11949178572412e-01 +-2.93939393939394e+01 -7.06130482490463e-01 3.64852362744942e-01 2.12237605316701e-01 +-2.87878787878788e+01 -7.09824479328829e-01 3.52565238488579e-01 2.12555391583848e-01 +-2.81818181818182e+01 -7.13516027506550e-01 3.40278114232216e-01 2.12872847967098e-01 +-2.75757575757576e+01 -7.17530381434993e-01 3.28305985630029e-01 2.13597061869978e-01 +-2.69696969696970e+01 -7.21682227375692e-01 3.16468866746567e-01 2.14495479961637e-01 +-2.63636363636364e+01 -7.25832258736785e-01 3.04631747863105e-01 2.15393660836009e-01 +-2.57575757575758e+01 -7.30267770470675e-01 2.92993562362201e-01 2.16593296530334e-01 +-2.51515151515151e+01 -7.35132964149189e-01 2.81653730571187e-01 2.18245185960105e-01 +-2.45454545454545e+01 -7.39997274048644e-01 2.70313898780173e-01 2.19896919526772e-01 +-2.39393939393939e+01 -7.44966676859083e-01 2.59028163484346e-01 2.21648566366930e-01 +-2.33333333333333e+01 -7.50889197184390e-01 2.48229307118538e-01 2.24300599299510e-01 +-2.27272727272727e+01 -7.56811618414165e-01 2.37430450752730e-01 2.26952544318588e-01 +-2.21212121212121e+01 -7.62733947044537e-01 2.26631594386922e-01 2.29604411305050e-01 +-2.15151515151515e+01 -7.65543180919198e-01 2.16298421341179e-01 2.33347719604617e-01 +-2.09090909090909e+01 -7.67159390551658e-01 2.06081699080272e-01 2.37363936868452e-01 +-2.03030303030303e+01 -7.70989589899503e-01 1.95864976819365e-01 2.41380122381193e-01 +-1.96969696969697e+01 -7.66408855179284e-01 1.86713082311620e-01 2.37110565273848e-01 +-1.90909090909091e+01 -7.53224334899666e-01 1.78625955319317e-01 2.24555711213706e-01 +-1.84848484848485e+01 -7.40515247767467e-01 1.70539222184923e-01 2.12001402771163e-01 +-1.78787878787879e+01 -7.28073414237448e-01 1.62452465875814e-01 1.99446889701465e-01 +-1.72727272727273e+01 -7.15796412819352e-01 1.54365338883510e-01 1.86891340465851e-01 +-1.66666666666667e+01 -7.03628403601917e-01 1.45137051028637e-01 1.74335949867985e-01 +-1.60606060606061e+01 -6.91536071334431e-01 1.35827440633388e-01 1.61780655103707e-01 +-1.54545454545455e+01 -6.79841375439502e-01 1.27125362674088e-01 1.49225873196518e-01 +-1.48484848484848e+01 -6.68371976472640e-01 1.18756044019379e-01 1.36670824522160e-01 +-1.42424242424242e+01 -6.57525266337486e-01 1.11081575507249e-01 1.24115046890632e-01 +-1.36363636363636e+01 -6.46919349317121e-01 1.03510536591038e-01 1.11559472566631e-01 +-1.30303030303030e+01 -6.36590196575789e-01 9.60197655285123e-02 9.90027923089362e-02 +-1.24242424242424e+01 -6.26616545201912e-01 8.84489364835728e-02 8.64466304336154e-02 +-1.18181818181818e+01 -6.16997647064756e-01 8.07255969659771e-02 7.38892790664918e-02 +-1.12121212121212e+01 -6.07806438992942e-01 7.26223306995905e-02 6.13323781273887e-02 +-1.06060606060606e+01 -5.99288567453162e-01 6.43078358166966e-02 4.87732017593027e-02 +-1.00000000000000e+01 -5.91657873003445e-01 5.59263606591254e-02 3.62141784693746e-02 +-9.39393939393939e+00 -5.79058163807746e-01 4.91379422584400e-02 2.49867487590630e-02 +-8.78787878787879e+00 -5.66700483456983e-01 4.25327427253251e-02 1.37556766416755e-02 +-8.18181818181818e+00 -5.52767057263263e-01 3.51385027365045e-02 2.51431078401171e-03 +-7.57575757575758e+00 -5.16152487631087e-01 3.07167300167049e-02 -3.52520860243561e-03 +-6.96969696969697e+00 -4.69757056162087e-01 2.73460615848954e-02 -7.35433309173912e-03 +-6.36363636363636e+00 -4.23157901477119e-01 2.40466853818601e-02 -1.16480887450771e-02 +-5.75757575757576e+00 -3.74765829542321e-01 2.11022048511000e-02 -1.59084513723056e-02 +-5.15151515151515e+00 -3.23413692430681e-01 1.89550579096399e-02 -1.86750851344994e-02 +-4.54545454545454e+00 -2.68547626763533e-01 1.70622389773778e-02 -2.19719612773405e-02 +-3.93939393939394e+00 -2.11994257260558e-01 1.53692119559176e-02 -2.56157244462441e-02 +-3.33333333333333e+00 -1.48415934878880e-01 1.48139917958905e-02 -2.94968023177144e-02 +-2.72727272727273e+00 -7.89769276979072e-02 1.41624540467447e-02 -3.39437653144343e-02 +-2.12121212121212e+00 -3.46478095391404e-03 1.34145873263993e-02 -3.86035781138906e-02 +-1.51515151515152e+00 7.38291063274909e-02 1.30921930075161e-02 -4.27533487199522e-02 +-9.09090909090912e-01 1.51829760730163e-01 1.28923820998857e-02 -4.69054889010057e-02 +-3.03030303030302e-01 2.30822308320161e-01 1.28050693423605e-02 -5.10801102705995e-02 + 3.03030303030302e-01 3.10463730114934e-01 1.27477575306067e-02 -5.50677649278274e-02 + 9.09090909090912e-01 3.90790263359822e-01 1.27353987638778e-02 -5.88795212672597e-02 + 1.51515151515152e+00 4.71284233730724e-01 1.28776954822189e-02 -6.27273016180439e-02 + 2.12121212121212e+00 5.50963097343411e-01 1.30675735894997e-02 -6.64832475878559e-02 + 2.72727272727273e+00 6.30138935816981e-01 1.32424674678596e-02 -6.95217238202173e-02 + 3.33333333333333e+00 7.08536320290482e-01 1.34717732475649e-02 -7.23228820759458e-02 + 3.93939393939394e+00 7.86307858387585e-01 1.38172159080549e-02 -7.49142757271172e-02 + 4.54545454545455e+00 8.62388339964567e-01 1.42557288224049e-02 -7.75040470102574e-02 + 5.15151515151515e+00 9.37700928676955e-01 1.47059776016534e-02 -8.00049921252249e-02 + 5.75757575757576e+00 1.01125073389474e+00 1.51614417050010e-02 -8.21454604598515e-02 + 6.36363636363637e+00 1.08227624065879e+00 1.57108190803841e-02 -8.39835694506992e-02 + 6.96969696969697e+00 1.15161256120026e+00 1.63448211385627e-02 -8.56439571000181e-02 + 7.57575757575757e+00 1.21596411426272e+00 1.71676404929355e-02 -8.74082304182359e-02 + 8.18181818181818e+00 1.27673300509297e+00 1.80775111046661e-02 -8.94455339298536e-02 + 8.78787878787879e+00 1.33119115050654e+00 1.91750329509376e-02 -9.16003178554933e-02 + 9.39393939393939e+00 1.37956425338417e+00 2.13859354652657e-02 -9.38392678971121e-02 + 1.00000000000000e+01 1.42465603147829e+00 2.40167211153884e-02 -9.61318882807184e-02 + 1.06060606060606e+01 1.44856679840724e+00 2.73518951987084e-02 -9.83269145446295e-02 + 1.12121212121212e+01 1.45643493495683e+00 3.11907783963854e-02 -1.01693563008612e-01 + 1.18181818181818e+01 1.44145511321968e+00 3.67776864017581e-02 -1.04240570768266e-01 + 1.24242424242424e+01 1.25811612577190e+00 4.49502463857501e-02 -9.87981028722830e-02 + 1.30303030303030e+01 1.21783548130362e+00 5.37917825568218e-02 -9.72024540714103e-02 + 1.36363636363636e+01 1.20160458150153e+00 6.40421590933513e-02 -9.82023678961166e-02 + 1.42424242424242e+01 1.18813191525126e+00 7.46618265741957e-02 -9.95181720845514e-02 + 1.48484848484848e+01 1.18027423785320e+00 8.60251229889524e-02 -1.01193555150372e-01 + 1.54545454545455e+01 1.17877779387270e+00 9.81117465457450e-02 -1.05541629489454e-01 + 1.60606060606061e+01 1.17689322444726e+00 1.10556666678342e-01 -1.10785671275185e-01 + 1.66666666666667e+01 1.16581038309829e+00 1.24057053255380e-01 -1.18134261648867e-01 + 1.72727272727273e+01 1.15665660147017e+00 1.37525823660165e-01 -1.25046831531383e-01 + 1.78787878787879e+01 1.14984732933414e+00 1.50955951675739e-01 -1.31427188552528e-01 + 1.84848484848485e+01 1.14985357005765e+00 1.64278673861716e-01 -1.35546000357850e-01 + 1.90909090909091e+01 1.14897293619198e+00 1.76960001690690e-01 -1.39369242924789e-01 + 1.96969696969697e+01 1.13396288213762e+00 1.86157753963698e-01 -1.44719855669495e-01 + 2.03030303030303e+01 1.12113454332556e+00 1.95864976819365e-01 -1.49461918843513e-01 + 2.09090909090909e+01 1.11049287841322e+00 2.06081699080272e-01 -1.53594296036503e-01 + 2.15151515151515e+01 1.09985087842677e+00 2.16298421341179e-01 -1.57724684571442e-01 + 2.21212121212121e+01 1.08964494555376e+00 2.26631594386922e-01 -1.61741842424593e-01 + 2.27272727272727e+01 1.08118409226682e+00 2.37430450752730e-01 -1.65312206684248e-01 + 2.33333333333333e+01 1.07272310525245e+00 2.48229307118538e-01 -1.68881329238900e-01 + 2.39393939393939e+01 1.06426197511829e+00 2.59028163484346e-01 -1.72449237026485e-01 + 2.45454545454545e+01 1.05716247952044e+00 2.70313898780173e-01 -1.75700716715067e-01 + 2.51515151515151e+01 1.05021311424356e+00 2.81653730571187e-01 -1.78916186478768e-01 + 2.57575757575758e+01 1.04326247901123e+00 2.92993562362201e-01 -1.82130682130006e-01 + 2.63636363636364e+01 1.03692547814336e+00 3.04631747863105e-01 -1.85209085023971e-01 + 2.69696969696970e+01 1.03099616857058e+00 3.16468866746567e-01 -1.88196490642796e-01 + 2.75757575757576e+01 1.02506425393147e+00 3.28305985630029e-01 -1.91182998125262e-01 + 2.81818181818182e+01 1.01932894884137e+00 3.40278114232216e-01 -1.94124420358041e-01 + 2.87878787878788e+01 1.01405525818665e+00 3.52565238488579e-01 -1.96961880499345e-01 + 2.93939393939394e+01 1.00877805189828e+00 3.64852362744942e-01 -1.99798436276836e-01 + 3.00000000000000e+01 1.00349736452608e+00 3.77139487001304e-01 -2.02634065252844e-01 + 3.30000000000000e+01 9.82998715735978e-01 4.43295420850300e-01 -2.15352590816283e-01 + 3.60000000000000e+01 9.63089651383735e-01 5.11590826220192e-01 -2.27863925187279e-01 + 3.90000000000000e+01 9.42175986921238e-01 5.81899603350932e-01 -2.39321618575565e-01 + 4.20000000000000e+01 9.17369367761984e-01 6.54103510491734e-01 -2.50662792778012e-01 + 4.50000000000000e+01 8.90994844258789e-01 7.26944601773029e-01 -2.61985791102602e-01 + 4.80000000000000e+01 8.59052634531658e-01 7.99654560229442e-01 -2.73143035398585e-01 + 5.10000000000000e+01 8.22819956247608e-01 8.70851810020694e-01 -2.84140610804423e-01 + 5.40000000000000e+01 7.78010344233567e-01 9.39023545233018e-01 -2.94794033259472e-01 + 5.70000000000000e+01 7.33199012906027e-01 1.00719475965353e+00 -3.05462909314392e-01 + 6.00000000000000e+01 6.88385299195316e-01 1.07536571368012e+00 -3.16145847013128e-01 + 6.30000000000000e+01 6.28130235918108e-01 1.13061410039362e+00 -3.25620798502509e-01 + 6.60000000000000e+01 5.67874167049533e-01 1.18586237634021e+00 -3.35110403637996e-01 + 6.90000000000000e+01 5.07616883385694e-01 1.24111065228680e+00 -3.44613531015476e-01 + 7.20000000000000e+01 4.40053035872077e-01 1.28321222932679e+00 -3.52880607742317e-01 + 7.50000000000000e+01 3.68836397224492e-01 1.31874072604392e+00 -3.60538886626655e-01 + 7.80000000000000e+01 2.97618557438900e-01 1.35426962988931e+00 -3.68212529205940e-01 + 8.10000000000000e+01 2.25125798524460e-01 1.38176161401983e+00 -3.75046689565342e-01 + 8.40000000000000e+01 1.50084444920197e-01 1.39318031348883e+00 -3.80189854624853e-01 + 8.70000000000000e+01 7.50422088870966e-02 1.40459910019038e+00 -3.85401065327424e-01 + 9.00000000000000e+01 -3.27826917250672e-07 1.41601778797233e+00 -3.90743940003956e-01 + 9.30000000000000e+01 -5.25255582791447e-02 1.40459908850334e+00 -3.92409982314967e-01 + 9.60000000000000e+01 -1.05050834785786e-01 1.39318034541842e+00 -3.94293016797664e-01 + 9.90000000000000e+01 -1.57576203402918e-01 1.38176151510008e+00 -3.96176174609728e-01 + 1.02000000000000e+02 -2.08323097887283e-01 1.35426945781572e+00 -3.94964753048719e-01 + 1.05000000000000e+02 -2.58180351390512e-01 1.31874096109859e+00 -3.92206337784692e-01 + 1.08000000000000e+02 -3.08037893527830e-01 1.28321205725494e+00 -3.89447790562342e-01 + 1.11000000000000e+02 -3.55334297402172e-01 1.24111017367587e+00 -3.85534983800253e-01 + 1.14000000000000e+02 -3.97508111898989e-01 1.18586253082399e+00 -3.79313668806810e-01 + 1.17000000000000e+02 -4.39681481271308e-01 1.13061446591332e+00 -3.73092768861011e-01 + 1.20000000000000e+02 -4.81854438801891e-01 1.07536616469558e+00 -3.66872427068639e-01 + 1.23000000000000e+02 -5.13223602126577e-01 1.00719521066899e+00 -3.59027141872641e-01 + 1.26000000000000e+02 -5.44590931294051e-01 9.39023996253647e-01 -3.51183092578474e-01 + 1.29000000000000e+02 -5.75956737945602e-01 8.70852261041322e-01 -3.43340078183588e-01 + 1.32000000000000e+02 -6.00029188829974e-01 7.99611206996042e-01 -3.36135466500916e-01 + 1.35000000000000e+02 -6.20451890084054e-01 7.26835497177056e-01 -3.29251904114765e-01 + 1.38000000000000e+02 -6.40870225785841e-01 6.54060157601795e-01 -3.22371150094234e-01 + 1.41000000000000e+02 -6.59280196399078e-01 5.82702871795151e-01 -3.17195017404215e-01 + 1.44000000000000e+02 -6.73672820323352e-01 5.14181705032495e-01 -3.15427742312397e-01 + 1.47000000000000e+02 -6.88056994571163e-01 4.45660752601736e-01 -3.13666489886140e-01 + 1.50000000000000e+02 -7.02433949228043e-01 3.77139907333099e-01 -3.11911025372031e-01 + 1.53000000000000e+02 -7.28273002358664e-01 3.21224917158276e-01 -3.26779546578991e-01 + 1.56000000000000e+02 -7.54094985201384e-01 2.65310015371530e-01 -3.41648669551904e-01 + 1.59000000000000e+02 -7.79902956443025e-01 2.09395231609251e-01 -3.56518297584456e-01 + 1.62000000000000e+02 -7.15623711897387e-01 1.69995730690300e-01 -3.89180151768352e-01 + 1.65000000000000e+02 -6.04668180255573e-01 1.38854010867083e-01 -4.30738080965074e-01 + 1.68000000000000e+02 -5.04633128784701e-01 1.07712184204155e-01 -4.72295103043239e-01 + 1.71000000000000e+02 -3.90299886270968e-01 7.84829800637506e-02 -4.50000513056908e-01 + 1.74000000000000e+02 -2.60199626255756e-01 5.30791102629704e-02 -2.99999717902353e-01 + 1.77000000000000e+02 -1.28700931105444e-01 4.42220543974298e-02 -1.48407664836567e-01 + 1.80000000000000e+02 0.00000000000000e+00 4.36560269351644e-02 0.00000000000000e+00 diff --git a/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_09.dat b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_09.dat new file mode 100644 index 00000000..709a0e40 --- /dev/null +++ b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_09.dat @@ -0,0 +1,254 @@ +! ------------ AirfoilInfo v1.01.x Input File ---------------------------------- +! AeroElasticSE FAST driver +! line +! line +! ------------------------------------------------------------------------------ +DEFAULT InterpOrd ! Interpolation order to use for quasi-steady table lookup {1=linear; 3=cubic spline; "default"} [default=3] +1 NonDimArea ! The non-dimensional area of the airfoil (area/chord^2) (set to 1.0 if unsure or unneeded) +@"NREL-2p8-127_AF09_Coords.txt" NumCoords ! The number of coordinates in the airfoil shape file. Set to zero if coordinates not included. +AF09_BL.txt BL_file ! The file name including the boundary layer characteristics of the profile. Ignored if the aeroacoustic module is not called. +1 NumTabs ! Number of airfoil tables in this file. Each table must have lines for Re and Ctrl. +! ------------------------------------------------------------------------------ +! data for table 1 +! ------------------------------------------------------------------------------ +6.000000 Re ! Reynolds number in millions +0 Ctrl ! Control setting (must be 0 for current AirfoilInfo) +True InclUAdata ! Is unsteady aerodynamics data included in this table? If TRUE, then include 30 UA coefficients below this line +!........................................ +-2.060385 alpha0 ! 0-lift angle of attack, depends on airfoil. +11.208140 alpha1 ! Angle of attack at f=0.7, (approximately the stall angle) for AOA>alpha0. (deg) +-7.861323 alpha2 ! Angle of attack at f=0.7, (approximately the stall angle) for AOA1] +0.000000 S2 ! Constant in the f curve best-fit for AOA> alpha1; by definition it depends on the airfoil. [ignored if UAMod<>1] +0.000000 S3 ! Constant in the f curve best-fit for alpha2<=AOA< alpha0; by definition it depends on the airfoil. [ignored if UAMod<>1] +0.000000 S4 ! Constant in the f curve best-fit for AOA< alpha2; by definition it depends on the airfoil. [ignored if UAMod<>1] +1.367424 Cn1 ! Critical value of C0n at leading edge separation. It should be extracted from airfoil data at a given Mach and Reynolds number. It can be calculated from the static value of Cn at either the break in the pitching moment or the loss of chord force at the onset of stall. It is close to the condition of maximum lift of the airfoil at low Mach numbers. +-0.824883 Cn2 ! As Cn1 for negative AOAs. +Default St_sh ! Strouhal's shedding frequency constant. [default = 0.19] +0.010934 Cd0 ! 2D drag coefficient value at 0-lift. +-0.049324 Cm0 ! 2D pitching moment coefficient about 1/4-chord location, at 0-lift, positive if nose up. [If the aerodynamics coefficients table does not include a column for Cm, this needs to be set to 0.0] +0.000000 k0 ! Constant in the \hat(x)_cp curve best-fit; = (\hat(x)_AC-0.25). [ignored if UAMod<>1] +0.000000 k1 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k2 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k3 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k1_hat ! Constant in the expression of Cc due to leading edge vortex effects. [ignored if UAMod<>1] +Default x_cp_bar ! Constant in the expression of \hat(x)_cp^v. [ignored if UAMod<>1, default = 0.2] +Default UACutout ! Angle of attack above which unsteady aerodynamics are disabled (deg). [Specifying the string "Default" sets UACutout to 45 degrees] +Default filtCutOff ! Cut-off frequency (-3 dB corner frequency) for low-pass filtering the AoA input to UA, as well as the 1st and 2nd derivatives (Hz) [default = 20] +!........................................ +! Table of aerodynamics coefficients +200 NumAlf ! Number of data lines in the following table +! Alpha Cl Cd Cm +! (deg) (-) (-) (-) +-1.80000000000000e+02 0.00000000000000e+00 5.31472191671717e-02 0.00000000000000e+00 +-1.77000000000000e+02 1.29495037060763e-01 5.31472191671717e-02 1.18521230701205e-01 +-1.74000000000000e+02 2.62196549024508e-01 6.37579530831230e-02 2.39999774321882e-01 +-1.71000000000000e+02 3.93295149394492e-01 9.55905031721947e-02 3.60000410445527e-01 +-1.68000000000000e+02 5.10233340661308e-01 1.28558250585849e-01 3.26000611777352e-01 +-1.65000000000000e+02 6.19785379304123e-01 1.62093583412369e-01 2.15002393125294e-01 +-1.62000000000000e+02 7.31395834011373e-01 1.95629300525583e-01 1.04002855069395e-01 +-1.59000000000000e+02 7.97042839057236e-01 2.36917620123939e-01 3.50287462844128e-02 +-1.56000000000000e+02 7.70832295867696e-01 2.93710882428943e-01 5.00110113837699e-02 +-1.53000000000000e+02 7.44620920477827e-01 3.50504182292723e-01 6.48349471240901e-02 +-1.50000000000000e+02 7.18408694438638e-01 4.07297530590864e-01 7.94722317169135e-02 +-1.47000000000000e+02 7.03823896258865e-01 4.76817027337738e-01 9.22485232622368e-02 +-1.44000000000000e+02 6.89238523528509e-01 5.46336591473471e-01 1.05021570591302e-01 +-1.41000000000000e+02 6.74652275680612e-01 6.15856290391738e-01 1.17790814864596e-01 +-1.38000000000000e+02 6.55921766878216e-01 6.88177317217559e-01 1.31322598661476e-01 +-1.35000000000000e+02 6.35119149734577e-01 7.61899002314359e-01 1.45235182430339e-01 +-1.32000000000000e+02 6.14315531955484e-01 8.35620937733996e-01 1.59144670993128e-01 +-1.29000000000000e+02 5.89758365423619e-01 9.07722303996263e-01 1.73171416661612e-01 +-1.26000000000000e+02 5.57694365436177e-01 9.76582524253020e-01 1.87436089134836e-01 +-1.23000000000000e+02 5.25630147618883e-01 1.04544221845313e+00 2.01697660743594e-01 +-1.20000000000000e+02 4.93565771807661e-01 1.11430164963474e+00 2.15955995381730e-01 +-1.17000000000000e+02 4.50397682635010e-01 1.16980036934638e+00 2.29069583999682e-01 +-1.14000000000000e+02 4.07229711397332e-01 1.22529885093775e+00 2.42179581353683e-01 +-1.11000000000000e+02 3.64062034832866e-01 1.28079690855731e+00 2.55285105310821e-01 +-1.08000000000000e+02 3.15627063533621e-01 1.32277521883958e+00 2.66511224315401e-01 +-1.05000000000000e+02 2.64558413703211e-01 1.35799355250651e+00 2.76794753835721e-01 +-1.02000000000000e+02 2.13490336137694e-01 1.39321148260576e+00 2.87071098135651e-01 +-9.90000000000000e+01 1.61500486209697e-01 1.42017677477570e+00 2.95908817817940e-01 +-9.60000000000000e+01 1.07667090348450e-01 1.43063643362188e+00 3.01875969512173e-01 +-9.30000000000000e+01 5.38337094334587e-02 1.44109601256217e+00 3.07830613812683e-01 +-9.00000000000000e+01 3.35991459655313e-07 1.45155555155023e+00 3.13757307492905e-01 +-8.70000000000000e+01 -5.38336543349781e-02 1.44109602326751e+00 3.15792074690342e-01 +-8.40000000000000e+01 -1.07667240878618e-01 1.43063640437435e+00 3.17709664434913e-01 +-8.10000000000000e+01 -1.61500019858388e-01 1.42017686538628e+00 3.19427985605789e-01 +-7.80000000000000e+01 -2.13490088801890e-01 1.39321165317520e+00 3.18443936149184e-01 +-7.50000000000000e+01 -2.64558751566886e-01 1.35799331950653e+00 3.16050829869962e-01 +-7.20000000000000e+01 -3.15626816200455e-01 1.32277538940729e+00 3.13657156553441e-01 +-6.90000000000000e+01 -3.64061660870620e-01 1.28079738933759e+00 3.10049989411700e-01 +-6.60000000000000e+01 -4.07229832102981e-01 1.22529869575376e+00 3.04015735248115e-01 +-6.30000000000000e+01 -4.50397968233045e-01 1.16980000216993e+00 2.97981084772964e-01 +-6.00000000000000e+01 -4.93565983944208e-01 1.11430119406435e+00 2.91946220973731e-01 +-5.70000000000000e+01 -5.25630359754821e-01 1.04544176288274e+00 2.84141782265212e-01 +-5.40000000000000e+01 -5.57694577570126e-01 9.76582068677410e-01 2.76337115591071e-01 +-5.10000000000000e+01 -5.89758577557172e-01 9.07721848420653e-01 2.68531992982216e-01 +-4.80000000000000e+01 -6.15975377464480e-01 8.35676496789876e-01 2.60891044708829e-01 +-4.50000000000000e+01 -6.39268597360940e-01 7.62038630661659e-01 2.53332180964662e-01 +-4.20000000000000e+01 -6.57581661720133e-01 6.88232875834521e-01 2.47037064737753e-01 +-3.90000000000000e+01 -6.74980379108277e-01 6.14826511890619e-01 2.41247071396765e-01 +-3.60000000000000e+01 -6.89869193378202e-01 5.43015121244335e-01 2.37267768231330e-01 +-3.30000000000000e+01 -7.03872456392545e-01 4.73784534746912e-01 2.35795153182948e-01 +-3.00000000000000e+01 -7.18408799575845e-01 4.07297098236698e-01 2.37089771150360e-01 +-2.93939393939394e+01 -7.21762686347836e-01 3.94552959906465e-01 2.38090915530434e-01 +-2.87878787878788e+01 -7.25116462207148e-01 3.81808821576231e-01 2.39093403016499e-01 +-2.81818181818182e+01 -7.28470126047924e-01 3.69064683245998e-01 2.40095875411411e-01 +-2.75757575757576e+01 -7.32236853727248e-01 3.56724431468315e-01 2.41620187509530e-01 +-2.69696969696970e+01 -7.36180584373604e-01 3.44557288776848e-01 2.43368158185924e-01 +-2.63636363636364e+01 -7.40124232008641e-01 3.32390146085381e-01 2.45116118010372e-01 +-2.57575757575758e+01 -7.44432056142082e-01 3.20478002655761e-01 2.47250782325627e-01 +-2.51515151515151e+01 -7.49286130044737e-01 3.08948298688103e-01 2.49965419735941e-01 +-2.45454545454545e+01 -7.54140163517274e-01 2.97418594720445e-01 2.52680050016007e-01 +-2.39393939393939e+01 -7.59128300719057e-01 2.85958242769248e-01 2.55522930540395e-01 +-2.33333333333333e+01 -7.65323729613723e-01 2.75122072393073e-01 2.59520140578325e-01 +-2.27272727272727e+01 -7.71519153975079e-01 2.64285902016898e-01 2.63517346594489e-01 +-2.21212121212121e+01 -7.77714574100304e-01 2.53449731640723e-01 2.67514549040905e-01 +-2.15151515151515e+01 -7.83978195814861e-01 2.43210638882764e-01 2.72910891584855e-01 +-2.09090909090909e+01 -7.90117542155355e-01 2.33120853936042e-01 2.78657108165319e-01 +-2.03030303030303e+01 -7.97012109620063e-01 2.23031068989321e-01 2.84403323293269e-01 +-1.96969696969697e+01 -7.95415736248302e-01 2.13313352612748e-01 2.80089060137697e-01 +-1.90909090909091e+01 -7.85263277790639e-01 2.03967683758259e-01 2.65714886768838e-01 +-1.84848484848485e+01 -7.75273314466664e-01 1.94622470054976e-01 2.51341410437202e-01 +-1.78787878787879e+01 -7.65374889035412e-01 1.85277229570461e-01 2.36967769403479e-01 +-1.72727272727273e+01 -7.55533108229545e-01 1.75931560715972e-01 2.22592985180729e-01 +-1.66666666666667e+01 -7.45728795354525e-01 1.66196420256137e-01 2.08218526695132e-01 +-1.60606060606061e+01 -7.35950554364156e-01 1.56433343834581e-01 1.93844333165442e-01 +-1.54545454545455e+01 -7.26308463193755e-01 1.46878222014310e-01 1.79470874697127e-01 +-1.48484848484848e+01 -7.16743375686355e-01 1.37436585788465e-01 1.65097285434163e-01 +-1.42424242424242e+01 -7.07390619723189e-01 1.28231667233805e-01 1.50723069814813e-01 +-1.36363636363636e+01 -6.98120667001908e-01 1.19062253074563e-01 1.36349337872941e-01 +-1.30303030303030e+01 -6.88944298853437e-01 1.09919099684084e-01 1.21974646106258e-01 +-1.24242424242424e+01 -6.79890334514997e-01 1.00749731941577e-01 1.07600926861901e-01 +-1.18181818181818e+01 -6.70956348082078e-01 9.15279934171627e-02 9.32263230029353e-02 +-1.12121212121212e+01 -6.62168843237812e-01 8.21771971589323e-02 7.88528466356555e-02 +-1.06060606060606e+01 -6.53611277615254e-01 7.27538640183303e-02 6.44774855298434e-02 +-1.00000000000000e+01 -6.45356230550116e-01 6.33080422182624e-02 5.01034327127313e-02 +-9.39393939393939e+00 -6.36593332900123e-01 5.41963669816850e-02 3.57833738354860e-02 +-8.78787878787879e+00 -6.27918256833836e-01 4.51475416350120e-02 2.14623968040231e-02 +-8.18181818181818e+00 -6.18711373162793e-01 3.58305294547305e-02 7.14198465445491e-03 +-7.57575757575758e+00 -5.80216174573165e-01 3.01489440959233e-02 -5.19349418320715e-04 +-6.96969696969697e+00 -5.28953354241068e-01 2.59835542019697e-02 -5.35572587261972e-03 +-6.36363636363636e+00 -4.73862537653747e-01 2.22211779699908e-02 -1.07634960479835e-02 +-5.75757575757576e+00 -4.16582198644429e-01 1.90003840623066e-02 -1.61245333665883e-02 +-5.15151515151515e+00 -3.55933513528219e-01 1.66928246089848e-02 -2.10369141861243e-02 +-4.54545454545454e+00 -2.91472100196896e-01 1.47078923324148e-02 -2.64604110668977e-02 +-3.93939393939394e+00 -2.25304889231469e-01 1.29545096367512e-02 -3.21126856296872e-02 +-3.33333333333333e+00 -1.54104000261012e-01 1.23887165275606e-02 -3.78462438825610e-02 +-2.72727272727273e+00 -8.16248041858842e-02 1.17323458130580e-02 -4.34613224548195e-02 +-2.12121212121212e+00 -7.62116470645060e-03 1.09678271146517e-02 -4.88326464973399e-02 +-1.51515151515152e+00 6.83134982557210e-02 1.06280353358650e-02 -5.37247752016293e-02 +-9.09090909090912e-01 1.44916946777653e-01 1.04099760350921e-02 -5.85191375679298e-02 +-3.03030303030302e-01 2.22554588237817e-01 1.02931716210053e-02 -6.33281972284231e-02 + 3.03030303030302e-01 3.00795206874542e-01 1.02297528304907e-02 -6.78528768736416e-02 + 9.09090909090912e-01 3.79652000805070e-01 1.02202988420258e-02 -7.20918564811688e-02 + 1.51515151515152e+00 4.59004148697031e-01 1.03956813611896e-02 -7.63468764323537e-02 + 2.12121212121212e+00 5.38292042421047e-01 1.06036731488726e-02 -8.03761253262362e-02 + 2.72727272727273e+00 6.17098027022441e-01 1.08115944967115e-02 -8.34392709248819e-02 + 3.33333333333333e+00 6.94907654704091e-01 1.10839446374173e-02 -8.61737788284095e-02 + 3.93939393939394e+00 7.71913058145968e-01 1.14291538648689e-02 -8.86385535504365e-02 + 4.54545454545455e+00 8.46751947966220e-01 1.18860333393268e-02 -9.11095009974341e-02 + 5.15151515151515e+00 9.20604899194484e-01 1.23569858194089e-02 -9.34332370032627e-02 + 5.75757575757576e+00 9.92199902524323e-01 1.28374739059253e-02 -9.53033834851092e-02 + 6.36363636363637e+00 1.06055718025240e+00 1.34310891694729e-02 -9.68110066273987e-02 + 6.96969696969697e+00 1.12674988698576e+00 1.40997355822941e-02 -9.80785912470612e-02 + 7.57575757575757e+00 1.18666342902678e+00 1.49845781349695e-02 -9.93714676847982e-02 + 8.18181818181818e+00 1.24314989353240e+00 1.59667211082838e-02 -1.00692149985168e-01 + 8.78787878787879e+00 1.29245687180882e+00 1.71544710253729e-02 -1.02035478870500e-01 + 9.39393939393939e+00 1.33396126311506e+00 1.95659937586037e-02 -1.03407560601880e-01 + 1.00000000000000e+01 1.37126009363817e+00 2.25665763961257e-02 -1.04797915194330e-01 + 1.06060606060606e+01 1.38618576553784e+00 2.67311075620441e-02 -1.05641194801641e-01 + 1.12121212121212e+01 1.38519725174546e+00 3.17846622479086e-02 -1.06586637285388e-01 + 1.18181818181818e+01 1.35493629423442e+00 3.87531354728749e-02 -1.07628263634721e-01 + 1.24242424242424e+01 1.31246186473740e+00 4.83484785906573e-02 -1.07847108308056e-01 + 1.30303030303030e+01 1.28680791441048e+00 5.91170543627865e-02 -1.08015031049527e-01 + 1.36363636363636e+01 1.26172678770879e+00 7.17168991472314e-02 -1.08181203384768e-01 + 1.42424242424242e+01 1.23769104210515e+00 8.49758848909100e-02 -1.08605313713084e-01 + 1.48484848484848e+01 1.21528767185958e+00 9.92702312554880e-02 -1.09411818544650e-01 + 1.54545454545455e+01 1.19968194488222e+00 1.14607265848385e-01 -1.13749735842298e-01 + 1.60606060606061e+01 1.18663909270316e+00 1.30222530116573e-01 -1.19428362054540e-01 + 1.66666666666667e+01 1.17688627348101e+00 1.45214198979932e-01 -1.27285721302187e-01 + 1.72727272727273e+01 1.16956684907482e+00 1.60165335729503e-01 -1.34601993519905e-01 + 1.78787878787879e+01 1.16522099838670e+00 1.75066932714929e-01 -1.41256962609131e-01 + 1.84848484848485e+01 1.16952525051625e+00 1.89830940964302e-01 -1.45028799262795e-01 + 1.90909090909091e+01 1.17284535113364e+00 2.03772684613384e-01 -1.48423774647318e-01 + 1.96969696969697e+01 1.15835573662925e+00 2.13248351672080e-01 -1.53767566099225e-01 + 2.03030303030303e+01 1.14530509433480e+00 2.23031068989321e-01 -1.58704075145085e-01 + 2.09090909090909e+01 1.13369372685470e+00 2.33120853936042e-01 -1.63233228331231e-01 + 2.15151515151515e+01 1.12208234404602e+00 2.43210638882764e-01 -1.67762290542514e-01 + 2.21212121212121e+01 1.11102321657310e+00 2.53449731640723e-01 -1.72148946259134e-01 + 2.27272727272727e+01 1.10217259984565e+00 2.64285902016898e-01 -1.75966397581727e-01 + 2.33333333333333e+01 1.09332197700060e+00 2.75122072393073e-01 -1.79783792100215e-01 + 2.39393939393939e+01 1.08447134760827e+00 2.85958242769248e-01 -1.83601131046924e-01 + 2.45454545454545e+01 1.07734542237668e+00 2.97418594720445e-01 -1.87014968760816e-01 + 2.51515151515151e+01 1.07041107379095e+00 3.08948298688103e-01 -1.90383934992330e-01 + 2.57575757575758e+01 1.06347666710874e+00 3.20478002655761e-01 -1.93752856661258e-01 + 2.63636363636364e+01 1.05732236007864e+00 3.32390146085381e-01 -1.96948677634826e-01 + 2.69696969696970e+01 1.05168813342601e+00 3.44557288776848e-01 -2.00029068561270e-01 + 2.75757575757576e+01 1.04605378759977e+00 3.56724431468315e-01 -2.03109418400795e-01 + 2.81818181818182e+01 1.04067256013258e+00 3.69064683245998e-01 -2.06133132039065e-01 + 2.87878787878788e+01 1.03588202408929e+00 3.81808821576232e-01 -2.09024762045095e-01 + 2.93939393939394e+01 1.03109132721680e+00 3.94552959906465e-01 -2.11916350679321e-01 + 3.00000000000000e+01 1.02630047109565e+00 4.07297098236698e-01 -2.14807896915288e-01 + 3.30000000000000e+01 1.00553169528085e+00 4.73784534746913e-01 -2.28328930073073e-01 + 3.60000000000000e+01 9.85527854289020e-01 5.43015121244335e-01 -2.41378773612232e-01 + 3.90000000000000e+01 9.64256669240620e-01 6.14826511890619e-01 -2.53786845019076e-01 + 4.20000000000000e+01 9.39401732187148e-01 6.88232875834521e-01 -2.65971257965397e-01 + 4.50000000000000e+01 9.13241579977801e-01 7.62038630661659e-01 -2.78098314901201e-01 + 4.80000000000000e+01 8.79965823978363e-01 8.35676496789876e-01 -2.89925721686919e-01 + 5.10000000000000e+01 8.42513311869095e-01 9.07721848420653e-01 -3.01541565653910e-01 + 5.40000000000000e+01 7.96707214786344e-01 9.76582068677410e-01 -3.12725809880497e-01 + 5.70000000000000e+01 7.50901373321919e-01 1.04544176288274e+00 -3.23914976497956e-01 + 6.00000000000000e+01 7.05095590005431e-01 1.11430119406435e+00 -3.35108765012171e-01 + 6.30000000000000e+01 6.43426651348128e-01 1.16980000216993e+00 -3.44954018840384e-01 + 6.60000000000000e+01 5.81757536770671e-01 1.22529869575376e+00 -3.54804262733281e-01 + 6.90000000000000e+01 5.20088366620145e-01 1.28079738933759e+00 -3.64659118816904e-01 + 7.20000000000000e+01 4.50895765482209e-01 1.32277538940729e+00 -3.73183031740474e-01 + 7.50000000000000e+01 3.77941618474775e-01 1.35799331950653e+00 -3.81044639026107e-01 + 7.80000000000000e+01 3.04986617856015e-01 1.39321165317520e+00 -3.88911546743740e-01 + 8.10000000000000e+01 2.30715110532685e-01 1.42017686538628e+00 -3.95889296470916e-01 + 8.40000000000000e+01 1.53810733540745e-01 1.43063640437435e+00 -4.01084668321152e-01 + 8.70000000000000e+01 7.69053727306556e-02 1.44109602326751e+00 -4.06287962899012e-01 + 9.00000000000000e+01 -3.35991459889849e-07 1.45155555155023e+00 -4.11502017960891e-01 + 9.30000000000000e+01 -5.38337094334587e-02 1.44109601256217e+00 -4.13894658825039e-01 + 9.60000000000000e+01 -1.07667090348450e-01 1.43063643362188e+00 -4.16297269931508e-01 + 9.90000000000000e+01 -1.61500486209697e-01 1.42017677477570e+00 -4.18699936551505e-01 + 1.02000000000000e+02 -2.13490336137694e-01 1.39321148260576e+00 -4.17907661987286e-01 + 1.05000000000000e+02 -2.64558413703211e-01 1.35799355250651e+00 -4.15518040952612e-01 + 1.08000000000000e+02 -3.15627063533621e-01 1.32277521883958e+00 -4.13127922002446e-01 + 1.11000000000000e+02 -3.64062034832866e-01 1.28079690855731e+00 -4.09526520529020e-01 + 1.14000000000000e+02 -4.07229711397332e-01 1.22529885093775e+00 -4.03502582615359e-01 + 1.17000000000000e+02 -4.50397682635010e-01 1.16980036934638e+00 -3.97478465589571e-01 + 1.20000000000000e+02 -4.93565771807662e-01 1.11430164963474e+00 -3.91454376227199e-01 + 1.23000000000000e+02 -5.25630147618883e-01 1.04544221845313e+00 -3.83664668897240e-01 + 1.26000000000000e+02 -5.57694365436177e-01 9.76582524253020e-01 -3.75875218145706e-01 + 1.29000000000000e+02 -5.89758365423620e-01 9.07722303996263e-01 -3.68085790436742e-01 + 1.32000000000000e+02 -6.14315531955485e-01 8.35620937733996e-01 -3.60884266412265e-01 + 1.35000000000000e+02 -6.35119149734577e-01 7.61899002314359e-01 -3.53977324090480e-01 + 1.38000000000000e+02 -6.55921766878216e-01 6.88177317217558e-01 -3.47071391893562e-01 + 1.41000000000000e+02 -6.74652275680612e-01 6.15856290391737e-01 -3.41901008734909e-01 + 1.44000000000000e+02 -6.89238523528509e-01 5.46336591473471e-01 -3.40201601680046e-01 + 1.47000000000000e+02 -7.03823896258865e-01 4.76817027337738e-01 -3.38504257224453e-01 + 1.50000000000000e+02 -7.18408694438638e-01 4.07297530590864e-01 -3.36808891109050e-01 + 1.53000000000000e+02 -7.44620920477827e-01 3.50504182292723e-01 -3.52050708459141e-01 + 1.56000000000000e+02 -7.70832295867696e-01 2.93710882428943e-01 -3.67292718466256e-01 + 1.59000000000000e+02 -7.97042839057236e-01 2.36917620123939e-01 -3.82534823044658e-01 + 1.62000000000000e+02 -7.25443285329967e-01 1.96119535360957e-01 -4.10092686634208e-01 + 1.65000000000000e+02 -6.04863200846212e-01 1.63319174643805e-01 -4.43808469577462e-01 + 1.68000000000000e+02 -4.87346219362824e-01 1.30518595329125e-01 -4.77523282896420e-01 + 1.71000000000000e+02 -3.66753120134991e-01 9.77955724163158e-02 -4.50000513056908e-01 + 1.74000000000000e+02 -2.44501896830564e-01 6.52276659281221e-02 -2.99999717902353e-01 + 1.77000000000000e+02 -1.20729578177091e-01 5.38728696135554e-02 -1.48151538376506e-01 + 1.80000000000000e+02 0.00000000000000e+00 5.31472191671717e-02 0.00000000000000e+00 diff --git a/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_10.dat b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_10.dat new file mode 100644 index 00000000..3d0828bf --- /dev/null +++ b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_10.dat @@ -0,0 +1,254 @@ +! ------------ AirfoilInfo v1.01.x Input File ---------------------------------- +! AeroElasticSE FAST driver +! line +! line +! ------------------------------------------------------------------------------ +DEFAULT InterpOrd ! Interpolation order to use for quasi-steady table lookup {1=linear; 3=cubic spline; "default"} [default=3] +1 NonDimArea ! The non-dimensional area of the airfoil (area/chord^2) (set to 1.0 if unsure or unneeded) +@"NREL-2p8-127_AF10_Coords.txt" NumCoords ! The number of coordinates in the airfoil shape file. Set to zero if coordinates not included. +AF10_BL.txt BL_file ! The file name including the boundary layer characteristics of the profile. Ignored if the aeroacoustic module is not called. +1 NumTabs ! Number of airfoil tables in this file. Each table must have lines for Re and Ctrl. +! ------------------------------------------------------------------------------ +! data for table 1 +! ------------------------------------------------------------------------------ +6.000000 Re ! Reynolds number in millions +0 Ctrl ! Control setting (must be 0 for current AirfoilInfo) +True InclUAdata ! Is unsteady aerodynamics data included in this table? If TRUE, then include 30 UA coefficients below this line +!........................................ +-2.064146 alpha0 ! 0-lift angle of attack, depends on airfoil. +11.141003 alpha1 ! Angle of attack at f=0.7, (approximately the stall angle) for AOA>alpha0. (deg) +-8.373634 alpha2 ! Angle of attack at f=0.7, (approximately the stall angle) for AOA1] +0.000000 S2 ! Constant in the f curve best-fit for AOA> alpha1; by definition it depends on the airfoil. [ignored if UAMod<>1] +0.000000 S3 ! Constant in the f curve best-fit for alpha2<=AOA< alpha0; by definition it depends on the airfoil. [ignored if UAMod<>1] +0.000000 S4 ! Constant in the f curve best-fit for AOA< alpha2; by definition it depends on the airfoil. [ignored if UAMod<>1] +1.372191 Cn1 ! Critical value of C0n at leading edge separation. It should be extracted from airfoil data at a given Mach and Reynolds number. It can be calculated from the static value of Cn at either the break in the pitching moment or the loss of chord force at the onset of stall. It is close to the condition of maximum lift of the airfoil at low Mach numbers. +-0.848243 Cn2 ! As Cn1 for negative AOAs. +Default St_sh ! Strouhal's shedding frequency constant. [default = 0.19] +0.010759 Cd0 ! 2D drag coefficient value at 0-lift. +-0.057548 Cm0 ! 2D pitching moment coefficient about 1/4-chord location, at 0-lift, positive if nose up. [If the aerodynamics coefficients table does not include a column for Cm, this needs to be set to 0.0] +0.000000 k0 ! Constant in the \hat(x)_cp curve best-fit; = (\hat(x)_AC-0.25). [ignored if UAMod<>1] +0.000000 k1 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k2 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k3 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k1_hat ! Constant in the expression of Cc due to leading edge vortex effects. [ignored if UAMod<>1] +Default x_cp_bar ! Constant in the expression of \hat(x)_cp^v. [ignored if UAMod<>1, default = 0.2] +Default UACutout ! Angle of attack above which unsteady aerodynamics are disabled (deg). [Specifying the string "Default" sets UACutout to 45 degrees] +Default filtCutOff ! Cut-off frequency (-3 dB corner frequency) for low-pass filtering the AoA input to UA, as well as the 1st and 2nd derivatives (Hz) [default = 20] +!........................................ +! Table of aerodynamics coefficients +200 NumAlf ! Number of data lines in the following table +! Alpha Cl Cd Cm +! (deg) (-) (-) (-) +-1.80000000000000e+02 0.00000000000000e+00 5.30837886627506e-02 0.00000000000000e+00 +-1.77000000000000e+02 1.24966191469559e-01 5.30837886627506e-02 1.18576829157013e-01 +-1.74000000000000e+02 2.52998633091314e-01 6.37003001697374e-02 2.39999774321882e-01 +-1.71000000000000e+02 3.79498286143344e-01 9.55501832215890e-02 3.60000410445527e-01 +-1.68000000000000e+02 4.98757573511548e-01 1.28321372265423e-01 3.22914823147173e-01 +-1.65000000000000e+02 6.15220538714466e-01 1.61553203552249e-01 2.07287957565546e-01 +-1.62000000000000e+02 7.27077094368088e-01 1.94785456665805e-01 9.16599143637722e-02 +-1.59000000000000e+02 7.93230980672808e-01 2.35846387240917e-01 1.84100886242669e-02 +-1.56000000000000e+02 7.68234137241237e-01 2.92564407901613e-01 3.03932586734567e-02 +-1.53000000000000e+02 7.43356372402597e-01 3.49282461855920e-01 4.28162358403718e-02 +-1.50000000000000e+02 7.18478522993120e-01 4.06000562593489e-01 5.56156944862064e-02 +-1.47000000000000e+02 7.03955906925430e-01 4.75651465566945e-01 6.92790833714106e-02 +-1.44000000000000e+02 6.89433035390160e-01 5.45302448258410e-01 8.29503219976363e-02 +-1.41000000000000e+02 6.74909652901486e-01 6.14953590391589e-01 9.66309029164283e-02 +-1.38000000000000e+02 6.56219474668182e-01 6.87418368921680e-01 1.10881678895009e-01 +-1.35000000000000e+02 6.35445907015363e-01 7.61289959942459e-01 1.25418499888186e-01 +-1.32000000000000e+02 6.14671501318397e-01 8.35161838486049e-01 1.39961030153749e-01 +-1.29000000000000e+02 5.90134200485388e-01 9.07415349226177e-01 1.54621277427466e-01 +-1.26000000000000e+02 5.58071091549210e-01 9.76432116678355e-01 1.69509055919750e-01 +-1.23000000000000e+02 5.26007827556163e-01 1.04544835687794e+00 1.84402154814945e-01 +-1.20000000000000e+02 4.93944486037582e-01 1.11446433346109e+00 1.99301684126228e-01 +-1.17000000000000e+02 4.50754244383126e-01 1.17011434599327e+00 2.13130402729061e-01 +-1.14000000000000e+02 4.07564132273452e-01 1.22576411981700e+00 2.26966296053101e-01 +-1.11000000000000e+02 3.64374322762834e-01 1.28141346851316e+00 2.40810540320626e-01 +-1.08000000000000e+02 3.15905431030774e-01 1.32353352870914e+00 2.52837246360334e-01 +-1.05000000000000e+02 2.64796957994024e-01 1.35888884163568e+00 2.63961625640692e-01 +-1.02000000000000e+02 2.13689029593013e-01 1.39424374942488e+00 2.75099894116298e-01 +-9.90000000000000e+01 1.61655412340594e-01 1.42133844008909e+00 2.84836104947235e-01 +-9.60000000000000e+01 1.07770377288908e-01 1.43191233870989e+00 2.91753073560900e-01 +-9.30000000000000e+01 5.38853538885643e-02 1.44248615655205e+00 2.98698830338381e-01 +-9.00000000000000e+01 3.36313787357514e-07 1.45305993400564e+00 3.05684965975821e-01 +-8.70000000000000e+01 -5.38852987372259e-02 1.44248616737432e+00 3.09060154363404e-01 +-8.40000000000000e+01 -1.07770527963470e-01 1.43191230914291e+00 3.12686281197342e-01 +-8.10000000000000e+01 -1.61654945541942e-01 1.42133853168932e+00 3.16767616953733e-01 +-7.80000000000000e+01 -2.13688782064248e-01 1.39424392065773e+00 3.16540498625861e-01 +-7.50000000000000e+01 -2.64797296121353e-01 1.35888860772946e+00 3.14266811229411e-01 +-7.20000000000000e+01 -3.15905183504718e-01 1.32353369994026e+00 3.11992145479124e-01 +-6.90000000000000e+01 -3.64373948609042e-01 1.28141395060407e+00 3.08496020987835e-01 +-6.60000000000000e+01 -4.07564253041044e-01 1.22576396420997e+00 3.02557290547327e-01 +-6.30000000000000e+01 -4.50754530127646e-01 1.17011397781587e+00 2.96617404810894e-01 +-6.00000000000000e+01 -4.93944698166970e-01 1.11446387685501e+00 2.90676423054807e-01 +-5.70000000000000e+01 -5.26008039685552e-01 1.04544790027186e+00 2.82948402317780e-01 +-5.40000000000000e+01 -5.58071303677059e-01 9.76431660067037e-01 2.75218817710457e-01 +-5.10000000000000e+01 -5.90134412613238e-01 9.07414892614858e-01 2.67487195859118e-01 +-4.80000000000000e+01 -6.16349723026200e-01 8.35214742285566e-01 2.59915443758204e-01 +-4.50000000000000e+01 -6.39641228159956e-01 7.61422951679187e-01 2.52421684677788e-01 +-4.20000000000000e+01 -6.57897683242975e-01 6.87471272303016e-01 2.46204422934917e-01 +-3.90000000000000e+01 -6.75245094925222e-01 6.13911269891018e-01 2.40506244340753e-01 +-3.60000000000000e+01 -6.90083088589439e-01 5.41941245231535e-01 2.36695331229210e-01 +-3.30000000000000e+01 -7.04017120189319e-01 4.72583293422338e-01 2.35442916975004e-01 +-3.00000000000000e+01 -7.18478627259844e-01 4.06000129199683e-01 2.37016869904415e-01 +-2.93939393939394e+01 -7.21798350573784e-01 3.93221418404654e-01 2.38091117333048e-01 +-2.87878787878788e+01 -7.25118073887724e-01 3.80442707609625e-01 2.39165364761681e-01 +-2.81818181818182e+01 -7.28437797201663e-01 3.67663996814596e-01 2.40239612190314e-01 +-2.75757575757576e+01 -7.32172588884317e-01 3.55293602246098e-01 2.41847562956378e-01 +-2.69696969696970e+01 -7.36085282271228e-01 3.43098215358386e-01 2.43684263346490e-01 +-2.63636363636364e+01 -7.39997975658139e-01 3.30902828470674e-01 2.45520963736601e-01 +-2.57575757575758e+01 -7.44276884748962e-01 3.18965212168995e-01 2.47753414207092e-01 +-2.51515151515151e+01 -7.49105032044442e-01 3.07414191669665e-01 2.50579397563581e-01 +-2.45454545454545e+01 -7.53933179339923e-01 2.95863171170336e-01 2.53405380920070e-01 +-2.39393939393939e+01 -7.58896243502194e-01 2.84382247917907e-01 2.56362693669404e-01 +-2.33333333333333e+01 -7.65073585586137e-01 2.73532213458751e-01 2.60501996380347e-01 +-2.27272727272727e+01 -7.71250927670079e-01 2.62682178999596e-01 2.64779889466675e-01 +-2.21212121212121e+01 -7.77428269754022e-01 2.51832144540440e-01 2.68945623496597e-01 +-2.15151515151515e+01 -7.90262923140693e-01 2.41893541513143e-01 2.73249028596959e-01 +-2.09090909090909e+01 -8.05906043706644e-01 2.32182854971129e-01 2.77270518618669e-01 +-2.03030303030303e+01 -8.19489198628311e-01 2.22472168429115e-01 2.81192694187527e-01 +-1.96969696969697e+01 -8.24678039235549e-01 2.13080793622121e-01 2.75632215545996e-01 +-1.90909090909091e+01 -8.21619989791241e-01 2.04008712486556e-01 2.60613787847909e-01 +-1.84848484848485e+01 -8.18197356256183e-01 1.95010678250887e-01 2.45586809616841e-01 +-1.78787878787879e+01 -8.14569480885818e-01 1.86007505483073e-01 2.30648571774812e-01 +-1.72727272727273e+01 -8.10814834138077e-01 1.76823863436936e-01 2.15753896541975e-01 +-1.66666666666667e+01 -8.06976123403415e-01 1.68593035533169e-01 2.00859509073193e-01 +-1.60606060606061e+01 -8.03078897629092e-01 1.60454418431078e-01 1.85965357045289e-01 +-1.54545454545455e+01 -7.97000707157957e-01 1.51710915395437e-01 1.71396869835783e-01 +-1.48484848484848e+01 -7.89576615706775e-01 1.42625264033402e-01 1.57006741726859e-01 +-1.42424242424242e+01 -7.78781317063958e-01 1.32791872599405e-01 1.43201565946783e-01 +-1.36363636363636e+01 -7.67357420824222e-01 1.22849813294929e-01 1.29490112449071e-01 +-1.30303030303030e+01 -7.55422617396779e-01 1.12823830974163e-01 1.15644996580170e-01 +-1.24242424242424e+01 -7.42969206287619e-01 1.02890282642851e-01 1.01449124172212e-01 +-1.18181818181818e+01 -7.30244644590558e-01 9.31176217950954e-02 8.72464359531469e-02 +-1.12121212121212e+01 -7.17231543580288e-01 8.37383245063512e-02 7.30648930269649e-02 +-1.06060606060606e+01 -7.03577356362280e-01 7.45798495908964e-02 5.90622202437287e-02 +-1.00000000000000e+01 -6.89105145844174e-01 6.55059849764586e-02 4.51630398367081e-02 +-9.39393939393939e+00 -6.76227800071737e-01 5.54692165142735e-02 3.11059783824235e-02 +-8.78787878787879e+00 -6.64141630347962e-01 4.52369131161758e-02 1.71623095710831e-02 +-8.18181818181818e+00 -6.54216850502614e-01 3.55800439872753e-02 3.42154297533580e-03 +-7.57575757575758e+00 -6.14625042059806e-01 2.91666756670593e-02 -3.86341370860449e-03 +-6.96969696969697e+00 -5.61841937827523e-01 2.43864881766210e-02 -8.43665697005592e-03 +-6.36363636363636e+00 -4.99189572128014e-01 2.06688208542298e-02 -1.37959149818896e-02 +-5.75757575757576e+00 -4.34608760745885e-01 1.76932591752901e-02 -1.92729400057168e-02 +-5.15151515151515e+00 -3.67348413458166e-01 1.56052490200204e-02 -2.57288663338659e-02 +-4.54545454545454e+00 -2.97220789753124e-01 1.38965283846311e-02 -3.24773660126783e-02 +-3.93939393939394e+00 -2.25827092845188e-01 1.24332806711584e-02 -3.91885815676604e-02 +-3.33333333333333e+00 -1.54050456378233e-01 1.19149897769548e-02 -4.56999911417254e-02 +-2.72727272727273e+00 -8.12318984160244e-02 1.13706359706548e-02 -5.16384940099625e-02 +-2.12121212121212e+00 -7.14979346296234e-03 1.07859435280497e-02 -5.70801147069148e-02 +-1.51515151515152e+00 6.87826749054011e-02 1.05033451229781e-02 -6.20466375298444e-02 +-9.09090909090912e-01 1.45369872154627e-01 1.03139004235661e-02 -6.68516603553039e-02 +-3.03030303030302e-01 2.23028758160340e-01 1.02094317053058e-02 -7.16176330178895e-02 + 3.03030303030302e-01 3.01237277028695e-01 1.01564455703337e-02 -7.60536458286783e-02 + 9.09090909090912e-01 3.80006385780218e-01 1.01544863426098e-02 -8.01685273418174e-02 + 1.51515151515152e+00 4.59246642973497e-01 1.03195069670379e-02 -8.42292432054636e-02 + 2.12121212121212e+00 5.38436193741909e-01 1.05158173919170e-02 -8.80305585640893e-02 + 2.72727272727273e+00 6.17086435268518e-01 1.07234607719624e-02 -9.09221588982618e-02 + 3.33333333333333e+00 6.94766649922142e-01 1.09892374201398e-02 -9.34851438113357e-02 + 3.93939393939394e+00 7.71665263445708e-01 1.12674755215391e-02 -9.57801882660128e-02 + 4.54545454545455e+00 8.46424118402375e-01 1.16353662750350e-02 -9.80494154414620e-02 + 5.15151515151515e+00 9.20198652009909e-01 1.20213692284540e-02 -1.00166544091476e-01 + 5.75757575757576e+00 9.91711074228843e-01 1.24325530524450e-02 -1.01849307770008e-01 + 6.36363636363637e+00 1.06002251469050e+00 1.29373530659327e-02 -1.03182589271796e-01 + 6.96969696969697e+00 1.12620049862159e+00 1.35051858034989e-02 -1.04281097204592e-01 + 7.57575757575757e+00 1.18623076703795e+00 1.42446030038888e-02 -1.05323489221343e-01 + 8.18181818181818e+00 1.24304860221996e+00 1.50702587438949e-02 -1.06330821016929e-01 + 8.78787878787879e+00 1.29339454484370e+00 1.60680959350975e-02 -1.07320656167730e-01 + 9.39393939393939e+00 1.33640612125946e+00 1.81467491655883e-02 -1.08107944391156e-01 + 1.00000000000000e+01 1.37469506451432e+00 2.09438769808961e-02 -1.08769953707875e-01 + 1.06060606060606e+01 1.39128542708790e+00 2.53973640660572e-02 -1.08704427997839e-01 + 1.12121212121212e+01 1.39247645190556e+00 3.08345002992362e-02 -1.08511132324392e-01 + 1.18181818181818e+01 1.36506866603177e+00 3.75119498467862e-02 -1.07969033181396e-01 + 1.24242424242424e+01 1.33988550587683e+00 4.76821530474488e-02 -1.09070781012852e-01 + 1.30303030303030e+01 1.28517385394240e+00 5.94392540313143e-02 -1.10747213245403e-01 + 1.36363636363636e+01 1.25643020037597e+00 7.18386529645335e-02 -1.10309370469218e-01 + 1.42424242424242e+01 1.22941101634947e+00 8.49147013682724e-02 -1.10076808850556e-01 + 1.48484848484848e+01 1.20587360276360e+00 9.89301897374668e-02 -1.10132396182924e-01 + 1.54545454545455e+01 1.18936767768177e+00 1.13924838258266e-01 -1.13810701314704e-01 + 1.60606060606061e+01 1.17565898671524e+00 1.29176297116898e-01 -1.19071521356745e-01 + 1.66666666666667e+01 1.16603643374085e+00 1.43801932752626e-01 -1.26420182833845e-01 + 1.72727272727273e+01 1.15901294982273e+00 1.58412873301332e-01 -1.33298298163097e-01 + 1.78787878787879e+01 1.15516613881923e+00 1.73005853001785e-01 -1.39601295567204e-01 + 1.84848484848485e+01 1.16035329239803e+00 1.87605989072833e-01 -1.43318174504004e-01 + 1.90909090909091e+01 1.16482121671689e+00 2.01471765042406e-01 -1.46723090792030e-01 + 1.96969696969697e+01 1.15241186617039e+00 2.11164662608912e-01 -1.52023933649729e-01 + 2.03030303030303e+01 1.14108152143087e+00 2.21109741610071e-01 -1.56986307485845e-01 + 2.09090909090909e+01 1.13083024354155e+00 2.31307016312692e-01 -1.61635219687799e-01 + 2.15151515151515e+01 1.12057896565223e+00 2.41504291015314e-01 -1.66292754579922e-01 + 2.21212121212121e+01 1.11061305902249e+00 2.51832144540440e-01 -1.70802437318188e-01 + 2.27272727272727e+01 1.10178834380504e+00 2.62682178999596e-01 -1.74726995984381e-01 + 2.33333333333333e+01 1.09296362858759e+00 2.73532213458751e-01 -1.78657586333139e-01 + 2.39393939393939e+01 1.08413891337014e+00 2.84382247917907e-01 -1.82623234550793e-01 + 2.45454545454545e+01 1.07704877435898e+00 2.95863171170336e-01 -1.86155882534370e-01 + 2.51515151515151e+01 1.07015136189154e+00 3.07414191669665e-01 -1.89640420415756e-01 + 2.57575757575758e+01 1.06325394942410e+00 3.18965212168995e-01 -1.93124958297141e-01 + 2.63636363636364e+01 1.05714092098968e+00 3.30902828470674e-01 -1.96422469773296e-01 + 2.69696969696970e+01 1.05155089650575e+00 3.43098215358386e-01 -1.99595277603454e-01 + 2.75757575757576e+01 1.04596087202182e+00 3.55293602246098e-01 -2.02768085433612e-01 + 2.81818181818182e+01 1.04062530585900e+00 3.67663996814596e-01 -2.05879229073642e-01 + 2.87878787878788e+01 1.03588342484769e+00 3.80442707609625e-01 -2.08846501945758e-01 + 2.93939393939394e+01 1.03114154383638e+00 3.93221418404654e-01 -2.11813774817874e-01 + 3.00000000000000e+01 1.02639966282507e+00 4.06000129199683e-01 -2.14781047689990e-01 + 3.30000000000000e+01 1.00573804168069e+00 4.72583293422338e-01 -2.28629026765098e-01 + 3.60000000000000e+01 9.85833707743003e-01 5.41941245231535e-01 -2.41944387146083e-01 + 3.90000000000000e+01 9.64635684439964e-01 6.13911269891018e-01 -2.55359517097689e-01 + 4.20000000000000e+01 9.39853820984217e-01 6.87471272303016e-01 -2.68402760096020e-01 + 4.50000000000000e+01 9.13773877837909e-01 7.61422951679187e-01 -2.81321973111748e-01 + 4.80000000000000e+01 8.80499938641377e-01 8.35214742285566e-01 -2.93829895857158e-01 + 5.10000000000000e+01 8.43049140618493e-01 9.07414892614859e-01 -3.06092438249886e-01 + 5.40000000000000e+01 7.97244356422135e-01 9.76431660067036e-01 -3.17878305263492e-01 + 5.70000000000000e+01 7.51439922147286e-01 1.04544790027186e+00 -3.29653788801724e-01 + 6.00000000000000e+01 7.05635662831859e-01 1.11446387685501e+00 -3.41419875328892e-01 + 6.30000000000000e+01 6.43935405201049e-01 1.17011397781587e+00 -3.51824168446815e-01 + 6.60000000000000e+01 5.82235011316305e-01 1.22576396420997e+00 -3.62218653318893e-01 + 6.90000000000000e+01 5.20534617431561e-01 1.28141395060407e+00 -3.72603978485147e-01 + 7.20000000000000e+01 4.51293480954431e-01 1.32353369994026e+00 -3.81654848148536e-01 + 7.50000000000000e+01 3.78282127550152e-01 1.35888860772946e+00 -3.90032025372884e-01 + 7.80000000000000e+01 3.05269896475863e-01 1.39424392065773e+00 -3.98398550132911e-01 + 8.10000000000000e+01 2.30935739780878e-01 1.42133853168932e+00 -4.05862264958857e-01 + 8.40000000000000e+01 1.53957823095881e-01 1.43191230914291e+00 -4.11528875629133e-01 + 8.70000000000000e+01 7.69789183415259e-02 1.44248616737432e+00 -4.17182529414559e-01 + 9.00000000000000e+01 -3.36313787592115e-07 1.45305993400564e+00 -4.22823883213375e-01 + 9.30000000000000e+01 -5.38853538885643e-02 1.44248615655205e+00 -4.25531830444160e-01 + 9.60000000000000e+01 -1.07770377288908e-01 1.43191233870989e+00 -4.28239883474790e-01 + 9.90000000000000e+01 -1.61655412340595e-01 1.42133844008909e+00 -4.30948043344561e-01 + 1.02000000000000e+02 -2.13689029593013e-01 1.39424374942488e+00 -4.30426032722678e-01 + 1.05000000000000e+02 -2.64796957994024e-01 1.35888884163568e+00 -4.28288858720630e-01 + 1.08000000000000e+02 -3.15905431030774e-01 1.32353352870914e+00 -4.26150923676660e-01 + 1.11000000000000e+02 -3.64374322762835e-01 1.28141346851316e+00 -4.22781294573843e-01 + 1.14000000000000e+02 -4.07564132273452e-01 1.22576411981700e+00 -4.16948201170771e-01 + 1.17000000000000e+02 -4.50754244383126e-01 1.17011434599327e+00 -4.11114214652485e-01 + 1.20000000000000e+02 -4.93944486037582e-01 1.11446433346109e+00 -4.05279567496773e-01 + 1.23000000000000e+02 -5.26007827556164e-01 1.04544835687794e+00 -3.97635867656992e-01 + 1.26000000000000e+02 -5.58071091549210e-01 9.76432116678355e-01 -3.89990992242211e-01 + 1.29000000000000e+02 -5.90134200485389e-01 9.07415349226176e-01 -3.82344714919725e-01 + 1.32000000000000e+02 -6.14671501318397e-01 8.35161838486048e-01 -3.75290062239593e-01 + 1.35000000000000e+02 -6.35445907015363e-01 7.61289959942459e-01 -3.68529899569896e-01 + 1.38000000000000e+02 -6.56219474668182e-01 6.87418368921679e-01 -3.61767875968571e-01 + 1.41000000000000e+02 -6.74909652901486e-01 6.14953590391588e-01 -3.56786256817077e-01 + 1.44000000000000e+02 -6.89433035390160e-01 5.45302448258410e-01 -3.55365699643800e-01 + 1.47000000000000e+02 -7.03955906925430e-01 4.75651465566945e-01 -3.53940753692651e-01 + 1.50000000000000e+02 -7.18478522993120e-01 4.06000562593488e-01 -3.52511578047886e-01 + 1.53000000000000e+02 -7.42629245947763e-01 3.49402521602820e-01 -3.67942713897313e-01 + 1.56000000000000e+02 -7.66779899087500e-01 2.92804540889390e-01 -3.83374818114856e-01 + 1.59000000000000e+02 -7.91051572510474e-01 2.36206619897226e-01 -3.98807852435555e-01 + 1.62000000000000e+02 -7.19307409708115e-01 1.95606690636341e-01 -4.23162217489700e-01 + 1.65000000000000e+02 -5.99422550148399e-01 1.63005892539676e-01 -4.51976932817733e-01 + 1.68000000000000e+02 -4.72905933087606e-01 1.30404868023183e-01 -4.80790683446680e-01 + 1.71000000000000e+02 -3.52738917050312e-01 9.78037326537191e-02 -4.50000513056908e-01 + 1.74000000000000e+02 -2.35159145800089e-01 6.52023755731394e-02 -2.99999717902353e-01 + 1.77000000000000e+02 -1.16216409329782e-01 5.38259028959444e-02 -1.48221036446267e-01 + 1.80000000000000e+02 0.00000000000000e+00 5.30837886627506e-02 0.00000000000000e+00 diff --git a/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_11.dat b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_11.dat new file mode 100644 index 00000000..742ec4f5 --- /dev/null +++ b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_11.dat @@ -0,0 +1,254 @@ +! ------------ AirfoilInfo v1.01.x Input File ---------------------------------- +! AeroElasticSE FAST driver +! line +! line +! ------------------------------------------------------------------------------ +DEFAULT InterpOrd ! Interpolation order to use for quasi-steady table lookup {1=linear; 3=cubic spline; "default"} [default=3] +1 NonDimArea ! The non-dimensional area of the airfoil (area/chord^2) (set to 1.0 if unsure or unneeded) +@"NREL-2p8-127_AF11_Coords.txt" NumCoords ! The number of coordinates in the airfoil shape file. Set to zero if coordinates not included. +AF11_BL.txt BL_file ! The file name including the boundary layer characteristics of the profile. Ignored if the aeroacoustic module is not called. +1 NumTabs ! Number of airfoil tables in this file. Each table must have lines for Re and Ctrl. +! ------------------------------------------------------------------------------ +! data for table 1 +! ------------------------------------------------------------------------------ +6.000000 Re ! Reynolds number in millions +0 Ctrl ! Control setting (must be 0 for current AirfoilInfo) +True InclUAdata ! Is unsteady aerodynamics data included in this table? If TRUE, then include 30 UA coefficients below this line +!........................................ +-2.081115 alpha0 ! 0-lift angle of attack, depends on airfoil. +11.269045 alpha1 ! Angle of attack at f=0.7, (approximately the stall angle) for AOA>alpha0. (deg) +-8.662155 alpha2 ! Angle of attack at f=0.7, (approximately the stall angle) for AOA1] +0.000000 S2 ! Constant in the f curve best-fit for AOA> alpha1; by definition it depends on the airfoil. [ignored if UAMod<>1] +0.000000 S3 ! Constant in the f curve best-fit for alpha2<=AOA< alpha0; by definition it depends on the airfoil. [ignored if UAMod<>1] +0.000000 S4 ! Constant in the f curve best-fit for AOA< alpha2; by definition it depends on the airfoil. [ignored if UAMod<>1] +1.400649 Cn1 ! Critical value of C0n at leading edge separation. It should be extracted from airfoil data at a given Mach and Reynolds number. It can be calculated from the static value of Cn at either the break in the pitching moment or the loss of chord force at the onset of stall. It is close to the condition of maximum lift of the airfoil at low Mach numbers. +-0.915233 Cn2 ! As Cn1 for negative AOAs. +Default St_sh ! Strouhal's shedding frequency constant. [default = 0.19] +0.010727 Cd0 ! 2D drag coefficient value at 0-lift. +-0.065156 Cm0 ! 2D pitching moment coefficient about 1/4-chord location, at 0-lift, positive if nose up. [If the aerodynamics coefficients table does not include a column for Cm, this needs to be set to 0.0] +0.000000 k0 ! Constant in the \hat(x)_cp curve best-fit; = (\hat(x)_AC-0.25). [ignored if UAMod<>1] +0.000000 k1 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k2 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k3 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k1_hat ! Constant in the expression of Cc due to leading edge vortex effects. [ignored if UAMod<>1] +Default x_cp_bar ! Constant in the expression of \hat(x)_cp^v. [ignored if UAMod<>1, default = 0.2] +Default UACutout ! Angle of attack above which unsteady aerodynamics are disabled (deg). [Specifying the string "Default" sets UACutout to 45 degrees] +Default filtCutOff ! Cut-off frequency (-3 dB corner frequency) for low-pass filtering the AoA input to UA, as well as the 1st and 2nd derivatives (Hz) [default = 20] +!........................................ +! Table of aerodynamics coefficients +200 NumAlf ! Number of data lines in the following table +! Alpha Cl Cd Cm +! (deg) (-) (-) (-) +-1.80000000000000e+02 0.00000000000000e+00 5.17338093025581e-02 0.00000000000000e+00 +-1.77000000000000e+02 1.20610218452195e-01 5.17338093025581e-02 1.18763338610947e-01 +-1.74000000000000e+02 2.43846180796722e-01 6.20803661366883e-02 2.39999774321882e-01 +-1.71000000000000e+02 3.65769725958049e-01 9.31203763075915e-02 3.60000410445527e-01 +-1.68000000000000e+02 4.84069232089561e-01 1.24885380987671e-01 3.21035049116140e-01 +-1.65000000000000e+02 6.01637542467089e-01 1.57012874460584e-01 2.02588544427697e-01 +-1.62000000000000e+02 7.13153594297870e-01 1.89140896133777e-01 8.41409821795466e-02 +-1.59000000000000e+02 7.80068980000668e-01 2.29356923814875e-01 7.97341748695581e-03 +-1.56000000000000e+02 7.58681265140819e-01 2.85748689900454e-01 1.75916291927228e-02 +-1.53000000000000e+02 7.37716006162308e-01 3.42140486787254e-01 2.79764209288751e-02 +-1.50000000000000e+02 7.16750629236893e-01 3.98532330574024e-01 3.87597184159220e-02 +-1.47000000000000e+02 7.02430836152056e-01 4.68441880461646e-01 5.28948486721724e-02 +-1.44000000000000e+02 6.88110788374351e-01 5.38351550730586e-01 6.70401805724200e-02 +-1.41000000000000e+02 6.73790231192722e-01 6.08261461770758e-01 8.11976416970075e-02 +-1.38000000000000e+02 6.55253757939153e-01 6.81025000549314e-01 9.58313303466701e-02 +-1.35000000000000e+02 6.34609335202059e-01 7.55215347408169e-01 1.10704411230940e-01 +-1.32000000000000e+02 6.13964075900703e-01 8.29406104470313e-01 1.25585263221553e-01 +-1.29000000000000e+02 5.89541757042321e-01 9.01995435488593e-01 1.40592248603482e-01 +-1.26000000000000e+02 5.57565301171594e-01 9.71381906816171e-01 1.55841088781127e-01 +-1.23000000000000e+02 5.25588689582014e-01 1.04076784806681e+00 1.71097114222845e-01 +-1.20000000000000e+02 4.93612000135919e-01 1.11015352428889e+00 1.86361656418168e-01 +-1.17000000000000e+02 4.50478535342387e-01 1.16621180599633e+00 2.00629220653074e-01 +-1.14000000000000e+02 4.07345160141662e-01 1.22226984751125e+00 2.14906094089605e-01 +-1.11000000000000e+02 3.64212007755362e-01 1.27832746077970e+00 2.29193883251082e-01 +-1.08000000000000e+02 3.15783665079539e-01 1.32087403967776e+00 2.41716558401183e-01 +-1.05000000000000e+02 2.64707686941683e-01 1.35666499851025e+00 2.53364833576556e-01 +-1.02000000000000e+02 2.13632134040282e-01 1.39245554721333e+00 2.65031201575310e-01 +-9.90000000000000e+01 1.61623631750871e-01 1.41999044316543e+00 2.75316312995168e-01 +-9.60000000000000e+01 1.07749190274494e-01 1.43101367601985e+00 2.82819378442760e-01 +-9.30000000000000e+01 5.38747603685306e-02 1.44203682466298e+00 2.90359307559513e-01 +-9.00000000000000e+01 3.36247670192969e-07 1.45305993120123e+00 2.97951186065388e-01 +-8.70000000000000e+01 -5.38747052280345e-02 1.44203683594514e+00 3.01753424548436e-01 +-8.40000000000000e+01 -1.07749340919434e-01 1.43101364519643e+00 3.05884772088962e-01 +-8.10000000000000e+01 -1.61623165043989e-01 1.41999053865818e+00 3.10613470732064e-01 +-7.80000000000000e+01 -2.13631886668320e-01 1.39245572055610e+00 3.10674655777832e-01 +-7.50000000000000e+01 -2.64708024854679e-01 1.35666476172186e+00 3.08542976324719e-01 +-7.20000000000000e+01 -3.15783417710861e-01 1.32087421301878e+00 3.06409302975954e-01 +-6.90000000000000e+01 -3.64211634092392e-01 1.27832794640741e+00 3.03044729448568e-01 +-6.60000000000000e+01 -4.07345280750829e-01 1.22226969076263e+00 2.97219713108405e-01 +-6.30000000000000e+01 -4.50478820711274e-01 1.16621143511785e+00 2.91391620398543e-01 +-6.00000000000000e+01 -4.93612211692021e-01 1.11015306523689e+00 2.85560191488404e-01 +-5.70000000000000e+01 -5.25588901138117e-01 1.04076738901481e+00 2.77925669828566e-01 +-5.40000000000000e+01 -5.57565512726151e-01 9.71381447758911e-01 2.70286195661910e-01 +-5.10000000000000e+01 -5.89541968596878e-01 9.01994976431333e-01 2.62640680641497e-01 +-4.80000000000000e+01 -6.15651105875399e-01 8.29449803698678e-01 2.55153878770895e-01 +-4.50000000000000e+01 -6.38826678153933e-01 7.55325331028288e-01 2.47739559108878e-01 +-4.20000000000000e+01 -6.56940774711891e-01 6.81068699431397e-01 2.41608950158798e-01 +-3.90000000000000e+01 -6.74138230588866e-01 6.07210570957826e-01 2.36033756265024e-01 +-3.60000000000000e+01 -6.88800358432074e-01 5.34964795566947e-01 2.32526368115935e-01 +-3.30000000000000e+01 -7.02527481598747e-01 4.65352126226771e-01 2.31660096996564e-01 +-3.00000000000000e+01 -7.16750731841146e-01 3.98531895640176e-01 2.33717011176468e-01 +-2.93939393939394e+01 -7.20014368241707e-01 3.85709000620782e-01 2.34916176725143e-01 +-2.87878787878788e+01 -7.23278004642269e-01 3.72886105601387e-01 2.36115342273819e-01 +-2.81818181818182e+01 -7.26541641042830e-01 3.60063210581993e-01 2.37314507822494e-01 +-2.75757575757576e+01 -7.30215084645349e-01 3.47650566598554e-01 2.39067661935682e-01 +-2.69696969696970e+01 -7.34064174972939e-01 3.35413759571076e-01 2.41058260087479e-01 +-2.63636363636364e+01 -7.37913265300529e-01 3.23176952543597e-01 2.43048858239275e-01 +-2.57575757575758e+01 -7.42124844608794e-01 3.11199070884588e-01 2.45450980247116e-01 +-2.51515151515151e+01 -7.46880072905424e-01 2.99609516932444e-01 2.48470292128175e-01 +-2.45454545454545e+01 -7.51635301202054e-01 2.88019962980301e-01 2.51489604009234e-01 +-2.39393939393939e+01 -7.56524250108274e-01 2.76500794819509e-01 2.54645697570981e-01 +-2.33333333333333e+01 -7.62616710389763e-01 2.65615112407906e-01 2.59032852740507e-01 +-2.27272727272727e+01 -7.68709170671251e-01 2.54729429996303e-01 2.63911099891641e-01 +-2.21212121212121e+01 -7.74801630952739e-01 2.43843747584701e-01 2.68391913865235e-01 +-2.15151515151515e+01 -7.93896255075763e-01 2.34765567487007e-01 2.69219982182975e-01 +-2.09090909090909e+01 -8.19588776751072e-01 2.26139379234369e-01 2.68013679183985e-01 +-2.03030303030303e+01 -8.41755850773015e-01 2.17513190981731e-01 2.66455457580854e-01 +-1.96969696969697e+01 -8.57132969513166e-01 2.09138320990721e-01 2.57323288186467e-01 +-1.90909090909091e+01 -8.65913538616401e-01 2.01014755044168e-01 2.40703240782996e-01 +-1.84848484848485e+01 -8.74215029540216e-01 1.93152415327005e-01 2.24051125011634e-01 +-1.78787878787879e+01 -8.82246941494251e-01 1.85271935431753e-01 2.07713877216966e-01 +-1.72727272727273e+01 -8.90112513417619e-01 1.76753055824415e-01 1.91533915208804e-01 +-1.66666666666667e+01 -8.97867665288278e-01 1.69666716562767e-01 1.75354108708192e-01 +-1.60606060606061e+01 -9.05545956258092e-01 1.62769575158031e-01 1.59174429439710e-01 +-1.54545454545455e+01 -9.05500228357417e-01 1.54709519958352e-01 1.44263287105186e-01 +-1.48484848484848e+01 -9.00650490354814e-01 1.45972869299812e-01 1.30048437843628e-01 +-1.42424242424242e+01 -8.83881928212747e-01 1.35695161200991e-01 1.18061058367204e-01 +-1.36363636363636e+01 -8.65135255067798e-01 1.25196579166224e-01 1.06372832901923e-01 +-1.30303030303030e+01 -8.44949235869776e-01 1.14536353092698e-01 9.41922629526705e-02 +-1.24242424242424e+01 -8.23438097507769e-01 1.04071539255474e-01 8.07476005612591e-02 +-1.18181818181818e+01 -8.01578346336287e-01 9.39351009261381e-02 6.72989309058954e-02 +-1.12121212121212e+01 -7.79436133521223e-01 8.45784112226453e-02 5.39664027575017e-02 +-1.06060606060606e+01 -7.56125420814654e-01 7.56686775243057e-02 4.13015037835521e-02 +-1.00000000000000e+01 -7.31404178229205e-01 6.69542054267392e-02 2.90154450614047e-02 +-9.39393939393939e+00 -7.10908164656284e-01 5.62659422161747e-02 1.61336287291465e-02 +-8.78787878787879e+00 -6.93895499794178e-01 4.51632034246090e-02 3.66630892977488e-03 +-8.18181818181818e+00 -6.82305849045296e-01 3.46949966165822e-02 -8.06490144015382e-03 +-7.57575757575758e+00 -6.41809741158512e-01 2.77831234233813e-02 -1.41096615374045e-02 +-6.96969696969697e+00 -5.88143925838256e-01 2.28417438781606e-02 -1.78405462944423e-02 +-6.36363636363636e+00 -5.18595414594118e-01 1.94965813878357e-02 -2.29439868991729e-02 +-5.75757575757576e+00 -4.47723085873360e-01 1.68485236815072e-02 -2.81966573016451e-02 +-5.15151515151515e+00 -3.75142989396497e-01 1.49610810018752e-02 -3.47182225820690e-02 +-4.54545454545454e+00 -3.00787223897522e-01 1.34635952053030e-02 -4.14011501128667e-02 +-3.93939393939394e+00 -2.25750200730196e-01 1.21953572497309e-02 -4.79556483496797e-02 +-3.33333333333333e+00 -1.53097407752943e-01 1.17061671579090e-02 -5.41961908245246e-02 +-2.72727272727273e+00 -7.95718917516246e-02 1.12293922425528e-02 -5.97874291038278e-02 +-2.12121212121212e+00 -5.03539621814182e-03 1.07440480589344e-02 -6.48477030716386e-02 +-1.51515151515152e+00 7.10741171824617e-02 1.04901796827387e-02 -6.95072912947862e-02 +-9.09090909090912e-01 1.47800523968434e-01 1.03183543231236e-02 -7.40089097305715e-02 +-3.03030303030302e-01 2.25712116064930e-01 1.02530762212861e-02 -7.84452609734865e-02 + 3.03030303030302e-01 3.04012747719234e-01 1.02309881009218e-02 -8.25691600591865e-02 + 9.09090909090912e-01 3.82711307380014e-01 1.02503405435553e-02 -8.63962105538320e-02 + 1.51515151515152e+00 4.61756851424667e-01 1.03813057971860e-02 -9.01104450324160e-02 + 2.12121212121212e+00 5.40685036400329e-01 1.05415949817604e-02 -9.35850435449342e-02 + 2.72727272727273e+00 6.18886227271413e-01 1.07445792627915e-02 -9.62817005798321e-02 + 3.33333333333333e+00 6.96227792951118e-01 1.09887579176491e-02 -9.86711658811812e-02 + 3.93939393939394e+00 7.72883389885004e-01 1.12344879960209e-02 -1.00807961075492e-01 + 4.54545454545455e+00 8.47551890939517e-01 1.15551058195410e-02 -1.02885524901180e-01 + 5.15151515151515e+00 9.21271553826334e-01 1.18923634479442e-02 -1.04819428291073e-01 + 5.75757575757576e+00 9.92784335144794e-01 1.22610882531594e-02 -1.06359973327630e-01 + 6.36363636363637e+00 1.06131473281146e+00 1.27079774642478e-02 -1.07580975239224e-01 + 6.96969696969697e+00 1.12787422242318e+00 1.32063108971969e-02 -1.08587510060800e-01 + 7.57575757575757e+00 1.18885675085141e+00 1.38302419296642e-02 -1.09502885178324e-01 + 8.18181818181818e+00 1.24720837846946e+00 1.45051079826196e-02 -1.10383577044148e-01 + 8.78787878787879e+00 1.30109155320978e+00 1.52650096833159e-02 -1.11295079946526e-01 + 9.39393939393939e+00 1.34910270552171e+00 1.69597298070715e-02 -1.11617299458299e-01 + 1.00000000000000e+01 1.39122211758901e+00 1.92951287014474e-02 -1.11579588588804e-01 + 1.06060606060606e+01 1.41374692668675e+00 2.32087315726581e-02 -1.10700973175584e-01 + 1.12121212121212e+01 1.42235063763216e+00 2.80043073060677e-02 -1.09633362298298e-01 + 1.18181818181818e+01 1.40509952208549e+00 3.36675325297581e-02 -1.08071370626820e-01 + 1.24242424242424e+01 1.36098461886640e+00 4.53311237959958e-02 -1.09677679611616e-01 + 1.30303030303030e+01 1.27121985294027e+00 5.94850170456720e-02 -1.12451230995673e-01 + 1.36363636363636e+01 1.23331688079203e+00 7.12491888525373e-02 -1.11569128322250e-01 + 1.42424242424242e+01 1.19929983782480e+00 8.34701602960147e-02 -1.10866527861742e-01 + 1.48484848484848e+01 1.17429197921907e+00 9.63163863742802e-02 -1.10364535193828e-01 + 1.54545454545455e+01 1.15693155875190e+00 1.09918192046590e-01 -1.12997477778780e-01 + 1.60606060606061e+01 1.14266018641121e+00 1.23724487625457e-01 -1.16993403213071e-01 + 1.66666666666667e+01 1.13325405216419e+00 1.37104753717798e-01 -1.22803327538571e-01 + 1.72727272727273e+01 1.12686629586509e+00 1.50546395471717e-01 -1.28360097087402e-01 + 1.78787878787879e+01 1.12416770644291e+00 1.64063052701384e-01 -1.33607452032450e-01 + 1.84848484848485e+01 1.13139272733087e+00 1.78010604421774e-01 -1.37206719425119e-01 + 1.90909090909091e+01 1.13867731668370e+00 1.91501101195136e-01 -1.40692310188144e-01 + 1.96969696969697e+01 1.13223871836009e+00 2.01790232355546e-01 -1.45868712277606e-01 + 2.03030303030303e+01 1.12592570808589e+00 2.12197188791206e-01 -1.50881669040385e-01 + 2.09090909090909e+01 1.11973829296607e+00 2.22721977167913e-01 -1.55819852215318e-01 + 2.15151515151515e+01 1.11355087784625e+00 2.33246765544621e-01 -1.60788589705368e-01 + 2.21212121212121e+01 1.10686018543461e+00 2.43843747584701e-01 -1.65603019715883e-01 + 2.27272727272727e+01 1.09815690169093e+00 2.54729429996303e-01 -1.69822108656288e-01 + 2.33333333333333e+01 1.08945361794725e+00 2.65615112407906e-01 -1.74062570732705e-01 + 2.39393939393939e+01 1.08075033420357e+00 2.76500794819509e-01 -1.78427259605238e-01 + 2.45454545454545e+01 1.07376593672417e+00 2.88019962980301e-01 -1.82284015244859e-01 + 2.51515151515151e+01 1.06697252249912e+00 2.99609516932444e-01 -1.86084335072627e-01 + 2.57575757575758e+01 1.06017910827406e+00 3.11199070884588e-01 -1.89884654900395e-01 + 2.63636363636364e+01 1.05416214500944e+00 3.23176952543597e-01 -1.93462066542360e-01 + 2.69696969696970e+01 1.04866289615838e+00 3.35413759571076e-01 -1.96890849633946e-01 + 2.75757575757576e+01 1.04316364730731e+00 3.47650566598554e-01 -2.00319632725532e-01 + 2.81818181818182e+01 1.03791578996892e+00 3.60063210581993e-01 -2.03673565505490e-01 + 2.87878787878788e+01 1.03325446250951e+00 3.72886105601387e-01 -2.06852862539969e-01 + 2.93939393939394e+01 1.02859313505011e+00 3.85709000620782e-01 -2.10032159574448e-01 + 3.00000000000000e+01 1.02393180759070e+00 3.98531895640176e-01 -2.13211456608927e-01 + 3.30000000000000e+01 1.00360981651186e+00 4.65352126226771e-01 -2.27906428002545e-01 + 3.60000000000000e+01 9.84001264428555e-01 5.34964795566947e-01 -2.41925534967727e-01 + 3.90000000000000e+01 9.63054591373508e-01 6.07210570957826e-01 -2.55861101384382e-01 + 4.20000000000000e+01 9.38486939161695e-01 6.81068699431397e-01 -2.69396898615722e-01 + 4.50000000000000e+01 9.12610178291857e-01 7.55325331028288e-01 -2.82806077238433e-01 + 4.80000000000000e+01 8.79501806448111e-01 8.29449803698678e-01 -2.95759616602379e-01 + 5.10000000000000e+01 8.42202650323331e-01 9.01994976431333e-01 -3.08464526695633e-01 + 5.40000000000000e+01 7.96521656220475e-01 9.71381447758911e-01 -3.20679850937119e-01 + 5.70000000000000e+01 7.50841011093444e-01 1.04076738901481e+00 -3.32886639691835e-01 + 6.00000000000000e+01 7.05160540452998e-01 1.11015306523690e+00 -3.45085056710935e-01 + 6.30000000000000e+01 6.43541341893905e-01 1.16621143511785e+00 -3.55934491344085e-01 + 6.60000000000000e+01 5.81922006714618e-01 1.22226969076263e+00 -3.66774194260320e-01 + 6.90000000000000e+01 5.20302671535330e-01 1.27832794640741e+00 -3.77604487698421e-01 + 7.20000000000000e+01 4.51119501480277e-01 1.32087421301878e+00 -3.87119214978594e-01 + 7.50000000000000e+01 3.78154568829116e-01 1.35666476172186e+00 -3.95968866317771e-01 + 7.80000000000000e+01 3.05188640011092e-01 1.39245572055610e+00 -4.04806568926510e-01 + 8.10000000000000e+01 2.30890390081552e-01 1.41999053865818e+00 -4.12748066743701e-01 + 8.40000000000000e+01 1.53927589898212e-01 1.43101364519643e+00 -4.18906566709380e-01 + 8.70000000000000e+01 7.69638017609944e-02 1.44203683594514e+00 -4.25049810698846e-01 + 9.00000000000000e+01 -3.36247670426886e-07 1.45305993120123e+00 -4.31178399042578e-01 + 9.30000000000000e+01 -5.38747603685306e-02 1.44203682466298e+00 -4.34104668279932e-01 + 9.60000000000000e+01 -1.07749190274494e-01 1.43101367601985e+00 -4.37031487108267e-01 + 9.90000000000000e+01 -1.61623631750871e-01 1.41999044316543e+00 -4.39958819257674e-01 + 1.02000000000000e+02 -2.13632134040282e-01 1.39245554721333e+00 -4.39636233003905e-01 + 1.05000000000000e+02 -2.64707686941683e-01 1.35666499851025e+00 -4.37688769297266e-01 + 1.08000000000000e+02 -3.15783665079539e-01 1.32087403967776e+00 -4.35740818710456e-01 + 1.11000000000000e+02 -3.64212007755363e-01 1.27832746077970e+00 -4.32550227083959e-01 + 1.14000000000000e+02 -4.07345160141662e-01 1.22226984751125e+00 -4.26873946888224e-01 + 1.17000000000000e+02 -4.50478535342387e-01 1.16621180599633e+00 -4.21196949202848e-01 + 1.20000000000000e+02 -4.93612000135919e-01 1.11015352428889e+00 -4.15519446213869e-01 + 1.23000000000000e+02 -5.25588689582014e-01 1.04076784806681e+00 -4.08013919223535e-01 + 1.26000000000000e+02 -5.57565301171594e-01 9.71381906816171e-01 -4.00507231110389e-01 + 1.29000000000000e+02 -5.89541757042322e-01 9.01995435488592e-01 -3.92999135332578e-01 + 1.32000000000000e+02 -6.13964075900704e-01 8.29406104470312e-01 -3.86098598415459e-01 + 1.35000000000000e+02 -6.34609335202059e-01 7.55215347408169e-01 -3.79500308090265e-01 + 1.38000000000000e+02 -6.55253757939153e-01 6.81025000549314e-01 -3.72899876934706e-01 + 1.41000000000000e+02 -6.73790231192722e-01 6.08261461770757e-01 -3.68126222376485e-01 + 1.44000000000000e+02 -6.88110788374351e-01 5.38351550730586e-01 -3.67006301532646e-01 + 1.47000000000000e+02 -7.02430836152056e-01 4.68441880461646e-01 -3.65881031661847e-01 + 1.50000000000000e+02 -7.16750629236893e-01 3.98532330574024e-01 -3.64750607711192e-01 + 1.53000000000000e+02 -7.34878858674711e-01 3.42608943418167e-01 -3.80350965963448e-01 + 1.56000000000000e+02 -7.53007027741238e-01 2.86685655813922e-01 -3.95955856199125e-01 + 1.59000000000000e+02 -7.71564544817183e-01 2.30762502127974e-01 -4.11565385415533e-01 + 1.62000000000000e+02 -7.00256219005735e-01 1.90909397104532e-01 -4.33416022361716e-01 + 1.65000000000000e+02 -5.83546590903823e-01 1.59091452320285e-01 -4.58385560746469e-01 + 1.68000000000000e+02 -4.58125712100344e-01 1.27273272145471e-01 -4.83354146585932e-01 + 1.71000000000000e+02 -3.41045278744180e-01 9.54550237835969e-02 -4.50000513056908e-01 + 1.74000000000000e+02 -2.27363439140247e-01 6.36366390444162e-02 -2.99999717902353e-01 + 1.77000000000000e+02 -1.12541609339478e-01 5.25040908476199e-02 -1.48454173263684e-01 + 1.80000000000000e+02 0.00000000000000e+00 5.17338093025581e-02 0.00000000000000e+00 diff --git a/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_12.dat b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_12.dat new file mode 100644 index 00000000..43ee56ca --- /dev/null +++ b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_12.dat @@ -0,0 +1,254 @@ +! ------------ AirfoilInfo v1.01.x Input File ---------------------------------- +! AeroElasticSE FAST driver +! line +! line +! ------------------------------------------------------------------------------ +DEFAULT InterpOrd ! Interpolation order to use for quasi-steady table lookup {1=linear; 3=cubic spline; "default"} [default=3] +1 NonDimArea ! The non-dimensional area of the airfoil (area/chord^2) (set to 1.0 if unsure or unneeded) +@"NREL-2p8-127_AF12_Coords.txt" NumCoords ! The number of coordinates in the airfoil shape file. Set to zero if coordinates not included. +AF12_BL.txt BL_file ! The file name including the boundary layer characteristics of the profile. Ignored if the aeroacoustic module is not called. +1 NumTabs ! Number of airfoil tables in this file. Each table must have lines for Re and Ctrl. +! ------------------------------------------------------------------------------ +! data for table 1 +! ------------------------------------------------------------------------------ +6.000000 Re ! Reynolds number in millions +0 Ctrl ! Control setting (must be 0 for current AirfoilInfo) +True InclUAdata ! Is unsteady aerodynamics data included in this table? If TRUE, then include 30 UA coefficients below this line +!........................................ +-2.104210 alpha0 ! 0-lift angle of attack, depends on airfoil. +11.449404 alpha1 ! Angle of attack at f=0.7, (approximately the stall angle) for AOA>alpha0. (deg) +-8.941354 alpha2 ! Angle of attack at f=0.7, (approximately the stall angle) for AOA1] +0.000000 S2 ! Constant in the f curve best-fit for AOA> alpha1; by definition it depends on the airfoil. [ignored if UAMod<>1] +0.000000 S3 ! Constant in the f curve best-fit for alpha2<=AOA< alpha0; by definition it depends on the airfoil. [ignored if UAMod<>1] +0.000000 S4 ! Constant in the f curve best-fit for AOA< alpha2; by definition it depends on the airfoil. [ignored if UAMod<>1] +1.433280 Cn1 ! Critical value of C0n at leading edge separation. It should be extracted from airfoil data at a given Mach and Reynolds number. It can be calculated from the static value of Cn at either the break in the pitching moment or the loss of chord force at the onset of stall. It is close to the condition of maximum lift of the airfoil at low Mach numbers. +-1.020492 Cn2 ! As Cn1 for negative AOAs. +Default St_sh ! Strouhal's shedding frequency constant. [default = 0.19] +0.010714 Cd0 ! 2D drag coefficient value at 0-lift. +-0.072028 Cm0 ! 2D pitching moment coefficient about 1/4-chord location, at 0-lift, positive if nose up. [If the aerodynamics coefficients table does not include a column for Cm, this needs to be set to 0.0] +0.000000 k0 ! Constant in the \hat(x)_cp curve best-fit; = (\hat(x)_AC-0.25). [ignored if UAMod<>1] +0.000000 k1 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k2 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k3 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k1_hat ! Constant in the expression of Cc due to leading edge vortex effects. [ignored if UAMod<>1] +Default x_cp_bar ! Constant in the expression of \hat(x)_cp^v. [ignored if UAMod<>1, default = 0.2] +Default UACutout ! Angle of attack above which unsteady aerodynamics are disabled (deg). [Specifying the string "Default" sets UACutout to 45 degrees] +Default filtCutOff ! Cut-off frequency (-3 dB corner frequency) for low-pass filtering the AoA input to UA, as well as the 1st and 2nd derivatives (Hz) [default = 20] +!........................................ +! Table of aerodynamics coefficients +200 NumAlf ! Number of data lines in the following table +! Alpha Cl Cd Cm +! (deg) (-) (-) (-) +-1.80000000000000e+02 0.00000000000000e+00 5.02017886725028e-02 0.00000000000000e+00 +-1.77000000000000e+02 1.16814702114733e-01 5.02017886725028e-02 1.18974998388536e-01 +-1.74000000000000e+02 2.35757260050863e-01 6.02419881354083e-02 2.39999774321882e-01 +-1.71000000000000e+02 3.53636476996742e-01 9.03629161351898e-02 3.60000410445527e-01 +-1.68000000000000e+02 4.69829759859863e-01 1.20986055059121e-01 3.19692038335689e-01 +-1.65000000000000e+02 5.86100406969184e-01 1.51860293583585e-01 1.99231033151485e-01 +-1.62000000000000e+02 6.97207018087719e-01 1.82735181026080e-01 7.87690618632042e-02 +-1.59000000000000e+02 7.65053274169454e-01 2.21992372815171e-01 4.59488938113571e-04 +-1.56000000000000e+02 7.47840212628704e-01 2.78013889729193e-01 8.23826475941633e-03 +-1.53000000000000e+02 7.31315050935883e-01 3.34035434615955e-01 1.69033914984109e-02 +-1.50000000000000e+02 7.14789733419415e-01 3.90057026535133e-01 2.57900977189505e-02 +-1.47000000000000e+02 7.00700113478808e-01 4.60260101212902e-01 4.02282514210461e-02 +-1.44000000000000e+02 6.86610239724511e-01 5.30463342418639e-01 5.46749993729137e-02 +-1.41000000000000e+02 6.72519858324716e-01 6.00666916692206e-01 6.91319722248670e-02 +-1.38000000000000e+02 6.54157816774948e-01 6.73769502775919e-01 8.40066813863651e-02 +-1.35000000000000e+02 6.33659953815723e-01 7.48321588883743e-01 9.90913902837609e-02 +-1.32000000000000e+02 6.13161255971681e-01 8.22874224418487e-01 1.14182857514007e-01 +-1.29000000000000e+02 5.88869424113624e-01 8.95844660221988e-01 1.29408668138862e-01 +-1.26000000000000e+02 5.56991306252975e-01 9.65650689048611e-01 1.44894245978222e-01 +-1.23000000000000e+02 5.25113031922222e-01 1.03545618459309e+00 1.60385940835181e-01 +-1.20000000000000e+02 4.93234679359342e-01 1.10526141350648e+00 1.75884859665492e-01 +-1.17000000000000e+02 4.50165647641462e-01 1.16178301844503e+00 1.90450025251094e-01 +-1.14000000000000e+02 4.07096660176995e-01 1.21830438150688e+00 2.05022854430753e-01 +-1.11000000000000e+02 3.64027804983567e-01 1.27482531278278e+00 2.19604660336798e-01 +-1.08000000000000e+02 3.15645479300682e-01 1.31785592534089e+00 2.32463316412531e-01 +-1.05000000000000e+02 2.64606377915867e-01 1.35414127581743e+00 2.44466971927803e-01 +-1.02000000000000e+02 2.13567566267535e-01 1.39042621049931e+00 2.56485516539190e-01 +-9.90000000000000e+01 1.61587565629768e-01 1.41846067229841e+00 2.67134366691667e-01 +-9.60000000000000e+01 1.07725146245282e-01 1.42999383096059e+00 2.75027548957952e-01 +-9.30000000000000e+01 5.38627383393683e-02 1.44152690151593e+00 2.82950978094881e-01 +-9.00000000000000e+01 3.36172637297600e-07 1.45305992801866e+00 2.90917363787953e-01 +-8.70000000000000e+01 -5.38626832111768e-02 1.44152691331999e+00 2.94767512788956e-01 +-8.40000000000000e+01 -1.07725296856606e-01 1.42999379871131e+00 2.98897742164918e-01 +-8.10000000000000e+01 -1.61587099027032e-01 1.41846077220858e+00 3.03536772948404e-01 +-7.80000000000000e+01 -2.13567319073521e-01 1.39042638623652e+00 3.03702648984174e-01 +-7.50000000000000e+01 -2.64606715585627e-01 1.35414103575821e+00 3.01751455652536e-01 +-7.20000000000000e+01 -3.15645232110603e-01 1.31785610107633e+00 2.99797410104482e-01 +-6.90000000000000e+01 -3.64027431877603e-01 1.27482580242423e+00 2.96601873383554e-01 +-6.60000000000000e+01 -4.07096780606374e-01 1.21830422346273e+00 2.90925626936627e-01 +-6.30000000000000e+01 -4.50165932584065e-01 1.16178264450123e+00 2.85244623169737e-01 +-6.00000000000000e+01 -4.93234890264853e-01 1.10526095167874e+00 2.79558323005520e-01 +-5.70000000000000e+01 -5.25113242827733e-01 1.03545572276536e+00 2.72051789581655e-01 +-5.40000000000000e+01 -5.56991517156933e-01 9.65650227215581e-01 2.64537349061016e-01 +-5.10000000000000e+01 -5.88869635017581e-01 8.95844198388958e-01 2.57013385477719e-01 +-4.80000000000000e+01 -6.14858281985569e-01 8.22907477862781e-01 2.49649988716779e-01 +-4.50000000000000e+01 -6.37902288159362e-01 7.48405461801475e-01 2.42355684979480e-01 +-4.20000000000000e+01 -6.55854829508633e-01 6.73802755955525e-01 2.36361332357867e-01 +-3.90000000000000e+01 -6.72882108422873e-01 5.99606299882174e-01 2.30958164591745e-01 +-3.60000000000000e+01 -6.87344655388143e-01 5.27047589477837e-01 2.27795230971316e-01 +-3.30000000000000e+01 -7.00836969047683e-01 4.57145854597990e-01 2.27367173402586e-01 +-3.00000000000000e+01 -7.14789834137016e-01 3.90056589853572e-01 2.29972174924480e-01 +-2.93939393939394e+01 -7.17989820447135e-01 3.77183552479970e-01 2.31313103482737e-01 +-2.87878787878788e+01 -7.21189806757255e-01 3.64310515106369e-01 2.32654032040993e-01 +-2.81818181818182e+01 -7.24389793067374e-01 3.51437477732768e-01 2.33994960599249e-01 +-2.75757575757576e+01 -7.27993615957789e-01 3.38976887108657e-01 2.35912898360177e-01 +-2.69696969696970e+01 -7.31770526515904e-01 3.26693074541322e-01 2.38078146993880e-01 +-2.63636363636364e+01 -7.35547437074019e-01 3.14409261973987e-01 2.40243395627583e-01 +-2.57575757575758e+01 -7.39682607350460e-01 3.02385685277020e-01 2.42838068946369e-01 +-2.51515151515151e+01 -7.44355083707426e-01 2.90752401734336e-01 2.46076779209917e-01 +-2.45454545454545e+01 -7.49027560064392e-01 2.79119118191653e-01 2.49315489473464e-01 +-2.39393939393939e+01 -7.53832399461519e-01 2.67556547894255e-01 2.52697168932637e-01 +-2.33333333333333e+01 -7.59828531846218e-01 2.56630410494836e-01 2.57365598831951e-01 +-2.27272727272727e+01 -7.65824664230917e-01 2.45704273095417e-01 2.62833561583836e-01 +-2.21212121212121e+01 -7.71820796615617e-01 2.34778135695999e-01 2.67654474711527e-01 +-2.15151515151515e+01 -7.96443477215383e-01 2.26676404363075e-01 2.64351420041365e-01 +-2.09090909090909e+01 -8.30849944454416e-01 2.19280956225120e-01 2.57191864213633e-01 +-2.03030303030303e+01 -8.61239798275855e-01 2.11885508087165e-01 2.49459359740882e-01 +-1.96969696969697e+01 -8.86851353917406e-01 2.04664215991167e-01 2.36345486505374e-01 +-1.90909090909091e+01 -9.07849523166766e-01 1.97617070085050e-01 2.17989979126022e-01 +-1.84848484848485e+01 -9.28438728259752e-01 1.90994947917113e-01 1.99581867965191e-01 +-1.78787878787879e+01 -9.48798009848073e-01 1.84343308202159e-01 1.81686497656418e-01 +-1.72727272727273e+01 -9.69015714430469e-01 1.76652563396641e-01 1.64047931232961e-01 +-1.66666666666667e+01 -9.89139234078135e-01 1.70406496274106e-01 1.46409370226095e-01 +-1.60606060606061e+01 -1.00919719372332e+00 1.64405524173896e-01 1.28770813650940e-01 +-1.54545454545455e+01 -1.01540755504446e+00 1.56862910031355e-01 1.13470810022679e-01 +-1.48484848484848e+01 -1.01298433891169e+00 1.48403778032376e-01 9.94548755135208e-02 +-1.42424242424242e+01 -9.89203767259323e-01 1.37794975860024e-01 8.94257900471029e-02 +-1.36363636363636e+01 -9.62014659606293e-01 1.26881241910317e-01 7.98089478777152e-02 +-1.30303030303030e+01 -9.32449292572719e-01 1.15751868266820e-01 6.93414419906876e-02 +-1.24242424242424e+01 -9.00792491049511e-01 1.04900663581092e-01 5.67713948672409e-02 +-1.18181818181818e+01 -8.68848659795491e-01 9.45041039998393e-02 4.42375285802314e-02 +-1.12121212121212e+01 -8.36808576348847e-01 8.51661045609216e-02 3.19958406592258e-02 +-1.06060606060606e+01 -8.03284211237670e-01 7.64433166380479e-02 2.09106002122012e-02 +-1.00000000000000e+01 -7.68096954585546e-01 6.80130732444816e-02 1.04779161942864e-02 +-9.39393939393939e+00 -7.39737601227035e-01 5.68394250941624e-02 -1.00892879318824e-03 +-8.78787878787879e+00 -7.17791627668883e-01 4.50577060106998e-02 -1.17953152141081e-02 +-8.18181818181818e+00 -7.04457618185764e-01 3.35556812007792e-02 -2.13372325268140e-02 +-7.57575757575758e+00 -6.63232806034972e-01 2.62982027978296e-02 -2.60669251138793e-02 +-6.96969696969697e+00 -6.08991380617151e-01 2.14176171488251e-02 -2.89228360247444e-02 +-6.36363636363636e+00 -5.33652028186316e-01 1.85402907866192e-02 -3.37736937247221e-02 +-5.75757575757576e+00 -4.57645786576647e-01 1.62204582639942e-02 -3.87352025598183e-02 +-5.15151515151515e+00 -3.80878183776993e-01 1.45075217386201e-02 -4.47429870829259e-02 +-4.54545454545454e+00 -3.03328576206396e-01 1.31751950655347e-02 -5.08206305818731e-02 +-3.93939393939394e+00 -2.25638938079791e-01 1.20463073814285e-02 -5.67577483907786e-02 +-3.33333333333333e+00 -1.51759128742261e-01 1.15765523813214e-02 -6.23461963393866e-02 +-2.72727272727273e+00 -7.72803618184935e-02 1.11443927588391e-02 -6.73647853995964e-02 +-2.12121212121212e+00 -2.14165309152243e-03 1.07204811423473e-02 -7.19089758691984e-02 +-1.51515151515152e+00 7.42011233954975e-02 1.04829792545349e-02 -7.61446613489007e-02 +-9.09090909090912e-01 1.51109201168349e-01 1.03234088196644e-02 -8.02509486552512e-02 +-3.03030303030302e-01 2.29344027261245e-01 1.03026060888101e-02 -8.42792874035115e-02 + 3.03030303030302e-01 3.07759215649705e-01 1.03155825014327e-02 -8.80359990719921e-02 + 9.09090909090912e-01 3.86363579252603e-01 1.03591204387569e-02 -9.15396518680686e-02 + 1.51515151515152e+00 4.65155136112344e-01 1.04514380417906e-02 -9.48849911388328e-02 + 2.12121212121212e+00 5.43742423609011e-01 1.05708486137771e-02 -9.80280317259123e-02 + 2.72727272727273e+00 6.21355563499191e-01 1.07685455281878e-02 -1.00538334680120e-01 + 3.33333333333333e+00 6.98247696483015e-01 1.09884995827544e-02 -1.02768385980751e-01 + 3.93939393939394e+00 7.74577272776593e-01 1.12160604908465e-02 -1.04764162336771e-01 + 4.54545454545455e+00 8.49123646294387e-01 1.15084433622475e-02 -1.06669894654905e-01 + 5.15151515151515e+00 9.22768835492197e-01 1.18149173971583e-02 -1.08443519681338e-01 + 5.75757575757576e+00 9.94281779511649e-01 1.21556943938836e-02 -1.09866171766382e-01 + 6.36363636363637e+00 1.06310529013751e+00 1.25630225021709e-02 -1.10999261303783e-01 + 6.96969696969697e+00 1.13016792278117e+00 1.30120459327629e-02 -1.11939153730602e-01 + 7.57575757575757e+00 1.19235719212211e+00 1.35489371100261e-02 -1.12757130291620e-01 + 8.18181818181818e+00 1.25253452840185e+00 1.41028478529467e-02 -1.13550777719788e-01 + 8.78787878787879e+00 1.31022818965375e+00 1.46613278249224e-02 -1.14419167648035e-01 + 9.39393939393939e+00 1.36351139175394e+00 1.60081512284208e-02 -1.14359279394763e-01 + 1.00000000000000e+01 1.40997780157282e+00 1.78443424094440e-02 -1.13736890758993e-01 + 1.06060606060606e+01 1.43923730215627e+00 2.09588631373841e-02 -1.12187901895665e-01 + 1.12121212121212e+01 1.45625328102718e+00 2.47924700140119e-02 -1.10420788252029e-01 + 1.18181818181818e+01 1.45052843686856e+00 2.93047053533567e-02 -1.08130034479078e-01 + 1.24242424242424e+01 1.37738927101704e+00 4.26630642527924e-02 -1.10097235207091e-01 + 1.30303030303030e+01 1.25402046394694e+00 5.95100927900937e-02 -1.13671143573967e-01 + 1.36363636363636e+01 1.20642687925599e+00 7.05802370100983e-02 -1.12460113720568e-01 + 1.42424242424242e+01 1.16512824375798e+00 8.18308265484637e-02 -1.11416728271022e-01 + 1.48484848484848e+01 1.13845165437591e+00 9.33501183013086e-02 -1.10513745021243e-01 + 1.54545454545455e+01 1.12012151200243e+00 1.05371259823310e-01 -1.12074593125414e-01 + 1.60606060606061e+01 1.10521158214097e+00 1.17537515544027e-01 -1.14635056143715e-01 + 1.66666666666667e+01 1.09605105013413e+00 1.29504477189816e-01 -1.18698748541531e-01 + 1.72727272727273e+01 1.09038474770029e+00 1.41619143192006e-01 -1.22755992205202e-01 + 1.78787878787879e+01 1.08898921460796e+00 1.53914338613840e-01 -1.26805354000924e-01 + 1.84848484848485e+01 1.09852690400848e+00 1.67121306650109e-01 -1.30271150233030e-01 + 1.90909090909091e+01 1.10900797848342e+00 1.80185918785840e-01 -1.33848294218024e-01 + 1.96969696969697e+01 1.10934527307501e+00 1.91151684117947e-01 -1.38883475019382e-01 + 2.03030303030303e+01 1.10872617200819e+00 2.02082800980853e-01 -1.43953835687333e-01 + 2.09090909090909e+01 1.10715062117621e+00 2.12979267414367e-01 -1.49203757196069e-01 + 2.15151515151515e+01 1.10557507034423e+00 2.23875733847882e-01 -1.54503423314042e-01 + 2.21212121212121e+01 1.10260124642550e+00 2.34778135695999e-01 -1.59652147931712e-01 + 2.27272727272727e+01 1.09403576887978e+00 2.45704273095417e-01 -1.64232639974624e-01 + 2.33333333333333e+01 1.08547029133405e+00 2.56630410494836e-01 -1.68847929010858e-01 + 2.39393939393939e+01 1.07690481378832e+00 2.67556547894255e-01 -1.73665468151725e-01 + 2.45454545454545e+01 1.07004041681628e+00 2.79119118191653e-01 -1.77890036537271e-01 + 2.51515151515151e+01 1.06336502473105e+00 2.90752401734336e-01 -1.82048720700615e-01 + 2.57575757575758e+01 1.05668963264583e+00 3.02385685277020e-01 -1.86207404863960e-01 + 2.63636363636364e+01 1.05078168869387e+00 3.14409261973987e-01 -1.90102460494435e-01 + 2.69696969696970e+01 1.04538545633799e+00 3.26693074541322e-01 -1.93821736457880e-01 + 2.75757575757576e+01 1.03998922398212e+00 3.38976887108657e-01 -1.97541012421324e-01 + 2.81818181818182e+01 1.03484090277918e+00 3.51437477732768e-01 -2.01170473836824e-01 + 2.87878787878788e+01 1.03027099131248e+00 3.64310515106369e-01 -2.04590385950606e-01 + 2.93939393939394e+01 1.02570107984578e+00 3.77183552479970e-01 -2.08010298064387e-01 + 3.00000000000000e+01 1.02113116837907e+00 3.90056589853572e-01 -2.11430210178169e-01 + 3.30000000000000e+01 1.00119460561295e+00 4.57145854597991e-01 -2.27086388641851e-01 + 3.60000000000000e+01 9.81921720811872e-01 5.27047589477837e-01 -2.41904140621254e-01 + 3.90000000000000e+01 9.61260291943995e-01 5.99606299882174e-01 -2.56159440416738e-01 + 4.20000000000000e+01 9.36935736815422e-01 6.73802755955525e-01 -2.70019544874094e-01 + 4.50000000000000e+01 9.11289556833257e-01 7.48405461801475e-01 -2.83768812367968e-01 + 4.80000000000000e+01 8.78369078677083e-01 8.22907477862781e-01 -2.97042946965006e-01 + 5.10000000000000e+01 8.41242012973183e-01 8.95844198388958e-01 -3.10074656049880e-01 + 5.40000000000000e+01 7.95701501741868e-01 9.65650227215581e-01 -3.22614713534726e-01 + 5.70000000000000e+01 7.50161338413173e-01 1.03545572276536e+00 -3.35153534620333e-01 + 6.00000000000000e+01 7.04621349034462e-01 1.10526095167874e+00 -3.47689985564868e-01 + 6.30000000000000e+01 6.43094140155942e-01 1.16178264450123e+00 -3.58895514925207e-01 + 6.60000000000000e+01 5.81566794241577e-01 1.21830422346273e+00 -3.70096619015063e-01 + 6.90000000000000e+01 5.20039448327212e-01 1.27482580242423e+00 -3.81292926550571e-01 + 7.20000000000000e+01 4.50922061318250e-01 1.31785610107633e+00 -3.91197073364813e-01 + 7.50000000000000e+01 3.78009809140240e-01 1.35414103575821e+00 -4.00450410082631e-01 + 7.80000000000000e+01 3.05096426319516e-01 1.39042638623652e+00 -4.09696121786907e-01 + 8.10000000000000e+01 2.30838925091062e-01 1.41846077220858e+00 -4.18058441063076e-01 + 8.40000000000000e+01 1.53893279831030e-01 1.42999379871131e+00 -4.24659851438870e-01 + 8.70000000000000e+01 7.69466467481749e-02 1.44152691331999e+00 -4.31250229720335e-01 + 9.00000000000000e+01 -3.36172637530740e-07 1.45305992801866e+00 -4.37829850424638e-01 + 9.30000000000000e+01 -5.38627383393683e-02 1.44152690151593e+00 -4.40933372026436e-01 + 9.60000000000000e+01 -1.07725146245282e-01 1.42999383096059e+00 -4.44037873446937e-01 + 9.90000000000000e+01 -1.61587565629768e-01 1.41846067229841e+00 -4.47143282683005e-01 + 1.02000000000000e+02 -2.13567566267535e-01 1.39042621049931e+00 -4.46986201155388e-01 + 1.05000000000000e+02 -2.64606377915867e-01 1.35414127581743e+00 -4.45198189623654e-01 + 1.08000000000000e+02 -3.15645479300682e-01 1.31785592534089e+00 -4.43410060853994e-01 + 1.11000000000000e+02 -3.64027804983567e-01 1.27482531278278e+00 -4.40372525830713e-01 + 1.14000000000000e+02 -4.07096660176995e-01 1.21830438150688e+00 -4.34835474017044e-01 + 1.17000000000000e+02 -4.50165647641462e-01 1.16178301844503e+00 -4.29298134131730e-01 + 1.20000000000000e+02 -4.93234679359343e-01 1.10526141350648e+00 -4.23760689165608e-01 + 1.23000000000000e+02 -5.25113031922223e-01 1.03545618459309e+00 -4.16386674177567e-01 + 1.26000000000000e+02 -5.56991306252975e-01 9.65650689048611e-01 -4.09012018270847e-01 + 1.29000000000000e+02 -5.88869424113624e-01 8.95844660221987e-01 -4.01636451380112e-01 + 1.32000000000000e+02 -6.13161255971681e-01 8.22874224418486e-01 -3.94888279932588e-01 + 1.35000000000000e+02 -6.33659953815723e-01 7.48321588883743e-01 -3.88452749684788e-01 + 1.38000000000000e+02 -6.54157816774948e-01 6.73769502775918e-01 -3.82015808693097e-01 + 1.41000000000000e+02 -6.72519858324716e-01 6.00666916692205e-01 -3.77450446527224e-01 + 1.44000000000000e+02 -6.86610239724511e-01 5.30463342418639e-01 -3.76628216553060e-01 + 1.47000000000000e+02 -7.00700113478808e-01 4.60260101212902e-01 -3.75801923510001e-01 + 1.50000000000000e+02 -7.14789733419415e-01 3.90057026535133e-01 -3.74971722702591e-01 + 1.53000000000000e+02 -7.26083351466705e-01 3.34899268561139e-01 -3.90699237662118e-01 + 1.56000000000000e+02 -7.37376919859767e-01 2.79741654709182e-01 -4.06434613881277e-01 + 1.59000000000000e+02 -7.49369636696621e-01 2.24584258977831e-01 -4.22178074951782e-01 + 1.62000000000000e+02 -6.78487565748514e-01 1.85578685533409e-01 -4.41942545112509e-01 + 1.65000000000000e+02 -5.65406079877361e-01 1.54649159831924e-01 -4.63714630913619e-01 + 1.68000000000000e+02 -4.44894229884888e-01 1.23719388559455e-01 -4.85485784604534e-01 + 1.71000000000000e+02 -3.31496503011607e-01 9.27895975192221e-02 -4.50000513056908e-01 + 1.74000000000000e+02 -2.20997628314192e-01 6.18597669425397e-02 -2.99999717902353e-01 + 1.77000000000000e+02 -1.09575522573893e-01 5.10040358195194e-02 -1.48718747985670e-01 + 1.80000000000000e+02 0.00000000000000e+00 5.02017886725028e-02 0.00000000000000e+00 diff --git a/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_13.dat b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_13.dat new file mode 100644 index 00000000..92b13a2b --- /dev/null +++ b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_13.dat @@ -0,0 +1,254 @@ +! ------------ AirfoilInfo v1.01.x Input File ---------------------------------- +! AeroElasticSE FAST driver +! line +! line +! ------------------------------------------------------------------------------ +DEFAULT InterpOrd ! Interpolation order to use for quasi-steady table lookup {1=linear; 3=cubic spline; "default"} [default=3] +1 NonDimArea ! The non-dimensional area of the airfoil (area/chord^2) (set to 1.0 if unsure or unneeded) +@"NREL-2p8-127_AF13_Coords.txt" NumCoords ! The number of coordinates in the airfoil shape file. Set to zero if coordinates not included. +AF13_BL.txt BL_file ! The file name including the boundary layer characteristics of the profile. Ignored if the aeroacoustic module is not called. +1 NumTabs ! Number of airfoil tables in this file. Each table must have lines for Re and Ctrl. +! ------------------------------------------------------------------------------ +! data for table 1 +! ------------------------------------------------------------------------------ +6.000000 Re ! Reynolds number in millions +0 Ctrl ! Control setting (must be 0 for current AirfoilInfo) +True InclUAdata ! Is unsteady aerodynamics data included in this table? If TRUE, then include 30 UA coefficients below this line +!........................................ +-2.132099 alpha0 ! 0-lift angle of attack, depends on airfoil. +11.682019 alpha1 ! Angle of attack at f=0.7, (approximately the stall angle) for AOA>alpha0. (deg) +-9.246885 alpha2 ! Angle of attack at f=0.7, (approximately the stall angle) for AOA1] +0.000000 S2 ! Constant in the f curve best-fit for AOA> alpha1; by definition it depends on the airfoil. [ignored if UAMod<>1] +0.000000 S3 ! Constant in the f curve best-fit for alpha2<=AOA< alpha0; by definition it depends on the airfoil. [ignored if UAMod<>1] +0.000000 S4 ! Constant in the f curve best-fit for AOA< alpha2; by definition it depends on the airfoil. [ignored if UAMod<>1] +1.467246 Cn1 ! Critical value of C0n at leading edge separation. It should be extracted from airfoil data at a given Mach and Reynolds number. It can be calculated from the static value of Cn at either the break in the pitching moment or the loss of chord force at the onset of stall. It is close to the condition of maximum lift of the airfoil at low Mach numbers. +-1.116975 Cn2 ! As Cn1 for negative AOAs. +Default St_sh ! Strouhal's shedding frequency constant. [default = 0.19] +0.010706 Cd0 ! 2D drag coefficient value at 0-lift. +-0.078417 Cm0 ! 2D pitching moment coefficient about 1/4-chord location, at 0-lift, positive if nose up. [If the aerodynamics coefficients table does not include a column for Cm, this needs to be set to 0.0] +0.000000 k0 ! Constant in the \hat(x)_cp curve best-fit; = (\hat(x)_AC-0.25). [ignored if UAMod<>1] +0.000000 k1 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k2 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k3 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k1_hat ! Constant in the expression of Cc due to leading edge vortex effects. [ignored if UAMod<>1] +Default x_cp_bar ! Constant in the expression of \hat(x)_cp^v. [ignored if UAMod<>1, default = 0.2] +Default UACutout ! Angle of attack above which unsteady aerodynamics are disabled (deg). [Specifying the string "Default" sets UACutout to 45 degrees] +Default filtCutOff ! Cut-off frequency (-3 dB corner frequency) for low-pass filtering the AoA input to UA, as well as the 1st and 2nd derivatives (Hz) [default = 20] +!........................................ +! Table of aerodynamics coefficients +200 NumAlf ! Number of data lines in the following table +! Alpha Cl Cd Cm +! (deg) (-) (-) (-) +-1.80000000000000e+02 0.00000000000000e+00 4.87439042124992e-02 0.00000000000000e+00 +-1.77000000000000e+02 1.13601999469549e-01 4.87439042124992e-02 1.19176415715757e-01 +-1.74000000000000e+02 2.28858413112315e-01 5.84925712756744e-02 2.39999774321882e-01 +-1.71000000000000e+02 3.43288316600078e-01 8.77388925055090e-02 3.60000410445527e-01 +-1.68000000000000e+02 4.57070767928178e-01 1.17275421818159e-01 3.18708357160145e-01 +-1.65000000000000e+02 5.71129134749526e-01 1.46957051785061e-01 1.96771841693633e-01 +-1.62000000000000e+02 6.81811167127312e-01 1.76639445546079e-01 7.48344304685462e-02 +-1.59000000000000e+02 7.50644491717964e-01 2.14984200570790e-01 -5.07801650458084e-03 +-1.56000000000000e+02 7.37523770619090e-01 2.70653385079522e-01 1.06132839067504e-03 +-1.53000000000000e+02 7.25223845001242e-01 3.26322594869384e-01 8.04336961373999e-03 +-1.50000000000000e+02 7.12923727515902e-01 3.81991851817702e-01 1.50360358377684e-02 +-1.47000000000000e+02 6.99053142386901e-01 4.52474247296891e-01 2.96995895978959e-02 +-1.44000000000000e+02 6.85182304280847e-01 5.22956853217613e-01 4.43686473866053e-02 +-1.41000000000000e+02 6.71310960202625e-01 5.93439880036427e-01 5.90442691380621e-02 +-1.38000000000000e+02 6.53114909413893e-01 6.66865106551800e-01 7.40923427363092e-02 +-1.35000000000000e+02 6.32756514043044e-01 7.41761426946880e-01 8.93274281204840e-02 +-1.32000000000000e+02 6.12397285385553e-01 8.16658429255323e-01 1.04567050663022e-01 +-1.29000000000000e+02 5.88229626117782e-01 8.89991527762646e-01 1.19947402883451e-01 +-1.26000000000000e+02 5.56445087582313e-01 9.60196811237631e-01 1.35603342201244e-01 +-1.23000000000000e+02 5.24660391861842e-01 1.03040155838038e+00 1.51263206732352e-01 +-1.20000000000000e+02 4.92875617551808e-01 1.10060603736703e+00 1.66927716624602e-01 +-1.17000000000000e+02 4.49867900921898e-01 1.15756854481392e+00 1.81710954488631e-01 +-1.14000000000000e+02 4.06860185400029e-01 1.21453080878140e+00 1.96498840434726e-01 +-1.11000000000000e+02 3.63852515987308e-01 1.27149263759476e+00 2.11292122383483e-01 +-1.08000000000000e+02 3.15513980484258e-01 1.31498386088960e+00 2.24396145865201e-01 +-1.05000000000000e+02 2.64509971345682e-01 1.35173967885259e+00 2.36659399343987e-01 +-1.02000000000000e+02 2.13506123000612e-01 1.38849507562982e+00 2.48931685712608e-01 +-9.90000000000000e+01 1.61553244788091e-01 1.41700492873292e+00 2.59841073682875e-01 +-9.60000000000000e+01 1.07702265733195e-01 1.42902333732993e+00 2.68014448982559e-01 +-9.30000000000000e+01 5.38512980694728e-02 1.44104165411306e+00 2.76206223274710e-01 +-9.00000000000000e+01 3.36101235326894e-07 1.45305992499009e+00 2.84424528048508e-01 +-8.70000000000000e+01 -5.38512429529903e-02 1.44104166641377e+00 2.88179235636605e-01 +-8.40000000000000e+01 -1.07702416312529e-01 1.42902330372378e+00 2.92116238002531e-01 +-8.10000000000000e+01 -1.61552778284462e-01 1.41700503284675e+00 2.96384910251329e-01 +-7.80000000000000e+01 -2.13505875975934e-01 1.38849525364560e+00 2.96589518980285e-01 +-7.50000000000000e+01 -2.64510308783977e-01 1.35173943568081e+00 2.94839423717641e-01 +-7.20000000000000e+01 -3.15513733464136e-01 1.31498403890358e+00 2.93086106067290e-01 +-6.90000000000000e+01 -3.63852143411397e-01 1.27149313105570e+00 2.90081406410839e-01 +-6.60000000000000e+01 -4.06860305658320e-01 1.21453064950441e+00 2.84576673209790e-01 +-6.30000000000000e+01 -4.49868185458844e-01 1.15756816795312e+00 2.79066340953731e-01 +-6.00000000000000e+01 -4.92875827838210e-01 1.10060557289787e+00 2.73549730680385e-01 +-5.70000000000000e+01 -5.24660602148244e-01 1.03040109391122e+00 2.66198212861305e-01 +-5.40000000000000e+01 -5.56445297867155e-01 9.60196346763153e-01 2.58837329083779e-01 +-5.10000000000000e+01 -5.88229836402624e-01 8.89991063288168e-01 2.51465219825159e-01 +-4.80000000000000e+01 -6.14103823719259e-01 8.16681742398572e-01 2.44260248495120e-01 +-4.50000000000000e+01 -6.37022630417404e-01 7.41820452687947e-01 2.37125494405563e-01 +-4.20000000000000e+01 -6.54821434392937e-01 6.66888419508008e-01 2.31318374407913e-01 +-3.90000000000000e+01 -6.71686771395590e-01 5.92370007881034e-01 2.26128186404354e-01 +-3.60000000000000e+01 -6.85959395421995e-01 5.19513505734105e-01 2.23293038777573e-01 +-3.30000000000000e+01 -6.99228262265746e-01 4.49336693515259e-01 2.23281989121863e-01 +-3.00000000000000e+01 -7.12923826438148e-01 3.81991413473000e-01 2.26408555434034e-01 +-2.93939393939394e+01 -7.16063242755988e-01 3.69070660189083e-01 2.27884386933293e-01 +-2.87878787878788e+01 -7.19202659073829e-01 3.56149906905165e-01 2.29360218432552e-01 +-2.81818181818182e+01 -7.22342075391669e-01 3.43229153621248e-01 2.30836049931811e-01 +-2.75757575757576e+01 -7.25879646593120e-01 3.30722936547354e-01 2.32910797277799e-01 +-2.69696969696970e+01 -7.29587870240511e-01 3.18394393090142e-01 2.35242244863728e-01 +-2.63636363636364e+01 -7.33296093887901e-01 3.06065849632931e-01 2.37573692449656e-01 +-2.57575757575758e+01 -7.37358552649944e-01 2.93998789131352e-01 2.40351599308823e-01 +-2.51515151515151e+01 -7.41952281524987e-01 2.82323892121304e-01 2.43799091024856e-01 +-2.45454545454545e+01 -7.46546010400030e-01 2.70648995111257e-01 2.47246582740888e-01 +-2.39393939393939e+01 -7.51270810440089e-01 2.59045122954569e-01 2.50842931746802e-01 +-2.33333333333333e+01 -7.57175276341296e-01 2.48080488228869e-01 2.55779025181128e-01 +-2.27272727272727e+01 -7.63079742242504e-01 2.37115853503168e-01 2.61669103088351e-01 +-2.21212121212121e+01 -7.68984208143711e-01 2.26151218777467e-01 2.66787136053718e-01 +-2.15151515151515e+01 -7.98558741205574e-01 2.18978684775324e-01 2.59268734046189e-01 +-2.09090909090909e+01 -8.39976990506764e-01 2.12754419878834e-01 2.46412877782449e-01 +-2.03030303030303e+01 -8.77626065799621e-01 2.06530154982344e-01 2.32873392185209e-01 +-1.96969696969697e+01 -9.12482277726115e-01 2.00406617873157e-01 2.16079231533506e-01 +-1.90909090909091e+01 -9.44653374099275e-01 1.94383802853063e-01 1.96196944890485e-01 +-1.84848484848485e+01 -9.76556738297402e-01 1.88868061750279e-01 1.76251855690617e-01 +-1.78787878787879e+01 -1.00830988060465e+00 1.83317104202353e-01 1.56918611734039e-01 +-1.72727272727273e+01 -1.03997095936839e+00 1.76526361566991e-01 1.37892024373634e-01 +-1.66666666666667e+01 -1.07157049021422e+00 1.70932183497624e-01 1.18865299601930e-01 +-1.60606060606061e+01 -1.10312717894668e+00 1.65593044673498e-01 9.98384624039651e-02 +-1.54545454545455e+01 -1.11507119669234e+00 1.58446673227857e-01 8.41684149093784e-02 +-1.48484848484848e+01 -1.11477271836942e+00 1.50207476871942e-01 7.03417694480957e-02 +-1.42424242424242e+01 -1.08423257216199e+00 1.39348090503607e-01 6.20173634895011e-02 +-1.36363636363636e+01 -1.04896032877406e+00 1.28119902100447e-01 5.40305604199166e-02 +-1.30303030303030e+01 -1.01046372636334e+00 1.16637431776633e-01 4.49260984726437e-02 +-1.24242424242424e+01 -9.69201936614847e-01 1.05499178414566e-01 3.32219061711730e-02 +-1.18181818181818e+01 -9.27767400425763e-01 9.49119646912448e-02 2.16483145014490e-02 +-1.12121212121212e+01 -8.86480598336731e-01 8.55891565143775e-02 1.06380104995937e-02 +-1.06060606060606e+01 -8.43514329482308e-01 7.70087578463476e-02 1.14934323347435e-03 +-1.00000000000000e+01 -7.98856262424989e-01 6.88029421594717e-02 -7.48514667045178e-03 +-9.39393939393939e+00 -7.63413220908471e-01 5.72619896948118e-02 -1.75515357315967e-02 +-8.78787878787879e+00 -7.36855164567028e-01 4.49241428048966e-02 -2.67299768784618e-02 +-8.18181818181818e+00 -7.21915221248136e-01 3.22666539335863e-02 -3.43270785756021e-02 +-7.57575757575758e+00 -6.80107790322963e-01 2.47696277944221e-02 -3.79455763749705e-02 +-6.96969696969697e+00 -6.25477329057538e-01 2.00640152396707e-02 -4.00917938604969e-02 +-6.36363636363636e+00 -5.45385415536934e-01 1.76703500104717e-02 -4.47595761821227e-02 +-5.75757575757576e+00 -4.65240863542729e-01 1.56676325439870e-02 -4.94624634693340e-02 +-5.15151515151515e+00 -3.85177304810552e-01 1.41170830647471e-02 -5.47806233959061e-02 +-4.54545454545454e+00 -3.05186013364708e-01 1.29299720858053e-02 -6.00838561640560e-02 +-3.93939393939394e+00 -2.25496618815856e-01 1.19194070246950e-02 -6.52622261528225e-02 +-3.33333333333333e+00 -1.50095854632385e-01 1.14661881877472e-02 -7.00888229733615e-02 +-2.72727272727273e+00 -7.44807687769198e-02 1.10712748312864e-02 -7.44803490024561e-02 +-2.12121212121212e+00 1.36241455738510e-03 1.06994983826237e-02 -7.84888091237353e-02 +-1.51515151515152e+00 7.79762724684800e-02 1.04764559842521e-02 -8.22769309796209e-02 +-9.09090909090912e-01 1.55093196357546e-01 1.03282187235360e-02 -8.59707384355398e-02 +-3.03030303030302e-01 2.33690956667381e-01 1.03497391513504e-02 -8.95788413712978e-02 + 3.03030303030302e-01 3.12230375322369e-01 1.03960832854878e-02 -9.29631294177707e-02 + 9.09090909090912e-01 3.90723642801794e-01 1.04626363547074e-02 -9.61417302922719e-02 + 1.51515151515152e+00 4.69223374488536e-01 1.05181765096339e-02 -9.91269841658500e-02 + 2.12121212121212e+00 5.47419021984281e-01 1.05986866302366e-02 -1.01951326898863e-01 + 2.72727272727273e+00 6.24353465324347e-01 1.07913520395363e-02 -1.04285374966365e-01 + 3.33333333333333e+00 7.00719049213690e-01 1.09882631518878e-02 -1.06367221462522e-01 + 3.93939393939394e+00 7.76662113860127e-01 1.11995924883540e-02 -1.08233532083904e-01 + 4.54545454545455e+00 8.51062527788879e-01 1.14677130840408e-02 -1.09981051673887e-01 + 5.15151515151515e+00 9.24618318776539e-01 1.17484143214346e-02 -1.11607861589439e-01 + 5.75757575757576e+00 9.96131045922850e-01 1.20661413484365e-02 -1.12922063002211e-01 + 6.36363636363637e+00 1.06530124476682e+00 1.24411013682114e-02 -1.13971538180268e-01 + 6.96969696969697e+00 1.13294924210721e+00 1.28499924886479e-02 -1.14845663241843e-01 + 7.57575757575757e+00 1.19647826401428e+00 1.33185723521347e-02 -1.15548552499834e-01 + 8.18181818181818e+00 1.25852214595514e+00 1.37822042010170e-02 -1.16225412192196e-01 + 8.78787878787879e+00 1.31953258382690e+00 1.42014660644829e-02 -1.16973536925898e-01 + 9.39393939393939e+00 1.37722282574832e+00 1.52499336492677e-02 -1.16582058795787e-01 + 1.00000000000000e+01 1.42782587729733e+00 1.66203055937069e-02 -1.15506211836930e-01 + 1.06060606060606e+01 1.46349417020859e+00 1.89049864855517e-02 -1.13428166197566e-01 + 1.12121212121212e+01 1.48851533807067e+00 2.17360570752516e-02 -1.11086533657004e-01 + 1.18181818181818e+01 1.49375899629952e+00 2.51530002017571e-02 -1.08182154414350e-01 + 1.24242424242424e+01 1.39019183027460e+00 4.01241150571406e-02 -1.10396226977541e-01 + 1.30303030303030e+01 1.23558289690220e+00 5.95330302498055e-02 -1.14566124306707e-01 + 1.36363636363636e+01 1.17983620766855e+00 6.99436564860179e-02 -1.13107355391663e-01 + 1.42424242424242e+01 1.13261025086269e+00 8.02708219712224e-02 -1.11811426810697e-01 + 1.48484848484848e+01 1.10434568242928e+00 9.05273912159466e-02 -1.10627750277284e-01 + 1.54545454545455e+01 1.08509274406338e+00 1.01044358671353e-01 -1.11196367879537e-01 + 1.60606060606061e+01 1.06957515718470e+00 1.11649937873699e-01 -1.12390832093296e-01 + 1.66666666666667e+01 1.06064834245443e+00 1.22271986435775e-01 -1.14792794654718e-01 + 1.72727272727273e+01 1.05566858193663e+00 1.33123890508199e-01 -1.17423076146692e-01 + 1.78787878787879e+01 1.05551304883942e+00 1.44256732007905e-01 -1.20332417004491e-01 + 1.84848484848485e+01 1.06725149416938e+00 1.56758954022331e-01 -1.23671200892881e-01 + 1.90909090909091e+01 1.08077437232159e+00 1.69418290548337e-01 -1.27335467738334e-01 + 1.96969696969697e+01 1.08755966688782e+00 1.81027946977387e-01 -1.32236261105666e-01 + 2.03030303030303e+01 1.09235894047421e+00 1.92457859565650e-01 -1.37361247840428e-01 + 2.09090909090909e+01 1.09517208072444e+00 2.03708018144370e-01 -1.42882710356362e-01 + 2.15151515151515e+01 1.09798522097467e+00 2.14958176723090e-01 -1.48463527012242e-01 + 2.21212121212121e+01 1.09854840217806e+00 2.26151218777467e-01 -1.53912838053508e-01 + 2.27272727272727e+01 1.09011406223620e+00 2.37115853503168e-01 -1.58878474315141e-01 + 2.33333333333333e+01 1.08167972229433e+00 2.48080488228869e-01 -1.63885629560299e-01 + 2.39393939393939e+01 1.07324538235247e+00 2.59045122954570e-01 -1.69134105044946e-01 + 2.45454545454545e+01 1.06649517893070e+00 2.70648995111257e-01 -1.73708687311479e-01 + 2.51515151515151e+01 1.05993209776363e+00 2.82323892121304e-01 -1.78208394164471e-01 + 2.57575757575758e+01 1.05336901659657e+00 2.93998789131352e-01 -1.82708101017462e-01 + 2.63636363636364e+01 1.04756481639234e+00 3.06065849632931e-01 -1.86905429493079e-01 + 2.69696969696970e+01 1.04226661544969e+00 3.18394393090142e-01 -1.90901141057530e-01 + 2.75757575757576e+01 1.03696841450705e+00 3.30722936547354e-01 -1.94896852621981e-01 + 2.81818181818182e+01 1.03191481277606e+00 3.43229153621248e-01 -1.98788509538092e-01 + 2.87878787878788e+01 1.02743189358122e+00 3.56149906905165e-01 -2.02437393101785e-01 + 2.93939393939394e+01 1.02294897438639e+00 3.69070660189083e-01 -2.06086276665478e-01 + 3.00000000000000e+01 1.01846605519156e+00 3.81991413473000e-01 -2.09735160229171e-01 + 3.30000000000000e+01 9.98896269436472e-01 4.49336693515259e-01 -2.26306031891365e-01 + 3.60000000000000e+01 9.79942808607176e-01 5.19513505734105e-01 -2.41883781570832e-01 + 3.90000000000000e+01 9.59552820645265e-01 5.92370007881034e-01 -2.56418564967551e-01 + 4.20000000000000e+01 9.35459598863631e-01 6.66888419508008e-01 -2.70550711580551e-01 + 4.50000000000000e+01 9.10032841705360e-01 7.41820452687947e-01 -2.84583661386136e-01 + 4.80000000000000e+01 8.77291164853731e-01 8.16681742398572e-01 -2.98125199456282e-01 + 5.10000000000000e+01 8.40327861925211e-01 8.89991063288168e-01 -3.11430203584398e-01 + 5.40000000000000e+01 7.94921035444153e-01 9.60196346763153e-01 -3.24242564733735e-01 + 5.70000000000000e+01 7.49514555844441e-01 1.03040109391122e+00 -3.37060914767786e-01 + 6.00000000000000e+01 7.04108249684082e-01 1.10060557289787e+00 -3.49883096668555e-01 + 6.30000000000000e+01 6.42668579003910e-01 1.15756816795312e+00 -3.61391087463078e-01 + 6.60000000000000e+01 5.81228770892357e-01 1.21453064950441e+00 -3.72900577797390e-01 + 6.90000000000000e+01 5.19788962780805e-01 1.27149313105570e+00 -3.84410594625320e-01 + 7.20000000000000e+01 4.50734175503690e-01 1.31498403890358e+00 -3.94650756300015e-01 + 7.50000000000000e+01 3.77872054532562e-01 1.35173943568081e+00 -4.04254594429255e-01 + 7.80000000000000e+01 3.05008674950305e-01 1.38849525364560e+00 -4.13856378244412e-01 + 8.10000000000000e+01 2.30789950548293e-01 1.41700503284675e+00 -4.22588303462247e-01 + 8.40000000000000e+01 1.53860630065887e-01 1.42902330372378e+00 -4.29581922692123e-01 + 8.70000000000000e+01 7.69303218853695e-02 1.44104166641377e+00 -4.36570514980957e-01 + 9.00000000000000e+01 -3.36101235559296e-07 1.45305992499009e+00 -4.43554018258070e-01 + 9.30000000000000e+01 -5.38512980694728e-02 1.44104165411306e+00 -4.46821429870465e-01 + 9.60000000000000e+01 -1.07702265733195e-01 1.42902333732993e+00 -4.50090063193436e-01 + 9.90000000000000e+01 -1.61553244788092e-01 1.41700492873292e+00 -4.53359826724784e-01 + 1.02000000000000e+02 -2.13506123000612e-01 1.38849507562982e+00 -4.53358356880233e-01 + 1.05000000000000e+02 -2.64509971345682e-01 1.35173967885259e+00 -4.51721761227933e-01 + 1.08000000000000e+02 -3.15513980484258e-01 1.31498386088960e+00 -4.50085315220303e-01 + 1.11000000000000e+02 -3.63852515987308e-01 1.27149263759476e+00 -4.47194708590916e-01 + 1.14000000000000e+02 -4.06860185400029e-01 1.21453080878140e+00 -4.41794921939120e-01 + 1.17000000000000e+02 -4.49867900921898e-01 1.15756854481392e+00 -4.36395234719870e-01 + 1.20000000000000e+02 -4.92875617551808e-01 1.10060603736703e+00 -4.30995807908883e-01 + 1.23000000000000e+02 -5.24660391861842e-01 1.03040155838038e+00 -4.23756434063717e-01 + 1.26000000000000e+02 -5.56445087582313e-01 9.60196811237631e-01 -4.16516996565852e-01 + 1.29000000000000e+02 -5.88229626117782e-01 8.89991527762645e-01 -4.09277210165741e-01 + 1.32000000000000e+02 -6.12397285385553e-01 8.16658429255322e-01 -4.02686723110960e-01 + 1.35000000000000e+02 -6.32756514043044e-01 7.41761426946880e-01 -3.96420479648652e-01 + 1.38000000000000e+02 -6.53114909413893e-01 6.66865106551800e-01 -3.90153798231996e-01 + 1.41000000000000e+02 -6.71310960202625e-01 5.93439880036427e-01 -3.85803144277468e-01 + 1.44000000000000e+02 -6.85182304280847e-01 5.22956853217613e-01 -3.85284327936909e-01 + 1.47000000000000e+02 -6.99053142386901e-01 4.52474247296891e-01 -3.84763389697547e-01 + 1.50000000000000e+02 -7.12923727515902e-01 3.81991851817701e-01 -3.84240435098614e-01 + 1.53000000000000e+02 -7.17713468565102e-01 3.27562673383999e-01 -4.00044506289342e-01 + 1.56000000000000e+02 -7.22503170158526e-01 2.73133681485946e-01 -4.15858223301289e-01 + 1.59000000000000e+02 -7.28127146175927e-01 2.18704987836167e-01 -4.31681847835051e-01 + 1.62000000000000e+02 -6.57546925365099e-01 1.80505932981753e-01 -4.49567289106761e-01 + 1.65000000000000e+02 -5.47955571734396e-01 1.50421834782562e-01 -4.68480081499263e-01 + 1.68000000000000e+02 -4.33508829076636e-01 1.20337481324609e-01 -4.87391973738006e-01 + 1.71000000000000e+02 -3.23710952534405e-01 9.02531541751285e-02 -4.50000513056908e-01 + 1.74000000000000e+02 -2.15807282191796e-01 6.01688796438182e-02 -2.99999717902353e-01 + 1.77000000000000e+02 -1.07173368611120e-01 4.95765701106933e-02 -1.48970519644697e-01 + 1.80000000000000e+02 0.00000000000000e+00 4.87439042124992e-02 0.00000000000000e+00 diff --git a/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_14.dat b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_14.dat new file mode 100644 index 00000000..229833e5 --- /dev/null +++ b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_14.dat @@ -0,0 +1,254 @@ +! ------------ AirfoilInfo v1.01.x Input File ---------------------------------- +! AeroElasticSE FAST driver +! line +! line +! ------------------------------------------------------------------------------ +DEFAULT InterpOrd ! Interpolation order to use for quasi-steady table lookup {1=linear; 3=cubic spline; "default"} [default=3] +1 NonDimArea ! The non-dimensional area of the airfoil (area/chord^2) (set to 1.0 if unsure or unneeded) +@"NREL-2p8-127_AF14_Coords.txt" NumCoords ! The number of coordinates in the airfoil shape file. Set to zero if coordinates not included. +AF14_BL.txt BL_file ! The file name including the boundary layer characteristics of the profile. Ignored if the aeroacoustic module is not called. +1 NumTabs ! Number of airfoil tables in this file. Each table must have lines for Re and Ctrl. +! ------------------------------------------------------------------------------ +! data for table 1 +! ------------------------------------------------------------------------------ +6.000000 Re ! Reynolds number in millions +0 Ctrl ! Control setting (must be 0 for current AirfoilInfo) +True InclUAdata ! Is unsteady aerodynamics data included in this table? If TRUE, then include 30 UA coefficients below this line +!........................................ +-2.166094 alpha0 ! 0-lift angle of attack, depends on airfoil. +11.851014 alpha1 ! Angle of attack at f=0.7, (approximately the stall angle) for AOA>alpha0. (deg) +-9.637248 alpha2 ! Angle of attack at f=0.7, (approximately the stall angle) for AOA1] +0.000000 S2 ! Constant in the f curve best-fit for AOA> alpha1; by definition it depends on the airfoil. [ignored if UAMod<>1] +0.000000 S3 ! Constant in the f curve best-fit for alpha2<=AOA< alpha0; by definition it depends on the airfoil. [ignored if UAMod<>1] +0.000000 S4 ! Constant in the f curve best-fit for AOA< alpha2; by definition it depends on the airfoil. [ignored if UAMod<>1] +1.502705 Cn1 ! Critical value of C0n at leading edge separation. It should be extracted from airfoil data at a given Mach and Reynolds number. It can be calculated from the static value of Cn at either the break in the pitching moment or the loss of chord force at the onset of stall. It is close to the condition of maximum lift of the airfoil at low Mach numbers. +-1.198117 Cn2 ! As Cn1 for negative AOAs. +Default St_sh ! Strouhal's shedding frequency constant. [default = 0.19] +0.010692 Cd0 ! 2D drag coefficient value at 0-lift. +-0.084655 Cm0 ! 2D pitching moment coefficient about 1/4-chord location, at 0-lift, positive if nose up. [If the aerodynamics coefficients table does not include a column for Cm, this needs to be set to 0.0] +0.000000 k0 ! Constant in the \hat(x)_cp curve best-fit; = (\hat(x)_AC-0.25). [ignored if UAMod<>1] +0.000000 k1 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k2 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k3 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k1_hat ! Constant in the expression of Cc due to leading edge vortex effects. [ignored if UAMod<>1] +Default x_cp_bar ! Constant in the expression of \hat(x)_cp^v. [ignored if UAMod<>1, default = 0.2] +Default UACutout ! Angle of attack above which unsteady aerodynamics are disabled (deg). [Specifying the string "Default" sets UACutout to 45 degrees] +Default filtCutOff ! Cut-off frequency (-3 dB corner frequency) for low-pass filtering the AoA input to UA, as well as the 1st and 2nd derivatives (Hz) [default = 20] +!........................................ +! Table of aerodynamics coefficients +200 NumAlf ! Number of data lines in the following table +! Alpha Cl Cd Cm +! (deg) (-) (-) (-) +-1.80000000000000e+02 0.00000000000000e+00 4.74971586892991e-02 0.00000000000000e+00 +-1.77000000000000e+02 1.11000230721027e-01 4.74971586892991e-02 1.19348662665291e-01 +-1.74000000000000e+02 2.23249498352695e-01 5.69965146964868e-02 2.39999774321882e-01 +-1.71000000000000e+02 3.34875005612777e-01 8.54948945736924e-02 3.60000410445527e-01 +-1.68000000000000e+02 4.46351865610983e-01 1.14102183123101e-01 3.18009867522619e-01 +-1.65000000000000e+02 5.57999076618718e-01 1.42763924737488e-01 1.95025625752222e-01 +-1.62000000000000e+02 6.68256570415867e-01 1.71426528385083e-01 7.20405402903902e-02 +-1.59000000000000e+02 7.38112012967269e-01 2.08990990812950e-01 -9.03147344265643e-03 +-1.56000000000000e+02 7.28701413125268e-01 2.64358869655133e-01 -4.58368783527860e-03 +-1.53000000000000e+02 7.20014801391652e-01 3.19726771476650e-01 4.84852864421045e-04 +-1.50000000000000e+02 7.11327966966767e-01 3.75094720564407e-01 5.41799540089436e-03 +-1.47000000000000e+02 6.97644694809602e-01 4.45815984052867e-01 2.02835508949186e-02 +-1.44000000000000e+02 6.83961170390853e-01 5.16537495536617e-01 3.51512653382985e-02 +-1.41000000000000e+02 6.70277141430926e-01 5.87259503028655e-01 5.00215815438595e-02 +-1.38000000000000e+02 6.52223041697912e-01 6.60960643393727e-01 6.52179053138514e-02 +-1.35000000000000e+02 6.31983915443519e-01 7.36151344151820e-01 8.05776041224766e-02 +-1.32000000000000e+02 6.11743957269201e-01 8.11342840122296e-01 9.59393162430393e-02 +-1.29000000000000e+02 5.87682487226497e-01 8.84986078503406e-01 1.11444964032245e-01 +-1.26000000000000e+02 5.55977975337812e-01 9.55532794347773e-01 1.27236023845822e-01 +-1.23000000000000e+02 5.24273305652762e-01 1.02607897125153e+00 1.43028582986147e-01 +-1.20000000000000e+02 4.92568557072479e-01 1.09662487869506e+00 1.58822953785748e-01 +-1.17000000000000e+02 4.49613275538441e-01 1.15396443469656e+00 1.73777165711677e-01 +-1.14000000000000e+02 4.06657958215625e-01 1.21130374584807e+00 1.88732854747424e-01 +-1.11000000000000e+02 3.63702613318511e-01 1.26864261896506e+00 2.03690155444885e-01 +-1.08000000000000e+02 3.15401526057875e-01 1.31252774478765e+00 2.16985072342206e-01 +-1.05000000000000e+02 2.64427526911241e-01 1.34968589451878e+00 2.29449925939083e-01 +-1.02000000000000e+02 2.13453578289375e-01 1.38684361845383e+00 2.41917717292569e-01 +-9.90000000000000e+01 1.61523894481612e-01 1.41576001404799e+00 2.53026853626378e-01 +-9.60000000000000e+01 1.07682698904138e-01 1.42819339598511e+00 2.61414906151363e-01 +-9.30000000000000e+01 5.38415146430987e-02 1.44062668293820e+00 2.69809084986757e-01 +-9.00000000000000e+01 3.36040174186750e-07 1.45305992240014e+00 2.78212559061635e-01 +-8.70000000000000e+01 -5.38414595366295e-02 1.44062669566363e+00 2.81853755036713e-01 +-8.40000000000000e+01 -1.07682849456116e-01 1.42819336121861e+00 2.85569122512613e-01 +-8.10000000000000e+01 -1.61523428062735e-01 1.41576012175667e+00 2.89419982005163e-01 +-7.80000000000000e+01 -2.13453331409509e-01 1.38684379841819e+00 2.89665265635515e-01 +-7.50000000000000e+01 -2.64427864151593e-01 1.34968564868523e+00 2.88138738774038e-01 +-7.20000000000000e+01 -3.15401279183096e-01 1.31252792475019e+00 2.86609458179388e-01 +-6.90000000000000e+01 -3.63702241195888e-01 1.26864311569235e+00 2.83820667109906e-01 +-6.60000000000000e+01 -4.06658078327606e-01 1.21130358551679e+00 2.78515251076842e-01 +-6.30000000000000e+01 -4.49613559728479e-01 1.15396405534123e+00 2.73204848612241e-01 +-6.00000000000000e+01 -4.92568766829435e-01 1.09662441196703e+00 2.67888882389067e-01 +-5.70000000000000e+01 -5.24273515409718e-01 1.02607850452350e+00 2.60728337244673e-01 +-5.40000000000000e+01 -5.55978185093202e-01 9.55532327614396e-01 2.53559556903730e-01 +-5.10000000000000e+01 -5.87682696981887e-01 8.84985611770030e-01 2.46380928095060e-01 +-4.80000000000000e+01 -6.13458630295659e-01 8.11357652574190e-01 2.39383508326475e-01 +-4.50000000000000e+01 -6.36270369602626e-01 7.36189121222556e-01 2.32464914094013e-01 +-4.20000000000000e+01 -6.53937701306032e-01 6.60975455724981e-01 2.26919127213316e-01 +-3.90000000000000e+01 -6.70664549725515e-01 5.86181715938499e-01 2.21997712524231e-01 +-3.60000000000000e+01 -6.84774756509486e-01 5.13070549905569e-01 2.19442879100228e-01 +-3.30000000000000e+01 -6.97852537348206e-01 4.42658498578043e-01 2.19788443952018e-01 +-3.00000000000000e+01 -7.11328064353672e-01 3.75094280797430e-01 2.23361039140397e-01 +-2.93939393939394e+01 -7.14415682762428e-01 3.62132722086743e-01 2.24952236186361e-01 +-2.87878787878788e+01 -7.17503301171185e-01 3.49171163376055e-01 2.26543433232325e-01 +-2.81818181818182e+01 -7.20590919579942e-01 3.36209604665368e-01 2.28134630278289e-01 +-2.75757575757576e+01 -7.24071834030542e-01 3.23664369017940e-01 2.30343477172995e-01 +-2.69696969696970e+01 -7.27721318387681e-01 3.11297572847134e-01 2.32817053854427e-01 +-2.63636363636364e+01 -7.31370802744820e-01 2.98930776676328e-01 2.35290630535858e-01 +-2.57575757575758e+01 -7.35371080478430e-01 2.86826529936594e-01 2.38225234034872e-01 +-2.51515151515151e+01 -7.39897466519906e-01 2.75116046152996e-01 2.41851270312120e-01 +-2.45454545454545e+01 -7.44423852561381e-01 2.63405562369399e-01 2.45477306589367e-01 +-2.39393939393939e+01 -7.49080204989271e-01 2.51766369918421e-01 2.49257235504190e-01 +-2.33333333333333e+01 -7.54906280057009e-01 2.40768813263367e-01 2.54422227951541e-01 +-2.27272727272727e+01 -7.60732355124748e-01 2.29771256608312e-01 2.60428793385145e-01 +-2.21212121212121e+01 -7.66558430192487e-01 2.18773699953258e-01 2.65754286761814e-01 +-2.15151515151515e+01 -8.00687554276612e-01 2.12395791755905e-01 2.54131477053226e-01 +-2.09090909090909e+01 -8.47011591503202e-01 2.07173092829286e-01 2.36349555357985e-01 +-2.03030303030303e+01 -8.90594276628836e-01 2.01950393902668e-01 2.17964558879003e-01 +-1.96969696969697e+01 -9.33116480486079e-01 1.96765628796972e-01 1.98214287245217e-01 +-1.90909090909091e+01 -9.74622494568323e-01 1.91618795366269e-01 1.77245579244523e-01 +-1.84848484848485e+01 -1.01601768577475e+00 1.86919414620951e-01 1.56221773196698e-01 +-1.78787878787879e+01 -1.05735116332665e+00 1.82188959514290e-01 1.35737748819307e-01 +-1.72727272727273e+01 -1.09864750288064e+00 1.76364686193561e-01 1.15524161434742e-01 +-1.66666666666667e+01 -1.13991853932663e+00 1.71295280735592e-01 9.53103144961163e-02 +-1.60606060606061e+01 -1.18117196285153e+00 1.66429521167139e-01 7.50962551972795e-02 +-1.54545454545455e+01 -1.19791272454831e+00 1.59575377638483e-01 5.91097556474128e-02 +-1.48484848484848e+01 -1.19934186806973e+00 1.51502853954205e-01 4.54449853411950e-02 +-1.42424242424242e+01 -1.16297897530355e+00 1.40460445425891e-01 3.82990945588821e-02 +-1.36363636363636e+01 -1.12077036373998e+00 1.29002431424042e-01 3.11065404436185e-02 +-1.30303030303030e+01 -1.07463320183473e+00 1.17263267706531e-01 2.26980761363050e-02 +-1.24242424242424e+01 -1.02518157920182e+00 1.05918643160515e-01 1.17933498379386e-02 +-1.18181818181818e+01 -9.75681942398755e-01 9.51959685529269e-02 1.19873623725293e-03 +-1.12121212121212e+01 -9.26571076805030e-01 8.58848934178665e-02 -8.41861521656647e-03 +-1.06060606060606e+01 -8.75664896114804e-01 7.74090431182947e-02 -1.63777998285526e-02 +-1.00000000000000e+01 -8.23237071758609e-01 6.93728235267388e-02 -2.34138528773980e-02 +-9.39393939393939e+00 -7.82111343672048e-01 5.75636308912248e-02 -3.21020160083091e-02 +-8.78787878787879e+00 -7.51375159974407e-01 4.47516034625548e-02 -3.98906956582438e-02 +-8.18181818181818e+00 -7.35088054943470e-01 3.08041630438302e-02 -4.60682064471990e-02 +-7.57575757575758e+00 -6.92836122752420e-01 2.31579933295670e-02 -4.89829934537834e-02 +-6.96969696969697e+00 -6.37949933369482e-01 1.87032507714761e-02 -5.07384454242695e-02 +-6.36363636363636e+00 -5.54161342148495e-01 1.67784052774049e-02 -5.53503816254145e-02 +-5.75757575757576e+00 -4.70840124165288e-01 1.50845427200835e-02 -5.98951476736281e-02 +-5.15151515151515e+00 -3.88292011066822e-01 1.36982538638481e-02 -6.45572843794330e-02 +-4.54545454545454e+00 -3.06502440552051e-01 1.26562227449715e-02 -6.91008881961310e-02 +-3.93939393939394e+00 -2.25310842700356e-01 1.17673191515673e-02 -7.35346491057446e-02 +-3.33333333333333e+00 -1.47988215381915e-01 1.13325276777439e-02 -7.76194041395815e-02 +-2.72727272727273e+00 -7.09984158942061e-02 1.09783067702849e-02 -8.14085077704442e-02 +-2.12121212121212e+00 5.67824274921396e-03 1.06696224794102e-02 -8.49142606714796e-02 +-1.51515151515152e+00 8.26102586756291e-02 1.04667274124626e-02 -8.82711832196438e-02 +-9.09090909090912e-01 1.59969016769918e-01 1.03323320303745e-02 -9.15655050496302e-02 +-3.03030303030302e-01 2.38974448513455e-01 1.03900461416016e-02 -9.47661275562079e-02 + 3.03030303030302e-01 3.17646859605712e-01 1.04649254982203e-02 -9.77901212356652e-02 + 9.09090909090912e-01 3.96007393557534e-01 1.05511605199152e-02 -1.00651121145792e-01 + 1.51515151515152e+00 4.74169429973799e-01 1.05752495413395e-02 -1.03293525376690e-01 + 2.12121212121212e+00 5.51911940760023e-01 1.06224929903068e-02 -1.05813765929291e-01 + 2.72727272727273e+00 6.28056580841275e-01 1.08108555850528e-02 -1.07977517357485e-01 + 3.33333333333333e+00 7.03798053899655e-01 1.09879017716880e-02 -1.09916646422344e-01 + 3.93939393939394e+00 7.79276493869128e-01 1.11758838962833e-02 -1.11658275595353e-01 + 4.54545454545455e+00 8.53499796067138e-01 1.14129478363666e-02 -1.13253311951308e-01 + 5.15151515151515e+00 9.26946560290491e-01 1.16638391697767e-02 -1.14737019623995e-01 + 5.75757575757576e+00 9.98458448466187e-01 1.19568385022413e-02 -1.15939256762654e-01 + 6.36363636363637e+00 1.06804425733062e+00 1.22991453288649e-02 -1.16892495532205e-01 + 6.96969696969697e+00 1.13638020854557e+00 1.26698916273089e-02 -1.17681562497719e-01 + 7.57575757575757e+00 1.20139147533564e+00 1.30839223585554e-02 -1.18207998448365e-01 + 8.18181818181818e+00 1.26525870625966e+00 1.34927417386065e-02 -1.18675618171796e-01 + 8.78787878787879e+00 1.32856174203142e+00 1.38637786532075e-02 -1.19120015634172e-01 + 9.39393939393939e+00 1.38894849360344e+00 1.46729594502212e-02 -1.18422993276735e-01 + 1.00000000000000e+01 1.44308909541765e+00 1.56494510556849e-02 -1.17051335409731e-01 + 1.06060606060606e+01 1.48423802370368e+00 1.71908084497653e-02 -1.14598756389549e-01 + 1.12121212121212e+01 1.51610502455934e+00 1.91222908592098e-02 -1.11779817617528e-01 + 1.18181818181818e+01 1.53072866564893e+00 2.16025680835697e-02 -1.08254794802547e-01 + 1.24242424242424e+01 1.39977849156389e+00 3.79528706066007e-02 -1.10603299151591e-01 + 1.30303030303030e+01 1.21617535220138e+00 5.95675147584135e-02 -1.15202550970118e-01 + 1.36363636363636e+01 1.15533504132719e+00 6.93992690943369e-02 -1.13563572716609e-01 + 1.42424242424242e+01 1.10480169457590e+00 7.89367459341939e-02 -1.12086468683529e-01 + 1.48484848484848e+01 1.07517912705030e+00 8.81134671681645e-02 -1.10736245553130e-01 + 1.54545454545455e+01 1.05513703714054e+00 9.73441034120854e-02 -1.10445332098790e-01 + 1.60606060606061e+01 1.03909979751391e+00 1.06615031950527e-01 -1.10471629053083e-01 + 1.66666666666667e+01 1.03037285182419e+00 1.16086945222589e-01 -1.11452522736188e-01 + 1.72727272727273e+01 1.02598020440334e+00 1.25858967571876e-01 -1.12862502655475e-01 + 1.78787878787879e+01 1.02688508760461e+00 1.35997793709910e-01 -1.14796926748810e-01 + 1.84848484848485e+01 1.04050556314885e+00 1.47897334941441e-01 -1.18027092927592e-01 + 1.90909090909091e+01 1.05662971405014e+00 1.60210090125818e-01 -1.21765865016242e-01 + 1.96969696969697e+01 1.06892917336845e+00 1.72370385761586e-01 -1.26551733685257e-01 + 2.03030303030303e+01 1.07836210245173e+00 1.84226855703769e-01 -1.31723435235985e-01 + 2.09090909090909e+01 1.08492833913008e+00 1.95779482763855e-01 -1.37432962053028e-01 + 2.15151515151515e+01 1.09149457580843e+00 2.07332109823942e-01 -1.43194849094184e-01 + 2.21212121212121e+01 1.09508251337799e+00 2.18773699953258e-01 -1.48870391290255e-01 + 2.27272727272727e+01 1.08676031896276e+00 2.29771256608312e-01 -1.54237881279540e-01 + 2.33333333333333e+01 1.07843812454753e+00 2.40768813263367e-01 -1.59641997918361e-01 + 2.39393939393939e+01 1.07011593013229e+00 2.51766369918421e-01 -1.65258999148450e-01 + 2.45454545454545e+01 1.06346338211567e+00 2.63405562369399e-01 -1.70132904338816e-01 + 2.51515151515151e+01 1.05699634637488e+00 2.75116046152996e-01 -1.74924245078642e-01 + 2.57575757575758e+01 1.05052931063409e+00 2.86826529936594e-01 -1.79715585818468e-01 + 2.63636363636364e+01 1.04481382943098e+00 2.98930776676328e-01 -1.84171410304438e-01 + 2.69696969696970e+01 1.03959946244701e+00 3.11297572847134e-01 -1.88403522528518e-01 + 2.75757575757576e+01 1.03438509546304e+00 3.23664369017940e-01 -1.92635634752598e-01 + 2.81818181818182e+01 1.02941249540321e+00 3.36209604665368e-01 -1.96751514558490e-01 + 2.87878787878788e+01 1.02500396977555e+00 3.49171163376055e-01 -2.00596208653092e-01 + 2.93939393939394e+01 1.02059544414789e+00 3.62132722086743e-01 -2.04440902747695e-01 + 3.00000000000000e+01 1.01618691852022e+00 3.75094280797430e-01 -2.08285596842297e-01 + 3.30000000000000e+01 9.96930791089291e-01 4.42658498578043e-01 -2.25638690746125e-01 + 3.60000000000000e+01 9.78250493475424e-01 5.13070549905569e-01 -2.41866371031337e-01 + 3.90000000000000e+01 9.58092634837620e-01 5.86181715938499e-01 -2.56756566563372e-01 + 4.20000000000000e+01 9.34197243420856e-01 6.60975455724981e-01 -2.71189386382951e-01 + 4.50000000000000e+01 9.08958131052610e-01 7.36189121222556e-01 -2.85513863759938e-01 + 4.80000000000000e+01 8.76369360506042e-01 8.11357652574190e-01 -2.99318564738472e-01 + 5.10000000000000e+01 8.39546103316861e-01 8.84985611770030e-01 -3.12885528690573e-01 + 5.40000000000000e+01 7.94253600616922e-01 9.55532327614396e-01 -3.25953209472103e-01 + 5.70000000000000e+01 7.48961443924963e-01 1.02607850452350e+00 -3.39030396022098e-01 + 6.00000000000000e+01 7.03669460235677e-01 1.09662441196703e+00 -3.52114744115643e-01 + 6.30000000000000e+01 6.42304649985047e-01 1.15396405534123e+00 -3.63896004000846e-01 + 6.60000000000000e+01 5.80939701964786e-01 1.21130358551679e+00 -3.75682451037757e-01 + 6.90000000000000e+01 5.19574753944523e-01 1.26864311569235e+00 -3.87472927093907e-01 + 7.20000000000000e+01 4.50573500357888e-01 1.31252792475019e+00 -3.98011457008727e-01 + 7.50000000000000e+01 3.77754250313412e-01 1.34968564868523e+00 -4.07925210836086e-01 + 7.80000000000000e+01 3.04933632222489e-01 1.38684379841819e+00 -4.17841195787456e-01 + 8.10000000000000e+01 2.30748068771223e-01 1.41576012175667e+00 -4.26898468755288e-01 + 8.40000000000000e+01 1.53832708821342e-01 1.42819336121861e+00 -4.34236382280660e-01 + 8.70000000000000e+01 7.69163612800006e-02 1.44062669566363e+00 -4.41574423427714e-01 + 9.00000000000000e+01 -3.36040174418520e-07 1.45305992240014e+00 -4.48912349036806e-01 + 9.30000000000000e+01 -5.38415146430987e-02 1.44062668293820e+00 -4.52353830558963e-01 + 9.60000000000000e+01 -1.07682698904138e-01 1.42819339598511e+00 -4.55796422926281e-01 + 9.90000000000000e+01 -1.61523894481612e-01 1.41576001404799e+00 -4.59240045315168e-01 + 1.02000000000000e+02 -2.13453578289375e-01 1.38684361845383e+00 -4.59405772291525e-01 + 1.05000000000000e+02 -2.64427526911242e-01 1.34968589451878e+00 -4.57933058035756e-01 + 1.08000000000000e+02 -3.15401526057875e-01 1.31252774478765e+00 -4.56460500541016e-01 + 1.11000000000000e+02 -3.63702613318511e-01 1.26864261896506e+00 -4.53729817735206e-01 + 1.14000000000000e+02 -4.06657958215626e-01 1.21130374584807e+00 -4.48482124934980e-01 + 1.17000000000000e+02 -4.49613275538441e-01 1.15396443469656e+00 -4.43234672446104e-01 + 1.20000000000000e+02 -4.92568557072479e-01 1.09662487869506e+00 -4.37987618819821e-01 + 1.23000000000000e+02 -5.24273305652762e-01 1.02607897125153e+00 -4.30899900449802e-01 + 1.26000000000000e+02 -5.55977975337812e-01 9.55532794347773e-01 -4.23812474118514e-01 + 1.29000000000000e+02 -5.87682487226498e-01 8.84986078503406e-01 -4.16725057602321e-01 + 1.32000000000000e+02 -6.11743957269202e-01 8.11342840122296e-01 -4.10311145379585e-01 + 1.35000000000000e+02 -6.31983915443519e-01 7.36151344151820e-01 -4.04234114284225e-01 + 1.38000000000000e+02 -6.52223041697912e-01 6.60960643393727e-01 -3.98157422646348e-01 + 1.41000000000000e+02 -6.70277141430926e-01 5.87259503028655e-01 -3.94043626890889e-01 + 1.44000000000000e+02 -6.83961170390853e-01 5.16537495536617e-01 -3.93855328257089e-01 + 1.47000000000000e+02 -6.97644694809602e-01 4.45815984052867e-01 -3.93666633192198e-01 + 1.50000000000000e+02 -7.11327966966768e-01 3.75094720564406e-01 -3.93477629010198e-01 + 1.53000000000000e+02 -7.10555758661770e-01 3.21288604729336e-01 -4.09291401293984e-01 + 1.56000000000000e+02 -7.09783519622452e-01 2.67482711700951e-01 -4.25113789480059e-01 + 1.59000000000000e+02 -7.09747287572277e-01 2.13677185443974e-01 -4.40944959963481e-01 + 1.62000000000000e+02 -6.39242744263654e-01 1.76167844671200e-01 -4.56979587409322e-01 + 1.65000000000000e+02 -5.32702098344237e-01 1.46806734460832e-01 -4.73112741890976e-01 + 1.68000000000000e+02 -4.24165693368368e-01 1.17445360706964e-01 -4.89245046545928e-01 + 1.71000000000000e+02 -3.17540377497210e-01 8.80840526647858e-02 -4.50000513056908e-01 + 1.74000000000000e+02 -2.11693558985589e-01 5.87228760490535e-02 -2.99999717902353e-01 + 1.77000000000000e+02 -1.05275486594639e-01 4.83558379259246e-02 -1.49185828331614e-01 + 1.80000000000000e+02 0.00000000000000e+00 4.74971586892991e-02 0.00000000000000e+00 diff --git a/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_15.dat b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_15.dat new file mode 100644 index 00000000..8a6d71ed --- /dev/null +++ b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_15.dat @@ -0,0 +1,254 @@ +! ------------ AirfoilInfo v1.01.x Input File ---------------------------------- +! AeroElasticSE FAST driver +! line +! line +! ------------------------------------------------------------------------------ +DEFAULT InterpOrd ! Interpolation order to use for quasi-steady table lookup {1=linear; 3=cubic spline; "default"} [default=3] +1 NonDimArea ! The non-dimensional area of the airfoil (area/chord^2) (set to 1.0 if unsure or unneeded) +@"NREL-2p8-127_AF15_Coords.txt" NumCoords ! The number of coordinates in the airfoil shape file. Set to zero if coordinates not included. +AF15_BL.txt BL_file ! The file name including the boundary layer characteristics of the profile. Ignored if the aeroacoustic module is not called. +1 NumTabs ! Number of airfoil tables in this file. Each table must have lines for Re and Ctrl. +! ------------------------------------------------------------------------------ +! data for table 1 +! ------------------------------------------------------------------------------ +6.000000 Re ! Reynolds number in millions +0 Ctrl ! Control setting (must be 0 for current AirfoilInfo) +True InclUAdata ! Is unsteady aerodynamics data included in this table? If TRUE, then include 30 UA coefficients below this line +!........................................ +-2.208961 alpha0 ! 0-lift angle of attack, depends on airfoil. +11.877956 alpha1 ! Angle of attack at f=0.7, (approximately the stall angle) for AOA>alpha0. (deg) +-10.077196 alpha2 ! Angle of attack at f=0.7, (approximately the stall angle) for AOA1] +0.000000 S2 ! Constant in the f curve best-fit for AOA> alpha1; by definition it depends on the airfoil. [ignored if UAMod<>1] +0.000000 S3 ! Constant in the f curve best-fit for alpha2<=AOA< alpha0; by definition it depends on the airfoil. [ignored if UAMod<>1] +0.000000 S4 ! Constant in the f curve best-fit for AOA< alpha2; by definition it depends on the airfoil. [ignored if UAMod<>1] +1.523431 Cn1 ! Critical value of C0n at leading edge separation. It should be extracted from airfoil data at a given Mach and Reynolds number. It can be calculated from the static value of Cn at either the break in the pitching moment or the loss of chord force at the onset of stall. It is close to the condition of maximum lift of the airfoil at low Mach numbers. +-1.245136 Cn2 ! As Cn1 for negative AOAs. +Default St_sh ! Strouhal's shedding frequency constant. [default = 0.19] +0.010644 Cd0 ! 2D drag coefficient value at 0-lift. +-0.090826 Cm0 ! 2D pitching moment coefficient about 1/4-chord location, at 0-lift, positive if nose up. [If the aerodynamics coefficients table does not include a column for Cm, this needs to be set to 0.0] +0.000000 k0 ! Constant in the \hat(x)_cp curve best-fit; = (\hat(x)_AC-0.25). [ignored if UAMod<>1] +0.000000 k1 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k2 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k3 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k1_hat ! Constant in the expression of Cc due to leading edge vortex effects. [ignored if UAMod<>1] +Default x_cp_bar ! Constant in the expression of \hat(x)_cp^v. [ignored if UAMod<>1, default = 0.2] +Default UACutout ! Angle of attack above which unsteady aerodynamics are disabled (deg). [Specifying the string "Default" sets UACutout to 45 degrees] +Default filtCutOff ! Cut-off frequency (-3 dB corner frequency) for low-pass filtering the AoA input to UA, as well as the 1st and 2nd derivatives (Hz) [default = 20] +!........................................ +! Table of aerodynamics coefficients +200 NumAlf ! Number of data lines in the following table +! Alpha Cl Cd Cm +! (deg) (-) (-) (-) +-1.80000000000000e+02 0.00000000000000e+00 4.67684423893836e-02 0.00000000000000e+00 +-1.77000000000000e+02 1.09408903050313e-01 4.67684423893836e-02 1.19449340115019e-01 +-1.74000000000000e+02 2.19827919665962e-01 5.61220773758285e-02 2.39999774321882e-01 +-1.71000000000000e+02 3.29742593401240e-01 8.41832894069106e-02 3.60000410445527e-01 +-1.68000000000000e+02 4.39652946023446e-01 1.12247441543861e-01 3.17657026395814e-01 +-1.65000000000000e+02 5.49568920893405e-01 1.40313063699431e-01 1.94143527053385e-01 +-1.62000000000000e+02 6.59436266220261e-01 1.68379605308450e-01 7.06292113109056e-02 +-1.59000000000000e+02 7.30300487636504e-01 2.05487990755536e-01 -1.10385648721879e-02 +-1.56000000000000e+02 7.23544790871733e-01 2.60679757996445e-01 -8.60356910819995e-03 +-1.53000000000000e+02 7.16970142385750e-01 3.15871546871301e-01 -6.03641287104454e-03 +-1.50000000000000e+02 7.10395253192162e-01 3.71063383075396e-01 -3.53054989193793e-03 +-1.47000000000000e+02 6.96821464496714e-01 4.41924263677891e-01 1.15622643794935e-02 +-1.44000000000000e+02 6.83247423957872e-01 5.12785414225651e-01 2.66551539940038e-02 +-1.41000000000000e+02 6.69672879714259e-01 5.83647104683221e-01 4.17481792755350e-02 +-1.38000000000000e+02 6.51701749637977e-01 6.57509515264151e-01 5.71032192754300e-02 +-1.35000000000000e+02 6.31532335564314e-01 7.32872279819475e-01 7.25892986682547e-02 +-1.32000000000000e+02 6.11362090369567e-01 8.08235905809873e-01 8.80756349445296e-02 +-1.29000000000000e+02 5.87362687378832e-01 8.82060419340625e-01 1.03702753521495e-01 +-1.26000000000000e+02 5.55704950650637e-01 9.52806700636205e-01 1.19611333221862e-01 +-1.23000000000000e+02 5.24047055768739e-01 1.02355244146660e+00 1.35519828983413e-01 +-1.20000000000000e+02 4.92389081812946e-01 1.09429791207450e+00 1.51428303263083e-01 +-1.17000000000000e+02 4.49464448320822e-01 1.15185785100299e+00 1.66519076342545e-01 +-1.14000000000000e+02 4.06539757473919e-01 1.20941754428038e+00 1.81609537109452e-01 +-1.11000000000000e+02 3.63614995985125e-01 1.26697679783968e+00 1.96699434164473e-01 +-1.08000000000000e+02 3.15335797028190e-01 1.31109215764924e+00 2.10144017964703e-01 +-1.05000000000000e+02 2.64379338566390e-01 1.34848546821470e+00 2.22765790368656e-01 +-1.02000000000000e+02 2.13422866177849e-01 1.38587835028935e+00 2.35387244205176e-01 +-9.90000000000000e+01 1.61506739379516e-01 1.41503236786356e+00 2.46653165683191e-01 +-9.60000000000000e+01 1.07671262193915e-01 1.42770829956833e+00 2.55208020338782e-01 +-9.30000000000000e+01 5.38357962810632e-02 1.44038413443613e+00 2.63762460154027e-01 +-9.00000000000000e+01 3.36004484266645e-07 1.45305992088633e+00 2.72316549083834e-01 +-8.70000000000000e+01 -5.38357411804466e-02 1.44038414740981e+00 2.75975908689839e-01 +-8.40000000000000e+01 -1.07671412729903e-01 1.42770826412360e+00 2.79637509125723e-01 +-8.10000000000000e+01 -1.61506273010176e-01 1.41503247767341e+00 2.83303463358523e-01 +-7.80000000000000e+01 -2.13422619382625e-01 1.38587853139263e+00 2.83673895090911e-01 +-7.50000000000000e+01 -2.64379675691045e-01 1.34848522082535e+00 2.82397275634580e-01 +-7.20000000000000e+01 -3.15335550238364e-01 1.31109233875070e+00 2.81119990974020e-01 +-6.90000000000000e+01 -3.63614624127447e-01 1.26697729647612e+00 2.78579207220845e-01 +-6.60000000000000e+01 -4.06539877500383e-01 1.20941738333287e+00 2.73511947958626e-01 +-6.30000000000000e+01 -4.49464732308094e-01 1.15185747018962e+00 2.68443139589274e-01 +-6.00000000000000e+01 -4.92389291260444e-01 1.09429744402618e+00 2.63372775517188e-01 +-5.70000000000000e+01 -5.24047265216237e-01 1.02355197341827e+00 2.56458829905844e-01 +-5.40000000000000e+01 -5.55705160096565e-01 9.52806232582514e-01 2.49542806281396e-01 +-5.10000000000000e+01 -5.87362896824760e-01 8.82059951286934e-01 2.42624285718169e-01 +-4.80000000000000e+01 -6.13081518081798e-01 8.08245749651705e-01 2.35914730168143e-01 +-4.50000000000000e+01 -6.35830677053252e-01 7.32897637152475e-01 2.29306703335177e-01 +-4.20000000000000e+01 -6.53421163894653e-01 6.57519359024154e-01 2.24147571871917e-01 +-3.90000000000000e+01 -6.70067066454672e-01 5.82564691354695e-01 2.19583471937992e-01 +-3.60000000000000e+01 -6.84082341201795e-01 5.09304675599610e-01 2.17192480713428e-01 +-3.30000000000000e+01 -6.97048433260438e-01 4.38755128231645e-01 2.17746484897517e-01 +-3.00000000000000e+01 -7.10395349681667e-01 3.71062942477108e-01 2.21579781653519e-01 +-2.93939393939394e+01 -7.13452692480888e-01 3.58077533205854e-01 2.23238409263915e-01 +-2.87878787878788e+01 -7.16510035280109e-01 3.45092123934599e-01 2.24897036874312e-01 +-2.81818181818182e+01 -7.19567378079330e-01 3.32106714663345e-01 2.26555664484708e-01 +-2.75757575757576e+01 -7.23015176952550e-01 3.19538672861810e-01 2.28842891870977e-01 +-2.69696969696970e+01 -7.26630328498820e-01 3.07149518178065e-01 2.31399542272472e-01 +-2.63636363636364e+01 -7.30245480045089e-01 2.94760363494321e-01 2.33956192673967e-01 +-2.57575757575758e+01 -7.34209413289690e-01 2.82634381591017e-01 2.36982384547252e-01 +-2.51515151515151e+01 -7.38696437793794e-01 2.70903097522626e-01 2.40712779195633e-01 +-2.45454545454545e+01 -7.43183462297898e-01 2.59171813454235e-01 2.44443173844013e-01 +-2.39393939393939e+01 -7.47799807451049e-01 2.47511976474211e-01 2.48330404264612e-01 +-2.33333333333333e+01 -7.53580063482705e-01 2.36495177121992e-01 2.53629186999333e-01 +-2.27272727272727e+01 -7.59360319514362e-01 2.25478377769773e-01 2.59138821302601e-01 +-2.21212121212121e+01 -7.65140575546019e-01 2.14461578417554e-01 2.64477816678713e-01 +-2.15151515151515e+01 -8.03302749793657e-01 2.08548124886777e-01 2.49301560239203e-01 +-2.09090909090909e+01 -8.50824045909576e-01 2.03910836081233e-01 2.28513888557106e-01 +-2.03030303030303e+01 -8.97768386898726e-01 1.99273547275689e-01 2.07575119743590e-01 +-1.96969696969697e+01 -9.44678207213724e-01 1.94637489543005e-01 1.86538818608059e-01 +-1.90909090909091e+01 -9.91555050415259e-01 1.90002662813539e-01 1.65441760982968e-01 +-1.84848484848485e+01 -1.03842681336623e+00 1.85480504382984e-01 1.44332068966338e-01 +-1.78787878787879e+01 -1.08529649705215e+00 1.80950527403410e-01 1.23357644166816e-01 +-1.72727272727273e+01 -1.13216603243267e+00 1.76145971766597e-01 1.02450261417032e-01 +-1.66666666666667e+01 -1.17903468591979e+00 1.71473937535991e-01 8.15425477213738e-02 +-1.60606060606061e+01 -1.22590272554085e+00 1.66848907281323e-01 6.06345632546291e-02 +-1.54545454545455e+01 -1.24540579219954e+00 1.60147463320380e-01 4.44630991177370e-02 +-1.48484848484848e+01 -1.24781000746850e+00 1.52164045091083e-01 3.08929440011085e-02 +-1.42424242424242e+01 -1.20802738977228e+00 1.41026803742556e-01 2.37904766410137e-02 +-1.36363636363636e+01 -1.16175523534967e+00 1.29449635840845e-01 1.56762299252564e-02 +-1.30303030303030e+01 -1.11115112057063e+00 1.17578013100753e-01 6.58924652136504e-03 +-1.24242424242424e+01 -1.05692194409935e+00 1.06127950509725e-01 -3.71182830764803e-03 +-1.18181818181818e+01 -1.00272814309195e+00 9.53368098006124e-02 -1.33696206088078e-02 +-1.12121212121212e+01 -9.49076573968545e-01 8.60321040274192e-02 -2.13872923605838e-02 +-1.06060606060606e+01 -8.93581807311589e-01 7.76106753832643e-02 -2.80731947658556e-02 +-1.00000000000000e+01 -8.36985941927378e-01 6.96649134803325e-02 -3.40347701647619e-02 +-9.39393939393939e+00 -7.93166380537571e-01 5.77167470270437e-02 -4.15395521632745e-02 +-8.78787878787879e+00 -7.59169809540880e-01 4.45159809940110e-02 -4.84819804761218e-02 +-8.18181818181818e+00 -7.42105465881365e-01 2.91170572332394e-02 -5.43926186316557e-02 +-7.57575757575758e+00 -6.99614592258827e-01 2.14382481096017e-02 -5.74658684394408e-02 +-6.96969696969697e+00 -6.44608817122756e-01 1.72874428994890e-02 -5.94924254124929e-02 +-6.36363636363636e+00 -5.58802274186132e-01 1.57551020164310e-02 -6.43044689253696e-02 +-5.75757575757576e+00 -4.73764998472755e-01 1.43502448275924e-02 -6.89249208066366e-02 +-5.15151515151515e+00 -3.89894394333158e-01 1.31419672724884e-02 -7.32603190020164e-02 +-4.54545454545454e+00 -3.07166264437107e-01 1.22637086666309e-02 -7.73190401255010e-02 +-3.93939393939394e+00 -2.25054198114775e-01 1.15266148059250e-02 -8.12466599743608e-02 +-3.33333333333333e+00 -1.45172725478899e-01 1.11181586895799e-02 -8.48048561058059e-02 +-2.72727272727273e+00 -6.64481817059381e-02 1.08213328544847e-02 -8.81461929096935e-02 +-2.12121212121212e+00 1.12495325557481e-02 1.06139900247299e-02 -9.12799422030186e-02 +-1.51515151515152e+00 8.85670296087496e-02 1.04479884948180e-02 -9.42942439451978e-02 +-9.09090909090912e-01 1.66213270670549e-01 1.03347362369138e-02 -9.72595244702951e-02 +-3.03030303030302e-01 2.45681839335204e-01 1.04136053686051e-02 -1.00116736668253e-01 + 3.03030303030302e-01 3.24493811021227e-01 1.05051634149457e-02 -1.02832528533338e-01 + 9.09090909090912e-01 4.02689577361445e-01 1.06029024359060e-02 -1.05409582524880e-01 + 1.51515151515152e+00 4.80450558739067e-01 1.06086084327215e-02 -1.07756982884227e-01 + 2.12121212121212e+00 5.57655020416299e-01 1.06364076844461e-02 -1.10007533488911e-01 + 2.72727272727273e+00 6.32854110854688e-01 1.08222553063749e-02 -1.12010805967812e-01 + 3.33333333333333e+00 7.07829104208440e-01 1.09871939917408e-02 -1.13813398304224e-01 + 3.93939393939394e+00 7.82726097125106e-01 1.11313590740197e-02 -1.15433563257352e-01 + 4.54545454545455e+00 8.56725036367504e-01 1.13155452275198e-02 -1.16880352315399e-01 + 5.15151515151515e+00 9.30032793828029e-01 1.15208350124478e-02 -1.18219662619805e-01 + 5.75757575757576e+00 1.00154268140207e+00 1.17795522060827e-02 -1.19293155287934e-01 + 6.36363636363637e+00 1.07164671957996e+00 1.20808443869704e-02 -1.20114824732784e-01 + 6.96969696969697e+00 1.14081776942528e+00 1.24089124959070e-02 -1.20769509296104e-01 + 7.57575757575757e+00 1.20747309170393e+00 1.27841449542467e-02 -1.20984177116947e-01 + 8.18181818181818e+00 1.27293094202657e+00 1.31971119963991e-02 -1.21040387776290e-01 + 8.78787878787879e+00 1.33631723158136e+00 1.36879819805424e-02 -1.20797951715922e-01 + 9.39393939393939e+00 1.39580208572342e+00 1.43634591973061e-02 -1.19814227819290e-01 + 1.00000000000000e+01 1.45201036734241e+00 1.51114679774447e-02 -1.18417062091605e-01 + 1.06060606060606e+01 1.49636269861419e+00 1.62052841025846e-02 -1.15842476045504e-01 + 1.12121212121212e+01 1.53223105339179e+00 1.75945580457730e-02 -1.12669856479682e-01 + 1.18181818181818e+01 1.55233724587327e+00 1.95273589024484e-02 -1.08387441695462e-01 + 1.24242424242424e+01 1.40485306788269e+00 3.66837894727473e-02 -1.10705453199216e-01 + 1.30303030303030e+01 1.19641936134212e+00 5.96341107919704e-02 -1.15524471863464e-01 + 1.36363636363636e+01 1.13694346952033e+00 6.90810774839366e-02 -1.13792452322283e-01 + 1.42424242424242e+01 1.08854773748024e+00 7.81569854013355e-02 -1.12222962444976e-01 + 1.48484848484848e+01 1.05813142651997e+00 8.67025410668526e-02 -1.10869165205536e-01 + 1.54545454545455e+01 1.03762808162079e+00 9.51813233811173e-02 -1.10006355575461e-01 + 1.60606060606061e+01 1.02128710765488e+00 1.03672155520267e-01 -1.09349864817940e-01 + 1.66666666666667e+01 1.01267698438400e+00 1.12471820673251e-01 -1.09500151103095e-01 + 1.72727272727273e+01 1.00862750152695e+00 1.21612657749372e-01 -1.10196871074556e-01 + 1.78787878787879e+01 1.01015219256151e+00 1.31170487057709e-01 -1.11561461369328e-01 + 1.84848484848485e+01 1.02487270501671e+00 1.42717764493646e-01 -1.14728141059506e-01 + 1.90909090909091e+01 1.04251728636470e+00 1.54827944679204e-01 -1.18510461076852e-01 + 1.96969696969697e+01 1.05803974641611e+00 1.67310086078875e-01 -1.23229156855034e-01 + 2.03030303030303e+01 1.07018102313405e+00 1.79415876584770e-01 -1.28428162973701e-01 + 2.09090909090909e+01 1.07894092523283e+00 1.91145294905368e-01 -1.34145582008302e-01 + 2.15151515151515e+01 1.08770082733162e+00 2.02874713225965e-01 -1.39876119614393e-01 + 2.21212121212121e+01 1.09305671932835e+00 2.14461578417554e-01 -1.45612662747519e-01 + 2.27272727272727e+01 1.08480007339250e+00 2.25478377769773e-01 -1.51382551672362e-01 + 2.33333333333333e+01 1.07654342745665e+00 2.36495177121992e-01 -1.57161617206521e-01 + 2.39393939393939e+01 1.06828678152080e+00 2.47511976474211e-01 -1.62994019825784e-01 + 2.45454545454545e+01 1.06169131258261e+00 2.59171813454235e-01 -1.68042877714576e-01 + 2.51515151515151e+01 1.05528041489594e+00 2.70903097522626e-01 -1.73004676950534e-01 + 2.57575757575758e+01 1.04886951720927e+00 2.82634381591017e-01 -1.77966476186493e-01 + 2.63636363636364e+01 1.04320589180274e+00 2.94760363494321e-01 -1.82573390251451e-01 + 2.69696969696970e+01 1.03804052533334e+00 3.07149518178065e-01 -1.86943677436481e-01 + 2.75757575757576e+01 1.03287515886394e+00 3.19538672861810e-01 -1.91313964621511e-01 + 2.81818181818182e+01 1.02794990386129e+00 3.32106714663345e-01 -1.95560901544960e-01 + 2.87878787878788e+01 1.02358486088827e+00 3.45092123934599e-01 -1.99520045880541e-01 + 2.93939393939394e+01 1.01921981791524e+00 3.58077533205854e-01 -2.03479190216121e-01 + 3.00000000000000e+01 1.01485477494222e+00 3.71062942477108e-01 -2.07438334551702e-01 + 3.30000000000000e+01 9.95781979176941e-01 4.38755128231646e-01 -2.25248633303694e-01 + 3.60000000000000e+01 9.77261344047451e-01 5.09304675599610e-01 -2.41856194661193e-01 + 3.90000000000000e+01 9.57239163797111e-01 5.82564691354695e-01 -2.57340269463326e-01 + 4.20000000000000e+01 9.33459403203811e-01 6.57519359024154e-01 -2.72202941735538e-01 + 4.50000000000000e+01 9.08329968243298e-01 7.32897637152475e-01 -2.86898149313765e-01 + 4.80000000000000e+01 8.75830570639952e-01 8.08245749651705e-01 -3.01010122893952e-01 + 5.10000000000000e+01 8.39089169459949e-01 8.82059951286934e-01 -3.14864677792113e-01 + 5.40000000000000e+01 7.93863488417853e-01 9.52806232582514e-01 -3.28197186474091e-01 + 5.70000000000000e+01 7.48638152873260e-01 1.02355197341827e+00 -3.41532795817309e-01 + 6.00000000000000e+01 7.03412990076103e-01 1.09429744402618e+00 -3.54870873320022e-01 + 6.30000000000000e+01 6.42091935358749e-01 1.15185747018962e+00 -3.66903187497261e-01 + 6.60000000000000e+01 5.80770742674055e-01 1.20941738333287e+00 -3.78937520560764e-01 + 6.90000000000000e+01 5.19449549989362e-01 1.26697729647612e+00 -3.90973534083543e-01 + 7.20000000000000e+01 4.50479586567496e-01 1.31109233875070e+00 -4.01764478228043e-01 + 7.50000000000000e+01 3.77685394357568e-01 1.34848522082535e+00 -4.11933663285151e-01 + 7.80000000000000e+01 3.04889770136817e-01 1.38587853139263e+00 -4.22104253439653e-01 + 8.10000000000000e+01 2.30723589089482e-01 1.41503247767341e+00 -4.31419619766910e-01 + 8.40000000000000e+01 1.53816388998543e-01 1.42770826412360e+00 -4.39023497820268e-01 + 8.70000000000000e+01 7.69082013784813e-02 1.44038414740981e+00 -4.46628018116478e-01 + 9.00000000000000e+01 -3.36004484498046e-07 1.45305992088633e+00 -4.54233190688659e-01 + 9.30000000000000e+01 -5.38357962810632e-02 1.44038413443613e+00 -4.57885786719435e-01 + 9.60000000000000e+01 -1.07671262193915e-01 1.42770829956833e+00 -4.61538677552376e-01 + 9.90000000000000e+01 -1.61506739379516e-01 1.41503236786356e+00 -4.65191853174755e-01 + 1.02000000000000e+02 -2.13422866177849e-01 1.38587835028935e+00 -4.65561570743231e-01 + 1.05000000000000e+02 -2.64379338566390e-01 1.34848546821470e+00 -4.64289725865889e-01 + 1.08000000000000e+02 -3.15335797028190e-01 1.31109215764924e+00 -4.63017478275328e-01 + 1.11000000000000e+02 -3.63614995985125e-01 1.26697679783968e+00 -4.60482928481624e-01 + 1.14000000000000e+02 -4.06539757473920e-01 1.20941754428038e+00 -4.55423611669011e-01 + 1.17000000000000e+02 -4.49464448320822e-01 1.15185785100299e+00 -4.50364064972578e-01 + 1.20000000000000e+02 -4.92389081812947e-01 1.09429791207450e+00 -4.45304488017237e-01 + 1.23000000000000e+02 -5.24047055768740e-01 1.02355244146660e+00 -4.38404309098436e-01 + 1.26000000000000e+02 -5.55704950650637e-01 9.52806700636205e-01 -4.31504104372525e-01 + 1.29000000000000e+02 -5.87362687378832e-01 8.82060419340624e-01 -4.24603632838989e-01 + 1.32000000000000e+02 -6.11362090369567e-01 8.08235905809873e-01 -4.18403572366859e-01 + 1.35000000000000e+02 -6.31532335564314e-01 7.32872279819475e-01 -4.12553840848231e-01 + 1.38000000000000e+02 -6.51701749637977e-01 6.57509515264151e-01 -4.06704379408258e-01 + 1.41000000000000e+02 -6.69672879714259e-01 5.83647104683220e-01 -4.02869826230333e-01 + 1.44000000000000e+02 -6.83247423957872e-01 5.12785414225651e-01 -4.03065008320271e-01 + 1.47000000000000e+02 -6.96821464496714e-01 4.41924263677891e-01 -4.03260077987011e-01 + 1.50000000000000e+02 -7.10395253192162e-01 3.71063383075396e-01 -4.03455201443317e-01 + 1.53000000000000e+02 -7.06372114301663e-01 3.17621444101635e-01 -4.19162152168120e-01 + 1.56000000000000e+02 -7.02348949774489e-01 2.64179749134792e-01 -4.34871119537335e-01 + 1.59000000000000e+02 -6.98510217081455e-01 2.10738460990774e-01 -4.50581918807084e-01 + 1.62000000000000e+02 -6.27628255763012e-01 1.73632254525860e-01 -4.64655763669874e-01 + 1.65000000000000e+02 -5.23023338960169e-01 1.44693727049735e-01 -4.77910305590711e-01 + 1.68000000000000e+02 -4.18349440675210e-01 1.15754931187723e-01 -4.91164080985006e-01 + 1.71000000000000e+02 -3.13741957550692e-01 8.68162240683767e-02 -4.50000513056908e-01 + 1.74000000000000e+02 -2.09161222825938e-01 5.78776944385058e-02 -2.99999717902353e-01 + 1.77000000000000e+02 -1.04100854082611e-01 4.76423262875679e-02 -1.49311675143774e-01 + 1.80000000000000e+02 0.00000000000000e+00 4.67684423893836e-02 0.00000000000000e+00 diff --git a/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_16.dat b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_16.dat new file mode 100644 index 00000000..42e6caf1 --- /dev/null +++ b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_16.dat @@ -0,0 +1,254 @@ +! ------------ AirfoilInfo v1.01.x Input File ---------------------------------- +! AeroElasticSE FAST driver +! line +! line +! ------------------------------------------------------------------------------ +DEFAULT InterpOrd ! Interpolation order to use for quasi-steady table lookup {1=linear; 3=cubic spline; "default"} [default=3] +1 NonDimArea ! The non-dimensional area of the airfoil (area/chord^2) (set to 1.0 if unsure or unneeded) +@"NREL-2p8-127_AF16_Coords.txt" NumCoords ! The number of coordinates in the airfoil shape file. Set to zero if coordinates not included. +AF16_BL.txt BL_file ! The file name including the boundary layer characteristics of the profile. Ignored if the aeroacoustic module is not called. +1 NumTabs ! Number of airfoil tables in this file. Each table must have lines for Re and Ctrl. +! ------------------------------------------------------------------------------ +! data for table 1 +! ------------------------------------------------------------------------------ +6.000000 Re ! Reynolds number in millions +0 Ctrl ! Control setting (must be 0 for current AirfoilInfo) +True InclUAdata ! Is unsteady aerodynamics data included in this table? If TRUE, then include 30 UA coefficients below this line +!........................................ +-2.302844 alpha0 ! 0-lift angle of attack, depends on airfoil. +11.519512 alpha1 ! Angle of attack at f=0.7, (approximately the stall angle) for AOA>alpha0. (deg) +-10.603134 alpha2 ! Angle of attack at f=0.7, (approximately the stall angle) for AOA1] +0.000000 S2 ! Constant in the f curve best-fit for AOA> alpha1; by definition it depends on the airfoil. [ignored if UAMod<>1] +0.000000 S3 ! Constant in the f curve best-fit for alpha2<=AOA< alpha0; by definition it depends on the airfoil. [ignored if UAMod<>1] +0.000000 S4 ! Constant in the f curve best-fit for AOA< alpha2; by definition it depends on the airfoil. [ignored if UAMod<>1] +1.490978 Cn1 ! Critical value of C0n at leading edge separation. It should be extracted from airfoil data at a given Mach and Reynolds number. It can be calculated from the static value of Cn at either the break in the pitching moment or the loss of chord force at the onset of stall. It is close to the condition of maximum lift of the airfoil at low Mach numbers. +-1.228842 Cn2 ! As Cn1 for negative AOAs. +Default St_sh ! Strouhal's shedding frequency constant. [default = 0.19] +0.010387 Cd0 ! 2D drag coefficient value at 0-lift. +-0.097277 Cm0 ! 2D pitching moment coefficient about 1/4-chord location, at 0-lift, positive if nose up. [If the aerodynamics coefficients table does not include a column for Cm, this needs to be set to 0.0] +0.000000 k0 ! Constant in the \hat(x)_cp curve best-fit; = (\hat(x)_AC-0.25). [ignored if UAMod<>1] +0.000000 k1 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k2 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k3 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k1_hat ! Constant in the expression of Cc due to leading edge vortex effects. [ignored if UAMod<>1] +Default x_cp_bar ! Constant in the expression of \hat(x)_cp^v. [ignored if UAMod<>1, default = 0.2] +Default UACutout ! Angle of attack above which unsteady aerodynamics are disabled (deg). [Specifying the string "Default" sets UACutout to 45 degrees] +Default filtCutOff ! Cut-off frequency (-3 dB corner frequency) for low-pass filtering the AoA input to UA, as well as the 1st and 2nd derivatives (Hz) [default = 20] +!........................................ +! Table of aerodynamics coefficients +200 NumAlf ! Number of data lines in the following table +! Alpha Cl Cd Cm +! (deg) (-) (-) (-) +-1.80000000000000e+02 0.00000000000000e+00 4.74945271221455e-02 0.00000000000000e+00 +-1.77000000000000e+02 1.09026165719319e-01 4.74945271221455e-02 1.19452717008645e-01 +-1.74000000000000e+02 2.19050122417552e-01 5.69933789541972e-02 2.39999774321882e-01 +-1.71000000000000e+02 3.28575719604901e-01 8.54902462894429e-02 3.60000410445527e-01 +-1.68000000000000e+02 4.38106914174825e-01 1.13986527655115e-01 3.17778142294727e-01 +-1.65000000000000e+02 5.47644046044007e-01 1.42482516042840e-01 1.94446315387067e-01 +-1.62000000000000e+02 6.57185375418956e-01 1.70979335776501e-01 7.11135800063474e-02 +-1.59000000000000e+02 7.28986558567270e-01 2.08325862036029e-01 -1.07467958526159e-02 +-1.56000000000000e+02 7.23604309898402e-01 2.63371501965611e-01 -1.08174141591834e-02 +-1.53000000000000e+02 7.17767305056863e-01 3.18417162412815e-01 -1.14148679848354e-02 +-1.50000000000000e+02 7.12445310173410e-01 3.73462869777982e-01 -1.26457400718686e-02 +-1.47000000000000e+02 6.98630831673898e-01 4.44240664843570e-01 2.75536840347873e-03 +-1.44000000000000e+02 6.84816100411641e-01 5.15018714390009e-01 1.81567857412231e-02 +-1.41000000000000e+02 6.71000863605846e-01 5.85797272916321e-01 3.36066126261243e-02 +-1.38000000000000e+02 6.52847363996135e-01 6.59563695332857e-01 4.92127237288619e-02 +-1.35000000000000e+02 6.32524741785104e-01 7.34824043633297e-01 6.48870780422191e-02 +-1.32000000000000e+02 6.12201334294277e-01 8.10085206753381e-01 8.05597032537663e-02 +-1.29000000000000e+02 5.88065552379780e-01 8.83801868347751e-01 9.63550603105852e-02 +-1.26000000000000e+02 5.56305003551198e-01 9.54429519550126e-01 1.12398380329180e-01 +-1.23000000000000e+02 5.24544329085952e-01 1.02505663119359e+00 1.28440896746455e-01 +-1.20000000000000e+02 4.92783591804722e-01 1.09568347306768e+00 1.44482743848553e-01 +-1.17000000000000e+02 4.49791636415260e-01 1.15311205772626e+00 1.59698551465877e-01 +-1.14000000000000e+02 4.06799639145038e-01 1.21054039721062e+00 1.74914207352244e-01 +-1.11000000000000e+02 3.63807602041395e-01 1.26796829798034e+00 1.90129494093679e-01 +-1.08000000000000e+02 3.15480318387913e-01 1.31194660547628e+00 2.03701386725598e-01 +-1.05000000000000e+02 2.64485370834833e-01 1.34920001392269e+00 2.16452268723353e-01 +-1.02000000000000e+02 2.13490407640989e-01 1.38645299548144e+00 2.29203915346582e-01 +-9.90000000000000e+01 1.61544432084705e-01 1.41546560806078e+00 2.40600993496564e-01 +-9.60000000000000e+01 1.07696390610193e-01 1.42799712574756e+00 2.49288387037645e-01 +-9.30000000000000e+01 5.38483605044154e-02 1.44052854770060e+00 2.57977933040283e-01 +-9.00000000000000e+01 3.36082901150735e-07 1.45305992178765e+00 2.66670007912819e-01 +-8.70000000000000e+01 -5.38483053909395e-02 1.44052856052647e+00 2.70653828346413e-01 +-8.40000000000000e+01 -1.07696541181314e-01 1.42799709070664e+00 2.74632091077504e-01 +-8.10000000000000e+01 -1.61543965606523e-01 1.41546571661960e+00 2.78605161493305e-01 +-7.80000000000000e+01 -2.13490160659344e-01 1.38645317590716e+00 2.79287028552001e-01 +-7.50000000000000e+01 -2.64485708214139e-01 1.34919976745892e+00 2.78321604655193e-01 +-7.20000000000000e+01 -3.15480071411678e-01 1.31194678590016e+00 2.77352606273105e-01 +-6.90000000000000e+01 -3.63807229600907e-01 1.26796879547887e+00 2.75114638009095e-01 +-6.60000000000000e+01 -4.06799759359618e-01 1.21054023663040e+00 2.70342633491159e-01 +-6.30000000000000e+01 -4.49791920847929e-01 1.15311167778193e+00 2.65569198485011e-01 +-6.00000000000000e+01 -4.92783801932097e-01 1.09568300580419e+00 2.60795303619874e-01 +-5.70000000000000e+01 -5.24544539213326e-01 1.02505616393010e+00 2.54185204039382e-01 +-5.40000000000000e+01 -5.56305213677325e-01 9.54429052281285e-01 2.47577553322180e-01 +-5.10000000000000e+01 -5.88065762505907e-01 8.83801401078910e-01 2.40973778659848e-01 +-4.80000000000000e+01 -6.13910354720703e-01 8.10097993520892e-01 2.34611596779972e-01 +-4.50000000000000e+01 -6.36797063706404e-01 7.34856757216810e-01 2.28377676012707e-01 +-4.20000000000000e+01 -6.54556371048421e-01 6.59576481995557e-01 2.23680283338938e-01 +-3.90000000000000e+01 -6.71380181626923e-01 5.84717599999870e-01 2.19536883348591e-01 +-3.60000000000000e+01 -6.85604200137604e-01 5.11546160178582e-01 2.17305088035508e-01 +-3.30000000000000e+01 -6.98815713908257e-01 4.41078428348352e-01 2.18054288333084e-01 +-3.00000000000000e+01 -7.12445408634725e-01 3.73462429674547e-01 2.22124678427173e-01 +-2.93939393939394e+01 -7.15569260532856e-01 3.60491220538288e-01 2.23842948054128e-01 +-2.87878787878788e+01 -7.18693112430987e-01 3.47520011402029e-01 2.25561217681083e-01 +-2.81818181818182e+01 -7.21816964329118e-01 3.34548802265771e-01 2.27279487308038e-01 +-2.75757575757576e+01 -7.25337539045798e-01 3.21994339673895e-01 2.29635020906344e-01 +-2.69696969696970e+01 -7.29028152413596e-01 3.09618498066121e-01 2.32263691065060e-01 +-2.63636363636364e+01 -7.32718765781393e-01 2.97242656458348e-01 2.34892361223777e-01 +-2.57575757575758e+01 -7.36762602567382e-01 2.85129614107284e-01 2.37997233303781e-01 +-2.51515151515151e+01 -7.41336192157463e-01 2.73410709392586e-01 2.41816297280826e-01 +-2.45454545454545e+01 -7.45909781747544e-01 2.61691804677889e-01 2.45635361257870e-01 +-2.39393939393939e+01 -7.50627141320397e-01 2.50043674398799e-01 2.49515043488697e-01 +-2.33333333333333e+01 -7.56638458572749e-01 2.39032527742441e-01 2.53940301739542e-01 +-2.27272727272727e+01 -7.62649775825102e-01 2.28021381086083e-01 2.57853785491344e-01 +-2.21212121212121e+01 -7.68661093077454e-01 2.17010234429726e-01 2.62068606039781e-01 +-2.15151515151515e+01 -8.07233018911813e-01 2.10719432824284e-01 2.44666939257051e-01 +-2.09090909090909e+01 -8.50063944721421e-01 2.05609021115132e-01 2.23825168737330e-01 +-2.03030303030303e+01 -8.94818933511164e-01 2.00498609405980e-01 2.03531509688972e-01 +-1.96969696969697e+01 -9.39301590592824e-01 1.95388221736857e-01 1.83458906167973e-01 +-1.90909090909091e+01 -9.83659564135496e-01 1.90277858106401e-01 1.63473959738679e-01 +-1.84848484848485e+01 -1.02835646060585e+00 1.84862741269290e-01 1.43541881926139e-01 +-1.78787878787879e+01 -1.07312022949524e+00 1.79623630734647e-01 1.23006204069627e-01 +-1.72727272727273e+01 -1.11789561032257e+00 1.75305320947758e-01 1.02174031312229e-01 +-1.66666666666667e+01 -1.16291637243167e+00 1.70479646552578e-01 8.13469192385163e-02 +-1.60606060606061e+01 -1.20810673312181e+00 1.65435507128552e-01 6.05261011893848e-02 +-1.54545454545455e+01 -1.22780192188674e+00 1.58414016648205e-01 4.42999154215266e-02 +-1.48484848484848e+01 -1.23148075482471e+00 1.50176007301149e-01 3.06001307793610e-02 +-1.42424242424242e+01 -1.19557688058349e+00 1.38991906593942e-01 2.19117759370747e-02 +-1.36363636363636e+01 -1.15320275631460e+00 1.27391804267069e-01 1.07082871223446e-02 +-1.30303030303030e+01 -1.10624218648539e+00 1.15510306693132e-01 -8.83566244868970e-04 +-1.24242424242424e+01 -1.05404262149901e+00 1.03763709632377e-01 -1.08587103233837e-02 +-1.18181818181818e+01 -1.00136072816888e+00 9.26167355272088e-02 -1.96543223095588e-02 +-1.12121212121212e+01 -9.48585842590762e-01 8.31140514128371e-02 -2.58402153588698e-02 +-1.06060606060606e+01 -8.93667893889375e-01 7.46227143327008e-02 -3.16390840974881e-02 +-1.00000000000000e+01 -8.38065195025141e-01 6.66511845807474e-02 -3.72575661487416e-02 +-9.39393939393939e+00 -7.95410787978230e-01 5.51236226526759e-02 -4.38865668044484e-02 +-8.78787878787879e+00 -7.59114580119346e-01 4.22612717076337e-02 -5.05975414003474e-02 +-8.18181818181818e+00 -7.39908303358907e-01 2.65347518460736e-02 -5.75870121728342e-02 +-7.57575757575758e+00 -6.95515216031812e-01 1.93744036977655e-02 -6.18696615221871e-02 +-6.96969696969697e+00 -6.38970352980065e-01 1.56903682577269e-02 -6.50444957534814e-02 +-6.36363636363636e+00 -5.53050978116223e-01 1.44330515252630e-02 -7.04916309908320e-02 +-5.75757575757576e+00 -4.67855482297821e-01 1.32728500481496e-02 -7.56445389562658e-02 +-5.15151515151515e+00 -3.83761883334006e-01 1.22747621729221e-02 -8.03433974705679e-02 +-4.54545454545454e+00 -3.00853428667449e-01 1.15921315939537e-02 -8.44964464276008e-02 +-3.93939393939394e+00 -2.18316833870855e-01 1.10444241869388e-02 -8.84303296892449e-02 +-3.33333333333333e+00 -1.35802226396340e-01 1.06756393000342e-02 -9.19189227982073e-02 +-2.72727272727273e+00 -5.52401875853970e-02 1.04478510242675e-02 -9.51462086023917e-02 +-2.12121212121212e+00 2.36396912458736e-02 1.03604338233977e-02 -9.81888615779641e-02 +-1.51515151515152e+00 1.01484614889655e-01 1.02452048792184e-02 -1.01004246307992e-01 +-9.09090909090912e-01 1.79466580667274e-01 1.01619214134529e-02 -1.03750330378995e-01 +-3.03030303030302e-01 2.59087622411868e-01 1.02426571705537e-02 -1.06360316407136e-01 + 3.03030303030302e-01 3.37837592391149e-01 1.03303065575862e-02 -1.08843506321385e-01 + 9.09090909090912e-01 4.15789971549744e-01 1.04212147734708e-02 -1.11177829034995e-01 + 1.51515151515152e+00 4.93147895935465e-01 1.04236090925569e-02 -1.13298457665409e-01 + 2.12121212121212e+00 5.69859535842775e-01 1.04645134860512e-02 -1.15323446159398e-01 + 2.72727272727273e+00 6.44307642449725e-01 1.06495299479427e-02 -1.17170718042645e-01 + 3.33333333333333e+00 7.18600940028201e-01 1.08126791422125e-02 -1.18836030380812e-01 + 3.93939393939394e+00 7.92950170251859e-01 1.09043051654465e-02 -1.20329319459463e-01 + 4.54545454545455e+00 8.66750625755535e-01 1.10287283292864e-02 -1.21622097750385e-01 + 5.15151515151515e+00 9.39936884951220e-01 1.11859719302871e-02 -1.22800063053947e-01 + 5.75757575757576e+00 1.01143404956829e+00 1.14111475039848e-02 -1.23696733437718e-01 + 6.36363636363637e+00 1.08182810267221e+00 1.16720384522875e-02 -1.24300128967657e-01 + 6.96969696969697e+00 1.15154797840494e+00 1.19507072068761e-02 -1.24706383395138e-01 + 7.57575757575757e+00 1.21829984832910e+00 1.23111001660822e-02 -1.24318393141766e-01 + 8.18181818181818e+00 1.28284334003200e+00 1.28453551133823e-02 -1.23573477309161e-01 + 8.78787878787879e+00 1.34152950781049e+00 1.37024581751005e-02 -1.22008658301098e-01 + 9.39393939393939e+00 1.39175204718020e+00 1.50501911010927e-02 -1.20764566885121e-01 + 1.00000000000000e+01 1.44072055032551e+00 1.67619493434159e-02 -1.19700808310407e-01 + 1.06060606060606e+01 1.47445006881312e+00 1.86588668153617e-02 -1.17383563054315e-01 + 1.12121212121212e+01 1.50211111367966e+00 2.06442638039865e-02 -1.13986779446044e-01 + 1.18181818181818e+01 1.51849743382808e+00 2.27949008726186e-02 -1.08801154929910e-01 + 1.24242424242424e+01 1.38110104869832e+00 3.91932789258445e-02 -1.10609411291075e-01 + 1.30303030303030e+01 1.17394609485373e+00 6.11116586730917e-02 -1.14753045755195e-01 + 1.36363636363636e+01 1.12719502884985e+00 7.05126133472740e-02 -1.13285854419029e-01 + 1.42424242424242e+01 1.08888194901864e+00 7.96731387425781e-02 -1.11992721439345e-01 + 1.48484848484848e+01 1.06009153338648e+00 8.83736363016277e-02 -1.11029145646405e-01 + 1.54545454545455e+01 1.04088100180195e+00 9.68845274277538e-02 -1.10082901069663e-01 + 1.60606060606061e+01 1.02566184269085e+00 1.05353288508621e-01 -1.09447986832365e-01 + 1.66666666666667e+01 1.01747136523085e+00 1.14011650931451e-01 -1.09533721766659e-01 + 1.72727272727273e+01 1.01393796533581e+00 1.23111695493764e-01 -1.10194974676891e-01 + 1.78787878787879e+01 1.01620977550644e+00 1.32751579382771e-01 -1.11556728709361e-01 + 1.84848484848485e+01 1.03062727147662e+00 1.44357732350225e-01 -1.14737403733058e-01 + 1.90909090909091e+01 1.04771493788588e+00 1.56504624193137e-01 -1.18523866085458e-01 + 1.96969696969697e+01 1.06291878178938e+00 1.68930683382824e-01 -1.23167550096525e-01 + 2.03030303030303e+01 1.07502785257006e+00 1.81134979640342e-01 -1.28324656352032e-01 + 2.09090909090909e+01 1.08382115536938e+00 1.93117500419765e-01 -1.33815690623442e-01 + 2.15151515151515e+01 1.09214908926105e+00 2.05100021199187e-01 -1.39246581437727e-01 + 2.21212121212121e+01 1.09715356486127e+00 2.16895622980487e-01 -1.44828119061210e-01 + 2.27272727272727e+01 1.08886762688942e+00 2.27943741095172e-01 -1.50978244430421e-01 + 2.33333333333333e+01 1.08058168891757e+00 2.38991859209858e-01 -1.57084368281988e-01 + 2.39393939393939e+01 1.07229575094571e+00 2.50039977324543e-01 -1.62956004038701e-01 + 2.45454545454545e+01 1.06558611366856e+00 2.61691804677889e-01 -1.68040941931674e-01 + 2.51515151515151e+01 1.05905161714547e+00 2.73410709392586e-01 -1.73040662366437e-01 + 2.57575757575758e+01 1.05251712062237e+00 2.85129614107284e-01 -1.78042939631076e-01 + 2.63636363636364e+01 1.04673941380572e+00 2.97242656458348e-01 -1.82687214968074e-01 + 2.69696969696970e+01 1.04146631186305e+00 3.09618498066121e-01 -1.87092862759889e-01 + 2.75757575757576e+01 1.03619320992039e+00 3.21994339673895e-01 -1.91500121873642e-01 + 2.81818181818182e+01 1.03116398723408e+00 3.34548802265770e-01 -1.95783309953570e-01 + 2.87878787878788e+01 1.02670376733233e+00 3.47520011402030e-01 -1.99774488550039e-01 + 2.93939393939394e+01 1.02224354743058e+00 3.60491220538288e-01 -2.03766728259228e-01 + 3.00000000000000e+01 1.01778332752883e+00 3.73462429674547e-01 -2.07760038049125e-01 + 3.30000000000000e+01 9.98306668405358e-01 4.41078428348352e-01 -2.25710390737701e-01 + 3.60000000000000e+01 9.79435247436346e-01 5.11546160178582e-01 -2.42439672107783e-01 + 3.90000000000000e+01 9.59115016848787e-01 5.84717599999870e-01 -2.58725778460445e-01 + 4.20000000000000e+01 9.35081102871063e-01 6.59576481995558e-01 -2.74139975914325e-01 + 4.50000000000000e+01 9.09710553576705e-01 7.34856757216810e-01 -2.89288459990168e-01 + 4.80000000000000e+01 8.77014675428035e-01 8.10097993520892e-01 -3.03752712432158e-01 + 5.10000000000000e+01 8.40093342319397e-01 8.83801401078911e-01 -3.17922061767336e-01 + 5.40000000000000e+01 7.94720827645917e-01 9.54429052281285e-01 -3.31525536369943e-01 + 5.70000000000000e+01 7.49348627860369e-01 1.02505616393010e+00 -3.45117992160713e-01 + 6.00000000000000e+01 7.03976585517588e-01 1.09568300580419e+00 -3.58702045370939e-01 + 6.30000000000000e+01 6.42559375800653e-01 1.15311167778193e+00 -3.70952105943644e-01 + 6.60000000000000e+01 5.81142028551168e-01 1.21054023663040e+00 -3.83194946194241e-01 + 6.90000000000000e+01 5.19724681301684e-01 1.26796879547887e+00 -3.95431861953200e-01 + 7.20000000000000e+01 4.50686006342368e-01 1.31194678590016e+00 -4.06412636751425e-01 + 7.50000000000000e+01 3.77836823546866e-01 1.34919976745892e+00 -4.16762432040660e-01 + 7.80000000000000e+01 3.04986205955287e-01 1.38645317590716e+00 -4.27107489371432e-01 + 8.10000000000000e+01 2.30777377649507e-01 1.41546571661960e+00 -4.36589691718973e-01 + 8.40000000000000e+01 1.53852221672675e-01 1.42799709070664e+00 -4.44350170094074e-01 + 8.70000000000000e+01 7.69261097609987e-02 1.44052856052647e+00 -4.52106372914785e-01 + 9.00000000000000e+01 -3.36082901382020e-07 1.45305992178765e+00 -4.59858962710058e-01 + 9.30000000000000e+01 -5.38483605044154e-02 1.44052854770060e+00 -4.63848553313885e-01 + 9.60000000000000e+01 -1.07696390610194e-01 1.42799712574756e+00 -4.67844287195712e-01 + 9.90000000000000e+01 -1.61544432084705e-01 1.41546560806078e+00 -4.71846453257926e-01 + 1.02000000000000e+02 -2.13490407640989e-01 1.38645299548144e+00 -4.72567917825502e-01 + 1.05000000000000e+02 -2.64485370834833e-01 1.34920001392269e+00 -4.71652413145928e-01 + 1.08000000000000e+02 -3.15480318387913e-01 1.31194660547628e+00 -4.70694898637910e-01 + 1.11000000000000e+02 -3.63807602041395e-01 1.26796829798034e+00 -4.68443341138964e-01 + 1.14000000000000e+02 -4.06799639145038e-01 1.21054039721062e+00 -4.63658575489138e-01 + 1.17000000000000e+02 -4.49791636415260e-01 1.15311205772626e+00 -4.58872593540100e-01 + 1.20000000000000e+02 -4.92783591804723e-01 1.09568347306768e+00 -4.54085669273530e-01 + 1.23000000000000e+02 -5.24544329085952e-01 1.02505663119359e+00 -4.47459524176604e-01 + 1.26000000000000e+02 -5.56305003551198e-01 9.54429519550126e-01 -4.40832384971193e-01 + 1.29000000000000e+02 -5.88065552379780e-01 8.83801868347751e-01 -4.34204079889270e-01 + 1.32000000000000e+02 -6.12201334294277e-01 8.10085206753381e-01 -4.28311374168508e-01 + 1.35000000000000e+02 -6.32524741785104e-01 7.34824043633297e-01 -4.22785962751293e-01 + 1.38000000000000e+02 -6.52847363996135e-01 6.59563695332856e-01 -4.17259798695567e-01 + 1.41000000000000e+02 -6.71000863605846e-01 5.85797272916321e-01 -4.13816791549941e-01 + 1.44000000000000e+02 -6.84816100411641e-01 5.15018714390009e-01 -4.14540480801535e-01 + 1.47000000000000e+02 -6.98630831673898e-01 4.44240664843570e-01 -4.15262578060876e-01 + 1.50000000000000e+02 -7.12445310173410e-01 3.73462869777981e-01 -4.15983399559589e-01 + 1.53000000000000e+02 -7.07009533624438e-01 3.20145904015172e-01 -4.31332989170919e-01 + 1.56000000000000e+02 -7.02319196022267e-01 2.66829166731978e-01 -4.46674211305675e-01 + 1.59000000000000e+02 -6.97067607564390e-01 2.13512805022704e-01 -4.61700248148900e-01 + 1.62000000000000e+02 -6.25252484559990e-01 1.76166650176245e-01 -4.73355693794957e-01 + 1.65000000000000e+02 -5.21043473383171e-01 1.46805733824602e-01 -4.83347659534527e-01 + 1.68000000000000e+02 -4.16835056347187e-01 1.17444553927237e-01 -4.93339032716489e-01 + 1.71000000000000e+02 -3.12626441266809e-01 8.80834460119835e-02 -4.50000513056908e-01 + 1.74000000000000e+02 -2.08417430088600e-01 5.87224820643139e-02 -2.99999717902353e-01 + 1.77000000000000e+02 -1.03734285731640e-01 4.83552281802738e-02 -1.49315896260807e-01 + 1.80000000000000e+02 0.00000000000000e+00 4.74945271221455e-02 0.00000000000000e+00 diff --git a/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_17.dat b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_17.dat new file mode 100644 index 00000000..217af07d --- /dev/null +++ b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_17.dat @@ -0,0 +1,254 @@ +! ------------ AirfoilInfo v1.01.x Input File ---------------------------------- +! AeroElasticSE FAST driver +! line +! line +! ------------------------------------------------------------------------------ +DEFAULT InterpOrd ! Interpolation order to use for quasi-steady table lookup {1=linear; 3=cubic spline; "default"} [default=3] +1 NonDimArea ! The non-dimensional area of the airfoil (area/chord^2) (set to 1.0 if unsure or unneeded) +@"NREL-2p8-127_AF17_Coords.txt" NumCoords ! The number of coordinates in the airfoil shape file. Set to zero if coordinates not included. +AF17_BL.txt BL_file ! The file name including the boundary layer characteristics of the profile. Ignored if the aeroacoustic module is not called. +1 NumTabs ! Number of airfoil tables in this file. Each table must have lines for Re and Ctrl. +! ------------------------------------------------------------------------------ +! data for table 1 +! ------------------------------------------------------------------------------ +6.000000 Re ! Reynolds number in millions +0 Ctrl ! Control setting (must be 0 for current AirfoilInfo) +True InclUAdata ! Is unsteady aerodynamics data included in this table? If TRUE, then include 30 UA coefficients below this line +!........................................ +-2.516492 alpha0 ! 0-lift angle of attack, depends on airfoil. +10.239483 alpha1 ! Angle of attack at f=0.7, (approximately the stall angle) for AOA>alpha0. (deg) +-11.166956 alpha2 ! Angle of attack at f=0.7, (approximately the stall angle) for AOA1] +0.000000 S2 ! Constant in the f curve best-fit for AOA> alpha1; by definition it depends on the airfoil. [ignored if UAMod<>1] +0.000000 S3 ! Constant in the f curve best-fit for alpha2<=AOA< alpha0; by definition it depends on the airfoil. [ignored if UAMod<>1] +0.000000 S4 ! Constant in the f curve best-fit for AOA< alpha2; by definition it depends on the airfoil. [ignored if UAMod<>1] +1.381088 Cn1 ! Critical value of C0n at leading edge separation. It should be extracted from airfoil data at a given Mach and Reynolds number. It can be calculated from the static value of Cn at either the break in the pitching moment or the loss of chord force at the onset of stall. It is close to the condition of maximum lift of the airfoil at low Mach numbers. +-1.159496 Cn2 ! As Cn1 for negative AOAs. +Default St_sh ! Strouhal's shedding frequency constant. [default = 0.19] +0.009688 Cd0 ! 2D drag coefficient value at 0-lift. +-0.104313 Cm0 ! 2D pitching moment coefficient about 1/4-chord location, at 0-lift, positive if nose up. [If the aerodynamics coefficients table does not include a column for Cm, this needs to be set to 0.0] +0.000000 k0 ! Constant in the \hat(x)_cp curve best-fit; = (\hat(x)_AC-0.25). [ignored if UAMod<>1] +0.000000 k1 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k2 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k3 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k1_hat ! Constant in the expression of Cc due to leading edge vortex effects. [ignored if UAMod<>1] +Default x_cp_bar ! Constant in the expression of \hat(x)_cp^v. [ignored if UAMod<>1, default = 0.2] +Default UACutout ! Angle of attack above which unsteady aerodynamics are disabled (deg). [Specifying the string "Default" sets UACutout to 45 degrees] +Default filtCutOff ! Cut-off frequency (-3 dB corner frequency) for low-pass filtering the AoA input to UA, as well as the 1st and 2nd derivatives (Hz) [default = 20] +!........................................ +! Table of aerodynamics coefficients +200 NumAlf ! Number of data lines in the following table +! Alpha Cl Cd Cm +! (deg) (-) (-) (-) +-1.80000000000000e+02 0.00000000000000e+00 5.02376982549728e-02 0.00000000000000e+00 +-1.77000000000000e+02 1.08718036745927e-01 5.02376982549728e-02 1.19452717008645e-01 +-1.74000000000000e+02 2.18430776525163e-01 6.02851812182215e-02 2.39999774321882e-01 +-1.71000000000000e+02 3.27646531789012e-01 9.04279599581437e-02 3.60000410445527e-01 +-1.68000000000000e+02 4.36869311875493e-01 1.20570256132886e-01 3.18260147906390e-01 +-1.65000000000000e+02 5.46099384730567e-01 1.50712311030671e-01 1.95651323790509e-01 +-1.62000000000000e+02 6.55334540103918e-01 1.80854868202663e-01 7.30412515523047e-02 +-1.59000000000000e+02 7.28010405538067e-01 2.19127710006320e-01 -9.45584975904147e-03 +-1.56000000000000e+02 7.24644310916020e-01 2.73660846032009e-01 -1.21837323981812e-02 +-1.53000000000000e+02 7.21308604937496e-01 3.28193998660095e-01 -1.57136492042310e-02 +-1.50000000000000e+02 7.20052599183224e-01 3.82727196695211e-01 -2.24733180893469e-02 +-1.47000000000000e+02 7.05344979121394e-01 4.53184198414303e-01 -6.72063266750436e-03 +-1.44000000000000e+02 6.90637102885333e-01 5.23641395400969e-01 9.03246882847654e-03 +-1.41000000000000e+02 6.75928714282518e-01 5.94098982936728e-01 2.49798597818277e-02 +-1.38000000000000e+02 6.57098483724279e-01 6.67494798442362e-01 4.09475868870872e-02 +-1.35000000000000e+02 6.36207340549935e-01 7.42359721972419e-01 5.68857580517079e-02 +-1.32000000000000e+02 6.15315579547438e-01 8.17225281824516e-01 7.28165592297191e-02 +-1.29000000000000e+02 5.90673724574305e-01 8.90525522009492e-01 8.88369855206700e-02 +-1.26000000000000e+02 5.58531663885406e-01 9.60695115424263e-01 1.05046529374471e-01 +-1.23000000000000e+02 5.26389596453192e-01 1.03086417277945e+00 1.21252954182462e-01 +-1.20000000000000e+02 4.94247525649446e-01 1.10103296211486e+00 1.37456542318889e-01 +-1.17000000000000e+02 4.51005751931015e-01 1.15795443010112e+00 1.52804706847535e-01 +-1.14000000000000e+02 4.07763995533133e-01 1.21487565475428e+00 1.68151691714967e-01 +-1.11000000000000e+02 3.64522317186419e-01 1.27179644456681e+00 1.83497290780899e-01 +-1.08000000000000e+02 3.16016600929376e-01 1.31524560139462e+00 1.97190287375102e-01 +-1.05000000000000e+02 2.64878825634709e-01 1.35195883914965e+00 2.10057619315569e-01 +-1.02000000000000e+02 2.13741036335945e-01 1.38867165620685e+00 2.22925091726200e-01 +-9.90000000000000e+01 1.61684301770569e-01 1.41713830337121e+00 2.34432883783133e-01 +-9.60000000000000e+01 1.07789636867620e-01 1.42911225356491e+00 2.43221503139034e-01 +-9.30000000000000e+01 5.38949836895802e-02 1.44108611228438e+00 2.52012246779875e-01 +-9.00000000000000e+01 3.36373889682523e-07 1.45305992526757e+00 2.60805612076082e-01 +-8.70000000000000e+01 -5.38949285283857e-02 1.44108612453959e+00 2.65268702964392e-01 +-8.40000000000000e+01 -1.07789787569110e-01 1.42911222008308e+00 2.69705899355330e-01 +-8.10000000000000e+01 -1.61683834888495e-01 1.41713840709990e+00 2.74118148425682e-01 +-7.80000000000000e+01 -2.13740788662556e-01 1.38867183401641e+00 2.75218906403952e-01 +-7.50000000000000e+01 -2.64879163958945e-01 1.35195859625958e+00 2.74653513726577e-01 +-7.20000000000000e+01 -3.16016353261405e-01 1.31524577920238e+00 2.74066661635360e-01 +-6.90000000000000e+01 -3.64521942583287e-01 1.27179693767224e+00 2.72190520318518e-01 +-6.60000000000000e+01 -4.07764116445761e-01 1.21487549559204e+00 2.67758304954097e-01 +-6.30000000000000e+01 -4.51006038016469e-01 1.15795405351184e+00 2.63309723707785e-01 +-6.00000000000000e+01 -4.94247738299703e-01 1.10103249788183e+00 2.58846174876524e-01 +-5.70000000000000e+01 -5.26389809103449e-01 1.03086370854641e+00 2.52537766967854e-01 +-5.40000000000000e+01 -5.58531876535596e-01 9.60694651185909e-01 2.46218241369695e-01 +-5.10000000000000e+01 -5.90673937224495e-01 8.90525057771137e-01 2.39889401901766e-01 +-4.80000000000000e+01 -6.16985978521229e-01 8.17249434089066e-01 2.33807907536728e-01 +-4.50000000000000e+01 -6.40383103818546e-01 7.42420845191650e-01 2.27849917319468e-01 +-4.20000000000000e+01 -6.58768869626067e-01 6.67518950513351e-01 2.23456296897971e-01 +-3.90000000000000e+01 -6.76252856241839e-01 5.93029893358622e-01 2.19662575489263e-01 +-3.60000000000000e+01 -6.91251469843313e-01 5.20200446113040e-01 2.17992553881491e-01 +-3.30000000000000e+01 -7.05373690625492e-01 4.50048605759265e-01 2.19429640986969e-01 +-3.00000000000000e+01 -7.20052704961507e-01 3.82726758502379e-01 2.24334644865001e-01 +-2.93939393939394e+01 -7.23423358758069e-01 3.69810374707743e-01 2.26262638995891e-01 +-2.87878787878788e+01 -7.26794012554631e-01 3.56893990913108e-01 2.28190633126782e-01 +-2.81818181818182e+01 -7.30164666351193e-01 3.43977607118473e-01 2.30118627257672e-01 +-2.75757575757576e+01 -7.33955296036718e-01 3.31475572351972e-01 2.32714210527911e-01 +-2.69696969696970e+01 -7.37925930829896e-01 3.19151130974461e-01 2.35595927974075e-01 +-2.63636363636364e+01 -7.41896565623074e-01 3.06826689596951e-01 2.38477645420239e-01 +-2.57575757575758e+01 -7.46236904909058e-01 2.94763605830315e-01 2.41858864830355e-01 +-2.51515151515151e+01 -7.51131714769935e-01 2.83092497567289e-01 2.45989220771138e-01 +-2.45454545454545e+01 -7.56026524630811e-01 2.71421389304264e-01 2.50119576711921e-01 +-2.39393939393939e+01 -7.61117995847343e-01 2.59818577841106e-01 2.53958515768821e-01 +-2.33333333333333e+01 -7.67979457339360e-01 2.48830450799340e-01 2.55174646451070e-01 +-2.27272727272727e+01 -7.74840918831377e-01 2.37842323757575e-01 2.56491201944605e-01 +-2.21212121212121e+01 -7.81702380323394e-01 2.26854196715809e-01 2.57271002838526e-01 +-2.15151515151515e+01 -8.12448284285856e-01 2.19127250982838e-01 2.39096729103820e-01 +-2.09090909090909e+01 -8.46418529847557e-01 2.12215810350734e-01 2.19171773544913e-01 +-2.03030303030303e+01 -8.82410390516615e-01 2.05304369718630e-01 1.99907002060488e-01 +-1.96969696969697e+01 -9.17302460891263e-01 1.98393040992681e-01 1.80908557885250e-01 +-1.90909090909091e+01 -9.51690757109299e-01 1.91481824166556e-01 1.62015766540326e-01 +-1.84848484848485e+01 -9.87451060932182e-01 1.84488095751064e-01 1.43186155335470e-01 +-1.78787878787879e+01 -1.02348107734750e+00 1.78125103821018e-01 1.23309320342863e-01 +-1.72727272727273e+01 -1.05955430524795e+00 1.72667345635547e-01 1.02937199694708e-01 +-1.66666666666667e+01 -1.09661808800758e+00 1.66429075696717e-01 8.25865362857696e-02 +-1.60606060606061e+01 -1.13436650818888e+00 1.59785188254103e-01 6.22621217533182e-02 +-1.54545454545455e+01 -1.15393444133063e+00 1.51574659183086e-01 4.58165236508863e-02 +-1.48484848484848e+01 -1.16179648627071e+00 1.42415253094923e-01 3.15133238851397e-02 +-1.42424242424242e+01 -1.14050675694352e+00 1.31113076076399e-01 2.06305497523611e-02 +-1.36363636363636e+01 -1.11318982416965e+00 1.19491463618837e-01 6.42328479698607e-03 +-1.30303030303030e+01 -1.08076735917766e+00 1.07643742796169e-01 -7.83926565619422e-03 +-1.24242424242424e+01 -1.03727303023693e+00 9.49346653316282e-02 -1.75014551808433e-02 +-1.18181818181818e+01 -9.91440219649850e-01 8.26304983608341e-02 -2.54111950263429e-02 +-1.12121212121212e+01 -9.43045452072816e-01 7.24323611406984e-02 -2.97310850160300e-02 +-1.06060606060606e+01 -8.91357118244056e-01 6.36793113860100e-02 -3.46811573258460e-02 +-1.00000000000000e+01 -8.38640919151541e-01 5.56031252905086e-02 -4.00042772613043e-02 +-9.39393939393939e+00 -7.97154810810589e-01 4.56286447472684e-02 -4.58057854493708e-02 +-8.78787878787879e+00 -7.57700218153473e-01 3.48441279722901e-02 -5.20559338844009e-02 +-8.18181818181818e+00 -7.29615756802838e-01 2.21903132460571e-02 -5.98183982708405e-02 +-7.57575757575758e+00 -6.77769009447363e-01 1.66725656645290e-02 -6.52314095706447e-02 +-6.96969696969697e+00 -6.15253643707113e-01 1.38193953292020e-02 -6.96903302338436e-02 +-6.36363636363636e+00 -5.29222888480069e-01 1.28208124258429e-02 -7.60443151485867e-02 +-5.75757575757576e+00 -4.43714189157886e-01 1.18605164320041e-02 -8.20746230823483e-02 +-5.15151515151515e+00 -3.59021198798114e-01 1.11014093554157e-02 -8.75040133661531e-02 +-4.54545454545454e+00 -2.75625966933364e-01 1.06136414059815e-02 -9.20337243383322e-02 +-3.93939393939394e+00 -1.92587400034749e-01 1.02273414896665e-02 -9.62397074831400e-02 +-3.33333333333333e+00 -1.09292475701538e-01 9.90518405717358e-03 -9.99005436593104e-02 +-2.72727272727273e+00 -2.77772625212584e-02 9.71093449432091e-03 -1.03217781859456e-01 +-2.12121212121212e+00 5.20911798292055e-02 9.64590630058275e-03 -1.06366269240076e-01 +-1.51515151515152e+00 1.30586446388122e-01 9.55659941113129e-03 -1.09005739501319e-01 +-9.09090909090912e-01 2.08840498658564e-01 9.49982823781086e-03 -1.11539847170668e-01 +-3.03030303030302e-01 2.87578475260949e-01 9.58414006664110e-03 -1.13902065395105e-01 + 3.03030303030302e-01 3.65664552744906e-01 9.65560539372337e-03 -1.16149780563894e-01 + 9.09090909090912e-01 4.43204973276288e-01 9.71978591639622e-03 -1.18219507269873e-01 + 1.51515151515152e+00 5.20281024804697e-01 9.71394548831763e-03 -1.20121864462230e-01 + 2.12121212121212e+00 5.96811467615798e-01 9.80332128304454e-03 -1.21920157367353e-01 + 2.72727272727273e+00 6.71434914937960e-01 9.98488831915120e-03 -1.23594864438980e-01 + 3.33333333333333e+00 7.45656831699806e-01 1.01455835290262e-02 -1.25107525282158e-01 + 3.93939393939394e+00 8.19857800959508e-01 1.02378295152185e-02 -1.26457757043226e-01 + 4.54545454545455e+00 8.93627925198807e-01 1.03669090136902e-02 -1.27577353045154e-01 + 5.15151515151515e+00 9.66788832639503e-01 1.05314448784099e-02 -1.28565417198802e-01 + 5.75757575757576e+00 1.03821639854981e+00 1.07650302198420e-02 -1.29227175957820e-01 + 6.36363636363637e+00 1.10795832677679e+00 1.10272583218359e-02 -1.29514536462203e-01 + 6.96969696969697e+00 1.17694418225097e+00 1.12742209874335e-02 -1.29549901025754e-01 + 7.57575757575757e+00 1.23921531344826e+00 1.16670639800197e-02 -1.28261266809327e-01 + 8.18181818181818e+00 1.29706014706839e+00 1.24490049337565e-02 -1.26386684375794e-01 + 8.78787878787879e+00 1.34554047570179e+00 1.37772189838099e-02 -1.23143424626972e-01 + 9.39393939393939e+00 1.37610897192605e+00 1.75961680761005e-02 -1.21674324726306e-01 + 1.00000000000000e+01 1.39836265121160e+00 2.28583111147752e-02 -1.21039639768622e-01 + 1.06060606060606e+01 1.39287314658036e+00 2.77463509449118e-02 -1.19204194226554e-01 + 1.12121212121212e+01 1.39004598907911e+00 3.19782079487326e-02 -1.15663804195089e-01 + 1.18181818181818e+01 1.39216407137552e+00 3.49921524756390e-02 -1.09850755288886e-01 + 1.24242424242424e+01 1.29370295829420e+00 4.85210271088614e-02 -1.10247193463411e-01 + 1.30303030303030e+01 1.14384582375774e+00 6.62157966012066e-02 -1.11897572147813e-01 + 1.36363636363636e+01 1.11782919778447e+00 7.57838750439830e-02 -1.11408861155646e-01 + 1.42424242424242e+01 1.09289947478728e+00 8.53102626033743e-02 -1.11136178965314e-01 + 1.48484848484848e+01 1.07102348419001e+00 9.46544491998690e-02 -1.11159785150535e-01 + 1.54545454545455e+01 1.05696164008760e+00 1.03374871102944e-01 -1.10493943921915e-01 + 1.60606060606061e+01 1.04604302431932e+00 1.11858598309336e-01 -1.10049366517221e-01 + 1.66666666666667e+01 1.03932307570257e+00 1.20082914343280e-01 -1.09980310610667e-01 + 1.72727272727273e+01 1.03747930790449e+00 1.29111242533919e-01 -1.10591886748552e-01 + 1.78787878787879e+01 1.04205220466167e+00 1.39122262444516e-01 -1.12023579838031e-01 + 1.84848484848485e+01 1.05490344379951e+00 1.50986790721675e-01 -1.15270449343547e-01 + 1.90909090909091e+01 1.06946548085938e+00 1.63292698023894e-01 -1.19065362073820e-01 + 1.96969696969697e+01 1.08276085154215e+00 1.75474320562998e-01 -1.23397138492291e-01 + 2.03030303030303e+01 1.09403365481318e+00 1.88008089241998e-01 -1.28358085737133e-01 + 2.09090909090909e+01 1.10239238595793e+00 2.00894023983065e-01 -1.33614744559156e-01 + 2.15151515151515e+01 1.10887254746938e+00 2.13779958724133e-01 -1.38763402571504e-01 + 2.21212121212121e+01 1.11237585687728e+00 2.26320681259285e-01 -1.44191042062497e-01 + 2.27272727272727e+01 1.10397482083247e+00 2.37480910168700e-01 -1.50693555732446e-01 + 2.33333333333333e+01 1.09557378478766e+00 2.48641139078116e-01 -1.57112728954266e-01 + 2.39393939393939e+01 1.08717274874285e+00 2.59801367987532e-01 -1.63133329944962e-01 + 2.45454545454545e+01 1.08003882943089e+00 2.71421389304264e-01 -1.68354300674623e-01 + 2.51515151515151e+01 1.07304569783844e+00 2.83092497567289e-01 -1.73495272149449e-01 + 2.57575757575758e+01 1.06605256624600e+00 2.94763605830315e-01 -1.78646564861648e-01 + 2.63636363636364e+01 1.05985153546545e+00 3.06826689596951e-01 -1.83426648708445e-01 + 2.69696969696970e+01 1.05417865395407e+00 3.19151130974461e-01 -1.87959534349431e-01 + 2.75757575757576e+01 1.04850577244270e+00 3.31475572351972e-01 -1.92498924465493e-01 + 2.81818181818182e+01 1.04309074438137e+00 3.43977607118473e-01 -1.96910710531247e-01 + 2.87878787878788e+01 1.03827732275955e+00 3.56893990913108e-01 -2.01014545276943e-01 + 2.93939393939394e+01 1.03346390113772e+00 3.69810374707743e-01 -2.05122663450476e-01 + 3.00000000000000e+01 1.02865047951590e+00 3.82726758502379e-01 -2.09235101253211e-01 + 3.30000000000000e+01 1.00767522728702e+00 4.50048605759265e-01 -2.27666231032229e-01 + 3.60000000000000e+01 9.87502112870606e-01 5.20200446113040e-01 -2.44805976520978e-01 + 3.90000000000000e+01 9.66075877033301e-01 5.93029893358622e-01 -2.61539856917676e-01 + 4.20000000000000e+01 9.41098858571731e-01 6.67518950513352e-01 -2.77304866762762e-01 + 4.50000000000000e+01 9.14833592285066e-01 7.42420845191650e-01 -2.92778427054725e-01 + 4.80000000000000e+01 8.81408622533811e-01 8.17249434089067e-01 -3.07497585034756e-01 + 5.10000000000000e+01 8.43819604431597e-01 8.90525057771138e-01 -3.21903684993278e-01 + 5.40000000000000e+01 7.97902221930250e-01 9.60694651185909e-01 -3.35704391970839e-01 + 5.70000000000000e+01 7.51985042501660e-01 1.03086370854641e+00 -3.49495136575764e-01 + 6.00000000000000e+01 7.06067964608676e-01 1.10103249788183e+00 -3.63279172814127e-01 + 6.30000000000000e+01 6.44293944876385e-01 1.15795405351184e+00 -3.75684064171539e-01 + 6.60000000000000e+01 5.82519789224936e-01 1.21487549559204e+00 -3.88081898949555e-01 + 6.90000000000000e+01 5.20745633573486e-01 1.27179693767224e+00 -4.00474177818223e-01 + 7.20000000000000e+01 4.51451982439921e-01 1.31524577920238e+00 -4.11592132530663e-01 + 7.50000000000000e+01 3.78398737499386e-01 1.35195859625958e+00 -4.22069569360111e-01 + 7.80000000000000e+01 3.05344055424385e-01 1.38867183401641e+00 -4.32541989601588e-01 + 8.10000000000000e+01 2.30976975521496e-01 1.41713840709990e+00 -4.42143819760501e-01 + 8.40000000000000e+01 1.53985190557838e-01 1.42911222008308e+00 -4.50008085895448e-01 + 8.70000000000000e+01 7.69925651285527e-02 1.44108612453959e+00 -4.57867677290619e-01 + 9.00000000000000e+01 -3.36373889913427e-07 1.45305992526757e+00 -4.65723360969959e-01 + 9.30000000000000e+01 -5.38949836895802e-02 1.44108611228438e+00 -4.70213156857291e-01 + 9.60000000000000e+01 -1.07789636867620e-01 1.42911225356491e+00 -4.74730592511974e-01 + 9.90000000000000e+01 -1.61684301770570e-01 1.41713830337121e+00 -4.79276533058230e-01 + 1.02000000000000e+02 -2.13741036335945e-01 1.38867165620685e+00 -4.80562246931058e-01 + 1.05000000000000e+02 -2.64878825634710e-01 1.35195883914965e+00 -4.80232757378909e-01 + 1.08000000000000e+02 -3.16016600929376e-01 1.31524560139462e+00 -4.79737782066907e-01 + 1.11000000000000e+02 -3.64522317186419e-01 1.27179644456681e+00 -4.77863421662414e-01 + 1.14000000000000e+02 -4.07763995533133e-01 1.21487565475428e+00 -4.73449633291489e-01 + 1.17000000000000e+02 -4.51005751931015e-01 1.15795443010112e+00 -4.69034472019867e-01 + 1.20000000000000e+02 -4.94247525649446e-01 1.10103296211486e+00 -4.64618222554077e-01 + 1.23000000000000e+02 -5.26389596453192e-01 1.03086417277945e+00 -4.58370282910620e-01 + 1.26000000000000e+02 -5.58531663885406e-01 9.60695115424263e-01 -4.52121193405810e-01 + 1.29000000000000e+02 -5.90673724574306e-01 8.90525522009491e-01 -4.45870794666629e-01 + 1.32000000000000e+02 -6.15315579547438e-01 8.17225281824516e-01 -4.40405924630618e-01 + 1.35000000000000e+02 -6.36207340549935e-01 7.42359721972419e-01 -4.35333210353452e-01 + 1.38000000000000e+02 -6.57098483724280e-01 6.67494798442361e-01 -4.30259571411825e-01 + 1.41000000000000e+02 -6.75928714282518e-01 5.94098982936727e-01 -4.27362077072584e-01 + 1.44000000000000e+02 -6.90637102885333e-01 5.23641395400969e-01 -4.28817330039073e-01 + 1.47000000000000e+02 -7.05344979121394e-01 4.53184198414303e-01 -4.30270852318803e-01 + 1.50000000000000e+02 -7.20052599183224e-01 3.82727196695211e-01 -4.31722931389651e-01 + 1.53000000000000e+02 -7.10181631872742e-01 3.29822360950801e-01 -4.46423672577750e-01 + 1.56000000000000e+02 -7.03319879618389e-01 2.76917694334790e-01 -4.61114380563247e-01 + 1.59000000000000e+02 -6.96086980977297e-01 2.24013284168088e-01 -4.74558545497368e-01 + 1.62000000000000e+02 -6.23394384096259e-01 1.85740697616627e-01 -4.83189489859145e-01 + 1.65000000000000e+02 -5.19495002406176e-01 1.54784146617186e-01 -4.89493605397558e-01 + 1.68000000000000e+02 -4.15596211308916e-01 1.23827350356444e-01 -4.95797422538914e-01 + 1.71000000000000e+02 -3.11697223350018e-01 9.28705619946343e-02 -4.50000513056908e-01 + 1.74000000000000e+02 -2.07797841658894e-01 6.19137894310576e-02 -2.99999717902353e-01 + 1.77000000000000e+02 -1.03426007186958e-01 5.10483521183991e-02 -1.49315896260807e-01 + 1.80000000000000e+02 0.00000000000000e+00 5.02376982549728e-02 0.00000000000000e+00 diff --git a/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_18.dat b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_18.dat new file mode 100644 index 00000000..2754301a --- /dev/null +++ b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_18.dat @@ -0,0 +1,254 @@ +! ------------ AirfoilInfo v1.01.x Input File ---------------------------------- +! AeroElasticSE FAST driver +! line +! line +! ------------------------------------------------------------------------------ +DEFAULT InterpOrd ! Interpolation order to use for quasi-steady table lookup {1=linear; 3=cubic spline; "default"} [default=3] +1 NonDimArea ! The non-dimensional area of the airfoil (area/chord^2) (set to 1.0 if unsure or unneeded) +@"NREL-2p8-127_AF18_Coords.txt" NumCoords ! The number of coordinates in the airfoil shape file. Set to zero if coordinates not included. +AF18_BL.txt BL_file ! The file name including the boundary layer characteristics of the profile. Ignored if the aeroacoustic module is not called. +1 NumTabs ! Number of airfoil tables in this file. Each table must have lines for Re and Ctrl. +! ------------------------------------------------------------------------------ +! data for table 1 +! ------------------------------------------------------------------------------ +6.000000 Re ! Reynolds number in millions +0 Ctrl ! Control setting (must be 0 for current AirfoilInfo) +True InclUAdata ! Is unsteady aerodynamics data included in this table? If TRUE, then include 30 UA coefficients below this line +!........................................ +-2.792370 alpha0 ! 0-lift angle of attack, depends on airfoil. +9.587807 alpha1 ! Angle of attack at f=0.7, (approximately the stall angle) for AOA>alpha0. (deg) +-11.610700 alpha2 ! Angle of attack at f=0.7, (approximately the stall angle) for AOA1] +0.000000 S2 ! Constant in the f curve best-fit for AOA> alpha1; by definition it depends on the airfoil. [ignored if UAMod<>1] +0.000000 S3 ! Constant in the f curve best-fit for alpha2<=AOA< alpha0; by definition it depends on the airfoil. [ignored if UAMod<>1] +0.000000 S4 ! Constant in the f curve best-fit for AOA< alpha2; by definition it depends on the airfoil. [ignored if UAMod<>1] +1.342044 Cn1 ! Critical value of C0n at leading edge separation. It should be extracted from airfoil data at a given Mach and Reynolds number. It can be calculated from the static value of Cn at either the break in the pitching moment or the loss of chord force at the onset of stall. It is close to the condition of maximum lift of the airfoil at low Mach numbers. +-1.062317 Cn2 ! As Cn1 for negative AOAs. +Default St_sh ! Strouhal's shedding frequency constant. [default = 0.19] +0.008843 Cd0 ! 2D drag coefficient value at 0-lift. +-0.109829 Cm0 ! 2D pitching moment coefficient about 1/4-chord location, at 0-lift, positive if nose up. [If the aerodynamics coefficients table does not include a column for Cm, this needs to be set to 0.0] +0.000000 k0 ! Constant in the \hat(x)_cp curve best-fit; = (\hat(x)_AC-0.25). [ignored if UAMod<>1] +0.000000 k1 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k2 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k3 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k1_hat ! Constant in the expression of Cc due to leading edge vortex effects. [ignored if UAMod<>1] +Default x_cp_bar ! Constant in the expression of \hat(x)_cp^v. [ignored if UAMod<>1, default = 0.2] +Default UACutout ! Angle of attack above which unsteady aerodynamics are disabled (deg). [Specifying the string "Default" sets UACutout to 45 degrees] +Default filtCutOff ! Cut-off frequency (-3 dB corner frequency) for low-pass filtering the AoA input to UA, as well as the 1st and 2nd derivatives (Hz) [default = 20] +!........................................ +! Table of aerodynamics coefficients +200 NumAlf ! Number of data lines in the following table +! Alpha Cl Cd Cm +! (deg) (-) (-) (-) +-1.80000000000000e+02 0.00000000000000e+00 5.36137248474854e-02 0.00000000000000e+00 +-1.77000000000000e+02 1.08504173136844e-01 5.36137248474854e-02 1.19452717008645e-01 +-1.74000000000000e+02 2.18001573212032e-01 6.43364093197600e-02 2.39999774321882e-01 +-1.71000000000000e+02 3.27002606158882e-01 9.65048147530414e-02 3.60000410445527e-01 +-1.68000000000000e+02 4.36007303027872e-01 1.28672864881152e-01 3.18853353245729e-01 +-1.65000000000000e+02 5.45015893840642e-01 1.60840737360825e-01 1.97134330215277e-01 +-1.62000000000000e+02 6.54027865395150e-01 1.93008707125421e-01 7.54136410554247e-02 +-1.59000000000000e+02 7.27335195948828e-01 2.32421567454577e-01 -7.86707963484010e-03 +-1.56000000000000e+02 7.26473886558584e-01 2.86323963827313e-01 -1.32688253981472e-02 +-1.53000000000000e+02 7.26401782562124e-01 3.40226371983972e-01 -1.93321617932501e-02 +-1.50000000000000e+02 7.29414906072036e-01 3.94128823688151e-01 -3.04550520731389e-02 +-1.47000000000000e+02 7.13608094775223e-01 4.64191024348164e-01 -1.44069907171891e-02 +-1.44000000000000e+02 6.97801023105656e-01 5.34253347401846e-01 1.64143099960009e-03 +-1.41000000000000e+02 6.81993430671987e-01 6.04315915251604e-01 1.79777655646737e-02 +-1.38000000000000e+02 6.62330345884982e-01 6.77255624037684e-01 3.42196692787287e-02 +-1.35000000000000e+02 6.40739522742596e-01 7.51633897455329e-01 5.03555236432470e-02 +-1.32000000000000e+02 6.19148287855155e-01 8.26012587517633e-01 6.64803246966578e-02 +-1.29000000000000e+02 5.93883607684111e-01 8.98800336981566e-01 8.26682061752675e-02 +-1.26000000000000e+02 5.61272019531039e-01 9.68406197695395e-01 9.89967979935854e-02 +-1.23000000000000e+02 5.28660570956951e-01 1.03801152665627e+00 1.15320660255902e-01 +-1.20000000000000e+02 4.96049192169745e-01 1.10761658975060e+00 1.31640184505148e-01 +-1.17000000000000e+02 4.52499966498427e-01 1.16391394816134e+00 1.47076828299769e-01 +-1.14000000000000e+02 4.08950831006833e-01 1.22021106550486e+00 1.62511306961593e-01 +-1.11000000000000e+02 3.65401918647224e-01 1.27650775277552e+00 1.77943395962959e-01 +-1.08000000000000e+02 3.16676605002551e-01 1.31930568274196e+00 1.91712305326037e-01 +-1.05000000000000e+02 2.65363051300195e-01 1.35535413126937e+00 2.04649708702310e-01 +-1.02000000000000e+02 2.14049485607990e-01 1.39140216671678e+00 2.17585944039292e-01 +-9.90000000000000e+01 1.61856439692740e-01 1.41919689307479e+00 2.29156194914714e-01 +-9.60000000000000e+01 1.07904395236486e-01 1.43048464375975e+00 2.37995669823376e-01 +-9.30000000000000e+01 5.39523629434884e-02 1.44177230821265e+00 2.46835565853370e-01 +-9.00000000000000e+01 3.36732009892260e-07 1.45305992955031e+00 2.55676268872361e-01 +-8.70000000000000e+01 -5.39523077235666e-02 1.44177231976554e+00 2.60546156064344e-01 +-8.40000000000000e+01 -1.07904546098422e-01 1.43048461219668e+00 2.65376218554658e-01 +-8.10000000000000e+01 -1.61855972313595e-01 1.41919699085902e+00 2.70167661087483e-01 +-7.80000000000000e+01 -2.14049237083272e-01 1.39140234130663e+00 2.71634637929492e-01 +-7.50000000000000e+01 -2.65363390787359e-01 1.35535389277745e+00 2.71422475089917e-01 +-7.20000000000000e+01 -3.16676356483258e-01 1.31930585733004e+00 2.71175587395195e-01 +-6.90000000000000e+01 -3.65401541382520e-01 1.27650824047434e+00 2.69624220790176e-01 +-6.60000000000000e+01 -4.08950952778550e-01 1.22021090808774e+00 2.65499895797782e-01 +-6.30000000000000e+01 -4.52500254617964e-01 1.16391357570114e+00 2.61346777314543e-01 +-6.00000000000000e+01 -4.96049407924919e-01 1.10761612924714e+00 2.57166068579216e-01 +-5.70000000000000e+01 -5.28660786712125e-01 1.03801106615281e+00 2.51133429071216e-01 +-5.40000000000000e+01 -5.61272235287598e-01 9.68405737186667e-01 2.45075869286174e-01 +-5.10000000000000e+01 -5.93883823440670e-01 8.98799876472838e-01 2.38994436395362e-01 +-4.80000000000000e+01 -6.20771155324413e-01 8.26050727323750e-01 2.33161030617360e-01 +-4.50000000000000e+01 -6.44796451070394e-01 7.51729984474128e-01 2.27439298824510e-01 +-4.20000000000000e+01 -6.63953200654077e-01 6.77293763541013e-01 2.23291102757799e-01 +-3.90000000000000e+01 -6.82249667333847e-01 6.03259850610683e-01 2.19817265076178e-01 +-3.60000000000000e+01 -6.98201576773723e-01 5.30851294361004e-01 2.18838619571564e-01 +-3.30000000000000e+01 -7.13444606626873e-01 4.61088222324340e-01 2.21122290445851e-01 +-3.00000000000000e+01 -7.29415020855328e-01 3.94128387846700e-01 2.27054455296579e-01 +-2.93939393939394e+01 -7.33089414277251e-01 3.81279477717506e-01 2.29240557823958e-01 +-2.87878787878788e+01 -7.36763807699173e-01 3.68430567588313e-01 2.31426660351336e-01 +-2.81818181818182e+01 -7.40438201121096e-01 3.55581657459119e-01 2.33612762878715e-01 +-2.75757575757576e+01 -7.44561188035578e-01 3.43144145729673e-01 2.36503775794692e-01 +-2.69696969696970e+01 -7.48876445797132e-01 3.30882962725711e-01 2.39696919079866e-01 +-2.63636363636364e+01 -7.53191703558686e-01 3.18621779721749e-01 2.42890062365039e-01 +-2.57575757575758e+01 -7.57896949106898e-01 3.06620180092045e-01 2.46611383026609e-01 +-2.51515151515151e+01 -7.63187085443502e-01 2.95007895024532e-01 2.51124846654346e-01 +-2.45454545454545e+01 -7.68477221780106e-01 2.83395609957020e-01 2.55638310282083e-01 +-2.39393939393939e+01 -7.74029112998335e-01 2.71848572457760e-01 2.59427106627508e-01 +-2.33333333333333e+01 -7.81936848828191e-01 2.60888775705009e-01 2.56693757133074e-01 +-2.27272727272727e+01 -7.89844584658047e-01 2.49928978952259e-01 2.54973507041906e-01 +-2.21212121212121e+01 -7.97752320487903e-01 2.38969182199509e-01 2.51757698493230e-01 +-2.15151515151515e+01 -8.17245649453576e-01 2.29474770810752e-01 2.34218156316905e-01 +-2.09090909090909e+01 -8.40715821523898e-01 2.20346800023089e-01 2.15558365010287e-01 +-2.03030303030303e+01 -8.64893147204684e-01 2.11218829235425e-01 1.97258668465790e-01 +-1.96969696969697e+01 -8.87438946084652e-01 2.02091078490948e-01 1.79104249713839e-01 +-1.90909090909091e+01 -9.09237361854086e-01 1.92963547777208e-01 1.61007469502170e-01 +-1.84848484848485e+01 -9.33071785400616e-01 1.84171846523930e-01 1.42945493987761e-01 +-1.78787878787879e+01 -9.57306241435504e-01 1.76283936647877e-01 1.23884251763747e-01 +-1.72727272727273e+01 -9.81604014520295e-01 1.68616795799771e-01 1.04367473421751e-01 +-1.66666666666667e+01 -1.00737125830751e+00 1.60297507335738e-01 8.48827458147722e-02 +-1.60606060606061e+01 -1.03415415721149e+00 1.51566539016137e-01 6.54371368564537e-02 +-1.54545454545455e+01 -1.05213926667993e+00 1.41887359500634e-01 4.85999555851204e-02 +-1.48484848484848e+01 -1.06411426754698e+00 1.31650218002569e-01 3.32132244253039e-02 +-1.42424242424242e+01 -1.06085920517278e+00 1.20325281854275e-01 1.97519541398105e-02 +-1.36363636363636e+01 -1.05297179510023e+00 1.08818108910721e-01 3.34724170517964e-03 +-1.30303030303030e+01 -1.04038617850512e+00 9.71704693558744e-02 -1.30280274230778e-02 +-1.24242424242424e+01 -1.00963309974379e+00 8.35931628390448e-02 -2.24525867458495e-02 +-1.18181818181818e+01 -9.74392976542105e-01 7.02569290424257e-02 -2.96665236814477e-02 +-1.12121212121212e+01 -9.33183989496999e-01 5.92863820290872e-02 -3.25396861725729e-02 +-1.06060606060606e+01 -8.87095198505282e-01 5.02112419249079e-02 -3.68554806252278e-02 +-1.00000000000000e+01 -8.39030346732209e-01 4.20062550430957e-02 -4.19667667411679e-02 +-9.39393939393939e+00 -7.98355307687373e-01 3.39431550888320e-02 -4.71586015184073e-02 +-8.78787878787879e+00 -7.55075718086549e-01 2.58616329336961e-02 -5.31128483759924e-02 +-8.18181818181818e+00 -7.12760376198709e-01 1.76807004789459e-02 -6.15557949547917e-02 +-7.57575757575758e+00 -6.50212657860430e-01 1.40779977251651e-02 -6.80037285779409e-02 +-6.96969696969697e+00 -5.79316182872428e-01 1.20930353131595e-02 -7.36947785344258e-02 +-6.36363636363636e+00 -4.93332487227875e-01 1.12571113999265e-02 -8.08636763018482e-02 +-5.75757575757576e+00 -4.07625165812638e-01 1.04386697349651e-02 -8.76670243494600e-02 +-5.15151515151515e+00 -3.22375665042248e-01 9.89046924180047e-03 -9.37249643058138e-02 +-4.54545454545454e+00 -2.38569752393226e-01 9.55568172944726e-03 -9.85721042394988e-02 +-3.93939393939394e+00 -1.55278792252772e-01 9.28231334429143e-03 -1.03000270064649e-01 +-3.33333333333333e+00 -7.27588785201134e-02 9.00905966504459e-03 -1.06804167238102e-01 +-2.72727272727273e+00 8.75545142458852e-03 8.82260921114890e-03 -1.10193484668354e-01 +-2.12121212121212e+00 8.90951677107422e-02 8.71711984822585e-03 -1.13439603715240e-01 +-1.51515151515152e+00 1.68020877233593e-01 8.63506810960759e-03 -1.15955900231793e-01 +-9.09090909090912e-01 2.46284645308487e-01 8.59786619783916e-03 -1.18329762049110e-01 +-3.03030303030302e-01 3.23526927130680e-01 8.68469307519355e-03 -1.20499605866875e-01 + 3.03030303030302e-01 4.00568746060339e-01 8.73666462420641e-03 -1.22563336532720e-01 + 9.09090909090912e-01 4.77532382355605e-01 8.76693795829447e-03 -1.24415248851028e-01 + 1.51515151515152e+00 5.54310964834009e-01 8.75563015487188e-03 -1.26154371277845e-01 + 2.12121212121212e+00 6.30748642497307e-01 8.89942708059405e-03 -1.27777288327563e-01 + 2.72727272727273e+00 7.05967166479233e-01 9.07466954914071e-03 -1.29308981144731e-01 + 3.33333333333333e+00 7.80411644410489e-01 9.23152948118853e-03 -1.30694777177827e-01 + 3.93939393939394e+00 8.54634907157449e-01 9.35773501083766e-03 -1.31925075915747e-01 + 4.54545454545455e+00 9.28368090200400e-01 9.52948973845109e-03 -1.32899735261145e-01 + 5.15151515151515e+00 1.00145694605734e+00 9.73306782417346e-03 -1.33724225695198e-01 + 5.75757575757576e+00 1.07270733762567e+00 1.00006966462114e-02 -1.34169484840169e-01 + 6.36363636363637e+00 1.14127724503204e+00 1.02973665103093e-02 -1.34153350705440e-01 + 6.96969696969697e+00 1.20864942903410e+00 1.05582170564899e-02 -1.33827802118801e-01 + 7.57575757575757e+00 1.26443440681650e+00 1.10668993698580e-02 -1.31662626204201e-01 + 8.18181818181818e+00 1.31327712628436e+00 1.21179224024120e-02 -1.28718467346890e-01 + 8.78787878787879e+00 1.34931677106702e+00 1.38745085223537e-02 -1.24009773357878e-01 + 9.39393939393939e+00 1.35685700568352e+00 2.07295073959453e-02 -1.22353831339396e-01 + 1.00000000000000e+01 1.34623269398792e+00 3.03611166129043e-02 -1.22101994507537e-01 + 1.06060606060606e+01 1.29247625354756e+00 3.89303371400334e-02 -1.20772828739056e-01 + 1.12121212121212e+01 1.25212720004798e+00 4.59269172993146e-02 -1.17349872385937e-01 + 1.18181818181818e+01 1.23668533143930e+00 5.00033361654154e-02 -1.11373005101486e-01 + 1.24242424242424e+01 1.18614194111661e+00 6.00007067895342e-02 -1.09801411206576e-01 + 1.30303030303030e+01 1.11590193321859e+00 7.24445919904755e-02 -1.08383334659172e-01 + 1.36363636363636e+01 1.11070643578549e+00 8.22712281118321e-02 -1.09098841523507e-01 + 1.42424242424242e+01 1.10016431536211e+00 9.22478830207050e-02 -1.10082030306725e-01 + 1.48484848484848e+01 1.08932388927719e+00 1.02384259095179e-01 -1.11305168394289e-01 + 1.54545454545455e+01 1.08265839747059e+00 1.11362550974526e-01 -1.11223542069270e-01 + 1.60606060606061e+01 1.07750353752455e+00 1.19864697023678e-01 -1.11093423299158e-01 + 1.66666666666667e+01 1.07245197326073e+00 1.27554831236544e-01 -1.10774119006494e-01 + 1.72727272727273e+01 1.07224113795030e+00 1.36494897934856e-01 -1.11302931932702e-01 + 1.78787878787879e+01 1.07862447668773e+00 1.46962675742666e-01 -1.12850875597998e-01 + 1.84848484848485e+01 1.08861259617754e+00 1.59145187067245e-01 -1.16200177309305e-01 + 1.90909090909091e+01 1.09918905179666e+00 1.71646795036045e-01 -1.20001587294594e-01 + 1.96969696969697e+01 1.10912810899916e+00 1.83527588865384e-01 -1.23816697554203e-01 + 2.03030303030303e+01 1.11825522290028e+00 1.96466839959649e-01 -1.28421649372128e-01 + 2.09090909090909e+01 1.12524803924632e+00 2.10464608199569e-01 -1.33477817053054e-01 + 2.15151515151515e+01 1.12945414332918e+00 2.24462376439488e-01 -1.38427537382908e-01 + 2.21212121212121e+01 1.13110996428679e+00 2.37920120683396e-01 -1.43742831263358e-01 + 2.27272727272727e+01 1.12256727679690e+00 2.49218324588170e-01 -1.50497808264014e-01 + 2.33333333333333e+01 1.11402458930701e+00 2.60516528492943e-01 -1.57166764414652e-01 + 2.39393939393939e+01 1.10548190181713e+00 2.71814732397717e-01 -1.63463059451524e-01 + 2.45454545454545e+01 1.09782581769558e+00 2.83395609957020e-01 -1.68925418413166e-01 + 2.51515151515151e+01 1.09026824294031e+00 2.95007895024532e-01 -1.74308243109077e-01 + 2.57575757575758e+01 1.08271066818504e+00 3.06620180092045e-01 -1.79706378559642e-01 + 2.63636363636364e+01 1.07598865169483e+00 3.18621779721749e-01 -1.84704949130393e-01 + 2.69696969696970e+01 1.06982376061140e+00 3.30882962725711e-01 -1.89437565776199e-01 + 2.75757575757576e+01 1.06365886952798e+00 3.43144145729673e-01 -1.94179831305997e-01 + 2.81818181818182e+01 1.05776902996474e+00 3.55581657459119e-01 -1.98785028498289e-01 + 2.87878787878788e+01 1.05252092222901e+00 3.68430567588313e-01 -2.03055245546250e-01 + 2.93939393939394e+01 1.04727281449329e+00 3.81279477717506e-01 -2.07331816726986e-01 + 3.00000000000000e+01 1.04202470675756e+00 3.94128387846700e-01 -2.11614795742417e-01 + 3.30000000000000e+01 1.01920513278199e+00 4.61088222324340e-01 -2.30709635446696e-01 + 3.60000000000000e+01 9.97430021449977e-01 5.30851294361004e-01 -2.48389635018723e-01 + 3.90000000000000e+01 9.74642622581348e-01 6.03259850610683e-01 -2.65244377392235e-01 + 4.20000000000000e+01 9.48504923410187e-01 6.77293763541014e-01 -2.81146520062724e-01 + 4.50000000000000e+01 9.21138527003474e-01 7.51729984474128e-01 -2.96778859241448e-01 + 4.80000000000000e+01 8.86816262654281e-01 8.26050727323750e-01 -3.11620664341732e-01 + 5.10000000000000e+01 8.48405523199447e-01 8.98799876472838e-01 -3.26146108681646e-01 + 5.40000000000000e+01 8.01817570694549e-01 9.68405737186667e-01 -3.40039290927774e-01 + 5.70000000000000e+01 7.55229683651232e-01 1.03801106615281e+00 -3.53931325023812e-01 + 6.00000000000000e+01 7.08641829338459e-01 1.10761612924715e+00 -3.67824192591327e-01 + 6.30000000000000e+01 6.46428682755529e-01 1.16391357570114e+00 -3.80297188353490e-01 + 6.60000000000000e+01 5.84215402239047e-01 1.22021090808774e+00 -3.92768487627463e-01 + 6.90000000000000e+01 5.22002121722564e-01 1.27650824047434e+00 -4.05238805155188e-01 + 7.20000000000000e+01 4.52394670864868e-01 1.31930585733004e+00 -4.16419077136110e-01 + 7.50000000000000e+01 3.79090286205083e-01 1.35535389277745e+00 -4.26952712546759e-01 + 7.80000000000000e+01 3.05784461532969e-01 1.39140234130664e+00 -4.37484524738100e-01 + 8.10000000000000e+01 2.31222621050345e-01 1.41919699085902e+00 -4.47140901263708e-01 + 8.40000000000000e+01 1.54148835649795e-01 1.43048461219668e+00 -4.55046838069807e-01 + 8.70000000000000e+01 7.70743518918329e-02 1.44177231976554e+00 -4.62950611733494e-01 + 9.00000000000000e+01 -3.36732010122695e-07 1.45305992955031e+00 -4.70852706467098e-01 + 9.30000000000000e+01 -5.39523629434884e-02 1.44177230821265e+00 -4.75763515343477e-01 + 9.60000000000000e+01 -1.07904395236486e-01 1.43048464375975e+00 -4.80716438183718e-01 + 9.90000000000000e+01 -1.61856439692741e-01 1.41919689307479e+00 -4.85712617490280e-01 + 1.02000000000000e+02 -2.14049485607990e-01 1.39140216671678e+00 -4.87463918618097e-01 + 1.05000000000000e+02 -2.65363051300195e-01 1.35535413126937e+00 -4.87615426725982e-01 + 1.08000000000000e+02 -3.16676605002551e-01 1.31930568274196e+00 -4.87522734138826e-01 + 1.11000000000000e+02 -3.65401918647224e-01 1.27650775277552e+00 -4.85996410622861e-01 + 1.14000000000000e+02 -4.08950831006833e-01 1.22021106550486e+00 -4.81927358927190e-01 + 1.17000000000000e+02 -4.52499966498427e-01 1.16391394816134e+00 -4.77857363874255e-01 + 1.20000000000000e+02 -4.96049192169745e-01 1.10761658975060e+00 -4.73786676400946e-01 + 1.23000000000000e+02 -5.28660570956951e-01 1.03801152665627e+00 -4.67894035404986e-01 + 1.26000000000000e+02 -5.61272019531039e-01 9.68406197695395e-01 -4.62000666821961e-01 + 1.29000000000000e+02 -5.93883607684111e-01 8.98800336981565e-01 -4.56106383315202e-01 + 1.32000000000000e+02 -6.19148287855155e-01 8.26012587517633e-01 -4.51045249617514e-01 + 1.35000000000000e+02 -6.40739522742596e-01 7.51633897455329e-01 -4.46400358390250e-01 + 1.38000000000000e+02 -6.62330345884983e-01 6.77255624037683e-01 -4.41754984328411e-01 + 1.41000000000000e+02 -6.81993430671987e-01 6.04315915251604e-01 -4.39372656415041e-01 + 1.44000000000000e+02 -6.97801023105656e-01 5.34253347401846e-01 -4.41516679399736e-01 + 1.47000000000000e+02 -7.13608094775223e-01 4.64191024348164e-01 -4.43659776127911e-01 + 1.50000000000000e+02 -7.29414906072037e-01 3.94128823688151e-01 -4.45802094533083e-01 + 1.53000000000000e+02 -7.15037146111127e-01 3.41731197240688e-01 -4.59822411066617e-01 + 1.56000000000000e+02 -7.05123336765058e-01 2.89333666877955e-01 -4.73837152031237e-01 + 1.59000000000000e+02 -6.95414684317536e-01 2.36936246357618e-01 -4.86012649076484e-01 + 1.62000000000000e+02 -6.22098323807239e-01 1.97523498321224e-01 -4.91995579783009e-01 + 1.65000000000000e+02 -5.18414913187139e-01 1.64603196340870e-01 -4.94997251401146e-01 + 1.68000000000000e+02 -4.14732090684931e-01 1.31682671601892e-01 -4.97998891218103e-01 + 1.71000000000000e+02 -3.11049072145794e-01 9.87620758945397e-02 -4.50000513056908e-01 + 1.74000000000000e+02 -2.07365661523777e-01 6.58413382471257e-02 -2.99999717902353e-01 + 1.77000000000000e+02 -1.03210513612473e-01 5.43627855211274e-02 -1.49315896260807e-01 + 1.80000000000000e+02 0.00000000000000e+00 5.36137248474854e-02 0.00000000000000e+00 diff --git a/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_19.dat b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_19.dat new file mode 100644 index 00000000..de96b588 --- /dev/null +++ b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_19.dat @@ -0,0 +1,254 @@ +! ------------ AirfoilInfo v1.01.x Input File ---------------------------------- +! AeroElasticSE FAST driver +! line +! line +! ------------------------------------------------------------------------------ +DEFAULT InterpOrd ! Interpolation order to use for quasi-steady table lookup {1=linear; 3=cubic spline; "default"} [default=3] +1 NonDimArea ! The non-dimensional area of the airfoil (area/chord^2) (set to 1.0 if unsure or unneeded) +@"NREL-2p8-127_AF19_Coords.txt" NumCoords ! The number of coordinates in the airfoil shape file. Set to zero if coordinates not included. +AF19_BL.txt BL_file ! The file name including the boundary layer characteristics of the profile. Ignored if the aeroacoustic module is not called. +1 NumTabs ! Number of airfoil tables in this file. Each table must have lines for Re and Ctrl. +! ------------------------------------------------------------------------------ +! data for table 1 +! ------------------------------------------------------------------------------ +6.000000 Re ! Reynolds number in millions +0 Ctrl ! Control setting (must be 0 for current AirfoilInfo) +True InclUAdata ! Is unsteady aerodynamics data included in this table? If TRUE, then include 30 UA coefficients below this line +!........................................ +-3.045221 alpha0 ! 0-lift angle of attack, depends on airfoil. +9.266236 alpha1 ! Angle of attack at f=0.7, (approximately the stall angle) for AOA>alpha0. (deg) +-11.753418 alpha2 ! Angle of attack at f=0.7, (approximately the stall angle) for AOA1] +0.000000 S2 ! Constant in the f curve best-fit for AOA> alpha1; by definition it depends on the airfoil. [ignored if UAMod<>1] +0.000000 S3 ! Constant in the f curve best-fit for alpha2<=AOA< alpha0; by definition it depends on the airfoil. [ignored if UAMod<>1] +0.000000 S4 ! Constant in the f curve best-fit for AOA< alpha2; by definition it depends on the airfoil. [ignored if UAMod<>1] +1.340318 Cn1 ! Critical value of C0n at leading edge separation. It should be extracted from airfoil data at a given Mach and Reynolds number. It can be calculated from the static value of Cn at either the break in the pitching moment or the loss of chord force at the onset of stall. It is close to the condition of maximum lift of the airfoil at low Mach numbers. +-0.990977 Cn2 ! As Cn1 for negative AOAs. +Default St_sh ! Strouhal's shedding frequency constant. [default = 0.19] +0.008173 Cd0 ! 2D drag coefficient value at 0-lift. +-0.112549 Cm0 ! 2D pitching moment coefficient about 1/4-chord location, at 0-lift, positive if nose up. [If the aerodynamics coefficients table does not include a column for Cm, this needs to be set to 0.0] +0.000000 k0 ! Constant in the \hat(x)_cp curve best-fit; = (\hat(x)_AC-0.25). [ignored if UAMod<>1] +0.000000 k1 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k2 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k3 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k1_hat ! Constant in the expression of Cc due to leading edge vortex effects. [ignored if UAMod<>1] +Default x_cp_bar ! Constant in the expression of \hat(x)_cp^v. [ignored if UAMod<>1, default = 0.2] +Default UACutout ! Angle of attack above which unsteady aerodynamics are disabled (deg). [Specifying the string "Default" sets UACutout to 45 degrees] +Default filtCutOff ! Cut-off frequency (-3 dB corner frequency) for low-pass filtering the AoA input to UA, as well as the 1st and 2nd derivatives (Hz) [default = 20] +!........................................ +! Table of aerodynamics coefficients +200 NumAlf ! Number of data lines in the following table +! Alpha Cl Cd Cm +! (deg) (-) (-) (-) +-1.80000000000000e+02 0.00000000000000e+00 5.58151028351338e-02 0.00000000000000e+00 +-1.77000000000000e+02 1.08403822920070e-01 5.58151028351338e-02 1.19452717008645e-01 +-1.74000000000000e+02 2.17800459908011e-01 6.69780604209238e-02 2.39999774321882e-01 +-1.71000000000000e+02 3.26700878169450e-01 1.00467299648537e-01 3.60000410445527e-01 +-1.68000000000000e+02 4.35601558622185e-01 1.33956266552371e-01 3.19240159788981e-01 +-1.65000000000000e+02 5.44502718536549e-01 1.67445097297493e-01 1.98101342058805e-01 +-1.62000000000000e+02 6.53405489525881e-01 2.00933761249497e-01 7.69605856327805e-02 +-1.59000000000000e+02 7.27019339407255e-01 2.41089984114099e-01 -6.83110332274381e-03 +-1.56000000000000e+02 7.28728560841196e-01 2.94581099251365e-01 -1.48336824338646e-02 +-1.53000000000000e+02 7.31142347309657e-01 3.48072223030611e-01 -2.31137907275188e-02 +-1.50000000000000e+02 7.35519708784298e-01 4.01563389144863e-01 -3.46869785111124e-02 +-1.47000000000000e+02 7.18996156868714e-01 4.71368155114379e-01 -1.84787848110211e-02 +-1.44000000000000e+02 7.02472341842677e-01 5.41172995959272e-01 -2.27031145595949e-03 +-1.41000000000000e+02 6.85948000576950e-01 6.10977986560267e-01 1.41215595154545e-02 +-1.38000000000000e+02 6.65741843359713e-01 6.83620285576331e-01 3.03710500677338e-02 +-1.35000000000000e+02 6.43694785635686e-01 7.57681233044139e-01 4.65119317299114e-02 +-1.32000000000000e+02 6.21647450545519e-01 8.31742453913374e-01 6.26455676270925e-02 +-1.29000000000000e+02 5.95976649852831e-01 9.04196027753608e-01 7.88432528643242e-02 +-1.26000000000000e+02 5.63058900774808e-01 9.73434299905923e-01 9.51782729473790e-02 +-1.23000000000000e+02 5.30141386686949e-01 1.04267204311347e+00 1.11510014334606e-01 +-1.20000000000000e+02 4.97223990089781e-01 1.11190952185851e+00 1.27838839143617e-01 +-1.17000000000000e+02 4.53474286743658e-01 1.16779992225404e+00 1.43283454610664e-01 +-1.14000000000000e+02 4.09724721085944e-01 1.22369008305982e+00 1.58726450315576e-01 +-1.11000000000000e+02 3.65975473161876e-01 1.27957981690164e+00 1.74167578217843e-01 +-1.08000000000000e+02 3.17106968448641e-01 1.32195310670654e+00 1.87944896444489e-01 +-1.05000000000000e+02 2.65678796360799e-01 1.35756807157142e+00 2.00890123017622e-01 +-1.02000000000000e+02 2.14250613596524e-01 1.39318262832361e+00 2.13833889964470e-01 +-9.90000000000000e+01 1.61968684256675e-01 1.42053922078900e+00 2.25410295218944e-01 +-9.60000000000000e+01 1.07979224785424e-01 1.43137952698492e+00 2.34252955588311e-01 +-9.30000000000000e+01 5.39897777632595e-02 1.44221975036700e+00 2.43094929221455e-01 +-9.00000000000000e+01 3.36965526401992e-07 1.45305993234293e+00 2.51936472308407e-01 +-8.70000000000000e+01 -5.39897225050438e-02 1.44221976146193e+00 2.56931622255970e-01 +-8.40000000000000e+01 -1.07979375751980e-01 1.43137949667301e+00 2.61901020827721e-01 +-8.10000000000000e+01 -1.61968216553408e-01 1.42053931469708e+00 2.66845383648936e-01 +-7.80000000000000e+01 -2.14250364516685e-01 1.39318280081402e+00 2.68479729146681e-01 +-7.50000000000000e+01 -2.65679136606263e-01 1.35756783594738e+00 2.68447877672478e-01 +-7.20000000000000e+01 -3.17106719374234e-01 1.32195327919519e+00 2.68392871736955e-01 +-6.90000000000000e+01 -3.65975094161662e-01 1.27958030107501e+00 2.67043843374306e-01 +-6.60000000000000e+01 -4.09724843417841e-01 1.22368992678063e+00 2.63130341234035e-01 +-6.30000000000000e+01 -4.53474576189544e-01 1.16779955248625e+00 2.59197088106754e-01 +-6.00000000000000e+01 -4.97224207869552e-01 1.11190906378698e+00 2.55244704276654e-01 +-5.70000000000000e+01 -5.30141604466721e-01 1.04267158504194e+00 2.49454887071623e-01 +-5.40000000000000e+01 -5.63059118556911e-01 9.73433841829142e-01 2.43646817884402e-01 +-5.10000000000000e+01 -5.95976867634935e-01 9.04195569676826e-01 2.37820619877023e-01 +-4.80000000000000e+01 -6.23239324536221e-01 8.31789714461067e-01 2.32266352846812e-01 +-4.50000000000000e+01 -6.47674226237690e-01 7.57800118621131e-01 2.26836908914070e-01 +-4.20000000000000e+01 -6.67333704892715e-01 6.83667545750015e-01 2.23029606785968e-01 +-3.90000000000000e+01 -6.86159958788100e-01 6.09930414983374e-01 2.19918132247163e-01 +-3.60000000000000e+01 -7.02733476031370e-01 5.37796305675443e-01 2.19390306691080e-01 +-3.30000000000000e+01 -7.18707342668409e-01 4.68286734608672e-01 2.22226002504236e-01 +-3.00000000000000e+01 -7.35519829439412e-01 4.01562954836658e-01 2.28827939791023e-01 +-2.93939393939394e+01 -7.39392279869158e-01 3.88758041707422e-01 2.31182344944843e-01 +-2.87878787878788e+01 -7.43264730298904e-01 3.75953128578187e-01 2.33536750098664e-01 +-2.81818181818182e+01 -7.47137180728651e-01 3.63148215448951e-01 2.35891155252484e-01 +-2.75757575757576e+01 -7.51476885097161e-01 3.50752776727396e-01 2.38974806555987e-01 +-2.69696969696970e+01 -7.56016858332907e-01 3.38532842092560e-01 2.42371018735316e-01 +-2.63636363636364e+01 -7.60556831568653e-01 3.26312907457723e-01 2.45767230914644e-01 +-2.57575757575758e+01 -7.65500018552221e-01 3.14351399285216e-01 2.49710318611517e-01 +-2.51515151515151e+01 -7.71047932183450e-01 3.02777470576641e-01 2.54473592128438e-01 +-2.45454545454545e+01 -7.76595845814680e-01 2.91203541868066e-01 2.59236865645359e-01 +-2.39393939393939e+01 -7.82447959329456e-01 2.79692872440278e-01 2.62992965843921e-01 +-2.33333333333333e+01 -7.91037930690711e-01 2.68751548786870e-01 2.57684311183680e-01 +-2.27272727272727e+01 -7.99627902051967e-01 2.57810225133461e-01 2.53255349257629e-01 +-2.21212121212121e+01 -8.08217873413222e-01 2.46868901480052e-01 2.47684440936497e-01 +-2.15151515151515e+01 -8.19990478826953e-01 2.36221993248645e-01 2.31504471971342e-01 +-2.09090909090909e+01 -8.34647953216695e-01 2.25648707810846e-01 2.13702005243607e-01 +-2.03030303030303e+01 -8.49132464561041e-01 2.15075422373046e-01 1.95960374750995e-01 +-1.96969696969697e+01 -8.62578663351143e-01 2.04502427490460e-01 1.78243288992263e-01 +-1.90909090909091e+01 -8.75549253302963e-01 1.93929723146649e-01 1.60535941747677e-01 +-1.84848484848485e+01 -8.89815545281606e-01 1.83695365421934e-01 1.42835185458870e-01 +-1.78787878787879e+01 -9.04336378911458e-01 1.74027498768236e-01 1.24649099331343e-01 +-1.72727272727273e+01 -9.18897356865547e-01 1.64194842338135e-01 1.06248581428441e-01 +-1.66666666666667e+01 -9.34393729163051e-01 1.54084754485664e-01 8.78685062390541e-02 +-1.60606060606061e+01 -9.50536639664486e-01 1.43764438001973e-01 6.95133639931887e-02 +-1.54545454545455e+01 -9.64734821551149e-01 1.33117373956884e-01 5.21860598369796e-02 +-1.48484848484848e+01 -9.77391904313972e-01 1.22286093821075e-01 3.54343122342188e-02 +-1.42424242424242e+01 -9.85991220935185e-01 1.11183046356548e-01 1.93441677911052e-02 +-1.36363636363636e+01 -9.92508781462450e-01 1.00022677031595e-01 1.86113773658177e-03 +-1.30303030303030e+01 -9.96614484588265e-01 8.88116806333893e-02 -1.56141016371839e-02 +-1.24242424242424e+01 -9.78086134430020e-01 7.52791871427589e-02 -2.49185975754885e-02 +-1.18181818181818e+01 -9.53932069219898e-01 6.20273381259160e-02 -3.17721050900264e-02 +-1.12121212121212e+01 -9.20876137842797e-01 5.07143911844155e-02 -3.39028634816218e-02 +-1.06060606060606e+01 -8.81577109301206e-01 4.14292282661460e-02 -3.79021056900473e-02 +-1.00000000000000e+01 -8.39208813140256e-01 3.31402553113552e-02 -4.29111295394993e-02 +-9.39393939393939e+00 -7.98914426405686e-01 2.63234936305883e-02 -4.78020739246981e-02 +-8.78787878787879e+00 -7.51657176842035e-01 2.00389695291873e-02 -5.40250476091291e-02 +-8.18181818181818e+00 -6.93679577084241e-01 1.48308481680817e-02 -6.34207316233908e-02 +-7.57575757575758e+00 -6.21203231263108e-01 1.23436646598620e-02 -7.09002799417693e-02 +-6.96969696969697e+00 -5.42846056045475e-01 1.08867824056562e-02 -7.76381592574485e-02 +-6.36363636363636e+00 -4.57248717599494e-01 1.00699499146877e-02 -8.51835466097516e-02 +-5.75757575757576e+00 -3.71772773815341e-01 9.34966265890492e-03 -9.22149694821789e-02 +-5.15151515151515e+00 -2.86510321252854e-01 8.93727471505472e-03 -9.83419419547575e-02 +-4.54545454545454e+00 -2.02800521849721e-01 8.69069179286290e-03 -1.03107031002192e-01 +-3.93939393939394e+00 -1.19779247070242e-01 8.48574750992013e-03 -1.07388031434577e-01 +-3.33333333333333e+00 -3.84842209773342e-02 8.25863893989330e-03 -1.11024512192661e-01 +-2.72727272727273e+00 4.24696095161102e-02 8.07912598948857e-03 -1.14232025558283e-01 +-2.12121212121212e+00 1.22655957049352e-01 7.94212397685742e-03 -1.17344637430821e-01 +-1.51515151515152e+00 2.01513656509836e-01 7.86589688092029e-03 -1.19802686323078e-01 +-9.09090909090912e-01 2.79423697181455e-01 7.84144762810594e-03 -1.22095855725919e-01 +-3.03030303030302e-01 3.55313195985403e-01 7.92627146648238e-03 -1.24166876151792e-01 + 3.03030303030302e-01 4.31348608046625e-01 7.96635081424009e-03 -1.26135660486964e-01 + 9.09090909090912e-01 5.07641470964623e-01 7.97255718827600e-03 -1.27871042553699e-01 + 1.51515151515152e+00 5.83948077422797e-01 7.96669925131739e-03 -1.29528648870106e-01 + 2.12121212121212e+00 6.60075851841618e-01 8.13587472418758e-03 -1.31061713680780e-01 + 2.72727272727273e+00 7.35527633751173e-01 8.30297676364884e-03 -1.32516554910940e-01 + 3.33333333333333e+00 8.09980208614822e-01 8.45480310834448e-03 -1.33834053323750e-01 + 3.93939393939394e+00 8.84045273581437e-01 8.60887609936009e-03 -1.34999421375079e-01 + 4.54545454545455e+00 9.57533521208408e-01 8.81210276724078e-03 -1.35895700708834e-01 + 5.15151515151515e+00 1.03035843997482e+00 9.04375918791339e-03 -1.36630117116849e-01 + 5.75757575757576e+00 1.10131375775296e+00 9.33994000860195e-03 -1.36951375051287e-01 + 6.36363636363637e+00 1.16891066608882e+00 9.67833808285477e-03 -1.36757550838472e-01 + 6.96969696969697e+00 1.23465262669807e+00 1.00087887591604e-02 -1.36219258169966e-01 + 7.57575757575757e+00 1.28575742789560e+00 1.07210657691971e-02 -1.33537358220650e-01 + 8.18181818181818e+00 1.32822847132065e+00 1.19390938706417e-02 -1.29971609720980e-01 + 8.78787878787879e+00 1.35408256195699e+00 1.39481484368526e-02 -1.24516098191203e-01 + 9.39393939393939e+00 1.34430353385980e+00 2.27726382829582e-02 -1.22692829271057e-01 + 1.00000000000000e+01 1.31224074007862e+00 3.52534094952587e-02 -1.22656293137505e-01 + 1.06060606060606e+01 1.22701127443843e+00 4.62229873456646e-02 -1.21636756952509e-01 + 1.12121212121212e+01 1.16219562577377e+00 5.50223378711124e-02 -1.18681954879612e-01 + 1.18181818181818e+01 1.13530358391339e+00 5.97915556707085e-02 -1.12985606092307e-01 + 1.24242424242424e+01 1.11600551029910e+00 6.74861674225558e-02 -1.09510733624339e-01 + 1.30303030303030e+01 1.09983288203511e+00 7.64936470016543e-02 -1.06091834625369e-01 + 1.36363636363636e+01 1.10710335628616e+00 8.65013832514091e-02 -1.07592565956690e-01 + 1.42424242424242e+01 1.10938358437695e+00 9.67716403001183e-02 -1.09394660231539e-01 + 1.48484848484848e+01 1.11061811797752e+00 1.07424572874100e-01 -1.11514011821931e-01 + 1.54545454545455e+01 1.11082268580784e+00 1.16571011915171e-01 -1.12131429881359e-01 + 1.60606060606061e+01 1.11033605299743e+00 1.25085168188146e-01 -1.12361290382414e-01 + 1.66666666666667e+01 1.10609925661839e+00 1.32426982839510e-01 -1.11763403041033e-01 + 1.72727272727273e+01 1.10609074419205e+00 1.41309497589980e-01 -1.12196477228094e-01 + 1.78787878787879e+01 1.11168148131629e+00 1.52075109775884e-01 -1.13878511431696e-01 + 1.84848484848485e+01 1.11799563681487e+00 1.64464965699760e-01 -1.17335103628994e-01 + 1.90909090909091e+01 1.12427870883996e+00 1.77094182598103e-01 -1.21133211985493e-01 + 1.96969696969697e+01 1.13008308302165e+00 1.88778817516490e-01 -1.24354909490447e-01 + 2.03030303030303e+01 1.13565448667379e+00 2.01982468205630e-01 -1.28506406560087e-01 + 2.09090909090909e+01 1.14015133774343e+00 2.16705220601696e-01 -1.33414633720588e-01 + 2.15151515151515e+01 1.14287461583876e+00 2.31427972997762e-01 -1.38269729436345e-01 + 2.21212121212121e+01 1.14332576014604e+00 2.45483672070678e-01 -1.43529989407809e-01 + 2.27272727272727e+01 1.13469070715944e+00 2.56871844199725e-01 -1.50406733035442e-01 + 2.33333333333333e+01 1.12605565417285e+00 2.68260016328771e-01 -1.57238953577331e-01 + 2.39393939393939e+01 1.11742060118626e+00 2.79648188457818e-01 -1.63893422540327e-01 + 2.45454545454545e+01 1.10942403333740e+00 2.91203541868066e-01 -1.69656064509149e-01 + 2.51515151515151e+01 1.10149840675555e+00 3.02777470576641e-01 -1.75327968907266e-01 + 2.57575757575758e+01 1.09357278017371e+00 3.14351399285216e-01 -1.81009617670108e-01 + 2.63636363636364e+01 1.08651104880220e+00 3.26312907457723e-01 -1.86249835379891e-01 + 2.69696969696970e+01 1.08002533707003e+00 3.38532842092560e-01 -1.91196015332576e-01 + 2.75757575757576e+01 1.07353962533786e+00 3.50752776727396e-01 -1.96148336213444e-01 + 2.81818181818182e+01 1.06734017933048e+00 3.63148215448951e-01 -2.00947535149472e-01 + 2.87878787878788e+01 1.06180862938348e+00 3.75953128578187e-01 -2.05379818120139e-01 + 2.93939393939394e+01 1.05627707943649e+00 3.88758041707422e-01 -2.09816145110101e-01 + 3.00000000000000e+01 1.05074552948950e+00 4.01562954836658e-01 -2.14256550297368e-01 + 3.30000000000000e+01 1.02672334375004e+00 4.68286734608673e-01 -2.33923275085492e-01 + 3.60000000000000e+01 1.00390363142049e+00 5.37796305675443e-01 -2.52023342292616e-01 + 3.90000000000000e+01 9.80228670131175e-01 6.09930414983374e-01 -2.68877380086188e-01 + 4.20000000000000e+01 9.53334135403550e-01 6.83667545750015e-01 -2.84801740802117e-01 + 4.50000000000000e+01 9.25249734105174e-01 7.57800118621131e-01 -3.00471220322711e-01 + 4.80000000000000e+01 8.90342378222425e-01 8.31789714461067e-01 -3.15332659299714e-01 + 5.10000000000000e+01 8.51395825660653e-01 9.04195569676826e-01 -3.29875873212572e-01 + 5.40000000000000e+01 8.04370620070051e-01 9.73433841829142e-01 -3.43774687106004e-01 + 5.70000000000000e+01 7.57345390210040e-01 1.04267158504194e+00 -3.57676244146600e-01 + 6.00000000000000e+01 7.10320148215417e-01 1.11190906378698e+00 -3.71581147754796e-01 + 6.30000000000000e+01 6.47820663786416e-01 1.16779955248625e+00 -3.84050834181803e-01 + 6.60000000000000e+01 5.85321046718599e-01 1.22368992678063e+00 -3.96521729786065e-01 + 6.90000000000000e+01 5.22821429650782e-01 1.27958030107501e+00 -4.08993794958095e-01 + 7.20000000000000e+01 4.53009361979119e-01 1.32195327919519e+00 -4.20171504341749e-01 + 7.50000000000000e+01 3.79541218701137e-01 1.35756783594738e+00 -4.30701936371378e-01 + 7.80000000000000e+01 3.06071633534284e-01 1.39318280081402e+00 -4.41232525983427e-01 + 8.10000000000000e+01 2.31382797116840e-01 1.42053931469708e+00 -4.50887242301039e-01 + 8.40000000000000e+01 1.54255542363546e-01 1.43137949667301e+00 -4.58789175569348e-01 + 8.70000000000000e+01 7.71276819161773e-02 1.44221976146193e+00 -4.66690861017101e-01 + 9.00000000000000e+01 -3.36965526632122e-07 1.45305993234293e+00 -4.74592503766813e-01 + 9.30000000000000e+01 -5.39897777632595e-02 1.44221975036700e+00 -4.79614013589955e-01 + 9.60000000000000e+01 -1.07979224785424e-01 1.43137952698492e+00 -4.84662548255213e-01 + 9.90000000000000e+01 -1.61968684256675e-01 1.42053922078900e+00 -4.89738716026789e-01 + 1.02000000000000e+02 -2.14250613596524e-01 1.39318262832361e+00 -4.91556612878414e-01 + 1.05000000000000e+02 -2.65678796360800e-01 1.35756807157142e+00 -4.91759948361478e-01 + 1.08000000000000e+02 -3.17106968448641e-01 1.32195310670654e+00 -4.91808185319412e-01 + 1.11000000000000e+02 -3.65975473161876e-01 1.27957981690164e+00 -4.90481329182113e-01 + 1.14000000000000e+02 -4.09724721085945e-01 1.22369008305982e+00 -4.86610622674850e-01 + 1.17000000000000e+02 -4.53474286743658e-01 1.16779992225404e+00 -4.82739400053527e-01 + 1.20000000000000e+02 -4.97223990089781e-01 1.11190952185851e+00 -4.78867879128044e-01 + 1.23000000000000e+02 -5.30141386686949e-01 1.04267204311347e+00 -4.73180864409918e-01 + 1.26000000000000e+02 -5.63058900774808e-01 9.73434299905923e-01 -4.67493542642030e-01 + 1.29000000000000e+02 -5.95976649852831e-01 9.04196027753607e-01 -4.61805698033490e-01 + 1.32000000000000e+02 -6.21647450545520e-01 8.31742453913373e-01 -4.56978785337660e-01 + 1.35000000000000e+02 -6.43694785635686e-01 7.57681233044139e-01 -4.52582281581552e-01 + 1.38000000000000e+02 -6.65741843359713e-01 6.83620285576330e-01 -4.48185737640142e-01 + 1.41000000000000e+02 -6.85948000576951e-01 6.10977986560267e-01 -4.46102392733155e-01 + 1.44000000000000e+02 -7.02472341842677e-01 5.41172995959272e-01 -4.48645505252371e-01 + 1.47000000000000e+02 -7.18996156868714e-01 4.71368155114379e-01 -4.51188446648819e-01 + 1.50000000000000e+02 -7.35519708784299e-01 4.01563389144863e-01 -4.53731249233545e-01 + 1.53000000000000e+02 -7.20041338298566e-01 3.49496494506179e-01 -4.67335818397252e-01 + 1.56000000000000e+02 -7.07403995417188e-01 2.97429648323240e-01 -4.80939257564229e-01 + 1.59000000000000e+02 -6.95102717992735e-01 2.45362816385929e-01 -4.93374572820376e-01 + 1.62000000000000e+02 -6.21487493690614e-01 2.05206612595701e-01 -4.97977180373460e-01 + 1.65000000000000e+02 -5.17905869149982e-01 1.71005823609649e-01 -4.98735700762325e-01 + 1.68000000000000e+02 -4.14324831560763e-01 1.36804826538108e-01 -4.99494277943921e-01 + 1.71000000000000e+02 -3.10743598323177e-01 1.02603707071835e-01 -4.50000513056908e-01 + 1.74000000000000e+02 -2.07161973779746e-01 6.84023428103841e-02 -2.99999717902353e-01 + 1.77000000000000e+02 -1.03108758635925e-01 5.65240009423786e-02 -1.49315896260807e-01 + 1.80000000000000e+02 0.00000000000000e+00 5.58151028351338e-02 0.00000000000000e+00 diff --git a/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_20.dat b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_20.dat new file mode 100644 index 00000000..b86dcd63 --- /dev/null +++ b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_20.dat @@ -0,0 +1,254 @@ +! ------------ AirfoilInfo v1.01.x Input File ---------------------------------- +! AeroElasticSE FAST driver +! line +! line +! ------------------------------------------------------------------------------ +DEFAULT InterpOrd ! Interpolation order to use for quasi-steady table lookup {1=linear; 3=cubic spline; "default"} [default=3] +1 NonDimArea ! The non-dimensional area of the airfoil (area/chord^2) (set to 1.0 if unsure or unneeded) +@"NREL-2p8-127_AF20_Coords.txt" NumCoords ! The number of coordinates in the airfoil shape file. Set to zero if coordinates not included. +AF20_BL.txt BL_file ! The file name including the boundary layer characteristics of the profile. Ignored if the aeroacoustic module is not called. +1 NumTabs ! Number of airfoil tables in this file. Each table must have lines for Re and Ctrl. +! ------------------------------------------------------------------------------ +! data for table 1 +! ------------------------------------------------------------------------------ +6.000000 Re ! Reynolds number in millions +0 Ctrl ! Control setting (must be 0 for current AirfoilInfo) +True InclUAdata ! Is unsteady aerodynamics data included in this table? If TRUE, then include 30 UA coefficients below this line +!........................................ +-3.223506 alpha0 ! 0-lift angle of attack, depends on airfoil. +9.164046 alpha1 ! Angle of attack at f=0.7, (approximately the stall angle) for AOA>alpha0. (deg) +-11.802083 alpha2 ! Angle of attack at f=0.7, (approximately the stall angle) for AOA1] +0.000000 S2 ! Constant in the f curve best-fit for AOA> alpha1; by definition it depends on the airfoil. [ignored if UAMod<>1] +0.000000 S3 ! Constant in the f curve best-fit for alpha2<=AOA< alpha0; by definition it depends on the airfoil. [ignored if UAMod<>1] +0.000000 S4 ! Constant in the f curve best-fit for AOA< alpha2; by definition it depends on the airfoil. [ignored if UAMod<>1] +1.346223 Cn1 ! Critical value of C0n at leading edge separation. It should be extracted from airfoil data at a given Mach and Reynolds number. It can be calculated from the static value of Cn at either the break in the pitching moment or the loss of chord force at the onset of stall. It is close to the condition of maximum lift of the airfoil at low Mach numbers. +-0.953798 Cn2 ! As Cn1 for negative AOAs. +Default St_sh ! Strouhal's shedding frequency constant. [default = 0.19] +0.007766 Cd0 ! 2D drag coefficient value at 0-lift. +-0.112979 Cm0 ! 2D pitching moment coefficient about 1/4-chord location, at 0-lift, positive if nose up. [If the aerodynamics coefficients table does not include a column for Cm, this needs to be set to 0.0] +0.000000 k0 ! Constant in the \hat(x)_cp curve best-fit; = (\hat(x)_AC-0.25). [ignored if UAMod<>1] +0.000000 k1 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k2 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k3 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k1_hat ! Constant in the expression of Cc due to leading edge vortex effects. [ignored if UAMod<>1] +Default x_cp_bar ! Constant in the expression of \hat(x)_cp^v. [ignored if UAMod<>1, default = 0.2] +Default UACutout ! Angle of attack above which unsteady aerodynamics are disabled (deg). [Specifying the string "Default" sets UACutout to 45 degrees] +Default filtCutOff ! Cut-off frequency (-3 dB corner frequency) for low-pass filtering the AoA input to UA, as well as the 1st and 2nd derivatives (Hz) [default = 20] +!........................................ +! Table of aerodynamics coefficients +200 NumAlf ! Number of data lines in the following table +! Alpha Cl Cd Cm +! (deg) (-) (-) (-) +-1.80000000000000e+02 0.00000000000000e+00 5.60839860376548e-02 1.47167178040004e-03 +-1.77000000000000e+02 1.08689836995157e-01 5.60839860376548e-02 1.20045412825477e-01 +-1.74000000000000e+02 2.18375213642741e-01 6.73007199605437e-02 2.39999774321882e-01 +-1.71000000000000e+02 3.27563004817197e-01 1.00951289964885e-01 3.60000410445527e-01 +-1.68000000000000e+02 4.36467171182598e-01 1.34633335777690e-01 3.19169994146170e-01 +-1.65000000000000e+02 5.45229528453792e-01 1.68331119127359e-01 1.97925928770713e-01 +-1.62000000000000e+02 6.53993133012884e-01 2.02028691114530e-01 7.66798765295578e-02 +-1.59000000000000e+02 7.27503940714938e-01 2.42310026594573e-01 -7.27450282376270e-03 +-1.56000000000000e+02 7.31110795820098e-01 2.95758666342963e-01 -1.72902036375927e-02 +-1.53000000000000e+02 7.34319596822270e-01 3.49207314408847e-01 -2.71905033085442e-02 +-1.50000000000000e+02 7.36523173539597e-01 4.02656004658303e-01 -3.53620431597287e-02 +-1.47000000000000e+02 7.19881808024148e-01 4.72422936035072e-01 -1.91283433052972e-02 +-1.44000000000000e+02 7.03240180419886e-01 5.42189935051373e-01 -2.89438151512004e-03 +-1.41000000000000e+02 6.86598028619283e-01 6.11957069351567e-01 1.32352052371265e-02 +-1.38000000000000e+02 6.66302604968628e-01 6.84555659899671e-01 2.92408808365066e-02 +-1.35000000000000e+02 6.44180552804007e-01 7.58569972827814e-01 4.52061276876922e-02 +-1.32000000000000e+02 6.22058248103176e-01 8.32584537348692e-01 6.11744715260335e-02 +-1.29000000000000e+02 5.96320693031764e-01 9.04989003183199e-01 7.72346550841547e-02 +-1.26000000000000e+02 5.63352620077395e-01 9.74173264003827e-01 9.34737950291405e-02 +-1.23000000000000e+02 5.30384796680654e-01 1.04335699334894e+00 1.09713844738546e-01 +-1.20000000000000e+02 4.97417098058063e-01 1.11254045696623e+00 1.25955007125395e-01 +-1.17000000000000e+02 4.53634438299479e-01 1.16837104972410e+00 1.41339031769430e-01 +-1.14000000000000e+02 4.09851924952369e-01 1.22420140310934e+00 1.56723518860802e-01 +-1.11000000000000e+02 3.66069746716654e-01 1.28003132998751e+00 1.72108208755073e-01 +-1.08000000000000e+02 3.17177705557324e-01 1.32234220591584e+00 1.85841350669341e-01 +-1.05000000000000e+02 2.65730694027691e-01 1.35789345342785e+00 1.98749244923706e-01 +-1.02000000000000e+02 2.14283672037506e-01 1.39344429355730e+00 2.11656834470358e-01 +-9.90000000000000e+01 1.61987132519313e-01 1.42073648944996e+00 2.23201790003783e-01 +-9.60000000000000e+01 1.07991521148030e-01 1.43151103914374e+00 2.32020842715942e-01 +-9.30000000000000e+01 5.39959252161754e-02 1.44228550652603e+00 2.40839683380319e-01 +-9.00000000000000e+01 3.37003894400466e-07 1.45305993275333e+00 2.49658549004585e-01 +-8.70000000000000e+01 -5.39958699516678e-02 1.44228551755366e+00 2.54494482776028e-01 +-8.40000000000000e+01 -1.07991672131789e-01 1.43151100901570e+00 2.59343605608854e-01 +-8.10000000000000e+01 -1.61986664762753e-01 1.42073658278841e+00 2.64205569719769e-01 +-7.80000000000000e+01 -2.14283422866425e-01 1.39344446573911e+00 2.65795815265371e-01 +-7.50000000000000e+01 -2.65731034397795e-01 1.35789321822535e+00 2.65755918593268e-01 +-7.20000000000000e+01 -3.17177456391675e-01 1.32234237809590e+00 2.65727119737369e-01 +-6.90000000000000e+01 -3.66069367431166e-01 1.28003181364278e+00 2.64438345067420e-01 +-6.60000000000000e+01 -4.09852047376346e-01 1.22420124699738e+00 2.60617266085316e-01 +-6.30000000000000e+01 -4.53634727963402e-01 1.16837068035199e+00 2.56805932797703e-01 +-6.00000000000000e+01 -4.97417316170630e-01 1.11253999925206e+00 2.53004344403069e-01 +-5.70000000000000e+01 -5.30385014793222e-01 1.04335653563477e+00 2.47400711870632e-01 +-5.40000000000000e+01 -5.63352838192439e-01 9.74172806284381e-01 2.41806514160262e-01 +-5.10000000000000e+01 -5.96320911146808e-01 9.04988545463753e-01 2.36221437763850e-01 +-4.80000000000000e+01 -6.23645028218618e-01 8.32633137744547e-01 2.30956513607567e-01 +-4.50000000000000e+01 -6.48147258055512e-01 7.58692207540872e-01 2.25857970172168e-01 +-4.20000000000000e+01 -6.67889372666217e-01 6.84604259911055e-01 2.22474982226598e-01 +-3.90000000000000e+01 -6.86802709568193e-01 6.10910749328229e-01 2.19736387390917e-01 +-3.60000000000000e+01 -7.03478405910380e-01 5.38816968440485e-01 2.19280528126823e-01 +-3.30000000000000e+01 -7.19572395319055e-01 4.69344655336830e-01 2.22204576432948e-01 +-3.00000000000000e+01 -7.36523295159899e-01 4.02655570575433e-01 2.28913832317185e-01 +-2.93939393939394e+01 -7.40428301639941e-01 3.89857123435579e-01 2.31295215800378e-01 +-2.87878787878788e+01 -7.44333308119982e-01 3.77058676295725e-01 2.33676599283572e-01 +-2.81818181818182e+01 -7.48238314600024e-01 3.64260229155871e-01 2.36057982766765e-01 +-2.75757575757576e+01 -7.52613641879506e-01 3.51870974153269e-01 2.39172506623836e-01 +-2.69696969696970e+01 -7.57190552507842e-01 3.39657102253967e-01 2.42601260453133e-01 +-2.63636363636364e+01 -7.61767463136177e-01 3.27443230354664e-01 2.46030014282430e-01 +-2.57575757575758e+01 -7.66749761722573e-01 3.15487613973748e-01 2.50008630333910e-01 +-2.51515151515151e+01 -7.72340047765258e-01 3.03919320680690e-01 2.54811911566304e-01 +-2.45454545454545e+01 -7.77930333807944e-01 2.92351027387632e-01 2.59615192798699e-01 +-2.39393939393939e+01 -7.83831337974498e-01 2.80845692169765e-01 2.63368296589326e-01 +-2.33333333333333e+01 -7.92528865412384e-01 2.69906991817601e-01 2.57669600084677e-01 +-2.27272727272727e+01 -8.01226392850269e-01 2.58968291465437e-01 2.51477123925418e-01 +-2.21212121212121e+01 -8.09923920288154e-01 2.48029591113273e-01 2.45907124300863e-01 +-2.15151515151515e+01 -8.20235783478513e-01 2.37173728120076e-01 2.31168860674295e-01 +-2.09090909090909e+01 -8.29622622700524e-01 2.26338579795089e-01 2.13713746850245e-01 +-2.03030303030303e+01 -8.39213259378848e-01 2.15503431470102e-01 1.96258633026194e-01 +-1.96969696969697e+01 -8.49342921178197e-01 2.04670828846016e-01 1.78811743339257e-01 +-1.90909090909091e+01 -8.59723555494070e-01 1.93840771778819e-01 1.61373077324190e-01 +-1.84848484848485e+01 -8.69355568885329e-01 1.82817117288920e-01 1.43848790063230e-01 +-1.78787878787879e+01 -8.78841519111643e-01 1.71507191312464e-01 1.26522966331281e-01 +-1.72727272727273e+01 -8.88304094365764e-01 1.60344653968440e-01 1.09264562513686e-01 +-1.66666666666667e+01 -8.97226846531499e-01 1.49299202250655e-01 9.19320215375475e-02 +-1.60606060606061e+01 -9.05768732409721e-01 1.38352219033920e-01 7.45346221583764e-02 +-1.54545454545455e+01 -9.14769264432095e-01 1.27532003288276e-01 5.67050762225817e-02 +-1.48484848484848e+01 -9.24224518221895e-01 1.16781059230677e-01 3.86315588318540e-02 +-1.42424242424242e+01 -9.34933174803990e-01 1.06107627638312e-01 2.02903974043766e-02 +-1.36363636363636e+01 -9.46580047643885e-01 9.54549647670512e-02 2.58155653624406e-03 +-1.30303030303030e+01 -9.59376519315215e-01 8.48210475936575e-02 -1.51277660357559e-02 +-1.24242424242424e+01 -9.49137204600254e-01 7.23014208476810e-02 -2.45207730999593e-02 +-1.18181818181818e+01 -9.33511315858133e-01 6.03072372984705e-02 -3.14401400294280e-02 +-1.12121212121212e+01 -9.07412559417457e-01 4.91969779770790e-02 -3.36076468476470e-02 +-1.06060606060606e+01 -8.74358654564795e-01 3.98750651939524e-02 -3.77019772884650e-02 +-1.00000000000000e+01 -8.37436227745362e-01 3.15713217351823e-02 -4.28344259088231e-02 +-9.39393939393939e+00 -7.97360016762257e-01 2.49748326421447e-02 -4.78167321636766e-02 +-8.78787878787879e+00 -7.46918091090845e-01 1.90106766562991e-02 -5.49142422548264e-02 +-8.18181818181818e+00 -6.76385235190348e-01 1.41430349552736e-02 -6.55740988464556e-02 +-7.57575757575758e+00 -5.97548773054335e-01 1.16500159105889e-02 -7.40578404001251e-02 +-6.96969696969697e+00 -5.14687150181851e-01 1.02794635432385e-02 -8.15694642369420e-02 +-6.36363636363636e+00 -4.29783331561822e-01 9.37100611916169e-03 -8.89972589526919e-02 +-5.75757575757576e+00 -3.44985681028980e-01 8.72254512466363e-03 -9.56743162334849e-02 +-5.15151515151515e+00 -2.60342088083212e-01 8.36628808560654e-03 -1.01294050980689e-01 +-4.54545454545454e+00 -1.77283987129221e-01 8.15049198443473e-03 -1.05574157964945e-01 +-3.93939393939394e+00 -9.49967516754283e-02 7.98399273984275e-03 -1.09327817332233e-01 +-3.33333333333333e+00 -1.45488178579448e-02 7.79517199106549e-03 -1.12477093218156e-01 +-2.72727272727273e+00 6.57363122021591e-02 7.63446498473685e-03 -1.15244192981836e-01 +-2.12121212121212e+00 1.45332789615814e-01 7.51105279420149e-03 -1.17982678474176e-01 +-1.51515151515152e+00 2.23672723468766e-01 7.44827862315605e-03 -1.20431702659156e-01 +-9.09090909090912e-01 3.00978847690010e-01 7.43157561421629e-03 -1.22712093550068e-01 +-3.03030303030302e-01 3.76098908531403e-01 7.51006367733051e-03 -1.24767379670863e-01 + 3.03030303030302e-01 4.51444826699281e-01 7.54938811200737e-03 -1.26721030186769e-01 + 9.09090909090912e-01 5.27096787476172e-01 7.54812362715996e-03 -1.28437544066459e-01 + 1.51515151515152e+00 6.02777798759360e-01 7.55798597733358e-03 -1.30082417308287e-01 + 2.12121212121212e+00 6.78328119290960e-01 7.71509624311103e-03 -1.31599798151816e-01 + 2.72727272727273e+00 7.53369580256120e-01 7.87416012848208e-03 -1.33039382183475e-01 + 3.33333333333333e+00 8.27436011075852e-01 8.02072404030208e-03 -1.34343039337526e-01 + 3.93939393939394e+00 9.01064324481151e-01 8.17634754573474e-03 -1.35496483033582e-01 + 4.54545454545455e+00 9.74097640300264e-01 8.37626659639857e-03 -1.36379157527485e-01 + 5.15151515151515e+00 1.04648944718360e+00 8.60497543451105e-03 -1.37098870871982e-01 + 5.75757575757576e+00 1.11709742972339e+00 8.90798254151872e-03 -1.37401161602970e-01 + 6.36363636363637e+00 1.18428988344244e+00 9.27589711393541e-03 -1.37179374672226e-01 + 6.96969696969697e+00 1.24896889274954e+00 9.70884746672005e-03 -1.36604163101376e-01 + 7.57575757575757e+00 1.29881944271375e+00 1.06632766664296e-02 -1.33835538319740e-01 + 8.18181818181818e+00 1.33958725078695e+00 1.19126582890210e-02 -1.30168176642310e-01 + 8.78787878787879e+00 1.36005346559897e+00 1.39779508814557e-02 -1.24720046583824e-01 + 9.39393939393939e+00 1.34301374720075e+00 2.30914396203260e-02 -1.22744826084420e-01 + 1.00000000000000e+01 1.30753093113672e+00 3.60092777128439e-02 -1.22742898670035e-01 + 1.06060606060606e+01 1.21740138674990e+00 4.73489216901772e-02 -1.21777727655646e-01 + 1.12121212121212e+01 1.14876626618267e+00 5.64290043026546e-02 -1.19509336453563e-01 + 1.18181818181818e+01 1.12008684609046e+00 6.13613926416215e-02 -1.14351014023090e-01 + 1.24242424242424e+01 1.10641679635825e+00 6.86990657706108e-02 -1.09572759572039e-01 + 1.30303030303030e+01 1.10001146588234e+00 7.71321227342433e-02 -1.05827721623316e-01 + 1.36363636363636e+01 1.10899885123525e+00 8.72204117979317e-02 -1.07475148520177e-01 + 1.42424242424242e+01 1.12008882355609e+00 9.75650647021123e-02 -1.09425019423431e-01 + 1.48484848484848e+01 1.13075597639677e+00 1.08294194106513e-01 -1.11906001460801e-01 + 1.54545454545455e+01 1.13516931068150e+00 1.17464255427677e-01 -1.13115892870182e-01 + 1.60606060606061e+01 1.13676837338324e+00 1.25978158509963e-01 -1.13656640925689e-01 + 1.66666666666667e+01 1.13211072570407e+00 1.33262514337462e-01 -1.12840862880448e-01 + 1.72727272727273e+01 1.13058655438625e+00 1.42129358900706e-01 -1.13195774561728e-01 + 1.78787878787879e+01 1.13267144501086e+00 1.52930376429612e-01 -1.14987235036101e-01 + 1.84848484848485e+01 1.13534488348534e+00 1.65326800303123e-01 -1.18507779175190e-01 + 1.90909090909091e+01 1.13808110384824e+00 1.77947867911582e-01 -1.22278286215279e-01 + 1.96969696969697e+01 1.13996942404966e+00 1.89581788465173e-01 -1.25014693335627e-01 + 2.03030303030303e+01 1.14136257005177e+00 2.02809939468738e-01 -1.28759059263829e-01 + 2.09090909090909e+01 1.14278916134738e+00 2.17632411113615e-01 -1.33592215797638e-01 + 2.15151515151515e+01 1.14520088380394e+00 2.32454882758493e-01 -1.38449866850649e-01 + 2.21212121212121e+01 1.14534623034980e+00 2.46593134049512e-01 -1.43713984431992e-01 + 2.27272727272727e+01 1.13669195126191e+00 2.57995207937436e-01 -1.50603549902548e-01 + 2.33333333333333e+01 1.12803767217403e+00 2.69397281825361e-01 -1.57514015684770e-01 + 2.39393939393939e+01 1.11938339308615e+00 2.80799355713285e-01 -1.64504480543572e-01 + 2.45454545454545e+01 1.11133045136127e+00 2.92351027387632e-01 -1.70538137552357e-01 + 2.51515151515151e+01 1.10334432346167e+00 3.03919320680690e-01 -1.76461209319149e-01 + 2.57575757575758e+01 1.09535819556207e+00 3.15487613973748e-01 -1.82379292873812e-01 + 2.63636363636364e+01 1.08824062881607e+00 3.27443230354664e-01 -1.87812657912168e-01 + 2.69696969696970e+01 1.08170219282164e+00 3.39657102253967e-01 -1.92922675867797e-01 + 2.75757575757576e+01 1.07516375682721e+00 3.51870974153269e-01 -1.98029550237023e-01 + 2.81818181818182e+01 1.06891342259585e+00 3.64260229155871e-01 -2.02965263331226e-01 + 2.87878787878788e+01 1.06333526814667e+00 3.77058676295725e-01 -2.07506580463469e-01 + 2.93939393939394e+01 1.05775711369748e+00 3.89857123435579e-01 -2.12045827432426e-01 + 3.00000000000000e+01 1.05217895924830e+00 4.02655570575433e-01 -2.16582986742122e-01 + 3.30000000000000e+01 1.02795917310136e+00 4.69344655336830e-01 -2.36555351110227e-01 + 3.60000000000000e+01 1.00496772750934e+00 5.38816968440485e-01 -2.54825361123685e-01 + 3.90000000000000e+01 9.81146869188920e-01 6.10910749328229e-01 -2.71702784264139e-01 + 4.20000000000000e+01 9.54127928885481e-01 6.84604259911056e-01 -2.87623690411183e-01 + 4.50000000000000e+01 9.25925507989752e-01 7.58692207540872e-01 -3.03272921560484e-01 + 4.80000000000000e+01 8.90921980696787e-01 8.32633137744547e-01 -3.18102995823141e-01 + 5.10000000000000e+01 8.51887356225999e-01 9.04988545463753e-01 -3.32607858873096e-01 + 5.40000000000000e+01 8.04790278249480e-01 9.74172806284381e-01 -3.46467861120541e-01 + 5.70000000000000e+01 7.57693159426409e-01 1.04335653563477e+00 -3.60325018324970e-01 + 6.00000000000000e+01 7.10596020180217e-01 1.11253999925206e+00 -3.74179542354393e-01 + 6.30000000000000e+01 6.48049471053151e-01 1.16837068035199e+00 -3.86611182558364e-01 + 6.60000000000000e+01 5.85502788028442e-01 1.22420124699738e+00 -3.99041445615547e-01 + 6.90000000000000e+01 5.22956102060375e-01 1.28003181364278e+00 -4.11470147230388e-01 + 7.20000000000000e+01 4.53110398690217e-01 1.32234237809590e+00 -4.22612100063294e-01 + 7.50000000000000e+01 3.79615336039622e-01 1.35789321822535e+00 -4.33110599511480e-01 + 7.80000000000000e+01 3.06118835606714e-01 1.39344446573911e+00 -4.43608014083683e-01 + 8.10000000000000e+01 2.31409126413095e-01 1.42073658278841e+00 -4.53232613764225e-01 + 8.40000000000000e+01 1.54273083446276e-01 1.43151100901570e+00 -4.61112452060330e-01 + 8.70000000000000e+01 7.71364489011903e-02 1.44228551755366e+00 -4.68991671868026e-01 + 9.00000000000000e+01 -3.37003894630567e-07 1.45305993275333e+00 -4.76870426093284e-01 + 9.30000000000000e+01 -5.39959252161754e-02 1.44228550652603e+00 -4.81692680238558e-01 + 9.60000000000000e+01 -1.07991521148031e-01 1.43151103914374e+00 -4.86490823116468e-01 + 9.90000000000000e+01 -1.61987132519313e-01 1.42073648944996e+00 -4.91273974428200e-01 + 1.02000000000000e+02 -2.14283672037506e-01 1.39344429355730e+00 -4.92759271498875e-01 + 1.05000000000000e+02 -2.65730694027692e-01 1.35789345342785e+00 -4.92588207197183e-01 + 1.08000000000000e+02 -3.17177705557324e-01 1.32234220591584e+00 -4.92507133962652e-01 + 1.11000000000000e+02 -3.66069746716655e-01 1.28003132998751e+00 -4.91213114955779e-01 + 1.14000000000000e+02 -4.09851924952369e-01 1.22420140310934e+00 -4.87375141860954e-01 + 1.17000000000000e+02 -4.53634438299479e-01 1.16837104972410e+00 -4.83536739448328e-01 + 1.20000000000000e+02 -4.97417098058063e-01 1.11254045696623e+00 -4.79698118822128e-01 + 1.23000000000000e+02 -5.30384796680655e-01 1.04335699334894e+00 -4.74045178392828e-01 + 1.26000000000000e+02 -5.63352620077395e-01 9.74173264003827e-01 -4.68392016442808e-01 + 1.29000000000000e+02 -5.96320693031764e-01 9.04989003183198e-01 -4.62734898551017e-01 + 1.32000000000000e+02 -6.22058248103176e-01 8.32584537348691e-01 -4.57940896727791e-01 + 1.35000000000000e+02 -6.44180552804007e-01 7.58569972827814e-01 -4.53579623270348e-01 + 1.38000000000000e+02 -6.66302604968628e-01 6.84555659899671e-01 -4.49218395373695e-01 + 1.41000000000000e+02 -6.86598028619283e-01 6.11957069351566e-01 -4.47177800534488e-01 + 1.44000000000000e+02 -7.03240180419886e-01 5.42189935051373e-01 -4.49778490640875e-01 + 1.47000000000000e+02 -7.19881808024148e-01 4.72422936035072e-01 -4.52379161521216e-01 + 1.50000000000000e+02 -7.36523173539597e-01 4.02656004658303e-01 -4.54979822788877e-01 + 1.53000000000000e+02 -7.23995989268374e-01 3.50606387738054e-01 -4.68570401665813e-01 + 1.56000000000000e+02 -7.10014434000594e-01 2.98556810596401e-01 -4.82106047676863e-01 + 1.59000000000000e+02 -6.95822993804938e-01 2.46507230442391e-01 -4.96319099842072e-01 + 1.62000000000000e+02 -6.22266685072149e-01 2.06230353085240e-01 -5.00873829028078e-01 + 1.65000000000000e+02 -5.18715046462665e-01 1.71839926690689e-01 -5.00546173646419e-01 + 1.68000000000000e+02 -4.15163994460962e-01 1.37449294383709e-01 -5.00218470478517e-01 + 1.71000000000000e+02 -3.11516836116274e-01 1.03069943092153e-01 -4.50000513056908e-01 + 1.74000000000000e+02 -2.07677460598702e-01 6.87131543581221e-02 -2.99999717902353e-01 + 1.77000000000000e+02 -1.03365251644600e-01 5.67869836313884e-02 -1.48723200443975e-01 + 1.80000000000000e+02 0.00000000000000e+00 5.60839860376548e-02 1.47167178040004e-03 diff --git a/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_21.dat b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_21.dat new file mode 100644 index 00000000..b3de07d8 --- /dev/null +++ b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_21.dat @@ -0,0 +1,254 @@ +! ------------ AirfoilInfo v1.01.x Input File ---------------------------------- +! AeroElasticSE FAST driver +! line +! line +! ------------------------------------------------------------------------------ +DEFAULT InterpOrd ! Interpolation order to use for quasi-steady table lookup {1=linear; 3=cubic spline; "default"} [default=3] +1 NonDimArea ! The non-dimensional area of the airfoil (area/chord^2) (set to 1.0 if unsure or unneeded) +@"NREL-2p8-127_AF21_Coords.txt" NumCoords ! The number of coordinates in the airfoil shape file. Set to zero if coordinates not included. +AF21_BL.txt BL_file ! The file name including the boundary layer characteristics of the profile. Ignored if the aeroacoustic module is not called. +1 NumTabs ! Number of airfoil tables in this file. Each table must have lines for Re and Ctrl. +! ------------------------------------------------------------------------------ +! data for table 1 +! ------------------------------------------------------------------------------ +6.000000 Re ! Reynolds number in millions +0 Ctrl ! Control setting (must be 0 for current AirfoilInfo) +True InclUAdata ! Is unsteady aerodynamics data included in this table? If TRUE, then include 30 UA coefficients below this line +!........................................ +-3.391748 alpha0 ! 0-lift angle of attack, depends on airfoil. +9.217593 alpha1 ! Angle of attack at f=0.7, (approximately the stall angle) for AOA>alpha0. (deg) +-11.634112 alpha2 ! Angle of attack at f=0.7, (approximately the stall angle) for AOA1] +0.000000 S2 ! Constant in the f curve best-fit for AOA> alpha1; by definition it depends on the airfoil. [ignored if UAMod<>1] +0.000000 S3 ! Constant in the f curve best-fit for alpha2<=AOA< alpha0; by definition it depends on the airfoil. [ignored if UAMod<>1] +0.000000 S4 ! Constant in the f curve best-fit for AOA< alpha2; by definition it depends on the airfoil. [ignored if UAMod<>1] +1.356958 Cn1 ! Critical value of C0n at leading edge separation. It should be extracted from airfoil data at a given Mach and Reynolds number. It can be calculated from the static value of Cn at either the break in the pitching moment or the loss of chord force at the onset of stall. It is close to the condition of maximum lift of the airfoil at low Mach numbers. +-0.907795 Cn2 ! As Cn1 for negative AOAs. +Default St_sh ! Strouhal's shedding frequency constant. [default = 0.19] +0.007422 Cd0 ! 2D drag coefficient value at 0-lift. +-0.113062 Cm0 ! 2D pitching moment coefficient about 1/4-chord location, at 0-lift, positive if nose up. [If the aerodynamics coefficients table does not include a column for Cm, this needs to be set to 0.0] +0.000000 k0 ! Constant in the \hat(x)_cp curve best-fit; = (\hat(x)_AC-0.25). [ignored if UAMod<>1] +0.000000 k1 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k2 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k3 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k1_hat ! Constant in the expression of Cc due to leading edge vortex effects. [ignored if UAMod<>1] +Default x_cp_bar ! Constant in the expression of \hat(x)_cp^v. [ignored if UAMod<>1, default = 0.2] +Default UACutout ! Angle of attack above which unsteady aerodynamics are disabled (deg). [Specifying the string "Default" sets UACutout to 45 degrees] +Default filtCutOff ! Cut-off frequency (-3 dB corner frequency) for low-pass filtering the AoA input to UA, as well as the 1st and 2nd derivatives (Hz) [default = 20] +!........................................ +! Table of aerodynamics coefficients +200 NumAlf ! Number of data lines in the following table +! Alpha Cl Cd Cm +! (deg) (-) (-) (-) +-1.80000000000000e+02 0.00000000000000e+00 5.43028798119170e-02 2.26615932282131e-02 +-1.77000000000000e+02 1.13025106629939e-01 5.43028798119170e-02 1.28579365822585e-01 +-1.74000000000000e+02 2.27085486936604e-01 6.51633944994418e-02 2.39999774321882e-01 +-1.71000000000000e+02 3.40628485406802e-01 9.77452951033210e-02 3.60000410445527e-01 +-1.68000000000000e+02 4.49810292581463e-01 1.30815585114068e-01 3.17166481479515e-01 +-1.65000000000000e+02 5.56811555009885e-01 1.64130064128025e-01 1.92917170488019e-01 +-1.62000000000000e+02 6.63814055955440e-01 1.97444368137118e-01 6.86658789432206e-02 +-1.59000000000000e+02 7.35163378078923e-01 2.37618358711485e-01 -1.63189555213320e-02 +-1.56000000000000e+02 7.36658480852925e-01 2.91511490364540e-01 -2.43269386035842e-02 +-1.53000000000000e+02 7.37191671747579e-01 3.45404633730741e-01 -3.20559725750530e-02 +-1.50000000000000e+02 7.35295872691298e-01 3.99297820213560e-01 -3.53001565756154e-02 +-1.47000000000000e+02 7.18798588287585e-01 4.69181021715765e-01 -1.90934045495720e-02 +-1.44000000000000e+02 7.02301063534926e-01 5.39064308687913e-01 -2.88639524111870e-03 +-1.41000000000000e+02 6.85803058067216e-01 6.08947766606052e-01 1.29498269612823e-02 +-1.38000000000000e+02 6.65616813110053e-01 6.81680698854136e-01 2.86882702662571e-02 +-1.35000000000000e+02 6.43586455890160e-01 7.55838362486724e-01 4.44546354620422e-02 +-1.32000000000000e+02 6.21555858594649e-01 8.29996331514374e-01 6.02291708250731e-02 +-1.29000000000000e+02 5.95899961956707e-01 9.02551799836887e-01 7.61226856194456e-02 +-1.26000000000000e+02 5.62993449444218e-01 9.71902259143020e-01 9.22427459258282e-02 +-1.23000000000000e+02 5.30087151245601e-01 1.04125214332386e+00 1.08365878635908e-01 +-1.20000000000000e+02 4.97180960199916e-01 1.11060173995280e+00 1.24492137036960e-01 +-1.17000000000000e+02 4.53438556744641e-01 1.16661616454686e+00 1.39794623246837e-01 +-1.14000000000000e+02 4.09696303308865e-01 1.22263034910072e+00 1.55098596191987e-01 +-1.11000000000000e+02 3.65954392283428e-01 1.27864410574316e+00 1.70403792833604e-01 +-1.08000000000000e+02 3.17091142370324e-01 1.32114669115373e+00 1.84082975431326e-01 +-1.05000000000000e+02 2.65667184017510e-01 1.35689358806697e+00 1.96954679095920e-01 +-1.02000000000000e+02 2.14243214939976e-01 1.39264007535569e+00 2.09826696172051e-01 +-9.90000000000000e+01 1.61964542361192e-01 1.42013008159586e+00 2.21340640675138e-01 +-9.60000000000000e+01 1.07976425758201e-01 1.43110676810732e+00 2.30136989903572e-01 +-9.30000000000000e+01 5.39883669172201e-02 1.44208337076307e+00 2.38933482205731e-01 +-9.00000000000000e+01 3.36956720911094e-07 1.45305993149174e+00 2.47730362549832e-01 +-8.70000000000000e+01 -5.39883116604485e-02 1.44208338199759e+00 2.52366652228794e-01 +-8.40000000000000e+01 -1.07976576721003e-01 1.43110673741406e+00 2.57034873165347e-01 +-8.10000000000000e+01 -1.61964074669558e-01 1.42013017668539e+00 2.61734177795205e-01 +-7.80000000000000e+01 -2.14242965880546e-01 1.39264024848507e+00 2.63181349488851e-01 +-7.50000000000000e+01 -2.65667524235096e-01 1.35689335157008e+00 2.63016349820918e-01 +-7.20000000000000e+01 -3.17090893316325e-01 1.32114686428136e+00 2.62879007650853e-01 +-6.90000000000000e+01 -3.65954013346774e-01 1.27864459099094e+00 2.61500645209288e-01 +-6.60000000000000e+01 -4.09696425620247e-01 1.22263019247474e+00 2.57610540723508e-01 +-6.30000000000000e+01 -4.53438846142231e-01 1.16661579395854e+00 2.53744590647427e-01 +-6.00000000000000e+01 -4.97181177905552e-01 1.11060128113950e+00 2.49902512739027e-01 +-5.70000000000000e+01 -5.30087368951238e-01 1.04125168451056e+00 2.44282377435672e-01 +-5.40000000000000e+01 -5.62993667151980e-01 9.71901800324015e-01 2.38685350754697e-01 +-5.10000000000000e+01 -5.95900179664471e-01 9.02551341017881e-01 2.33110985323929e-01 +-4.80000000000000e+01 -6.23148878462794e-01 8.30040803802850e-01 2.27879411582758e-01 +-4.50000000000000e+01 -6.47568761333111e-01 7.55950278420295e-01 2.22834475134647e-01 +-4.20000000000000e+01 -6.67209820511491e-01 6.81725170790388e-01 2.19541528712913e-01 +-3.90000000000000e+01 -6.86016653934843e-01 6.07897658893372e-01 2.16860523607545e-01 +-3.60000000000000e+01 -7.02567434351865e-01 5.35679831809432e-01 2.16283272016665e-01 +-3.30000000000000e+01 -7.18514395643352e-01 4.66093046844495e-01 2.19061994245276e-01 +-3.00000000000000e+01 -7.35295993131416e-01 3.99297385438155e-01 2.25596659795295e-01 +-2.93939393939394e+01 -7.39161194393161e-01 3.86479064937486e-01 2.27934329427074e-01 +-2.87878787878788e+01 -7.43026395654906e-01 3.73660744436817e-01 2.30271999058854e-01 +-2.81818181818182e+01 -7.46891596916650e-01 3.60842423936148e-01 2.32609668690633e-01 +-2.75757575757576e+01 -7.51223361563041e-01 3.48434171659383e-01 2.35674061206088e-01 +-2.69696969696970e+01 -7.55755099099513e-01 3.36201677983836e-01 2.39049933104880e-01 +-2.63636363636364e+01 -7.60286836635986e-01 3.23969184308288e-01 2.42425805003671e-01 +-2.57575757575758e+01 -7.65221306359447e-01 3.11995455491433e-01 2.46346530788199e-01 +-2.51515151515151e+01 -7.70759780501553e-01 3.00409813654186e-01 2.51084410416232e-01 +-2.45454545454545e+01 -7.76298254643659e-01 2.88824171816938e-01 2.55822290044264e-01 +-2.39393939393939e+01 -7.82132311059061e-01 2.77302256598583e-01 2.59616206109365e-01 +-2.33333333333333e+01 -7.90626665160274e-01 2.66353893288030e-01 2.54914267352217e-01 +-2.27272727272727e+01 -7.99121019261486e-01 2.55405529977478e-01 2.49019152637843e-01 +-2.21212121212121e+01 -8.07615373362699e-01 2.44457166666925e-01 2.44656741536136e-01 +-2.15151515151515e+01 -8.17117669056492e-01 2.33552006854907e-01 2.32819418554197e-01 +-2.09090909090909e+01 -8.23661297618886e-01 2.22657650696563e-01 2.18130675248769e-01 +-2.03030303030303e+01 -8.30697385161204e-01 2.11763294538219e-01 2.03441931943341e-01 +-1.96969696969697e+01 -8.39130226130645e-01 2.00903773822104e-01 1.88879827702874e-01 +-1.90909090909091e+01 -8.48263760915409e-01 1.90079086577562e-01 1.74444355363349e-01 +-1.84848484848485e+01 -8.54491663822831e-01 1.78820853261852e-01 1.58678068289752e-01 +-1.78787878787879e+01 -8.60163856305434e-01 1.66900896684023e-01 1.43105400370003e-01 +-1.72727272727273e+01 -8.65742368749698e-01 1.55433036053471e-01 1.27344882544298e-01 +-1.66666666666667e+01 -8.69217768752512e-01 1.44247604332767e-01 1.10578705840612e-01 +-1.60606060606061e+01 -8.71119382404463e-01 1.33299705468418e-01 9.29795736467647e-02 +-1.54545454545455e+01 -8.74590802382996e-01 1.22693011692481e-01 7.42553100122313e-02 +-1.48484848484848e+01 -8.79448011540517e-01 1.12275192353923e-01 5.48980138044471e-02 +-1.42424242424242e+01 -8.88041287646387e-01 1.02097518094139e-01 3.47904219734257e-02 +-1.36363636363636e+01 -8.99011386472906e-01 9.19774216439529e-02 1.62310520565996e-02 +-1.30303030303030e+01 -9.12832326690409e-01 8.19089384860160e-02 -2.31248158698626e-03 +-1.24242424242424e+01 -9.05837733998151e-01 7.05955147275284e-02 -1.32519999298020e-02 +-1.18181818181818e+01 -8.94149738372733e-01 6.00304976315857e-02 -2.19483169052786e-02 +-1.12121212121212e+01 -8.72289143999857e-01 4.92518839816106e-02 -2.63426664394142e-02 +-1.06060606060606e+01 -8.43836935503105e-01 3.99601622843484e-02 -3.25182305032108e-02 +-1.00000000000000e+01 -8.11533667684698e-01 3.16634689071838e-02 -3.96531690559947e-02 +-9.39393939393939e+00 -7.73775299793918e-01 2.50351497976403e-02 -4.66232350387770e-02 +-8.78787878787879e+00 -7.24386153510650e-01 1.90363399048990e-02 -5.58158243641951e-02 +-8.18181818181818e+00 -6.51350581746786e-01 1.39307768873385e-02 -6.82565719779272e-02 +-7.57575757575758e+00 -5.70259292800422e-01 1.11966451026731e-02 -7.78318201646995e-02 +-6.96969696969697e+00 -4.84863483201162e-01 9.80210985000549e-03 -8.59002125918137e-02 +-6.36363636363636e+00 -4.01260274507495e-01 8.79364513160939e-03 -9.27920938216900e-02 +-5.75757575757576e+00 -3.17829037962407e-01 8.21072836680058e-03 -9.88413955927494e-02 +-5.15151515151515e+00 -2.34560631356565e-01 7.89417831655769e-03 -1.03830189790787e-01 +-4.54545454545454e+00 -1.52768219821946e-01 7.69629272463115e-03 -1.07609067491263e-01 +-3.93939393939394e+00 -7.17446885276158e-02 7.55980850277901e-03 -1.10714124632562e-01 +-3.33333333333333e+00 7.65266106535894e-03 7.40740590680152e-03 -1.13312526310592e-01 +-2.72727272727273e+00 8.69540435134952e-02 7.26852935125166e-03 -1.15619076304701e-01 +-2.12121212121212e+00 1.65602650506344e-01 7.16999070079818e-03 -1.17974728073125e-01 +-1.51515151515152e+00 2.43153008832856e-01 7.12240036540634e-03 -1.20398358450422e-01 +-9.09090909090912e-01 3.19690083645440e-01 7.11221121992558e-03 -1.22659469489510e-01 +-3.03030303030302e-01 3.94185583692908e-01 7.18341302084739e-03 -1.24698324985504e-01 + 3.03030303030302e-01 4.68902411410735e-01 7.22469085552886e-03 -1.26637855769298e-01 + 9.09090909090912e-01 5.43881635947123e-01 7.21999237311871e-03 -1.28343787287290e-01 + 1.51515151515152e+00 6.18852988644897e-01 7.24722163406657e-03 -1.29976534377553e-01 + 2.12121212121212e+00 6.93718405482782e-01 7.38406188230317e-03 -1.31468930098195e-01 + 2.72727272727273e+00 7.68149611769229e-01 7.53516389223080e-03 -1.32869142821252e-01 + 3.33333333333333e+00 8.41715172859199e-01 7.67641621971856e-03 -1.34133903242727e-01 + 3.93939393939394e+00 9.14829634658937e-01 7.82676312299375e-03 -1.35268602227928e-01 + 4.54545454545455e+00 9.87354918951398e-01 8.01392970071129e-03 -1.36139906970678e-01 + 5.15151515151515e+00 1.05927746446687e+00 8.23073134973320e-03 -1.36861989320736e-01 + 5.75757575757576e+00 1.12953343156332e+00 8.53450625263956e-03 -1.37191762867414e-01 + 6.36363636363637e+00 1.19646607280768e+00 8.93008691845142e-03 -1.37002644214539e-01 + 6.96969696969697e+00 1.26024731016983e+00 9.47027625942907e-03 -1.36418678279720e-01 + 7.57575757575757e+00 1.30971003050197e+00 1.06647324108263e-02 -1.33671247589578e-01 + 8.18181818181818e+00 1.35040217332210e+00 1.19527461931973e-02 -1.30058175517731e-01 + 8.78787878787879e+00 1.37091316495312e+00 1.39974785904022e-02 -1.24857926363025e-01 + 9.39393939393939e+00 1.35667712683307e+00 2.24354236046123e-02 -1.22733114545900e-01 + 1.00000000000000e+01 1.32700007053080e+00 3.43303944973221e-02 -1.22710273741457e-01 + 1.06060606060606e+01 1.24713203043916e+00 4.48348853319247e-02 -1.21775958563809e-01 + 1.12121212121212e+01 1.18632667549810e+00 5.33280007969130e-02 -1.20204637608153e-01 + 1.18181818181818e+01 1.16131302771668e+00 5.88308583503445e-02 -1.15957794313766e-01 + 1.24242424242424e+01 1.14844752198994e+00 6.69420911628980e-02 -1.11212235524214e-01 + 1.30303030303030e+01 1.14161039119524e+00 7.59411805359307e-02 -1.07908924395850e-01 + 1.36363636363636e+01 1.14446202808895e+00 8.67113082553106e-02 -1.09652277516758e-01 + 1.42424242424242e+01 1.15360925201834e+00 9.73732500785179e-02 -1.11627155262551e-01 + 1.48484848484848e+01 1.16355448827020e+00 1.07873104416001e-01 -1.14134059252607e-01 + 1.54545454545455e+01 1.16664773714290e+00 1.16951528881583e-01 -1.15612411766512e-01 + 1.60606060606061e+01 1.16661013255713e+00 1.25430946902501e-01 -1.16354027535650e-01 + 1.66666666666667e+01 1.15970818612903e+00 1.32782384020419e-01 -1.15612441871561e-01 + 1.72727272727273e+01 1.15449556243335e+00 1.41571380936791e-01 -1.15991269265136e-01 + 1.78787878787879e+01 1.15081418671560e+00 1.52117413613284e-01 -1.17753256291338e-01 + 1.84848484848485e+01 1.14958568526759e+00 1.64075993230739e-01 -1.21043159594879e-01 + 1.90909090909091e+01 1.14892881211198e+00 1.76252052672837e-01 -1.24587774021336e-01 + 1.96969696969697e+01 1.14714298858187e+00 1.87659451395701e-01 -1.27408729102206e-01 + 2.03030303030303e+01 1.14429050732898e+00 2.00561453897594e-01 -1.31242484394764e-01 + 2.09090909090909e+01 1.14266964540886e+00 2.14958144733618e-01 -1.36284282472763e-01 + 2.15151515151515e+01 1.14423506135131e+00 2.29354835569642e-01 -1.41385269444278e-01 + 2.21212121212121e+01 1.14307069922354e+00 2.43146307939168e-01 -1.46827329115247e-01 + 2.27272727272727e+01 1.13437676569340e+00 2.54517529167918e-01 -1.53633328645347e-01 + 2.33333333333333e+01 1.12568283216327e+00 2.65888750396669e-01 -1.60489831976375e-01 + 2.39393939393939e+01 1.11698889863313e+00 2.77259971625421e-01 -1.67539646177715e-01 + 2.45454545454545e+01 1.10899853924541e+00 2.88824171816938e-01 -1.73613983027854e-01 + 2.51515151515151e+01 1.10108635308077e+00 3.00409813654186e-01 -1.79569604350001e-01 + 2.57575757575758e+01 1.09317416691613e+00 3.11995455491433e-01 -1.85513172087669e-01 + 2.63636363636364e+01 1.08612496192253e+00 3.23969184308288e-01 -1.90961864811472e-01 + 2.69696969696970e+01 1.07965116711405e+00 3.36201677983836e-01 -1.96080224256372e-01 + 2.75757575757576e+01 1.07317737230558e+00 3.48434171659383e-01 -2.01190987495797e-01 + 2.81818181818182e+01 1.06698932003423e+00 3.60842423936148e-01 -2.06125820524907e-01 + 2.87878787878788e+01 1.06146794315678e+00 3.73660744436817e-01 -2.10662136737585e-01 + 2.93939393939394e+01 1.05594656627932e+00 3.86479064937486e-01 -2.15193450579188e-01 + 3.00000000000000e+01 1.05042518940186e+00 3.99297385438155e-01 -2.19719719772206e-01 + 3.30000000000000e+01 1.02644827609649e+00 4.66093046844495e-01 -2.39615606337711e-01 + 3.60000000000000e+01 1.00366641718899e+00 5.35679831809432e-01 -2.57787676201759e-01 + 3.90000000000000e+01 9.80023910642716e-01 6.07897658893372e-01 -2.74564735422046e-01 + 4.20000000000000e+01 9.53157091193240e-01 6.81725170790389e-01 -2.90390686664731e-01 + 4.50000000000000e+01 9.25099031707945e-01 7.55950278420295e-01 -3.05940905817259e-01 + 4.80000000000000e+01 8.90213156909925e-01 8.30040803802850e-01 -3.20687232891725e-01 + 5.10000000000000e+01 8.51286270268613e-01 9.02551341017882e-01 -3.35111108629908e-01 + 5.40000000000000e+01 8.04277100153241e-01 9.71901800324015e-01 -3.48903550668194e-01 + 5.70000000000000e+01 7.57267880913182e-01 1.04125168451056e+00 -3.62689866471288e-01 + 6.00000000000000e+01 7.10258637110966e-01 1.11060128113950e+00 -3.76470193714150e-01 + 6.30000000000000e+01 6.47769674730578e-01 1.16661579395854e+00 -3.88852281816777e-01 + 6.60000000000000e+01 5.85280557002702e-01 1.22263019247474e+00 -4.01231358690575e-01 + 6.90000000000000e+01 5.22791393951418e-01 1.27864459099094e+00 -4.13607260555449e-01 + 7.20000000000000e+01 4.52986794514127e-01 1.32114686428136e+00 -4.24708378476078e-01 + 7.50000000000000e+01 3.79524626640559e-01 1.35689335157008e+00 -4.35171875987646e-01 + 7.80000000000000e+01 3.06061084931655e-01 1.39264024848507e+00 -4.45633420993565e-01 + 8.10000000000000e+01 2.31376934566227e-01 1.42013017668539e+00 -4.55226551749704e-01 + 8.40000000000000e+01 1.54251651146622e-01 1.43110673741406e+00 -4.63084866775445e-01 + 8.70000000000000e+01 7.71257414576533e-02 1.44208338199759e+00 -4.70942168414430e-01 + 9.00000000000000e+01 -3.36956721141558e-07 1.45305993149174e+00 -4.78798611378502e-01 + 9.30000000000000e+01 -5.39883669172201e-02 1.44208337076307e+00 -4.83401960300538e-01 + 9.60000000000000e+01 -1.07976425758202e-01 1.43110676810732e+00 -4.87843492281115e-01 + 9.90000000000000e+01 -1.61964542361192e-01 1.42013008159586e+00 -4.92246671349029e-01 + 1.02000000000000e+02 -2.14243214939976e-01 1.39264007535569e+00 -4.93334961576679e-01 + 1.05000000000000e+02 -2.65667184017510e-01 1.35689358806697e+00 -4.92747792758473e-01 + 1.08000000000000e+02 -3.17091142370324e-01 1.32114669115373e+00 -4.92489218692733e-01 + 1.11000000000000e+02 -3.65954392283428e-01 1.27864410574316e+00 -4.91167327902475e-01 + 1.14000000000000e+02 -4.09696303308866e-01 1.22263034910072e+00 -4.87302639052758e-01 + 1.17000000000000e+02 -4.53438556744641e-01 1.16661616454686e+00 -4.83437520681149e-01 + 1.20000000000000e+02 -4.97180960199916e-01 1.11060173995280e+00 -4.79572183996746e-01 + 1.23000000000000e+02 -5.30087151245601e-01 1.04125214332386e+00 -4.73893974859065e-01 + 1.26000000000000e+02 -5.62993449444218e-01 9.71902259143020e-01 -4.68215548654545e-01 + 1.29000000000000e+02 -5.95899961956708e-01 9.02551799836887e-01 -4.62491545543420e-01 + 1.32000000000000e+02 -6.21555858594649e-01 8.29996331514373e-01 -4.57600132450428e-01 + 1.35000000000000e+02 -6.43586455890160e-01 7.55838362486724e-01 -4.53140066017817e-01 + 1.38000000000000e+02 -6.65616813110053e-01 6.81680698854136e-01 -4.48679982709285e-01 + 1.41000000000000e+02 -6.85803058067216e-01 6.08947766606052e-01 -4.46525550737110e-01 + 1.44000000000000e+02 -7.02301063534926e-01 5.39064308687913e-01 -4.48982440146784e-01 + 1.47000000000000e+02 -7.18798588287585e-01 4.69181021715765e-01 -4.51439319035616e-01 + 1.50000000000000e+02 -7.35295872691298e-01 3.99297820213560e-01 -4.53896192664215e-01 + 1.53000000000000e+02 -7.28330506319376e-01 3.46647734139971e-01 -4.68325381164791e-01 + 1.56000000000000e+02 -7.17850798388541e-01 2.93997685207009e-01 -4.82051328896962e-01 + 1.59000000000000e+02 -7.06863743588803e-01 2.41347630242394e-01 -4.98256732246163e-01 + 1.62000000000000e+02 -6.34811170157550e-01 2.01242252961188e-01 -5.03086039127970e-01 + 1.65000000000000e+02 -5.31470448900505e-01 1.67409320614642e-01 -5.01928907588892e-01 + 1.68000000000000e+02 -4.28130311834334e-01 1.33576175967328e-01 -5.00771566637685e-01 + 1.71000000000000e+02 -3.23313093840734e-01 9.99186368162403e-02 -4.50000513056908e-01 + 1.74000000000000e+02 -2.15541645031820e-01 6.66123168560943e-02 -2.99999717902353e-01 + 1.77000000000000e+02 -1.07279423135448e-01 5.50240468507236e-02 -1.40189247446868e-01 + 1.80000000000000e+02 0.00000000000000e+00 5.43028798119170e-02 2.26615932282131e-02 diff --git a/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_22.dat b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_22.dat new file mode 100644 index 00000000..c2189748 --- /dev/null +++ b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_22.dat @@ -0,0 +1,254 @@ +! ------------ AirfoilInfo v1.01.x Input File ---------------------------------- +! AeroElasticSE FAST driver +! line +! line +! ------------------------------------------------------------------------------ +DEFAULT InterpOrd ! Interpolation order to use for quasi-steady table lookup {1=linear; 3=cubic spline; "default"} [default=3] +1 NonDimArea ! The non-dimensional area of the airfoil (area/chord^2) (set to 1.0 if unsure or unneeded) +@"NREL-2p8-127_AF22_Coords.txt" NumCoords ! The number of coordinates in the airfoil shape file. Set to zero if coordinates not included. +AF22_BL.txt BL_file ! The file name including the boundary layer characteristics of the profile. Ignored if the aeroacoustic module is not called. +1 NumTabs ! Number of airfoil tables in this file. Each table must have lines for Re and Ctrl. +! ------------------------------------------------------------------------------ +! data for table 1 +! ------------------------------------------------------------------------------ +6.000000 Re ! Reynolds number in millions +0 Ctrl ! Control setting (must be 0 for current AirfoilInfo) +True InclUAdata ! Is unsteady aerodynamics data included in this table? If TRUE, then include 30 UA coefficients below this line +!........................................ +-3.566308 alpha0 ! 0-lift angle of attack, depends on airfoil. +9.412539 alpha1 ! Angle of attack at f=0.7, (approximately the stall angle) for AOA>alpha0. (deg) +-11.254245 alpha2 ! Angle of attack at f=0.7, (approximately the stall angle) for AOA1] +0.000000 S2 ! Constant in the f curve best-fit for AOA> alpha1; by definition it depends on the airfoil. [ignored if UAMod<>1] +0.000000 S3 ! Constant in the f curve best-fit for alpha2<=AOA< alpha0; by definition it depends on the airfoil. [ignored if UAMod<>1] +0.000000 S4 ! Constant in the f curve best-fit for AOA< alpha2; by definition it depends on the airfoil. [ignored if UAMod<>1] +1.372317 Cn1 ! Critical value of C0n at leading edge separation. It should be extracted from airfoil data at a given Mach and Reynolds number. It can be calculated from the static value of Cn at either the break in the pitching moment or the loss of chord force at the onset of stall. It is close to the condition of maximum lift of the airfoil at low Mach numbers. +-0.851187 Cn2 ! As Cn1 for negative AOAs. +Default St_sh ! Strouhal's shedding frequency constant. [default = 0.19] +0.007099 Cd0 ! 2D drag coefficient value at 0-lift. +-0.113167 Cm0 ! 2D pitching moment coefficient about 1/4-chord location, at 0-lift, positive if nose up. [If the aerodynamics coefficients table does not include a column for Cm, this needs to be set to 0.0] +0.000000 k0 ! Constant in the \hat(x)_cp curve best-fit; = (\hat(x)_AC-0.25). [ignored if UAMod<>1] +0.000000 k1 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k2 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k3 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k1_hat ! Constant in the expression of Cc due to leading edge vortex effects. [ignored if UAMod<>1] +Default x_cp_bar ! Constant in the expression of \hat(x)_cp^v. [ignored if UAMod<>1, default = 0.2] +Default UACutout ! Angle of attack above which unsteady aerodynamics are disabled (deg). [Specifying the string "Default" sets UACutout to 45 degrees] +Default filtCutOff ! Cut-off frequency (-3 dB corner frequency) for low-pass filtering the AoA input to UA, as well as the 1st and 2nd derivatives (Hz) [default = 20] +!........................................ +! Table of aerodynamics coefficients +200 NumAlf ! Number of data lines in the following table +! Alpha Cl Cd Cm +! (deg) (-) (-) (-) +-1.80000000000000e+02 0.00000000000000e+00 5.07556742159798e-02 6.34072788301272e-02 +-1.77000000000000e+02 1.21373168046836e-01 5.07556742159798e-02 1.44989137166855e-01 +-1.74000000000000e+02 2.43858124753276e-01 6.09067517869507e-02 2.39999774321882e-01 +-1.71000000000000e+02 3.65787584521499e-01 9.13603177509608e-02 3.60000410445527e-01 +-1.68000000000000e+02 4.75515174866590e-01 1.23180858733612e-01 3.13292467675056e-01 +-1.65000000000000e+02 5.79141972913914e-01 1.55684871270972e-01 1.83232181192322e-01 +-1.62000000000000e+02 6.82769984990416e-01 1.88188793392151e-01 5.31699414433441e-02 +-1.59000000000000e+02 7.49929094529181e-01 2.28115056904519e-01 -3.37679356965932e-02 +-1.56000000000000e+02 7.45401898546715e-01 2.82885752112716e-01 -3.57982585441417e-02 +-1.53000000000000e+02 7.40045790863415e-01 3.37656465738121e-01 -3.75882513662505e-02 +-1.50000000000000e+02 7.32596618631745e-01 3.92427224341668e-01 -3.50272634037363e-02 +-1.47000000000000e+02 7.16416220992227e-01 4.62548307459531e-01 -1.89393396903141e-02 +-1.44000000000000e+02 7.00235624959091e-01 5.32669512974126e-01 -2.85117921368804e-03 +-1.41000000000000e+02 6.84054632124555e-01 6.02790963290924e-01 1.27311247792732e-02 +-1.38000000000000e+02 6.64108508380734e-01 6.75798748422820e-01 2.82558445968883e-02 +-1.35000000000000e+02 6.42279826820249e-01 7.50249695107020e-01 4.38571814291932e-02 +-1.32000000000000e+02 6.20450921675678e-01 8.24701058603098e-01 5.94656947948800e-02 +-1.29000000000000e+02 5.94974616376641e-01 8.97565459936934e-01 7.52120953201059e-02 +-1.26000000000000e+02 5.62203493473854e-01 9.67255929411789e-01 9.12244354642672e-02 +-1.23000000000000e+02 5.29432511812518e-01 1.03694573967196e+00 1.07239613164941e-01 +-1.20000000000000e+02 4.96661600769268e-01 1.10663522033711e+00 1.23257579300455e-01 +-1.17000000000000e+02 4.53007747800845e-01 1.16302575005567e+00 1.38481557370608e-01 +-1.14000000000000e+02 4.09354049149219e-01 1.21941603836822e+00 1.53706780948661e-01 +-1.11000000000000e+02 3.65700701685022e-01 1.27580589589615e+00 1.68932988096397e-01 +-1.08000000000000e+02 3.16900772369631e-01 1.31870071696580e+00 1.82560097851392e-01 +-1.05000000000000e+02 2.65527512940554e-01 1.35484791704772e+00 1.95399125304991e-01 +-1.02000000000000e+02 2.14154242205798e-01 1.39099470291805e+00 2.08238303928547e-01 +-9.90000000000000e+01 1.61914865702625e-01 1.41888942602526e+00 2.19722912577175e-01 +-9.60000000000000e+01 1.07943240147024e-01 1.43027966616597e+00 2.28497123718656e-01 +-9.30000000000000e+01 5.39717537188113e-02 1.44166981929167e+00 2.37271383106753e-01 +-9.00000000000000e+01 3.36853033223878e-07 1.45305992891065e+00 2.46045939350736e-01 +-8.70000000000000e+01 -5.39716984790431e-02 1.44166983094945e+00 2.50473302115734e-01 +-8.40000000000000e+01 -1.07943391063713e-01 1.43027963431632e+00 2.54928173585132e-01 +-8.10000000000000e+01 -1.61914398153851e-01 1.41888952469734e+00 2.59409826519098e-01 +-7.80000000000000e+01 -2.14153993391912e-01 1.39099487798618e+00 2.60637456906859e-01 +-7.50000000000000e+01 -2.65527852822723e-01 1.35484767790248e+00 2.60250041617006e-01 +-7.20000000000000e+01 -3.16900523561175e-01 1.31870089203215e+00 2.59886362685276e-01 +-6.90000000000000e+01 -3.65700323515595e-01 1.27580638440210e+00 2.58282671903770e-01 +-6.60000000000000e+01 -4.09354171212959e-01 1.21941588069058e+00 2.54173349716066e-01 +-6.30000000000000e+01 -4.53008036612590e-01 1.16302537697905e+00 2.50084873782204e-01 +-6.00000000000000e+01 -4.96661817579899e-01 1.10663475927516e+00 2.46016982651216e-01 +-5.70000000000000e+01 -5.29432728623149e-01 1.03694527861001e+00 2.40180820587871e-01 +-5.40000000000000e+01 -5.62203710285886e-01 9.67255468343294e-01 2.34364534434322e-01 +-5.10000000000000e+01 -5.94974833188673e-01 8.97564998868439e-01 2.28567701938433e-01 +-4.80000000000000e+01 -6.22057662441151e-01 8.24737086109294e-01 2.23106850479156e-01 +-4.50000000000000e+01 -6.46296436287407e-01 7.50340502131161e-01 2.17827122416360e-01 +-4.20000000000000e+01 -6.65715236572083e-01 6.75834775642757e-01 2.14270938724142e-01 +-3.90000000000000e+01 -6.84287831284676e-01 6.01733100265088e-01 2.11324975236861e-01 +-3.60000000000000e+01 -7.00563864724568e-01 5.29261493580405e-01 2.10489244413362e-01 +-3.30000000000000e+01 -7.16187489056336e-01 4.59440503480610e-01 2.12957840755690e-01 +-3.00000000000000e+01 -7.32596736476158e-01 3.92426788149384e-01 2.19119564417483e-01 +-2.93939393939394e+01 -7.36374389172812e-01 3.79567808225057e-01 2.21363823380573e-01 +-2.87878787878788e+01 -7.40152041869467e-01 3.66708828300729e-01 2.23608082343664e-01 +-2.81818181818182e+01 -7.43929694566121e-01 3.53849848376402e-01 2.25852341306755e-01 +-2.75757575757576e+01 -7.48165648451628e-01 3.41402728220191e-01 2.28809630520161e-01 +-2.69696969696970e+01 -7.52598033982392e-01 3.29132134535727e-01 2.32072530342035e-01 +-2.63636363636364e+01 -7.57030419513156e-01 3.16861540851264e-01 2.35335430163909e-01 +-2.57575757575758e+01 -7.61859695409693e-01 3.04850755726473e-01 2.39132514207883e-01 +-2.51515151515151e+01 -7.67284214354563e-01 2.93229622889516e-01 2.43730750086607e-01 +-2.45454545454545e+01 -7.72708733299433e-01 2.81608490052560e-01 2.48328985965330e-01 +-2.39393939393939e+01 -7.78397371018865e-01 2.70052672159968e-01 2.52203196387113e-01 +-2.33333333333333e+01 -7.86463128844015e-01 2.59084701411948e-01 2.49561037521642e-01 +-2.27272727272727e+01 -7.94528886669166e-01 2.48116730663927e-01 2.45890720916381e-01 +-2.21212121212121e+01 -8.02594644494317e-01 2.37148759915907e-01 2.43586283408853e-01 +-2.15151515151515e+01 -8.10907795657620e-01 2.26212863295167e-01 2.36219129070528e-01 +-2.09090909090909e+01 -8.16516141250483e-01 2.15284987269397e-01 2.26807332042050e-01 +-2.03030303030303e+01 -8.22548837928087e-01 2.04357111243626e-01 2.17395535013573e-01 +-1.96969696969697e+01 -8.30002084619816e-01 1.93526156053271e-01 2.08338072839810e-01 +-1.90909090909091e+01 -8.38276075640665e-01 1.82792116215481e-01 1.99634925475900e-01 +-1.84848484848485e+01 -8.41525789425216e-01 1.71763238665119e-01 1.87206613897995e-01 +-1.78787878787879e+01 -8.43830658066113e-01 1.60232706599968e-01 1.74288223907780e-01 +-1.72727272727273e+01 -8.45969420405482e-01 1.49310415673877e-01 1.60399611180235e-01 +-1.66666666666667e+01 -8.44462724081164e-01 1.38631475065992e-01 1.43746150937375e-01 +-1.60606060606061e+01 -8.40100015006392e-01 1.28157201231612e-01 1.24821818047702e-01 +-1.54545454545455e+01 -8.37817603025782e-01 1.18032218056081e-01 1.04802159358542e-01 +-1.48484848484848e+01 -8.37183712471984e-01 1.08103958885772e-01 8.41678532118364e-02 +-1.42424242424242e+01 -8.40890120256044e-01 9.84661435612030e-02 6.27214130589554e-02 +-1.36363636363636e+01 -8.46817406852861e-01 8.88896748069138e-02 4.26434421043484e-02 +-1.30303030303030e+01 -8.55315988459211e-01 7.93654273525520e-02 2.26015400198430e-02 +-1.24242424242424e+01 -8.47245180473497e-01 6.91820678235402e-02 8.67599048926910e-03 +-1.18181818181818e+01 -8.35432683112564e-01 5.98195535661050e-02 -3.47219937244458e-03 +-1.12121212121212e+01 -8.15393459831635e-01 4.94939958051427e-02 -1.22220313441137e-02 +-1.06060606060606e+01 -7.90094798205374e-01 4.03354037886031e-02 -2.24327341739879e-02 +-1.00000000000000e+01 -7.61704104709643e-01 3.20697982337656e-02 -3.34296643848299e-02 +-9.39393939393939e+00 -7.28357715972300e-01 2.53011224655095e-02 -4.42541982301917e-02 +-8.78787878787879e+00 -6.84142454187570e-01 1.91495037741205e-02 -5.66943316671589e-02 +-8.18181818181818e+00 -6.17979429458198e-01 1.37667951514698e-02 -7.13770363239650e-02 +-7.57575757575758e+00 -5.38103979710377e-01 1.08227708003567e-02 -8.21189162256499e-02 +-6.96969696969697e+00 -4.51631211888217e-01 9.39164055487013e-03 -9.05502975056676e-02 +-6.36363636363636e+00 -3.69904831929908e-01 8.28680451711851e-03 -9.65427316699646e-02 +-5.75757575757576e+00 -2.88476726756192e-01 7.76135087915599e-03 -1.01757959286034e-01 +-5.15151515151515e+00 -2.07260475931238e-01 7.47535721667608e-03 -1.06060127684791e-01 +-4.54545454545454e+00 -1.27279930853378e-01 7.28615916745306e-03 -1.09371226057769e-01 +-3.93939393939394e+00 -4.80058499406509e-02 7.17092890724474e-03 -1.11865483581015e-01 +-3.33333333333333e+00 2.99773467049867e-02 7.05390574872594e-03 -1.13980246411455e-01 +-2.72727272727273e+00 1.07925041765181e-01 6.93627094208034e-03 -1.15908672907983e-01 +-2.12121212121212e+00 1.85286698580458e-01 6.86333451961630e-03 -1.17939670229949e-01 +-1.51515151515152e+00 2.61818679801486e-01 6.83016135377631e-03 -1.20251324856380e-01 +-9.09090909090912e-01 3.37437336745196e-01 6.82527631097856e-03 -1.22427420055716e-01 +-3.03030303030302e-01 4.11339964275432e-01 6.88875118426107e-03 -1.24393823575531e-01 + 3.03030303030302e-01 4.85425194785723e-01 6.93305859100922e-03 -1.26271092424251e-01 + 9.09090909090912e-01 5.59688748393245e-01 6.92641095940415e-03 -1.27930360286602e-01 + 1.51515151515152e+00 6.33889422008781e-01 6.97145778583218e-03 -1.29509636273062e-01 + 2.12121212121212e+00 7.08007295477312e-01 7.08503567582370e-03 -1.30948866987131e-01 + 2.72727272727273e+00 7.81743944095907e-01 7.22808542364998e-03 -1.32280278589569e-01 + 3.33333333333333e+00 8.54768718499635e-01 7.36394317569994e-03 -1.33476357648126e-01 + 3.93939393939394e+00 9.27343605653137e-01 7.50800878324420e-03 -1.34580752920963e-01 + 4.54545454545455e+00 9.99337144270299e-01 7.68025178023798e-03 -1.35437140997352e-01 + 5.15151515151515e+00 1.07077533588784e+00 7.88250770331053e-03 -1.36171448237875e-01 + 5.75757575757576e+00 1.14067573993544e+00 8.18560595986809e-03 -1.36563716920552e-01 + 6.36363636363637e+00 1.20738594989603e+00 8.61082274432950e-03 -1.36450536130407e-01 + 6.96969696969697e+00 1.27030534457503e+00 9.26154940433015e-03 -1.35865188748459e-01 + 7.57575757575757e+00 1.31967720204744e+00 1.06711516164033e-02 -1.33196036139163e-01 + 8.18181818181818e+00 1.36117901696138e+00 1.20457201580521e-02 -1.29734082098160e-01 + 8.78787878787879e+00 1.38645164475349e+00 1.40141299367242e-02 -1.24969368476653e-01 + 9.39393939393939e+00 1.38364788675440e+00 2.10604272519143e-02 -1.22681471706985e-01 + 1.00000000000000e+01 1.36632615029107e+00 3.08301921000425e-02 -1.22594505197778e-01 + 1.06060606060606e+01 1.30793900793488e+00 3.95953728731437e-02 -1.21768157631026e-01 + 1.12121212121212e+01 1.26354919483254e+00 4.68596237969062e-02 -1.20824315241689e-01 + 1.18181818181818e+01 1.24622078267823e+00 5.34209201004403e-02 -1.17862121865541e-01 + 1.24242424242424e+01 1.23316572300737e+00 6.31476016531568e-02 -1.14380907459069e-01 + 1.30303030303030e+01 1.22283883104523e+00 7.34240891191203e-02 -1.12038188702533e-01 + 1.36363636363636e+01 1.21302095714098e+00 8.54972535339130e-02 -1.13922354181064e-01 + 1.42424242424242e+01 1.20995851746224e+00 9.67529857851515e-02 -1.15899802821485e-01 + 1.48484848484848e+01 1.20957781975123e+00 1.06783261680667e-01 -1.18176308348192e-01 + 1.54545454545455e+01 1.20628232400092e+00 1.15676133910572e-01 -1.19630275206793e-01 + 1.60606060606061e+01 1.20129649682940e+00 1.24088573760305e-01 -1.20475625038284e-01 + 1.66666666666667e+01 1.19049649901642e+00 1.31588359571251e-01 -1.20087718033958e-01 + 1.72727272727273e+01 1.17964142895866e+00 1.40230863472286e-01 -1.20588628022729e-01 + 1.78787878787879e+01 1.16825933056011e+00 1.50270037306760e-01 -1.22187730969383e-01 + 1.84848484848485e+01 1.16279372315999e+00 1.61375170677979e-01 -1.24959559895277e-01 + 1.90909090909091e+01 1.15872202145603e+00 1.72688440191291e-01 -1.28082765397647e-01 + 1.96969696969697e+01 1.15339844517572e+00 1.83671166909384e-01 -1.31533890864235e-01 + 2.03030303030303e+01 1.14667353640152e+00 1.95931329664752e-01 -1.35939723395958e-01 + 2.09090909090909e+01 1.14214263161388e+00 2.09469000726538e-01 -1.41468507832042e-01 + 2.15151515151515e+01 1.14163199846552e+00 2.23006671788323e-01 -1.47048295239323e-01 + 2.21212121212121e+01 1.13801617834194e+00 2.36098095781483e-01 -1.52838501078495e-01 + 2.27272727272727e+01 1.12925112767887e+00 2.47404990655498e-01 -1.59470164140170e-01 + 2.33333333333333e+01 1.12048607701580e+00 2.58711885529513e-01 -1.66145346243189e-01 + 2.39393939393939e+01 1.11172102635272e+00 2.70018780403529e-01 -1.72987104001955e-01 + 2.45454545454545e+01 1.10386992919784e+00 2.81608490052560e-01 -1.78880886757862e-01 + 2.51515151515151e+01 1.09612038024829e+00 2.93229622889516e-01 -1.84660438598366e-01 + 2.57575757575758e+01 1.08837083129873e+00 3.04850755726473e-01 -1.90429603885151e-01 + 2.63636363636364e+01 1.08147195893053e+00 3.16861540851264e-01 -1.95726297856203e-01 + 2.69696969696970e+01 1.07514029241291e+00 3.29132134535727e-01 -2.00707647194441e-01 + 2.75757575757576e+01 1.06880862589528e+00 3.41402728220191e-01 -2.05682450895045e-01 + 2.81818181818182e+01 1.06275754212664e+00 3.53849848376402e-01 -2.10489790164498e-01 + 2.87878787878788e+01 1.05736109527898e+00 3.66708828300730e-01 -2.14916711454757e-01 + 2.93939393939394e+01 1.05196464843131e+00 3.79567808225057e-01 -2.19339322210173e-01 + 3.00000000000000e+01 1.04656820158365e+00 3.92426788149384e-01 -2.23757586000285e-01 + 3.30000000000000e+01 1.02312514415356e+00 4.59440503480610e-01 -2.43238943532748e-01 + 3.60000000000000e+01 1.00080435367758e+00 5.29261493580405e-01 -2.61084484698553e-01 + 3.90000000000000e+01 9.77554126454961e-01 6.01733100265088e-01 -2.77608856801414e-01 + 4.20000000000000e+01 9.51021881685284e-01 6.75834775642758e-01 -2.93234977723852e-01 + 4.50000000000000e+01 9.23281318212600e-01 7.50340502131161e-01 -3.08601809213403e-01 + 4.80000000000000e+01 8.88654194131487e-01 8.24737086109295e-01 -3.23208356054975e-01 + 5.10000000000000e+01 8.49964254625460e-01 8.97564998868439e-01 -3.37506814180089e-01 + 5.40000000000000e+01 8.03148423080423e-01 9.67255468343294e-01 -3.51200699120049e-01 + 5.70000000000000e+01 7.56332531480030e-01 1.03694527861001e+00 -3.64889313118346e-01 + 6.00000000000000e+01 7.09516609852189e-01 1.10663475927516e+00 -3.78572770796720e-01 + 6.30000000000000e+01 6.47154294385920e-01 1.16302537697905e+00 -3.90891753454121e-01 + 6.60000000000000e+01 5.84791782254718e-01 1.21941588069058e+00 -4.03208150894803e-01 + 6.90000000000000e+01 5.22429143308335e-01 1.27580638440210e+00 -4.15521834280170e-01 + 7.20000000000000e+01 4.52714954299060e-01 1.31870089203215e+00 -4.26575704118960e-01 + 7.50000000000000e+01 3.79325140754361e-01 1.35484767790248e+00 -4.36999473643461e-01 + 7.80000000000000e+01 3.05934076441010e-01 1.39099487798618e+00 -4.47421477951532e-01 + 8.10000000000000e+01 2.31306131004083e-01 1.41888952469734e+00 -4.56980574222415e-01 + 8.40000000000000e+01 1.54204508701838e-01 1.43027963431632e+00 -4.64815596729305e-01 + 8.70000000000000e+01 7.71021882732242e-02 1.44166983094945e+00 -4.72649698806517e-01 + 9.00000000000000e+01 -3.36853033455059e-07 1.45305992891065e+00 -4.80483033427282e-01 + 9.30000000000000e+01 -5.39717537188113e-02 1.44166981929167e+00 -4.84882001487256e-01 + 9.60000000000000e+01 -1.07943240147024e-01 1.43027966616597e+00 -4.88977291312720e-01 + 9.90000000000000e+01 -1.61914865702625e-01 1.41888942602526e+00 -4.93035304646623e-01 + 1.02000000000000e+02 -2.14154242205798e-01 1.39099470291805e+00 -4.93786567296916e-01 + 1.05000000000000e+02 -2.65527512940555e-01 1.35484791704772e+00 -4.92868936308638e-01 + 1.08000000000000e+02 -3.16900772369631e-01 1.31870071696580e+00 -4.92410220071252e-01 + 1.11000000000000e+02 -3.65700701685022e-01 1.27580589589615e+00 -4.90965426724924e-01 + 1.14000000000000e+02 -4.09354049149220e-01 1.21941603836822e+00 -4.86982932906717e-01 + 1.17000000000000e+02 -4.53007747800845e-01 1.16302575005567e+00 -4.83000008666658e-01 + 1.20000000000000e+02 -4.96661600769268e-01 1.10663522033711e+00 -4.79016865676293e-01 + 1.23000000000000e+02 -5.29432511812518e-01 1.03694573967196e+00 -4.73227232421762e-01 + 1.26000000000000e+02 -5.62203493473854e-01 9.67255929411789e-01 -4.67437401740092e-01 + 1.29000000000000e+02 -5.94974616376641e-01 8.97565459936934e-01 -4.61550294565979e-01 + 1.32000000000000e+02 -6.20450921675679e-01 8.24701058603098e-01 -4.56453890288661e-01 + 1.35000000000000e+02 -6.42279826820249e-01 7.50249695107020e-01 -4.51785141239963e-01 + 1.38000000000000e+02 -6.64108508380734e-01 6.75798748422819e-01 -4.47116255471473e-01 + 1.41000000000000e+02 -6.84054632124555e-01 6.02790963290923e-01 -4.44720379804122e-01 + 1.44000000000000e+02 -7.00235624959091e-01 5.32669512974126e-01 -4.46870542783319e-01 + 1.47000000000000e+02 -7.16416220992227e-01 4.62548307459531e-01 -4.49020707038669e-01 + 1.50000000000000e+02 -7.32596618631745e-01 3.92427224341668e-01 -4.51170871932074e-01 + 1.53000000000000e+02 -7.33272841626932e-01 3.38604126000068e-01 -4.67244946323259e-01 + 1.56000000000000e+02 -7.30920747814166e-01 2.84781062373784e-01 -4.81810042653382e-01 + 1.59000000000000e+02 -7.28131423029985e-01 2.30957992223316e-01 -4.99843304573404e-01 + 1.62000000000000e+02 -6.59004284451097e-01 1.91223709907543e-01 -5.04964107373118e-01 + 1.65000000000000e+02 -5.56057205936165e-01 1.58533940661002e-01 -5.03102799944957e-01 + 1.68000000000000e+02 -4.53110707101343e-01 1.25843946014156e-01 -5.01241125772289e-01 + 1.71000000000000e+02 -3.46031678268841e-01 9.36455360526948e-02 -4.50000513056908e-01 + 1.74000000000000e+02 -2.30687396505613e-01 6.24303184126113e-02 -2.99999717902353e-01 + 1.77000000000000e+02 -1.14817786337317e-01 5.15140111366759e-02 -1.23779476102597e-01 + 1.80000000000000e+02 0.00000000000000e+00 5.07556742159798e-02 6.34072788301272e-02 diff --git a/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_23.dat b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_23.dat new file mode 100644 index 00000000..1d9534a4 --- /dev/null +++ b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_23.dat @@ -0,0 +1,254 @@ +! ------------ AirfoilInfo v1.01.x Input File ---------------------------------- +! AeroElasticSE FAST driver +! line +! line +! ------------------------------------------------------------------------------ +DEFAULT InterpOrd ! Interpolation order to use for quasi-steady table lookup {1=linear; 3=cubic spline; "default"} [default=3] +1 NonDimArea ! The non-dimensional area of the airfoil (area/chord^2) (set to 1.0 if unsure or unneeded) +@"NREL-2p8-127_AF23_Coords.txt" NumCoords ! The number of coordinates in the airfoil shape file. Set to zero if coordinates not included. +AF23_BL.txt BL_file ! The file name including the boundary layer characteristics of the profile. Ignored if the aeroacoustic module is not called. +1 NumTabs ! Number of airfoil tables in this file. Each table must have lines for Re and Ctrl. +! ------------------------------------------------------------------------------ +! data for table 1 +! ------------------------------------------------------------------------------ +6.000000 Re ! Reynolds number in millions +0 Ctrl ! Control setting (must be 0 for current AirfoilInfo) +True InclUAdata ! Is unsteady aerodynamics data included in this table? If TRUE, then include 30 UA coefficients below this line +!........................................ +-3.734961 alpha0 ! 0-lift angle of attack, depends on airfoil. +9.697795 alpha1 ! Angle of attack at f=0.7, (approximately the stall angle) for AOA>alpha0. (deg) +-10.684389 alpha2 ! Angle of attack at f=0.7, (approximately the stall angle) for AOA1] +0.000000 S2 ! Constant in the f curve best-fit for AOA> alpha1; by definition it depends on the airfoil. [ignored if UAMod<>1] +0.000000 S3 ! Constant in the f curve best-fit for alpha2<=AOA< alpha0; by definition it depends on the airfoil. [ignored if UAMod<>1] +0.000000 S4 ! Constant in the f curve best-fit for AOA< alpha2; by definition it depends on the airfoil. [ignored if UAMod<>1] +1.401232 Cn1 ! Critical value of C0n at leading edge separation. It should be extracted from airfoil data at a given Mach and Reynolds number. It can be calculated from the static value of Cn at either the break in the pitching moment or the loss of chord force at the onset of stall. It is close to the condition of maximum lift of the airfoil at low Mach numbers. +-0.842106 Cn2 ! As Cn1 for negative AOAs. +Default St_sh ! Strouhal's shedding frequency constant. [default = 0.19] +0.006818 Cd0 ! 2D drag coefficient value at 0-lift. +-0.113242 Cm0 ! 2D pitching moment coefficient about 1/4-chord location, at 0-lift, positive if nose up. [If the aerodynamics coefficients table does not include a column for Cm, this needs to be set to 0.0] +0.000000 k0 ! Constant in the \hat(x)_cp curve best-fit; = (\hat(x)_AC-0.25). [ignored if UAMod<>1] +0.000000 k1 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k2 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k3 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k1_hat ! Constant in the expression of Cc due to leading edge vortex effects. [ignored if UAMod<>1] +Default x_cp_bar ! Constant in the expression of \hat(x)_cp^v. [ignored if UAMod<>1, default = 0.2] +Default UACutout ! Angle of attack above which unsteady aerodynamics are disabled (deg). [Specifying the string "Default" sets UACutout to 45 degrees] +Default filtCutOff ! Cut-off frequency (-3 dB corner frequency) for low-pass filtering the AoA input to UA, as well as the 1st and 2nd derivatives (Hz) [default = 20] +!........................................ +! Table of aerodynamics coefficients +200 NumAlf ! Number of data lines in the following table +! Alpha Cl Cd Cm +! (deg) (-) (-) (-) +-1.80000000000000e+02 0.00000000000000e+00 4.63087218239101e-02 1.12294918356446e-01 +-1.77000000000000e+02 1.31407871834538e-01 4.63087218239101e-02 1.64677969845384e-01 +-1.74000000000000e+02 2.64019510355404e-01 5.55704139343663e-02 2.39999774321882e-01 +-1.71000000000000e+02 3.96029843973720e-01 8.33557943190768e-02 3.60000410445527e-01 +-1.68000000000000e+02 5.06430868461261e-01 1.13562290370517e-01 3.08610785372619e-01 +-1.65000000000000e+02 6.06027490595898e-01 1.44979315997335e-01 1.71528030078362e-01 +-1.62000000000000e+02 7.05625285482958e-01 1.76396375603631e-01 3.44433778978911e-02 +-1.59000000000000e+02 7.67703923736826e-01 2.15960936619897e-01 -5.47934885866511e-02 +-1.56000000000000e+02 7.55397723550236e-01 2.71820224837142e-01 -4.90352678454869e-02 +-1.53000000000000e+02 7.42659054409641e-01 3.27679539787795e-01 -4.31517727134676e-02 +-1.50000000000000e+02 7.28828504793094e-01 3.83538902055256e-01 -3.44596878302946e-02 +-1.47000000000000e+02 7.13090480114408e-01 4.53967729130364e-01 -1.86189086211220e-02 +-1.44000000000000e+02 6.97352307618548e-01 5.24396727029221e-01 -2.77793532551869e-03 +-1.41000000000000e+02 6.81613839477788e-01 5.94826066587771e-01 1.25927965767874e-02 +-1.38000000000000e+02 6.62002920890116e-01 6.68189421819665e-01 2.79774029417006e-02 +-1.35000000000000e+02 6.40455784934676e-01 7.43019778936259e-01 4.34673885521046e-02 +-1.32000000000000e+02 6.18908433527060e-01 8.17850698969113e-01 5.89612242447798e-02 +-1.29000000000000e+02 5.93682830023854e-01 8.91114749342423e-01 7.46038609930899e-02 +-1.26000000000000e+02 5.61100704888174e-01 9.61245052954708e-01 9.05389699091404e-02 +-1.23000000000000e+02 5.28518625044670e-01 1.03137459621631e+00 1.06475722031366e-01 +-1.20000000000000e+02 4.95936567846408e-01 1.10150375931678e+00 1.22414010239834e-01 +-1.17000000000000e+02 4.52406347782145e-01 1.15838084536770e+00 1.37579477845402e-01 +-1.14000000000000e+02 4.08876283070132e-01 1.21525768824574e+00 1.52745471209185e-01 +-1.11000000000000e+02 3.65346571871469e-01 1.27213409662221e+00 1.67911731135092e-01 +-1.08000000000000e+02 3.16635035430310e-01 1.31553636143885e+00 1.81492961378994e-01 +-1.05000000000000e+02 2.65332546911451e-01 1.35220145187604e+00 1.94295080678717e-01 +-1.02000000000000e+02 2.14030046275947e-01 1.38886612216712e+00 2.07096904272415e-01 +-9.90000000000000e+01 1.61845527217881e-01 1.41728443461560e+00 2.18547504691698e-01 +-9.60000000000000e+01 1.07896933109836e-01 1.42920967418575e+00 2.27294974831625e-01 +-9.30000000000000e+01 5.39485757284989e-02 1.44113482265378e+00 2.36042235203500e-01 +-9.00000000000000e+01 3.36708372806976e-07 1.45305992557158e+00 2.44789532965389e-01 +-8.70000000000000e+01 -5.39485205124533e-02 1.44113483485913e+00 2.48978944307922e-01 +-8.40000000000000e+01 -1.07897083962124e-01 1.42920964084012e+00 2.53182684189232e-01 +-8.10000000000000e+01 -1.61845059868626e-01 1.41728453792232e+00 2.57400380355460e-01 +-7.80000000000000e+01 -2.14029797804819e-01 1.38886629974350e+00 2.58354097127670e-01 +-7.50000000000000e+01 -2.65332886325409e-01 1.35220120930450e+00 2.57682039063764e-01 +-7.20000000000000e+01 -3.16634786964608e-01 1.31553653901342e+00 2.57022063927401e-01 +-6.90000000000000e+01 -3.65346194773105e-01 1.27213458934316e+00 2.55116538347366e-01 +-6.60000000000000e+01 -4.08876404788159e-01 1.21525752920760e+00 2.50706504502961e-01 +-6.30000000000000e+01 -4.52406635775942e-01 1.15838046907205e+00 2.46307312278457e-01 +-6.00000000000000e+01 -4.95936783407592e-01 1.10150329534591e+00 2.41918834523807e-01 +-5.70000000000000e+01 -5.28518840605854e-01 1.03137413224544e+00 2.35766279929407e-01 +-5.40000000000000e+01 -5.61100920449807e-01 9.61244588976293e-01 2.29623980263181e-01 +-5.10000000000000e+01 -5.93683045585487e-01 8.91114285364008e-01 2.23491601843586e-01 +-4.80000000000000e+01 -6.20534325092436e-01 8.17875803160575e-01 2.17675688732665e-01 +-4.50000000000000e+01 -6.44520273887822e-01 7.43083281614397e-01 2.12024856819171e-01 +-4.20000000000000e+01 -6.63628799731457e-01 6.68214525810191e-01 2.08040444001537e-01 +-3.90000000000000e+01 -6.81874399513891e-01 5.93758161928647e-01 2.04674544610408e-01 +-3.60000000000000e+01 -6.97766871415788e-01 5.20958260992169e-01 2.03489583532797e-01 +-3.30000000000000e+01 -7.12939161093519e-01 4.50834279245390e-01 2.05538204979316e-01 +-3.00000000000000e+01 -7.28828619013840e-01 3.83538464029985e-01 2.11194373081700e-01 +-2.93939393939394e+01 -7.32484050886326e-01 3.70626883995265e-01 2.13311958401767e-01 +-2.87878787878788e+01 -7.36139482758811e-01 3.57715303960545e-01 2.15429543721834e-01 +-2.81818181818182e+01 -7.39794914631297e-01 3.44803723925826e-01 2.17547129041902e-01 +-2.75757575757576e+01 -7.43897116047021e-01 3.32306320069088e-01 2.20359205164668e-01 +-2.69696969696970e+01 -7.48190806550193e-01 3.19986435516351e-01 2.23468945736725e-01 +-2.63636363636364e+01 -7.52484497053364e-01 3.07666550963613e-01 2.26578686308783e-01 +-2.57575757575758e+01 -7.57166921645990e-01 2.95607827569598e-01 2.30208187650959e-01 +-2.51515151515151e+01 -7.62432356773396e-01 2.83940785046750e-01 2.34617209011481e-01 +-2.45454545454545e+01 -7.67697791900801e-01 2.72273742523902e-01 2.39026230372002e-01 +-2.39393939393939e+01 -7.73185913789781e-01 2.60674093105127e-01 2.42999615685138e-01 +-2.33333333333333e+01 -7.80678259646152e-01 2.49680994670638e-01 2.43052192230589e-01 +-2.27272727272727e+01 -7.88170605502522e-01 2.38687896236150e-01 2.42568426653275e-01 +-2.21212121212121e+01 -7.95662951358893e-01 2.27694797801661e-01 2.42847201975787e-01 +-2.15151515151515e+01 -8.03122917039084e-01 2.16821981366589e-01 2.40650679427694e-01 +-2.09090909090909e+01 -8.09131542492648e-01 2.05979243168443e-01 2.37504038302243e-01 +-2.03030303030303e+01 -8.15361532190997e-01 1.95136504970297e-01 2.34357397176791e-01 +-1.96969696969697e+01 -8.22724297362875e-01 1.84465173018459e-01 2.31838282654647e-01 +-1.90909090909091e+01 -8.30906925089566e-01 1.73965237616411e-01 2.29946659236386e-01 +-1.84848484848485e+01 -8.31918112583414e-01 1.63453683142057e-01 2.21457087959307e-01 +-1.78787878787879e+01 -8.31595126485506e-01 1.52804171278659e-01 2.11525887706305e-01 +-1.72727272727273e+01 -8.31031369674327e-01 1.42866609967544e-01 1.99629022620351e-01 +-1.66666666666667e+01 -8.25256436764452e-01 1.33056030411927e-01 1.82862818294272e-01 +-1.60606060606061e+01 -8.15283902136340e-01 1.23352246439714e-01 1.62108086965354e-01 +-1.54545454545455e+01 -8.07202667770935e-01 1.13892061964644e-01 1.40642855087825e-01 +-1.48484848484848e+01 -8.00484816929381e-01 1.04572113067813e-01 1.18780315352772e-01 +-1.42424242424242e+01 -7.97273008609856e-01 9.54960779870226e-02 9.63104203643558e-02 +-1.36363636363636e+01 -7.95411303466245e-01 8.64650864864851e-02 7.45927649489055e-02 +-1.30303030303030e+01 -7.95017738651442e-01 7.74696737429739e-02 5.29180621304360e-02 +-1.24242424242424e+01 -7.83491668219477e-01 6.82294219737490e-02 3.53906464364337e-02 +-1.18181818181818e+01 -7.69390633326341e-01 5.96867612177415e-02 1.90461834027338e-02 +-1.12121212121212e+01 -7.49852461255598e-01 4.99975509367422e-02 4.95579546151236e-03 +-1.06060606060606e+01 -7.26864172133525e-01 4.11158480572885e-02 -1.01481331303818e-02 +-1.00000000000000e+01 -7.01883025098080e-01 3.29149003627515e-02 -2.57966293458753e-02 +-9.39393939393939e+00 -6.73760079004400e-01 2.58543044614024e-02 -4.12961616654669e-02 +-8.78787878787879e+00 -6.36634699427489e-01 1.93848671125434e-02 -5.74839914192587e-02 +-8.18181818181818e+00 -5.81874634591272e-01 1.36623501221776e-02 -7.45539130446945e-02 +-7.57575757575758e+00 -5.05150686435173e-01 1.05716894357738e-02 -8.64279283248293e-02 +-6.96969696969697e+00 -4.18595232643061e-01 9.10734541656171e-03 -9.50674159963851e-02 +-6.36363636363636e+00 -3.38986978205484e-01 7.90162668231047e-03 -9.99599652998083e-02 +-5.75757575757576e+00 -2.59840510197803e-01 7.41964713494604e-03 -1.04208933106189e-01 +-5.15151515151515e+00 -1.80988998184422e-01 7.14720887337387e-03 -1.07763832355698e-01 +-4.54545454545454e+00 -1.03071489415176e-01 6.95243839815077e-03 -1.10602747534693e-01 +-3.93939393939394e+00 -2.57708400834061e-02 6.84633480589618e-03 -1.12642875373749e-01 +-3.33333333333333e+00 5.06291120206322e-02 6.76146535162503e-03 -1.14417763754454e-01 +-2.72727272727273e+00 1.27032191349935e-01 6.66325312920406e-03 -1.16093113518882e-01 +-2.12121212121212e+00 2.02920139434825e-01 6.61583701230752e-03 -1.17866755340555e-01 +-1.51515151515152e+00 2.78307232368702e-01 6.59553135545088e-03 -1.19945517730907e-01 +-9.09090909090912e-01 3.52936192696077e-01 6.59403346409144e-03 -1.21944793137844e-01 +-3.03030303030302e-01 4.26320562661541e-01 6.64943771563519e-03 -1.23760507757517e-01 + 3.03030303030302e-01 4.99818577478435e-01 6.69818073560818e-03 -1.25508281414915e-01 + 9.09090909090912e-01 5.73376543665411e-01 6.69183344611623e-03 -1.27070496093681e-01 + 1.51515151515152e+00 6.46799556143286e-01 6.75524511750563e-03 -1.28538560457679e-01 + 2.12121212121212e+00 7.20154880913483e-01 6.84155940142869e-03 -1.29906010197320e-01 + 2.72727272727273e+00 7.93147472633957e-01 6.97678572298154e-03 -1.31165648253112e-01 + 3.33333333333333e+00 8.65616018748002e-01 7.10739240893340e-03 -1.32288860283965e-01 + 3.93939393939394e+00 9.37648112828365e-01 7.24422887006074e-03 -1.33365853998558e-01 + 4.54545454545455e+00 1.00910358732349e+00 7.39983874217581e-03 -1.34215184053867e-01 + 5.15151515151515e+00 1.08005492256340e+00 7.58558750578516e-03 -1.34976127499023e-01 + 5.75757575757576e+00 1.14960510771521e+00 7.88653428093343e-03 -1.35458436688932e-01 + 6.36363636363637e+00 1.21615416551218e+00 8.34153340579227e-03 -1.35456842953982e-01 + 6.96969696969697e+00 1.27828480587284e+00 9.10488091440775e-03 -1.34893951393780e-01 + 7.57575757575757e+00 1.32797468584652e+00 1.06845025707761e-02 -1.32377276048360e-01 + 8.18181818181818e+00 1.37107050025369e+00 1.21820686740787e-02 -1.29169553035756e-01 + 8.78787878787879e+00 1.40369513738070e+00 1.40255937471439e-02 -1.25043047898281e-01 + 9.39393939393939e+00 1.41709683794245e+00 1.92334681728973e-02 -1.22574062592608e-01 + 1.00000000000000e+01 1.41645872036543e+00 2.62062454721527e-02 -1.22372841879845e-01 + 1.06060606060606e+01 1.38657460264657e+00 3.26763717983368e-02 -1.21751932897855e-01 + 1.12121212121212e+01 1.36400259487080e+00 3.83098431246971e-02 -1.21315233753301e-01 + 1.18181818181818e+01 1.35688821281416e+00 4.60809911460502e-02 -1.19819418114883e-01 + 1.24242424242424e+01 1.34089573725963e+00 5.79456504379348e-02 -1.18207966359576e-01 + 1.30303030303030e+01 1.32223161769021e+00 7.00497051047743e-02 -1.17191325445144e-01 + 1.36363636363636e+01 1.29585304328532e+00 8.36737099489719e-02 -1.19176336444020e-01 + 1.42424242424242e+01 1.27550502164861e+00 9.56164211836313e-02 -1.21085843980632e-01 + 1.48484848484848e+01 1.26031280258829e+00 1.05038483493522e-01 -1.22965364533929e-01 + 1.54545454545455e+01 1.24817918569169e+00 1.13694141927813e-01 -1.24250481062770e-01 + 1.60606060606061e+01 1.23659506592632e+00 1.22025178103146e-01 -1.25145411447740e-01 + 1.66666666666667e+01 1.22112439263804e+00 1.29733166820717e-01 -1.25238540045732e-01 + 1.72727272727273e+01 1.20372487247866e+00 1.38204896553668e-01 -1.25906002656970e-01 + 1.78787878787879e+01 1.18372803528903e+00 1.47610097212096e-01 -1.27281617838633e-01 + 1.84848484848485e+01 1.17400652248468e+00 1.57673262028419e-01 -1.29411130817857e-01 + 1.90909090909091e+01 1.16668752601417e+00 1.67940267889330e-01 -1.32031130540839e-01 + 1.96969696969697e+01 1.15802631000889e+00 1.78430476422176e-01 -1.36362103439965e-01 + 2.03030303030303e+01 1.14825771518914e+00 1.89897612594817e-01 -1.41556026190695e-01 + 2.09090909090909e+01 1.14104652446381e+00 2.02341731675555e-01 -1.47700684953726e-01 + 2.15151515151515e+01 1.13734479071489e+00 2.14785850756294e-01 -1.53871949597139e-01 + 2.21212121212121e+01 1.13089213779505e+00 2.26985477991913e-01 -1.60089208840245e-01 + 2.27272727272727e+01 1.12204977020079e+00 2.38207389411154e-01 -1.66490399157068e-01 + 2.33333333333333e+01 1.11320740260652e+00 2.49429300830395e-01 -1.72914291335786e-01 + 2.39393939393939e+01 1.10436503501225e+00 2.60651212249636e-01 -1.79425078294699e-01 + 2.45454545454545e+01 1.09671055899213e+00 2.72273742523902e-01 -1.85035919192311e-01 + 2.51515151515151e+01 1.08918806808547e+00 2.83940785046750e-01 -1.90542124148107e-01 + 2.57575757575758e+01 1.08166557717880e+00 2.95607827569598e-01 -1.96042910921405e-01 + 2.63636363636364e+01 1.07497654178085e+00 3.07666550963613e-01 -2.01108325476125e-01 + 2.69696969696970e+01 1.06884322973428e+00 3.19986435516351e-01 -2.05883282560142e-01 + 2.75757575757576e+01 1.06270991768772e+00 3.32306320069088e-01 -2.10654825089128e-01 + 2.81818181818182e+01 1.05685002491795e+00 3.44803723925826e-01 -2.15273237837376e-01 + 2.87878787878788e+01 1.05162805573452e+00 3.57715303960546e-01 -2.19539750840593e-01 + 2.93939393939394e+01 1.04640608655109e+00 3.70626883995265e-01 -2.23804015238057e-01 + 3.00000000000000e+01 1.04118411736767e+00 3.83538464029985e-01 -2.28066012025690e-01 + 3.30000000000000e+01 1.01848589840269e+00 4.50834279245390e-01 -2.46961206869889e-01 + 3.60000000000000e+01 9.96808909621796e-01 5.20958260992169e-01 -2.64359434793424e-01 + 3.90000000000000e+01 9.74106328942832e-01 5.93758161928647e-01 -2.80547282143363e-01 + 4.20000000000000e+01 9.48041157048807e-01 6.68214525810192e-01 -2.95913378121082e-01 + 4.50000000000000e+01 9.20743807181201e-01 7.43083281614397e-01 -3.11045980331182e-01 + 4.80000000000000e+01 8.86477884798320e-01 8.17875803160575e-01 -3.25477187585035e-01 + 5.10000000000000e+01 8.48118712495052e-01 8.91114285364008e-01 -3.39620328980538e-01 + 5.40000000000000e+01 8.01572777205266e-01 9.61244588976293e-01 -3.53193383869185e-01 + 5.70000000000000e+01 7.55026776527843e-01 1.03137413224544e+00 -3.66763595394112e-01 + 6.00000000000000e+01 7.08480743156850e-01 1.10150329534591e+00 -3.80331070227688e-01 + 6.30000000000000e+01 6.46295216458993e-01 1.15838046907205e+00 -3.92574049260776e-01 + 6.60000000000000e+01 5.84109443410254e-01 1.21525752920760e+00 -4.04815652134246e-01 + 6.90000000000000e+01 5.21923445770576e-01 1.27213458934316e+00 -4.17055794570706e-01 + 7.20000000000000e+01 4.52335480264868e-01 1.31553653901342e+00 -4.28053298659701e-01 + 7.50000000000000e+01 3.79046682354287e-01 1.35220120930450e+00 -4.38429394598601e-01 + 7.80000000000000e+01 3.05756781496138e-01 1.38886629974350e+00 -4.48804321680909e-01 + 8.10000000000000e+01 2.31207286740326e-01 1.41728453792232e+00 -4.58322686478495e-01 + 8.40000000000000e+01 1.54138691138483e-01 1.42920964084012e+00 -4.66128863644011e-01 + 8.70000000000000e+01 7.70693031576111e-02 1.44113483485913e+00 -4.73934397736458e-01 + 9.00000000000000e+01 -3.36708373039042e-07 1.45305992557158e+00 -4.81739438540332e-01 + 9.30000000000000e+01 -5.39485757284989e-02 1.44113482265378e+00 -4.85914001849487e-01 + 9.60000000000000e+01 -1.07896933109837e-01 1.42920967418575e+00 -4.89748119107250e-01 + 9.90000000000000e+01 -1.61845527217882e-01 1.41728443461560e+00 -4.93557987335880e-01 + 1.02000000000000e+02 -2.14030046275947e-01 1.38886612216712e+00 -4.94077965350438e-01 + 1.05000000000000e+02 -2.65332546911451e-01 1.35220145187604e+00 -4.92944920029321e-01 + 1.08000000000000e+02 -3.16635035430310e-01 1.31553636143885e+00 -4.92245915161826e-01 + 1.11000000000000e+02 -3.65346571871470e-01 1.27213409662221e+00 -4.90545503515274e-01 + 1.14000000000000e+02 -4.08876283070132e-01 1.21525768824574e+00 -4.86317993590270e-01 + 1.17000000000000e+02 -4.52406347782145e-01 1.15838084536770e+00 -4.82090051371639e-01 + 1.20000000000000e+02 -4.95936567846409e-01 1.10150375931678e+00 -4.77861889492743e-01 + 1.23000000000000e+02 -5.28518625044671e-01 1.03137459621631e+00 -4.71840511315534e-01 + 1.26000000000000e+02 -5.61100704888174e-01 9.61245052954708e-01 -4.65818976558725e-01 + 1.29000000000000e+02 -5.93682830023854e-01 8.91114749342422e-01 -4.59682348306178e-01 + 1.32000000000000e+02 -6.18908433527060e-01 8.17850698969113e-01 -4.54312399338742e-01 + 1.35000000000000e+02 -6.40455784934676e-01 7.43019778936259e-01 -4.49364062058548e-01 + 1.38000000000000e+02 -6.62002920890116e-01 6.68189421819664e-01 -4.44415444601716e-01 + 1.41000000000000e+02 -6.81613839477788e-01 5.94826066587770e-01 -4.41694691787043e-01 + 1.44000000000000e+02 -6.97352307618548e-01 5.24396727029221e-01 -4.43429686334623e-01 + 1.47000000000000e+02 -7.13090480114408e-01 4.53967729130364e-01 -4.45164688600493e-01 + 1.50000000000000e+02 -7.28828504793094e-01 3.83538902055256e-01 -4.46899694725369e-01 + 1.53000000000000e+02 -7.38250770119389e-01 3.28279710588330e-01 -4.64997809025810e-01 + 1.56000000000000e+02 -7.46093272753856e-01 2.73020555057756e-01 -4.81308204600343e-01 + 1.59000000000000e+02 -7.53707623020192e-01 2.17761400703393e-01 -5.00902986460923e-01 + 1.62000000000000e+02 -6.88143441383303e-01 1.78536848703957e-01 -5.06252966573203e-01 + 1.65000000000000e+02 -5.85650053883360e-01 1.47329733490110e-01 -5.03908411641623e-01 + 1.68000000000000e+02 -4.83157240864670e-01 1.16122375886185e-01 -5.01563371955391e-01 + 1.71000000000000e+02 -3.73345827031091e-01 8.57857267499245e-02 -4.50000513056908e-01 + 1.74000000000000e+02 -2.48896869884329e-01 5.71905351997449e-02 -2.99999717902353e-01 + 1.77000000000000e+02 -1.23881031171309e-01 4.71151394500337e-02 -1.04090643424068e-01 + 1.80000000000000e+02 0.00000000000000e+00 4.63087218239101e-02 1.12294918356446e-01 diff --git a/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_24.dat b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_24.dat new file mode 100644 index 00000000..59306058 --- /dev/null +++ b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_24.dat @@ -0,0 +1,254 @@ +! ------------ AirfoilInfo v1.01.x Input File ---------------------------------- +! AeroElasticSE FAST driver +! line +! line +! ------------------------------------------------------------------------------ +DEFAULT InterpOrd ! Interpolation order to use for quasi-steady table lookup {1=linear; 3=cubic spline; "default"} [default=3] +1 NonDimArea ! The non-dimensional area of the airfoil (area/chord^2) (set to 1.0 if unsure or unneeded) +@"NREL-2p8-127_AF24_Coords.txt" NumCoords ! The number of coordinates in the airfoil shape file. Set to zero if coordinates not included. +AF24_BL.txt BL_file ! The file name including the boundary layer characteristics of the profile. Ignored if the aeroacoustic module is not called. +1 NumTabs ! Number of airfoil tables in this file. Each table must have lines for Re and Ctrl. +! ------------------------------------------------------------------------------ +! data for table 1 +! ------------------------------------------------------------------------------ +6.000000 Re ! Reynolds number in millions +0 Ctrl ! Control setting (must be 0 for current AirfoilInfo) +True InclUAdata ! Is unsteady aerodynamics data included in this table? If TRUE, then include 30 UA coefficients below this line +!........................................ +-3.881348 alpha0 ! 0-lift angle of attack, depends on airfoil. +10.220205 alpha1 ! Angle of attack at f=0.7, (approximately the stall angle) for AOA>alpha0. (deg) +-10.228661 alpha2 ! Angle of attack at f=0.7, (approximately the stall angle) for AOA1] +0.000000 S2 ! Constant in the f curve best-fit for AOA> alpha1; by definition it depends on the airfoil. [ignored if UAMod<>1] +0.000000 S3 ! Constant in the f curve best-fit for alpha2<=AOA< alpha0; by definition it depends on the airfoil. [ignored if UAMod<>1] +0.000000 S4 ! Constant in the f curve best-fit for AOA< alpha2; by definition it depends on the airfoil. [ignored if UAMod<>1] +1.447089 Cn1 ! Critical value of C0n at leading edge separation. It should be extracted from airfoil data at a given Mach and Reynolds number. It can be calculated from the static value of Cn at either the break in the pitching moment or the loss of chord force at the onset of stall. It is close to the condition of maximum lift of the airfoil at low Mach numbers. +-0.835242 Cn2 ! As Cn1 for negative AOAs. +Default St_sh ! Strouhal's shedding frequency constant. [default = 0.19] +0.006598 Cd0 ! 2D drag coefficient value at 0-lift. +-0.113186 Cm0 ! 2D pitching moment coefficient about 1/4-chord location, at 0-lift, positive if nose up. [If the aerodynamics coefficients table does not include a column for Cm, this needs to be set to 0.0] +0.000000 k0 ! Constant in the \hat(x)_cp curve best-fit; = (\hat(x)_AC-0.25). [ignored if UAMod<>1] +0.000000 k1 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k2 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k3 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k1_hat ! Constant in the expression of Cc due to leading edge vortex effects. [ignored if UAMod<>1] +Default x_cp_bar ! Constant in the expression of \hat(x)_cp^v. [ignored if UAMod<>1, default = 0.2] +Default UACutout ! Angle of attack above which unsteady aerodynamics are disabled (deg). [Specifying the string "Default" sets UACutout to 45 degrees] +Default filtCutOff ! Cut-off frequency (-3 dB corner frequency) for low-pass filtering the AoA input to UA, as well as the 1st and 2nd derivatives (Hz) [default = 20] +!........................................ +! Table of aerodynamics coefficients +200 NumAlf ! Number of data lines in the following table +! Alpha Cl Cd Cm +! (deg) (-) (-) (-) +-1.80000000000000e+02 0.00000000000000e+00 4.20239297897650e-02 1.57138208863316e-01 +-1.77000000000000e+02 1.40632365655801e-01 4.20239297897650e-02 1.82737995898986e-01 +-1.74000000000000e+02 2.82553053900608e-01 5.04286683283111e-02 2.39999774321882e-01 +-1.71000000000000e+02 4.23830336360153e-01 7.56431598642469e-02 3.60000410445527e-01 +-1.68000000000000e+02 5.34869114486967e-01 1.04245693608263e-01 3.04280258541825e-01 +-1.65000000000000e+02 6.30788993375323e-01 1.34542208912873e-01 1.60701763545007e-01 +-1.62000000000000e+02 7.26709994336859e-01 1.64838896980479e-01 1.71214488498863e-02 +-1.59000000000000e+02 7.84071397760670e-01 2.04002209021424e-01 -7.41764661492530e-02 +-1.56000000000000e+02 7.64500626823811e-01 2.60898469061760e-01 -6.11103531608993e-02 +-1.53000000000000e+02 7.44806596412559e-01 3.17794763757350e-01 -4.80087218730144e-02 +-1.50000000000000e+02 7.24801607355001e-01 3.74691108028256e-01 -3.36803071761103e-02 +-1.47000000000000e+02 7.09536340567078e-01 4.45426278146463e-01 -1.81789006503532e-02 +-1.44000000000000e+02 6.94270972610212e-01 5.16161667949901e-01 -2.67735864084869e-03 +-1.41000000000000e+02 6.79005402308234e-01 5.86897497139490e-01 1.25267866649444e-02 +-1.38000000000000e+02 6.59752709771772e-01 6.60614800800240e-01 2.78426345762092e-02 +-1.35000000000000e+02 6.38506464206380e-01 7.35822835648326e-01 4.32768039375504e-02 +-1.32000000000000e+02 6.17259998089925e-01 8.11031580816670e-01 5.87121989579576e-02 +-1.29000000000000e+02 5.92302309505059e-01 8.84693447887175e-01 7.43012013825991e-02 +-1.26000000000000e+02 5.59922158385802e-01 9.55261551412121e-01 9.01959583834699e-02 +-1.23000000000000e+02 5.27541955630656e-01 1.02582880155467e+00 1.06091386661389e-01 +-1.20000000000000e+02 4.95161727058530e-01 1.09639562502197e+00 1.21987354023941e-01 +-1.17000000000000e+02 4.51763647235390e-01 1.15375704715292e+00 1.37121497118599e-01 +-1.14000000000000e+02 4.08365719274480e-01 1.21111822435222e+00 1.52255604498479e-01 +-1.11000000000000e+02 3.64968138119650e-01 1.26847896334996e+00 1.67389419062474e-01 +-1.08000000000000e+02 3.16351063621799e-01 1.31238637614246e+00 1.80934520183943e-01 +-1.05000000000000e+02 2.65124202709162e-01 1.34956702339128e+00 1.93694959616565e-01 +-1.02000000000000e+02 2.13897328813262e-01 1.38674724458622e+00 2.06454767299050e-01 +-9.90000000000000e+01 1.61771435376163e-01 1.41568677594618e+00 2.17866871578471e-01 +-9.60000000000000e+01 1.07847463915400e-01 1.42814457068853e+00 2.26583332591711e-01 +-9.30000000000000e+01 5.39238186798111e-02 1.44060227026035e+00 2.35299390910874e-01 +-9.00000000000000e+01 3.36553857038623e-07 1.45305992224777e+00 2.44015288398801e-01 +-8.70000000000000e+01 -5.39237634891041e-02 1.44060228301076e+00 2.47951662237116e-01 +-8.40000000000000e+01 -1.07847614698837e-01 1.42814453585376e+00 2.51892083934148e-01 +-8.10000000000000e+01 -1.61770968240210e-01 1.41568688386634e+00 2.55836458741642e-01 +-7.80000000000000e+01 -2.13897080708414e-01 1.38674742465954e+00 2.56509498151152e-01 +-7.50000000000000e+01 -2.65124541622777e-01 1.34956677740889e+00 2.55548599134485e-01 +-7.20000000000000e+01 -3.16350815522372e-01 1.31238655621395e+00 2.54590706463430e-01 +-6.90000000000000e+01 -3.64967762165930e-01 1.26847946026667e+00 2.52383955015723e-01 +-6.60000000000000e+01 -4.08365840623045e-01 1.21111806395980e+00 2.47675595024712e-01 +-6.30000000000000e+01 -4.51763934354955e-01 1.15375666765293e+00 2.42970286422080e-01 +-6.00000000000000e+01 -4.95161941284426e-01 1.09639515815556e+00 2.38268000115941e-01 +-5.70000000000000e+01 -5.27542169856552e-01 1.02582833468826e+00 2.31806506435537e-01 +-5.40000000000000e+01 -5.59922372611185e-01 9.55261084537245e-01 2.25347767167551e-01 +-5.10000000000000e+01 -5.92302523730443e-01 8.84692981012299e-01 2.18891521602934e-01 +-4.80000000000000e+01 -6.18906352581358e-01 8.11045812993734e-01 2.12734135842278e-01 +-4.50000000000000e+01 -6.42622113131780e-01 7.35859162213287e-01 2.06728126759377e-01 +-4.20000000000000e+01 -6.61399051379004e-01 6.60629032861292e-01 2.02335706314512e-01 +-3.90000000000000e+01 -6.79295197663792e-01 5.85819587866301e-01 1.98564860746646e-01 +-3.60000000000000e+01 -6.94777748193317e-01 5.12692903825368e-01 1.97017430019138e-01 +-3.30000000000000e+01 -7.09467742340985e-01 4.42267305815927e-01 1.98629231822253e-01 +-3.00000000000000e+01 -7.24801717703120e-01 3.74690668178350e-01 2.03759075670758e-01 +-2.93939393939394e+01 -7.28326530814462e-01 3.61726727869206e-01 2.05744738406902e-01 +-2.87878787878788e+01 -7.31851343925804e-01 3.48762787560061e-01 2.07730401143047e-01 +-2.81818181818182e+01 -7.35376157037146e-01 3.35798847250917e-01 2.09716063879191e-01 +-2.75757575757576e+01 -7.39335418161425e-01 3.23251387701133e-01 2.12376937449998e-01 +-2.69696969696970e+01 -7.43480887264291e-01 3.10882435217812e-01 2.15327211917801e-01 +-2.63636363636364e+01 -7.47626356367156e-01 2.98513482734492e-01 2.18277486385603e-01 +-2.57575757575758e+01 -7.52151842029857e-01 2.86407040228379e-01 2.21732543995886e-01 +-2.51515151515151e+01 -7.57247263964635e-01 2.74694301506801e-01 2.25944658673781e-01 +-2.45454545454545e+01 -7.62342685899414e-01 2.62981562785224e-01 2.30156773351676e-01 +-2.39393939393939e+01 -7.67618823549025e-01 2.51338309217338e-01 2.34224184613365e-01 +-2.33333333333333e+01 -7.74521437619550e-01 2.40320435485340e-01 2.36989237113918e-01 +-2.27272727272727e+01 -7.81424051690076e-01 2.29302561753342e-01 2.39601565570627e-01 +-2.21212121212121e+01 -7.88326665760601e-01 2.18284688021344e-01 2.42470674291164e-01 +-2.15151515151515e+01 -7.95622047703425e-01 2.07577437194191e-01 2.45095428001552e-01 +-2.09090909090909e+01 -8.02604681726082e-01 1.96947862073894e-01 2.47624260079401e-01 +-2.03030303030303e+01 -8.09650349475145e-01 1.86318286953598e-01 2.50153092157250e-01 +-1.96969696969697e+01 -8.17637506447164e-01 1.75928434913981e-01 2.53560038839616e-01 +-1.90909090909091e+01 -8.26477015311138e-01 1.65778292393816e-01 2.57845050451215e-01 +-1.84848484848485e+01 -8.26084809962742e-01 1.55849503459699e-01 2.52897003259897e-01 +-1.78787878787879e+01 -8.23983493243247e-01 1.46076930679257e-01 2.45664651306383e-01 +-1.72727272727273e+01 -8.21570138202451e-01 1.37130650088349e-01 2.35566574130545e-01 +-1.66666666666667e+01 -8.12443964880370e-01 1.28220565266013e-01 2.18667326209765e-01 +-1.60606060606061e+01 -7.97844348659724e-01 1.19340921345769e-01 1.96202242311259e-01 +-1.54545454545455e+01 -7.84422413764076e-01 1.10579594948523e-01 1.73424826407758e-01 +-1.48484848484848e+01 -7.71787584327422e-01 1.01887960544163e-01 1.50473470711618e-01 +-1.42424242424242e+01 -7.61134965931686e-01 9.33387624500803e-02 1.27203383377638e-01 +-1.36363636363636e+01 -7.51019037969479e-01 8.48128124492238e-02 1.04178189645314e-01 +-1.30303030303030e+01 -7.41421130409000e-01 7.63034135314191e-02 8.11835234005733e-02 +-1.24242424242424e+01 -7.26117069582958e-01 6.77522789215004e-02 6.03315753701249e-02 +-1.18181818181818e+01 -7.09450417189115e-01 5.96236347309660e-02 4.00791186975229e-02 +-1.12121212121212e+01 -6.90082557893989e-01 5.06890203132416e-02 2.09663498148639e-02 +-1.06060606060606e+01 -6.69006785525034e-01 4.21875347068638e-02 1.31821761243166e-03 +-1.00000000000000e+01 -6.46973736816406e-01 3.40753735771777e-02 -1.86162729145852e-02 +-9.39393939393939e+00 -6.23566521153584e-01 2.66139202130595e-02 -3.84582682239768e-02 +-8.78787878787879e+00 -5.93143909692991e-01 1.97080621922025e-02 -5.81227331911647e-02 +-8.18181818181818e+00 -5.49437129950642e-01 1.36122296354314e-02 -7.73434792653389e-02 +-7.57575757575758e+00 -4.76129595933123e-01 1.04462591632936e-02 -9.01887084685705e-02 +-6.96969696969697e+00 -3.89923494054396e-01 8.96219583042148e-03 -9.89373513292037e-02 +-6.36363636363636e+00 -3.12270511910677e-01 7.65469409261513e-03 -1.02756750711562e-01 +-5.75757575757576e+00 -2.35244495718475e-01 7.20033215041447e-03 -1.06054556847806e-01 +-5.15151515151515e+00 -1.58611001142337e-01 6.92443690785538e-03 -1.08867710719892e-01 +-4.54545454545454e+00 -8.26264788487249e-02 6.71182503055839e-03 -1.11241902473054e-01 +-3.93939393939394e+00 -7.17505732470964e-03 6.60399736858371e-03 -1.13032741919541e-01 +-3.33333333333333e+00 6.77399244143484e-02 6.54568110870987e-03 -1.14632383709498e-01 +-2.72727272727273e+00 1.42670380661859e-01 6.46364824529083e-03 -1.16181617095474e-01 +-2.12121212121212e+00 2.17139817585866e-01 6.43953237954945e-03 -1.17766630428816e-01 +-1.51515151515152e+00 2.91428740135327e-01 6.42972618595009e-03 -1.19525590995757e-01 +-9.09090909090912e-01 3.65128859297927e-01 6.42967209033216e-03 -1.21282061863669e-01 +-3.03030303030302e-01 4.38105121735726e-01 6.47736400956553e-03 -1.22890854235333e-01 + 3.03030303030302e-01 5.11112071056141e-01 6.53139868052610e-03 -1.24460808318302e-01 + 9.09090909090912e-01 5.84048322897008e-01 6.52730920651946e-03 -1.25889751980391e-01 + 1.51515151515152e+00 6.56771187401434e-01 6.60828592671719e-03 -1.27205103311759e-01 + 2.12121212121212e+00 7.29431355319300e-01 6.66584266708599e-03 -1.28498098736987e-01 + 2.72727272727273e+00 8.01715099938977e-01 6.79410605892685e-03 -1.29703511469116e-01 + 3.33333333333333e+00 8.73667737101458e-01 6.92003913189438e-03 -1.30770162129486e-01 + 3.93939393939394e+00 9.45203779381055e-01 7.04950954145510e-03 -1.31831672743512e-01 + 4.54545454545455e+00 1.01616262246952e+00 7.18868096099871e-03 -1.32686207865223e-01 + 5.15151515151515e+00 1.08666504585964e+00 7.35805565558534e-03 -1.33484479795433e-01 + 5.75757575757576e+00 1.15589713891403e+00 7.65596176371924e-03 -1.34065604697579e-01 + 6.36363636363637e+00 1.22235143346160e+00 8.13782849850763e-03 -1.34188428144082e-01 + 6.96969696969697e+00 1.28381732514628e+00 9.00700508163636e-03 -1.33672116338428e-01 + 7.57575757575757e+00 1.33414824858160e+00 1.07028357691023e-02 -1.31358398670661e-01 + 8.18181818181818e+00 1.37921530349790e+00 1.23338548134546e-02 -1.28462440465876e-01 + 8.78787878787879e+00 1.41929596248767e+00 1.40314224567824e-02 -1.25079434784614e-01 + 9.39393939393939e+00 1.44895179840671e+00 1.73667127363230e-02 -1.22426571069460e-01 + 1.00000000000000e+01 1.46562058968523e+00 2.15076283531428e-02 -1.22080342259589e-01 + 1.06060606060606e+01 1.46482275209920e+00 2.56482444467929e-02 -1.21729653497994e-01 + 1.12121212121212e+01 1.46455008673655e+00 2.96173727205461e-02 -1.21654814919871e-01 + 1.18181818181818e+01 1.46787480330173e+00 3.84335406340759e-02 -1.21545340375698e-01 + 1.24242424242424e+01 1.44626795909455e+00 5.24745071699755e-02 -1.21745587084181e-01 + 1.30303030303030e+01 1.41548464258938e+00 6.65727041455837e-02 -1.22132303153946e-01 + 1.36363636363636e+01 1.37245053342376e+00 8.16057042391146e-02 -1.24136435674557e-01 + 1.42424242424242e+01 1.33537840735922e+00 9.41511245499718e-02 -1.25907093812210e-01 + 1.48484848484848e+01 1.30613659580939e+00 1.02967015650268e-01 -1.27351580700688e-01 + 1.54545454545455e+01 1.28553302955425e+00 1.11389370579920e-01 -1.28462528314075e-01 + 1.60606060606061e+01 1.26758424346921e+00 1.19644615010785e-01 -1.29390414755028e-01 + 1.66666666666667e+01 1.24771591748635e+00 1.27576133928679e-01 -1.29935088016977e-01 + 1.72727272727273e+01 1.22417688851766e+00 1.35896595584476e-01 -1.30758578064231e-01 + 1.78787878787879e+01 1.19608311119412e+00 1.44692436629616e-01 -1.31924607905431e-01 + 1.84848484848485e+01 1.18255480628068e+00 1.53780455374608e-01 -1.33460435656660e-01 + 1.90909090909091e+01 1.17242740863741e+00 1.63075826898732e-01 -1.35618139566060e-01 + 1.96969696969697e+01 1.16082579219221e+00 1.73132593582544e-01 -1.40776664039364e-01 + 2.03030303030303e+01 1.14904324940101e+00 1.83847599384671e-01 -1.46705689236554e-01 + 2.09090909090909e+01 1.13954137740033e+00 1.95220881544062e-01 -1.53430242057478e-01 + 2.15151515151515e+01 1.13215807394264e+00 2.06594163703453e-01 -1.60162370933814e-01 + 2.21212121212121e+01 1.12321585235273e+00 2.17919889776365e-01 -1.66781417553110e-01 + 2.27272727272727e+01 1.11431119585911e+00 2.29055440435074e-01 -1.72948251497559e-01 + 2.33333333333333e+01 1.10540653936549e+00 2.40190991093782e-01 -1.79121549823611e-01 + 2.39393939393939e+01 1.09650188287188e+00 2.51326541752491e-01 -1.85319591539483e-01 + 2.45454545454545e+01 1.08905958113101e+00 2.62981562785224e-01 -1.90662311121533e-01 + 2.51515151515151e+01 1.08177975975634e+00 2.74694301506801e-01 -1.95908674546375e-01 + 2.57575757575758e+01 1.07449993838168e+00 2.86407040228379e-01 -2.01153495137443e-01 + 2.63636363636364e+01 1.06803512793561e+00 2.98513482734492e-01 -2.05997699680956e-01 + 2.69696969696970e+01 1.06211374254334e+00 3.10882435217812e-01 -2.10574738593792e-01 + 2.75757575757576e+01 1.05619235715106e+00 3.23251387701133e-01 -2.15150805208106e-01 + 2.81818181818182e+01 1.05053677218194e+00 3.35798847250917e-01 -2.19587044062714e-01 + 2.87878787878788e+01 1.04550133499893e+00 3.48762787560062e-01 -2.23698575936724e-01 + 2.93939393939394e+01 1.04046589781592e+00 3.61726727869206e-01 -2.27809467517628e-01 + 3.00000000000000e+01 1.03543046063291e+00 3.74690668178350e-01 -2.31919713393992e-01 + 3.30000000000000e+01 1.01352784881378e+00 4.42267305815928e-01 -2.50242753909780e-01 + 3.60000000000000e+01 9.92539022396652e-01 5.12692903825368e-01 -2.67200657190209e-01 + 3.90000000000000e+01 9.70421727927888e-01 5.85819587866301e-01 -2.83055031736328e-01 + 4.20000000000000e+01 9.44855717457034e-01 6.60629032861292e-01 -2.98162017656836e-01 + 4.50000000000000e+01 9.18032014729747e-01 7.35859162213287e-01 -3.13059792814360e-01 + 4.80000000000000e+01 8.84152091109475e-01 8.11045812993735e-01 -3.27314348631916e-01 + 5.10000000000000e+01 8.46146395641528e-01 8.84692981012299e-01 -3.41300099207024e-01 + 5.40000000000000e+01 7.99888891241725e-01 9.55261084537245e-01 -3.54749948670230e-01 + 5.70000000000000e+01 7.53631324948729e-01 1.02582833468826e+00 -3.68198870181370e-01 + 6.00000000000000e+01 7.07373727709371e-01 1.09639515815556e+00 -3.81646953266444e-01 + 6.30000000000000e+01 6.45377123529131e-01 1.15375666765293e+00 -3.93810500184529e-01 + 6.60000000000000e+01 5.83380227301456e-01 1.21111806395980e+00 -4.05973624922660e-01 + 6.90000000000000e+01 5.21383016795821e-01 1.26847946026667e+00 -4.18136288721357e-01 + 7.20000000000000e+01 4.51929954630524e-01 1.31238655621395e+00 -4.29073410119878e-01 + 7.50000000000000e+01 3.78749119266611e-01 1.34956677740889e+00 -4.39397752827040e-01 + 7.80000000000000e+01 3.05567316722722e-01 1.38674742465954e+00 -4.49721404047000e-01 + 8.10000000000000e+01 2.31101650731069e-01 1.41568688386634e+00 -4.59194843301813e-01 + 8.40000000000000e+01 1.54068346468134e-01 1.42814453585376e+00 -4.66968167272936e-01 + 8.70000000000000e+01 7.70341547111549e-02 1.44060228301076e+00 -4.74741064431118e-01 + 9.00000000000000e+01 -3.36553857271529e-07 1.45305992224777e+00 -4.82513681756923e-01 + 9.30000000000000e+01 -5.39238186798111e-02 1.44060227026035e+00 -4.86445774433152e-01 + 9.60000000000000e+01 -1.07847463915400e-01 1.42814457068853e+00 -4.90136599398835e-01 + 9.90000000000000e+01 -1.61771435376163e-01 1.41568677594618e+00 -4.93816587592719e-01 + 1.02000000000000e+02 -2.13897328813262e-01 1.38674724458622e+00 -4.94219233630832e-01 + 1.05000000000000e+02 -2.65124202709163e-01 1.34956702339128e+00 -4.92980933650800e-01 + 1.08000000000000e+02 -3.16351063621799e-01 1.31238637614246e+00 -4.92020295748683e-01 + 1.11000000000000e+02 -3.64968138119650e-01 1.26847896334996e+00 -4.89968875412941e-01 + 1.14000000000000e+02 -4.08365719274481e-01 1.21111822435222e+00 -4.85404915466942e-01 + 1.17000000000000e+02 -4.51763647235390e-01 1.15375704715292e+00 -4.80840520657040e-01 + 1.20000000000000e+02 -4.95161727058530e-01 1.09639562502197e+00 -4.76275904937341e-01 + 1.23000000000000e+02 -5.27541955630656e-01 1.02582880155467e+00 -4.69936300398934e-01 + 1.26000000000000e+02 -5.59922158385802e-01 9.55261551412121e-01 -4.63596595371752e-01 + 1.29000000000000e+02 -5.92302309505059e-01 8.84693447887175e-01 -4.57173092895786e-01 + 1.32000000000000e+02 -6.17259998089925e-01 8.11031580816670e-01 -4.51522499663600e-01 + 1.35000000000000e+02 -6.38506464206380e-01 7.35822835648326e-01 -4.46286234978398e-01 + 1.38000000000000e+02 -6.59752709771772e-01 6.60614800800239e-01 -4.41049558888129e-01 + 1.41000000000000e+02 -6.79005402308234e-01 5.86897497139489e-01 -4.37992891545696e-01 + 1.44000000000000e+02 -6.94270972610212e-01 5.16161667949901e-01 -4.39296259388551e-01 + 1.47000000000000e+02 -7.09536340567078e-01 4.45426278146463e-01 -4.40599632549160e-01 + 1.50000000000000e+02 -7.24801607355002e-01 3.74691108028256e-01 -4.41903008368551e-01 + 1.53000000000000e+02 -7.42599775012969e-01 3.18083719972620e-01 -4.61912096005589e-01 + 1.56000000000000e+02 -7.59948055761679e-01 2.61476373424413e-01 -4.80619093073397e-01 + 1.59000000000000e+02 -7.77231254388352e-01 2.04869044049550e-01 -5.01430259356238e-01 + 1.62000000000000e+02 -7.14992328958953e-01 1.66181531595306e-01 -5.06906825399297e-01 + 1.65000000000000e+02 -6.12895046906355e-01 1.36454079153225e-01 -5.04317113525236e-01 + 1.68000000000000e+02 -5.10798334796026e-01 1.06726367365571e-01 -5.01726853472064e-01 + 1.71000000000000e+02 -3.98460526443325e-01 7.82171286957471e-02 -4.50000513056908e-01 + 1.74000000000000e+02 -2.65640047479978e-01 5.21448931484207e-02 -2.99999717902353e-01 + 1.77000000000000e+02 -1.32214471307849e-01 4.28782038261505e-02 -8.60306173704663e-02 + 1.80000000000000e+02 0.00000000000000e+00 4.20239297897650e-02 1.57138208863316e-01 diff --git a/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_25.dat b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_25.dat new file mode 100644 index 00000000..5afdaa9e --- /dev/null +++ b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_25.dat @@ -0,0 +1,254 @@ +! ------------ AirfoilInfo v1.01.x Input File ---------------------------------- +! AeroElasticSE FAST driver +! line +! line +! ------------------------------------------------------------------------------ +DEFAULT InterpOrd ! Interpolation order to use for quasi-steady table lookup {1=linear; 3=cubic spline; "default"} [default=3] +1 NonDimArea ! The non-dimensional area of the airfoil (area/chord^2) (set to 1.0 if unsure or unneeded) +@"NREL-2p8-127_AF25_Coords.txt" NumCoords ! The number of coordinates in the airfoil shape file. Set to zero if coordinates not included. +AF25_BL.txt BL_file ! The file name including the boundary layer characteristics of the profile. Ignored if the aeroacoustic module is not called. +1 NumTabs ! Number of airfoil tables in this file. Each table must have lines for Re and Ctrl. +! ------------------------------------------------------------------------------ +! data for table 1 +! ------------------------------------------------------------------------------ +6.000000 Re ! Reynolds number in millions +0 Ctrl ! Control setting (must be 0 for current AirfoilInfo) +True InclUAdata ! Is unsteady aerodynamics data included in this table? If TRUE, then include 30 UA coefficients below this line +!........................................ +-3.985066 alpha0 ! 0-lift angle of attack, depends on airfoil. +10.901847 alpha1 ! Angle of attack at f=0.7, (approximately the stall angle) for AOA>alpha0. (deg) +-9.933710 alpha2 ! Angle of attack at f=0.7, (approximately the stall angle) for AOA1] +0.000000 S2 ! Constant in the f curve best-fit for AOA> alpha1; by definition it depends on the airfoil. [ignored if UAMod<>1] +0.000000 S3 ! Constant in the f curve best-fit for alpha2<=AOA< alpha0; by definition it depends on the airfoil. [ignored if UAMod<>1] +0.000000 S4 ! Constant in the f curve best-fit for AOA< alpha2; by definition it depends on the airfoil. [ignored if UAMod<>1] +1.525701 Cn1 ! Critical value of C0n at leading edge separation. It should be extracted from airfoil data at a given Mach and Reynolds number. It can be calculated from the static value of Cn at either the break in the pitching moment or the loss of chord force at the onset of stall. It is close to the condition of maximum lift of the airfoil at low Mach numbers. +-0.831442 Cn2 ! As Cn1 for negative AOAs. +Default St_sh ! Strouhal's shedding frequency constant. [default = 0.19] +0.006462 Cd0 ! 2D drag coefficient value at 0-lift. +-0.113020 Cm0 ! 2D pitching moment coefficient about 1/4-chord location, at 0-lift, positive if nose up. [If the aerodynamics coefficients table does not include a column for Cm, this needs to be set to 0.0] +0.000000 k0 ! Constant in the \hat(x)_cp curve best-fit; = (\hat(x)_AC-0.25). [ignored if UAMod<>1] +0.000000 k1 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k2 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k3 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k1_hat ! Constant in the expression of Cc due to leading edge vortex effects. [ignored if UAMod<>1] +Default x_cp_bar ! Constant in the expression of \hat(x)_cp^v. [ignored if UAMod<>1, default = 0.2] +Default UACutout ! Angle of attack above which unsteady aerodynamics are disabled (deg). [Specifying the string "Default" sets UACutout to 45 degrees] +Default filtCutOff ! Cut-off frequency (-3 dB corner frequency) for low-pass filtering the AoA input to UA, as well as the 1st and 2nd derivatives (Hz) [default = 20] +!........................................ +! Table of aerodynamics coefficients +200 NumAlf ! Number of data lines in the following table +! Alpha Cl Cd Cm +! (deg) (-) (-) (-) +-1.80000000000000e+02 0.00000000000000e+00 3.88896555692602e-02 1.88439381768847e-01 +-1.77000000000000e+02 1.47085076149199e-01 3.88896555692602e-02 1.95344118058902e-01 +-1.74000000000000e+02 2.95517626324669e-01 4.66675428003909e-02 2.39999774321882e-01 +-1.71000000000000e+02 4.43277326259944e-01 7.00014598350941e-02 3.60000410445527e-01 +-1.68000000000000e+02 5.54775230424015e-01 9.73983403883863e-02 3.01232293768575e-01 +-1.65000000000000e+02 6.48142659931080e-01 1.26826655280201e-01 1.53081887186124e-01 +-1.62000000000000e+02 7.41511167200111e-01 1.56255257014288e-01 4.92973254323252e-03 +-1.59000000000000e+02 7.95540100041439e-01 1.95090056664802e-01 -8.77735264750430e-02 +-1.56000000000000e+02 7.70906453274779e-01 2.52736933946693e-01 -6.95971986266622e-02 +-1.53000000000000e+02 7.46262520842411e-01 3.10383851618106e-01 -5.14181728633164e-02 +-1.50000000000000e+02 7.21593009442639e-01 3.68030820520305e-01 -3.29558765859875e-02 +-1.47000000000000e+02 7.06704434537952e-01 4.38996595677444e-01 -1.77699153461743e-02 +-1.44000000000000e+02 6.91815791203747e-01 5.09962627721908e-01 -2.58387309352737e-03 +-1.41000000000000e+02 6.76927011005616e-01 5.80929173559367e-01 1.25078923479111e-02 +-1.38000000000000e+02 6.57959749926485e-01 6.54912916084138e-01 2.78036722103928e-02 +-1.35000000000000e+02 6.36953256680495e-01 7.30405250831853e-01 4.32213182447573e-02 +-1.32000000000000e+02 6.15946530568564e-01 8.05898408123014e-01 5.86392271290690e-02 +-1.29000000000000e+02 5.91202311709038e-01 8.79859730223254e-01 7.42120371863231e-02 +-1.26000000000000e+02 5.58983089632388e-01 9.50757374661013e-01 9.00945304458618e-02 +-1.23000000000000e+02 5.26763742046105e-01 1.02165410059611e+00 1.05977334757586e-01 +-1.20000000000000e+02 4.94544331707351e-01 1.09255036729705e+00 1.21860311283846e-01 +-1.17000000000000e+02 4.51251550031352e-01 1.15027637837716e+00 1.36984793751777e-01 +-1.14000000000000e+02 4.07958914685959e-01 1.20800214320170e+00 1.52109035307253e-01 +-1.11000000000000e+02 3.64666615300881e-01 1.26572746703947e+00 1.67232779609297e-01 +-1.08000000000000e+02 3.16124806380124e-01 1.31001514786660e+00 1.80754313543723e-01 +-1.05000000000000e+02 2.64958202719693e-01 1.34758390486677e+00 1.93478045106979e-01 +-1.02000000000000e+02 2.13791585385510e-01 1.38515223136569e+00 2.06201034298060e-01 +-9.90000000000000e+01 1.61712404778857e-01 1.41448412769015e+00 2.17579378110101e-01 +-9.60000000000000e+01 1.07808058099348e-01 1.42734280690261e+00 2.26268358308198e-01 +-9.30000000000000e+01 5.39041000974291e-02 1.44020138788200e+00 2.34956873390276e-01 +-9.00000000000000e+01 3.36430787768757e-07 1.45305991974575e+00 2.43645159242670e-01 +-8.70000000000000e+01 -5.39040449269041e-02 1.44020140104271e+00 2.47370504797659e-01 +-8.40000000000000e+01 -1.07808208827910e-01 1.42734277094688e+00 2.51096140965095e-01 +-8.10000000000000e+01 -1.61711937812911e-01 1.41448423908313e+00 2.54822075502831e-01 +-7.80000000000000e+01 -2.13791337572500e-01 1.38515241331870e+00 2.55274888244729e-01 +-7.50000000000000e+01 -2.64958541234654e-01 1.34758365631669e+00 2.54091230125327e-01 +-7.20000000000000e+01 -3.16124558572532e-01 1.31001532981777e+00 2.52907274609395e-01 +-6.90000000000000e+01 -3.64666240259218e-01 1.26572796711458e+00 2.50475282099874e-01 +-6.60000000000000e+01 -4.07959035740134e-01 1.20800198178982e+00 2.45546802529565e-01 +-6.30000000000000e+01 -4.51251836454270e-01 1.15027599646507e+00 2.40618557245280e-01 +-6.00000000000000e+01 -4.94544544869283e-01 1.09254989825106e+00 2.35690538113475e-01 +-5.70000000000000e+01 -5.26763955208036e-01 1.02165363155013e+00 2.29009342263561e-01 +-5.40000000000000e+01 -5.58983302793074e-01 9.50756905605912e-01 2.22328163344933e-01 +-5.10000000000000e+01 -5.91202524869724e-01 8.79859261168152e-01 2.15646770887959e-01 +-4.80000000000000e+01 -6.17609187893117e-01 8.05904457214662e-01 2.09254779518151e-01 +-4.50000000000000e+01 -6.41109664805937e-01 7.30421122636189e-01 2.03007644172430e-01 +-4.20000000000000e+01 -6.59622394239239e-01 6.54918965123690e-01 1.98342023604304e-01 +-3.90000000000000e+01 -6.77240098048986e-01 5.79843727554838e-01 1.94293653388780e-01 +-3.60000000000000e+01 -6.92396015978899e-01 5.06471062583234e-01 1.92463840058657e-01 +-3.30000000000000e+01 -7.06701742382219e-01 4.35818415197548e-01 1.93734767779497e-01 +-3.00000000000000e+01 -7.21593116705023e-01 3.68030379296879e-01 1.98453590087422e-01 +-2.93939393939394e+01 -7.25013851405679e-01 3.55027024133188e-01 2.00336203048920e-01 +-2.87878787878788e+01 -7.28434586106336e-01 3.42023668969498e-01 2.02218816010418e-01 +-2.81818181818182e+01 -7.31855320806992e-01 3.29020313805808e-01 2.04101428971916e-01 +-2.75757575757576e+01 -7.35700687071979e-01 3.16435173390334e-01 2.06644209454419e-01 +-2.69696969696970e+01 -7.39728053905235e-01 3.04029283243158e-01 2.09469943146406e-01 +-2.63636363636364e+01 -7.43755420738490e-01 2.91623393095983e-01 2.12295676838393e-01 +-2.57575757575758e+01 -7.48155857417494e-01 2.79481029799510e-01 2.15614520779263e-01 +-2.51515151515151e+01 -7.53115811916466e-01 2.67733895360822e-01 2.19672915167868e-01 +-2.45454545454545e+01 -7.58075766415437e-01 2.55986760922134e-01 2.23731309556473e-01 +-2.39393939393939e+01 -7.63184374708742e-01 2.44310701465517e-01 2.27866482494864e-01 +-2.33333333333333e+01 -7.69630895931130e-01 2.33274330608002e-01 2.32692677246016e-01 +-2.27272727272727e+01 -7.76077417153518e-01 2.22237959750487e-01 2.37506340633904e-01 +-2.21212121212121e+01 -7.82523938375906e-01 2.11201588892972e-01 2.42358034603878e-01 +-2.15151515151515e+01 -7.90135337461922e-01 2.00684998703353e-01 2.48462729786897e-01 +-2.09090909090909e+01 -7.98004310296648e-01 1.90298387115310e-01 2.54903342970304e-01 +-2.03030303030303e+01 -8.05878455195337e-01 1.79911775527268e-01 2.61343956153712e-01 +-1.96969696969697e+01 -8.14697917585567e-01 1.69812568423152e-01 2.68837595176999e-01 +-1.90909090909091e+01 -8.24455334435024e-01 1.60000749544382e-01 2.77384200470083e-01 +-1.84848484848485e+01 -8.23371484569383e-01 1.50522208073122e-01 2.74858417075755e-01 +-1.78787878787879e+01 -8.20283137594642e-01 1.41330694311538e-01 2.69517114356924e-01 +-1.72727272727273e+01 -8.16827722657021e-01 1.33081595034303e-01 2.60706462733926e-01 +-1.66666666666667e+01 -8.05487645465897e-01 1.24835482427222e-01 2.43743487370455e-01 +-1.60606060606061e+01 -7.87698090979399e-01 1.16591881249401e-01 2.20110391522602e-01 +-1.54545454545455e+01 -7.70279194203751e-01 1.08379515150144e-01 1.96405027014696e-01 +-1.48484848484848e+01 -7.53095337434051e-01 1.00185501796409e-01 1.72659305608295e-01 +-1.42424242424242e+01 -7.36494264951863e-01 9.20339115415058e-02 1.48824706874429e-01 +-1.36363636363636e+01 -7.20003204011376e-01 8.38888551728098e-02 1.25023839281306e-01 +-1.30303030303030e+01 -7.03596374099641e-01 7.57475802314855e-02 1.01231760751629e-01 +-1.24242424242424e+01 -6.85592076723291e-01 6.76111043119601e-02 7.80448576791677e-02 +-1.18181818181818e+01 -6.67194751585540e-01 5.96056150740760e-02 5.50235291976979e-02 +-1.12121212121212e+01 -6.48063815783503e-01 5.13317377912542e-02 3.23188744507143e-02 +-1.06060606060606e+01 -6.28468277340486e-01 4.31836623215413e-02 9.45993928821119e-03 +-1.00000000000000e+01 -6.08620538268602e-01 3.51540278791994e-02 -1.34796433221792e-02 +-9.39393939393939e+00 -5.88452257587033e-01 2.73199794208228e-02 -3.63905317831286e-02 +-8.78787878787879e+00 -5.62689873667493e-01 2.00084704728355e-02 -5.85506772245690e-02 +-8.18181818181818e+00 -5.26523769001160e-01 1.35978263788546e-02 -7.93058161363485e-02 +-7.57575757575758e+00 -4.55695305492732e-01 1.04092109922848e-02 -9.28284077848926e-02 +-6.96969696969697e+00 -3.69845487410935e-01 8.91871368739218e-03 -1.01630482628221e-01 +-6.36363636363636e+00 -2.93598733915834e-01 7.52845137064097e-03 -1.04647217860029e-01 +-5.75757575757576e+00 -2.18105319246992e-01 7.08800169590747e-03 -1.07214517170429e-01 +-5.15151515151515e+00 -1.43086395099137e-01 6.80050156749210e-03 -1.09441582594168e-01 +-4.54545454545454e+00 -6.85129984815250e-02 6.56750484797770e-03 -1.11442618030446e-01 +-3.93939393939394e+00 5.58385912432804e-03 6.45301670656877e-03 -1.13148191085356e-01 +-3.33333333333333e+00 7.94070262060676e-02 6.41289348325262e-03 -1.14695006520256e-01 +-2.72727272727273e+00 1.53241011838806e-01 6.34203948696765e-03 -1.16207049641120e-01 +-2.12121212121212e+00 2.26643908165568e-01 6.33526268400175e-03 -1.17673564802273e-01 +-1.51515151515152e+00 3.00105384199722e-01 6.33260375138770e-03 -1.19135271104034e-01 +-9.09090909090912e-01 3.73112750667490e-01 6.33272155108629e-03 -1.20666056314306e-01 +-3.03030303030302e-01 4.45821550130321e-01 6.37447853784405e-03 -1.22082515446199e-01 + 3.03030303030302e-01 5.18490342544224e-01 6.43313505799646e-03 -1.23487187085283e-01 + 9.09090909090912e-01 5.90981181373800e-01 6.43182319665414e-03 -1.24792255974836e-01 + 1.51515151515152e+00 6.63194082651710e-01 6.52639345810673e-03 -1.25965661272832e-01 + 2.12121212121212e+00 7.35342582721669e-01 6.56033089540737e-03 -1.27200682447364e-01 + 2.72727272727273e+00 8.07087488554538e-01 6.68351242329311e-03 -1.28376340413356e-01 + 3.33333333333333e+00 8.78653932202791e-01 6.80603711634661e-03 -1.29410676299065e-01 + 3.93939393939394e+00 9.49821767187520e-01 6.92963005547727e-03 -1.30468108847082e-01 + 4.54545454545455e+00 1.02040859265783e+00 7.05596856935910e-03 -1.31334420191275e-01 + 5.15151515151515e+00 1.09057426257294e+00 7.21258284329372e-03 -1.32167739152710e-01 + 5.75757575757576e+00 1.15956993076019e+00 7.50770133128459e-03 -1.32829150435812e-01 + 6.36363636363637e+00 1.22598231576016e+00 8.00921749308073e-03 -1.33054200393040e-01 + 6.96969696969697e+00 1.28698208452707e+00 8.95907167395873e-03 -1.32588516874154e-01 + 7.57575757575757e+00 1.33798080221868e+00 1.07198763892550e-02 -1.30460457192223e-01 + 8.18181818181818e+00 1.38474488602779e+00 1.24584314382430e-02 -1.27836892595172e-01 + 8.78787878787879e+00 1.43030567824273e+00 1.40331639261087e-02 -1.25090100383291e-01 + 9.39393939393939e+00 1.47200490845414e+00 1.59305690309036e-02 -1.22289478404177e-01 + 1.00000000000000e+01 1.50215101421504e+00 1.79091658579838e-02 -1.21813999638841e-01 + 1.06060606060606e+01 1.52370646388859e+00 2.02673536853439e-02 -1.21708944902389e-01 + 1.12121212121212e+01 1.54059319776331e+00 2.29572858937563e-02 -1.21848482617505e-01 + 1.18181818181818e+01 1.55195059906285e+00 3.24577496194005e-02 -1.22761051253168e-01 + 1.24242424242424e+01 1.52438898981163e+00 4.81678475665162e-02 -1.24233830041100e-01 + 1.30303030303030e+01 1.48202855383678e+00 6.38795341948320e-02 -1.25730475238576e-01 + 1.36363636363636e+01 1.42634733955077e+00 7.98865843582198e-02 -1.27696791571033e-01 + 1.42424242424242e+01 1.37740933666151e+00 9.28335727033232e-02 -1.29317173288097e-01 + 1.48484848484848e+01 1.33848755611934e+00 1.01192691262027e-01 -1.30420940714982e-01 + 1.54545454545455e+01 1.31190755280546e+00 1.09441241406769e-01 -1.31424351641477e-01 + 1.60606060606061e+01 1.28938235719693e+00 1.17642799704135e-01 -1.32380797174879e-01 + 1.66666666666667e+01 1.26634018563845e+00 1.25753041098846e-01 -1.33237196626024e-01 + 1.72727272727273e+01 1.23834102937778e+00 1.33971665700699e-01 -1.34168012171228e-01 + 1.78787878787879e+01 1.20427767029161e+00 1.42322760041168e-01 -1.35189926091386e-01 + 1.84848484848485e+01 1.18799320204888e+00 1.50716604683360e-01 -1.36311946607811e-01 + 1.90909090909091e+01 1.17586795447335e+00 1.59325448714249e-01 -1.38145765919180e-01 + 1.96969696969697e+01 1.16211889516567e+00 1.69092448832339e-01 -1.43872565373133e-01 + 2.03030303030303e+01 1.14927412966545e+00 1.79265230696872e-01 -1.50302804965374e-01 + 2.09090909090909e+01 1.13814235040425e+00 1.89843817264378e-01 -1.57438574430759e-01 + 2.15151515151515e+01 1.12766323714321e+00 2.00422403831884e-01 -1.64574965529124e-01 + 2.21212121212121e+01 1.11706175944146e+00 2.11099174825611e-01 -1.71481480893725e-01 + 2.27272727272727e+01 1.10811964282661e+00 2.22168582499681e-01 -1.77468729848466e-01 + 2.33333333333333e+01 1.09917752621176e+00 2.33237990173751e-01 -1.83456509220763e-01 + 2.39393939393939e+01 1.09023540959691e+00 2.44307397847821e-01 -1.89446318845786e-01 + 2.45454545454545e+01 1.08296339319592e+00 2.55986760922134e-01 -1.94609075142135e-01 + 2.51515151515151e+01 1.07587693949360e+00 2.67733895360822e-01 -1.99679830094226e-01 + 2.57575757575758e+01 1.06879048579128e+00 2.79481029799510e-01 -2.04750458453214e-01 + 2.63636363636364e+01 1.06250432210796e+00 2.91623393095983e-01 -2.09443081756152e-01 + 2.69696969696970e+01 1.05675176801362e+00 3.04029283243158e-01 -2.13883658690320e-01 + 2.75757575757576e+01 1.05099921391928e+00 3.16435173390334e-01 -2.18324155845132e-01 + 2.81818181818182e+01 1.04550641150444e+00 3.29020313805808e-01 -2.22633305796399e-01 + 2.87878787878788e+01 1.04061964435123e+00 3.42023668969498e-01 -2.26636130753221e-01 + 2.93939393939394e+01 1.03573287719801e+00 3.55027024133188e-01 -2.30638903172504e-01 + 3.00000000000000e+01 1.03084611004479e+00 3.68030379296879e-01 -2.34641622610226e-01 + 3.30000000000000e+01 1.00957720103222e+00 4.35818415197548e-01 -2.52554076744310e-01 + 3.60000000000000e+01 9.89136784047915e-01 5.06471062583234e-01 -2.69189950621486e-01 + 3.90000000000000e+01 9.67485857943026e-01 5.79843727554838e-01 -2.84796609339440e-01 + 4.20000000000000e+01 9.42317581833575e-01 6.54918965123690e-01 -2.99708632363911e-01 + 4.50000000000000e+01 9.15871274073578e-01 7.30421122636189e-01 -3.14427587661614e-01 + 4.80000000000000e+01 8.82298905466505e-01 8.05904457214662e-01 -3.28546217819211e-01 + 5.10000000000000e+01 8.44574853445087e-01 8.79859261168152e-01 -3.42409667613951e-01 + 5.40000000000000e+01 7.98547167692681e-01 9.50756905605912e-01 -3.55762881953981e-01 + 5.70000000000000e+01 7.52519428332893e-01 1.02165363155013e+00 -3.69115906506285e-01 + 6.00000000000000e+01 7.06491662169616e-01 1.09254989825106e+00 -3.82468805440661e-01 + 6.30000000000000e+01 6.44645585302091e-01 1.15027599646507e+00 -3.94568162072562e-01 + 6.60000000000000e+01 5.82799184406010e-01 1.20800198178982e+00 -4.06667464188502e-01 + 6.90000000000000e+01 5.20952406629315e-01 1.26572796711458e+00 -4.18766708415905e-01 + 7.20000000000000e+01 4.51606840984605e-01 1.31001532981777e+00 -4.29653737684229e-01 + 7.50000000000000e+01 3.78512034916063e-01 1.34758365631669e+00 -4.39934681615426e-01 + 7.80000000000000e+01 3.05416356557281e-01 1.38515241331870e+00 -4.50215120171697e-01 + 8.10000000000000e+01 2.31017478817704e-01 1.41448423908313e+00 -4.59650318443595e-01 + 8.40000000000000e+01 1.54012292275277e-01 1.42734277094688e+00 -4.67395115002369e-01 + 8.70000000000000e+01 7.70061458096371e-02 1.44020140104271e+00 -4.75139563653944e-01 + 9.00000000000000e+01 -3.36430788002270e-07 1.45305991974575e+00 -4.82883809780470e-01 + 9.30000000000000e+01 -5.39041000974291e-02 1.44020138788200e+00 -4.86608736540749e-01 + 9.60000000000000e+01 -1.07808058099348e-01 1.42734280690261e+00 -4.90252008054739e-01 + 9.90000000000000e+01 -1.61712404778857e-01 1.41448412769015e+00 -4.93892480524254e-01 + 1.02000000000000e+02 -2.13791585385510e-01 1.38515223136569e+00 -4.94260121211006e-01 + 1.05000000000000e+02 -2.64958202719694e-01 1.34758390486677e+00 -4.92991191870403e-01 + 1.08000000000000e+02 -3.16124806380124e-01 1.31001514786660e+00 -4.91810583583353e-01 + 1.11000000000000e+02 -3.64666615300881e-01 1.26572746703946e+00 -4.89432902349955e-01 + 1.14000000000000e+02 -4.07958914685959e-01 1.20800214320170e+00 -4.84556213718753e-01 + 1.17000000000000e+02 -4.51251550031352e-01 1.15027637837716e+00 -4.79679087834588e-01 + 1.20000000000000e+02 -4.94544331707352e-01 1.09255036729705e+00 -4.74801739879191e-01 + 1.23000000000000e+02 -5.26763742046105e-01 1.02165410059611e+00 -4.68166345460196e-01 + 1.26000000000000e+02 -5.58983089632388e-01 9.50757374661013e-01 -4.61530902688578e-01 + 1.29000000000000e+02 -5.91202311709038e-01 8.79859730223253e-01 -4.54866722642821e-01 + 1.32000000000000e+02 -6.15946530568564e-01 8.05898408123014e-01 -4.48999508288356e-01 + 1.35000000000000e+02 -6.36953256680495e-01 7.30405250831853e-01 -4.43540325890876e-01 + 1.38000000000000e+02 -6.57959749926485e-01 6.54912916084137e-01 -4.38080640740675e-01 + 1.41000000000000e+02 -6.76927011005616e-01 5.80929173559366e-01 -4.34763066576705e-01 + 1.44000000000000e+02 -6.91815791203747e-01 5.09962627721908e-01 -4.35729731767291e-01 + 1.47000000000000e+02 -7.06704434537952e-01 4.38996595677444e-01 -4.36696394806281e-01 + 1.50000000000000e+02 -7.21593009442639e-01 3.68030820520304e-01 -4.37663056769512e-01 + 1.53000000000000e+02 -7.45653551873146e-01 3.10460824874659e-01 -4.59043940512908e-01 + 1.56000000000000e+02 -7.69677114596338e-01 2.52890877728508e-01 -4.79978567205265e-01 + 1.59000000000000e+02 -7.93695164530012e-01 1.95320965150743e-01 -5.01585589518735e-01 + 1.62000000000000e+02 -7.33817088309609e-01 1.57056754662604e-01 -5.07101903167502e-01 + 1.65000000000000e+02 -6.31982311416204e-01 1.28445558491906e-01 -5.04439049525879e-01 + 1.68000000000000e+02 -5.30148101457015e-01 9.98340901844233e-02 -5.01775628100030e-01 + 1.71000000000000e+02 -4.16032857149841e-01 7.26838423842623e-02 -4.50000513056908e-01 + 1.74000000000000e+02 -2.77354970782234e-01 4.84561038187240e-02 -2.99999717902353e-01 + 1.77000000000000e+02 -1.38045242443721e-01 3.97799508651227e-02 -7.34244952105506e-02 + 1.80000000000000e+02 0.00000000000000e+00 3.88896555692602e-02 1.88439381768847e-01 diff --git a/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_26.dat b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_26.dat new file mode 100644 index 00000000..dbffc457 --- /dev/null +++ b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_26.dat @@ -0,0 +1,254 @@ +! ------------ AirfoilInfo v1.01.x Input File ---------------------------------- +! AeroElasticSE FAST driver +! line +! line +! ------------------------------------------------------------------------------ +DEFAULT InterpOrd ! Interpolation order to use for quasi-steady table lookup {1=linear; 3=cubic spline; "default"} [default=3] +1 NonDimArea ! The non-dimensional area of the airfoil (area/chord^2) (set to 1.0 if unsure or unneeded) +@"NREL-2p8-127_AF26_Coords.txt" NumCoords ! The number of coordinates in the airfoil shape file. Set to zero if coordinates not included. +AF26_BL.txt BL_file ! The file name including the boundary layer characteristics of the profile. Ignored if the aeroacoustic module is not called. +1 NumTabs ! Number of airfoil tables in this file. Each table must have lines for Re and Ctrl. +! ------------------------------------------------------------------------------ +! data for table 1 +! ------------------------------------------------------------------------------ +6.000000 Re ! Reynolds number in millions +0 Ctrl ! Control setting (must be 0 for current AirfoilInfo) +True InclUAdata ! Is unsteady aerodynamics data included in this table? If TRUE, then include 30 UA coefficients below this line +!........................................ +-4.024504 alpha0 ! 0-lift angle of attack, depends on airfoil. +11.306876 alpha1 ! Angle of attack at f=0.7, (approximately the stall angle) for AOA>alpha0. (deg) +-9.832558 alpha2 ! Angle of attack at f=0.7, (approximately the stall angle) for AOA1] +0.000000 S2 ! Constant in the f curve best-fit for AOA> alpha1; by definition it depends on the airfoil. [ignored if UAMod<>1] +0.000000 S3 ! Constant in the f curve best-fit for alpha2<=AOA< alpha0; by definition it depends on the airfoil. [ignored if UAMod<>1] +0.000000 S4 ! Constant in the f curve best-fit for AOA< alpha2; by definition it depends on the airfoil. [ignored if UAMod<>1] +1.557234 Cn1 ! Critical value of C0n at leading edge separation. It should be extracted from airfoil data at a given Mach and Reynolds number. It can be calculated from the static value of Cn at either the break in the pitching moment or the loss of chord force at the onset of stall. It is close to the condition of maximum lift of the airfoil at low Mach numbers. +-0.830241 Cn2 ! As Cn1 for negative AOAs. +Default St_sh ! Strouhal's shedding frequency constant. [default = 0.19] +0.006417 Cd0 ! 2D drag coefficient value at 0-lift. +-0.112920 Cm0 ! 2D pitching moment coefficient about 1/4-chord location, at 0-lift, positive if nose up. [If the aerodynamics coefficients table does not include a column for Cm, this needs to be set to 0.0] +0.000000 k0 ! Constant in the \hat(x)_cp curve best-fit; = (\hat(x)_AC-0.25). [ignored if UAMod<>1] +0.000000 k1 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k2 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k3 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k1_hat ! Constant in the expression of Cc due to leading edge vortex effects. [ignored if UAMod<>1] +Default x_cp_bar ! Constant in the expression of \hat(x)_cp^v. [ignored if UAMod<>1, default = 0.2] +Default UACutout ! Angle of attack above which unsteady aerodynamics are disabled (deg). [Specifying the string "Default" sets UACutout to 45 degrees] +Default filtCutOff ! Cut-off frequency (-3 dB corner frequency) for low-pass filtering the AoA input to UA, as well as the 1st and 2nd derivatives (Hz) [default = 20] +!........................................ +! Table of aerodynamics coefficients +200 NumAlf ! Number of data lines in the following table +! Alpha Cl Cd Cm +! (deg) (-) (-) (-) +-1.80000000000000e+02 0.00000000000000e+00 3.76960235595695e-02 1.99999773877240e-01 +-1.77000000000000e+02 1.49471735352601e-01 3.76960235595695e-02 1.99999908932130e-01 +-1.74000000000000e+02 3.00312823771888e-01 4.52351857356452e-02 2.39999774321882e-01 +-1.71000000000000e+02 4.50470172837611e-01 6.78529197680463e-02 3.60000410445527e-01 +-1.68000000000000e+02 5.62141155839517e-01 9.47828831363562e-02 3.00100260054970e-01 +-1.65000000000000e+02 6.54569405002126e-01 1.23868910842549e-01 1.50251816114612e-01 +-1.62000000000000e+02 7.46998713314856e-01 1.52955271849131e-01 4.01655036174478e-04 +-1.59000000000000e+02 7.99786871669241e-01 1.91656566827607e-01 -9.28122671239639e-02 +-1.56000000000000e+02 7.73294071101042e-01 2.49587404486670e-01 -7.27556273551054e-02 +-1.53000000000000e+02 7.46801068143765e-01 3.07518284704543e-01 -5.26992343631414e-02 +-1.50000000000000e+02 7.20307991381284e-01 3.65449216784473e-01 -3.26429713183966e-02 +-1.47000000000000e+02 7.05570279118452e-01 4.36504377442686e-01 -1.75932612156202e-02 +-1.44000000000000e+02 6.90832510562523e-01 5.07559809506317e-01 -2.54349362777964e-03 +-1.41000000000000e+02 6.76094629416376e-01 5.78615784400165e-01 1.25063869759018e-02 +-1.38000000000000e+02 6.57241681367617e-01 6.52702801625277e-01 2.78005506087723e-02 +-1.35000000000000e+02 6.36331208215415e-01 7.28305333867222e-01 4.32168556727977e-02 +-1.32000000000000e+02 6.15420495447980e-01 8.03908732446007e-01 5.86333373939491e-02 +-1.29000000000000e+02 5.90761768946044e-01 8.77986125240427e-01 7.42048196933668e-02 +-1.26000000000000e+02 5.58606997203396e-01 9.49011499212308e-01 9.00863038811510e-02 +-1.23000000000000e+02 5.26452071104699e-01 1.02003593058481e+00 1.05968066745090e-01 +-1.20000000000000e+02 4.94297067830864e-01 1.09105989067524e+00 1.21849968941896e-01 +-1.17000000000000e+02 4.51046459413193e-01 1.14892722035528e+00 1.36973650595313e-01 +-1.14000000000000e+02 4.07795994504977e-01 1.20679430326659e+00 1.52097072994041e-01 +-1.11000000000000e+02 3.64545860001903e-01 1.26466094411154e+00 1.67219979864857e-01 +-1.08000000000000e+02 3.16034194150131e-01 1.30909602388533e+00 1.80733002070115e-01 +-1.05000000000000e+02 2.64891722560637e-01 1.34681522084817e+00 1.93441069750703e-01 +-1.02000000000000e+02 2.13749237020859e-01 1.38453398558587e+00 2.06148391816051e-01 +-9.90000000000000e+01 1.61688764627702e-01 1.41401796960994e+00 2.17512374667702e-01 +-9.60000000000000e+01 1.07792278764948e-01 1.42703203551508e+00 2.26189620904871e-01 +-9.30000000000000e+01 5.38962046405121e-02 1.44004600200010e+00 2.34866400852709e-01 +-9.00000000000000e+01 3.36381509980986e-07 1.45305991877594e+00 2.43542947660101e-01 +-8.70000000000000e+01 -5.38961494780680e-02 1.44004601531985e+00 2.47180800161873e-01 +-8.40000000000000e+01 -1.07792429471529e-01 1.42703199912486e+00 2.50818607319856e-01 +-8.10000000000000e+01 -1.61688297729853e-01 1.41401808234901e+00 2.54456386687213e-01 +-7.80000000000000e+01 -2.13748989324725e-01 1.38453416826749e+00 2.54821414135407e-01 +-7.50000000000000e+01 -2.64892060915943e-01 1.34681497130280e+00 2.53550009143848e-01 +-7.20000000000000e+01 -3.16033946459415e-01 1.30909620656510e+00 2.52278018725637e-01 +-6.90000000000000e+01 -3.64545485325515e-01 1.26466144541088e+00 2.49759250841147e-01 +-6.60000000000000e+01 -4.07796115441250e-01 1.20679414145955e+00 2.44746825927138e-01 +-6.30000000000000e+01 -4.51046745557096e-01 1.14892683750823e+00 2.39734401012678e-01 +-6.00000000000000e+01 -4.94297280566681e-01 1.09105942078444e+00 2.34721961096712e-01 +-5.70000000000000e+01 -5.26452283840516e-01 1.02003546069401e+00 2.27959404332693e-01 +-5.40000000000000e+01 -5.58607209937681e-01 9.49011029312154e-01 2.21196621737505e-01 +-5.10000000000000e+01 -5.90761981680330e-01 8.77985655340273e-01 2.14433387476536e-01 +-4.80000000000000e+01 -6.17089681519895e-01 8.03911609903610e-01 2.07957006233653e-01 +-4.50000000000000e+01 -6.40503939057214e-01 7.28313277731023e-01 2.01624046889681e-01 +-4.20000000000000e+01 -6.58910854376636e-01 6.52705679055557e-01 1.96862418589880e-01 +-3.90000000000000e+01 -6.76417043986716e-01 5.77527415759156e-01 1.92714525781683e-01 +-3.60000000000000e+01 -6.91442145788392e-01 5.04059407890188e-01 1.90773036499847e-01 +-3.30000000000000e+01 -7.05593980685524e-01 4.33318752640849e-01 1.91909028051921e-01 +-3.00000000000000e+01 -7.20308097407842e-01 3.65448775028654e-01 1.96465078139101e-01 +-2.93939393939394e+01 -7.23687148982083e-01 3.52430142214952e-01 1.98306875240709e-01 +-2.87878787878788e+01 -7.27066200556324e-01 3.39411509401249e-01 2.00148672342317e-01 +-2.81818181818182e+01 -7.30445252130566e-01 3.26392876587547e-01 2.01990469443925e-01 +-2.75757575757576e+01 -7.34245004132877e-01 3.13793130446363e-01 2.04486479544941e-01 +-2.69696969696970e+01 -7.38225071786241e-01 3.01372922565738e-01 2.07262890698687e-01 +-2.63636363636364e+01 -7.42205139439605e-01 2.88952714685113e-01 2.10039301852433e-01 +-2.57575757575758e+01 -7.46555494689374e-01 2.76796428164473e-01 2.13304205864706e-01 +-2.51515151515151e+01 -7.51461195033535e-01 2.65035962173593e-01 2.17301735315320e-01 +-2.45454545454545e+01 -7.56366895377697e-01 2.53275496182714e-01 2.21299264765933e-01 +-2.39393939393939e+01 -7.61408712929841e-01 2.41586724908869e-01 2.25459999520073e-01 +-2.33333333333333e+01 -7.67675611706775e-01 2.30543219968779e-01 2.31089613603274e-01 +-2.27272727272727e+01 -7.73942510483708e-01 2.19499715028689e-01 2.36719227686470e-01 +-2.21212121212121e+01 -7.80209409260641e-01 2.08456210088599e-01 2.42348842244097e-01 +-2.15151515151515e+01 -7.88045843131190e-01 1.98028913518013e-01 2.49772937268922e-01 +-2.09090909090909e+01 -7.96274761734597e-01 1.87755708677063e-01 2.57645768551195e-01 +-2.03030303030303e+01 -8.04503680338007e-01 1.77482503836112e-01 2.65518599833468e-01 +-1.96969696969697e+01 -8.13721581766036e-01 1.67514312390042e-01 2.74509055953088e-01 +-1.90909090909091e+01 -8.23928410071538e-01 1.57851117084127e-01 2.84617073685583e-01 +-1.84848484848485e+01 -8.22646776262130e-01 1.48546940538688e-01 2.82973389715262e-01 +-1.78787878787879e+01 -8.19241192016627e-01 1.39555178352410e-01 2.78335523489406e-01 +-1.72727272727273e+01 -8.15446589363820e-01 1.31559887902139e-01 2.70012950129364e-01 +-1.66666666666667e+01 -8.03296483777369e-01 1.23564597452339e-01 2.53038201146750e-01 +-1.60606060606061e+01 -7.84310128533453e-01 1.15569307002924e-01 2.28984472824905e-01 +-1.54545454545455e+01 -7.65324759977866e-01 1.07574974865435e-01 2.04931438081052e-01 +-1.48484848484848e+01 -7.46339081540475e-01 9.95804834752580e-02 1.80878286802668e-01 +-1.42424242424242e+01 -7.27352144425903e-01 9.15851948410960e-02 1.56824554692099e-01 +-1.36363636363636e+01 -7.08366589041831e-01 8.35901811716822e-02 1.32771649802369e-01 +-1.30303030303030e+01 -6.89379329405081e-01 7.55946407967314e-02 1.08716220908226e-01 +-1.24242424242424e+01 -6.70394070681262e-01 6.75996503421858e-02 8.46633366461469e-02 +-1.18181818181818e+01 -6.51407025524249e-01 5.96041815994357e-02 6.06090692018439e-02 +-1.12121212121212e+01 -6.32421761536482e-01 5.16093484929349e-02 3.65561615953677e-02 +-1.06060606060606e+01 -6.13435225841655e-01 4.36139224210943e-02 1.25016108288645e-02 +-1.00000000000000e+01 -5.94449142982321e-01 3.56199339544178e-02 -1.15512079994493e-02 +-9.39393939393939e+00 -5.75463842145924e-01 2.76249494874552e-02 -3.56050262327576e-02 +-8.78787878787879e+00 -5.51403957680999e-01 2.01382266354268e-02 -5.87079502546054e-02 +-8.18181818181818e+00 -5.17926474912583e-01 1.35966762681344e-02 -8.00434679031281e-02 +-7.57575757575758e+00 -4.48013073952105e-01 1.04062079021587e-02 -9.38202181483299e-02 +-6.96969696969697e+00 -3.62306704515139e-01 8.91516259682469e-03 -1.02639355883834e-01 +-6.36363636363636e+00 -2.86592646559465e-01 7.49092009640339e-03 -1.05345389259135e-01 +-5.75757575757576e+00 -2.11681427543666e-01 7.05454354406601e-03 -1.07624248784689e-01 +-5.15151515151515e+00 -1.37278368249321e-01 6.76061495526902e-03 -1.09615083165669e-01 +-4.54545454545454e+00 -6.32446849221684e-02 6.51817990062387e-03 -1.11463657718864e-01 +-3.93939393939394e+00 1.03326039502837e-02 6.40000102450966e-03 -1.13157562089362e-01 +-3.33333333333333e+00 8.37357402666289e-02 6.36666345248257e-03 -1.14700049263230e-01 +-2.72727272727273e+00 1.57144890016423e-01 6.30000080854981e-03 -1.16209080405868e-01 +-2.12121212121212e+00 2.30132013733438e-01 6.30000067359949e-03 -1.17633366714045e-01 +-1.51515151515152e+00 3.03270133033896e-01 6.30000062134854e-03 -1.18966679175655e-01 +-9.09090909090912e-01 3.76007831012725e-01 6.30000062466049e-03 -1.20399983368341e-01 +-3.03030303030302e-01 4.48619593833060e-01 6.33939706788298e-03 -1.21733367482865e-01 + 3.03030303030302e-01 5.21162110305859e-01 6.40000063237506e-03 -1.23066648228140e-01 + 9.09090909090912e-01 5.93482962845902e-01 6.40000060506645e-03 -1.24318211551559e-01 + 1.51515151515152e+00 6.65499465508473e-01 6.50000049630823e-03 -1.25430305714767e-01 + 2.12121212121212e+00 7.37449721921112e-01 6.52424015611961e-03 -1.26642406027256e-01 + 2.72727272727273e+00 8.08982255779155e-01 6.64545608432346e-03 -1.27809109728731e-01 + 3.33333333333333e+00 8.80397540133069e-01 6.76666331848451e-03 -1.28833312226978e-01 + 3.93939393939394e+00 9.51421795343730e-01 6.88788064407856e-03 -1.29890930275742e-01 + 4.54545454545455e+00 1.02186277965824e+00 7.00909038513147e-03 -1.30763637928484e-01 + 5.15151515151515e+00 1.09189625174699e+00 7.16061521492726e-03 -1.31612160993914e-01 + 5.75757575757576e+00 1.16079950494080e+00 7.45454396592225e-03 -1.32306067865226e-01 + 6.36363636363637e+00 1.22720136736217e+00 7.96365014632842e-03 -1.32572739637886e-01 + 6.96969696969697e+00 1.28802461132675e+00 8.94546191359972e-03 -1.32130308376179e-01 + 7.57575757575757e+00 1.33932328366435e+00 1.07272367904880e-02 -1.30081875964063e-01 + 8.18181818181818e+00 1.38679182149843e+00 1.25091238234984e-02 -1.27572684159305e-01 + 8.78787878787879e+00 1.43442621343129e+00 1.40333059500536e-02 -1.25090961368079e-01 + 9.39393939393939e+00 1.48072468189907e+00 1.53666957749600e-02 -1.22230263597817e-01 + 1.00000000000000e+01 1.51619948622988e+00 1.65000203201040e-02 -1.21700002321685e-01 + 1.06060606060606e+01 1.54652613869201e+00 1.81605911900563e-02 -1.21700000182581e-01 + 1.12121212121212e+01 1.57015106631391e+00 2.03485522545774e-02 -1.21912123883377e-01 + 1.18181818181818e+01 1.58466270949876e+00 3.00903977018941e-02 -1.23218106611257e-01 + 1.24242424242424e+01 1.55439005671114e+00 4.64546703161752e-02 -1.25157568402582e-01 + 1.30303030303030e+01 1.50697011272490e+00 6.28179584205508e-02 -1.27096913764242e-01 + 1.36363636363636e+01 1.44636122440245e+00 7.91823777231142e-02 -1.29036401923583e-01 + 1.42424242424242e+01 1.39302933029550e+00 9.22728672271796e-02 -1.30587869102437e-01 + 1.48484848484848e+01 1.35060444483994e+00 1.00454826054870e-01 -1.31557584992825e-01 + 1.54545454545455e+01 1.32181783503487e+00 1.08636431096634e-01 -1.32527257164245e-01 + 1.60606060606061e+01 1.29757628829158e+00 1.16817964892734e-01 -1.33496920105626e-01 + 1.66666666666667e+01 1.27333348139179e+00 1.24999918769171e-01 -1.34466631124069e-01 + 1.72727272727273e+01 1.24363607861721e+00 1.33181874793555e-01 -1.35436343590531e-01 + 1.78787878787879e+01 1.20727187838534e+00 1.41363833443233e-01 -1.36406057826813e-01 + 1.84848484848485e+01 1.18992975180798e+00 1.49497904111867e-01 -1.37375729577547e-01 + 1.90909090909091e+01 1.17704327758037e+00 1.57851104306908e-01 -1.39089566615125e-01 + 1.96969696969697e+01 1.16246123156071e+00 1.67514298578136e-01 -1.45021783264679e-01 + 2.03030303030303e+01 1.14929279501434e+00 1.77482491349607e-01 -1.51632325921770e-01 + 2.09090909090909e+01 1.13753806488326e+00 1.87755699876179e-01 -1.58921232961736e-01 + 2.15151515151515e+01 1.12578334814572e+00 1.98028908402751e-01 -1.66210140001703e-01 + 2.21212121212121e+01 1.11458879313232e+00 2.08456208053037e-01 -1.73224589305943e-01 + 2.27272727272727e+01 1.10563435435787e+00 2.19499713649760e-01 -1.79141490064069e-01 + 2.33333333333333e+01 1.09667991558342e+00 2.30543219246483e-01 -1.85058390822194e-01 + 2.39393939393939e+01 1.08772547680897e+00 2.41586724843207e-01 -1.90975291580320e-01 + 2.45454545454545e+01 1.08052192847356e+00 2.53275496182714e-01 -1.96074563757929e-01 + 2.51515151515151e+01 1.07351291933540e+00 2.65035962173593e-01 -2.01082990269719e-01 + 2.57575757575758e+01 1.06650391019725e+00 2.76796428164473e-01 -2.06091416781509e-01 + 2.63636363636364e+01 1.06028929009176e+00 2.88952714685113e-01 -2.10729582407184e-01 + 2.69696969696970e+01 1.05460434497302e+00 3.01372922565738e-01 -2.15120869083270e-01 + 2.75757575757576e+01 1.04891939985428e+00 3.13793130446363e-01 -2.19512155759356e-01 + 2.81818181818182e+01 1.04349178876274e+00 3.26392876587547e-01 -2.23774943907361e-01 + 2.87878787878788e+01 1.03866457222799e+00 3.39411509401249e-01 -2.27737927876115e-01 + 2.93939393939394e+01 1.03383735569325e+00 3.52430142214952e-01 -2.31700911844869e-01 + 3.00000000000000e+01 1.02901013915851e+00 3.65448775028654e-01 -2.35663895813623e-01 + 3.30000000000000e+01 1.00799497239599e+00 4.33318752640849e-01 -2.53423032735973e-01 + 3.60000000000000e+01 9.87774208309456e-01 5.04059407890188e-01 -2.69936839647807e-01 + 3.90000000000000e+01 9.66310062840480e-01 5.77527415759156e-01 -2.85448460530465e-01 + 4.20000000000000e+01 9.41301077680331e-01 6.52705679055557e-01 -3.00284956735113e-01 + 4.50000000000000e+01 9.15005912938840e-01 7.28313277731023e-01 -3.14934033957096e-01 + 4.80000000000000e+01 8.81556716458514e-01 8.03911609903610e-01 -3.28999148408511e-01 + 5.10000000000000e+01 8.43945459545643e-01 8.77985655340274e-01 -3.42814120520528e-01 + 5.40000000000000e+01 7.98009814198267e-01 9.49011029312154e-01 -3.56128791872664e-01 + 5.70000000000000e+01 7.52074119773438e-01 1.02003546069401e+00 -3.69443361508008e-01 + 6.00000000000000e+01 7.06138400810069e-01 1.09105942078444e+00 -3.82757880285344e-01 + 6.30000000000000e+01 6.44352607936286e-01 1.14892683750823e+00 -3.94831155449636e-01 + 6.60000000000000e+01 5.82566479201223e-01 1.20679414145955e+00 -4.06904419974219e-01 + 6.90000000000000e+01 5.20779950464649e-01 1.26466144541088e+00 -4.18977684498238e-01 + 7.20000000000000e+01 4.51477437795751e-01 1.30909620656510e+00 -4.29844047643928e-01 + 7.50000000000000e+01 3.78417087022892e-01 1.34681497130280e+00 -4.40106984807332e-01 + 7.80000000000000e+01 3.05355899035943e-01 1.38453416826749e+00 -4.50369439573171e-01 + 8.10000000000000e+01 2.30983768185259e-01 1.41401808234901e+00 -4.59788640889162e-01 + 8.40000000000000e+01 1.53989842100278e-01 1.42703199912486e+00 -4.67521393514335e-01 + 8.70000000000000e+01 7.69949278241990e-02 1.44004601531985e+00 -4.75253805212904e-01 + 9.00000000000000e+01 -3.36381510214729e-07 1.45305991877594e+00 -4.82986020891325e-01 + 9.30000000000000e+01 -5.38962046405121e-02 1.44004600200010e+00 -4.86623800258682e-01 + 9.60000000000000e+01 -1.07792278764948e-01 1.42703203551508e+00 -4.90261391797100e-01 + 9.90000000000000e+01 -1.61688764627702e-01 1.41401796960994e+00 -4.93898611078009e-01 + 1.02000000000000e+02 -2.13749237020859e-01 1.38453398558587e+00 -4.94263399100741e-01 + 1.05000000000000e+02 -2.64891722560637e-01 1.34681522084817e+00 -4.92992006930170e-01 + 1.08000000000000e+02 -3.16034194150131e-01 1.30909602388533e+00 -4.91720002039579e-01 + 1.11000000000000e+02 -3.64545860001904e-01 1.26466094411154e+00 -4.89201398052675e-01 + 1.14000000000000e+02 -4.07795994504977e-01 1.20679430326659e+00 -4.84189631673154e-01 + 1.17000000000000e+02 -4.51046459413193e-01 1.14892722035528e+00 -4.79177427008757e-01 + 1.20000000000000e+02 -4.94297067830864e-01 1.09105989067524e+00 -4.74164999771467e-01 + 1.23000000000000e+02 -5.26452071104699e-01 1.02003593058481e+00 -4.67401844027926e-01 + 1.26000000000000e+02 -5.58606997203396e-01 9.49011499212308e-01 -4.60638662451069e-01 + 1.29000000000000e+02 -5.90761768946045e-01 8.77986125240427e-01 -4.53875428596403e-01 + 1.32000000000000e+02 -6.15420495447981e-01 8.03908732446007e-01 -4.47922999380913e-01 + 1.35000000000000e+02 -6.36331208215415e-01 7.28305333867222e-01 -4.42375971721764e-01 + 1.38000000000000e+02 -6.57241681367618e-01 6.52702801625276e-01 -4.36828407635875e-01 + 1.41000000000000e+02 -6.76094629416376e-01 5.78615784400164e-01 -4.33407828184422e-01 + 1.44000000000000e+02 -6.90832510562523e-01 5.07559809506317e-01 -4.34241235261194e-01 + 1.47000000000000e+02 -7.05570279118452e-01 4.36504377442686e-01 -4.35074635971279e-01 + 1.50000000000000e+02 -7.20307991381284e-01 3.65449216784472e-01 -4.35908033498135e-01 + 1.53000000000000e+02 -7.46801056114916e-01 3.07518286202364e-01 -4.57805090339867e-01 + 1.56000000000000e+02 -7.73294047043302e-01 2.49587407482254e-01 -4.79701903131578e-01 + 1.59000000000000e+02 -7.99786835582591e-01 1.91656571320831e-01 -5.01598162643685e-01 + 1.62000000000000e+02 -7.40790686340429e-01 1.53560875453361e-01 -5.07117800599876e-01 + 1.65000000000000e+02 -6.39049345205277e-01 1.25382917483086e-01 -5.04448986449598e-01 + 1.68000000000000e+02 -5.37308569933658e-01 9.72046824115369e-02 -5.01779602888075e-01 + 1.71000000000000e+02 -4.22533354527340e-01 7.05773220395183e-02 -4.50000513056908e-01 + 1.74000000000000e+02 -2.81688650312917e-01 4.70517834722228e-02 -2.99999717902353e-01 + 1.77000000000000e+02 -1.40202209005507e-01 3.86002803503690e-02 -6.87687043373218e-02 + 1.80000000000000e+02 0.00000000000000e+00 3.76960235595695e-02 1.99999773877240e-01 diff --git a/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_27.dat b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_27.dat new file mode 100644 index 00000000..e92595fb --- /dev/null +++ b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_27.dat @@ -0,0 +1,254 @@ +! ------------ AirfoilInfo v1.01.x Input File ---------------------------------- +! AeroElasticSE FAST driver +! line +! line +! ------------------------------------------------------------------------------ +DEFAULT InterpOrd ! Interpolation order to use for quasi-steady table lookup {1=linear; 3=cubic spline; "default"} [default=3] +1 NonDimArea ! The non-dimensional area of the airfoil (area/chord^2) (set to 1.0 if unsure or unneeded) +@"NREL-2p8-127_AF27_Coords.txt" NumCoords ! The number of coordinates in the airfoil shape file. Set to zero if coordinates not included. +AF27_BL.txt BL_file ! The file name including the boundary layer characteristics of the profile. Ignored if the aeroacoustic module is not called. +1 NumTabs ! Number of airfoil tables in this file. Each table must have lines for Re and Ctrl. +! ------------------------------------------------------------------------------ +! data for table 1 +! ------------------------------------------------------------------------------ +6.000000 Re ! Reynolds number in millions +0 Ctrl ! Control setting (must be 0 for current AirfoilInfo) +True InclUAdata ! Is unsteady aerodynamics data included in this table? If TRUE, then include 30 UA coefficients below this line +!........................................ +-4.024505 alpha0 ! 0-lift angle of attack, depends on airfoil. +11.306884 alpha1 ! Angle of attack at f=0.7, (approximately the stall angle) for AOA>alpha0. (deg) +-9.832557 alpha2 ! Angle of attack at f=0.7, (approximately the stall angle) for AOA1] +0.000000 S2 ! Constant in the f curve best-fit for AOA> alpha1; by definition it depends on the airfoil. [ignored if UAMod<>1] +0.000000 S3 ! Constant in the f curve best-fit for alpha2<=AOA< alpha0; by definition it depends on the airfoil. [ignored if UAMod<>1] +0.000000 S4 ! Constant in the f curve best-fit for AOA< alpha2; by definition it depends on the airfoil. [ignored if UAMod<>1] +1.557235 Cn1 ! Critical value of C0n at leading edge separation. It should be extracted from airfoil data at a given Mach and Reynolds number. It can be calculated from the static value of Cn at either the break in the pitching moment or the loss of chord force at the onset of stall. It is close to the condition of maximum lift of the airfoil at low Mach numbers. +-0.830241 Cn2 ! As Cn1 for negative AOAs. +Default St_sh ! Strouhal's shedding frequency constant. [default = 0.19] +0.006417 Cd0 ! 2D drag coefficient value at 0-lift. +-0.112920 Cm0 ! 2D pitching moment coefficient about 1/4-chord location, at 0-lift, positive if nose up. [If the aerodynamics coefficients table does not include a column for Cm, this needs to be set to 0.0] +0.000000 k0 ! Constant in the \hat(x)_cp curve best-fit; = (\hat(x)_AC-0.25). [ignored if UAMod<>1] +0.000000 k1 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k2 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k3 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k1_hat ! Constant in the expression of Cc due to leading edge vortex effects. [ignored if UAMod<>1] +Default x_cp_bar ! Constant in the expression of \hat(x)_cp^v. [ignored if UAMod<>1, default = 0.2] +Default UACutout ! Angle of attack above which unsteady aerodynamics are disabled (deg). [Specifying the string "Default" sets UACutout to 45 degrees] +Default filtCutOff ! Cut-off frequency (-3 dB corner frequency) for low-pass filtering the AoA input to UA, as well as the 1st and 2nd derivatives (Hz) [default = 20] +!........................................ +! Table of aerodynamics coefficients +200 NumAlf ! Number of data lines in the following table +! Alpha Cl Cd Cm +! (deg) (-) (-) (-) +-1.80000000000000e+02 0.00000000000000e+00 3.76960000000000e-02 2.00000000000000e-01 +-1.77000000000000e+02 1.49471782056503e-01 3.76960000000000e-02 2.00000000000000e-01 +-1.74000000000000e+02 3.00312917607843e-01 4.52351574641884e-02 2.39999774321882e-01 +-1.71000000000000e+02 4.50470313592540e-01 6.78528773607728e-02 3.60000410445527e-01 +-1.68000000000000e+02 5.62141300000530e-01 9.47828314689296e-02 3.00100237874998e-01 +-1.65000000000000e+02 6.54569530813285e-01 1.23868852352745e-01 1.50251760664942e-01 +-1.62000000000000e+02 7.46998820775784e-01 1.52955206537882e-01 4.01566317437541e-04 +-1.59000000000000e+02 7.99786954801670e-01 1.91656498833410e-01 -9.28123657821359e-02 +-1.56000000000000e+02 7.73294117948629e-01 2.49587342086377e-01 -7.27556892942309e-02 +-1.53000000000000e+02 7.46801078706125e-01 3.07518227898197e-01 -5.26992595835046e-02 +-1.50000000000000e+02 7.20307965658325e-01 3.65449165572087e-01 -3.26429649313102e-02 +-1.47000000000000e+02 7.05570256415403e-01 4.36504328003481e-01 -1.75932576097200e-02 +-1.44000000000000e+02 6.90832490879619e-01 5.07559761840581e-01 -2.54349280354572e-03 +-1.41000000000000e+02 6.76094612754094e-01 5.78615738508475e-01 1.25063869759013e-02 +-1.38000000000000e+02 6.57241666993606e-01 6.52702757782292e-01 2.78005506087711e-02 +-1.35000000000000e+02 6.36331195763501e-01 7.28305292210269e-01 4.32168556727960e-02 +-1.32000000000000e+02 6.15420484918018e-01 8.03908692975958e-01 5.86333373939468e-02 +-1.29000000000000e+02 5.90761760127430e-01 8.77986088072914e-01 7.42048196933640e-02 +-1.26000000000000e+02 5.58606989674918e-01 9.49011464578596e-01 9.00863038811478e-02 +-1.23000000000000e+02 5.26452064865786e-01 1.02003589848443e+00 1.05968066745086e-01 +-1.20000000000000e+02 4.94297062881228e-01 1.09105986110795e+00 1.21849968941892e-01 +-1.17000000000000e+02 4.51046455307775e-01 1.14892719359139e+00 1.36973650595308e-01 +-1.14000000000000e+02 4.07795991243718e-01 1.20679427930608e+00 1.52097072994036e-01 +-1.11000000000000e+02 3.64545857584686e-01 1.26466092295440e+00 1.67219979864852e-01 +-1.08000000000000e+02 3.16034192336304e-01 1.30909600565222e+00 1.80733001904303e-01 +-1.05000000000000e+02 2.64891721229873e-01 1.34681520559943e+00 1.93441069265733e-01 +-1.02000000000000e+02 2.13749236173153e-01 1.38453397332146e+00 2.06148391012093e-01 +-9.90000000000000e+01 1.61688764154489e-01 1.41401796036258e+00 2.17512373571396e-01 +-9.60000000000000e+01 1.07792278449096e-01 1.42703202935019e+00 2.26189619569497e-01 +-9.30000000000000e+01 5.38962044824732e-02 1.44004599891764e+00 2.34866399278379e-01 +-9.00000000000000e+01 3.36381508994621e-07 1.45305991877593e+00 2.43542945846872e-01 +-8.70000000000000e+01 -5.38961493200293e-02 1.44004601223740e+00 2.47180796579284e-01 +-8.40000000000000e+01 -1.07792429155678e-01 1.42703199295995e+00 2.50818601967904e-01 +-8.10000000000000e+01 -1.61688297256642e-01 1.41401807310167e+00 2.54456379565910e-01 +-7.80000000000000e+01 -2.13748988477021e-01 1.38453415600310e+00 2.54821405258420e-01 +-7.50000000000000e+01 -2.64892059585176e-01 1.34681495605404e+00 2.53549998518008e-01 +-7.20000000000000e+01 -3.16033944645590e-01 1.30909618833200e+00 2.52278006351131e-01 +-6.90000000000000e+01 -3.64545482908305e-01 1.26466142425377e+00 2.49759236748571e-01 +-6.60000000000000e+01 -4.07796112179989e-01 1.20679411749904e+00 2.44746810177687e-01 +-6.30000000000000e+01 -4.51046741451673e-01 1.14892681074432e+00 2.39734383606802e-01 +-6.00000000000000e+01 -4.94297275617037e-01 1.09105939121714e+00 2.34721942034639e-01 +-5.70000000000000e+01 -5.26452277601595e-01 1.02003542859361e+00 2.27959383679512e-01 +-5.40000000000000e+01 -5.58607202409195e-01 9.49010994678426e-01 2.21196599493265e-01 +-5.10000000000000e+01 -5.90761972861707e-01 8.77985618172743e-01 2.14433363641336e-01 +-4.80000000000000e+01 -6.17089671120620e-01 8.03911570370645e-01 2.07956980763680e-01 +-4.50000000000000e+01 -6.40503926932036e-01 7.28313235916803e-01 2.01624019763027e-01 +-4.20000000000000e+01 -6.58910840133311e-01 6.52705635149657e-01 1.96862389618034e-01 +-3.90000000000000e+01 -6.76417027511146e-01 5.77527369809482e-01 1.92714494884031e-01 +-3.60000000000000e+01 -6.91442126694186e-01 5.04059360049167e-01 1.90773003374389e-01 +-3.30000000000000e+01 -7.05593958510807e-01 4.33318703053973e-01 1.91908992233939e-01 +-3.00000000000000e+01 -7.20308071684859e-01 3.65448723816258e-01 1.96465039072780e-01 +-2.93939393939394e+01 -7.23687122424702e-01 3.52430090699486e-01 1.98306835359819e-01 +-2.87878787878788e+01 -7.27066173164544e-01 3.39411457582714e-01 2.00148631646857e-01 +-2.81818181818182e+01 -7.30445223904387e-01 3.26392824465942e-01 2.01990427933895e-01 +-2.75757575757576e+01 -7.34244974993610e-01 3.13793078035017e-01 2.04486437101527e-01 +-2.69696969696970e+01 -7.38225041700157e-01 3.01372869870364e-01 2.07262847270964e-01 +-2.63636363636364e+01 -7.42205108406705e-01 2.88952661705710e-01 2.10039257440401e-01 +-2.57575757575758e+01 -7.46555462653963e-01 2.76796374908870e-01 2.13304160376248e-01 +-2.51515151515151e+01 -7.51461161912085e-01 2.65035908653530e-01 2.17301688612281e-01 +-2.45454545454545e+01 -7.56366861170206e-01 2.53275442398190e-01 2.21299216848314e-01 +-2.39393939393939e+01 -7.61408677387006e-01 2.41586670872199e-01 2.25459952105595e-01 +-2.33333333333333e+01 -7.67675572584808e-01 2.30543165790786e-01 2.31089582151761e-01 +-2.27272727272727e+01 -7.73942467782610e-01 2.19499660709374e-01 2.36719212197927e-01 +-2.21212121212121e+01 -7.80209362980412e-01 2.08456155627962e-01 2.42348842244093e-01 +-2.15151515151515e+01 -7.88045801889462e-01 1.98028860914946e-01 2.49772963288095e-01 +-2.09090909090909e+01 -7.96274727686348e-01 1.87755658431417e-01 2.57645822511188e-01 +-2.03030303030303e+01 -8.04503653483233e-01 1.77482455947888e-01 2.65518681734281e-01 +-1.96969696969697e+01 -8.13721563222721e-01 1.67514267203666e-01 2.74509167058282e-01 +-1.90909090909091e+01 -8.23928400957602e-01 1.57851074944005e-01 2.84617215258648e-01 +-1.84848484848485e+01 -8.22646763588942e-01 1.48546901850923e-01 2.82973548468764e-01 +-1.78787878787879e+01 -8.19241173382965e-01 1.39555143470384e-01 2.78335696038153e-01 +-1.72727272727273e+01 -8.15446564330172e-01 1.31559857952983e-01 2.70013132308244e-01 +-1.66666666666667e+01 -8.03296442896411e-01 1.23564572435581e-01 2.53038383173389e-01 +-1.60606060606061e+01 -7.84310064075638e-01 1.15569286918180e-01 2.28984646695628e-01 +-1.54545454545455e+01 -7.65324664303493e-01 1.07574959135167e-01 2.04931605118311e-01 +-1.48484848484848e+01 -7.46338949873589e-01 9.95804717419686e-02 1.80878447733115e-01 +-1.42424242424242e+01 -7.27351964982053e-01 9.15851862245671e-02 1.56824711255353e-01 +-1.36363636363636e+01 -7.08366360011050e-01 8.35901755495681e-02 1.32771801638210e-01 +-1.30303030303030e+01 -6.89379049576426e-01 7.55946380877238e-02 1.08716367776058e-01 +-1.24242424242424e+01 -6.70393771825338e-01 6.75996503421813e-02 8.46634665540094e-02 +-1.18181818181818e+01 -6.51406715493019e-01 5.96041815994351e-02 6.06091788446317e-02 +-1.12121212121212e+01 -6.32421454753742e-01 5.16093541595814e-02 3.65562447387649e-02 +-1.06060606060606e+01 -6.13434931389144e-01 4.36139312036515e-02 1.25016705283901e-02 +-1.00000000000000e+01 -5.94448865749824e-01 3.56199434645880e-02 -1.15511700947924e-02 +-9.39393939393939e+00 -5.75463587974779e-01 2.76249557125666e-02 -3.56050107398163e-02 +-8.78787878787879e+00 -5.51403736673166e-01 2.01382292840361e-02 -5.87079533337773e-02 +-8.18181818181818e+00 -5.17926305822838e-01 1.35966762681340e-02 -8.00434824257992e-02 +-7.57575757575758e+00 -4.48012922709353e-01 1.04062079021576e-02 -9.38202376741164e-02 +-6.96969696969697e+00 -3.62306556115099e-01 8.91516259682331e-03 -1.02639375733790e-01 +-6.36363636363636e+00 -2.86592508663283e-01 7.49091941073086e-03 -1.05345402946346e-01 +-5.75757575757576e+00 -2.11681301136276e-01 7.05454293237208e-03 -1.07624256716558e-01 +-5.15151515151515e+00 -1.37278254009080e-01 6.76061420557612e-03 -1.09615086355391e-01 +-4.54545454545454e+00 -6.32445813538124e-02 6.51817895525840e-03 -1.11463657835562e-01 +-3.93939393939394e+00 1.03326972358679e-02 6.40000000000000e-03 -1.13157562089366e-01 +-3.33333333333333e+00 8.37358252318253e-02 6.36666256139732e-03 -1.14700049263232e-01 +-2.72727272727273e+00 1.57144966549608e-01 6.30000000000000e-03 -1.16209080405869e-01 +-2.12121212121212e+00 2.30132082000148e-01 6.30000000000000e-03 -1.17633365893514e-01 +-1.51515151515152e+00 3.03270194866406e-01 6.30000000000000e-03 -1.18966675734322e-01 +-9.09090909090912e-01 3.76007887483945e-01 6.30000000000000e-03 -1.20399977937206e-01 +-3.03030303030302e-01 4.48619648411214e-01 6.33939639599868e-03 -1.21733360355986e-01 + 3.03030303030302e-01 5.21162162400790e-01 6.40000000000000e-03 -1.23066639644014e-01 + 9.09090909090912e-01 5.93483011578421e-01 6.40000000000000e-03 -1.24318201875268e-01 + 1.51515151515152e+00 6.65499510346614e-01 6.50000000000000e-03 -1.25430294786980e-01 + 2.12121212121212e+00 7.37449762821818e-01 6.52423946422604e-03 -1.26642394642260e-01 + 2.72727272727273e+00 8.08982292442682e-01 6.64545535339469e-03 -1.27809098180552e-01 + 3.33333333333333e+00 8.80397573785818e-01 6.76666256139732e-03 -1.28833300491179e-01 + 3.93939393939394e+00 9.51421826139261e-01 6.88787983927956e-03 -1.29890918553516e-01 + 4.54545454545455e+00 1.02186280754731e+00 7.00908947762920e-03 -1.30763626343404e-01 + 5.15151515151515e+00 1.09189627700035e+00 7.16061420557612e-03 -1.31612149719516e-01 + 5.75757575757576e+00 1.16079952835358e+00 7.45454293237208e-03 -1.32306057243163e-01 + 6.36363636363637e+00 1.22720139059598e+00 7.96364926341358e-03 -1.32572729852683e-01 + 6.96969696969697e+00 1.28802463107430e+00 8.94546166938641e-03 -1.32130299072563e-01 + 7.57575757575757e+00 1.33932330958836e+00 1.07272369407300e-02 -1.30081868282978e-01 + 8.18181818181818e+00 1.38679186165234e+00 1.25091248425769e-02 -1.27572678796319e-01 + 8.78787878787879e+00 1.43442629439737e+00 1.40333059500537e-02 -1.25090961368079e-01 + 9.39393939393939e+00 1.48072485366775e+00 1.53666845487907e-02 -1.22230262389112e-01 + 1.00000000000000e+01 1.51619976429293e+00 1.64999922859505e-02 -1.21700000000000e-01 + 1.06060606060606e+01 1.54652659135150e+00 1.81605492792916e-02 -1.21700000000000e-01 + 1.12121212121212e+01 1.57015165312925e+00 2.03485003516014e-02 -1.21912125087900e-01 + 1.18181818181818e+01 1.58466335911404e+00 3.00903504536651e-02 -1.23218115609323e-01 + 1.24242424242424e+01 1.55439065028940e+00 4.64546360854226e-02 -1.25157586499013e-01 + 1.30303030303030e+01 1.50697060273102e+00 6.28179372626244e-02 -1.27096940712607e-01 + 1.36363636363636e+01 1.44636161651328e+00 7.91823635414146e-02 -1.29036428271575e-01 + 1.42424242424242e+01 1.39302963646758e+00 9.22728558241098e-02 -1.30587894023598e-01 + 1.48484848484848e+01 1.35060468299441e+00 1.00454811136793e-01 -1.31557607245842e-01 + 1.54545454545455e+01 1.32181803006545e+00 1.08636414852911e-01 -1.32527278797382e-01 + 1.60606060606061e+01 1.29757644961134e+00 1.16817948256172e-01 -1.33496942015546e-01 + 1.66666666666667e+01 1.27333361905524e+00 1.24999903568856e-01 -1.34466655237790e-01 + 1.72727272727273e+01 1.24363618274871e+00 1.33181858881539e-01 -1.35436368460034e-01 + 1.78787878787879e+01 1.20727193691457e+00 1.41363814194223e-01 -1.36406081682278e-01 + 1.84848484848485e+01 1.18992978938591e+00 1.49497879761678e-01 -1.37375750456550e-01 + 1.90909090909091e+01 1.17704330010331e+00 1.57851074944005e-01 -1.39089585145003e-01 + 1.96969696969697e+01 1.16246123752382e+00 1.67514267203666e-01 -1.45021805782080e-01 + 2.03030303030303e+01 1.14929279501435e+00 1.77482455947888e-01 -1.51632351934001e-01 + 2.09090909090909e+01 1.13753805254846e+00 1.87755658431417e-01 -1.58921261976074e-01 + 2.15151515151515e+01 1.12578331008257e+00 1.98028860914946e-01 -1.66210172018147e-01 + 2.21212121212121e+01 1.11458874358451e+00 2.08456155627962e-01 -1.73224623443957e-01 + 2.27272727272727e+01 1.10563430457793e+00 2.19499660709374e-01 -1.79141522802416e-01 + 2.33333333333333e+01 1.09667986557135e+00 2.30543165790786e-01 -1.85058422160874e-01 + 2.39393939393939e+01 1.08772542656477e+00 2.41586670872199e-01 -1.90975321519332e-01 + 2.45454545454545e+01 1.08052187960139e+00 2.53275442398190e-01 -1.96074592475065e-01 + 2.51515151515151e+01 1.07351287201350e+00 2.65035908653530e-01 -2.01083017784734e-01 + 2.57575757575758e+01 1.06650386442561e+00 2.76796374908870e-01 -2.06091443094404e-01 + 2.63636363636364e+01 1.06028924575223e+00 2.88952661705710e-01 -2.10729607665482e-01 + 2.69696969696970e+01 1.05460430198682e+00 3.01372869870364e-01 -2.15120893385337e-01 + 2.75757575757576e+01 1.04891935822142e+00 3.13793078035017e-01 -2.19512179105193e-01 + 2.81818181818182e+01 1.04349174843484e+00 3.26392824465942e-01 -2.23774966350859e-01 + 2.87878787878788e+01 1.03866453309221e+00 3.39411457582714e-01 -2.27737949543009e-01 + 2.93939393939394e+01 1.03383731774957e+00 3.52430090699486e-01 -2.31700932735158e-01 + 3.00000000000000e+01 1.02901010240694e+00 3.65448723816258e-01 -2.35663915927308e-01 + 3.30000000000000e+01 1.00799494072346e+00 4.33318703053973e-01 -2.53423049843193e-01 + 3.60000000000000e+01 9.87774181033947e-01 5.04059360049167e-01 -2.69936854350083e-01 + 3.90000000000000e+01 9.66310039303889e-01 5.77527369809482e-01 -2.85448473353340e-01 + 4.20000000000000e+01 9.41301057332367e-01 6.52705635149657e-01 -3.00284968060017e-01 + 4.50000000000000e+01 9.15005895616392e-01 7.28313235916803e-01 -3.14934043892456e-01 + 4.80000000000000e+01 8.81556701601667e-01 8.03911570370646e-01 -3.28999157277327e-01 + 5.10000000000000e+01 8.43945446946677e-01 8.77985618172744e-01 -3.42814128421300e-01 + 5.40000000000000e+01 7.98009803441727e-01 9.49010994678426e-01 -3.56128799002399e-01 + 5.70000000000000e+01 7.52074110859421e-01 1.02003542859361e+00 -3.69443367867275e-01 + 6.00000000000000e+01 7.06138393738624e-01 1.09105939121714e+00 -3.82757885874428e-01 + 6.30000000000000e+01 6.44352602071576e-01 1.14892681074432e+00 -3.94831160514253e-01 + 6.60000000000000e+01 5.82566474543015e-01 1.20679411749904e+00 -4.06904424514653e-01 + 6.90000000000000e+01 5.20779947012492e-01 1.26466142425377e+00 -4.18977688515053e-01 + 7.20000000000000e+01 4.51477435205418e-01 1.30909618833200e+00 -4.29844051243441e-01 + 7.50000000000000e+01 3.78417085122278e-01 1.34681495605404e+00 -4.40106988042700e-01 + 7.80000000000000e+01 3.05355897825734e-01 1.38453415600310e+00 -4.50369442444556e-01 + 8.10000000000000e+01 2.30983767510451e-01 1.41401807310167e+00 -4.59788643436343e-01 + 8.40000000000000e+01 1.53989841650875e-01 1.42703199295995e+00 -4.67521395816866e-01 + 8.70000000000000e+01 7.69949275996385e-02 1.44004601223740e+00 -4.75253807270785e-01 + 9.00000000000000e+01 -3.36381509228363e-07 1.45305991877593e+00 -4.82986022704544e-01 + 9.30000000000000e+01 -5.38962044824732e-02 1.44004599891764e+00 -4.86623800302551e-01 + 9.60000000000000e+01 -1.07792278449097e-01 1.42703202935019e+00 -4.90261391797104e-01 + 9.90000000000000e+01 -1.61688764154490e-01 1.41401796036258e+00 -4.93898611078011e-01 + 1.02000000000000e+02 -2.13749236173153e-01 1.38453397332146e+00 -4.94263399100743e-01 + 1.05000000000000e+02 -2.64891721229873e-01 1.34681520559943e+00 -4.92992006930171e-01 + 1.08000000000000e+02 -3.16034192336304e-01 1.30909600565222e+00 -4.91720000190610e-01 + 1.11000000000000e+02 -3.64545857584686e-01 1.26466092295440e+00 -4.89201393327162e-01 + 1.14000000000000e+02 -4.07795991243718e-01 1.20679427930608e+00 -4.84189624190406e-01 + 1.17000000000000e+02 -4.51046455307775e-01 1.14892719359139e+00 -4.79177416768754e-01 + 1.20000000000000e+02 -4.94297062881228e-01 1.09105986110795e+00 -4.74164986774198e-01 + 1.23000000000000e+02 -5.26452064865786e-01 1.02003589848443e+00 -4.67401828422766e-01 + 1.26000000000000e+02 -5.58606989674918e-01 9.49011464578596e-01 -4.60638644238479e-01 + 1.29000000000000e+02 -5.90761760127430e-01 8.77986088072913e-01 -4.53875408386550e-01 + 1.32000000000000e+02 -6.15420484918018e-01 8.03908692975958e-01 -4.47922977473614e-01 + 1.35000000000000e+02 -6.36331195763501e-01 7.28305292210269e-01 -4.42375948063776e-01 + 1.38000000000000e+02 -6.57241666993606e-01 6.52702757782291e-01 -4.36828382226539e-01 + 1.41000000000000e+02 -6.76094612754094e-01 5.78615738508474e-01 -4.33407800721224e-01 + 1.44000000000000e+02 -6.90832490879619e-01 5.07559761840581e-01 -4.34241205139103e-01 + 1.47000000000000e+02 -7.05570256415403e-01 4.36504328003481e-01 -4.35074603190205e-01 + 1.50000000000000e+02 -7.20307965658325e-01 3.65449165572087e-01 -4.35907998058031e-01 + 1.53000000000000e+02 -7.46801078706125e-01 3.07518227898197e-01 -4.57805065052203e-01 + 1.56000000000000e+02 -7.73294117948629e-01 2.49587342086377e-01 -4.79701897484255e-01 + 1.59000000000000e+02 -7.99786954801670e-01 1.91656498833410e-01 -5.01598162643690e-01 + 1.62000000000000e+02 -7.40790822868899e-01 1.53560806333696e-01 -5.07117800599882e-01 + 1.65000000000000e+02 -6.39049483540701e-01 1.25382856960915e-01 -5.04448986449602e-01 + 1.68000000000000e+02 -5.37308710076014e-01 9.72046304867630e-02 -5.01779602888076e-01 + 1.71000000000000e+02 -4.22533481739914e-01 7.05772804657932e-02 -4.50000513056908e-01 + 1.74000000000000e+02 -2.81688735121593e-01 4.70517557569334e-02 -2.99999717902353e-01 + 1.77000000000000e+02 -1.40202251216632e-01 3.86002570677554e-02 -6.87686132694523e-02 + 1.80000000000000e+02 0.00000000000000e+00 3.76960000000000e-02 2.00000000000000e-01 diff --git a/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_28.dat b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_28.dat new file mode 100644 index 00000000..1adeee56 --- /dev/null +++ b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_28.dat @@ -0,0 +1,254 @@ +! ------------ AirfoilInfo v1.01.x Input File ---------------------------------- +! AeroElasticSE FAST driver +! line +! line +! ------------------------------------------------------------------------------ +DEFAULT InterpOrd ! Interpolation order to use for quasi-steady table lookup {1=linear; 3=cubic spline; "default"} [default=3] +1 NonDimArea ! The non-dimensional area of the airfoil (area/chord^2) (set to 1.0 if unsure or unneeded) +@"NREL-2p8-127_AF28_Coords.txt" NumCoords ! The number of coordinates in the airfoil shape file. Set to zero if coordinates not included. +AF28_BL.txt BL_file ! The file name including the boundary layer characteristics of the profile. Ignored if the aeroacoustic module is not called. +1 NumTabs ! Number of airfoil tables in this file. Each table must have lines for Re and Ctrl. +! ------------------------------------------------------------------------------ +! data for table 1 +! ------------------------------------------------------------------------------ +6.000000 Re ! Reynolds number in millions +0 Ctrl ! Control setting (must be 0 for current AirfoilInfo) +True InclUAdata ! Is unsteady aerodynamics data included in this table? If TRUE, then include 30 UA coefficients below this line +!........................................ +-4.024505 alpha0 ! 0-lift angle of attack, depends on airfoil. +11.306884 alpha1 ! Angle of attack at f=0.7, (approximately the stall angle) for AOA>alpha0. (deg) +-9.832557 alpha2 ! Angle of attack at f=0.7, (approximately the stall angle) for AOA1] +0.000000 S2 ! Constant in the f curve best-fit for AOA> alpha1; by definition it depends on the airfoil. [ignored if UAMod<>1] +0.000000 S3 ! Constant in the f curve best-fit for alpha2<=AOA< alpha0; by definition it depends on the airfoil. [ignored if UAMod<>1] +0.000000 S4 ! Constant in the f curve best-fit for AOA< alpha2; by definition it depends on the airfoil. [ignored if UAMod<>1] +1.557235 Cn1 ! Critical value of C0n at leading edge separation. It should be extracted from airfoil data at a given Mach and Reynolds number. It can be calculated from the static value of Cn at either the break in the pitching moment or the loss of chord force at the onset of stall. It is close to the condition of maximum lift of the airfoil at low Mach numbers. +-0.830241 Cn2 ! As Cn1 for negative AOAs. +Default St_sh ! Strouhal's shedding frequency constant. [default = 0.19] +0.006417 Cd0 ! 2D drag coefficient value at 0-lift. +-0.112920 Cm0 ! 2D pitching moment coefficient about 1/4-chord location, at 0-lift, positive if nose up. [If the aerodynamics coefficients table does not include a column for Cm, this needs to be set to 0.0] +0.000000 k0 ! Constant in the \hat(x)_cp curve best-fit; = (\hat(x)_AC-0.25). [ignored if UAMod<>1] +0.000000 k1 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k2 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k3 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k1_hat ! Constant in the expression of Cc due to leading edge vortex effects. [ignored if UAMod<>1] +Default x_cp_bar ! Constant in the expression of \hat(x)_cp^v. [ignored if UAMod<>1, default = 0.2] +Default UACutout ! Angle of attack above which unsteady aerodynamics are disabled (deg). [Specifying the string "Default" sets UACutout to 45 degrees] +Default filtCutOff ! Cut-off frequency (-3 dB corner frequency) for low-pass filtering the AoA input to UA, as well as the 1st and 2nd derivatives (Hz) [default = 20] +!........................................ +! Table of aerodynamics coefficients +200 NumAlf ! Number of data lines in the following table +! Alpha Cl Cd Cm +! (deg) (-) (-) (-) +-1.80000000000000e+02 0.00000000000000e+00 3.76960000000000e-02 2.00000000000000e-01 +-1.77000000000000e+02 1.49471782056503e-01 3.76960000000000e-02 2.00000000000000e-01 +-1.74000000000000e+02 3.00312917607843e-01 4.52351574641884e-02 2.39999774321882e-01 +-1.71000000000000e+02 4.50470313592540e-01 6.78528773607728e-02 3.60000410445527e-01 +-1.68000000000000e+02 5.62141300000530e-01 9.47828314689296e-02 3.00100237874998e-01 +-1.65000000000000e+02 6.54569530813285e-01 1.23868852352745e-01 1.50251760664942e-01 +-1.62000000000000e+02 7.46998820775784e-01 1.52955206537882e-01 4.01566317437541e-04 +-1.59000000000000e+02 7.99786954801670e-01 1.91656498833410e-01 -9.28123657821359e-02 +-1.56000000000000e+02 7.73294117948629e-01 2.49587342086377e-01 -7.27556892942309e-02 +-1.53000000000000e+02 7.46801078706125e-01 3.07518227898197e-01 -5.26992595835046e-02 +-1.50000000000000e+02 7.20307965658325e-01 3.65449165572087e-01 -3.26429649313102e-02 +-1.47000000000000e+02 7.05570256415403e-01 4.36504328003481e-01 -1.75932576097200e-02 +-1.44000000000000e+02 6.90832490879619e-01 5.07559761840581e-01 -2.54349280354572e-03 +-1.41000000000000e+02 6.76094612754094e-01 5.78615738508475e-01 1.25063869759013e-02 +-1.38000000000000e+02 6.57241666993606e-01 6.52702757782292e-01 2.78005506087711e-02 +-1.35000000000000e+02 6.36331195763501e-01 7.28305292210269e-01 4.32168556727960e-02 +-1.32000000000000e+02 6.15420484918018e-01 8.03908692975958e-01 5.86333373939468e-02 +-1.29000000000000e+02 5.90761760127430e-01 8.77986088072914e-01 7.42048196933640e-02 +-1.26000000000000e+02 5.58606989674918e-01 9.49011464578596e-01 9.00863038811478e-02 +-1.23000000000000e+02 5.26452064865786e-01 1.02003589848443e+00 1.05968066745086e-01 +-1.20000000000000e+02 4.94297062881228e-01 1.09105986110795e+00 1.21849968941892e-01 +-1.17000000000000e+02 4.51046455307775e-01 1.14892719359139e+00 1.36973650595308e-01 +-1.14000000000000e+02 4.07795991243718e-01 1.20679427930608e+00 1.52097072994036e-01 +-1.11000000000000e+02 3.64545857584686e-01 1.26466092295440e+00 1.67219979864852e-01 +-1.08000000000000e+02 3.16034192336304e-01 1.30909600565222e+00 1.80733001904303e-01 +-1.05000000000000e+02 2.64891721229873e-01 1.34681520559943e+00 1.93441069265733e-01 +-1.02000000000000e+02 2.13749236173153e-01 1.38453397332146e+00 2.06148391012093e-01 +-9.90000000000000e+01 1.61688764154489e-01 1.41401796036258e+00 2.17512373571396e-01 +-9.60000000000000e+01 1.07792278449096e-01 1.42703202935019e+00 2.26189619569497e-01 +-9.30000000000000e+01 5.38962044824732e-02 1.44004599891764e+00 2.34866399278379e-01 +-9.00000000000000e+01 3.36381508994621e-07 1.45305991877593e+00 2.43542945846872e-01 +-8.70000000000000e+01 -5.38961493200293e-02 1.44004601223740e+00 2.47180796579284e-01 +-8.40000000000000e+01 -1.07792429155678e-01 1.42703199295995e+00 2.50818601967904e-01 +-8.10000000000000e+01 -1.61688297256642e-01 1.41401807310167e+00 2.54456379565910e-01 +-7.80000000000000e+01 -2.13748988477021e-01 1.38453415600310e+00 2.54821405258420e-01 +-7.50000000000000e+01 -2.64892059585176e-01 1.34681495605404e+00 2.53549998518008e-01 +-7.20000000000000e+01 -3.16033944645590e-01 1.30909618833200e+00 2.52278006351131e-01 +-6.90000000000000e+01 -3.64545482908305e-01 1.26466142425377e+00 2.49759236748571e-01 +-6.60000000000000e+01 -4.07796112179989e-01 1.20679411749904e+00 2.44746810177687e-01 +-6.30000000000000e+01 -4.51046741451673e-01 1.14892681074432e+00 2.39734383606802e-01 +-6.00000000000000e+01 -4.94297275617037e-01 1.09105939121714e+00 2.34721942034639e-01 +-5.70000000000000e+01 -5.26452277601595e-01 1.02003542859361e+00 2.27959383679512e-01 +-5.40000000000000e+01 -5.58607202409195e-01 9.49010994678426e-01 2.21196599493265e-01 +-5.10000000000000e+01 -5.90761972861707e-01 8.77985618172743e-01 2.14433363641336e-01 +-4.80000000000000e+01 -6.17089671120620e-01 8.03911570370645e-01 2.07956980763680e-01 +-4.50000000000000e+01 -6.40503926932036e-01 7.28313235916803e-01 2.01624019763027e-01 +-4.20000000000000e+01 -6.58910840133311e-01 6.52705635149657e-01 1.96862389618034e-01 +-3.90000000000000e+01 -6.76417027511146e-01 5.77527369809482e-01 1.92714494884031e-01 +-3.60000000000000e+01 -6.91442126694186e-01 5.04059360049167e-01 1.90773003374389e-01 +-3.30000000000000e+01 -7.05593958510807e-01 4.33318703053973e-01 1.91908992233939e-01 +-3.00000000000000e+01 -7.20308071684859e-01 3.65448723816258e-01 1.96465039072780e-01 +-2.93939393939394e+01 -7.23687122424702e-01 3.52430090699486e-01 1.98306835359819e-01 +-2.87878787878788e+01 -7.27066173164544e-01 3.39411457582714e-01 2.00148631646857e-01 +-2.81818181818182e+01 -7.30445223904387e-01 3.26392824465942e-01 2.01990427933895e-01 +-2.75757575757576e+01 -7.34244974993610e-01 3.13793078035017e-01 2.04486437101527e-01 +-2.69696969696970e+01 -7.38225041700157e-01 3.01372869870364e-01 2.07262847270964e-01 +-2.63636363636364e+01 -7.42205108406705e-01 2.88952661705710e-01 2.10039257440401e-01 +-2.57575757575758e+01 -7.46555462653963e-01 2.76796374908870e-01 2.13304160376248e-01 +-2.51515151515151e+01 -7.51461161912085e-01 2.65035908653530e-01 2.17301688612281e-01 +-2.45454545454545e+01 -7.56366861170206e-01 2.53275442398190e-01 2.21299216848314e-01 +-2.39393939393939e+01 -7.61408677387006e-01 2.41586670872199e-01 2.25459952105595e-01 +-2.33333333333333e+01 -7.67675572584808e-01 2.30543165790786e-01 2.31089582151761e-01 +-2.27272727272727e+01 -7.73942467782610e-01 2.19499660709374e-01 2.36719212197927e-01 +-2.21212121212121e+01 -7.80209362980412e-01 2.08456155627962e-01 2.42348842244093e-01 +-2.15151515151515e+01 -7.88045801889462e-01 1.98028860914946e-01 2.49772963288095e-01 +-2.09090909090909e+01 -7.96274727686348e-01 1.87755658431417e-01 2.57645822511188e-01 +-2.03030303030303e+01 -8.04503653483233e-01 1.77482455947888e-01 2.65518681734281e-01 +-1.96969696969697e+01 -8.13721563222721e-01 1.67514267203666e-01 2.74509167058282e-01 +-1.90909090909091e+01 -8.23928400957602e-01 1.57851074944005e-01 2.84617215258648e-01 +-1.84848484848485e+01 -8.22646763588942e-01 1.48546901850923e-01 2.82973548468764e-01 +-1.78787878787879e+01 -8.19241173382965e-01 1.39555143470384e-01 2.78335696038153e-01 +-1.72727272727273e+01 -8.15446564330172e-01 1.31559857952983e-01 2.70013132308244e-01 +-1.66666666666667e+01 -8.03296442896411e-01 1.23564572435581e-01 2.53038383173389e-01 +-1.60606060606061e+01 -7.84310064075638e-01 1.15569286918180e-01 2.28984646695628e-01 +-1.54545454545455e+01 -7.65324664303493e-01 1.07574959135167e-01 2.04931605118311e-01 +-1.48484848484848e+01 -7.46338949873589e-01 9.95804717419686e-02 1.80878447733115e-01 +-1.42424242424242e+01 -7.27351964982053e-01 9.15851862245671e-02 1.56824711255353e-01 +-1.36363636363636e+01 -7.08366360011050e-01 8.35901755495681e-02 1.32771801638210e-01 +-1.30303030303030e+01 -6.89379049576426e-01 7.55946380877238e-02 1.08716367776058e-01 +-1.24242424242424e+01 -6.70393771825338e-01 6.75996503421813e-02 8.46634665540094e-02 +-1.18181818181818e+01 -6.51406715493019e-01 5.96041815994351e-02 6.06091788446317e-02 +-1.12121212121212e+01 -6.32421454753742e-01 5.16093541595814e-02 3.65562447387649e-02 +-1.06060606060606e+01 -6.13434931389144e-01 4.36139312036515e-02 1.25016705283901e-02 +-1.00000000000000e+01 -5.94448865749824e-01 3.56199434645880e-02 -1.15511700947924e-02 +-9.39393939393939e+00 -5.75463587974779e-01 2.76249557125666e-02 -3.56050107398163e-02 +-8.78787878787879e+00 -5.51403736673166e-01 2.01382292840361e-02 -5.87079533337773e-02 +-8.18181818181818e+00 -5.17926305822838e-01 1.35966762681340e-02 -8.00434824257992e-02 +-7.57575757575758e+00 -4.48012922709353e-01 1.04062079021576e-02 -9.38202376741164e-02 +-6.96969696969697e+00 -3.62306556115099e-01 8.91516259682331e-03 -1.02639375733790e-01 +-6.36363636363636e+00 -2.86592508663283e-01 7.49091941073086e-03 -1.05345402946346e-01 +-5.75757575757576e+00 -2.11681301136276e-01 7.05454293237208e-03 -1.07624256716558e-01 +-5.15151515151515e+00 -1.37278254009080e-01 6.76061420557612e-03 -1.09615086355391e-01 +-4.54545454545454e+00 -6.32445813538124e-02 6.51817895525840e-03 -1.11463657835562e-01 +-3.93939393939394e+00 1.03326972358679e-02 6.40000000000000e-03 -1.13157562089366e-01 +-3.33333333333333e+00 8.37358252318253e-02 6.36666256139732e-03 -1.14700049263232e-01 +-2.72727272727273e+00 1.57144966549608e-01 6.30000000000000e-03 -1.16209080405869e-01 +-2.12121212121212e+00 2.30132082000148e-01 6.30000000000000e-03 -1.17633365893514e-01 +-1.51515151515152e+00 3.03270194866406e-01 6.30000000000000e-03 -1.18966675734322e-01 +-9.09090909090912e-01 3.76007887483945e-01 6.30000000000000e-03 -1.20399977937206e-01 +-3.03030303030302e-01 4.48619648411214e-01 6.33939639599868e-03 -1.21733360355986e-01 + 3.03030303030302e-01 5.21162162400790e-01 6.40000000000000e-03 -1.23066639644014e-01 + 9.09090909090912e-01 5.93483011578421e-01 6.40000000000000e-03 -1.24318201875268e-01 + 1.51515151515152e+00 6.65499510346614e-01 6.50000000000000e-03 -1.25430294786980e-01 + 2.12121212121212e+00 7.37449762821818e-01 6.52423946422604e-03 -1.26642394642260e-01 + 2.72727272727273e+00 8.08982292442682e-01 6.64545535339469e-03 -1.27809098180552e-01 + 3.33333333333333e+00 8.80397573785818e-01 6.76666256139732e-03 -1.28833300491179e-01 + 3.93939393939394e+00 9.51421826139261e-01 6.88787983927956e-03 -1.29890918553516e-01 + 4.54545454545455e+00 1.02186280754731e+00 7.00908947762920e-03 -1.30763626343404e-01 + 5.15151515151515e+00 1.09189627700035e+00 7.16061420557612e-03 -1.31612149719516e-01 + 5.75757575757576e+00 1.16079952835358e+00 7.45454293237208e-03 -1.32306057243163e-01 + 6.36363636363637e+00 1.22720139059598e+00 7.96364926341358e-03 -1.32572729852683e-01 + 6.96969696969697e+00 1.28802463107430e+00 8.94546166938641e-03 -1.32130299072563e-01 + 7.57575757575757e+00 1.33932330958836e+00 1.07272369407300e-02 -1.30081868282978e-01 + 8.18181818181818e+00 1.38679186165234e+00 1.25091248425769e-02 -1.27572678796319e-01 + 8.78787878787879e+00 1.43442629439737e+00 1.40333059500537e-02 -1.25090961368079e-01 + 9.39393939393939e+00 1.48072485366775e+00 1.53666845487907e-02 -1.22230262389112e-01 + 1.00000000000000e+01 1.51619976429293e+00 1.64999922859505e-02 -1.21700000000000e-01 + 1.06060606060606e+01 1.54652659135150e+00 1.81605492792916e-02 -1.21700000000000e-01 + 1.12121212121212e+01 1.57015165312925e+00 2.03485003516014e-02 -1.21912125087900e-01 + 1.18181818181818e+01 1.58466335911404e+00 3.00903504536651e-02 -1.23218115609323e-01 + 1.24242424242424e+01 1.55439065028940e+00 4.64546360854226e-02 -1.25157586499013e-01 + 1.30303030303030e+01 1.50697060273102e+00 6.28179372626244e-02 -1.27096940712607e-01 + 1.36363636363636e+01 1.44636161651328e+00 7.91823635414146e-02 -1.29036428271575e-01 + 1.42424242424242e+01 1.39302963646758e+00 9.22728558241098e-02 -1.30587894023598e-01 + 1.48484848484848e+01 1.35060468299441e+00 1.00454811136793e-01 -1.31557607245842e-01 + 1.54545454545455e+01 1.32181803006545e+00 1.08636414852911e-01 -1.32527278797382e-01 + 1.60606060606061e+01 1.29757644961134e+00 1.16817948256172e-01 -1.33496942015546e-01 + 1.66666666666667e+01 1.27333361905524e+00 1.24999903568856e-01 -1.34466655237790e-01 + 1.72727272727273e+01 1.24363618274871e+00 1.33181858881539e-01 -1.35436368460034e-01 + 1.78787878787879e+01 1.20727193691457e+00 1.41363814194223e-01 -1.36406081682278e-01 + 1.84848484848485e+01 1.18992978938591e+00 1.49497879761678e-01 -1.37375750456550e-01 + 1.90909090909091e+01 1.17704330010331e+00 1.57851074944005e-01 -1.39089585145003e-01 + 1.96969696969697e+01 1.16246123752382e+00 1.67514267203666e-01 -1.45021805782080e-01 + 2.03030303030303e+01 1.14929279501435e+00 1.77482455947888e-01 -1.51632351934001e-01 + 2.09090909090909e+01 1.13753805254846e+00 1.87755658431417e-01 -1.58921261976074e-01 + 2.15151515151515e+01 1.12578331008257e+00 1.98028860914946e-01 -1.66210172018147e-01 + 2.21212121212121e+01 1.11458874358451e+00 2.08456155627962e-01 -1.73224623443957e-01 + 2.27272727272727e+01 1.10563430457793e+00 2.19499660709374e-01 -1.79141522802416e-01 + 2.33333333333333e+01 1.09667986557135e+00 2.30543165790786e-01 -1.85058422160874e-01 + 2.39393939393939e+01 1.08772542656477e+00 2.41586670872199e-01 -1.90975321519332e-01 + 2.45454545454545e+01 1.08052187960139e+00 2.53275442398190e-01 -1.96074592475065e-01 + 2.51515151515151e+01 1.07351287201350e+00 2.65035908653530e-01 -2.01083017784734e-01 + 2.57575757575758e+01 1.06650386442561e+00 2.76796374908870e-01 -2.06091443094404e-01 + 2.63636363636364e+01 1.06028924575223e+00 2.88952661705710e-01 -2.10729607665482e-01 + 2.69696969696970e+01 1.05460430198682e+00 3.01372869870364e-01 -2.15120893385337e-01 + 2.75757575757576e+01 1.04891935822142e+00 3.13793078035017e-01 -2.19512179105193e-01 + 2.81818181818182e+01 1.04349174843484e+00 3.26392824465942e-01 -2.23774966350859e-01 + 2.87878787878788e+01 1.03866453309221e+00 3.39411457582714e-01 -2.27737949543009e-01 + 2.93939393939394e+01 1.03383731774957e+00 3.52430090699486e-01 -2.31700932735158e-01 + 3.00000000000000e+01 1.02901010240694e+00 3.65448723816258e-01 -2.35663915927308e-01 + 3.30000000000000e+01 1.00799494072346e+00 4.33318703053973e-01 -2.53423049843193e-01 + 3.60000000000000e+01 9.87774181033947e-01 5.04059360049167e-01 -2.69936854350083e-01 + 3.90000000000000e+01 9.66310039303889e-01 5.77527369809482e-01 -2.85448473353340e-01 + 4.20000000000000e+01 9.41301057332367e-01 6.52705635149657e-01 -3.00284968060017e-01 + 4.50000000000000e+01 9.15005895616392e-01 7.28313235916803e-01 -3.14934043892456e-01 + 4.80000000000000e+01 8.81556701601667e-01 8.03911570370646e-01 -3.28999157277327e-01 + 5.10000000000000e+01 8.43945446946677e-01 8.77985618172744e-01 -3.42814128421300e-01 + 5.40000000000000e+01 7.98009803441727e-01 9.49010994678426e-01 -3.56128799002399e-01 + 5.70000000000000e+01 7.52074110859421e-01 1.02003542859361e+00 -3.69443367867275e-01 + 6.00000000000000e+01 7.06138393738624e-01 1.09105939121714e+00 -3.82757885874428e-01 + 6.30000000000000e+01 6.44352602071576e-01 1.14892681074432e+00 -3.94831160514253e-01 + 6.60000000000000e+01 5.82566474543015e-01 1.20679411749904e+00 -4.06904424514653e-01 + 6.90000000000000e+01 5.20779947012492e-01 1.26466142425377e+00 -4.18977688515053e-01 + 7.20000000000000e+01 4.51477435205418e-01 1.30909618833200e+00 -4.29844051243441e-01 + 7.50000000000000e+01 3.78417085122278e-01 1.34681495605404e+00 -4.40106988042700e-01 + 7.80000000000000e+01 3.05355897825734e-01 1.38453415600310e+00 -4.50369442444556e-01 + 8.10000000000000e+01 2.30983767510451e-01 1.41401807310167e+00 -4.59788643436343e-01 + 8.40000000000000e+01 1.53989841650875e-01 1.42703199295995e+00 -4.67521395816866e-01 + 8.70000000000000e+01 7.69949275996385e-02 1.44004601223740e+00 -4.75253807270785e-01 + 9.00000000000000e+01 -3.36381509228363e-07 1.45305991877593e+00 -4.82986022704544e-01 + 9.30000000000000e+01 -5.38962044824732e-02 1.44004599891764e+00 -4.86623800302551e-01 + 9.60000000000000e+01 -1.07792278449097e-01 1.42703202935019e+00 -4.90261391797104e-01 + 9.90000000000000e+01 -1.61688764154490e-01 1.41401796036258e+00 -4.93898611078011e-01 + 1.02000000000000e+02 -2.13749236173153e-01 1.38453397332146e+00 -4.94263399100743e-01 + 1.05000000000000e+02 -2.64891721229873e-01 1.34681520559943e+00 -4.92992006930171e-01 + 1.08000000000000e+02 -3.16034192336304e-01 1.30909600565222e+00 -4.91720000190610e-01 + 1.11000000000000e+02 -3.64545857584686e-01 1.26466092295440e+00 -4.89201393327162e-01 + 1.14000000000000e+02 -4.07795991243718e-01 1.20679427930608e+00 -4.84189624190406e-01 + 1.17000000000000e+02 -4.51046455307775e-01 1.14892719359139e+00 -4.79177416768754e-01 + 1.20000000000000e+02 -4.94297062881228e-01 1.09105986110795e+00 -4.74164986774198e-01 + 1.23000000000000e+02 -5.26452064865786e-01 1.02003589848443e+00 -4.67401828422766e-01 + 1.26000000000000e+02 -5.58606989674918e-01 9.49011464578596e-01 -4.60638644238479e-01 + 1.29000000000000e+02 -5.90761760127430e-01 8.77986088072913e-01 -4.53875408386550e-01 + 1.32000000000000e+02 -6.15420484918018e-01 8.03908692975958e-01 -4.47922977473614e-01 + 1.35000000000000e+02 -6.36331195763501e-01 7.28305292210269e-01 -4.42375948063776e-01 + 1.38000000000000e+02 -6.57241666993606e-01 6.52702757782291e-01 -4.36828382226539e-01 + 1.41000000000000e+02 -6.76094612754094e-01 5.78615738508474e-01 -4.33407800721224e-01 + 1.44000000000000e+02 -6.90832490879619e-01 5.07559761840581e-01 -4.34241205139103e-01 + 1.47000000000000e+02 -7.05570256415403e-01 4.36504328003481e-01 -4.35074603190205e-01 + 1.50000000000000e+02 -7.20307965658325e-01 3.65449165572087e-01 -4.35907998058031e-01 + 1.53000000000000e+02 -7.46801078706125e-01 3.07518227898197e-01 -4.57805065052203e-01 + 1.56000000000000e+02 -7.73294117948629e-01 2.49587342086377e-01 -4.79701897484255e-01 + 1.59000000000000e+02 -7.99786954801670e-01 1.91656498833410e-01 -5.01598162643690e-01 + 1.62000000000000e+02 -7.40790822868899e-01 1.53560806333696e-01 -5.07117800599882e-01 + 1.65000000000000e+02 -6.39049483540701e-01 1.25382856960915e-01 -5.04448986449602e-01 + 1.68000000000000e+02 -5.37308710076014e-01 9.72046304867630e-02 -5.01779602888076e-01 + 1.71000000000000e+02 -4.22533481739914e-01 7.05772804657932e-02 -4.50000513056908e-01 + 1.74000000000000e+02 -2.81688735121593e-01 4.70517557569334e-02 -2.99999717902353e-01 + 1.77000000000000e+02 -1.40202251216632e-01 3.86002570677554e-02 -6.87686132694523e-02 + 1.80000000000000e+02 0.00000000000000e+00 3.76960000000000e-02 2.00000000000000e-01 diff --git a/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_29.dat b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_29.dat new file mode 100644 index 00000000..31764aed --- /dev/null +++ b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_29.dat @@ -0,0 +1,254 @@ +! ------------ AirfoilInfo v1.01.x Input File ---------------------------------- +! AeroElasticSE FAST driver +! line +! line +! ------------------------------------------------------------------------------ +DEFAULT InterpOrd ! Interpolation order to use for quasi-steady table lookup {1=linear; 3=cubic spline; "default"} [default=3] +1 NonDimArea ! The non-dimensional area of the airfoil (area/chord^2) (set to 1.0 if unsure or unneeded) +@"NREL-2p8-127_AF29_Coords.txt" NumCoords ! The number of coordinates in the airfoil shape file. Set to zero if coordinates not included. +AF29_BL.txt BL_file ! The file name including the boundary layer characteristics of the profile. Ignored if the aeroacoustic module is not called. +1 NumTabs ! Number of airfoil tables in this file. Each table must have lines for Re and Ctrl. +! ------------------------------------------------------------------------------ +! data for table 1 +! ------------------------------------------------------------------------------ +6.000000 Re ! Reynolds number in millions +0 Ctrl ! Control setting (must be 0 for current AirfoilInfo) +True InclUAdata ! Is unsteady aerodynamics data included in this table? If TRUE, then include 30 UA coefficients below this line +!........................................ +-4.024505 alpha0 ! 0-lift angle of attack, depends on airfoil. +11.306884 alpha1 ! Angle of attack at f=0.7, (approximately the stall angle) for AOA>alpha0. (deg) +-9.832557 alpha2 ! Angle of attack at f=0.7, (approximately the stall angle) for AOA1] +0.000000 S2 ! Constant in the f curve best-fit for AOA> alpha1; by definition it depends on the airfoil. [ignored if UAMod<>1] +0.000000 S3 ! Constant in the f curve best-fit for alpha2<=AOA< alpha0; by definition it depends on the airfoil. [ignored if UAMod<>1] +0.000000 S4 ! Constant in the f curve best-fit for AOA< alpha2; by definition it depends on the airfoil. [ignored if UAMod<>1] +1.557235 Cn1 ! Critical value of C0n at leading edge separation. It should be extracted from airfoil data at a given Mach and Reynolds number. It can be calculated from the static value of Cn at either the break in the pitching moment or the loss of chord force at the onset of stall. It is close to the condition of maximum lift of the airfoil at low Mach numbers. +-0.830241 Cn2 ! As Cn1 for negative AOAs. +Default St_sh ! Strouhal's shedding frequency constant. [default = 0.19] +0.006417 Cd0 ! 2D drag coefficient value at 0-lift. +-0.112920 Cm0 ! 2D pitching moment coefficient about 1/4-chord location, at 0-lift, positive if nose up. [If the aerodynamics coefficients table does not include a column for Cm, this needs to be set to 0.0] +0.000000 k0 ! Constant in the \hat(x)_cp curve best-fit; = (\hat(x)_AC-0.25). [ignored if UAMod<>1] +0.000000 k1 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k2 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k3 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k1_hat ! Constant in the expression of Cc due to leading edge vortex effects. [ignored if UAMod<>1] +Default x_cp_bar ! Constant in the expression of \hat(x)_cp^v. [ignored if UAMod<>1, default = 0.2] +Default UACutout ! Angle of attack above which unsteady aerodynamics are disabled (deg). [Specifying the string "Default" sets UACutout to 45 degrees] +Default filtCutOff ! Cut-off frequency (-3 dB corner frequency) for low-pass filtering the AoA input to UA, as well as the 1st and 2nd derivatives (Hz) [default = 20] +!........................................ +! Table of aerodynamics coefficients +200 NumAlf ! Number of data lines in the following table +! Alpha Cl Cd Cm +! (deg) (-) (-) (-) +-1.80000000000000e+02 0.00000000000000e+00 3.76960000000000e-02 2.00000000000000e-01 +-1.77000000000000e+02 1.49471782056503e-01 3.76960000000000e-02 2.00000000000000e-01 +-1.74000000000000e+02 3.00312917607843e-01 4.52351574641884e-02 2.39999774321882e-01 +-1.71000000000000e+02 4.50470313592540e-01 6.78528773607728e-02 3.60000410445527e-01 +-1.68000000000000e+02 5.62141300000530e-01 9.47828314689296e-02 3.00100237874998e-01 +-1.65000000000000e+02 6.54569530813285e-01 1.23868852352745e-01 1.50251760664942e-01 +-1.62000000000000e+02 7.46998820775784e-01 1.52955206537882e-01 4.01566317437541e-04 +-1.59000000000000e+02 7.99786954801670e-01 1.91656498833410e-01 -9.28123657821359e-02 +-1.56000000000000e+02 7.73294117948629e-01 2.49587342086377e-01 -7.27556892942309e-02 +-1.53000000000000e+02 7.46801078706125e-01 3.07518227898197e-01 -5.26992595835046e-02 +-1.50000000000000e+02 7.20307965658325e-01 3.65449165572087e-01 -3.26429649313102e-02 +-1.47000000000000e+02 7.05570256415403e-01 4.36504328003481e-01 -1.75932576097200e-02 +-1.44000000000000e+02 6.90832490879619e-01 5.07559761840581e-01 -2.54349280354572e-03 +-1.41000000000000e+02 6.76094612754094e-01 5.78615738508475e-01 1.25063869759013e-02 +-1.38000000000000e+02 6.57241666993606e-01 6.52702757782292e-01 2.78005506087711e-02 +-1.35000000000000e+02 6.36331195763501e-01 7.28305292210269e-01 4.32168556727960e-02 +-1.32000000000000e+02 6.15420484918018e-01 8.03908692975958e-01 5.86333373939468e-02 +-1.29000000000000e+02 5.90761760127430e-01 8.77986088072914e-01 7.42048196933640e-02 +-1.26000000000000e+02 5.58606989674918e-01 9.49011464578596e-01 9.00863038811478e-02 +-1.23000000000000e+02 5.26452064865786e-01 1.02003589848443e+00 1.05968066745086e-01 +-1.20000000000000e+02 4.94297062881228e-01 1.09105986110795e+00 1.21849968941892e-01 +-1.17000000000000e+02 4.51046455307775e-01 1.14892719359139e+00 1.36973650595308e-01 +-1.14000000000000e+02 4.07795991243718e-01 1.20679427930608e+00 1.52097072994036e-01 +-1.11000000000000e+02 3.64545857584686e-01 1.26466092295440e+00 1.67219979864852e-01 +-1.08000000000000e+02 3.16034192336304e-01 1.30909600565222e+00 1.80733001904303e-01 +-1.05000000000000e+02 2.64891721229873e-01 1.34681520559943e+00 1.93441069265733e-01 +-1.02000000000000e+02 2.13749236173153e-01 1.38453397332146e+00 2.06148391012093e-01 +-9.90000000000000e+01 1.61688764154489e-01 1.41401796036258e+00 2.17512373571396e-01 +-9.60000000000000e+01 1.07792278449096e-01 1.42703202935019e+00 2.26189619569497e-01 +-9.30000000000000e+01 5.38962044824732e-02 1.44004599891764e+00 2.34866399278379e-01 +-9.00000000000000e+01 3.36381508994621e-07 1.45305991877593e+00 2.43542945846872e-01 +-8.70000000000000e+01 -5.38961493200293e-02 1.44004601223740e+00 2.47180796579284e-01 +-8.40000000000000e+01 -1.07792429155678e-01 1.42703199295995e+00 2.50818601967904e-01 +-8.10000000000000e+01 -1.61688297256642e-01 1.41401807310167e+00 2.54456379565910e-01 +-7.80000000000000e+01 -2.13748988477021e-01 1.38453415600310e+00 2.54821405258420e-01 +-7.50000000000000e+01 -2.64892059585176e-01 1.34681495605404e+00 2.53549998518008e-01 +-7.20000000000000e+01 -3.16033944645590e-01 1.30909618833200e+00 2.52278006351131e-01 +-6.90000000000000e+01 -3.64545482908305e-01 1.26466142425377e+00 2.49759236748571e-01 +-6.60000000000000e+01 -4.07796112179989e-01 1.20679411749904e+00 2.44746810177687e-01 +-6.30000000000000e+01 -4.51046741451673e-01 1.14892681074432e+00 2.39734383606802e-01 +-6.00000000000000e+01 -4.94297275617037e-01 1.09105939121714e+00 2.34721942034639e-01 +-5.70000000000000e+01 -5.26452277601595e-01 1.02003542859361e+00 2.27959383679512e-01 +-5.40000000000000e+01 -5.58607202409195e-01 9.49010994678426e-01 2.21196599493265e-01 +-5.10000000000000e+01 -5.90761972861707e-01 8.77985618172743e-01 2.14433363641336e-01 +-4.80000000000000e+01 -6.17089671120620e-01 8.03911570370645e-01 2.07956980763680e-01 +-4.50000000000000e+01 -6.40503926932036e-01 7.28313235916803e-01 2.01624019763027e-01 +-4.20000000000000e+01 -6.58910840133311e-01 6.52705635149657e-01 1.96862389618034e-01 +-3.90000000000000e+01 -6.76417027511146e-01 5.77527369809482e-01 1.92714494884031e-01 +-3.60000000000000e+01 -6.91442126694186e-01 5.04059360049167e-01 1.90773003374389e-01 +-3.30000000000000e+01 -7.05593958510807e-01 4.33318703053973e-01 1.91908992233939e-01 +-3.00000000000000e+01 -7.20308071684859e-01 3.65448723816258e-01 1.96465039072780e-01 +-2.93939393939394e+01 -7.23687122424702e-01 3.52430090699486e-01 1.98306835359819e-01 +-2.87878787878788e+01 -7.27066173164544e-01 3.39411457582714e-01 2.00148631646857e-01 +-2.81818181818182e+01 -7.30445223904387e-01 3.26392824465942e-01 2.01990427933895e-01 +-2.75757575757576e+01 -7.34244974993610e-01 3.13793078035017e-01 2.04486437101527e-01 +-2.69696969696970e+01 -7.38225041700157e-01 3.01372869870364e-01 2.07262847270964e-01 +-2.63636363636364e+01 -7.42205108406705e-01 2.88952661705710e-01 2.10039257440401e-01 +-2.57575757575758e+01 -7.46555462653963e-01 2.76796374908870e-01 2.13304160376248e-01 +-2.51515151515151e+01 -7.51461161912085e-01 2.65035908653530e-01 2.17301688612281e-01 +-2.45454545454545e+01 -7.56366861170206e-01 2.53275442398190e-01 2.21299216848314e-01 +-2.39393939393939e+01 -7.61408677387006e-01 2.41586670872199e-01 2.25459952105595e-01 +-2.33333333333333e+01 -7.67675572584808e-01 2.30543165790786e-01 2.31089582151761e-01 +-2.27272727272727e+01 -7.73942467782610e-01 2.19499660709374e-01 2.36719212197927e-01 +-2.21212121212121e+01 -7.80209362980412e-01 2.08456155627962e-01 2.42348842244093e-01 +-2.15151515151515e+01 -7.88045801889462e-01 1.98028860914946e-01 2.49772963288095e-01 +-2.09090909090909e+01 -7.96274727686348e-01 1.87755658431417e-01 2.57645822511188e-01 +-2.03030303030303e+01 -8.04503653483233e-01 1.77482455947888e-01 2.65518681734281e-01 +-1.96969696969697e+01 -8.13721563222721e-01 1.67514267203666e-01 2.74509167058282e-01 +-1.90909090909091e+01 -8.23928400957602e-01 1.57851074944005e-01 2.84617215258648e-01 +-1.84848484848485e+01 -8.22646763588942e-01 1.48546901850923e-01 2.82973548468764e-01 +-1.78787878787879e+01 -8.19241173382965e-01 1.39555143470384e-01 2.78335696038153e-01 +-1.72727272727273e+01 -8.15446564330172e-01 1.31559857952983e-01 2.70013132308244e-01 +-1.66666666666667e+01 -8.03296442896411e-01 1.23564572435581e-01 2.53038383173389e-01 +-1.60606060606061e+01 -7.84310064075638e-01 1.15569286918180e-01 2.28984646695628e-01 +-1.54545454545455e+01 -7.65324664303493e-01 1.07574959135167e-01 2.04931605118311e-01 +-1.48484848484848e+01 -7.46338949873589e-01 9.95804717419686e-02 1.80878447733115e-01 +-1.42424242424242e+01 -7.27351964982053e-01 9.15851862245671e-02 1.56824711255353e-01 +-1.36363636363636e+01 -7.08366360011050e-01 8.35901755495681e-02 1.32771801638210e-01 +-1.30303030303030e+01 -6.89379049576426e-01 7.55946380877238e-02 1.08716367776058e-01 +-1.24242424242424e+01 -6.70393771825338e-01 6.75996503421813e-02 8.46634665540094e-02 +-1.18181818181818e+01 -6.51406715493019e-01 5.96041815994351e-02 6.06091788446317e-02 +-1.12121212121212e+01 -6.32421454753742e-01 5.16093541595814e-02 3.65562447387649e-02 +-1.06060606060606e+01 -6.13434931389144e-01 4.36139312036515e-02 1.25016705283901e-02 +-1.00000000000000e+01 -5.94448865749824e-01 3.56199434645880e-02 -1.15511700947924e-02 +-9.39393939393939e+00 -5.75463587974779e-01 2.76249557125666e-02 -3.56050107398163e-02 +-8.78787878787879e+00 -5.51403736673166e-01 2.01382292840361e-02 -5.87079533337773e-02 +-8.18181818181818e+00 -5.17926305822838e-01 1.35966762681340e-02 -8.00434824257992e-02 +-7.57575757575758e+00 -4.48012922709353e-01 1.04062079021576e-02 -9.38202376741164e-02 +-6.96969696969697e+00 -3.62306556115099e-01 8.91516259682331e-03 -1.02639375733790e-01 +-6.36363636363636e+00 -2.86592508663283e-01 7.49091941073086e-03 -1.05345402946346e-01 +-5.75757575757576e+00 -2.11681301136276e-01 7.05454293237208e-03 -1.07624256716558e-01 +-5.15151515151515e+00 -1.37278254009080e-01 6.76061420557612e-03 -1.09615086355391e-01 +-4.54545454545454e+00 -6.32445813538124e-02 6.51817895525840e-03 -1.11463657835562e-01 +-3.93939393939394e+00 1.03326972358679e-02 6.40000000000000e-03 -1.13157562089366e-01 +-3.33333333333333e+00 8.37358252318253e-02 6.36666256139732e-03 -1.14700049263232e-01 +-2.72727272727273e+00 1.57144966549608e-01 6.30000000000000e-03 -1.16209080405869e-01 +-2.12121212121212e+00 2.30132082000148e-01 6.30000000000000e-03 -1.17633365893514e-01 +-1.51515151515152e+00 3.03270194866406e-01 6.30000000000000e-03 -1.18966675734322e-01 +-9.09090909090912e-01 3.76007887483945e-01 6.30000000000000e-03 -1.20399977937206e-01 +-3.03030303030302e-01 4.48619648411214e-01 6.33939639599868e-03 -1.21733360355986e-01 + 3.03030303030302e-01 5.21162162400790e-01 6.40000000000000e-03 -1.23066639644014e-01 + 9.09090909090912e-01 5.93483011578421e-01 6.40000000000000e-03 -1.24318201875268e-01 + 1.51515151515152e+00 6.65499510346614e-01 6.50000000000000e-03 -1.25430294786980e-01 + 2.12121212121212e+00 7.37449762821818e-01 6.52423946422604e-03 -1.26642394642260e-01 + 2.72727272727273e+00 8.08982292442682e-01 6.64545535339469e-03 -1.27809098180552e-01 + 3.33333333333333e+00 8.80397573785818e-01 6.76666256139732e-03 -1.28833300491179e-01 + 3.93939393939394e+00 9.51421826139261e-01 6.88787983927956e-03 -1.29890918553516e-01 + 4.54545454545455e+00 1.02186280754731e+00 7.00908947762920e-03 -1.30763626343404e-01 + 5.15151515151515e+00 1.09189627700035e+00 7.16061420557612e-03 -1.31612149719516e-01 + 5.75757575757576e+00 1.16079952835358e+00 7.45454293237208e-03 -1.32306057243163e-01 + 6.36363636363637e+00 1.22720139059598e+00 7.96364926341358e-03 -1.32572729852683e-01 + 6.96969696969697e+00 1.28802463107430e+00 8.94546166938641e-03 -1.32130299072563e-01 + 7.57575757575757e+00 1.33932330958836e+00 1.07272369407300e-02 -1.30081868282978e-01 + 8.18181818181818e+00 1.38679186165234e+00 1.25091248425769e-02 -1.27572678796319e-01 + 8.78787878787879e+00 1.43442629439737e+00 1.40333059500537e-02 -1.25090961368079e-01 + 9.39393939393939e+00 1.48072485366775e+00 1.53666845487907e-02 -1.22230262389112e-01 + 1.00000000000000e+01 1.51619976429293e+00 1.64999922859505e-02 -1.21700000000000e-01 + 1.06060606060606e+01 1.54652659135150e+00 1.81605492792916e-02 -1.21700000000000e-01 + 1.12121212121212e+01 1.57015165312925e+00 2.03485003516014e-02 -1.21912125087900e-01 + 1.18181818181818e+01 1.58466335911404e+00 3.00903504536651e-02 -1.23218115609323e-01 + 1.24242424242424e+01 1.55439065028940e+00 4.64546360854226e-02 -1.25157586499013e-01 + 1.30303030303030e+01 1.50697060273102e+00 6.28179372626244e-02 -1.27096940712607e-01 + 1.36363636363636e+01 1.44636161651328e+00 7.91823635414146e-02 -1.29036428271575e-01 + 1.42424242424242e+01 1.39302963646758e+00 9.22728558241098e-02 -1.30587894023598e-01 + 1.48484848484848e+01 1.35060468299441e+00 1.00454811136793e-01 -1.31557607245842e-01 + 1.54545454545455e+01 1.32181803006545e+00 1.08636414852911e-01 -1.32527278797382e-01 + 1.60606060606061e+01 1.29757644961134e+00 1.16817948256172e-01 -1.33496942015546e-01 + 1.66666666666667e+01 1.27333361905524e+00 1.24999903568856e-01 -1.34466655237790e-01 + 1.72727272727273e+01 1.24363618274871e+00 1.33181858881539e-01 -1.35436368460034e-01 + 1.78787878787879e+01 1.20727193691457e+00 1.41363814194223e-01 -1.36406081682278e-01 + 1.84848484848485e+01 1.18992978938591e+00 1.49497879761678e-01 -1.37375750456550e-01 + 1.90909090909091e+01 1.17704330010331e+00 1.57851074944005e-01 -1.39089585145003e-01 + 1.96969696969697e+01 1.16246123752382e+00 1.67514267203666e-01 -1.45021805782080e-01 + 2.03030303030303e+01 1.14929279501435e+00 1.77482455947888e-01 -1.51632351934001e-01 + 2.09090909090909e+01 1.13753805254846e+00 1.87755658431417e-01 -1.58921261976074e-01 + 2.15151515151515e+01 1.12578331008257e+00 1.98028860914946e-01 -1.66210172018147e-01 + 2.21212121212121e+01 1.11458874358451e+00 2.08456155627962e-01 -1.73224623443957e-01 + 2.27272727272727e+01 1.10563430457793e+00 2.19499660709374e-01 -1.79141522802416e-01 + 2.33333333333333e+01 1.09667986557135e+00 2.30543165790786e-01 -1.85058422160874e-01 + 2.39393939393939e+01 1.08772542656477e+00 2.41586670872199e-01 -1.90975321519332e-01 + 2.45454545454545e+01 1.08052187960139e+00 2.53275442398190e-01 -1.96074592475065e-01 + 2.51515151515151e+01 1.07351287201350e+00 2.65035908653530e-01 -2.01083017784734e-01 + 2.57575757575758e+01 1.06650386442561e+00 2.76796374908870e-01 -2.06091443094404e-01 + 2.63636363636364e+01 1.06028924575223e+00 2.88952661705710e-01 -2.10729607665482e-01 + 2.69696969696970e+01 1.05460430198682e+00 3.01372869870364e-01 -2.15120893385337e-01 + 2.75757575757576e+01 1.04891935822142e+00 3.13793078035017e-01 -2.19512179105193e-01 + 2.81818181818182e+01 1.04349174843484e+00 3.26392824465942e-01 -2.23774966350859e-01 + 2.87878787878788e+01 1.03866453309221e+00 3.39411457582714e-01 -2.27737949543009e-01 + 2.93939393939394e+01 1.03383731774957e+00 3.52430090699486e-01 -2.31700932735158e-01 + 3.00000000000000e+01 1.02901010240694e+00 3.65448723816258e-01 -2.35663915927308e-01 + 3.30000000000000e+01 1.00799494072346e+00 4.33318703053973e-01 -2.53423049843193e-01 + 3.60000000000000e+01 9.87774181033947e-01 5.04059360049167e-01 -2.69936854350083e-01 + 3.90000000000000e+01 9.66310039303889e-01 5.77527369809482e-01 -2.85448473353340e-01 + 4.20000000000000e+01 9.41301057332367e-01 6.52705635149657e-01 -3.00284968060017e-01 + 4.50000000000000e+01 9.15005895616392e-01 7.28313235916803e-01 -3.14934043892456e-01 + 4.80000000000000e+01 8.81556701601667e-01 8.03911570370646e-01 -3.28999157277327e-01 + 5.10000000000000e+01 8.43945446946677e-01 8.77985618172744e-01 -3.42814128421300e-01 + 5.40000000000000e+01 7.98009803441727e-01 9.49010994678426e-01 -3.56128799002399e-01 + 5.70000000000000e+01 7.52074110859421e-01 1.02003542859361e+00 -3.69443367867275e-01 + 6.00000000000000e+01 7.06138393738624e-01 1.09105939121714e+00 -3.82757885874428e-01 + 6.30000000000000e+01 6.44352602071576e-01 1.14892681074432e+00 -3.94831160514253e-01 + 6.60000000000000e+01 5.82566474543015e-01 1.20679411749904e+00 -4.06904424514653e-01 + 6.90000000000000e+01 5.20779947012492e-01 1.26466142425377e+00 -4.18977688515053e-01 + 7.20000000000000e+01 4.51477435205418e-01 1.30909618833200e+00 -4.29844051243441e-01 + 7.50000000000000e+01 3.78417085122278e-01 1.34681495605404e+00 -4.40106988042700e-01 + 7.80000000000000e+01 3.05355897825734e-01 1.38453415600310e+00 -4.50369442444556e-01 + 8.10000000000000e+01 2.30983767510451e-01 1.41401807310167e+00 -4.59788643436343e-01 + 8.40000000000000e+01 1.53989841650875e-01 1.42703199295995e+00 -4.67521395816866e-01 + 8.70000000000000e+01 7.69949275996385e-02 1.44004601223740e+00 -4.75253807270785e-01 + 9.00000000000000e+01 -3.36381509228363e-07 1.45305991877593e+00 -4.82986022704544e-01 + 9.30000000000000e+01 -5.38962044824732e-02 1.44004599891764e+00 -4.86623800302551e-01 + 9.60000000000000e+01 -1.07792278449097e-01 1.42703202935019e+00 -4.90261391797104e-01 + 9.90000000000000e+01 -1.61688764154490e-01 1.41401796036258e+00 -4.93898611078011e-01 + 1.02000000000000e+02 -2.13749236173153e-01 1.38453397332146e+00 -4.94263399100743e-01 + 1.05000000000000e+02 -2.64891721229873e-01 1.34681520559943e+00 -4.92992006930171e-01 + 1.08000000000000e+02 -3.16034192336304e-01 1.30909600565222e+00 -4.91720000190610e-01 + 1.11000000000000e+02 -3.64545857584686e-01 1.26466092295440e+00 -4.89201393327162e-01 + 1.14000000000000e+02 -4.07795991243718e-01 1.20679427930608e+00 -4.84189624190406e-01 + 1.17000000000000e+02 -4.51046455307775e-01 1.14892719359139e+00 -4.79177416768754e-01 + 1.20000000000000e+02 -4.94297062881228e-01 1.09105986110795e+00 -4.74164986774198e-01 + 1.23000000000000e+02 -5.26452064865786e-01 1.02003589848443e+00 -4.67401828422766e-01 + 1.26000000000000e+02 -5.58606989674918e-01 9.49011464578596e-01 -4.60638644238479e-01 + 1.29000000000000e+02 -5.90761760127430e-01 8.77986088072913e-01 -4.53875408386550e-01 + 1.32000000000000e+02 -6.15420484918018e-01 8.03908692975958e-01 -4.47922977473614e-01 + 1.35000000000000e+02 -6.36331195763501e-01 7.28305292210269e-01 -4.42375948063776e-01 + 1.38000000000000e+02 -6.57241666993606e-01 6.52702757782291e-01 -4.36828382226539e-01 + 1.41000000000000e+02 -6.76094612754094e-01 5.78615738508474e-01 -4.33407800721224e-01 + 1.44000000000000e+02 -6.90832490879619e-01 5.07559761840581e-01 -4.34241205139103e-01 + 1.47000000000000e+02 -7.05570256415403e-01 4.36504328003481e-01 -4.35074603190205e-01 + 1.50000000000000e+02 -7.20307965658325e-01 3.65449165572087e-01 -4.35907998058031e-01 + 1.53000000000000e+02 -7.46801078706125e-01 3.07518227898197e-01 -4.57805065052203e-01 + 1.56000000000000e+02 -7.73294117948629e-01 2.49587342086377e-01 -4.79701897484255e-01 + 1.59000000000000e+02 -7.99786954801670e-01 1.91656498833410e-01 -5.01598162643690e-01 + 1.62000000000000e+02 -7.40790822868899e-01 1.53560806333696e-01 -5.07117800599882e-01 + 1.65000000000000e+02 -6.39049483540701e-01 1.25382856960915e-01 -5.04448986449602e-01 + 1.68000000000000e+02 -5.37308710076014e-01 9.72046304867630e-02 -5.01779602888076e-01 + 1.71000000000000e+02 -4.22533481739914e-01 7.05772804657932e-02 -4.50000513056908e-01 + 1.74000000000000e+02 -2.81688735121593e-01 4.70517557569334e-02 -2.99999717902353e-01 + 1.77000000000000e+02 -1.40202251216632e-01 3.86002570677554e-02 -6.87686132694523e-02 + 1.80000000000000e+02 0.00000000000000e+00 3.76960000000000e-02 2.00000000000000e-01 diff --git a/Test_Cases/NREL_2p8_127/NREL-2.8-127.xlsx b/Test_Cases/NREL_2p8_127/NREL-2.8-127.xlsx new file mode 100644 index 0000000000000000000000000000000000000000..5d5d8946639878b3e2597fa3f73ca99c53f5af73 GIT binary patch literal 14107 zcmeHu1$P`tvUQ6ki!8F(VrC|bnVFfHnJsEb7BkBNibyZdI>JKryO zulk&>Q=JvJvm)bWL}f(ENrHi+0w4j<004jhz|ZDCVFLmHfI|QPC;(_sO+i~5Cu18Y zT_txrV@GXTH)|{W9B@$bECA^H{r`9TFV;Y*(vVFz{l_-dLtdeFmC)?q;$mo=W*kl8 zeW+x&ST*AMT}<+4Z!!~kH>T_Rp~xFXFFSD7~cE`kEJO0KE)5l{SZcp5cJ zyUGlcQxK2OycDF+nh_6<2?+DCiUIW!-}Eaa9no6za3kY~o@F;Ly(3YK=8T>4dS~5d zF8`_MaOEu7xoX!Yi=R=jS1FEH$IOFyWuY{~8pg*mcQCJR7{*>Vw$wka(ETR%@iQ5s zFWlP#p&fxA&DQ|y%_m6LIF4nY`!E;RDs1TI=uhzok+baVQR&NoBv*a(m~ze=IB-9> zV?hVA#oKV4hmsY9wTv8oyv@W51nk#$p1r++0p$LJrgh5nMAz@OC-vS6`%Y6`2V*No zI@&+J|Bs&ki#hpkk6s!pE!#s62Rsvd4j#OlTZ{fEAnD34)u^$a*#Oz#gj5% zWdmE*VcbNT??Ph!0X%OAht%$OQq8W#Ir9q|xC!xEpkyYoF zP+AAdix-Vd`k(?KGx9y-gy;ZC){U=5E%U`lhI=m?Oi#(+`H+7YUg7$?$NF!QU@Mfb zrhowe_3y3?@m(`+R&=hm4weSCww8bRu~KDC+Y_VB2dDj<8wzqFec8v$smt zGEc}w4xJP#fSP{hqT;I!S1AFH6>VcrR*B<9L!S1O2NSPHYfaT<6g1qOF{J^r{PHQ% zJqXLs1&>kgKrihhV)G9Q7eJXC)8&JWai6ynr=C8Kp$84HulZ?*dGXd}7}`41sZM0A zdGKl~TC+mk3SY3asmLjsV-?g@fySws@+kBBT!C^p0bQz8i8FzF-qP4jU`Vxu$osA& zmMutS<57Mkp=x(D!|rRKy|KztJcwD%DtlWGhCLAKDx0^TT9#Eh7Xt8D^(*_?{0?SH zED~YYFA~0hm>G&b#=R{v)BB+NpX_1a1pmbF=V3_b0i)XTj!AIsywvHcd>Apq_`zaE z61eG&G{$XLb6qooRL`Bx)Q zTLp^eUzhMbtBl}*6NzZt$*U9MFWoavHCk?%oWA zy7ZAEQ`-{-0^at9Ab#E?e&J8#m+WhYNf*SbdYSx5*o#QFK6*jQ#3qn`#6FnP$Mn;X zjlT+glf6cP3wHGTX83t`dYn$8CkVxU(JA?mFSB;+iCLG)V$F6!e^}ESK8r7g$cpT4 zrA2~kxJ|QaQBhufo2hgco8sCn4PL9q=Y`YCRk(Ril|kfQtYie7rIQ!_B}16_s-qI= zLJDE);tnY-vMZW&d|r5ipTy-+{^VDaaGEjPBcu4CaelEEz?sPezZH7RF*)&uVnsu< zH;d0XrIv(BXCL?aVpi(suWyfNzH#2gBNL%Jo9=S$#HGDX;UPUAUV*AwF4zjf#rnLemO1(AR7%v zL<><;*yNm;r?Ual>?8cbVO+WN_v(^T5+{|NCXZQ09 z_9yq$bi8x)zgg_Z6Q6YT-qQT;>aYONAnz>xhqwE8F8|B(fxHK%?{mTb?xR#eTC(>& zFoS&!rgu$qK|@+{q9Z(3K0<^Zs-;*VC1CQo-oU18)>fOBqyw`Bx}S{=xZJTIY=fcP zbWs(4Lk9Oiu{z^|upPS^1A{g=Df{d%3W0)re0WrH0*jF9h|O>mvVs^qzStA6d$N0YHFvUr z82t7;@T|@GrE!DWhL^5fwP6G?*q7!E(f8pV&)4&9z~bfUrD4~>@oUh^6JqcNYg)@r zZtl~F?MPZ*oBA4!?ZZ&g+@nd=R@702=$-4)?)KHaB-?`M`m&o-O=C0nss_7GM_>Qp zNK(nju9fq{i-~*75|%n$1v>V;@7u}Y>Fd<;*skX28ufgKZ-=LAQ*%>KZ$ZgX$(U~L zR8K(K$j((oL&?qd49nR|!4Y~AlyCXN_r0^z3x*wE+e{}%=O&%Cigqiw#He~p8(m(! z-Q2$2xV+n!4Ws@W(WBicD*MeEinlYGp&&BN*Cn+(TdXkIexsK8fsG0tU-oC+4KlW& z`3}je@s6Vcn@id}b2s!IqhF*mOQqlY-?*OdU$4+UCpK`Z(RFySKhNR4&EEuz;%!7h z?faG|`mUnC`BbWVJw9D}xHqX^esp!i-@BTzxM=}QJji~EyCdS0qNQb1R5liJB+H?om;TQ{v1(vA&2Ap zYFXdf@iYF?Zl`Bv+B9rzd*|uqFbeF;IP1m+4YAK^mEjWI+u^`n66h-$^ZcoM0v=w5 zx9@d8pY|nNeaz2af}EC%a@{vzr1 zA%#e$GzOC)SD#{-w{wJzBJQoj?6&Q8F*!_a@9MI6aa?jMO4d^2d9fi46|1u+rkr0U z_bfE?N!UT_*P+sY_#H+ixTzE)^C5j-gkBH4YZEkOB`S}gc3viL=9hgi6v|zUb^O6f z+@42-H&zZIWF_sK@h4^#i`0e+))BfCE{0ah@4lQ`~wdak}JOmN8nFUNN{d z$*y&}pyem1?&#>CUB{_POK{wB42-*SDEp+v%h?7D@dV-+kafrl>%lk+GIBU;+xZOo zNf*@{srX;%DWH1|C+c3&u26oKne}iq{UYfih_`67(AWrm=4203uC4V-ozjVU47Fh2 zTzX`kfH9sxFmo}k{asNeRJw3{E~wwZhCa0=TefZDxN8K{d2yu2-{;!SmT;mH2_2C- zY;ZC%Eq;^MrIQQWKTLb?h`J<;HZ2f6_KYYS(=p+P2}v>rYug?%Tq)5_!de_MmUbsC zDbX8##w-XUT~}9cr1fbIE-?B@u4C04rkwk|GcoW2QE`gffubAWRg6aLAonAedg#HU zy2>9dulY1a30$*BaOHJdW4;+=H`z{%y?4f*9+v{52bV!Awe-#^r?V?{y$=;=1_o;x z>kM;>5;IyPW>YzJYnNYKny4p=YqzbF_L%Hd*s%KpoNQ0(kOLJbbkcP$COK)+tdN4o zrB}B;RJ*kPsTO=eM`dDl*Vq`Ej*L-l(~C<&Bkq!x`7uIg+|ylsazbaE0l2;*MS$b5 z8!8Ti>rWIJ>ejjyoGnGA*{@6{)1FAN$+d_*1jJj_M=?V4zh$=@_1gS z-{$53Df^y9Uw_10Wv)Yknf1;Nver}M^U}DO3NQp5+w)shk`#(nM&BQQ$>UO6=^1zl z?R(7_+!mE7jZOaaBS|ZvCsbgEIUtRHQf?Q}N(vhEd6a|)tOD6+jj)@+INf4Y1H!hX3Eq#xYmeFRHQ9rxFsE+W6 zRa-!-LHL%8n5W;`H+6p3&cwm2KZCZyPVG$0Jcc>KaZZvD7RX5-AeG6-l5S$FFQ`>_ z5G{^t=oZkImYr+(v@K%CrlhHPT1sEFUSpwu36G?>Z`2yZ-sg9tun-KiqH@|fbpUhe zZ(t2-Q8zfN&dulAAZ`fz@T%f^w!qBg$J?CtN+vOwzX{{Kg@Z<qD}l}f5ukU{+VNIr)8Db@6n&ln9Es-$AUK8NNm(O-HnA7gOO*)p&4+_*V=KS*+_ z0scmwQ+dCCZP(<)#WnPk$xbleCuBlVpm}nNPqlkVi+t2=sEr?QOIi(HsU1wcznwX< zM`(WEIgphcNDNWcEtApR%$zKycU4Va(>$cGI4)1l*-d9htzZ_i8d@*qOdkW`HqBg` z*73-x# zVnTi=yImQqBdOD}p!ZR_4kq`<%}vAJ!g> zIKQ>z8X>N;lAH>y0E5%oiOAwo#KEo2lFp!Ye})*a|M1(3|1i5KmQJ}6(NkBXon02h z*bEtK@*UU}*Gg%8D8PF+=I+ItH=3X^#up8aJ~%XKN@<@qkN_@H&*lwJbN0bV{S(LNkRsiT)t?ols4Y}=@+yr<+4q% zrF+O`J`qXQVAOQhJObTRCFdb&5nn3lg2Hx@;xYyiDCZ5a1A9tsraL*cP2#MdjeviB zd8mzXk{8I!Fo<;K2e~r0@`bPJsaf(ZqnOeq^Ha>JM0@gtlfpoRdELDqOhM}>FA|!L zZak91DCO(KGqA=uXGDTol;HcZxoz(1#I6#WD<_^b*hARUiCZ`_MrPg>O7z**Ag_W@ z2q+eT@du6Z0|tgMPp_KFkVQu|AV zxGV`BB>h>!LR6z#XN$Q6Ilu14On&UAfK1r^qbt5;KSIxUjJLPsaKr=Z{L8~@EWV3- zNp;F`iw#snh_@oIyJUVvdfg{6LW}(L3|ABzIE(BWBocYcIL(JowlOU`ccYzaT-go4 zmltL4kKp4~+`j-94iqe!uuC3Jy=j&|5u4*AOvq;n0r>P;j6Nz7n>$Ro zLo90QY`xofjqY5VHIW%v`3P!@E~grKuftnMxb;NcgezrpxcIT( zO6{7hnmeWdL=y>(niscMhkuT-|Hd3bER>r3cp4ypLMtRO0G50< z*asBxtl0DxRTB@*(wag=mCqv5DROM_E@xq;O*Tp<$3!Jv74ixVQVbhFQX$gzEg!#| zO;Ur=h+|?_$fr>lEa@r|sM+nGhLKChENU>EN3r%i@>Y8B<0!XW9MH;kb=MuS{fOm( zA@)Jq(sN`-O5J36GNL_nPl3d5S`8cGtvH zfp^7^=CyV@Wx^#)a-0ZSlB)K2`U{flt{bpSBa!8Orw>n?9`foi_{jQeqpFE0p>g;k zRC+UMLb~PK1joYYe#Kd~Z2Gz#>k|rX-QRriA-XGfMIw$(QS=Hz{zqS>-a13 z*i+2KfzfRuYc_?M%Lo*mj9vnMS%`)zcNUXWyEY9wb8W@r^eX&&_-$RhB>`MpIY#z^ z7TDK>{aextQkMB2UiLj}6Zy;Q>)Pq89jlw@2|&3d@H!?F-GkPF+z)XiEWOs{^Ho&) zb2e^09~vP5Yfd`8bY9<-*TrtbVuAKAye?8j5^F#MQ+Xo)cbD`7$Ziu zbgB32LR7KVZ3d`lO4$lIv>4(}lO!~6?sST*a(BS637JOP+ouaF71p+toyf^gS05~v zw9PS_^`f`?*AWC}3cbmeZ}(k3h~cvee>C&gY1=}0x6o^1`Y$#H3gJb=&XY-MHX8EV z@}+VW!VJY5=UQc$v_wI~-Ljx#vvL%s=q$;a2;i{tviOrpt^FsrC|9kYR`=%{`#Oac z)EvC`%yTMNj5c6=gpRyZD39l_(n(Xk4zYwjVx^1RIUttr*r0-^xU?C&@1`~!WTJ^i zQh6I5x!(Y}zUZC+uW91lXd~z3-SZQ1hz0HWW5SU4k>pyx5oS;^rw5-0?Z`I`7$VEA z&#`IE(G9+=N0ukk5NyDfc?hpwJi&MpJ;xMtNzCiXUqiZNsM>^jQ^;7aA?^lh^;o8P zu`Ac(AppFo;m{~*#_lDUufb}t^iv%&)UlSDs}%Pcu2X#NI%3o{6*>1FXKQ(4P*VGZ{fWJF;OP3B(2I&A3#wr1%!eP48 z*xry`zmm8&c$D6ej?JC1BAyHF=DGi_FbkC-*%N4~mUniRl4bxd!{p>IOJPHlCIm0 zd5!5A%#F0RcK9mbm;)#8XEsWsLF^B_v0Pa};iDQ|Bj}fchncK*O$VvNgI>IZ{~!pL zIIU97)Q0zyMh#Z$>&j-JYg?pakjZTZW}bc;SGNNSO@|%ia36S&j$9VgkH7$+*trM7 zqU`ojJe+8SAndpE(LBW_yP0%9v{px$nQ zhY*t9v?V^*u0g%coDQB0h;(OAFl*2?lne=bbrLcKv%(g#@ZRIebmxKReGAXH)>>KL z@-IX_zCn>+mJ2}%o`xoqtOK}|;ngNQD% z*7DCMei^-c68G_vdMf>O@A0F;=dti|=nhJXBsDqRLQ~V%ag2mNTQieg(JTaNnSogY zQX8&j#m!gzAeSKDFa}FQ^_4rGr_Dl1lbNR%(JGgHK5^nY(#{@xTu1;2kSH^w?9gBV z4+CAlY5g2Q!WOAB_$Z-b+)W&eU@wQo+`1w1d^@vufMZnGBB$u~6>2O4``ruM63Y`*YtR^iioy1jP1Im9zog^N7;LmnVm- zms7pE_HD<53(Z%=VAqlxleWg?^FYG~J1_57_b2g_nYXLXfj6kXTWjh<|JW|`-qMf% zN5cHiwI(MsV{2o&KfnK6W;#|M3&UnZ?LdFzg>!U$X4#1%S>K$nid!Q#%819Qt3Q@k zVPcGJ#YO=o;kZ#C|B;s@V9Omp%?AeGb{z#nTzh~wMK-obRJKc;W+kEF0v{&&+E!3- zm+9ki<#aLKmh2BH)>sM{`g$(;C79Wme3}f>EOZ_al^4-S) z$$AKSU=i#=$SOM#Pn=_g@>3r)Fs8B7gxzn0G<-m;o9O$e0UX?b_2f@fc?xA1M6vfe z{swZM-i!o9$M6XfzMe&`vRe!>0`TGF8>+=sB-vFvJ=FpsLHi1)xCG0W`k4$|pSL}y z@5qsneas$6UiQ!%=sr!UkP7WWstej=y)iaP>3OM5IbI%gSxn4Ft%4cr{P zXmr$17l4>C`zPerFLE9w*hK5Y%RSCzx2T>ek9=C6)YYzO!Yz&pTF6rJtpwu1HE#;T zR`65sX!QhVm=u^EEo7nUYW6Hhp6JLmTwBTsi90j`X@lx4T$`5BjJo$DQP$xC_}gMB zCgh{xOO6#3rPK)7b~VCJ8F>I-K^2I_w}<-RWGA7k8^g#sHhWh{W}uO6fyktKjY<^o z63X`#JbthFMBnP^8Gj^b>xHUeE8Myn^bSeYKT~DRvEkEYa(lj>A6x}@aQj~GKlJEU zH`P%}+CY&gDxS_o>At zp>KHK?8!#qF0bI=CZ7|8R-Kn`8J>}b>H8r(U4Zar^wJCT#_}QUyA+;|41(%t;vaT9 zSDtjQ;HdROw0`NZTx!OGAw|3WBWASn#|j)m3@o_qVMae0 z9ele)Nz3Vog*?7dTs<062TK0p48FnQ@Av?>gYfiOyO%Xq(qVtPDGY-thTCN^Lhg&> zvQ+F~uMa5#fpCm#fH=BW)Do8vw;+yOHN$EHOnvu@31K6|Pm9!evXDpPaonob@RT+@ zbSMAHFyrMf^^0|5p-fzyS49cSEf|VU;r$q%4Lpu&lln{}drecSgn9|M#}cJfgX79K z>3Sf>vBj426b?zyRK|A~@z#~5w)XyRpU6XzHhw%{39U(Jv+t%Wd1OQ)NN=)$?&AFn zo1s{M*r$(e=@37PfL1q6^7wS>rEN#$V_P$zr@PL5(hiR4Wr2x*+i*MfQQp%3i#`zg z104FAe+b&EmQY5ChSh0&+F}|jA{eTON*hYt&xpQ>&}y=0*Wu5uAdZj_QJNP|@tkSo z#(P43H86L0)RrD*nX8?4v89gl?#hljbN6pg#U?X4JQc>{mMK>n{WrHa{1z##UVg)* zXP5h#vaMCSOa$?#BM^Np0#%rDF-=uDo+?YtS41WYWQ=xsIEPIlFOp?go z*Wf-|FPlB`*;jH^Pl6<0n!(VQGQpO2#*o)V5J1&24b)jmQJZp7o020C3u!mw#lFg+kxpY0ujkln2@Z|kCaq#vX{%| zq0R!jfs%;X@&RQZqi4YlvWaL`6Fo<<(FIdH)8^h)KM@nXI#?*4Q!7qp7?L3-*)zVE zMwiAn0iJmZC&!vf_3K9-jh$3JD!erNk4{{JZj4<-=D;-!`Aiu+zb(abyVv5r4ct=V zC7kXyyojhaFwQ+Tq#tT(bW~80p(SAuT2D@#OU1P(W8+L>=|7DurM|n8w6n7BJ^%K72 zQgF7KGSB8khQ^`XlC}u}dCpy;b!*l;46KWu=KCn4w0f&d&$pTy`ITBGYG^pwS=M`N zXAySpi*hpF!HiK2XFlp9iH!Tl;nmhT6DU`|FCKQj>;($@asswVMC6at*n{z`dSR<^ z>JiWztsG=DZ$1=OP-_y4H1Sya9Uqkf6ta=(OM+Z5R7PGZwGN#r5jXW>KXis-`X~u$(!os9V~t_tz9gFOzODF!P{hV zCy(bjgLKL?&)_}QDyMM1oVO9dBP`F^$Q`kLsB>u0gtj0t_Q_Q*gi4U$Dr~@h$$G)3 zGSu6p@HT1(+*!2Lzx{2FA2Y}eRp33x|NNfghyREBb#!vKGIsnUzcZ?$Z97Ac>Mgp> ztL8ItS@okAe`XS3+4 zRPrc2_2Ep8$CdQR5109|5^*$8#btQ0ICZa5P=#}3WEnT;y#BiyEXB;|Uyq8bjW}Ks zPP?@miSc3p55{6XKRvqIS{fdM#Ij2c{L~-pu#zNFA$Kk4r2Xmq3gNph!<2N5O_KPw z^i{FgHYWY-D(@GiceL#DVn7b?9WsQG`JZqtyO&g$TFQw1FAQxFO0yL`7s)Vs*Rixm za!r{Y)x&L^>ZI)wA@nPu87)71uT4wHUmyJ9H+{os2(bOiw&R7|w;tUeZ3DDO>7vBy zcOAg$Cdp=ewCtIVYoU^k^!dpB#+S=ZRcbZYjA9<5Gyg(8>Y}Dsokc@~`~{Zl8b-fF zT(tbD6SqMEUGAnptIB*TZ8~{o8c=L9H|`TrT!v^2rzC=f9n9yFhi(PxM=i)wzoM26WOf4i9wzkVH8U^1+jDlBNgR4% z#WepCP5U5N_XW7yqa6&(;|GCMrFIwdw4^ysNnzGO5Rr}ZM6paU*51XhIiSL7_1&Sz zfonpa_hh7s1`iRf@{t$X#Uh|Rj<`8VV9$u}wodFEYDJB`)jlB0ti^Pd{(+|>GFMrI5XBVLf`5)NQZe_;X4Rp{P$i7qQzw@ezkndM%Qry|)mCGXZdFEWlTV(r$Y#1n$73)-C-qi)Q`VauJva9-~95DrtZVe>f; zC`?|^OJN_ML_*{+onTDckY*~1DvM4^DK98mN=>}d9Co0F0Xm<#6=1O5fi*=-tR#G= z^s+72?JT}#J!Ro@qHfq1;kbf$yzm(~F2L9astb~Y_yUJXnP&gZn<)xQ%J~N{aFyds zQ6+c;e?q)heSbVB3jw?hmE-wbK^_o1gGrE&w}?NPPJeCrfXA0jcXA3U_k4iAfySQ+ zjpO~rl8I&zNZq2_z;K<6JKVJ>V_kSK^5asaoUMe5qqbIA%>Pji3#!`#o@TiE#+Vuk z#=lit8@5yl_OXY^WJpWOG>I4Zqx;2`gwZGL8TaoL&t=Uh+4Zh)fp_H-{X_A8R6qPP zq5Y3?h`-X>e-=XoMskUa4VMvqVLQdJ~OQ8dr5CGk*q`k{v~?8(w%3+qc=s9HLix-;sZ-l_qd+zRTi z$C2K6Uu<$a#>Flt0>wF^^>}i`I0l7JF25S^AGzLUT6!aZ=Ub1CT;0O_od#<02o3w+ zpPm{G03iE^2JGH#&dJz8(b&o9596cz?V5qsz})6IenN6Z4`ZOi+UdwcUVpQ%CmL5s z!^(WsMbW&vjEI3iyl(`-cnm*FT%4$S2y(k)3vb(AH0lY=Wu3qO6+rjsZO|9dMQ(+@ z<*u9gh4<>GH*alJ82DKX!Oj5fH zFp#6A(iwa9+0T6Ty7#ykdAv~VPZvk1Ytd1ldOZ{h>kwZ;^8MWE+t1*{wx-x=y}?y5@$$(^TD@l3C=_0t<0;*qR_w%Gb!2;I zvqTAK9t=McdAV?2J%ook-Hs+I$3(ndor+u*7&|i^9i4*>`NF5nQdT{02-*+CyX0&T z%kH-1{gG#Uj7i|ZAGSp_hrHOAX;{O3D`_^vqp_*Gn7Y37(9pAjA>qdOBZ^&_A0gng z1F?w7&+Jlv+z%XeN!;!66@;f(UqYd9;_gH)`QL4CuD4jwvr5M?$I*%me&24G+i_H7 zDOYNtLMR-CC|Cu(T26#5!FERD{;II)%JEtJ1k3W*Go_W6qMsVh`08F{=V|dZ;@1!X z_GMKLii)_FryJx1%%SRJt$`)045UWU7?2yIs<#egImMqSd)YE zD>V>Py{^;;iLE!4&Ns}iCJrf$IbMjWpPF6rIE?t|>GmijzJ|l8dmTO1Cl|V#g9-tT zZHa!H;I_D??Slpp3sZN&z(*4Kbz4N&OCb#h#mM0+geZ8akYv1yLXLGdQ==Y7<#g{V z<~Hk@u@#o-7VB~n0_adlb!(y>J~Yd0(g7-Yey_4D9(-9Y?)|yFs}x-6Ttj?o4e&nk zv7m;-z^d@xr*bnPJ?z^-y`FA$ZZ2&?dV_^!L@*1~QNJ5F$p+-%=h4dA2z$)BL-VUpH&joO|n!km(ZFq+BQ=Rgf#Q;dQcN>b!l=;WU8kSgT~9A;;ag<()8{C>Z)) zKY<>o{uYk?-XPek1uN+cSMLbN#UTBK4Eu_oEvMr+n@)=CBbg^|i&1w>km5~Gkg1ng zi<>31&VoCS(#pJ1;RA%s5fA(>p+rq literal 0 HcmV?d00001 diff --git a/Test_Cases/NREL_2p8_127/NREL-2.8-127_pitch-speed.csv b/Test_Cases/NREL_2p8_127/NREL-2.8-127_pitch-speed.csv new file mode 100644 index 00000000..8a37882c --- /dev/null +++ b/Test_Cases/NREL_2p8_127/NREL-2.8-127_pitch-speed.csv @@ -0,0 +1,31 @@ +mps,pitch,speed +3,0,5 +3.889649963,0,5 +4.684006997,0,5.638983608 +5.377830234,0,6.474263714 +5.966542092,0,7.183002305 +6.446258474,0,7.760523392 +6.813814392,0,8.20301671 +7.066784852,0,8.507562856 +7.203500851,0,8.67215255 +7.223060389,0,8.695699891 +7.320786359,0,8.813350259 +7.535153079,0,9.071422123 +7.864746237,0,9.468212823 +8.307391303,1.972625303,10.00110448 +8.860167873,3.729032675,10.66658129 +9.519428937,5.277405528,11.46025268 +10.28082494,6.571034001,12.0388027 +10.68187298,7.135654103,12.0388027 +11.13933248,8.260696288,12.0388027 +12.08928745,10.26526353,12.0388027 +13.1244224,12.14867141,12.0388027 +14.23790791,13.95715081,12.0388027 +15.42239763,15.71431664,12.0388027 +16.67007674,17.45490652,12.0388027 +17.97271352,19.14151062,12.0388027 +19.32171368,20.8231505,12.0388027 +20.70817701,22.44383927,12.0388027 +22.12295617,24.03032967,12.0388027 +23.55671697,25.61093372,12.0388027 +25,27.13341342,12.0388027 diff --git a/Test_Cases/NREL_2p8_127/NREL-2p8-127.fst b/Test_Cases/NREL_2p8_127/NREL-2p8-127.fst new file mode 100644 index 00000000..c177d10c --- /dev/null +++ b/Test_Cases/NREL_2p8_127/NREL-2p8-127.fst @@ -0,0 +1,71 @@ +------- OpenFAST INPUT FILE ------------------------------------------- +Generated with AeroElasticSE FAST driver +---------------------- SIMULATION CONTROL -------------------------------------- +False Echo - Echo input data to .ech (flag) +"FATAL" AbortLevel - Error level when simulation should abort (string) {"WARNING", "SEVERE", "FATAL"} +300.0 TMax - Total run time (s) +0.005 DT - Recommended module time step (s) +2 InterpOrder - Interpolation order for input/output time history (-) {1=linear, 2=quadratic} +0 NumCrctn - Number of correction iterations (-) {0=explicit calculation, i.e., no corrections} +99999.0 DT_UJac - Time between calls to get Jacobians (s) +1000000.0 UJacSclFact - Scaling factor used in Jacobians (-) +---------------------- FEATURE SWITCHES AND FLAGS ------------------------------ +1 CompElast - Compute structural dynamics (switch) {1=ElastoDyn; 2=ElastoDyn + BeamDyn for blades} +1 CompInflow - Compute inflow wind velocities (switch) {0=still air; 1=InflowWind; 2=external from OpenFOAM} +2 CompAero - Compute aerodynamic loads (switch) {0=None; 1=AeroDyn v14; 2=AeroDyn v15} +1 CompServo - Compute control and electrical-drive dynamics (switch) {0=None; 1=ServoDyn} +0 CompHydro - Compute hydrodynamic loads (switch) {0=None; 1=HydroDyn} +0 CompSub - Compute sub-structural dynamics (switch) {0=None; 1=SubDyn; 2=External Platform MCKF} +0 CompMooring - Compute mooring system (switch) {0=None; 1=MAP++; 2=FEAMooring; 3=MoorDyn; 4=OrcaFlex} +0 CompIce - Compute ice loads (switch) {0=None; 1=IceFloe; 2=IceDyn} +0 MHK - MHK turbine type (switch) {0=Not an MHK turbine; 1=Fixed MHK turbine; 2=Floating MHK turbine} +---------------------- ENVIRONMENTAL CONDITIONS -------------------------------- + 9.80665 Gravity - Gravitational acceleration (m/s^2) + 1.225 AirDens - Air density (kg/m^3) + 0 WtrDens - Water density (kg/m^3) + 1.464E-05 KinVisc - Kinematic viscosity of working fluid (m^2/s) + 335 SpdSound - Speed of sound in working fluid (m/s) + 103500 Patm - Atmospheric pressure (Pa) [used only for an MHK turbine cavitation check] + 1700 Pvap - Vapour pressure of working fluid (Pa) [used only for an MHK turbine cavitation check] + 0 WtrDpth - Water depth (m) + 0 MSL2SWL - Offset between still-water level and mean sea level (m) [positive upward] +---------------------- INPUT FILES --------------------------------------------- +"NREL-2p8-127_ElastoDyn.dat" EDFile - Name of file containing ElastoDyn input parameters (quoted string) +"none" BDBldFile(1) - Name of file containing BeamDyn input parameters for blade 1 (quoted string) +"none" BDBldFile(2) - Name of file containing BeamDyn input parameters for blade 2 (quoted string) +"none" BDBldFile(3) - Name of file containing BeamDyn input parameters for blade 3 (quoted string) +"NREL-2p8-127_InflowFile.dat" InflowFile - Name of file containing inflow wind input parameters (quoted string) +"NREL-2p8-127_AeroDyn15.dat" AeroFile - Name of file containing aerodynamic input parameters (quoted string) +"NREL-2p8-127_ServoDyn.dat" ServoFile - Name of file containing control and electrical-drive input parameters (quoted string) +"none" HydroFile - Name of file containing hydrodynamic input parameters (quoted string) +"none" SubFile - Name of file containing sub-structural input parameters (quoted string) +"none" MooringFile - Name of file containing mooring system input parameters (quoted string) +"none" IceFile - Name of file containing ice input parameters (quoted string) +---------------------- OUTPUT -------------------------------------------------- +False SumPrint - Print summary data to ".sum" (flag) +10.0 SttsTime - Amount of time between screen status messages (s) +99999.0 ChkptTime - Amount of time between creating checkpoint files for potential restart (s) +default DT_Out - Time step for tabular output (s) (or "default") +0.0 TStart - Time to begin tabular output (s) +1 OutFileFmt - Format for tabular (time-marching) output file (switch) {1: text file [.out], 2: binary file [.outb], 3: both} +True TabDelim - Use tab delimiters in text tabular output file? (flag) {uses spaces if false} +"ES10.3E2" OutFmt - Format used for text tabular output, excluding the time channel. Resulting field should be 10 characters. (quoted string) +---------------------- LINEARIZATION ------------------------------------------- +False Linearize - Linearization analysis (flag) +False CalcSteady - Calculate a steady-state periodic operating point before linearization? [unused if Linearize=False] (flag) +3 TrimCase - Controller parameter to be trimmed {1:yaw; 2:torque; 3:pitch} [used only if CalcSteady=True] (-) +0.001 TrimTol - Tolerance for the rotational speed convergence [used only if CalcSteady=True] (-) +0.01 TrimGain - Proportional gain for the rotational speed error (>0) [used only if CalcSteady=True] (rad/(rad/s) for yaw or pitch; Nm/(rad/s) for torque) +0.0 Twr_Kdmp - Damping factor for the tower [used only if CalcSteady=True] (N/(m/s)) +0.0 Bld_Kdmp - Damping factor for the blades [used only if CalcSteady=True] (N/(m/s)) +2 NLinTimes - Number of times to linearize (-) [>=1] [unused if Linearize=False] +30.000000, 60.000000 LinTimes - List of times at which to linearize (s) [1 to NLinTimes] [used only when Linearize=True and CalcSteady=False] +1 LinInputs - Inputs included in linearization (switch) {0=none; 1=standard; 2=all module inputs (debug)} [unused if Linearize=False] +1 LinOutputs - Outputs included in linearization (switch) {0=none; 1=from OutList(s); 2=all module outputs (debug)} [unused if Linearize=False] +False LinOutJac - Include full Jacobians in linearization output (for debug) (flag) [unused if Linearize=False; used only if LinInputs=LinOutputs=2] +False LinOutMod - Write module-level linearization output files in addition to output for full system? (flag) [unused if Linearize=False] +---------------------- VISUALIZATION ------------------------------------------ +0 WrVTK - VTK visualization data output: (switch) {0=none; 1=initialization data only; 2=animation} +2 VTK_type - Type of VTK visualization data: (switch) {1=surfaces; 2=basic meshes (lines/points); 3=all meshes (debug)} [unused if WrVTK=0] +False VTK_fields - Write mesh fields to VTK data files? (flag) {true/false} [unused if WrVTK=0] +10.0 VTK_fps - Frame rate for VTK output (frames per second){will use closest integer multiple of DT} [used only if WrVTK=2] diff --git a/Test_Cases/NREL_2p8_127/NREL-2p8-127_AeroDyn15.dat b/Test_Cases/NREL_2p8_127/NREL-2p8-127_AeroDyn15.dat new file mode 100644 index 00000000..a3742899 --- /dev/null +++ b/Test_Cases/NREL_2p8_127/NREL-2p8-127_AeroDyn15.dat @@ -0,0 +1,134 @@ +------- AERODYN v15.03.* INPUT FILE ------------------------------------------------ +Generated with AeroElasticSE FAST driver +====== General Options ============================================================================ +False Echo - Echo the input to ".AD.ech"? (flag) +default DTAero - Time interval for aerodynamic calculations {or "default"} (s) +1 WakeMod - Type of wake/induction model (switch) {0=none, 1=BEMT, 2=DBEMT, 3=OLAF} [WakeMod cannot be 2 or 3 when linearizing] +2 AFAeroMod - Type of blade airfoil aerodynamics model (switch) {1=steady model, 2=Beddoes-Leishman unsteady model} [AFAeroMod must be 1 when linearizing] +0 TwrPotent - Type tower influence on wind based on potential flow around the tower (switch) {0=none, 1=baseline potential flow, 2=potential flow with Bak correction} +0 TwrShadow - Calculate tower influence on wind based on downstream tower shadow (switch) {0=none, 1=Powles model, 2=Eames model} +False TwrAero - Calculate tower aerodynamic loads? (flag) +False FrozenWake - Assume frozen wake during linearization? (flag) [used only when WakeMod=1 and when linearizing] +False CavitCheck - Perform cavitation check? (flag) [AFAeroMod must be 1 when CavitCheck=true] +False Buoyancy - Include buoyancy effects? (flag) +False CompAA - Flag to compute AeroAcoustics calculation [only used when WakeMod=1 or 2] +AeroAcousticsInput.dat AA_InputFile - AeroAcoustics input file [used only when CompAA=true] +====== Environmental Conditions =================================================================== +"default" AirDens - Air density (kg/m^3) +"default" KinVisc - Kinematic air viscosity (m^2/s) +"default" SpdSound - Speed of sound (m/s) +"default" Patm - Atmospheric pressure (Pa) [used only when CavitCheck=True] +"default" Pvap - Vapour pressure of fluid (Pa) [used only when CavitCheck=True] +====== Blade-Element/Momentum Theory Options ====================================================== [used only when WakeMod=1] +2 SkewMod - Type of skewed-wake correction model (switch) {1=uncoupled, 2=Pitt/Peters, 3=coupled} [unused when WakeMod=0 or 3] +1.4726215563702154 SkewModFactor - Constant used in Pitt/Peters skewed wake model {or "default" is 15/32*pi} (-) [used only when SkewMod=2; unused when WakeMod=0 or 3] +True TipLoss - Use the Prandtl tip-loss model? (flag) [unused when WakeMod=0 or 3] +True HubLoss - Use the Prandtl hub-loss model? (flag) [unused when WakeMod=0 or 3] +True TanInd - Include tangential induction in BEMT calculations? (flag) [unused when WakeMod=0 or 3] +True AIDrag - Include the drag term in the axial-induction calculation? (flag) [unused when WakeMod=0 or 3] +True TIDrag - Include the drag term in the tangential-induction calculation? (flag) [unused when WakeMod=0,3 or TanInd=FALSE] +default IndToler - Convergence tolerance for BEMT nonlinear solve residual equation {or "default"} (-) [unused when WakeMod=0 or 3] +500 MaxIter - Maximum number of iteration steps (-) [unused when WakeMod=0] +====== Dynamic Blade-Element/Momentum Theory Options ====================================================== [used only when WakeMod=1] +2 DBEMT_Mod - Type of dynamic BEMT (DBEMT) model {1=constant tau1, 2=time-dependent tau1} (-) [used only when WakeMod=2] +2.0 tau1_const - Time constant for DBEMT (s) [used only when WakeMod=2 and DBEMT_Mod=1] +====== OLAF -- cOnvecting LAgrangian Filaments (Free Vortex Wake) Theory Options ================== [used only when WakeMod=3] +NREL-2p8-127_OLAF.dat OLAFInputFileName - Input file for OLAF [used only when WakeMod=3] +====== Beddoes-Leishman Unsteady Airfoil Aerodynamics Options ===================================== [used only when AFAeroMod=2] +3 UAMod - Unsteady Aero Model Switch (switch) {1=Baseline model (Original), 2=Gonzalez's variant (changes in Cn,Cc,Cm), 3=Minnema/Pierce variant (changes in Cc and Cm)} [used only when AFAeroMod=2] +True FLookup - Flag to indicate whether a lookup for f' will be calculated (TRUE) or whether best-fit exponential equations will be used (FALSE); if FALSE S1-S4 must be provided in airfoil input files (flag) [used only when AFAeroMod=2] +====== Airfoil Information ========================================================================= +1 AFTabMod - Interpolation method for multiple airfoil tables {1=1D interpolation on AoA (first table only); 2=2D interpolation on AoA and Re; 3=2D interpolation on AoA and UserProp} (-) +1 InCol_Alfa - The column in the airfoil tables that contains the angle of attack (-) +2 InCol_Cl - The column in the airfoil tables that contains the lift coefficient (-) +3 InCol_Cd - The column in the airfoil tables that contains the drag coefficient (-) +4 InCol_Cm - The column in the airfoil tables that contains the pitching-moment coefficient; use zero if there is no Cm column (-) +0 InCol_Cpmin - The column in the airfoil tables that contains the Cpmin coefficient; use zero if there is no Cpmin column (-) +30 NumAFfiles - Number of airfoil files used (-) +"Airfoils/NREL-2p8-127_AeroDyn15_Polar_00.dat" AFNames - Airfoil file names (NumAFfiles lines) (quoted strings) +"Airfoils/NREL-2p8-127_AeroDyn15_Polar_01.dat" +"Airfoils/NREL-2p8-127_AeroDyn15_Polar_02.dat" +"Airfoils/NREL-2p8-127_AeroDyn15_Polar_03.dat" +"Airfoils/NREL-2p8-127_AeroDyn15_Polar_04.dat" +"Airfoils/NREL-2p8-127_AeroDyn15_Polar_05.dat" +"Airfoils/NREL-2p8-127_AeroDyn15_Polar_06.dat" +"Airfoils/NREL-2p8-127_AeroDyn15_Polar_07.dat" +"Airfoils/NREL-2p8-127_AeroDyn15_Polar_08.dat" +"Airfoils/NREL-2p8-127_AeroDyn15_Polar_09.dat" +"Airfoils/NREL-2p8-127_AeroDyn15_Polar_10.dat" +"Airfoils/NREL-2p8-127_AeroDyn15_Polar_11.dat" +"Airfoils/NREL-2p8-127_AeroDyn15_Polar_12.dat" +"Airfoils/NREL-2p8-127_AeroDyn15_Polar_13.dat" +"Airfoils/NREL-2p8-127_AeroDyn15_Polar_14.dat" +"Airfoils/NREL-2p8-127_AeroDyn15_Polar_15.dat" +"Airfoils/NREL-2p8-127_AeroDyn15_Polar_16.dat" +"Airfoils/NREL-2p8-127_AeroDyn15_Polar_17.dat" +"Airfoils/NREL-2p8-127_AeroDyn15_Polar_18.dat" +"Airfoils/NREL-2p8-127_AeroDyn15_Polar_19.dat" +"Airfoils/NREL-2p8-127_AeroDyn15_Polar_20.dat" +"Airfoils/NREL-2p8-127_AeroDyn15_Polar_21.dat" +"Airfoils/NREL-2p8-127_AeroDyn15_Polar_22.dat" +"Airfoils/NREL-2p8-127_AeroDyn15_Polar_23.dat" +"Airfoils/NREL-2p8-127_AeroDyn15_Polar_24.dat" +"Airfoils/NREL-2p8-127_AeroDyn15_Polar_25.dat" +"Airfoils/NREL-2p8-127_AeroDyn15_Polar_26.dat" +"Airfoils/NREL-2p8-127_AeroDyn15_Polar_27.dat" +"Airfoils/NREL-2p8-127_AeroDyn15_Polar_28.dat" +"Airfoils/NREL-2p8-127_AeroDyn15_Polar_29.dat" +====== Rotor/Blade Properties ===================================================================== +True UseBlCm - Include aerodynamic pitching moment in calculations? (flag) +"NREL-2p8-127_AeroDyn15_blade.dat" ADBlFile(1) - Name of file containing distributed aerodynamic properties for Blade #1 (-) +"NREL-2p8-127_AeroDyn15_blade.dat" ADBlFile(2) - Name of file containing distributed aerodynamic properties for Blade #2 (-) [unused if NumBl < 2] +"NREL-2p8-127_AeroDyn15_blade.dat" ADBlFile(3) - Name of file containing distributed aerodynamic properties for Blade #3 (-) [unused if NumBl < 3] +====== Hub Properties ============================================================================== [used only when Buoyancy=True] +0.0 VolHub - Hub volume (m^3) +0.0 HubCenBx - Hub center of buoyancy x direction offset (m) +====== Nacelle Properties ========================================================================== [used only when Buoyancy=True] +0.0 VolNac - Nacelle volume (m^3) +0,0,0 NacCenB - Position of nacelle center of buoyancy from yaw bearing in nacelle coordinates (m) +====== Tail fin Aerodynamics ======================================================================== +False TFinAero - Calculate tail fin aerodynamics model (flag) +"unused" TFinFile - Input file for tail fin aerodynamics [used only when TFinAero=True] +====== Tower Influence and Aerodynamics ============================================================= [used only when TwrPotent/=0, TwrShadow/=0, or TwrAero=True] +10 NumTwrNds - Number of tower nodes used in the analysis (-) [used only when TwrPotent/=0, TwrShadow/=0, or TwrAero=True] +TwrElev TwrDiam TwrCd TwrTI TwrCb !TwrTI used only with TwrShadow=2, TwrCb used only with Buoyancy=True +(m) (m) (-) (-) (-) + 8.650000000000000e+00 3.999999999999999e+00 5.000000000000000e-01 1.000000000000000e-01 0.0 + 1.730800925925926e+01 4.000000000000000e+00 5.000000000000000e-01 1.000000000000000e-01 0.0 + 2.595800925925926e+01 4.000000000000000e+00 5.000000000000000e-01 1.000000000000000e-01 0.0 + 3.461601851851852e+01 3.953273204469021e+00 5.000000000000000e-01 1.000000000000000e-01 0.0 + 4.326601851851852e+01 3.712118013878008e+00 5.000000000000000e-01 1.000000000000000e-01 0.0 + 5.191601851851851e+01 3.433099970059946e+00 5.000000000000000e-01 1.000000000000000e-01 0.0 + 6.057402777777778e+01 3.130385763598736e+00 5.000000000000000e-01 1.000000000000000e-01 0.0 + 6.922402777777778e+01 2.796113422345067e+00 5.000000000000000e-01 1.000000000000000e-01 0.0 + 7.787402777777778e+01 2.382646880140990e+00 5.000000000000000e-01 1.000000000000000e-01 0.0 + 8.650000000000000e+01 2.324880163918676e+00 5.000000000000000e-01 1.000000000000000e-01 0.0 +====== Outputs ==================================================================================== +False SumPrint - Generate a summary file listing input options and interpolated properties to ".AD.sum"? (flag) +0 NBlOuts - Number of blade node outputs [0 - 9] (-) +4, 7, 10, 13, 15, 18, 21, 24, 27 BlOutNd - Blade nodes whose values will be output (-) +0 NTwOuts - Number of tower node outputs [0 - 9] (-) +0 TwOutNd - Tower nodes whose values will be output (-) + OutList - The next line(s) contains a list of output parameters. See OutListParameters.xlsx for a listing of available output channels, (-) +"B1Azimuth" +"B2Azimuth" +"B3Azimuth" +END of input file (the word "END" must appear in the first 3 columns of this last OutList line) +====== Outputs for all blade stations (same ending as above for B1N1.... =========================== [optional section] +3 BldNd_BladesOut - Number of blades to output all node information at. Up to number of blades on turbine. (-) +"All" BldNd_BlOutNd - Future feature will allow selecting a portion of the nodes to output. Not implemented yet. (-) + OutList - The next line(s) contains a list of output parameters. See OutListParameters.xlsx for a listing of available output channels, (-) +"Fx, Fy" +"Vx, Vy" +Vrel +TnInd +AxInd +Theta +Phi +Vindx +Vindy +Alpha +Fl +Fd +END (the word "END" must appear in the first 3 columns of this last OutList line in the optional nodal output section) +--------------------------------------------------------------------------------------- diff --git a/Test_Cases/NREL_2p8_127/NREL-2p8-127_AeroDyn15_blade.dat b/Test_Cases/NREL_2p8_127/NREL-2p8-127_AeroDyn15_blade.dat new file mode 100644 index 00000000..fd4b728f --- /dev/null +++ b/Test_Cases/NREL_2p8_127/NREL-2p8-127_AeroDyn15_blade.dat @@ -0,0 +1,36 @@ +------- AERODYN v15.00.* BLADE DEFINITION INPUT FILE ------------------------------------- +Generated with AeroElasticSE FAST driver +====== Blade Properties ================================================================= +30 NumBlNds - Number of blade nodes used in the analysis (-) + BlSpn BlCrvAC BlSwpAC BlCrvAng BlTwist BlChord BlAFID + (m) (m) (m) (deg) (deg) (m) (-) + 0.000000000000000e+00 0.000000000000000e+00 0.000000000000000e+00 0.000000000000000e+00 1.999622705006573e+01 2.565746018075444e+00 1 + 2.119199517912653e+00 0.000000000000000e+00 0.000000000000000e+00 0.000000000000000e+00 1.931018243810786e+01 3.361938565422448e+00 2 + 4.238399035825307e+00 0.000000000000000e+00 0.000000000000000e+00 -2.621743302803628e-03 1.831714953780435e+01 4.045185045024725e+00 3 + 6.357598553737958e+00 -1.939408866995070e-04 0.000000000000000e+00 -6.412784123456707e-02 1.708763041181490e+01 4.534861529323176e+00 4 + 8.476798071650611e+00 -4.743793103448273e-03 0.000000000000000e+00 -1.978684279841359e-01 1.569212712279918e+01 4.750344090758699e+00 5 + 1.059599758956327e+01 -1.483103448275862e-02 0.000000000000000e+00 -3.150569530999122e-01 1.382289586770404e+01 4.737620755206947e+00 6 + 1.271519710747592e+01 -2.804970443349753e-02 0.000000000000000e+00 -4.200820236296363e-01 1.124554309027298e+01 4.683448688307037e+00 7 + 1.483439662538857e+01 -4.590591133004925e-02 0.000000000000000e+00 -5.312359339597873e-01 8.602632953470145e+00 4.602338372007760e+00 8 + 1.695359614330122e+01 -6.734679802955665e-02 0.000000000000000e+00 -6.413089831677180e-01 6.549224739725965e+00 4.505595976960268e+00 9 + 1.907279566121387e+01 -9.334512315270936e-02 0.000000000000000e+00 -7.594874026577699e-01 5.408188380153923e+00 4.380463162058345e+00 10 + 2.119199517912653e+01 -1.235274876847291e-01 0.000000000000000e+00 -8.814019981123943e-01 4.552816793256156e+00 4.183546777131121e+00 11 + 2.331119469703918e+01 -1.585433990147783e-01 0.000000000000000e+00 -1.022348344095032e+00 3.850103071189125e+00 3.945902894366683e+00 12 + 2.543039421495183e+01 -1.991506896551724e-01 0.000000000000000e+00 -1.183293448295596e+00 3.210053831367405e+00 3.702763428157307e+00 13 + 2.754959373286449e+01 -2.460701477832512e-01 0.000000000000000e+00 -1.342781789240282e+00 2.548277995517243e+00 3.476193009639851e+00 14 + 2.966879325077715e+01 -2.984725615763546e-01 0.000000000000000e+00 -1.515812813319435e+00 1.868987870564891e+00 3.235485886652345e+00 15 + 3.178799276868979e+01 -3.581878325123153e-01 0.000000000000000e+00 -1.698337241682368e+00 1.247026288989173e+00 2.994660335764964e+00 16 + 3.390719228660245e+01 -4.240869950738916e-01 0.000000000000000e+00 -1.908238044665007e+00 7.591906266374636e-01 2.774705218558286e+00 17 + 3.602639180451509e+01 -4.993217733990146e-01 0.000000000000000e+00 -2.133886441082087e+00 4.659000465949885e-01 2.591930205580583e+00 18 + 3.814559132242776e+01 -5.819026600985221e-01 0.000000000000000e+00 -2.384324918476038e+00 2.731580237682558e-01 2.424912635092513e+00 19 + 4.026479084034041e+01 -6.756489655172412e-01 0.000000000000000e+00 -2.659453831887105e+00 1.231485664729688e-01 2.273929330687443e+00 20 + 4.238399035825307e+01 -7.785625123152710e-01 0.000000000000000e+00 -2.957313507988756e+00 -1.889923787502366e-02 2.146862384202469e+00 21 + 4.450318987616572e+01 -8.943162068965517e-01 0.000000000000000e+00 -3.294896483624423e+00 -1.841259535939614e-01 2.051800999525918e+00 22 + 4.662238939407835e+01 -1.022164926108374e+00 0.000000000000000e+00 -3.676725314021781e+00 -3.432314804149588e-01 1.991284282831078e+00 23 + 4.874158891199102e+01 -1.166111724137931e+00 0.000000000000000e+00 -4.102651579820645e+00 -5.034899071419768e-01 1.944879951099011e+00 24 + 5.086078842990366e+01 -1.325395270935961e+00 0.000000000000000e+00 -4.585680344442696e+00 -6.944182383563149e-01 1.888109521438915e+00 25 + 5.297998794781633e+01 -1.504970886699507e+00 0.000000000000000e+00 -5.166689492052464e+00 -9.464479611794926e-01 1.795137265041130e+00 26 + 5.509918746572898e+01 -1.707078275862069e+00 0.000000000000000e+00 -5.829761241403034e+00 -1.331448785580028e+00 1.572950482786750e+00 27 + 5.721838698364163e+01 -1.935478029556650e+00 0.000000000000000e+00 -6.607040906671076e+00 -1.857716459023805e+00 1.205686533770803e+00 28 + 5.933758650155428e+01 -2.194745172413793e+00 0.000000000000000e+00 -7.654100340223317e+00 -2.493070572147947e+00 7.343636341297369e-01 29 + 6.145678601946693e+01 -2.500000000000000e+00 0.000000000000000e+00 -8.281837270494590e+00 -3.205330715589577e+00 1.999999999999999e-01 30 diff --git a/Test_Cases/NREL_2p8_127/NREL-2p8-127_Cp_Ct_Cq.txt b/Test_Cases/NREL_2p8_127/NREL-2p8-127_Cp_Ct_Cq.txt new file mode 100644 index 00000000..2268df83 --- /dev/null +++ b/Test_Cases/NREL_2p8_127/NREL-2p8-127_Cp_Ct_Cq.txt @@ -0,0 +1,111 @@ +# ----- Rotor performance tables for the WISDEM tuning wind turbine ----- +# ------------ Written on Jul-01-21 using the ROSCO toolbox ------------ + +# Pitch angle vector, 30 entries - x axis (matrix columns) (deg) +-5.0 -3.793 -2.586 -1.379 -0.1724 1.034 2.241 3.448 4.655 5.862 7.069 8.276 9.483 10.69 11.9 13.1 14.31 15.52 16.72 17.93 19.14 20.34 21.55 22.76 23.97 25.17 26.38 27.59 28.79 30.0 +# TSR vector, 30 entries - y axis (matrix rows) (-) +2.0 2.345 2.69 3.034 3.379 3.724 4.069 4.414 4.759 5.103 5.448 5.793 6.138 6.483 6.828 7.172 7.517 7.862 8.207 8.552 8.897 9.241 9.586 9.931 10.28 10.62 10.97 11.31 11.66 12.0 +# Wind speed vector - z axis (m/s) +10.68 + +# Power coefficient + +0.005733 0.008358 0.010931 0.013451 0.015923 0.018353 0.020747 0.023112 0.025459 0.027794 0.030128 0.032473 0.034841 0.037250 0.039720 0.042275 0.044947 0.047736 0.050369 0.052438 0.053782 0.054536 0.054902 0.055053 0.055070 0.054924 0.054451 0.053413 0.051671 0.049088 +0.010473 0.014052 0.017571 0.021038 0.024463 0.027857 0.031232 0.034602 0.037982 0.041391 0.044855 0.048407 0.052073 0.055894 0.059917 0.063725 0.066595 0.068386 0.069435 0.070068 0.070525 0.070875 0.070899 0.070223 0.068520 0.065563 0.061477 0.056461 0.050687 0.044351 +0.016648 0.021451 0.026198 0.030903 0.035583 0.040258 0.044950 0.049690 0.054525 0.059496 0.064610 0.069956 0.075525 0.080323 0.083509 0.085464 0.086777 0.087879 0.088967 0.089747 0.089510 0.087678 0.083964 0.078635 0.072110 0.064721 0.056667 0.048586 0.039467 0.029816 +0.024451 0.030790 0.037088 0.043370 0.049664 0.056017 0.062499 0.069156 0.075949 0.082980 0.090401 0.096848 0.101076 0.103789 0.105878 0.107957 0.110172 0.111665 0.111132 0.107849 0.102059 0.094460 0.085644 0.075982 0.066327 0.055369 0.043639 0.032509 0.020157 0.007204 +0.034042 0.042277 0.050504 0.058774 0.067185 0.075810 0.084575 0.093427 0.102846 0.111995 0.118495 0.122686 0.126019 0.129475 0.133430 0.136352 0.136037 0.131773 0.124323 0.114686 0.103692 0.091818 0.079871 0.066581 0.053315 0.038287 0.023162 0.007449 -0.008632 -0.024586 +0.045585 0.056130 0.066777 0.077664 0.088762 0.099834 0.111077 0.123170 0.133767 0.140785 0.145956 0.151011 0.157146 0.162829 0.164232 0.160094 0.151678 0.140464 0.127481 0.113476 0.099240 0.083738 0.067897 0.050473 0.032437 0.013439 -0.006199 -0.025342 -0.045516 -0.065143 +0.059260 0.072709 0.086474 0.100339 0.113961 0.127912 0.142939 0.155463 0.163934 0.171005 0.179040 0.188615 0.194301 0.192393 0.184326 0.172304 0.157818 0.142304 0.125481 0.108163 0.089149 0.070050 0.048899 0.026622 0.003778 -0.018932 -0.042759 -0.066818 -0.089995 -0.111563 +0.075452 0.092497 0.109469 0.125954 0.142837 0.161240 0.176710 0.187609 0.197446 0.209785 0.222490 0.226531 0.221214 0.209858 0.194803 0.177987 0.159296 0.139878 0.119164 0.097278 0.073947 0.048842 0.022621 -0.004023 -0.031153 -0.059069 -0.087357 -0.114578 -0.140484 -0.164736 +0.094511 0.115022 0.134762 0.154737 0.176972 0.196672 0.211032 0.224473 0.242210 0.257277 0.259309 0.251325 0.237445 0.219974 0.200798 0.179364 0.157090 0.133189 0.107637 0.080632 0.051709 0.021678 -0.009667 -0.041001 -0.073080 -0.105950 -0.138447 -0.169104 -0.197971 -0.224775 +0.115766 0.139262 0.162531 0.188762 0.214007 0.233062 0.250893 0.274820 0.291963 0.292630 0.283030 0.267459 0.248387 0.227009 0.203460 0.177863 0.150485 0.121761 0.090582 0.058077 0.023979 -0.011436 -0.047266 -0.084214 -0.121988 -0.160064 -0.196335 -0.230319 -0.262503 -0.292769 +0.138202 0.165180 0.195145 0.226872 0.252196 0.275177 0.305983 0.325658 0.326244 0.316157 0.300345 0.280365 0.256598 0.230927 0.201729 0.171679 0.139290 0.105344 0.069408 0.031095 -0.008598 -0.049591 -0.091288 -0.133915 -0.178094 -0.220525 -0.260789 -0.299211 -0.335296 -0.368913 +0.161551 0.194903 0.233072 0.266466 0.295512 0.333944 0.357168 0.359266 0.350611 0.334697 0.314121 0.289567 0.260693 0.230418 0.196940 0.161915 0.124757 0.085182 0.042894 -0.000790 -0.046411 -0.092800 -0.140820 -0.191037 -0.240613 -0.287931 -0.333389 -0.376354 -0.416036 -0.453961 +0.187222 0.230589 0.273386 0.309857 0.356719 0.384733 0.390248 0.383896 0.370565 0.350414 0.324413 0.295499 0.262058 0.226919 0.188856 0.149185 0.106270 0.060944 0.012546 -0.037082 -0.088941 -0.142059 -0.197711 -0.254659 -0.309941 -0.363301 -0.414317 -0.461320 -0.506034 -0.548809 +0.218182 0.270155 0.315870 0.371977 0.406056 0.416968 0.415541 0.404376 0.386195 0.360803 0.331422 0.297575 0.260704 0.220885 0.178443 0.132842 0.084899 0.032868 -0.022005 -0.078304 -0.136540 -0.197173 -0.261078 -0.325020 -0.387095 -0.447192 -0.502963 -0.555496 -0.605861 -0.653204 +0.254532 0.310663 0.376823 0.417704 0.436754 0.440281 0.435650 0.419393 0.397694 0.368784 0.336011 0.298185 0.257418 0.212716 0.165233 0.114373 0.059332 0.000710 -0.060597 -0.123897 -0.189821 -0.259087 -0.331270 -0.402899 -0.472743 -0.538898 -0.600642 -0.659473 -0.715589 -0.767490 +0.291345 0.362540 0.414077 0.442759 0.456364 0.457699 0.448489 0.431127 0.405674 0.375079 0.338260 0.297381 0.251595 0.202536 0.149608 0.092156 0.031270 -0.034407 -0.103383 -0.174606 -0.248877 -0.327443 -0.408776 -0.488867 -0.566514 -0.639447 -0.707853 -0.773526 -0.835768 -0.891588 +0.334267 0.392389 0.429122 0.454490 0.467414 0.468861 0.458486 0.439783 0.413047 0.379503 0.339810 0.294277 0.244514 0.190251 0.131042 0.067919 -0.000899 -0.074042 -0.150532 -0.230353 -0.313772 -0.402998 -0.493743 -0.583001 -0.669214 -0.748849 -0.825066 -0.898389 -0.966410 -1.025596 +0.357581 0.399673 0.430692 0.453633 0.471348 0.474079 0.465908 0.446519 0.418911 0.382644 0.339619 0.290170 0.235615 0.175506 0.110900 0.039947 -0.035948 -0.117185 -0.202556 -0.291136 -0.385516 -0.485608 -0.586336 -0.686466 -0.780338 -0.868234 -0.953223 -1.034163 -1.107681 -1.169678 +0.359089 0.395909 0.422920 0.446887 0.467916 0.476719 0.470246 0.452129 0.422792 0.384528 0.337886 0.284550 0.224670 0.159553 0.087437 0.009559 -0.074879 -0.164757 -0.258939 -0.357948 -0.463740 -0.575130 -0.688215 -0.798454 -0.900816 -0.998198 -1.092491 -1.181114 -1.259757 -1.324162 +0.352122 0.384922 0.412733 0.437293 0.459923 0.475065 0.473237 0.455603 0.425796 0.384974 0.335221 0.277195 0.212880 0.140688 0.062025 -0.024286 -0.117337 -0.216450 -0.320583 -0.430204 -0.548805 -0.673230 -0.799147 -0.919437 -1.031241 -1.139238 -1.243211 -1.339491 -1.422841 -1.489579 +0.337476 0.371192 0.400519 0.426291 0.450198 0.470638 0.473926 0.458015 0.427354 0.384641 0.331021 0.269346 0.198533 0.120306 0.033570 -0.061171 -0.163388 -0.272615 -0.386793 -0.509148 -0.641390 -0.779702 -0.918883 -1.049570 -1.172336 -1.291740 -1.405715 -1.509537 -1.597202 -1.666605 +0.318547 0.355113 0.386350 0.414679 0.439769 0.463178 0.472160 0.458769 0.428164 0.383342 0.326610 0.259227 0.183042 0.097321 0.002524 -0.100828 -0.213043 -0.332841 -0.458853 -0.594695 -0.741354 -0.895436 -1.047980 -1.189453 -1.324645 -1.456077 -1.580322 -1.691499 -1.783230 -1.855996 +0.296861 0.336357 0.371125 0.401227 0.428782 0.453625 0.468379 0.458572 0.427993 0.381040 0.320153 0.248295 0.165371 0.072165 -0.031080 -0.144120 -0.266822 -0.398094 -0.536575 -0.686751 -0.849789 -1.020458 -1.186248 -1.339816 -1.488593 -1.632618 -1.767333 -1.885639 -1.981441 -2.058554 +0.272813 0.316283 0.353808 0.387167 0.416653 0.443733 0.462868 0.457131 0.426821 0.377287 0.313149 0.235527 0.145893 0.044924 -0.067233 -0.190687 -0.324377 -0.467771 -0.619850 -0.786143 -0.967008 -1.154934 -1.333959 -1.501288 -1.664564 -1.821724 -1.967047 -2.092251 -2.192423 -2.275093 +0.246069 0.293978 0.335450 0.371711 0.404252 0.432681 0.455569 0.454421 0.424708 0.373151 0.304575 0.221274 0.124762 0.015593 -0.106430 -0.240075 -0.386009 -0.542363 -0.709498 -0.892981 -1.093361 -1.298929 -1.491618 -1.674356 -1.852938 -2.023747 -2.179757 -2.311694 -2.416806 -2.506397 +0.216826 0.269453 0.315238 0.355775 0.390496 0.421499 0.446849 0.450470 0.421163 0.367613 0.294770 0.205703 0.101961 -0.016317 -0.147823 -0.293601 -0.452261 -0.622484 -0.805520 -1.007723 -1.229078 -1.452472 -1.659852 -1.859420 -2.054090 -2.239027 -2.405773 -2.544411 -2.655240 -2.753201 +0.185378 0.242932 0.294130 0.338148 0.376456 0.409645 0.437023 0.444746 0.416677 0.361007 0.283893 0.188900 0.076999 -0.050213 -0.192792 -0.350430 -0.522552 -0.707567 -0.908176 -1.130888 -1.374382 -1.615659 -1.839260 -2.056853 -2.268390 -2.467901 -2.645409 -2.790903 -2.908382 -3.016187 +0.151541 0.215077 0.270909 0.319887 0.361564 0.397134 0.425931 0.437697 0.411248 0.353437 0.271813 0.170258 0.050180 -0.086481 -0.240782 -0.411284 -0.597745 -0.798619 -1.017747 -1.262940 -1.529489 -1.788749 -2.030361 -2.267024 -2.496202 -2.710710 -2.898994 -3.051693 -3.176877 -3.295979 +0.116719 0.184724 0.246682 0.300410 0.345826 0.383484 0.414182 0.429382 0.404775 0.344986 0.258834 0.150170 0.022144 -0.125552 -0.291478 -0.476005 -0.677661 -0.895479 -1.134529 -1.404210 -1.694559 -1.972164 -2.233589 -2.490305 -2.737888 -2.967794 -3.166880 -3.327314 -3.461362 -3.593163 +0.083160 0.153221 0.220860 0.279749 0.328690 0.369159 0.401864 0.419718 0.397476 0.335735 0.244382 0.129245 -0.008566 -0.166737 -0.345714 -0.544710 -0.762454 -0.998353 -1.258854 -1.554935 -1.869688 -2.166410 -2.449315 -2.727062 -2.993813 -3.239497 -3.449471 -3.618299 -3.762458 -3.908311 + + +# Thrust coefficient + +0.092617 0.091973 0.091282 0.090551 0.089789 0.089009 0.088223 0.087443 0.086683 0.085957 0.085280 0.084668 0.084140 0.083714 0.083409 0.083241 0.083187 0.083136 0.082900 0.082292 0.081228 0.079766 0.078062 0.076284 0.074489 0.072639 0.070589 0.068103 0.065041 0.061235 +0.107807 0.107099 0.106370 0.105637 0.104916 0.104226 0.103585 0.103012 0.102531 0.102166 0.101942 0.101882 0.102014 0.102313 0.102613 0.102616 0.102036 0.100793 0.099051 0.097090 0.095137 0.093216 0.091122 0.088501 0.085056 0.080536 0.075010 0.068694 0.061744 0.054369 +0.125690 0.125020 0.124378 0.123788 0.123275 0.122867 0.122595 0.122492 0.122590 0.122922 0.123517 0.124280 0.124878 0.124839 0.123887 0.122169 0.120092 0.118075 0.116232 0.114243 0.111480 0.107417 0.101732 0.094621 0.086475 0.077627 0.068292 0.059385 0.049429 0.039068 +0.146469 0.145968 0.145568 0.145305 0.145219 0.145353 0.145746 0.146440 0.147476 0.148736 0.149769 0.149930 0.148898 0.147006 0.144888 0.143119 0.141664 0.139693 0.136101 0.130177 0.122042 0.112323 0.101588 0.090223 0.079407 0.067285 0.054557 0.043004 0.030260 0.017273 +0.170322 0.170162 0.170211 0.170521 0.171142 0.172124 0.173518 0.175280 0.176969 0.177796 0.177163 0.175410 0.173408 0.172028 0.171348 0.169865 0.165714 0.158160 0.147807 0.135540 0.122189 0.108233 0.094835 0.080132 0.065961 0.050014 0.034389 0.018544 0.003193 -0.010886 +0.197455 0.197860 0.198615 0.199780 0.201413 0.203541 0.205932 0.207836 0.208292 0.207137 0.205373 0.204234 0.204557 0.204565 0.200976 0.192600 0.180449 0.165872 0.149876 0.133238 0.117061 0.099744 0.082616 0.064007 0.045159 0.025713 0.006302 -0.011125 -0.028289 -0.044210 +0.228108 0.229335 0.231075 0.233378 0.236206 0.239147 0.241258 0.241561 0.240420 0.239344 0.240052 0.242465 0.241498 0.233969 0.220968 0.204514 0.186057 0.167281 0.147603 0.127937 0.106751 0.086199 0.063660 0.040417 0.017219 -0.004685 -0.025932 -0.045670 -0.063692 -0.079450 +0.262520 0.264837 0.267792 0.271266 0.274765 0.277277 0.277848 0.277232 0.277418 0.280948 0.284986 0.281401 0.269491 0.252166 0.231752 0.210486 0.187865 0.165132 0.141511 0.117131 0.091777 0.064983 0.037642 0.010798 -0.015186 -0.039683 -0.062267 -0.082642 -0.100832 -0.116042 +0.300899 0.304470 0.308545 0.312661 0.315868 0.317175 0.317479 0.319387 0.326537 0.331420 0.324563 0.308564 0.287341 0.263390 0.239016 0.212699 0.186421 0.158835 0.130094 0.100520 0.069495 0.038176 0.006565 -0.023392 -0.051487 -0.077331 -0.101050 -0.121896 -0.139281 -0.152655 +0.343271 0.347913 0.352697 0.356873 0.359360 0.360881 0.364797 0.376183 0.381530 0.371589 0.352097 0.327447 0.300692 0.272771 0.243417 0.212456 0.180280 0.147567 0.112935 0.077849 0.042129 0.006311 -0.028141 -0.060918 -0.090649 -0.117951 -0.142121 -0.162077 -0.177778 -0.190200 +0.389280 0.394727 0.400026 0.404078 0.407075 0.413055 0.429223 0.435350 0.423077 0.400722 0.374104 0.344727 0.312349 0.279252 0.242837 0.206780 0.169140 0.130977 0.091820 0.051267 0.010784 -0.029060 -0.066758 -0.100984 -0.132612 -0.160509 -0.184044 -0.202810 -0.217522 -0.228949 +0.438633 0.445040 0.450918 0.455672 0.463524 0.485007 0.492799 0.479208 0.455888 0.426352 0.393770 0.358519 0.319308 0.280331 0.238875 0.197193 0.154621 0.110858 0.065544 0.020470 -0.024506 -0.067347 -0.107384 -0.144048 -0.176562 -0.204438 -0.227047 -0.244755 -0.258294 -0.268897 +0.491706 0.499452 0.506279 0.515668 0.542884 0.553453 0.539904 0.515588 0.485998 0.450602 0.410018 0.368368 0.323023 0.277884 0.231163 0.184623 0.136206 0.086882 0.036071 -0.013663 -0.062666 -0.108746 -0.151171 -0.189073 -0.222113 -0.249567 -0.271188 -0.287669 -0.300602 -0.310227 +0.549345 0.558514 0.569279 0.602408 0.616664 0.604690 0.582220 0.550051 0.512271 0.468142 0.422118 0.373239 0.323447 0.272627 0.221194 0.168412 0.115188 0.059566 0.003362 -0.051146 -0.103573 -0.152467 -0.196894 -0.235916 -0.269224 -0.295885 -0.316232 -0.332225 -0.344350 -0.352382 +0.612101 0.624375 0.664085 0.681142 0.674153 0.650222 0.621076 0.578484 0.533557 0.482845 0.431122 0.376532 0.321741 0.265249 0.208409 0.150399 0.090234 0.028797 -0.032224 -0.091118 -0.147230 -0.198731 -0.244615 -0.284679 -0.317626 -0.343032 -0.363010 -0.378328 -0.389183 -0.395374 +0.681140 0.722494 0.744937 0.741819 0.723240 0.692359 0.650892 0.603471 0.550332 0.495575 0.437299 0.378355 0.317265 0.255902 0.193374 0.128796 0.063320 -0.003921 -0.070382 -0.133867 -0.193205 -0.246832 -0.294513 -0.334907 -0.366839 -0.391968 -0.411381 -0.425701 -0.435248 -0.438943 +0.784148 0.809192 0.808836 0.792982 0.766161 0.727627 0.678346 0.624772 0.566940 0.506098 0.442987 0.377600 0.311662 0.244545 0.175539 0.105591 0.033001 -0.039972 -0.111103 -0.178920 -0.241079 -0.297271 -0.346084 -0.386032 -0.417835 -0.442342 -0.461133 -0.474603 -0.482332 -0.482920 +0.878798 0.878837 0.863060 0.835105 0.802967 0.756008 0.703552 0.644299 0.581942 0.515391 0.446747 0.375978 0.304277 0.230822 0.156465 0.079145 0.000687 -0.078083 -0.154487 -0.225874 -0.291394 -0.349551 -0.398730 -0.438965 -0.470211 -0.494454 -0.512604 -0.524870 -0.530317 -0.527179 +0.954018 0.939321 0.909436 0.873286 0.832514 0.783431 0.725750 0.663095 0.594833 0.523420 0.448910 0.372835 0.294905 0.216166 0.134425 0.050923 -0.034393 -0.118873 -0.199777 -0.275311 -0.343458 -0.403080 -0.453308 -0.493210 -0.524351 -0.548257 -0.565667 -0.576443 -0.579083 -0.571691 +1.023567 0.991396 0.952287 0.906521 0.858662 0.807150 0.747584 0.679776 0.607111 0.529975 0.450234 0.367981 0.284931 0.198845 0.110913 0.020042 -0.071681 -0.161822 -0.247543 -0.326338 -0.397314 -0.458714 -0.509404 -0.549186 -0.580227 -0.603771 -0.620315 -0.629247 -0.628527 -0.616549 +1.082395 1.041804 0.991706 0.937500 0.883506 0.829745 0.767582 0.695892 0.617983 0.535899 0.450029 0.362870 0.272561 0.180369 0.084918 -0.012918 -0.111052 -0.207054 -0.296861 -0.379668 -0.453228 -0.515758 -0.566811 -0.606870 -0.637885 -0.661022 -0.676524 -0.683203 -0.678594 -0.661917 +1.139470 1.088591 1.028946 0.968630 0.908004 0.850049 0.785703 0.710556 0.628371 0.540937 0.449853 0.355602 0.259321 0.159705 0.057014 -0.047554 -0.152331 -0.253888 -0.348541 -0.434946 -0.510661 -0.574581 -0.626062 -0.666337 -0.697360 -0.720024 -0.734260 -0.738241 -0.729302 -0.707987 +1.193356 1.132284 1.066459 0.998428 0.932385 0.868695 0.802509 0.724743 0.637956 0.545168 0.447725 0.347749 0.244209 0.137366 0.027344 -0.084534 -0.195804 -0.303098 -0.402185 -0.491831 -0.569969 -0.635054 -0.687035 -0.727643 -0.758678 -0.780783 -0.793478 -0.794302 -0.780726 -0.754961 +1.246139 1.176860 1.102810 1.028791 0.956073 0.887434 0.818433 0.738064 0.646836 0.548098 0.445275 0.338296 0.227647 0.113522 -0.003991 -0.123338 -0.241002 -0.353871 -0.457470 -0.550699 -0.630979 -0.697211 -0.749803 -0.790834 -0.821861 -0.843294 -0.854136 -0.851351 -0.832973 -0.803032 +1.297833 1.220927 1.139862 1.058606 0.980276 0.905327 0.833196 0.750616 0.655027 0.550899 0.441477 0.327617 0.209871 0.088199 -0.037295 -0.163462 -0.287985 -0.406413 -0.514793 -0.611346 -0.693698 -0.761096 -0.814426 -0.855942 -0.886923 -0.907540 -0.916195 -0.909382 -0.886156 -0.852355 +1.349499 1.264699 1.176444 1.089146 1.003822 0.923619 0.847140 0.762383 0.662108 0.552546 0.436663 0.315954 0.190856 0.061078 -0.071728 -0.205866 -0.337083 -0.461115 -0.573945 -0.673753 -0.758148 -0.826758 -0.880950 -0.922989 -0.953877 -0.973504 -0.979625 -0.968430 -0.940389 -0.903039 +1.401303 1.308592 1.213895 1.119148 1.027971 0.941861 0.860452 0.772903 0.668581 0.553361 0.431060 0.303363 0.170279 0.032750 -0.108329 -0.249749 -0.387655 -0.517261 -0.634906 -0.737912 -0.824352 -0.894252 -0.949413 -0.991994 -1.022726 -1.041166 -1.044395 -1.028546 -0.995775 -0.955152 +1.452242 1.353400 1.250891 1.149892 1.052236 0.960061 0.872934 0.782638 0.674455 0.553511 0.424528 0.289397 0.148463 0.002987 -0.146530 -0.295534 -0.440250 -0.575517 -0.697662 -0.803821 -0.892330 -0.963626 -1.019849 -1.062972 -1.093473 -1.110511 -1.110480 -1.089791 -1.052396 -1.008724 +1.502155 1.397642 1.288756 1.180858 1.076625 0.977784 0.885198 0.791667 0.679649 0.553086 0.417399 0.274454 0.126013 -0.028498 -0.185977 -0.343001 -0.494588 -0.635562 -0.762201 -0.871489 -0.962109 -1.034918 -1.092283 -1.135935 -1.166113 -1.181520 -1.177866 -1.152220 -1.110323 -1.063759 +1.548197 1.442437 1.326903 1.212074 1.100665 0.995531 0.897392 0.799857 0.684430 0.552127 0.409217 0.259083 0.101756 -0.061061 -0.227233 -0.392126 -0.550655 -0.697385 -0.828511 -0.940928 -1.033720 -1.108161 -1.166734 -1.210891 -1.240644 -1.254176 -1.246561 -1.215880 -1.169616 -1.120255 + + +# Torque coefficient + +0.002876 0.004193 0.005484 0.006749 0.007989 0.009208 0.010409 0.011596 0.012773 0.013945 0.015116 0.016292 0.017480 0.018689 0.019929 0.021210 0.022551 0.023950 0.025271 0.026309 0.026984 0.027362 0.027545 0.027621 0.027630 0.027557 0.027319 0.026798 0.025925 0.024629 +0.004482 0.006014 0.007519 0.009003 0.010469 0.011921 0.013366 0.014808 0.016254 0.017713 0.019195 0.020715 0.022284 0.023919 0.025641 0.027270 0.028499 0.029265 0.029714 0.029985 0.030180 0.030330 0.030340 0.030051 0.029322 0.028057 0.026309 0.024162 0.021691 0.018980 +0.006211 0.008003 0.009774 0.011529 0.013275 0.015019 0.016770 0.018538 0.020342 0.022197 0.024104 0.026099 0.028177 0.029967 0.031155 0.031885 0.032374 0.032786 0.033192 0.033483 0.033394 0.032711 0.031325 0.029337 0.026902 0.024146 0.021141 0.018126 0.014724 0.011124 +0.008085 0.010182 0.012264 0.014342 0.016423 0.018524 0.020667 0.022868 0.025115 0.027440 0.029894 0.032026 0.033424 0.034321 0.035012 0.035699 0.036432 0.036925 0.036749 0.035664 0.033749 0.031236 0.028321 0.025126 0.021933 0.018310 0.014430 0.010750 0.006666 0.002382 +0.010108 0.012554 0.014996 0.017452 0.019950 0.022511 0.025113 0.027742 0.030539 0.033256 0.035186 0.036430 0.037420 0.038446 0.039620 0.040488 0.040395 0.039128 0.036916 0.034054 0.030790 0.027264 0.023717 0.019770 0.015831 0.011369 0.006878 0.002212 -0.002563 -0.007300 +0.012283 0.015124 0.017993 0.020926 0.023916 0.026900 0.029929 0.033187 0.036043 0.037934 0.039327 0.040689 0.042342 0.043873 0.044251 0.043136 0.040869 0.037847 0.034349 0.030575 0.026740 0.022563 0.018294 0.013600 0.008740 0.003621 -0.001670 -0.006828 -0.012264 -0.017552 +0.014614 0.017931 0.021325 0.024745 0.028104 0.031544 0.035250 0.038339 0.040428 0.042171 0.044153 0.046514 0.047916 0.047446 0.045456 0.042492 0.038919 0.035093 0.030945 0.026674 0.021985 0.017275 0.012059 0.006565 0.000932 -0.004669 -0.010545 -0.016478 -0.022194 -0.027513 +0.017154 0.021028 0.024887 0.028635 0.032473 0.036657 0.040174 0.042652 0.044888 0.047693 0.050582 0.051500 0.050292 0.047710 0.044287 0.040464 0.036215 0.031800 0.027091 0.022115 0.016811 0.011104 0.005143 -0.000914 -0.007082 -0.013429 -0.019860 -0.026048 -0.031938 -0.037452 +0.019929 0.024255 0.028417 0.032629 0.037318 0.041472 0.044500 0.047334 0.051075 0.054252 0.054680 0.052997 0.050070 0.046386 0.042342 0.037822 0.033125 0.028085 0.022697 0.017003 0.010904 0.004571 -0.002038 -0.008646 -0.015410 -0.022342 -0.029194 -0.035659 -0.041746 -0.047398 +0.022762 0.027382 0.031957 0.037115 0.042078 0.045825 0.049331 0.054035 0.057406 0.057537 0.055650 0.052588 0.048838 0.044635 0.040005 0.034972 0.029588 0.023941 0.017810 0.011419 0.004715 -0.002249 -0.009294 -0.016558 -0.023985 -0.031472 -0.038603 -0.045286 -0.051614 -0.057565 +0.025454 0.030422 0.035941 0.041785 0.046449 0.050681 0.056355 0.059978 0.060087 0.058229 0.055317 0.051637 0.047259 0.042531 0.037154 0.031619 0.025654 0.019402 0.012783 0.005727 -0.001584 -0.009134 -0.016813 -0.024664 -0.032801 -0.040616 -0.048031 -0.055108 -0.061754 -0.067945 +0.027983 0.033760 0.040371 0.046156 0.051187 0.057844 0.061866 0.062230 0.060731 0.057974 0.054410 0.050157 0.045156 0.039912 0.034113 0.028046 0.021610 0.014755 0.007430 -0.000137 -0.008039 -0.016074 -0.024392 -0.033090 -0.041677 -0.049874 -0.057748 -0.065190 -0.072063 -0.078632 +0.030608 0.037697 0.044694 0.050656 0.058317 0.062897 0.063799 0.062760 0.060581 0.057286 0.053036 0.048309 0.042842 0.037097 0.030875 0.024389 0.017373 0.009963 0.002051 -0.006062 -0.014540 -0.023224 -0.032322 -0.041632 -0.050670 -0.059393 -0.067733 -0.075418 -0.082728 -0.089721 +0.033772 0.041816 0.048892 0.057577 0.062852 0.064541 0.064320 0.062592 0.059778 0.055847 0.051300 0.046061 0.040353 0.034190 0.027621 0.020562 0.013141 0.005088 -0.003406 -0.012120 -0.021134 -0.030520 -0.040411 -0.050309 -0.059917 -0.069219 -0.077852 -0.085983 -0.093779 -0.101107 +0.037408 0.045658 0.055381 0.061390 0.064189 0.064708 0.064027 0.061638 0.058449 0.054200 0.049383 0.043824 0.037832 0.031263 0.024284 0.016809 0.008720 0.000104 -0.008906 -0.018209 -0.027898 -0.038078 -0.048686 -0.059214 -0.069479 -0.079201 -0.088276 -0.096922 -0.105169 -0.112797 +0.040760 0.050721 0.057931 0.061943 0.063847 0.064034 0.062745 0.060316 0.056755 0.052475 0.047324 0.041605 0.035199 0.028335 0.020931 0.012893 0.004375 -0.004814 -0.014464 -0.024428 -0.034819 -0.045810 -0.057189 -0.068394 -0.079257 -0.089461 -0.099031 -0.108219 -0.116927 -0.124736 +0.044620 0.052378 0.057282 0.060668 0.062393 0.062586 0.061201 0.058705 0.055136 0.050658 0.045360 0.039282 0.032639 0.025396 0.017492 0.009066 -0.000120 -0.009884 -0.020094 -0.030749 -0.041884 -0.053794 -0.065908 -0.077822 -0.089331 -0.099961 -0.110134 -0.119922 -0.129002 -0.136902 +0.045638 0.051011 0.054970 0.057898 0.060159 0.060507 0.059464 0.056990 0.053466 0.048837 0.043346 0.037035 0.030072 0.022400 0.014154 0.005098 -0.004588 -0.014956 -0.025852 -0.037158 -0.049204 -0.061979 -0.074835 -0.087614 -0.099595 -0.110814 -0.121661 -0.131991 -0.141374 -0.149287 +0.043905 0.048407 0.051710 0.054640 0.057211 0.058288 0.057496 0.055281 0.051694 0.047016 0.041313 0.034791 0.027470 0.019508 0.010691 0.001169 -0.009155 -0.020145 -0.031660 -0.043766 -0.056701 -0.070320 -0.084147 -0.097626 -0.110141 -0.122048 -0.133577 -0.144413 -0.154028 -0.161903 +0.041317 0.045166 0.048429 0.051311 0.053967 0.055743 0.055529 0.053460 0.049962 0.045172 0.039334 0.032526 0.024979 0.016508 0.007278 -0.002850 -0.013768 -0.025398 -0.037617 -0.050479 -0.064396 -0.078996 -0.093770 -0.107885 -0.121004 -0.133676 -0.145876 -0.157174 -0.166954 -0.174785 +0.038064 0.041867 0.045175 0.048081 0.050778 0.053083 0.053454 0.051660 0.048201 0.043384 0.037336 0.030380 0.022393 0.013569 0.003786 -0.006900 -0.018429 -0.030748 -0.043627 -0.057427 -0.072343 -0.087943 -0.103641 -0.118381 -0.132228 -0.145696 -0.158551 -0.170261 -0.180149 -0.187977 +0.034588 0.038559 0.041951 0.045027 0.047751 0.050293 0.051268 0.049814 0.046491 0.041624 0.035464 0.028147 0.019875 0.010567 0.000274 -0.010948 -0.023133 -0.036140 -0.049823 -0.064573 -0.080497 -0.097228 -0.113791 -0.129153 -0.143832 -0.158103 -0.171594 -0.183666 -0.193626 -0.201527 +0.031074 0.035208 0.038848 0.041999 0.044883 0.047484 0.049028 0.048001 0.044800 0.039886 0.033512 0.025991 0.017310 0.007554 -0.003253 -0.015086 -0.027930 -0.041671 -0.056166 -0.071886 -0.088952 -0.106817 -0.124171 -0.140246 -0.155820 -0.170896 -0.184997 -0.197381 -0.207409 -0.215481 +0.027565 0.031958 0.035749 0.039120 0.042099 0.044835 0.046769 0.046189 0.043127 0.038122 0.031641 0.023798 0.014741 0.004539 -0.006793 -0.019267 -0.032775 -0.047264 -0.062630 -0.079433 -0.097708 -0.116696 -0.134785 -0.151692 -0.168190 -0.184069 -0.198753 -0.211404 -0.221525 -0.229878 +0.024029 0.028707 0.032757 0.036298 0.039475 0.042252 0.044487 0.044375 0.041473 0.036438 0.029742 0.021608 0.012183 0.001523 -0.010393 -0.023443 -0.037694 -0.052962 -0.069283 -0.087200 -0.106767 -0.126841 -0.145657 -0.163502 -0.180941 -0.197620 -0.212855 -0.225738 -0.236003 -0.244751 +0.020486 0.025458 0.029784 0.033614 0.036894 0.039823 0.042218 0.042560 0.039792 0.034732 0.027850 0.019435 0.009633 -0.001542 -0.013966 -0.027739 -0.042730 -0.058812 -0.076106 -0.095210 -0.116123 -0.137230 -0.156823 -0.175678 -0.194071 -0.211544 -0.227298 -0.240396 -0.250867 -0.260123 +0.016964 0.022230 0.026916 0.030944 0.034449 0.037486 0.039992 0.040698 0.038130 0.033035 0.025979 0.017286 0.007046 -0.004595 -0.017642 -0.032068 -0.047818 -0.064749 -0.083106 -0.103486 -0.125768 -0.147847 -0.168309 -0.188221 -0.207578 -0.225835 -0.242079 -0.255393 -0.266143 -0.276008 +0.013445 0.019081 0.024035 0.028380 0.032078 0.035233 0.037788 0.038832 0.036486 0.031357 0.024115 0.015105 0.004452 -0.007673 -0.021362 -0.036489 -0.053031 -0.070853 -0.090294 -0.112047 -0.135695 -0.158696 -0.180132 -0.201128 -0.221461 -0.240492 -0.257196 -0.270744 -0.281850 -0.292416 +0.010049 0.015904 0.021238 0.025864 0.029774 0.033016 0.035659 0.036967 0.034849 0.029701 0.022284 0.012929 0.001906 -0.010809 -0.025095 -0.040981 -0.058343 -0.077096 -0.097676 -0.120894 -0.145892 -0.169792 -0.192299 -0.214401 -0.235717 -0.255510 -0.272650 -0.286463 -0.298004 -0.309351 +0.006954 0.012812 0.018468 0.023393 0.027485 0.030869 0.033604 0.035097 0.033237 0.028074 0.020435 0.010808 -0.000716 -0.013943 -0.028909 -0.045549 -0.063757 -0.083483 -0.105266 -0.130024 -0.156344 -0.181156 -0.204813 -0.228038 -0.250344 -0.270888 -0.288446 -0.302563 -0.314618 -0.326814 + diff --git a/Test_Cases/NREL_2p8_127/NREL-2p8-127_DISCON.IN b/Test_Cases/NREL_2p8_127/NREL-2p8-127_DISCON.IN new file mode 100644 index 00000000..85d74785 --- /dev/null +++ b/Test_Cases/NREL_2p8_127/NREL-2p8-127_DISCON.IN @@ -0,0 +1,158 @@ +! Controller parameter input file for the WISDEM tuning wind turbine +! - File written using ROSCO version 2.3.0 controller tuning logic on 07/01/21 + +!------- DEBUG ------------------------------------------------------------ +2 ! 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 and/or tower fore-aft motion (for floating) {0: disable, 1: generator speed, 2: tower-top fore-aft motion, 3: generator speed and tower-top fore-aft motion} +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: Immersion and Invariance Estimator, 2: Extended Kalman Filter} +1 ! PS_Mode - Pitch saturation mode {0: no pitch saturation, 1: implement pitch saturation} +0 ! SD_Mode - Shutdown mode {0: no shutdown procedure, 1: pitch to max pitch at shutdown} +0 ! Fl_Mode - Floating specific feedback mode {0: no nacelle velocity feedback, 1: feed back translational velocity, 2: feed back rotational veloicty} +0 ! TD_Mode - Tower damper mode {0: no tower damper, 1: feed back translational nacelle accelleration to pitch angle} +0 ! Flp_Mode - Flap control mode {0: no flap control, 1: steady state flap angle, 2: Proportional flap control, 2: Cyclic (1P) flap control} +0 ! OL_Mode - Open loop control mode {0: no open loop control, 1: open loop control vs. time} +0 ! PA_Mode - Pitch actuator mode {0 - not used, 1 - first order filter, 2 - second order filter} +0 ! PF_Mode - Pitch fault mode {0 - not used, 1 - constant offset on one or more blades} +1 ! AWC_Mode - Active wake control {0 - not used, 1 - SNL method} +0 ! Ext_Mode - External control mode {0 - not used, 1 - call external dynamic library} +0 ! ZMQ_Mode - Fuse ZeroMQ interface {0: unused, 1: Yaw Control} + +!------- FILTERS ---------------------------------------------------------- +2.09625 ! F_LPFCornerFreq - Corner frequency (-3dB point) in the low-pass filters, [rad/s] +0.00000 ! F_LPFDamping - Damping coefficient {used only when F_FilterType = 2} [-] +100.00000 ! F_NotchCornerFreq - Natural frequency of the notch filter, [rad/s] +0.00000 0.25000 ! F_NotchBetaNumDen - Two notch damping values (numerator and denominator, resp) - determines the width and depth of the notch, [-] +0.628320000000 ! F_SSCornerFreq - Corner frequency (-3dB point) in the first order low pass filter for the setpoint smoother, [rad/s]. +0.20944 ! F_WECornerFreq - Corner frequency (-3dB point) in the first order low pass filter for the wind speed estimate [rad/s]. +0.17952 ! F_YawErr - Low pass filter corner frequency for yaw controller [rad/s]. +0.20000 1.00000 ! F_FlCornerFreq - Natural frequency and damping in the second order low pass filter of the tower-top fore-aft motion for floating feedback control [rad/s, -]. +0.01042 ! F_FlHighPassFreq - Natural frequency of first-order high-pass filter for nacelle fore-aft motion [rad/s]. +1.74957 1.00000 ! F_FlpCornerFreq - Corner frequency and damping in the second order low pass filter of the blade root bending moment for flap control [rad/s, -]. + +!------- BLADE PITCH CONTROL ---------------------------------------------- +29 ! PC_GS_n - Amount of gain-scheduling table entries +0.086568 0.116114 0.139911 0.160483 0.179061 0.196300 0.212523 0.227992 0.242512 0.256650 0.270553 0.283361 0.296184 0.308667 0.320716 0.332616 0.343903 0.355566 0.366454 0.377409 0.387896 0.398463 0.408845 0.419345 0.429098 0.438839 0.448558 0.458211 0.467708 ! PC_GS_angles - Gain-schedule table: pitch angles [rad]. +-0.013659 -0.011910 -0.010483 -0.009298 -0.008298 -0.007442 -0.006701 -0.006054 -0.005484 -0.004977 -0.004525 -0.004118 -0.003750 -0.003416 -0.003111 -0.002832 -0.002575 -0.002338 -0.002119 -0.001915 -0.001726 -0.001549 -0.001384 -0.001229 -0.001083 -0.000947 -0.000818 -0.000696 -0.000581 ! PC_GS_KP - Gain-schedule table: pitch controller kp gains [s]. +-0.001637 -0.001470 -0.001335 -0.001222 -0.001127 -0.001045 -0.000975 -0.000913 -0.000859 -0.000811 -0.000768 -0.000729 -0.000694 -0.000662 -0.000633 -0.000607 -0.000582 -0.000560 -0.000539 -0.000520 -0.000502 -0.000485 -0.000469 -0.000454 -0.000440 -0.000427 -0.000415 -0.000404 -0.000393 ! 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 ! 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 ! PC_GS_TF - Gain-schedule table: pitch controller tf gains (derivative filter) +1.570000000000 ! PC_MaxPit - Maximum physical pitch limit, [rad]. +-0.17453290000 ! PC_MinPit - Minimum physical pitch limit, [rad]. +0.122170000000 ! PC_MaxRat - Maximum pitch rate (in absolute value) in pitch controller, [rad/s]. +-0.12217000000 ! PC_MinRat - Minimum pitch rate (in absolute value) in pitch controller, [rad/s]. +122.2879500000 ! PC_RefSpd - Desired (reference) HSS speed for pitch controller, [rad/s]. +0.000000000000 ! PC_FinePit - Record 5: Below-rated pitch angle set-point, [rad] +0.017450000000 ! PC_Switch - Angle above lowest minimum pitch angle for switch, [rad] + +!------- INDIVIDUAL PITCH CONTROL ----------------------------------------- +0.0 0.0 ! IPC_Vramp - Start and end wind speeds for cut-in ramp function. First entry: IPC inactive, second entry: IPC fully active. [m/s] +0 ! IPC_SatMode - IPC Saturation method (0 - no saturation (except by PC_MinPit), 1 - saturate by PS_BldPitchMin, 2 - saturate sotfly (full IPC cycle) by PC_MinPit, 3 - saturate softly by PS_BldPitchMin) +0.1 ! IPC_IntSat - Integrator saturation (maximum signal amplitude contribution to pitch from IPC), [rad] +0.000e+00 0.000e+00 ! IPC_KP - Proportional gain for the individual pitch controller: first parameter for 1P reductions, second for 2P reductions, [-] +0.000e+00 0.000e+00 ! IPC_KI - Integral gain for the individual pitch controller: first parameter for 1P reductions, second for 2P reductions, [-] +0.000000 0.000000 ! 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 ------------------------------------------------ +93.94773000000 ! VS_GenEff - Generator efficiency mechanical power -> electrical power, [should match the efficiency defined in the generator properties!], [%] +24371.81831000 ! VS_ArSatTq - Above rated generator torque PI control saturation, [Nm] +1500000.000000 ! VS_MaxRat - Maximum torque rate (in absolute value) in torque controller, [Nm/s]. +26809.00014000 ! VS_MaxTq - Maximum generator torque in Region 3 (HSS side), [Nm]. +0.000000000000 ! VS_MinTq - Minimum generator (HSS side), [Nm]. +50.78908000000 ! VS_MinOMSpd - Optimal mode minimum speed, cut-in speed towards optimal mode gain path, [rad/s] +2.055580000000 ! VS_Rgn2K - Generator torque constant in Region 2 (HSS side), [Nm/(rad/s)^2] +2800000.000000 ! VS_RtPwr - Wind turbine rated power [W] +24371.81831000 ! VS_RtTq - Rated torque, [Nm]. +122.2879500000 ! VS_RefSpd - Rated generator speed [rad/s] +1 ! VS_n - Number of generator PI torque controller gains +-585.918650000 ! VS_KP - Proportional gain for generator PI torque controller [-]. (Only used in the transitional 2.5 region if VS_ControlMode =/ 2) +-84.3526100000 ! VS_KI - Integral gain for generator PI torque controller [s]. (Only used in the transitional 2.5 region if VS_ControlMode =/ 2) +8.00 ! VS_TSRopt - Power-maximizing region 2 tip-speed-ratio [rad]. + +!------- SETPOINT SMOOTHER --------------------------------------------- +1.00000 ! SS_VSGain - Variable speed torque controller setpoint smoother gain, [-]. +0.00100 ! SS_PCGain - Collective pitch controller setpoint smoother gain, [-]. + +!------- WIND SPEED ESTIMATOR --------------------------------------------- +63.457 ! WE_BladeRadius - Blade length (distance from hub center to blade tip), [m] +1 ! WE_CP_n - Amount of parameters in the Cp array +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], [-] +19841843.18798 ! 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] +"NREL-2p8-127_Cp_Ct_Cq.txt" ! PerfFileName - File containing rotor performance tables (Cp,Ct,Cq) +30 30 ! PerfTableSize - Size of rotor performance tables, first number refers to number of blade pitch angles, second number referse to number of tip-speed ratios +59 ! WE_FOPoles_N - Number of first-order system poles used in EKF +3.00 3.24 3.48 3.72 3.97 4.21 4.45 4.69 4.93 5.17 5.41 5.66 5.90 6.14 6.38 6.62 6.86 7.10 7.34 7.59 7.83 8.07 8.31 8.55 8.79 9.03 9.28 9.52 9.76 10.00 10.52 11.03 11.55 12.07 12.59 13.10 13.62 14.14 14.66 15.17 15.69 16.21 16.72 17.24 17.76 18.28 18.79 19.31 19.83 20.34 20.86 21.38 21.90 22.41 22.93 23.45 23.97 24.48 25.00 ! WE_FOPoles_v - Wind speeds corresponding to first-order system poles [m/s] +-0.03755370 -0.04057526 -0.04359682 -0.04661839 -0.04963995 -0.05266151 -0.05568307 -0.05870463 -0.06172620 -0.06474776 -0.06776932 -0.07079088 -0.07381244 -0.07683401 -0.07985557 -0.08287713 -0.08589869 -0.08892026 -0.09194182 -0.09496338 -0.09798494 -0.10100650 -0.10402807 -0.10704963 -0.11007119 -0.11309275 -0.11611431 -0.11913588 -0.12215744 -0.12442309 -0.08151313 -0.09670796 -0.11491145 -0.13526498 -0.15708028 -0.18040671 -0.20314889 -0.22784461 -0.25427479 -0.28079304 -0.30962195 -0.33563012 -0.36680258 -0.39642727 -0.42479673 -0.45403549 -0.48608257 -0.52014667 -0.55456520 -0.58971549 -0.61985547 -0.65379097 -0.69212406 -0.73040974 -0.75941587 -0.79271437 -0.82808748 -0.86351689 -0.90081887 ! WE_FOPoles - First order system poles [1/s] + +!------- YAW CONTROL ------------------------------------------------------ +0.00000 ! Y_uSwitch - Wind speed to switch between Y_ErrThresh. If zero, only the first value of Y_ErrThresh is used [m/s] +4.000000 8.000000 ! Y_ErrThresh - Yaw error threshold/deadband. Turbine begins to yaw when it passes this. If Y_uSwitch is zero, only the first value is used. [deg]. +0.00870 ! Y_Rate - Yaw rate [rad/s] +0.00000 ! Y_MErrSet - Integrator saturation (maximum signal amplitude contribution to pitch from yaw-by-IPC), [rad] +0.00000 ! Y_IPC_IntSat - Integrator saturation (maximum signal amplitude contribution to pitch from yaw-by-IPC), [rad] +0.00000 ! Y_IPC_KP - Yaw-by-IPC proportional controller gain Kp +0.00000 ! Y_IPC_KI - Yaw-by-IPC integral controller gain Ki + +!------- 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_HPFCornerFreq - 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] + +!------- MINIMUM PITCH SATURATION ------------------------------------------- +59 ! PS_BldPitchMin_N - Number of values in minimum blade pitch lookup table (should equal number of values in PS_WindSpeeds and PS_BldPitchMin) +3.0000 3.2414 3.4828 3.7241 3.9655 4.2069 4.4483 4.6897 4.9310 5.1724 5.4138 5.6552 5.8966 6.1379 6.3793 6.6207 6.8621 7.1034 7.3448 7.5862 7.8276 8.0690 8.3103 8.5517 8.7931 9.0345 9.2759 9.5172 9.7586 10.0000 10.5172 11.0345 11.5517 12.0690 12.5862 13.1034 13.6207 14.1379 14.6552 15.1724 15.6897 16.2069 16.7241 17.2414 17.7586 18.2759 18.7931 19.3103 19.8276 20.3448 20.8621 21.3793 21.8966 22.4138 22.9310 23.4483 23.9655 24.4828 25.0000 ! PS_WindSpeeds - Wind speeds corresponding to minimum blade pitch angles [m/s] +0.00000000 0.00000000 0.00000000 0.00000000 0.00000000 0.00000000 0.00000000 0.00000000 0.00000000 0.00000000 0.00000000 0.00000000 0.00000000 0.00000000 0.00000000 0.00000000 0.00000000 0.00000000 0.00000000 0.00000000 0.00000000 0.00000000 0.00763391 0.02582598 0.04121469 0.05415541 0.06572411 0.07607035 0.08541836 0.09383601 0.10711337 0.11980981 0.13230324 0.14429856 0.15620583 0.16769078 0.17903230 0.19036255 0.20094970 0.21164306 0.22225798 0.23236325 0.24250097 0.25268462 0.26261996 0.27261663 0.28234372 0.29204627 0.30171741 0.31126513 0.32058559 0.33032494 0.33977293 0.34883344 0.35807953 0.36776628 0.37731052 0.38609588 0.39489943 ! PS_BldPitchMin - Minimum blade pitch angles [rad] + +!------- SHUTDOWN ----------------------------------------------------------- +0.567710000000 ! SD_MaxPit - Maximum blade pitch angle to initiate shutdown, [rad] +0.418880000000 ! SD_CornerFreq - Cutoff Frequency for first order low-pass filter for blade pitch angle, [rad/s] + +!------- Floating ----------------------------------------------------------- +0.000000000000 ! Fl_Kp - Nacelle velocity proportional feedback gain [s] + +!------- FLAP ACTUATION ----------------------------------------------------- +0.000000000000 ! Flp_Angle - Initial or steady state flap angle [rad] +0.00000000e+00 ! Flp_Kp - Blade root bending moment proportional gain for flap control [s] +0.00000000e+00 ! Flp_Ki - Flap displacement integral gain for flap control [-] +0.000000000000 ! Flp_MaxPit - Maximum (and minimum) flap pitch angle [rad] + +!------- Open Loop Control ----------------------------------------------------- +"unused" ! OL_Filename - Input file with open loop timeseries (absolute path or relative to this file) +0 ! Ind_Breakpoint - The column in OL_Filename that contains the breakpoint (time if OL_Mode = 1) +0 ! Ind_BldPitch - The column in OL_Filename that contains the blade pitch input in rad +0 ! Ind_GenTq - The column in OL_Filename that contains the generator torque in Nm +0 ! Ind_YawRate - The column in OL_Filename that contains the generator torque in Nm + +!------- Pitch Actuator Model ----------------------------------------------------- +3.140000000000 ! PA_CornerFreq - Pitch actuator bandwidth/cut-off frequency [rad/s] +0.707000000000 ! PA_Damping - Pitch actuator damping ratio [-, unused if PA_Mode = 1] + +!------- Pitch Actuator Faults ----------------------------------------------------- +0.00000000 0.00000000 0.00000000 ! PF_Offsets - Constant blade pitch offsets for blades 1-3 [rad] + +!------- AWC Modifications ----------------------------------------------------- +1 ! AWC_NumModes - Number of modes +1 ! AWC_n - azimuthal mode number +0.05 ! AWC_freq - frequency [Hz] +1.0 ! AWC_amp - amplitude [deg] +0.0 ! AWC_clockangle - clock angle [deg] + +!------- External Controller Interface ----------------------------------------------------- +"unused" ! DLL_FileName - Name/location of the dynamic library in the Bladed-DLL format +"unused" ! DLL_InFile - Name of input file sent to the DLL (-) +"DISCON" ! DLL_ProcName - Name of procedure in DLL to be called (-) + +!------- ZeroMQ Interface --------------------------------------------------------- +"tcp://localhost:5555" ! ZMQ_CommAddress - Communication address for ZMQ server, (e.g. "tcp://localhost:5555") +2 ! ZMQ_UpdatePeriod - Call ZeroMQ every [x] seconds, [s] diff --git a/Test_Cases/NREL_2p8_127/NREL-2p8-127_ElastoDyn.dat b/Test_Cases/NREL_2p8_127/NREL-2p8-127_ElastoDyn.dat new file mode 100644 index 00000000..6cced857 --- /dev/null +++ b/Test_Cases/NREL_2p8_127/NREL-2p8-127_ElastoDyn.dat @@ -0,0 +1,210 @@ +------- ELASTODYN v1.03.* INPUT FILE ------------------------------------------- +Generated with AeroElasticSE FAST driver +---------------------- SIMULATION CONTROL -------------------------------------- +False Echo - Echo input data to ".ech" (flag) +3 Method - Integration method: {1: RK4, 2: AB4, or 3: ABM4} (-) +default DT Integration time step (s) +---------------------- DEGREES OF FREEDOM -------------------------------------- +True FlapDOF1 - First flapwise blade mode DOF (flag) +True FlapDOF2 - Second flapwise blade mode DOF (flag) +True EdgeDOF - First edgewise blade mode DOF (flag) +False TeetDOF - Rotor-teeter DOF (flag) [unused for 3 blades] +False DrTrDOF - Drivetrain rotational-flexibility DOF (flag) +True GenDOF - Generator DOF (flag) +False YawDOF - Yaw DOF (flag) +False TwFADOF1 - First fore-aft tower bending-mode DOF (flag) +False TwFADOF2 - Second fore-aft tower bending-mode DOF (flag) +False TwSSDOF1 - First side-to-side tower bending-mode DOF (flag) +False TwSSDOF2 - Second side-to-side tower bending-mode DOF (flag) +False PtfmSgDOF - Platform horizontal surge translation DOF (flag) +False PtfmSwDOF - Platform horizontal sway translation DOF (flag) +False PtfmHvDOF - Platform vertical heave translation DOF (flag) +False PtfmRDOF - Platform roll tilt rotation DOF (flag) +False PtfmPDOF - Platform pitch tilt rotation DOF (flag) +False PtfmYDOF - Platform yaw rotation DOF (flag) +---------------------- INITIAL CONDITIONS -------------------------------------- +0.0 OoPDefl - Initial out-of-plane blade-tip displacement (meters) +0.0 IPDefl - Initial in-plane blade-tip deflection (meters) +0.0 BlPitch(1) - Blade 1 initial pitch (degrees) +0.0 BlPitch(2) - Blade 2 initial pitch (degrees) +0.0 BlPitch(3) - Blade 3 initial pitch (degrees) [unused for 2 blades] +0.0 TeetDefl - Initial or fixed teeter angle (degrees) [unused for 3 blades] +0.0 Azimuth - Initial azimuth angle for blade 1 (degrees) +7.223281620282807 RotSpeed - Initial or fixed rotor speed (rpm) +0.0 NacYaw - Initial or fixed nacelle-yaw angle (degrees) +0.0 TTDspFA - Initial fore-aft tower-top displacement (meters) +0.0 TTDspSS - Initial side-to-side tower-top displacement (meters) +0.0 PtfmSurge - Initial or fixed horizontal surge translational displacement of platform (meters) +0.0 PtfmSway - Initial or fixed horizontal sway translational displacement of platform (meters) +0.0 PtfmHeave - Initial or fixed vertical heave translational displacement of platform (meters) +0.0 PtfmRoll - Initial or fixed roll tilt rotational displacement of platform (degrees) +0.0 PtfmPitch - Initial or fixed pitch tilt rotational displacement of platform (degrees) +0.0 PtfmYaw - Initial or fixed yaw rotational displacement of platform (degrees) +---------------------- TURBINE CONFIGURATION ----------------------------------- +3 NumBl - Number of blades (-) +63.45678601946693 TipRad - The distance from the rotor apex to the blade tip (meters) +2.0 HubRad - The distance from the rotor apex to the blade root (meters) +-3.0 PreCone(1) - Blade 1 cone angle (degrees) +-3.0 PreCone(2) - Blade 2 cone angle (degrees) +-3.0 PreCone(3) - Blade 3 cone angle (degrees) [unused for 2 blades] +0.0 HubCM - Distance from rotor apex to hub mass [positive downwind] (meters) +0.0 UndSling - Undersling length [distance from teeter pin to the rotor apex] (meters) [unused for 3 blades] +0.0 Delta3 - Delta-3 angle for teetering rotors (degrees) [unused for 3 blades] +0.0 AzimB1Up - Azimuth value to use for I/O when blade 1 points up (degrees) +-5.0 OverHang - Distance from yaw axis to rotor apex [3 blades] or teeter pin [2 blades] (meters) +0.0 ShftGagL - Distance from rotor apex [3 blades] or teeter pin [2 blades] to shaft strain gages [positive for upwind rotors] (meters) +-4.999629720311564 ShftTilt - Rotor shaft tilt angle (degrees) +0.8829822658380706 NacCMxn - Downwind distance from the tower-top to the nacelle CM (meters) +-0.08924556522324154 NacCMyn - Lateral distance from the tower-top to the nacelle CM (meters) +0.8326312050685473 NacCMzn - Vertical distance from the tower-top to the nacelle CM (meters) +0.0 NcIMUxn - Downwind distance from the tower-top to the nacelle IMU (meters) +0.0 NcIMUyn - Lateral distance from the tower-top to the nacelle IMU (meters) +0.0 NcIMUzn - Vertical distance from the tower-top to the nacelle IMU (meters) +1.1177004388298077 Twr2Shft - Vertical distance from the tower-top to the rotor shaft (meters) +86.5 TowerHt - Height of tower above ground level [onshore] or MSL [offshore] (meters) +0.0 TowerBsHt - Height of tower base above ground level [onshore] or MSL [offshore] (meters) +0.0 PtfmCMxt - Downwind distance from the ground level [onshore] or MSL [offshore] to the platform CM (meters) +0.0 PtfmCMyt - Lateral distance from the ground level [onshore] or MSL [offshore] to the platform CM (meters) +0.0 PtfmCMzt - Vertical distance from the ground level [onshore] or MSL [offshore] to the platform CM (meters) +0.0 PtfmRefzt - Vertical distance from the ground level [onshore] or MSL [offshore] to the platform reference point (meters) +---------------------- MASS AND INERTIA ---------------------------------------- +0.0 TipMass(1) - Tip-brake mass, blade 1 (kg) +0.0 TipMass(2) - Tip-brake mass, blade 2 (kg) +0.0 TipMass(3) - Tip-brake mass, blade 3 (kg) [unused for 2 blades] +7482.264184443234 HubMass - Hub mass (kg) +28639.287453422658 HubIner - Hub inertia about rotor axis [3 blades] or teeter axis [2 blades] (kg m^2) +4940.938090969189 GenIner - Generator inertia about HSS (kg m^2) +113487.2812241146 NacMass - Nacelle mass (kg) +693579.6265889656 NacYIner - Nacelle inertia about yaw axis (kg m^2) +3353.0472655982394 YawBrMass - Yaw bearing mass (kg) +0.0 PtfmMass - Platform mass (kg) +0.0 PtfmRIner - Platform inertia for roll tilt rotation about the platform CM (kg m^2) +0.0 PtfmPIner - Platform inertia for pitch tilt rotation about the platform CM (kg m^2) +0.0 PtfmYIner - Platform inertia for yaw rotation about the platform CM (kg m^2) +---------------------- BLADE --------------------------------------------------- +50 BldNodes - Number of blade nodes (per blade) used for analysis (-) +"NREL-2p8-127_ElastoDyn_blade.dat" BldFile1 - Name of file containing properties for blade 1 (quoted string) +"NREL-2p8-127_ElastoDyn_blade.dat" BldFile2 - Name of file containing properties for blade 2 (quoted string) +"NREL-2p8-127_ElastoDyn_blade.dat" BldFile3 - Name of file containing properties for blade 3 (quoted string) [unused for 2 blades] +---------------------- ROTOR-TEETER -------------------------------------------- +0 TeetMod - Rotor-teeter spring/damper model {0: none, 1: standard, 2: user-defined from routine UserTeet} (switch) [unused for 3 blades] +0.0 TeetDmpP - Rotor-teeter damper position (degrees) [used only for 2 blades and when TeetMod=1] +0.0 TeetDmp - Rotor-teeter damping constant (N-m/(rad/s)) [used only for 2 blades and when TeetMod=1] +0.0 TeetCDmp - Rotor-teeter rate-independent Coulomb-damping moment (N-m) [used only for 2 blades and when TeetMod=1] +0.0 TeetSStP - Rotor-teeter soft-stop position (degrees) [used only for 2 blades and when TeetMod=1] +0.0 TeetHStP - Rotor-teeter hard-stop position (degrees) [used only for 2 blades and when TeetMod=1] +0.0 TeetSSSp - Rotor-teeter soft-stop linear-spring constant (N-m/rad) [used only for 2 blades and when TeetMod=1] +0.0 TeetHSSp - Rotor-teeter hard-stop linear-spring constant (N-m/rad) [used only for 2 blades and when TeetMod=1] +---------------------- DRIVETRAIN ---------------------------------------------- +95.5 GBoxEff - Gearbox efficiency (%) +97.0 GBRatio - Gearbox ratio (-) +283287696.9043701 DTTorSpr - Drivetrain torsional spring (N-m/rad) +1500541.6644456587 DTTorDmp - Drivetrain torsional damper (N-m/(rad/s)) +---------------------- FURLING ------------------------------------------------- +False Furling - Read in additional model properties for furling turbine (flag) [must currently be FALSE) +"none" FurlFile - Name of file containing furling properties (quoted string) [unused when Furling=False] +---------------------- TOWER --------------------------------------------------- +20 TwrNodes - Number of tower nodes used for analysis (-) +"NREL-2p8-127_ElastoDyn_tower.dat" TwrFile - Name of file containing tower properties (quoted string) +---------------------- OUTPUT -------------------------------------------------- +False SumPrint - Print summary data to ".sum" (flag) +1 OutFile - Switch to determine where output will be placed: {1: in module output file only; 2: in glue code output file only; 3: both} (currently unused) +True TabDelim - Use tab delimiters in text tabular output file? (flag) (currently unused) +"ES10.3E2" OutFmt - Format used for text tabular output (except time). Resulting field should be 10 characters. (quoted string) (currently unused) +0.0 TStart - Time to begin tabular output (s) (currently unused) +1 DecFact - Decimation factor for tabular output {1: output every time step} (-) (currently unused) +9 NTwGages - Number of tower nodes that have strain gages for output [0 to 9] (-) +2, 4, 6, 8, 10, 12, 14, 16, 18 TwrGagNd - List of tower nodes that have strain gages [1 to TwrNodes] (-) [unused if NTwGages=0] +9 NBlGages - Number of blade nodes that have strain gages for output [0 to 9] (-) +6, 11, 16, 21, 26, 31, 36, 41, 46 BldGagNd - List of blade nodes that have strain gages [1 to BldNodes] (-) [unused if NBlGages=0] + OutList - The next line(s) contains a list of output parameters. See OutListParameters.xlsx for a listing of available output channels, (-) +"Azimuth" +"BldPitch1" +"BldPitch2" +"BldPitch3" +"GenSpeed" +"LSSTipMys" +"LSSTipMzs" +"LSShftFys" +"LSShftFzs" +"NacYaw" +"RootFxb1" +"RootFxb2" +"RootFxb3" +"RootFxc1" +"RootFxc2" +"RootFxc3" +"RootFyb1" +"RootFyb2" +"RootFyb3" +"RootFyc1" +"RootFyc2" +"RootFyc3" +"RootFzb1" +"RootFzb2" +"RootFzb3" +"RootFzc1" +"RootFzc2" +"RootFzc3" +"RootMxb1" +"RootMxb2" +"RootMxb3" +"RootMxc1" +"RootMxc2" +"RootMxc3" +"RootMyb1" +"RootMyb2" +"RootMyb3" +"RootMyc1" +"RootMyc2" +"RootMyc3" +"RootMzb1" +"RootMzb2" +"RootMzb3" +"RootMzc1" +"RootMzc2" +"RootMzc3" +"RotSpeed" +"RotThrust" +"RotTorq" +"Spn1MLxb1" +"Spn1MLyb1" +"Spn2MLxb1" +"Spn2MLyb1" +"Spn3MLxb1" +"Spn3MLyb1" +"Spn4MLxb1" +"Spn4MLyb1" +"Spn5MLxb1" +"Spn5MLyb1" +"Spn6MLxb1" +"Spn6MLyb1" +"Spn7MLxb1" +"Spn7MLyb1" +"Spn8MLxb1" +"Spn8MLyb1" +"Spn9MLxb1" +"Spn9MLyb1" +"TipDxb1" +"TipDxb2" +"TipDxb3" +"TipDxc1" +"TipDxc2" +"TipDxc3" +"TipDyb1" +"TipDyb2" +"TipDyb3" +"TipDyc1" +"TipDyc2" +"TipDyc3" +"TipDzb1" +"TipDzb2" +"TipDzb3" +"TipDzc1" +"TipDzc2" +"TipDzc3" +"TwrBsMxt" +"TwrBsMyt" +"TwrBsMzt" +END of input file (the word "END" must appear in the first 3 columns of this last OutList line) +--------------------------------------------------------------------------------------- diff --git a/Test_Cases/NREL_2p8_127/NREL-2p8-127_ElastoDyn_blade.dat b/Test_Cases/NREL_2p8_127/NREL-2p8-127_ElastoDyn_blade.dat new file mode 100644 index 00000000..662c3af1 --- /dev/null +++ b/Test_Cases/NREL_2p8_127/NREL-2p8-127_ElastoDyn_blade.dat @@ -0,0 +1,62 @@ +------- ELASTODYN V1.00.* INDIVIDUAL BLADE INPUT FILE -------------------------- +Generated with AeroElasticSE FAST driver +---------------------- BLADE PARAMETERS ---------------------------------------- +30 NBlInpSt - Number of blade input stations (-) +1.0 BldFlDmp1 - Blade flap mode #1 structural damping in percent of critical (%) +1.0 BldFlDmp2 - Blade flap mode #2 structural damping in percent of critical (%) +1.0 BldEdDmp1 - Blade edge mode #1 structural damping in percent of critical (%) +---------------------- BLADE ADJUSTMENT FACTORS -------------------------------- +1.0 FlStTunr1 - Blade flapwise modal stiffness tuner, 1st mode (-) +1.0 FlStTunr2 - Blade flapwise modal stiffness tuner, 2nd mode (-) +1.0 AdjBlMs - Factor to adjust blade mass density (-) +1.0 AdjFlSt - Factor to adjust blade flap stiffness (-) +1.0 AdjEdSt - Factor to adjust blade edge stiffness (-) +---------------------- DISTRIBUTED BLADE PROPERTIES ---------------------------- + BlFract PitchAxis StrcTwst BMassDen FlpStff EdgStff + (-) (-) (deg) (kg/m) (Nm^2) (Nm^2) + 0.000000000000000e+00 5.000000000000000e-01 1.999622705006573e+01 9.710303775720137e+02 8.916645581889803e+09 8.916996828171421e+09 + 3.448275862068966e-02 4.797651657064801e-01 1.931018243810786e+01 9.360384963432447e+02 1.473326655503917e+10 1.503401326999529e+10 + 6.896551724137932e-02 4.100052021425268e-01 1.831714953780435e+01 7.384411481979697e+02 1.350641277548294e+10 1.668758117393011e+10 + 1.034482758620690e-01 3.512493343557562e-01 1.708763041181490e+01 5.242503736808504e+02 7.750625550591639e+09 1.313891689544163e+10 + 1.379310344827586e-01 3.110092285118687e-01 1.569212712279918e+01 4.095720481213451e+02 4.517970071596079e+09 1.065397599903997e+10 + 1.724137931034483e-01 2.834806852225638e-01 1.382289586770404e+01 2.986034040547503e+02 2.639603257135735e+09 7.691984348826207e+09 + 2.068965517241379e-01 2.649028377616424e-01 1.124554309027298e+01 2.242709960488304e+02 1.722995952419500e+09 5.352469758607450e+09 + 2.413793103448276e-01 2.524820938264642e-01 8.602632953470145e+00 2.129606273581960e+02 1.483184105878141e+09 4.327677642529569e+09 + 2.758620689655172e-01 2.449189056667618e-01 6.549224739725965e+00 2.091698491908484e+02 1.365990134494710e+09 3.614205549153540e+09 + 3.103448275862069e-01 2.413757812153578e-01 5.408188380153923e+00 1.968505270832688e+02 1.161884350732890e+09 3.059348888224575e+09 + 3.448275862068965e-01 2.409997816578705e-01 4.552816793256156e+00 1.840381495123537e+02 9.314103670023195e+08 2.635487762688528e+09 + 3.793103448275861e-01 2.438939371115084e-01 3.850103071189125e+00 1.707777565800272e+02 7.316000308334582e+08 2.188136539118910e+09 + 4.137931034482759e-01 2.495413982689942e-01 3.210053831367405e+00 1.577448933617357e+02 5.813400904874783e+08 1.847593613150510e+09 + 4.482758620689655e-01 2.579313748558032e-01 2.548277995517243e+00 1.472572881966913e+02 4.757592505107988e+08 1.631226610849327e+09 + 4.827586206896552e-01 2.680075313847211e-01 1.868987870564891e+00 1.385288690289785e+02 3.862376543475163e+08 1.405932074273394e+09 + 5.172413793103448e-01 2.786890302281694e-01 1.247026288989173e+00 1.303134456935171e+02 3.086236872618167e+08 1.086079003669758e+09 + 5.517241379310345e-01 2.889455550381649e-01 7.591906266374636e-01 1.214132928926456e+02 2.441246000330141e+08 7.279449241103762e+08 + 5.862068965517241e-01 2.981867550411185e-01 4.659000465949885e-01 1.130051988362277e+02 1.889011712485603e+08 4.718010458987974e+08 + 6.206896551724138e-01 3.061372927610646e-01 2.731580237682558e-01 1.057369028682480e+02 1.426024838771875e+08 3.311232129595062e+08 + 6.551724137931035e-01 3.119763987397355e-01 1.231485664729688e-01 9.974549711305480e+01 1.081121588014881e+08 2.531064287089206e+08 + 6.896551724137934e-01 3.154698036179193e-01 -1.889923787502366e-02 9.455111640202743e+01 8.496507419955346e+07 1.976683193694704e+08 + 7.241379310344830e-01 3.174252972719749e-01 -1.841259535939614e-01 8.918927437076574e+01 6.699354322582775e+07 1.803010747112424e+08 + 7.586206896551723e-01 3.157084507688791e-01 -3.432314804149588e-01 8.015835414506564e+01 5.106806818035772e+07 1.739724378313888e+08 + 7.931034482758621e-01 3.095467116664537e-01 -5.034899071419768e-01 7.140526341375902e+01 3.929235153694874e+07 1.684420237335510e+08 + 8.275862068965517e-01 2.996558060513167e-01 -6.944182383563149e-01 5.563937030326857e+01 2.849850000919442e+07 7.873543089740016e+07 + 8.620689655172414e-01 2.881116856742882e-01 -9.464479611794926e-01 4.591127859162181e+01 1.982854313004774e+07 6.415110790287662e+07 + 8.965517241379312e-01 2.777712184636389e-01 -1.331448785580028e+00 3.521480844524145e+01 1.075138794875714e+07 4.514001039735875e+07 + 9.310344827586208e-01 2.706279229199988e-01 -1.857716459023805e+00 2.414179066974884e+01 3.638232945365374e+06 2.616242592743580e+07 + 9.655172413793103e-01 2.665260978643628e-01 -2.493070572147947e+00 3.678240377890068e+00 8.650778718250984e+04 1.574666086617074e+06 + 1.000000000000000e+00 2.500000000000000e-01 -3.205330715589577e+00 1.002353815775734e+00 1.628296293397697e+03 3.168732291579445e+04 +---------------------- BLADE MODE SHAPES --------------------------------------- +0.004521475330089924 BldFl1Sh(2) - Flap mode 1, coeff of x^2 +1.0698094815587011 BldFl1Sh(3) - , coeff of x^3 +-0.1043639462789789 BldFl1Sh(4) - , coeff of x^4 +0.7886224122132662 BldFl1Sh(5) - , coeff of x^5 +-0.7585894228230783 BldFl1Sh(6) - , coeff of x^6 +-0.5138424457535536 BldFl2Sh(2) - Flap mode 2, coeff of x^2 +2.93531699885226 BldFl2Sh(3) - , coeff of x^3 +-19.409314950811712 BldFl2Sh(4) - , coeff of x^4 +32.48595903814384 BldFl2Sh(5) - , coeff of x^5 +-14.498118640430834 BldFl2Sh(6) - , coeff of x^6 +0.17685846482119558 BldEdgSh(2) - Edge mode 1, coeff of x^2 +1.9926745320317614 BldEdgSh(3) - , coeff of x^3 +-4.492670447108128 BldEdgSh(4) - , coeff of x^4 +6.331998738711197 BldEdgSh(5) - , coeff of x^5 +-3.0088612884560257 BldEdgSh(6) - , coeff of x^6 diff --git a/Test_Cases/NREL_2p8_127/NREL-2p8-127_ElastoDyn_tower.dat b/Test_Cases/NREL_2p8_127/NREL-2p8-127_ElastoDyn_tower.dat new file mode 100644 index 00000000..670d3ccc --- /dev/null +++ b/Test_Cases/NREL_2p8_127/NREL-2p8-127_ElastoDyn_tower.dat @@ -0,0 +1,50 @@ +------- ELASTODYN V1.00.* TOWER INPUT FILE ------------------------------------- +Generated with AeroElasticSE FAST driver +---------------------- TOWER PARAMETERS ---------------------------------------- +9 NTwInpSt - Number of input stations to specify tower geometry +1.0 TwrFADmp(1) - Tower 1st fore-aft mode structural damping ratio (%) +1.0 TwrFADmp(2) - Tower 2nd fore-aft mode structural damping ratio (%) +1.0 TwrSSDmp(1) - Tower 1st side-to-side mode structural damping ratio (%) +1.0 TwrSSDmp(2) - Tower 2nd side-to-side mode structural damping ratio (%) +---------------------- TOWER ADJUSTMUNT FACTORS -------------------------------- +1.0 FAStTunr(1) - Tower fore-aft modal stiffness tuner, 1st mode (-) +1.0 FAStTunr(2) - Tower fore-aft modal stiffness tuner, 2nd mode (-) +1.0 SSStTunr(1) - Tower side-to-side stiffness tuner, 1st mode (-) +1.0 SSStTunr(2) - Tower side-to-side stiffness tuner, 2nd mode (-) +1.0 AdjTwMa - Factor to adjust tower mass density (-) +1.0 AdjFASt - Factor to adjust tower fore-aft stiffness (-) +1.0 AdjSSSt - Factor to adjust tower side-to-side stiffness (-) +---------------------- DISTRIBUTED TOWER PROPERTIES ---------------------------- + HtFract TMassDen TwFAStif TwSSStif + (-) (kg/m) (Nm^2) (Nm^2) + 0.000000000000000e+00 3.027735301310815e+03 1.474853951124582e+11 1.474853951124582e+11 + 1.250433977548895e-01 2.718841246770161e+03 1.326329677125010e+11 1.326329677125010e+11 + 2.500867955097790e-01 2.405464101729817e+03 1.161354662267779e+11 1.161354662267779e+11 + 3.751301932646685e-01 2.112377458665061e+03 9.479550671463214e+10 9.479550671463214e+10 + 5.001157273463720e-01 1.947002758491315e+03 7.586780853389151e+10 7.586780853389151e+10 + 6.251591251012615e-01 1.783363103134093e+03 5.857866350808070e+10 5.857866350808070e+10 + 7.502025228561510e-01 1.603905893716689e+03 4.289862070041790e+10 4.289862070041790e+10 + 8.751880569378545e-01 1.409173987955922e+03 2.871944175926664e+10 2.871944175926664e+10 + 1.000000000000000e+00 1.161806938102961e+03 1.956567246347168e+10 1.956567246347168e+10 +---------------------- TOWER FORE-AFT MODE SHAPES ------------------------------ +1.0623105807354711 TwFAM1Sh(2) - Mode 1, coefficient of x^2 term +-0.12782107145017788 TwFAM1Sh(3) - , coefficient of x^3 term +-0.11374039457578099 TwFAM1Sh(4) - , coefficient of x^4 term +0.4380734650926717 TwFAM1Sh(5) - , coefficient of x^5 term +-0.2588225798021839 TwFAM1Sh(6) - , coefficient of x^6 term +916.0158542297875 TwFAM2Sh(2) - Mode 2, coefficient of x^2 term +-524.0268078619857 TwFAM2Sh(3) - , coefficient of x^3 term +-620.6941658768418 TwFAM2Sh(4) - , coefficient of x^4 term +844.0762210901079 TwFAM2Sh(5) - , coefficient of x^5 term +-614.3711015810677 TwFAM2Sh(6) - , coefficient of x^6 term +---------------------- TOWER SIDE-TO-SIDE MODE SHAPES -------------------------- +1.0569471838310198 TwSSM1Sh(2) - Mode 1, coefficient of x^2 term +-0.1296167767277 TwSSM1Sh(3) - , coefficient of x^3 term +-0.09657367230257455 TwSSM1Sh(4) - , coefficient of x^4 term +0.4145201607812788 TwSSM1Sh(5) - , coefficient of x^5 term +-0.24527689558202392 TwSSM1Sh(6) - , coefficient of x^6 term +66.717537330485 TwSSM2Sh(2) - Mode 2, coefficient of x^2 term +-28.88940079202735 TwSSM2Sh(3) - , coefficient of x^3 term +-68.66726547883196 TwSSM2Sh(4) - , coefficient of x^4 term +94.08317763633714 TwSSM2Sh(5) - , coefficient of x^5 term +-62.24404869596283 TwSSM2Sh(6) - , coefficient of x^6 term diff --git a/Test_Cases/NREL_2p8_127/NREL-2p8-127_InflowFile.dat b/Test_Cases/NREL_2p8_127/NREL-2p8-127_InflowFile.dat new file mode 100644 index 00000000..401fd0a0 --- /dev/null +++ b/Test_Cases/NREL_2p8_127/NREL-2p8-127_InflowFile.dat @@ -0,0 +1,57 @@ +------- InflowWind v3.01.* INPUT FILE ------------------------------------------------------------------------- +Generated with AeroElasticSE FAST driver +--------------------------------------------------------------------------------------------------------------- +False Echo - Echo input data to .ech (flag) +1 WindType - switch for wind file type (1=steady; 2=uniform; 3=binary TurbSim FF; 4=binary Bladed-style FF; 5=HAWC format; 6=User defined; 7=native Bladed FF) +0.0 PropagationDir - Direction of wind propagation (meteoroligical rotation from aligned with X (positive rotates towards -Y) -- degrees) +0.0 VFlowAng - Upflow angle (degrees) (not used for native Bladed format WindType=7) +1 NWindVel - Number of points to output the wind velocity (0 to 9) +0.0 WindVxiList - List of coordinates in the inertial X direction (m) +0.0 WindVyiList - List of coordinates in the inertial Y direction (m) +88.5 WindVziList - List of coordinates in the inertial Z direction (m) +================== Parameters for Steady Wind Conditions [used only for WindType = 1] ========================= +6.0 HWindSpeed - Horizontal windspeed (m/s) +87.66 RefHt - Reference height for horizontal wind speed (m) +0.0 PLexp - Power law exponent (-) +================== Parameters for Uniform wind file [used only for WindType = 2] ============================ +"none" Filename_Uni - Filename of time series data for uniform wind field. (-) +87.66 RefHt_Uni - Reference height for horizontal wind speed (m) +1.0 RefLength - Reference length for linear horizontal and vertical sheer (-) +================== Parameters for Binary TurbSim Full-Field files [used only for WindType = 3] ============== +"none" FileName_BTS - Name of the Full field wind file to use (.bts) +================== Parameters for Binary Bladed-style Full-Field files [used only for WindType = 4] ========= +"none" FilenameRoot - Rootname of the full-field wind file to use (.wnd, .sum) +False TowerFile - Have tower file (.twr) (flag) +================== Parameters for HAWC-format binary files [Only used with WindType = 5] ===================== +"none" FileName_u - name of the file containing the u-component fluctuating wind (.bin) +"none" FileName_v - name of the file containing the v-component fluctuating wind (.bin) +"none" FileName_w - name of the file containing the w-component fluctuating wind (.bin) +2 nx - number of grids in the x direction (in the 3 files above) (-) +2 ny - number of grids in the y direction (in the 3 files above) (-) +2 nz - number of grids in the z direction (in the 3 files above) (-) +10 dx - distance (in meters) between points in the x direction (m) +10 dy - distance (in meters) between points in the y direction (m) +10 dz - distance (in meters) between points in the z direction (m) +0.0 RefHt_Hawc - reference height; the height (in meters) of the vertical center of the grid (m) +------------- Scaling parameters for turbulence --------------------------------------------------------- +0 ScaleMethod - Turbulence scaling method [0 = none, 1 = direct scaling, 2 = calculate scaling factor based on a desired standard deviation] +1.0 SFx - Turbulence scaling factor for the x direction (-) [ScaleMethod=1] +1.0 SFy - Turbulence scaling factor for the y direction (-) [ScaleMethod=1] +1.0 SFz - Turbulence scaling factor for the z direction (-) [ScaleMethod=1] +1.0 SigmaFx - Turbulence standard deviation to calculate scaling from in x direction (m/s) [ScaleMethod=2] +1.0 SigmaFy - Turbulence standard deviation to calculate scaling from in y direction (m/s) [ScaleMethod=2] +1.0 SigmaFz - Turbulence standard deviation to calculate scaling from in z direction (m/s) [ScaleMethod=2] +------------- Mean wind profile parameters (added to HAWC-format files) --------------------------------- +0.0 URef - Mean u-component wind speed at the reference height (m/s) +0 WindProfile - Wind profile type (0=constant;1=logarithmic,2=power law) +0.0 PLExp_Hawc - Power law exponent (-) (used for PL wind profile type only) +0.0 Z0 - Surface roughness length (m) (used for LG wind profile type only) +0 XOffset - Initial offset in +x direction (shift of wind box) (-) +====================== OUTPUT ================================================== +False SumPrint - Print summary data to .IfW.sum (flag) +OutList - The next line(s) contains a list of output parameters. See OutListParameters.xlsx for a listing of available output channels, (-) +"Wind1Velx" +"Wind1Vely" +"Wind1Velz" +END of input file (the word "END" must appear in the first 3 columns of this last OutList line) +--------------------------------------------------------------------------------------- diff --git a/Test_Cases/NREL_2p8_127/NREL-2p8-127_ServoDyn.dat b/Test_Cases/NREL_2p8_127/NREL-2p8-127_ServoDyn.dat new file mode 100644 index 00000000..bdc2d74d --- /dev/null +++ b/Test_Cases/NREL_2p8_127/NREL-2p8-127_ServoDyn.dat @@ -0,0 +1,110 @@ +------- SERVODYN v1.05.* INPUT FILE -------------------------------------------- +Generated with AeroElasticSE FAST driver +---------------------- SIMULATION CONTROL -------------------------------------- +False Echo - Echo input data to .ech (flag) +default DT - Communication interval for controllers (s) (or "default") +---------------------- PITCH CONTROL ------------------------------------------- +5 PCMode - Pitch control mode {0: none, 3: user-defined from routine PitchCntrl, 4: user-defined from Simulink/Labview, 5: user-defined from Bladed-style DLL} (switch) +0.0 TPCOn - Time to enable active pitch control (s) [unused when PCMode=0] +99999.0 TPitManS(1) - Time to start override pitch maneuver for blade 1 and end standard pitch control (s) +99999.0 TPitManS(2) - Time to start override pitch maneuver for blade 2 and end standard pitch control (s) +99999.0 TPitManS(3) - Time to start override pitch maneuver for blade 3 and end standard pitch control (s) [unused for 2 blades] +7.0 PitManRat(1) - Pitch rate at which override pitch maneuver heads toward final pitch angle for blade 1 (deg/s) +7.0 PitManRat(2) - Pitch rate at which override pitch maneuver heads toward final pitch angle for blade 2 (deg/s) +7.0 PitManRat(3) - Pitch rate at which override pitch maneuver heads toward final pitch angle for blade 3 (deg/s) [unused for 2 blades] +90.0 BlPitchF(1) - Blade 1 final pitch for pitch maneuvers (degrees) +90.0 BlPitchF(2) - Blade 2 final pitch for pitch maneuvers (degrees) +90.0 BlPitchF(3) - Blade 3 final pitch for pitch maneuvers (degrees) [unused for 2 blades] +---------------------- GENERATOR AND TORQUE CONTROL ---------------------------- +5 VSContrl - Variable-speed control mode {0: none, 1: simple VS, 3: user-defined from routine UserVSCont, 4: user-defined from Simulink/Labview, 5: user-defined from Bladed-style DLL} (switch) +1 GenModel - Generator model {1: simple, 2: Thevenin, 3: user-defined from routine UserGen} (switch) [used only when VSContrl=0] +93.94772808556249 GenEff - Generator efficiency [ignored by the Thevenin and user-defined generator models] (%) +True GenTiStr - Method to start the generator {T: timed using TimGenOn, F: generator speed using SpdGenOn} (flag) +True GenTiStp - Method to stop the generator {T: timed using TimGenOf, F: when generator power = 0} (flag) +99999.0 SpdGenOn - Generator speed to turn on the generator for a startup (HSS speed) (rpm) [used only when GenTiStr=False] +0.0 TimGenOn - Time to turn on the generator for a startup (s) [used only when GenTiStr=True] +99999.0 TimGenOf - Time to turn off the generator (s) [used only when GenTiStp=True] +---------------------- SIMPLE VARIABLE-SPEED TORQUE CONTROL -------------------- +99999.0 VS_RtGnSp - Rated generator speed for simple variable-speed generator control (HSS side) (rpm) [used only when VSContrl=1] +99999.0 VS_RtTq - Rated generator torque/constant generator torque in Region 3 for simple variable-speed generator control (HSS side) (N-m) [used only when VSContrl=1] +99999.0 VS_Rgn2K - Generator torque constant in Region 2 for simple variable-speed generator control (HSS side) (N-m/rpm^2) [used only when VSContrl=1] +99999.0 VS_SlPc - Rated generator slip percentage in Region 2 1/2 for simple variable-speed generator control (%) [used only when VSContrl=1] +---------------------- SIMPLE INDUCTION GENERATOR ------------------------------ +99999.0 SIG_SlPc - Rated generator slip percentage (%) [used only when VSContrl=0 and GenModel=1] +99999.0 SIG_SySp - Synchronous (zero-torque) generator speed (rpm) [used only when VSContrl=0 and GenModel=1] +99999.0 SIG_RtTq - Rated torque (N-m) [used only when VSContrl=0 and GenModel=1] +99999.0 SIG_PORt - Pull-out ratio (Tpullout/Trated) (-) [used only when VSContrl=0 and GenModel=1] +---------------------- THEVENIN-EQUIVALENT INDUCTION GENERATOR ----------------- +99999.0 TEC_Freq - Line frequency [50 or 60] (Hz) [used only when VSContrl=0 and GenModel=2] +0 TEC_NPol - Number of poles [even integer > 0] (-) [used only when VSContrl=0 and GenModel=2] +99999.0 TEC_SRes - Stator resistance (ohms) [used only when VSContrl=0 and GenModel=2] +99999.0 TEC_RRes - Rotor resistance (ohms) [used only when VSContrl=0 and GenModel=2] +99999.0 TEC_VLL - Line-to-line RMS voltage (volts) [used only when VSContrl=0 and GenModel=2] +99999.0 TEC_SLR - Stator leakage reactance (ohms) [used only when VSContrl=0 and GenModel=2] +99999.0 TEC_RLR - Rotor leakage reactance (ohms) [used only when VSContrl=0 and GenModel=2] +99999.0 TEC_MR - Magnetizing reactance (ohms) [used only when VSContrl=0 and GenModel=2] +---------------------- HIGH-SPEED SHAFT BRAKE ---------------------------------- +0 HSSBrMode - HSS brake model {0: none, 1: simple, 3: user-defined from routine UserHSSBr, 4: user-defined from Simulink/Labview, 5: user-defined from Bladed-style DLL} (switch) +99999.0 THSSBrDp - Time to initiate deployment of the HSS brake (s) +99999.0 HSSBrDT - Time for HSS-brake to reach full deployment once initiated (sec) [used only when HSSBrMode=1] +99999.0 HSSBrTqF - Fully deployed HSS-brake torque (N-m) +---------------------- NACELLE-YAW CONTROL ------------------------------------- +0 YCMode - Yaw control mode {0: none, 3: user-defined from routine UserYawCont, 4: user-defined from Simulink/Labview, 5: user-defined from Bladed-style DLL} (switch) +99999.0 TYCOn - Time to enable active yaw control (s) [unused when YCMode=0] +0.0 YawNeut - Neutral yaw position--yaw spring force is zero at this yaw (degrees) +496739375.65069634 YawSpr - Nacelle-yaw spring constant (N-m/rad) +187442.5509148155 YawDamp - Nacelle-yaw damping constant (N-m/(rad/s)) +99999.0 TYawManS - Time to start override yaw maneuver and end standard yaw control (s) +0.25 YawManRat - Yaw maneuver rate (in absolute value) (deg/s) +0.0 NacYawF - Final yaw angle for override yaw maneuvers (degrees) +---------------------- AERODYNAMIC FLOW CONTROL -------------------------------- + 0 AfCmode - Airfoil control mode {0: none, 1: cosine wave cycle, 4: user-defined from Simulink/Labview, 5: user-defined from Bladed-style DLL} (switch) + 0 AfC_Mean - Mean level for cosine cycling or steady value (-) [used only with AfCmode==1] + 0 AfC_Amp - Amplitude for for cosine cycling of flap signal (-) [used only with AfCmode==1] + 0 AfC_Phase - Phase relative to the blade azimuth (0 is vertical) for for cosine cycling of flap signal (deg) [used only with AfCmode==1] +---------------------- STRUCTURAL CONTROL -------------------------------------- +0 NumBStC - Number of blade structural controllers (integer) +"unused" BStCfiles - Name of the files for blade structural controllers (quoted strings) [unused when NumBStC==0] +0 NumNStC - Number of nacelle structural controllers (integer) +"unused" NStCfiles - Name of the files for nacelle structural controllers (quoted strings) [unused when NumNStC==0] +0 NumTStC - Number of tower structural controllers (integer) +"unused" TStCfiles - Name of the files for tower structural controllers (quoted strings) [unused when NumTStC==0] +0 NumSStC - Number of substructure structural controllers (integer) +"unused" SStCfiles - Name of the files for substructure structural controllers (quoted strings) [unused when NumSStC==0] +---------------------- CABLE CONTROL ------------------------------------------- + 0 CCmode - Cable control mode {0: none, 4: user-defined from Simulink/Labview, 5: user-defined from Bladed-style DLL} (switch) +---------------------- BLADED INTERFACE ---------------------------------------- [used only with Bladed Interface] +"/pscratch/ndeveld/awc/ROSCO_B/ROSCO/build/libdiscon.so" DLL_FileName - Name/location of the dynamic library {.dll [Windows] or .so [Linux]} in the Bladed-DLL format (-) [used only with Bladed Interface] +"NREL-2p8-127_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] +False DLL_Ramp - Whether a linear ramp should be used between DLL_DT time steps [introduces time shift when true] (flag) [used only with Bladed Interface] +99999.0 BPCutoff - Cuttoff frequency for low-pass filter on blade pitch from DLL (Hz) [used only with Bladed Interface] +0.0 NacYaw_North - Reference yaw angle of the nacelle when the upwind end points due North (deg) [used only with Bladed Interface] +1 Ptch_Cntrl - Record 28: Use individual pitch control {0: collective pitch; 1: individual pitch control} (switch) [used only with Bladed Interface] +0.0 Ptch_SetPnt - Record 5: Below-rated pitch angle set-point (deg) [used only with Bladed Interface] +0.0 Ptch_Min - Record 6: Minimum pitch angle (deg) [used only with Bladed Interface] +0.0 Ptch_Max - Record 7: Maximum pitch angle (deg) [used only with Bladed Interface] +0.0 PtchRate_Min - Record 8: Minimum pitch rate (most negative value allowed) (deg/s) [used only with Bladed Interface] +0.0 PtchRate_Max - Record 9: Maximum pitch rate (deg/s) [used only with Bladed Interface] +0.0 Gain_OM - Record 16: Optimal mode gain (Nm/(rad/s)^2) [used only with Bladed Interface] +0.0 GenSpd_MinOM - Record 17: Minimum generator speed (rpm) [used only with Bladed Interface] +0.0 GenSpd_MaxOM - Record 18: Optimal mode maximum speed (rpm) [used only with Bladed Interface] +0.0 GenSpd_Dem - Record 19: Demanded generator speed above rated (rpm) [used only with Bladed Interface] +0.0 GenTrq_Dem - Record 22: Demanded generator torque above rated (Nm) [used only with Bladed Interface] +0.0 GenPwr_Dem - Record 13: Demanded power (W) [used only with Bladed Interface] +---------------------- BLADED INTERFACE TORQUE-SPEED LOOK-UP TABLE ------------- +0 DLL_NumTrq - Record 26: No. of points in torque-speed look-up table {0 = none and use the optimal mode parameters; nonzero = ignore the optimal mode PARAMETERs by setting Record 16 to 0.0} (-) [used only with Bladed Interface] +GenSpd_TLU GenTrq_TLU +(rpm) (Nm) +---------------------- OUTPUT -------------------------------------------------- +False SumPrint - Print summary data to .sum (flag) (currently unused) +1 OutFile - Switch to determine where output will be placed: {1: in module output file only; 2: in glue code output file only; 3: both} (currently unused) +True TabDelim - Use tab delimiters in text tabular output file? (flag) (currently unused) +"ES10.3E2" OutFmt - Format used for text tabular output (except time). Resulting field should be 10 characters. (quoted string) (currently unused) +0.0 TStart - Time to begin tabular output (s) (currently unused) + OutList - The next line(s) contains a list of output parameters. See OutListParameters.xlsx for a listing of available output channels, (-) +"GenPwr" +"GenTq" +END of input file (the word "END" must appear in the first 3 columns of this last OutList line) +--------------------------------------------------------------------------------------- diff --git a/Tune_Cases/NREL2p8.yaml b/Tune_Cases/NREL2p8.yaml new file mode 100644 index 00000000..2b39b420 --- /dev/null +++ b/Tune_Cases/NREL2p8.yaml @@ -0,0 +1,50 @@ +--- # ---------------------NREL Generic controller tuning input file ------------------- + # Written for use with ROSCO_Toolbox tuning procedures + # Turbine: NREL 5MW Reference Wind Turbine +# ------------------------------ OpenFAST PATH DEFINITIONS ------------------------------ +path_params: + FAST_InputFile: 'NREL-2p8-127.fst' # Name of *.fst file + FAST_directory: '../Test_Cases/NREL_2p8_127' # Main OpenFAST model directory, where the *.fst lives + # Optional + rotor_performance_filename: 'NREL-2p8-127_Cp_Ct_Cq.txt' # Filename for rotor performance text file (if it has been generated by ccblade already) + +# -------------------------------- TURBINE PARAMETERS ----------------------------------- +turbine_params: + rotor_inertia: 38677040.613 # Rotor inertia [kg m^2], {Available in Elastodyn .sum file} + rated_rotor_speed: 1.26711 # Rated rotor speed [rad/s] + v_min: 3.0 # Cut-in wind speed [m/s] + v_rated: 11.4 # Rated wind speed [m/s] + v_max: 25.0 # Cut-out wind speed [m/s], -- Does not need to be exact (JUST ASSUME FOR NOW) + max_pitch_rate: 0.1745 # Maximum blade pitch rate [rad/s] + max_torque_rate: 1500000. # Maximum torque rate [Nm/s], {~1/4 VS_RtTq/s} + rated_power: 5000000. # Rated Power [W] + bld_edgewise_freq: 6.2831853 # Blade edgewise first natural frequency [rad/s] + bld_flapwise_freq: 0.0 # Blade flapwise first natural frequency [rad/s] + # Optional + # TSR_operational: # None # Desired below-rated operational tip speed ratio (Cp-maximizing TSR is used if not defined) +#------------------------------- CONTROLLER PARAMETERS ---------------------------------- +controller_params: + # Controller flags + LoggingLevel: 1 # {0: write no debug files, 1: write standard output .dbg-file, 2: write standard output .dbg-file and complete avrSWAP-array .dbg2-file + F_LPFType: 1 # {1: first-order low-pass filter, 2: second-order low-pass filter}, [rad/s] (currently filters generator speed and pitch control signals) + F_NotchType: 0 # Notch filter on generator speed and/or tower fore-aft motion (for floating) {0: disable, 1: generator speed, 2: tower-top fore-aft motion, 3: generator speed and tower-top fore-aft motion} + IPC_ControlMode: 0 # Turn Individual Pitch Control (IPC) for fatigue load reductions (pitch contribution) {0: off, 1: 1P reductions, 2: 1P+2P reductions} + VS_ControlMode: 3 # Generator torque control mode in above rated conditions {0: constant torque, 1: constant power, 2: TSR tracking PI control} + PC_ControlMode: 1 # Blade pitch control mode {0: No pitch, fix to fine pitch, 1: active PI blade pitch control} + Y_ControlMode: 0 # Yaw control mode {0: no yaw control, 1: yaw rate control, 2: yaw-by-IPC} + SS_Mode: 1 # Setpoint Smoother mode {0: no setpoint smoothing, 1: introduce setpoint smoothing} + WE_Mode: 2 # Wind speed estimator mode {0: One-second low pass filtered hub height wind speed, 1: Immersion and Invariance Estimator (Ortega et al.)} + PS_Mode: 1 # Pitch saturation mode {0: no pitch saturation, 1: peak shaving, 2: Cp-maximizing pitch saturation, 3: peak shaving and Cp-maximizing pitch saturation} + SD_Mode: 0 # Shutdown mode {0: no shutdown procedure, 1: pitch to max pitch at shutdown} + Fl_Mode: 0 # Floating specific feedback mode {0: no nacelle velocity feedback, 1: nacelle velocity feedback} + Flp_Mode: 0 # Flap control mode {0: no flap control, 1: steady state flap angle, 2: Proportional flap control} + # Controller parameters + zeta_pc: 0.7 # Pitch controller desired damping ratio [-] + omega_pc: 0.6 # Pitch controller desired natural frequency [rad/s] + zeta_vs: 0.7 # Torque controller desired damping ratio [-] + omega_vs: 0.15 # Torque controller desired natural frequency [rad/s] + twr_freq: 0.4499 # Tower natural frequency [rad/s] + ptfm_freq: 0.2325 # Platform natural frequency [rad/s] (OC4Hywind Parameters, here) + # Optional + ps_percent: 0.80 # Percent peak shaving [%, <= 1 ], {default = 80%} + sd_maxpit: 0.4363 # Maximum blade pitch angle to initiate shutdown [rad], {default = bld pitch at v_max} From 1ccc1b36bfe413a8c3039f34f243f08acb409dd4 Mon Sep 17 00:00:00 2001 From: dzalkind <65573423+dzalkind@users.noreply.github.com> Date: Tue, 7 Mar 2023 14:56:48 -0700 Subject: [PATCH 063/224] Platform control and Optional Inputs (#227) * Fix yaw threshold documentation in DISCON * Fix debug unit labels * Add nacelle heading error to DebugVar * Update ROSCO_IO and Types * Read NacHeading from OpenFAST * Update DISCONs * Fix ******s in dbg files * Allow single U in power_curve * Initialize floating feedback filters at 0, make optional input for filts * give dummy units if dbg units missing * Update FAST_wrapper.py Fix UnboundLocalError: local variable 'e' referenced before assignment * Update example_08.py Remove tmin so that entire simulation is plotted. Removing tmin=10 because with that setting only the final timestep of the simulation is loaded * Update linear_model handling for new pyFAST, will break with weis import * Try with conda installed compiler * Re-do filter initialization, reset value unused for now * Regen registry and discons * Read optional MoorDyn control input * Add cable control index values and initial implementation for opt inputs * Add CC_Mode input, use schema description in file writing * Add initial cable control module, tidy and expand dbg3 output * Output first index of LocalVar for nonspecified length arrays * Add initial line kinematics * Add initial line kinematics - part 2 * Generalize actuator time constant, make input * Move input line reading to start * Fix CC_ActTau * Apply line kinematics to avrSWAP * Add StC readers/writers * Update reader/writer/inputs for OpenFAST v3.4.0 * Add StC control inputs, fix allocation location for CC * Add initial structural control * Add platform motion signals as ROSCO inputs * Fix StC in reader * Update ParseInAry_Opt to set default, ready to copy * Copy ParseInAry_Opt to double instance * Add ParseInput_Int_Opt, ready for copy * Add ParseInput_Dbl_Opt, fix others * Switch back to logical flag for default, make FindLine subroutine * Add optional string parsing subroutine * Refactor ReadSetParameters for optional inputs * Filter FA_AccHPF only when used, per optional inputs * Offset WSE input saturation from 0 if necessary * Move CurDate to Helpers * Make ptfm control local vars not allocatable * Tidy file writing when rosco_vt read from another input * Update input files in Test_Cases * Add Echo file writing and input to ROSCO * Check for failure after each input section, tidy OL default * Init and read OL inputs after checking inputs * Close echo file so it all shows up * Remove return after not finding line * Remove a few more returns, specify default array length properly * Tidy up error messages around array length * Fix string reading * Skip array parsing if line not found * Increase max word size for long file paths * Fix example headers * Add defaults logic for filters * Skip ExtController call if failed * Tidy up CheckInputs based on optional input testing * Add example for testing optional inputs * Tidy input file formatting * Fix expected result in 21_optional_inputs * Add cable control example * Fix openfast exe * Enable CCmode, MD outputs, set channel ID in example 22 * Add structural control example, not in CI due to OF reqs * Add input yaml for StC example * Tidy comments, file closing * Remove default CC_* params from DISCON_dict * Tidy example 23 readme * Add StC indices of avrswap to dbg3 * Tidy utilities and example 23 * Add API changes to docs * Update toolbox input * Delay DLC 1.4 start, use AFAeroMod of 1 * Disable UA for all tests --------- Co-authored-by: Alex Clerc --- Examples/01_turbine_model.py | 2 +- Examples/02_ccblade.py | 2 +- Examples/03_tune_controller.py | 2 +- Examples/04_simple_sim.py | 2 +- Examples/05_openfast_sim.py | 2 +- Examples/06_peak_shaving.py | 2 +- Examples/07_openfast_outputs.py | 2 +- Examples/08_run_turbsim.py | 2 +- Examples/09_distributed_aero.py | 2 +- Examples/10_linear_params.py | 2 +- Examples/11_robust_tuning.py | 2 +- Examples/21_optional_inputs.py | 51 ++ Examples/22_cable_control.py | 119 +++ Examples/23_structural_control.py | 88 +++ Examples/example_inputs/minimal_DISCON.IN | 99 +++ Examples/example_inputs/minimal_DISCON_err.IN | 106 +++ Examples/test_examples.py | 6 +- ROSCO/rosco_registry/rosco_types.yaml | 145 +++- ROSCO/rosco_registry/write_registry.py | 46 +- ROSCO/src/Constants.f90 | 2 + ROSCO/src/ControllerBlocks.f90 | 2 +- ROSCO/src/Controllers.f90 | 104 +++ ROSCO/src/DISCON.F90 | 14 +- ROSCO/src/Filters.f90 | 58 +- ROSCO/src/Functions.f90 | 65 -- ROSCO/src/ROSCO_Helpers.f90 | 722 +++++++++++++++++- ROSCO/src/ROSCO_IO.f90 | 232 +++++- ROSCO/src/ROSCO_Types.f90 | 41 + ROSCO/src/ReadSetParameters.f90 | 553 ++++++++------ ROSCO_testing/ROSCO_testing.py | 3 +- ROSCO_toolbox/control_interface.py | 2 + ROSCO_toolbox/controller.py | 2 + ROSCO_toolbox/inputs/toolbox_schema.yaml | 44 +- ROSCO_toolbox/ofTools/case_gen/CaseGen_IEC.py | 3 + ROSCO_toolbox/ofTools/case_gen/run_FAST.py | 5 +- ROSCO_toolbox/ofTools/fast_io/FAST_reader.py | 176 ++++- ROSCO_toolbox/ofTools/fast_io/FAST_writer.py | 19 +- ROSCO_toolbox/utilities.py | 41 +- Test_Cases/BAR_10/BAR_10_DISCON.IN | 18 +- .../DISCON-UMaineSemi.IN | 18 +- .../StC-Force-Col1.dat | 95 +++ .../StC-Force-Col2.dat | 95 +++ .../StC-Force-Col3.dat | 95 +++ Test_Cases/NREL-5MW/DISCON.IN | 18 +- Tune_Cases/IEA15MW_ballast.yaml | 59 ++ Tune_Cases/IEA15MW_cable.yaml | 59 ++ docs/source/api_change.rst | 28 + docs/source/toolbox_input.rst | 54 +- 48 files changed, 2938 insertions(+), 371 deletions(-) create mode 100644 Examples/21_optional_inputs.py create mode 100644 Examples/22_cable_control.py create mode 100644 Examples/23_structural_control.py create mode 100644 Examples/example_inputs/minimal_DISCON.IN create mode 100644 Examples/example_inputs/minimal_DISCON_err.IN create mode 100644 Test_Cases/IEA-15-240-RWT-UMaineSemi/StC-Force-Col1.dat create mode 100644 Test_Cases/IEA-15-240-RWT-UMaineSemi/StC-Force-Col2.dat create mode 100644 Test_Cases/IEA-15-240-RWT-UMaineSemi/StC-Force-Col3.dat create mode 100644 Tune_Cases/IEA15MW_ballast.yaml create mode 100644 Tune_Cases/IEA15MW_cable.yaml diff --git a/Examples/01_turbine_model.py b/Examples/01_turbine_model.py index 14a30fc2..95a69bac 100644 --- a/Examples/01_turbine_model.py +++ b/Examples/01_turbine_model.py @@ -1,5 +1,5 @@ ''' ------------ Example_01 -------------- +----------- 01_turbine_model -------------- Load and save a turbine model ------------------------------------- In this example: diff --git a/Examples/02_ccblade.py b/Examples/02_ccblade.py index 8d09aaff..11afd6a2 100644 --- a/Examples/02_ccblade.py +++ b/Examples/02_ccblade.py @@ -1,5 +1,5 @@ ''' ------------ Example_03 -------------- +----------- 02_ccblade -------------- Run CCblade, save a rotor performance text file ------------------------------------- diff --git a/Examples/03_tune_controller.py b/Examples/03_tune_controller.py index a4308390..4aa19369 100644 --- a/Examples/03_tune_controller.py +++ b/Examples/03_tune_controller.py @@ -1,5 +1,5 @@ ''' ------------ Example_04 -------------- +----------- 03_tune_controller -------------- Load a turbine model and tune the controller ------------------------------------- diff --git a/Examples/04_simple_sim.py b/Examples/04_simple_sim.py index 29d0c7b2..aba7e468 100644 --- a/Examples/04_simple_sim.py +++ b/Examples/04_simple_sim.py @@ -1,5 +1,5 @@ ''' ------------ Example_05 -------------- +----------- 04_simple_sim -------------- Run and plot a simple simple step wind simulation ------------------------------------- diff --git a/Examples/05_openfast_sim.py b/Examples/05_openfast_sim.py index a11f1b30..7dd33085 100644 --- a/Examples/05_openfast_sim.py +++ b/Examples/05_openfast_sim.py @@ -1,5 +1,5 @@ ''' ------------ Example_06 -------------- +----------- 05_openfast_sim -------------- Load a turbine, tune a controller, run OpenFAST simulation ------------------------------------- diff --git a/Examples/06_peak_shaving.py b/Examples/06_peak_shaving.py index fdad7db8..525e4fc0 100644 --- a/Examples/06_peak_shaving.py +++ b/Examples/06_peak_shaving.py @@ -1,5 +1,5 @@ ''' ------------ Example_07 -------------- +----------- 06_peak_shavings -------------- Load saved turbine, tune controller, plot minimum pitch schedule ------------------------------------- diff --git a/Examples/07_openfast_outputs.py b/Examples/07_openfast_outputs.py index a794baf0..d50eab99 100644 --- a/Examples/07_openfast_outputs.py +++ b/Examples/07_openfast_outputs.py @@ -1,5 +1,5 @@ ''' ------------ Example_08 -------------- +----------- 07_openfast_outputss -------------- Plot some OpenFAST output data ------------------------------------- diff --git a/Examples/08_run_turbsim.py b/Examples/08_run_turbsim.py index bdabca8a..488b07ea 100644 --- a/Examples/08_run_turbsim.py +++ b/Examples/08_run_turbsim.py @@ -1,5 +1,5 @@ ''' ------------ Example_09 -------------- +----------- 08_run_turbsim -------------- Run TurbSim to create wind field binary ------------------------------------- diff --git a/Examples/09_distributed_aero.py b/Examples/09_distributed_aero.py index 6d970194..234fd6de 100644 --- a/Examples/09_distributed_aero.py +++ b/Examples/09_distributed_aero.py @@ -1,5 +1,5 @@ ''' ------------ Example_10 -------------- +----------- 09_distributed_aero -------------- Tune a controller for distributed aerodynamic control ------------------------------------- diff --git a/Examples/10_linear_params.py b/Examples/10_linear_params.py index b0c2470f..69aa3094 100644 --- a/Examples/10_linear_params.py +++ b/Examples/10_linear_params.py @@ -1,5 +1,5 @@ ''' ------------ Example_11 -------------- +----------- 10_linear_params -------------- Load a turbine, tune a controller, export linear model ------------------------------------- diff --git a/Examples/11_robust_tuning.py b/Examples/11_robust_tuning.py index 65f676d3..aa4d7df6 100644 --- a/Examples/11_robust_tuning.py +++ b/Examples/11_robust_tuning.py @@ -1,5 +1,5 @@ ''' ------------ Example_12 -------------- +----------- 11_robust_tuning -------------- Controller tuning to satisfy a robustness criteria ------------------------------------- NOTE: This example necessitates the mbc3 through either pyFAST or WEIS diff --git a/Examples/21_optional_inputs.py b/Examples/21_optional_inputs.py new file mode 100644 index 00000000..8a69b0ac --- /dev/null +++ b/Examples/21_optional_inputs.py @@ -0,0 +1,51 @@ +''' +----------- 21_optional_inputse_discon_version ----------------- +Test and demonstrate update_discon_version() function for converting an old ROSCO input +to the current version +''' + +import os, platform +from ROSCO_toolbox import control_interface as ROSCO_ci +from ROSCO_toolbox import sim as ROSCO_sim +from ROSCO_toolbox import turbine as ROSCO_turbine +import numpy as np + + +this_dir = os.path.dirname(os.path.abspath(__file__)) +rosco_dir = os.path.dirname(this_dir) + +example_out_dir = os.path.join(this_dir,'examples_out') +example_in_dir = os.path.join(this_dir,'example_inputs') + + +def main(): + + # Set up rosco_dll + if platform.system() == 'Windows': + rosco_dll = os.path.join(rosco_dir, 'ROSCO/build/libdiscon.dll') + elif platform.system() == 'Darwin': + rosco_dll = os.path.join(rosco_dir, 'ROSCO/build/libdiscon.dylib') + else: + rosco_dll = os.path.join(rosco_dir, 'ROSCO/build/libdiscon.so') + + # Load turbine model from saved pickle + turbine = ROSCO_turbine.Turbine + turbine = turbine.load(os.path.join(example_out_dir,'01_NREL5MW_saved.p')) + + # Not an extensive list, but can add if issues arise + param_filenames = [ + os.path.join(example_in_dir, 'minimal_DISCON.IN'), # pass + os.path.join(example_in_dir, 'minimal_DISCON_err.IN'), # fail + ] + + avi_fail = [] + for param_filename in param_filenames: + controller_int = ROSCO_ci.ControllerInterface(rosco_dll,param_filename=param_filename,sim_name='sim1') + controller_int.kill_discon() + avi_fail.append(controller_int.aviFAIL.value) + + # Check whether controller call failed + assert avi_fail == [0,-1], "Unexpected pass/fail" + +if __name__ == "__main__": + main() \ No newline at end of file diff --git a/Examples/22_cable_control.py b/Examples/22_cable_control.py new file mode 100644 index 00000000..8c808200 --- /dev/null +++ b/Examples/22_cable_control.py @@ -0,0 +1,119 @@ +''' +----------- 22_cable_control ------------------------ +Run openfast with ROSCO and cable control +----------------------------------------------- + +Set up and run simulation with pitch offsets, check outputs + +''' + +import os, platform +from ROSCO_toolbox.ofTools.case_gen.run_FAST import run_FAST_ROSCO +from ROSCO_toolbox.ofTools.case_gen import CaseLibrary as cl +from ROSCO_toolbox.ofTools.fast_io import output_processing +import numpy as np +from ROSCO_toolbox.ofTools.fast_io.FAST_reader import InputReader_OpenFAST +from ROSCO_toolbox.inputs.validation import load_rosco_yaml +import matplotlib.pyplot as plt + +''' +ROSCO currently supports user-defined hooks for cable control actuation, if CC_Mode = 1. +The control logic can be determined in Controllers.f90 with the CableControl subroutine. +The CableControl subroutine takes an array of CC_DesiredL (length) equal to the ChannelIDs set in MoorDyn and +determines the length and change in length needed for MoorDyn using a 2nd order actuator model (CC_ActTau). +In the DISCON input, users must specify CC_GroupIndex relating to the deltaL of each control ChannelID. +These indices can be found in the ServoDyn summary file (*SrvD.sum) + +In the example below (and hard-coded in ROSCO) a step change of -10 m on line 1 is applied at 50 sec. +''' + + +#directories +this_dir = os.path.dirname(os.path.abspath(__file__)) +rosco_dir = os.path.dirname(this_dir) +example_out_dir = os.path.join(this_dir,'examples_out') +os.makedirs(example_out_dir,exist_ok=True) + +if platform.system() == 'Windows': + lib_name = os.path.realpath(os.path.join(this_dir, '../ROSCO/build/libdiscon.dll')) +elif platform.system() == 'Darwin': + lib_name = os.path.realpath(os.path.join(this_dir, '../ROSCO/build/libdiscon.dylib')) +else: + lib_name = os.path.realpath(os.path.join(this_dir, '../ROSCO/build/libdiscon.so')) + + +def main(): + + # Input yaml and output directory + parameter_filename = os.path.join(rosco_dir,'Tune_Cases/IEA15MW_cable.yaml') + run_dir = os.path.join(example_out_dir,'22_cable_control') + os.makedirs(run_dir,exist_ok=True) + + # Read initial input file + inps = load_rosco_yaml(parameter_filename) + path_params = inps['path_params'] + + # Change inputs programatically, read first + reader = InputReader_OpenFAST() + reader.FAST_InputFile = path_params['FAST_InputFile'] + reader.FAST_directory = os.path.join(rosco_dir,'Tune_Cases',path_params['FAST_directory']) + reader.execute() + + # Set control line mapping (ChannelID -> Line(s)) + reader.fst_vt['MoorDyn']['ChannelID'] = [1, 2, 3] + reader.fst_vt['MoorDyn']['Lines_Control'] = [['1'], ['2'], ['3']] + + # Make segments longer + reader.fst_vt['MoorDyn']['NumSegs'] = [20,20,20] + + # Outputs + reader.fst_vt['MoorDyn']['Outputs'] = ['l', 'l', 'l'] + + # Set up ServoDyn for cable control + reader.fst_vt['ServoDyn']['CCmode'] = 5 + + # simulation set up + r = run_FAST_ROSCO() + r.tuning_yaml = parameter_filename + r.wind_case_fcn = cl.simp_step # single step wind input + r.wind_case_fcn = cl.power_curve + r.wind_case_opts = { + 'U': [9], + 'T_max': 100, + } + r.case_inputs = {} + r.fst_vt = reader.fst_vt + # r.controller_params = controller_params + r.save_dir = run_dir + r.rosco_dir = rosco_dir + + r.run_FAST() + + + op = output_processing.output_processing() + op2 = output_processing.output_processing() + + md_out = op.load_fast_out([os.path.join(run_dir,'IEA15MW_cable/power_curve/base/IEA15MW_cable_0.MD.Line1.out')], tmin=0) + local_vars = op2.load_fast_out([os.path.join(run_dir,'IEA15MW_cable/power_curve/base/IEA15MW_cable_0.RO.dbg2')], tmin=0) + + fig, axs = plt.subplots(4,1) + axs[0].plot(local_vars[0]['Time'],local_vars[0]['CC_DesiredL'],label='CC_DesiredL') + axs[1].plot(local_vars[0]['Time'],local_vars[0]['CC_ActuatedL'],label='CC_ActuatedL') + axs[2].plot(local_vars[0]['Time'],local_vars[0]['CC_ActuatedDL'],label='CC_ActuatedDL') + axs[3].plot(md_out[0]['Time'],md_out[0]['Seg20Lst'],label='Seg20Lst') + + [a.legend() for a in axs] + [a.grid() for a in axs] + + if False: + plt.show() + else: + plt.savefig(os.path.join(example_out_dir,'22_cable_control.png')) + + # Check that the last segment of line 1 shrinks by 10 m + np.testing.assert_almost_equal(md_out[0]['Seg20Lst'][-1] - md_out[0]['Seg20Lst'][0], -10, 2) + + + +if __name__=="__main__": + main() \ No newline at end of file diff --git a/Examples/23_structural_control.py b/Examples/23_structural_control.py new file mode 100644 index 00000000..2a49b0f5 --- /dev/null +++ b/Examples/23_structural_control.py @@ -0,0 +1,88 @@ +''' +----------- 23_structural_control ------------------------ +Run openfast with ROSCO and structural control +----------------------------------------------- + +Set up and run simulation with pitch offsets, check outputs + +''' + +import os, platform +from ROSCO_toolbox.ofTools.case_gen.run_FAST import run_FAST_ROSCO +from ROSCO_toolbox.ofTools.case_gen import CaseLibrary as cl +import numpy as np +from ROSCO_toolbox.ofTools.fast_io.FAST_reader import InputReader_OpenFAST +from ROSCO_toolbox.inputs.validation import load_rosco_yaml + +''' +ROSCO currently supports user-defined hooks for structural control control actuation, if StC_Mode = 1. +The control logic can be determined in Controllers.f90 with the StructrualControl subroutine. +In the DISCON input, users must specify StC_GroupIndex relating to the control ChannelID. +These indices can be found in the ServoDyn summary file (*SrvD.sum) + +In the example below (and hard-coded in ROSCO) a step change of -4e5 N on the first structural controller +is applied at 50 sec. + +The develop branch (as of Mar 3, 2023) of OpenFAST (v3.5.0, upcoming) is required to run this example +''' + + +#directories +this_dir = os.path.dirname(os.path.abspath(__file__)) +rosco_dir = os.path.dirname(this_dir) +example_out_dir = os.path.join(this_dir,'examples_out') +os.makedirs(example_out_dir,exist_ok=True) + +if platform.system() == 'Windows': + lib_name = os.path.realpath(os.path.join(this_dir, '../ROSCO/build/libdiscon.dll')) +elif platform.system() == 'Darwin': + lib_name = os.path.realpath(os.path.join(this_dir, '../ROSCO/build/libdiscon.dylib')) +else: + lib_name = os.path.realpath(os.path.join(this_dir, '../ROSCO/build/libdiscon.so')) + + +def main(): + + # Input yaml and output directory + parameter_filename = os.path.join(rosco_dir,'Tune_Cases/IEA15MW_ballast.yaml') + run_dir = os.path.join(example_out_dir,'23_structural_control') + os.makedirs(run_dir,exist_ok=True) + + # Read initial input file + inps = load_rosco_yaml(parameter_filename) + path_params = inps['path_params'] + + # Change inputs programatically, read first + reader = InputReader_OpenFAST() + reader.FAST_InputFile = path_params['FAST_InputFile'] + reader.FAST_directory = os.path.join(rosco_dir,'Tune_Cases',path_params['FAST_directory']) + # reader.FAST_directory = '/Users/dzalkind/Tools/ROSCO1/Test_Cases/ptfm_control_archive/IEA-15-240-RWT-UMaineSemi_ballast' + reader.execute() + + reader.fst_vt['ServoDyn']['NumSStC'] = 3 + reader.fst_vt['ServoDyn']['SStCfiles'] = ['StC-Force-Col1.dat', 'StC-Force-Col2.dat', 'StC-Force-Col3.dat'] + # Add SStC file inputs + for StC_file in reader.fst_vt['ServoDyn']['SStCfiles']: + reader.fst_vt['SStC'].append(reader.read_StC(StC_file)) + + + # simulation set up + r = run_FAST_ROSCO() + r.tuning_yaml = parameter_filename + r.wind_case_fcn = cl.simp_step # single step wind input + r.wind_case_fcn = cl.power_curve + r.wind_case_opts = { + 'U': [9], + 'T_max': 100, + } + r.case_inputs = {} + r.fst_vt = reader.fst_vt + r.save_dir = run_dir + r.rosco_dir = rosco_dir + + r.run_FAST() + + + +if __name__=="__main__": + main() \ No newline at end of file diff --git a/Examples/example_inputs/minimal_DISCON.IN b/Examples/example_inputs/minimal_DISCON.IN new file mode 100644 index 00000000..21716d03 --- /dev/null +++ b/Examples/example_inputs/minimal_DISCON.IN @@ -0,0 +1,99 @@ +! Controller parameter input file for the NREL-5MW wind turbine +! - File written using ROSCO version 2.7.0 controller tuning logic on 02/27/23 + +!------- DEBUG ------------------------------------------------------------ +0 ! LoggingLevel - (0: write no debug files, 1: write standard output .dbg-file, 2: LoggingLevel 1 + ROSCO LocalVars (.dbg2) 3: LoggingLevel 2 + complete avrSWAP-array (.dbg3)) +0 ! Echo - (0 - no Echo, 1 - Echo input data to .echo) + +!------- 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 +3 ! VS_ControlMode - Generator torque control mode in above rated conditions {0: constant torque, 1: constant power, 2: TSR tracking PI control with constant torque, 3: TSR tracking PI control with constant power} +1 ! PC_ControlMode - Blade pitch control mode {0: No pitch, fix to fine pitch, 1: active PI blade pitch control} +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: Immersion and Invariance Estimator, 2: Extended Kalman Filter} +1 ! PS_Mode - Pitch saturation mode {0: no pitch saturation, 1: implement pitch saturation} + +Extra lines that ROSCO doesn't care about anymore + +!------- FILTERS ---------------------------------------------------------- +1.57080 ! F_LPFCornerFreq - Corner frequency (-3dB point) in the low-pass filters, [rad/s] +0.62830 ! F_SSCornerFreq - Corner frequency (-3dB point) in the first order low pass filter for the setpoint smoother, [rad/s]. +0.20944 ! F_WECornerFreq - Corner frequency (-3dB point) in the first order low pass filter for the wind speed estimate [rad/s]. +0.17952 ! F_YawErr - Low pass filter corner frequency for yaw controller [rad/s]. +0.000000 1.000000 ! F_FlCornerFreq - Natural frequency and damping in the second order low pass filter of the tower-top fore-aft motion for floating feedback control [rad/s, -]. +0.01042 ! F_FlHighPassFreq - Natural frequency of first-order high-pass filter for nacelle fore-aft motion [rad/s]. +0.000000 1.000000 ! F_FlpCornerFreq - Corner frequency and damping in the second order low pass filter of the blade root bending moment for flap control [rad/s, -]. + +!------- BLADE PITCH CONTROL ---------------------------------------------- +30 ! PC_GS_n - Amount of gain-scheduling table entries +0.056789 0.084492 0.106018 0.124332 0.140807 0.155903 0.169931 0.183270 0.196062 0.208354 0.220050 0.231503 0.242646 0.253377 0.263967 0.274233 0.284343 0.294292 0.303997 0.313626 0.322957 0.332260 0.341319 0.350368 0.359221 0.368059 0.376700 0.385301 0.393691 0.402050 ! PC_GS_angles - Gain-schedule table: pitch angles [rad]. +-0.020655 -0.018159 -0.016134 -0.014459 -0.013049 -0.011846 -0.010809 -0.009904 -0.009108 -0.008403 -0.007774 -0.007209 -0.006698 -0.006235 -0.005813 -0.005427 -0.005072 -0.004745 -0.004442 -0.004162 -0.003901 -0.003657 -0.003430 -0.003217 -0.003017 -0.002829 -0.002652 -0.002484 -0.002326 -0.002176 ! PC_GS_KP - Gain-schedule table: pitch controller kp gains [s]. +-0.008388 -0.007514 -0.006805 -0.006218 -0.005725 -0.005304 -0.004940 -0.004624 -0.004345 -0.004098 -0.003878 -0.003680 -0.003501 -0.003339 -0.003192 -0.003056 -0.002932 -0.002817 -0.002712 -0.002613 -0.002522 -0.002437 -0.002357 -0.002283 -0.002212 -0.002147 -0.002085 -0.002026 -0.001971 -0.001918 ! PC_GS_KI - Gain-schedule table: pitch controller ki gains [-]. +0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 ! PC_GS_KD - Gain-schedule table: pitch controller kd gains +0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 ! PC_GS_TF - Gain-schedule table: pitch controller tf gains (derivative filter) +1.570000000000 ! PC_MaxPit - Maximum physical pitch limit, [rad]. +0.000880000000 ! PC_MinPit - Minimum physical pitch limit, [rad]. +0.174500000000 ! PC_MaxRat - Maximum pitch rate (in absolute value) in pitch controller, [rad/s]. +-0.17450000000 ! PC_MinRat - Minimum pitch rate (in absolute value) in pitch controller, [rad/s]. +122.9096700000 ! PC_RefSpd - Desired (reference) HSS speed for pitch controller, [rad/s]. +0.000880000000 ! PC_FinePit - Record 5: Below-rated pitch angle set-point, [rad] +0.017450000000 ! PC_Switch - Angle above lowest minimum pitch angle for switch, [rad] + +!------- INDIVIDUAL PITCH CONTROL ----------------------------------------- +9.120000 11.400000 ! IPC_Vramp - Start and end wind speeds for cut-in ramp function. First entry: IPC inactive, second entry: IPC fully active. [m/s] +2 ! IPC_SatMode - IPC Saturation method (0 - no saturation (except by PC_MinPit), 1 - saturate by PS_BldPitchMin, 2 - saturate sotfly (full IPC cycle) by PC_MinPit, 3 - saturate softly by PS_BldPitchMin) +0.3 ! IPC_IntSat - Integrator saturation (maximum signal amplitude contribution to pitch from IPC), [rad] +0.000e+00 0.000e+00 ! IPC_KP - Proportional gain for the individual pitch controller: first parameter for 1P reductions, second for 2P reductions, [-] +0.000e+00 0.000e+00 ! IPC_KI - Integral gain for the individual pitch controller: first parameter for 1P reductions, second for 2P reductions, [-] +0.000000 0.000000 ! 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 ------------------------------------------------ +94.40000000000 ! VS_GenEff - Generator efficiency mechanical power -> electrical power, [should match the efficiency defined in the generator properties!], [%] +43093.51876000 ! VS_ArSatTq - Above rated generator torque PI control saturation, [Nm] +1500000.000000 ! VS_MaxRat - Maximum torque rate (in absolute value) in torque controller, [Nm/s]. +47402.87063000 ! VS_MaxTq - Maximum generator torque in Region 3 (HSS side), [Nm]. +0.000000000000 ! VS_MinTq - Minimum generator torque (HSS side), [Nm]. +35.29006000000 ! VS_MinOMSpd - Minimum generator speed [rad/s] +2.185750000000 ! VS_Rgn2K - Generator torque constant in Region 2 (HSS side), [Nm/(rad/s)^2] +5000000.000000 ! VS_RtPwr - Wind turbine rated power [W] +43093.51876000 ! VS_RtTq - Rated torque, [Nm]. +122.9096700000 ! VS_RefSpd - Rated generator speed [rad/s] +1 ! VS_n - Number of generator PI torque controller gains +-657.442080000 ! VS_KP - Proportional gain for generator PI torque controller [-]. (Only used in the transitional 2.5 region if VS_ControlMode =/ 2) +-104.507080000 ! VS_KI - Integral gain for generator PI torque controller [s]. (Only used in the transitional 2.5 region if VS_ControlMode =/ 2) +7.64 ! VS_TSRopt - Power-maximizing region 2 tip-speed-ratio [rad]. + +!------- SETPOINT SMOOTHER --------------------------------------------- +1.00000 ! SS_VSGain - Variable speed torque controller setpoint smoother gain, [-]. +0.00100 ! SS_PCGain - Collective pitch controller setpoint smoother gain, [-]. + +Extra lines that ROSCO doesn't care about anymore + +!------- WIND SPEED ESTIMATOR --------------------------------------------- +63.000 ! WE_BladeRadius - Blade length (distance from hub center to blade tip), [m] +1 ! WE_CP_n - Amount of parameters in the Cp array +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], [-] +43702538.05700 ! 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.NREL5MW.txt" ! PerfFileName - File containing rotor performance tables (Cp,Ct,Cq) (absolute path or relative to this file) +36 26 ! PerfTableSize - Size of rotor performance tables, first number refers to number of blade pitch angles, second number referse to number of tip-speed ratios +60 ! WE_FOPoles_N - Number of first-order system poles used in EKF +3.0000 3.2897 3.5793 3.8690 4.1586 4.4483 4.7379 5.0276 5.3172 5.6069 5.8966 6.1862 6.4759 6.7655 7.0552 7.3448 7.6345 7.9241 8.2138 8.5034 8.7931 9.0828 9.3724 9.6621 9.9517 10.2414 10.5310 10.8207 11.1103 11.4000 11.8533 12.3067 12.7600 13.2133 13.6667 14.1200 14.5733 15.0267 15.4800 15.9333 16.3867 16.8400 17.2933 17.7467 18.2000 18.6533 19.1067 19.5600 20.0133 20.4667 20.9200 21.3733 21.8267 22.2800 22.7333 23.1867 23.6400 24.0933 24.5467 25.0000 ! WE_FOPoles_v - Wind speeds corresponding to first-order system poles [m/s] +-0.01638154 -0.01796321 -0.01954487 -0.02112654 -0.02270820 -0.02428987 -0.02587154 -0.02745320 -0.02903487 -0.03061653 -0.03219820 -0.03377987 -0.03536153 -0.03694320 -0.03852486 -0.04010653 -0.04168820 -0.04326986 -0.04485153 -0.04643319 -0.04801486 -0.04959652 -0.05117819 -0.05275986 -0.05434152 -0.05592319 -0.05758373 -0.05882656 -0.06845507 -0.05992890 0.02094683 0.01327182 0.00285485 -0.00935731 -0.02210773 -0.03573037 -0.04990222 -0.06404904 -0.07899629 -0.09463190 -0.10954192 -0.12525205 -0.14168652 -0.15843395 -0.17415061 -0.19052486 -0.20780146 -0.22581018 -0.24373777 -0.26010871 -0.27706767 -0.29551708 -0.31430599 -0.33428552 -0.35420853 -0.37183729 -0.38936451 -0.40828911 -0.42758878 -0.44818175 ! WE_FOPoles - First order system poles [1/s] + +!------- MINIMUM PITCH SATURATION ------------------------------------------- +60 ! PS_BldPitchMin_N - Number of values in minimum blade pitch lookup table (should equal number of values in PS_WindSpeeds and PS_BldPitchMin) +3.0000 3.2897 3.5793 3.8690 4.1586 4.4483 4.7379 5.0276 5.3172 5.6069 5.8966 6.1862 6.4759 6.7655 7.0552 7.3448 7.6345 7.9241 8.2138 8.5034 8.7931 9.0828 9.3724 9.6621 9.9517 10.2414 10.5310 10.8207 11.1103 11.4000 11.8533 12.3067 12.7600 13.2133 13.6667 14.1200 14.5733 15.0267 15.4800 15.9333 16.3867 16.8400 17.2933 17.7467 18.2000 18.6533 19.1067 19.5600 20.0133 20.4667 20.9200 21.3733 21.8267 22.2800 22.7333 23.1867 23.6400 24.0933 24.5467 25.0000 ! PS_WindSpeeds - Wind speeds corresponding to minimum blade pitch angles [m/s] +0.00088027 0.00088027 0.00088027 0.00088027 0.00088027 0.00088027 0.00088027 0.00088027 0.00088027 0.00088027 0.00088027 0.00088027 0.00088027 0.00088027 0.00088027 0.00088027 0.00088027 0.00088027 0.00088027 0.00088027 0.00088027 0.00088027 0.00088027 0.00088027 0.00088027 0.01116187 0.02310060 0.03164156 0.03968639 0.04741131 0.05899071 0.07019329 0.08090119 0.09141661 0.10169361 0.11174124 0.12170066 0.13137494 0.14103377 0.15048120 0.15989580 0.16913227 0.17831010 0.18739638 0.19643591 0.20537011 0.21419674 0.22293719 0.23161365 0.24025975 0.24885012 0.25735704 0.26578040 0.27407178 0.28233051 0.29047594 0.29867838 0.30674517 0.31490089 0.32284411 ! PS_BldPitchMin - Minimum blade pitch angles [rad] + +!------- SHUTDOWN ----------------------------------------------------------- +0.436300000000 ! SD_MaxPit - Maximum blade pitch angle to initiate shutdown, [rad] +0.418880000000 ! SD_CornerFreq - Cutoff Frequency for first order low-pass filter for blade pitch angle, [rad/s] + +!------- Floating ----------------------------------------------------------- +0.000000000000 ! Fl_Kp - Nacelle velocity proportional feedback gain [s] + +Extra lines that ROSCO doesn't care about anymore \ No newline at end of file diff --git a/Examples/example_inputs/minimal_DISCON_err.IN b/Examples/example_inputs/minimal_DISCON_err.IN new file mode 100644 index 00000000..327af71c --- /dev/null +++ b/Examples/example_inputs/minimal_DISCON_err.IN @@ -0,0 +1,106 @@ +! Controller parameter input file for the NREL-5MW wind turbine +! - File written using ROSCO version 2.7.0 controller tuning logic on 02/27/23 + +!------- DEBUG ------------------------------------------------------------ +0 ! LoggingLevel - (0: write no debug files, 1: write standard output .dbg-file, 2: LoggingLevel 1 + ROSCO LocalVars (.dbg2) 3: LoggingLevel 2 + complete avrSWAP-array (.dbg3)) +1 ! Echo - (0 - no Echo, 1 - Echo input data to .echo) + +!------- 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 and/or tower fore-aft motion (for floating) {0: disable, 1: generator speed, 2: tower-top fore-aft motion, 3: generator speed and tower-top fore-aft motion} +1 ! IPC_ControlMode - Turn Individual Pitch Control (IPC) for fatigue load reductions (pitch contribution) {0: off, 1: 1P reductions, 2: 1P+2P reductions} +3 ! VS_ControlMode - Generator torque control mode in above rated conditions {0: constant torque, 1: constant power, 2: TSR tracking PI control with constant torque, 3: TSR tracking PI control with constant power} +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} +0 ! WE_Mode - Wind speed estimator mode {0: One-second low pass filtered hub height wind speed, 1: Immersion and Invariance Estimator, 2: Extended Kalman Filter} +0 ! SD_Mode - Shutdown mode {0: no shutdown procedure, 1: pitch to max pitch at shutdown} +0 ! Fl_Mode - Floating specific feedback mode {0: no nacelle velocity feedback, 1: feed back translational velocity, 2: feed back rotational veloicty} +0 ! TD_Mode - Tower damper mode {0: no tower damper, 1: feed back translational nacelle accelleration to pitch angle} +0 ! Flp_Mode - Flap control mode {0: no flap control, 1: steady state flap angle, 2: Proportional flap control, 2: Cyclic (1P) flap control} +0 ! OL_Mode - Open loop control mode {0: no open loop control, 1: open loop control vs. time} +0 ! PA_Mode - Pitch actuator mode {0 - not used, 1 - first order filter, 2 - second order filter} +0 ! PF_Mode - Pitch fault mode {0 - not used, 1 - constant offset on one or more blades} +0 ! ZMQ_Mode - Fuse ZeroMQ interface {0: unused, 1: Yaw Control} +0 ! CC_Mode - Cable control mode [0- unused, 1- User defined, 2- Position control (not yet implemented)] +1 ! StC_Mode - Structural control mode [0- unused, 1- User defined] + +Extra lines that ROSCO doesn't care about anymore + + + + +!------- FILTERS ---------------------------------------------------------- +1.57080 ! F_LPFCornerFreq - Corner frequency (-3dB point) in the low-pass filters, [rad/s] +0.00000 ! F_LPFDamping - Damping coefficient {used only when F_FilterType = 2} [-] +0.00000 ! F_NotchCornerFreq - Natural frequency of the notch filter, [rad/s] +0.000000 0.250000 ! F_NotchBetaNumDen - Two notch damping values (numerator and denominator, resp) - determines the width and depth of the notch, [-] +0.62830 ! F_SSCornerFreq - Corner frequency (-3dB point) in the first order low pass filter for the setpoint smoother, [rad/s]. +0.20944 ! F_WECornerFreq - Corner frequency (-3dB point) in the first order low pass filter for the wind speed estimate [rad/s]. +0.17952 ! F_YawErr - Low pass filter corner frequency for yaw controller [rad/s]. +0.000000 1.000000 ! F_FlCornerFreq - Natural frequency and damping in the second order low pass filter of the tower-top fore-aft motion for floating feedback control [rad/s, -]. +0.01042 ! F_FlHighPassFreq - Natural frequency of first-order high-pass filter for nacelle fore-aft motion [rad/s]. +0.000000 1.000000 ! F_FlpCornerFreq - Corner frequency and damping in the second order low pass filter of the blade root bending moment for flap control [rad/s, -]. + +!------- BLADE PITCH CONTROL ---------------------------------------------- +30 ! PC_GS_n - Amount of gain-scheduling table entries +0.056789 0.084492 0.106018 0.124332 0.140807 0.155903 0.169931 0.183270 0.196062 0.208354 0.220050 0.231503 0.242646 0.253377 0.263967 0.274233 0.284343 0.294292 0.303997 0.313626 0.322957 0.332260 0.341319 0.350368 0.359221 0.368059 0.376700 0.385301 0.393691 0.402050 ! PC_GS_angles - Gain-schedule table: pitch angles [rad]. +-0.020655 -0.018159 -0.016134 -0.014459 -0.013049 -0.011846 -0.010809 -0.009904 -0.009108 -0.008403 -0.007774 -0.007209 -0.006698 -0.006235 -0.005813 -0.005427 -0.005072 -0.004745 -0.004442 -0.004162 -0.003901 -0.003657 -0.003430 -0.003217 -0.003017 -0.002829 -0.002652 -0.002484 -0.002326 -0.002176 ! PC_GS_KP - Gain-schedule table: pitch controller kp gains [s]. +-0.008388 -0.007514 -0.006805 -0.006218 -0.005725 -0.005304 -0.004940 -0.004624 -0.004345 -0.004098 -0.003878 -0.003680 -0.003501 -0.003339 -0.003192 -0.003056 -0.002932 -0.002817 -0.002712 -0.002613 -0.002522 -0.002437 -0.002357 -0.002283 -0.002212 -0.002147 -0.002085 -0.002026 -0.001971 -0.001918 ! PC_GS_KI - Gain-schedule table: pitch controller ki gains [-]. +0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 ! PC_GS_KD - Gain-schedule table: pitch controller kd gains +0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 ! PC_GS_TF - Gain-schedule table: pitch controller tf gains (derivative filter) +1.570000000000 ! PC_MaxPit - Maximum physical pitch limit, [rad]. +0.000880000000 ! PC_MinPit - Minimum physical pitch limit, [rad]. +0.174500000000 ! PC_MaxRat - Maximum pitch rate (in absolute value) in pitch controller, [rad/s]. +-0.17450000000 ! PC_MinRat - Minimum pitch rate (in absolute value) in pitch controller, [rad/s]. +122.9096700000 ! PC_RefSpd - Desired (reference) HSS speed for pitch controller, [rad/s]. +0.000880000000 ! PC_FinePit - Record 5: Below-rated pitch angle set-point, [rad] +0.017450000000 ! PC_Switch - Angle above lowest minimum pitch angle for switch, [rad] + +!------- INDIVIDUAL PITCH CONTROL ----------------------------------------- +9.120000 11.400000 ! IPC_Vramp - Start and end wind speeds for cut-in ramp function. First entry: IPC inactive, second entry: IPC fully active. [m/s] +2 ! IPC_SatMode - IPC Saturation method (0 - no saturation (except by PC_MinPit), 1 - saturate by PS_BldPitchMin, 2 - saturate sotfly (full IPC cycle) by PC_MinPit, 3 - saturate softly by PS_BldPitchMin) +0.3 ! IPC_IntSat - Integrator saturation (maximum signal amplitude contribution to pitch from IPC), [rad] +0.000e+00 0.000e+00 ! IPC_KP - Proportional gain for the individual pitch controller: first parameter for 1P reductions, second for 2P reductions, [-] +0.000e+00 0.000e+00 ! IPC_KI - Integral gain for the individual pitch controller: first parameter for 1P reductions, second for 2P reductions, [-] +0.000000 0.000000 ! 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 ------------------------------------------------ +94.40000000000 ! VS_GenEff - Generator efficiency mechanical power -> electrical power, [should match the efficiency defined in the generator properties!], [%] +43093.51876000 ! VS_ArSatTq - Above rated generator torque PI control saturation, [Nm] +1500000.000000 ! VS_MaxRat - Maximum torque rate (in absolute value) in torque controller, [Nm/s]. +47402.87063000 ! VS_MaxTq - Maximum generator torque in Region 3 (HSS side), [Nm]. +0.000000000000 ! VS_MinTq - Minimum generator torque (HSS side), [Nm]. +35.29006000000 ! VS_MinOMSpd - Minimum generator speed [rad/s] +2.185750000000 ! VS_Rgn2K - Generator torque constant in Region 2 (HSS side), [Nm/(rad/s)^2] +5000000.000000 ! VS_RtPwr - Wind turbine rated power [W] +43093.51876000 ! VS_RtTq - Rated torque, [Nm]. +122.9096700000 ! VS_RefSpd - Rated generator speed [rad/s] +1 ! VS_n - Number of generator PI torque controller gains +-657.442080000 ! VS_KP - Proportional gain for generator PI torque controller [-]. (Only used in the transitional 2.5 region if VS_ControlMode =/ 2) +-104.507080000 ! VS_KI - Integral gain for generator PI torque controller [s]. (Only used in the transitional 2.5 region if VS_ControlMode =/ 2) +7.64 ! VS_TSRopt - Power-maximizing region 2 tip-speed-ratio [rad]. + +!------- SETPOINT SMOOTHER --------------------------------------------- +1.00000 ! SS_VSGain - Variable speed torque controller setpoint smoother gain, [-]. +0.00100 ! SS_PCGain - Collective pitch controller setpoint smoother gain, [-]. + +Extra lines that ROSCO doesn't care about anymore + +!------- WIND SPEED ESTIMATOR --------------------------------------------- +63.000 ! WE_BladeRadius - Blade length (distance from hub center to blade tip), [m] +97.0 ! WE_GearboxRatio - Gearbox ratio [>=1], [-] + +!------- MINIMUM PITCH SATURATION ------------------------------------------- +60 ! PS_BldPitchMin_N - Number of values in minimum blade pitch lookup table (should equal number of values in PS_WindSpeeds and PS_BldPitchMin) +0.00088027 0.00088027 0.00088027 0.00088027 0.00088027 0.00088027 0.00088027 0.00088027 0.00088027 0.00088027 0.00088027 0.00088027 0.00088027 0.00088027 0.00088027 0.00088027 0.00088027 0.00088027 0.00088027 0.00088027 0.00088027 0.00088027 0.00088027 0.00088027 0.00088027 0.01116187 0.02310060 0.03164156 0.03968639 0.04741131 0.05899071 0.07019329 0.08090119 0.09141661 0.10169361 0.11174124 0.12170066 0.13137494 0.14103377 0.15048120 0.15989580 0.16913227 0.17831010 0.18739638 0.19643591 0.20537011 0.21419674 0.22293719 0.23161365 0.24025975 0.24885012 0.25735704 0.26578040 0.27407178 0.28233051 0.29047594 0.29867838 0.30674517 0.31490089 0.32284411 ! PS_BldPitchMin - Minimum blade pitch angles [rad] + +!------- SHUTDOWN ----------------------------------------------------------- +0.436300000000 ! SD_MaxPit - Maximum blade pitch angle to initiate shutdown, [rad] +0.418880000000 ! SD_CornerFreq - Cutoff Frequency for first order low-pass filter for blade pitch angle, [rad/s] + +!------- Floating ----------------------------------------------------------- +0.000000000000 ! Fl_Kp - Nacelle velocity proportional feedback gain [s] + +Extra lines that ROSCO doesn't care about anymore \ No newline at end of file diff --git a/Examples/test_examples.py b/Examples/test_examples.py index 89d9e6c9..6f46db30 100644 --- a/Examples/test_examples.py +++ b/Examples/test_examples.py @@ -19,9 +19,11 @@ '14_open_loop_control', '15_pass_through', '16_external_dll', - '17_zeromq_interface', - '18_pitch_offsets', # NJA: only runs on unix in CI + '17_zeromq_interface', # NJA: only runs on unix in CI + '18_pitch_offsets', '19_update_discon_version', + '21_optional_inputs', + '22_cable_control', 'update_rosco_discons', ] diff --git a/ROSCO/rosco_registry/rosco_types.yaml b/ROSCO/rosco_registry/rosco_types.yaml index 81ad0953..ff831169 100644 --- a/ROSCO/rosco_registry/rosco_types.yaml +++ b/ROSCO/rosco_registry/rosco_types.yaml @@ -69,7 +69,9 @@ ControlParameters: LoggingLevel: <<: *integer description: 0 - write no debug files, 1 - write standard output .dbg-file, 2 - write standard output .dbg-file and complete avrSWAP-array .dbg2-file - + Echo: + <<: *integer + description: 0 - no Echo, 1 - Echo input data to .echo # Filters F_LPFType: <<: *integer @@ -479,6 +481,38 @@ ControlParameters: <<: *real description: Integer for zeromq update frequency + # Cable control + CC_Mode: + <<: *integer + description: Flag for ZeroMQ (0-off, 1-yaw} + + CC_Group_N: + <<: *integer + description: Number of cable control groups + + CC_ActTau: + <<: *real + description: Time constant for line actuator [s] + + CC_GroupIndex: + <<: *integer + description: Cable control group indices + allocatable: True + + # StC Control + StC_Mode: + <<: *integer + description: Flag for ZeroMQ (0-off, 1-yaw} + + StC_Group_N: + <<: *integer + description: Number of cable control groups + + StC_GroupIndex: + <<: *integer + description: Cable control group indices + allocatable: True + # Calculated PC_RtTq99: <<: *real @@ -581,6 +615,46 @@ FilterParameters: <<: *real dimension: (99) description: Second order filter - Previous output 1 + lpfV_a2: + <<: *real + dimension: (99) + description: Second order filter - Denominator coefficient 1 + lpfV_a1: + <<: *real + dimension: (99) + description: Second order filter - Denominator coefficient 1 + lpfV_a0: + <<: *real + dimension: (99) + description: Second order filter - Denominator coefficient 0 + lpfV_b2: + <<: *real + dimension: (99) + description: Second order filter - Numerator coefficient 2 + lpfV_b1: + <<: *real + dimension: (99) + description: Second order filter - Numerator coefficient 1 + lpfV_b0: + <<: *real + dimension: (99) + description: Second order filter - Numerator coefficient 0 + lpfV_InputSignalLast2: + <<: *real + dimension: (99) + description: Second order filter - Previous input 2 + lpfV_OutputSignalLast2: + <<: *real + dimension: (99) + description: Second order filter - Previous output 2 + lpfV_InputSignalLast1: + <<: *real + dimension: (99) + description: Second order filter - Previous input 1 + lpfV_OutputSignalLast1: + <<: *real + dimension: (99) + description: Second order filter - Previous output 1 hpf_InputSignalLast: <<: *real dimension: (99) @@ -902,6 +976,72 @@ LocalVariables: <<: *real FA_AccF: <<: *real + PtfmTDX: + <<: *real + description: Platform motion -- Displacement TDX (m)') + PtfmTDY: + <<: *real + description: Platform motion -- Displacement TDY (m)') + PtfmTDZ: + <<: *real + description: Platform motion -- Displacement TDZ (m)') + PtfmRDX: + <<: *real + description: Platform motion -- Displacement RDX (rad)') + PtfmRDY: + <<: *real + description: Platform motion -- Displacement RDY (rad)') + PtfmRDZ: + <<: *real + description: Platform motion -- Displacement RDZ (rad)') + PtfmTVX: + <<: *real + description: Platform motion -- Velocity TVX (m/s)') + PtfmTVY: + <<: *real + description: Platform motion -- Velocity TVY (m/s)') + PtfmTVZ: + <<: *real + description: Platform motion -- Velocity TVZ (m/s)') + PtfmRVX: + <<: *real + description: Platform motion -- Velocity RVX (rad/s)') + PtfmRVY: + <<: *real + description: Platform motion -- Velocity RVY (rad/s)') + PtfmRVZ: + <<: *real + description: Platform motion -- Velocity RVZ (rad/s)') + PtfmTAX: + <<: *real + description: Platform motion -- Acceleration TAX (m/s^2)') + PtfmTAY: + <<: *real + description: Platform motion -- Acceleration TAY (m/s^2)') + PtfmTAZ: + <<: *real + description: Platform motion -- Acceleration TAZ (m/s^2)') + PtfmRAX: + <<: *real + description: Platform motion -- Acceleration RAX (rad/s^2)') + PtfmRAY: + <<: *real + description: Platform motion -- Acceleration RAY (rad/s^2)') + PtfmRAZ: + <<: *real + description: Platform motion -- Acceleration RAZ (rad/s^2)') + CC_DesiredL: + <<: *real + size: 12 + CC_ActuatedL: + <<: *real + size: 12 + CC_ActuatedDL: + <<: *real + size: 12 + StC_Input: + <<: *real + size: 12 Flp_Angle: <<: *real description: Flap Angle (rad) @@ -945,6 +1085,9 @@ ObjectInstances: instSecLPF: <<: *integer description: Second order low-pass filter instance + instSecLPFV: + <<: *integer + description: Second order low-pass filter instance instHPF: <<: *integer description: High-pass filter instance diff --git a/ROSCO/rosco_registry/write_registry.py b/ROSCO/rosco_registry/write_registry.py index 09c855b3..83c9211c 100644 --- a/ROSCO/rosco_registry/write_registry.py +++ b/ROSCO/rosco_registry/write_registry.py @@ -163,7 +163,7 @@ def write_roscoio(yfile): file.write(' Close ( Un )\n') file.write(' ENDIF\n') file.write(' ! Read Parameter files\n') - file.write(' CALL ReadControlParameterFileSub(CntrPar, zmqVar, LocalVar%ACC_INFILE, LocalVar%ACC_INFILE_SIZE, ErrVar)\n') + file.write(' CALL ReadControlParameterFileSub(CntrPar, zmqVar, LocalVar%ACC_INFILE, LocalVar%ACC_INFILE_SIZE, RootName, ErrVar)\n') file.write(' IF (CntrPar%WE_Mode > 0) THEN\n') file.write(' CALL READCpFile(CntrPar, PerfData, ErrVar)\n') file.write(' ENDIF\n') @@ -191,6 +191,13 @@ def write_roscoio(yfile): file.write(' CHARACTER(size_avcOUTNAME-1), INTENT(IN) :: RootName ! a Fortran version of the input C string (not considered an array here) [subtract 1 for the C null-character]\n') file.write(' CHARACTER(200) :: Version ! git version of ROSCO\n') file.write(' CHARACTER(15), ALLOCATABLE :: DebugOutStrings(:), DebugOutUnits(:)\n') + file.write('\n') + file.write(' ! Avr output writing\n') + file.write(' INTEGER(IntKi), SAVE, DIMENSION(:), ALLOCATABLE :: avrIndices\n') + file.write(' INTEGER(IntKi) :: avrBaseLength = 85\n') + file.write(' INTEGER(IntKi) :: Ind\n') + file.write(' CHARACTER(100) :: avrFmt\n') + file.write('\n') file.write(' REAL(DbKi), ALLOCATABLE :: DebugOutData(:)\n \n') file.write(' CHARACTER(15), ALLOCATABLE :: LocalVarOutStrings(:)\n') file.write(' REAL(DbKi), ALLOCATABLE :: LocalVarOutData(:)\n \n') @@ -242,8 +249,11 @@ def write_roscoio(yfile): file.write(' nLocalVars = {}\n'.format(len(lv_strings))) file.write(' Allocate(LocalVarOutData(nLocalVars))\n') file.write(' Allocate(LocalVarOutStrings(nLocalVars))\n') + + # Loop through LocalVariables for lv_idx, localvar in enumerate(lv_strings): - if reg['LocalVariables'][localvar]['size'] > 0: + # If an array, only show first + if reg['LocalVariables'][localvar]['size'] > 0 or reg['LocalVariables'][localvar]['allocatable']: file.write(' LocalVarOutData({}) = LocalVar%{}(1)\n'.format(lv_idx+1, localvar)) else: file.write(' LocalVarOutData({}) = LocalVar%{}\n'.format(lv_idx+1, localvar)) @@ -283,13 +293,39 @@ def write_roscoio(yfile): file.write("\n") # avrSWAP debug file.write(" IF (CntrPar%LoggingLevel > 2) THEN\n") + file.write(" ! Set avrIndices, start with basic indices\n") + file.write(" Allocate(avrIndices(avrBaseLength))\n") + file.write(" DO Ind = 1, avrBaseLength\n") + file.write(" avrIndices(Ind) = Ind\n") + file.write(" END DO\n") + file.write("\n") + file.write(" ! Cable control indices\n") + file.write(" IF (CntrPar%CC_Mode > 0) THEN\n") + file.write(" DO Ind = 1, SIZE(CntrPar%CC_GroupIndex)\n") + file.write(" Call AddToList(avrIndices,CntrPar%CC_GroupIndex(Ind))\n") + file.write(" Call AddToList(avrIndices,CntrPar%CC_GroupIndex(Ind)+1)\n") + file.write(" END DO\n") + file.write(" END IF\n") + file.write("\n") + file.write(" ! Structural control indices\n") + file.write(" IF (CntrPar%StC_Mode > 0) THEN\n") + file.write(" DO Ind = 1, SIZE(CntrPar%StC_GroupIndex)\n") + file.write(" Call AddToList(avrIndices,CntrPar%StC_GroupIndex(Ind))\n") + file.write(" END DO\n") + file.write(" END IF\n") + file.write("\n") + file.write(" ! Format string\n") + file.write(" avrFmt = '(A21,'//TRIM(Int2LStr(SIZE(avrIndices)))//'(TR12," + '"' + "'//'" + "AvrSWAP(" + '",I4,"' + ')"' + "))'\n") + # file.write(" WRITE(UnDb3,'"+'(A,85("'+"'//Tab//'"+'AvrSWAP("'+',I2,")"'+"))') 'LocalVar%Time ', (i,i=1, 85)\n") + file.write("\n") file.write(" CALL GetNewUnit(UnDb3, ErrVar)\n") file.write(" OPEN(unit=UnDb3, FILE=TRIM(RootName)//'.RO.dbg3')\n") file.write(" WRITE(UnDb3,'(/////)')\n") - file.write(" WRITE(UnDb3,'"+'(A,85("'+"'//Tab//'"+'AvrSWAP("'+',I2,")"'+"))') 'LocalVar%Time ', (i,i=1, 85)\n") - file.write(" WRITE(UnDb3,'"+'(A,85("'+"'//Tab//'"+'(-)"'+"))') '(s)'"+'\n') + file.write(" WRITE(UnDb3,avrFmt) 'LocalVar%Time ', (avrIndices)\n") + file.write(" WRITE(UnDb3,'(A21,'//TRIM(Int2LStr(SIZE(avrIndices)))//'(TR22," + '"(-)"' + "))') '(s)'\n") file.write(" END IF\n") file.write(" END IF\n") + file.write("\n") file.write(" ! Print simulation status, every 10 seconds\n") file.write(" IF (MODULO(LocalVar%Time, 10.0_DbKi) == 0) THEN\n") file.write(" WRITE(*, 100) LocalVar%GenSpeedF*RPS2RPM, LocalVar%BlPitch(1)*R2D, avrSWAP(15)/1000.0, LocalVar%WE_Vw\n") @@ -320,7 +356,7 @@ def write_roscoio(yfile): file.write(" END IF\n") file.write("\n") file.write(" IF(CntrPar%LoggingLevel > 2) THEN\n") - file.write(" WRITE (UnDb3, FmtDat) LocalVar%Time, avrSWAP(1: 85)\n") + file.write(" WRITE (UnDb3, FmtDat) LocalVar%Time, avrSWAP(avrIndices)\n") file.write(" END IF\n") file.write("\n") file.write("END SUBROUTINE Debug\n") diff --git a/ROSCO/src/Constants.f90 b/ROSCO/src/Constants.f90 index 0da3ac94..7f519985 100644 --- a/ROSCO/src/Constants.f90 +++ b/ROSCO/src/Constants.f90 @@ -35,4 +35,6 @@ MODULE Constants INTEGER(IntKi), PARAMETER :: ErrID_Fatal = 4 !< ErrStat parameter indicating "fatal error"; simulation should end INTEGER, PARAMETER :: BITS_IN_ADDR = C_INTPTR_T*8 !< The number of bits in an address (32-bit or 64-bit). + CHARACTER(1), PARAMETER :: Tab = CHAR( 9 ) + END MODULE Constants diff --git a/ROSCO/src/ControllerBlocks.f90 b/ROSCO/src/ControllerBlocks.f90 index 3e453052..390be8d0 100644 --- a/ROSCO/src/ControllerBlocks.f90 +++ b/ROSCO/src/ControllerBlocks.f90 @@ -201,7 +201,7 @@ SUBROUTINE WindSpeedEstimator(LocalVar, CntrPar, objInst, PerfData, DebugVar, Er ! Saturate inputs to WSE IF (LocalVar%RotSpeedF < 0.25 * CntrPar%VS_MinOMSpd / CntrPar%WE_GearboxRatio) THEN - WE_Inp_Speed = 0.25 * CntrPar%VS_MinOMSpd / CntrPar%WE_GearboxRatio + WE_Inp_Speed = 0.25 * CntrPar%VS_MinOMSpd / CntrPar%WE_GearboxRatio + EPSILON(1.0_DbKi) ! If this is 0, could cause problems... ELSE WE_Inp_Speed = LocalVar%RotSpeedF END IF diff --git a/ROSCO/src/Controllers.f90 b/ROSCO/src/Controllers.f90 index fd7a15f4..da8966fc 100644 --- a/ROSCO/src/Controllers.f90 +++ b/ROSCO/src/Controllers.f90 @@ -601,4 +601,108 @@ SUBROUTINE FlapControl(avrSWAP, CntrPar, LocalVar, objInst) RETURN ENDIF END SUBROUTINE FlapControl + +!------------------------------------------------------------------------------------------------------------------------------- + SUBROUTINE CableControl(avrSWAP, CntrPar, LocalVar, objInst) + ! Cable controller + ! CC_Mode = 0, No cable control, this code not executed + ! CC_Mode = 1, User-defined cable control + ! CC_Mode = 2, Position control, not yet implemented + ! + ! Note that LocalVar%CC_Actuated*(), and CC_Desired() has a fixed max size of 12, which can be increased in rosco_types.yaml + ! + USE ROSCO_Types, ONLY : ControlParameters, LocalVariables, ObjectInstances + + REAL(ReKi), INTENT(INOUT) :: avrSWAP(*) ! The swap array, used to pass data to, and receive data from, the DLL controller. + + TYPE(ControlParameters), INTENT(INOUT) :: CntrPar + TYPE(LocalVariables), INTENT(INOUT) :: LocalVar + TYPE(ObjectInstances), INTENT(INOUT) :: objInst + + ! Internal Variables + Integer(IntKi) :: I_GROUP + + + IF (CntrPar%CC_Mode == 1) THEN + ! User defined control + + IF (LocalVar%Time > 50) THEN + ! Shorten first group by 4 m + LocalVar%CC_DesiredL(1) = -10 + + + END IF + + + + END IF + + ! Convert desired to actuated line length and delta length for all groups + + DO I_GROUP = 1, CntrPar%CC_Group_N + + ! Get Actuated deltaL + LocalVar%CC_ActuatedDL(I_GROUP) = SecLPFilter_Vel(LocalVar%CC_DesiredL(I_GROUP),LocalVar%DT,2*PI/CntrPar%CC_ActTau,1.0, & + LocalVar%FP,LocalVar%iStatus,LocalVar%restart,objInst%instSecLPFV) + + ! Integrate + LocalVar%CC_ActuatedL(I_GROUP) = PIController(LocalVar%CC_ActuatedDL(I_GROUP),0.0_DbKi,1.0_DbKi, & + -1000.0_DbKi,1000.0_DbKi,LocalVar%DT,LocalVar%CC_ActuatedDL(1), & + LocalVar%piP, LocalVar%restart, objInst%instPI) + + END DO + + ! Assign to avrSWAP + DO I_GROUP = 1, CntrPar%CC_Group_N + + avrSWAP(CntrPar%CC_GroupIndex(I_GROUP)) = LocalVar%CC_ActuatedL(I_GROUP) + avrSWAP(CntrPar%CC_GroupIndex(I_GROUP)+1) = LocalVar%CC_ActuatedDL(I_GROUP) + + END DO + + END SUBROUTINE CableControl + +!------------------------------------------------------------------------------------------------------------------------------- +SUBROUTINE StructuralControl(avrSWAP, CntrPar, LocalVar, objInst) + ! Cable controller + ! StC_Mode = 0, No cable control, this code not executed + ! StC_Mode = 1, User-defined cable control + ! StC_Mode = 2, Ballast-like control, not yet implemented + ! + ! Note that LocalVar%StC_Input() has a fixed max size of 12, which can be increased in rosco_types.yaml + ! + USE ROSCO_Types, ONLY : ControlParameters, LocalVariables, ObjectInstances + + REAL(ReKi), INTENT(INOUT) :: avrSWAP(*) ! The swap array, used to pass data to, and receive data from, the DLL controller. + + TYPE(ControlParameters), INTENT(INOUT) :: CntrPar + TYPE(LocalVariables), INTENT(INOUT) :: LocalVar + TYPE(ObjectInstances), INTENT(INOUT) :: objInst + + ! Internal Variables + Integer(IntKi) :: I_GROUP + + + IF (CntrPar%StC_Mode == 1) THEN + ! User defined control + + IF (LocalVar%Time > 50) THEN + ! Step change in input of -4500 N + LocalVar%StC_Input(1) = -4e5 + + + END IF + + + + END IF + + + ! Assign to avrSWAP + DO I_GROUP = 1, CntrPar%StC_Group_N + avrSWAP(CntrPar%StC_GroupIndex(I_GROUP)) = LocalVar%StC_Input(I_GROUP) + END DO + + END SUBROUTINE StructuralControl +!------------------------------------------------------------------------------------------------------------------------------- END MODULE Controllers diff --git a/ROSCO/src/DISCON.F90 b/ROSCO/src/DISCON.F90 index e27b06b8..9482ca51 100644 --- a/ROSCO/src/DISCON.F90 +++ b/ROSCO/src/DISCON.F90 @@ -82,10 +82,10 @@ SUBROUTINE DISCON(avrSWAP, aviFAIL, accINFILE, avcOUTNAME, avcMSG) BIND (C, NAME CALL ReadAvrSWAP(avrSWAP, LocalVar, CntrPar) ! Set Control Parameters -CALL SetParameters(avrSWAP, accINFILE, SIZE(avcMSG), CntrPar, LocalVar, objInst, PerfData, zmqVar, ErrVar) +CALL SetParameters(avrSWAP, accINFILE, SIZE(avcMSG), CntrPar, LocalVar, objInst, PerfData, zmqVar, RootName, ErrVar) ! Call external controller, if desired -IF (CntrPar%Ext_Mode > 0) THEN +IF (CntrPar%Ext_Mode > 0 .AND. ErrVar%aviFAIL >= 0) THEN CALL ExtController(avrSWAP, CntrPar, LocalVar, ExtDLL, ErrVar) ! Data from external dll is in ExtDLL%avrSWAP, it's unused in the following code END IF @@ -116,6 +116,16 @@ SUBROUTINE DISCON(avrSWAP, aviFAIL, accINFILE, avcOUTNAME, avcMSG) BIND (C, NAME IF (CntrPar%Flp_Mode > 0) THEN CALL FlapControl(avrSWAP, CntrPar, LocalVar, objInst) END IF + + ! Cable control + IF (CntrPar%CC_Mode > 0) THEN + CALL CableControl(avrSWAP,CntrPar,LocalVar, objInst) + END IF + + ! Structural control + IF (CntrPar%StC_Mode > 0) THEN + CALL StructuralControl(avrSWAP,CntrPar,LocalVar, objInst) + END IF IF ( CntrPar%LoggingLevel > 0 ) THEN CALL Debug(LocalVar, CntrPar, DebugVar, ErrVar, avrSWAP, RootName, SIZE(avcOUTNAME)) diff --git a/ROSCO/src/Filters.f90 b/ROSCO/src/Filters.f90 index a108dfda..2a5ee24b 100644 --- a/ROSCO/src/Filters.f90 +++ b/ROSCO/src/Filters.f90 @@ -119,6 +119,58 @@ REAL(DbKi) FUNCTION SecLPFilter(InputSignal, DT, CornerFreq, Damp, FP, iStatus, inst = inst + 1 END FUNCTION SecLPFilter + +!------------------------------------------------------------------------------------------------------------------------------- + REAL(DbKi) FUNCTION SecLPFilter_Vel(InputSignal, DT, CornerFreq, Damp, FP, iStatus, reset, inst, InitialValue) + ! Discrete time Low-Pass Filter (output is velocity) of the form: + ! Continuous Time Form: H(s) = s CornerFreq^2/(s^2 + 2*CornerFreq*Damp*s + CornerFreq^2) + ! Discrete Time From: H(z) = (b2*z^2 + b1*z + b0) / (a2*z^2 + a1*z + a0) + USE ROSCO_Types, ONLY : FilterParameters + TYPE(FilterParameters), INTENT(INOUT) :: FP + REAL(DbKi), INTENT(IN) :: InputSignal + REAL(DbKi), INTENT(IN) :: DT ! time step [s] + REAL(DbKi), INTENT(IN) :: CornerFreq ! corner frequency [rad/s] + REAL(DbKi), INTENT(IN) :: Damp ! Dampening constant + INTEGER(IntKi), INTENT(IN) :: iStatus ! A status flag set by the simulation as follows: 0 if this is the first call, 1 for all subsequent time steps, -1 if this is the final call at the end of the simulation. + INTEGER(IntKi), INTENT(INOUT) :: inst ! Instance number. Every instance of this function needs to have an unique instance number to ensure instances don't influence each other. + LOGICAL(4), INTENT(IN) :: reset ! Reset the filter to the input signal + REAL(DbKi), OPTIONAL, INTENT(IN) :: InitialValue ! Value to set when reset + + REAL(DbKi) :: InitialValue_ ! Value to set when reset + + ! Defaults + InitialValue_ = InputSignal + IF (PRESENT(InitialValue)) InitialValue_ = InitialValue + + ! Initialization + IF ((iStatus == 0) .OR. reset ) THEN + FP%lpfV_OutputSignalLast1(inst) = InitialValue_ + FP%lpfV_OutputSignalLast2(inst) = InitialValue_ + FP%lpfV_InputSignalLast1(inst) = InitialValue_ + FP%lpfV_InputSignalLast2(inst) = InitialValue_ + + ! Coefficients + FP%lpfV_a2(inst) = DT**2.0*CornerFreq**2.0 + 4.0 + 4.0*Damp*CornerFreq*DT + FP%lpfV_a1(inst) = 2.0*DT**2.0*CornerFreq**2.0 - 8.0 + FP%lpfV_a0(inst) = DT**2.0*CornerFreq**2.0 + 4.0 - 4.0*Damp*CornerFreq*DT + FP%lpfV_b2(inst) = 2.0*DT*CornerFreq**2.0 + FP%lpfV_b1(inst) = 0.0 + FP%lpfV_b0(inst) = -2.0*DT*CornerFreq**2.0 + ENDIF + + ! Filter + SecLPFilter_Vel = 1.0/FP%lpfV_a2(inst) * (FP%lpfV_b2(inst)*InputSignal + FP%lpfV_b1(inst)*FP%lpfV_InputSignalLast1(inst) + FP%lpfV_b0(inst)*FP%lpfV_InputSignalLast2(inst) - FP%lpfV_a1(inst)*FP%lpfV_OutputSignalLast1(inst) - FP%lpfV_a0(inst)*FP%lpfV_OutputSignalLast2(inst)) + + ! Save signals for next time step + FP%lpfV_InputSignalLast2(inst) = FP%lpfV_InputSignalLast1(inst) + FP%lpfV_InputSignalLast1(inst) = InputSignal + FP%lpfV_OutputSignalLast2(inst) = FP%lpfV_OutputSignalLast1(inst) + FP%lpfV_OutputSignalLast1(inst) = SecLPFilter_Vel + + inst = inst + 1 + + END FUNCTION SecLPFilter_Vel + !------------------------------------------------------------------------------------------------------------------------------- REAL(DbKi) FUNCTION HPFilter( InputSignal, DT, CornerFreq, FP, iStatus, reset, inst, InitialValue) ! Discrete time High-Pass Filter @@ -316,7 +368,11 @@ SUBROUTINE PreFilterMeasuredSignals(CntrPar, LocalVar, DebugVar, objInst, ErrVar LocalVar%FA_AccF = NotchFilter(LocalVar%FA_AccF, LocalVar%DT, CntrPar%F_NotchCornerFreq, CntrPar%F_NotchBetaNumDen(1), CntrPar%F_NotchBetaNumDen(2), LocalVar%FP, LocalVar%iStatus, LocalVar%restart, objInst%instNotch) ! Fixed Damping ENDIF ENDIF - LocalVar%FA_AccHPF = HPFilter(LocalVar%FA_Acc, LocalVar%DT, CntrPar%FA_HPFCornerFreq, LocalVar%FP, LocalVar%iStatus, LocalVar%restart, objInst%instHPF) + + ! FA acc for ForeAft damping, condition matches whether it's used in Controllers.f90 + IF ((CntrPar%TD_Mode > 0) .OR. (CntrPar%Y_ControlMode == 2)) THEN + LocalVar%FA_AccHPF = HPFilter(LocalVar%FA_Acc, LocalVar%DT, CntrPar%FA_HPFCornerFreq, LocalVar%FP, LocalVar%iStatus, LocalVar%restart, objInst%instHPF) + ENDIF ! Filter Wind Speed Estimator Signal LocalVar%We_Vw_F = LPFilter(LocalVar%WE_Vw, LocalVar%DT,CntrPar%F_WECornerFreq, LocalVar%FP, LocalVar%iStatus, LocalVar%restart, objInst%instLPF) ! 30 second time constant diff --git a/ROSCO/src/Functions.f90 b/ROSCO/src/Functions.f90 index 3e0e225e..4f4a936e 100644 --- a/ROSCO/src/Functions.f90 +++ b/ROSCO/src/Functions.f90 @@ -600,69 +600,4 @@ END FUNCTION sigma -!------------------------------------------------------------------------------------------------------------------------------- - ! Copied from NWTC_IO.f90 -!> This function returns a character string encoded with today's date in the form dd-mmm-ccyy. -FUNCTION CurDate( ) - - ! Function declaration. - - CHARACTER(11) :: CurDate !< 'dd-mmm-yyyy' string with the current date - - - ! Local declarations. - - CHARACTER(8) :: CDate ! String to hold the returned value from the DATE_AND_TIME subroutine call. - - - - ! Call the system date function. - - CALL DATE_AND_TIME ( CDate ) - - - ! Parse out the day. - - CurDate(1:3) = CDate(7:8)//'-' - - - ! Parse out the month. - - SELECT CASE ( CDate(5:6) ) - CASE ( '01' ) - CurDate(4:6) = 'Jan' - CASE ( '02' ) - CurDate(4:6) = 'Feb' - CASE ( '03' ) - CurDate(4:6) = 'Mar' - CASE ( '04' ) - CurDate(4:6) = 'Apr' - CASE ( '05' ) - CurDate(4:6) = 'May' - CASE ( '06' ) - CurDate(4:6) = 'Jun' - CASE ( '07' ) - CurDate(4:6) = 'Jul' - CASE ( '08' ) - CurDate(4:6) = 'Aug' - CASE ( '09' ) - CurDate(4:6) = 'Sep' - CASE ( '10' ) - CurDate(4:6) = 'Oct' - CASE ( '11' ) - CurDate(4:6) = 'Nov' - CASE ( '12' ) - CurDate(4:6) = 'Dec' - END SELECT - - - ! Parse out the year. - - CurDate(7:11) = '-'//CDate(1:4) - - - RETURN - END FUNCTION CurDate - - END MODULE Functions diff --git a/ROSCO/src/ROSCO_Helpers.f90 b/ROSCO/src/ROSCO_Helpers.f90 index c030cc84..a10a1b72 100644 --- a/ROSCO/src/ROSCO_Helpers.f90 +++ b/ROSCO/src/ROSCO_Helpers.f90 @@ -28,14 +28,22 @@ MODULE ROSCO_Helpers MODULE PROCEDURE ParseInput_Str ! Parses a character string from a string. MODULE PROCEDURE ParseInput_Dbl ! Parses a double-precision REAL from a string. MODULE PROCEDURE ParseInput_Int ! Parses an INTEGER from a string. + MODULE PROCEDURE ParseInput_Int_Opt ! Parses an INTEGER from a string. Optional input. + MODULE PROCEDURE ParseInput_Dbl_Opt ! Parses an double-precision REAL from a string. Optional input. + MODULE PROCEDURE ParseInput_Str_Opt ! Parses an character string from a string. Optional input. ! MODULE PROCEDURE ParseInput_Log ! Parses an LOGICAL from a string. END INTERFACE - INTERFACE ParseAry ! Parse an array of numbers from a string. + INTERFACE ParseAry ! Parse an array of numbers from a string. MODULE PROCEDURE ParseDbAry ! Parse an array of double-precision REAL values. MODULE PROCEDURE ParseInAry ! Parse an array of whole numbers. + MODULE PROCEDURE ParseInAry_Opt ! Parse an array of whole numbers. Optional inputs. + MODULE PROCEDURE ParseDbAry_Opt ! Parse an array of double-precision REAL values. Optional inputs. END INTERFACE + INTEGER(IntKi), PARAMETER :: MaxLineLength = 2048 ! characters + INTEGER(IntKi), PARAMETER :: MaxParamLength = 200 ! characters, file paths can be long + CONTAINS !======================================================================= @@ -43,13 +51,13 @@ MODULE ROSCO_Helpers subroutine ParseInput_Int(Un, CurLine, VarName, FileName, Variable, ErrVar, CheckName) USE ROSCO_Types, ONLY : ErrorVariables - CHARACTER(1024) :: Line + CHARACTER(MaxLineLength) :: Line INTEGER(IntKi), INTENT(IN ) :: Un ! Input file unit - CHARACTER(*), INTENT(IN ) :: VarName ! Input file unit - CHARACTER(*), INTENT(IN ) :: FileName ! Input file unit + CHARACTER(*), INTENT(IN ) :: VarName ! Input file unit + CHARACTER(*), INTENT(IN ) :: FileName ! Input file unit INTEGER(IntKi), INTENT(INOUT) :: CurLine ! Current line of input - TYPE(ErrorVariables), INTENT(INOUT) :: ErrVar ! Current line of input - CHARACTER(20) :: Words (2) ! The two "words" parsed from the line + TYPE(ErrorVariables), INTENT(INOUT) :: ErrVar ! Current line of input + CHARACTER(MaxParamLength) :: Words (2) ! The two "words" parsed from the line INTEGER(IntKi), INTENT(INOUT) :: Variable ! Variable INTEGER(IntKi) :: ErrStatLcl ! Error status local to this routine. @@ -102,6 +110,250 @@ subroutine ParseInput_Int(Un, CurLine, VarName, FileName, Variable, ErrVar, Chec END subroutine ParseInput_Int + !======================================================================= + ! Parse integer input: read line, check that variable name is in line, handle errors + subroutine ParseInput_Int_Opt(FileLines, VarName, Variable, FileName, ErrVar, AllowDefault, UnEc) + USE ROSCO_Types, ONLY : ErrorVariables + + CHARACTER(*), INTENT(IN ), DIMENSION(:) :: FileLines ! Input file unit + CHARACTER(*), INTENT(IN ) :: VarName ! Input file unit + CHARACTER(*), INTENT(IN ) :: FileName ! Input file unit + TYPE(ErrorVariables), INTENT(INOUT) :: ErrVar ! Current line of input + INTEGER(IntKi), INTENT(INOUT) :: Variable ! Variable + Integer(IntKi), OPTIONAL, INTENT(IN ) :: UnEc ! Variable + + + ! Flag (usually control mode) specifying whether default is allowed, 0 - yes, nonzero - no + LOGICAL, OPTIONAL, INTENT(IN ) :: AllowDefault + + INTEGER(IntKi) :: CurLine ! Current line of input + CHARACTER(MaxParamLength) :: Words (2) ! The two "words" parsed from the line + CHARACTER(MaxParamLength) :: VarNameUC + CHARACTER(MaxLineLength) :: Line + INTEGER(IntKi) :: ErrStatLcl ! Error status local to this routine. + INTEGER(IntKi) :: I, VarLineIndex ! Line indexer + LOGICAL :: AllowDefault_, FoundLine + CHARACTER(*), PARAMETER :: RoutineName = 'ParseInput_Int_Opt' + + + ! Figure out if we allow default + AllowDefault_ = .TRUE. + if (PRESENT(AllowDefault)) AllowDefault_ = AllowDefault + + ! If we've already failed, don't read anything + IF (ErrVar%aviFAIL >= 0) THEN + + CALL FindLine(FileLines, VarName, FoundLine, Line, CurLine) + + ! Separate line again + CALL GetWords ( Line, Words, 2 ) + + ! PRINT *, "Line: ", Line + + ! Print warning with default + IF (.NOT. FoundLine) THEN + IF (.NOT. AllowDefault_) THEN + ErrVar%aviFAIL = -1 + ErrVar%ErrMsg = RoutineName//':Missing or default values are not allowed for '//TRIM( VarName )//'. Please check control modes.' + RETURN + ENDIF + + Variable = 0 ! Default of integer inputs is 0 for now + PRINT *, "Did not find "//TRIM( VarName )//" in input file. Using default value of ", Variable + ENDIF + + ! Debugging: show what's being read, turn into Echo later + IF (DEBUG_PARSING) THEN + print *, 'Read: '//TRIM(Words(1))//' and '//TRIM(Words(2)),' on line ', CurLine + END IF + + ! IF We haven't failed already + IF (ErrVar%aviFAIL >= 0 .AND. FoundLine) THEN + + ! Read the variable + READ (Words(1),*,IOSTAT=ErrStatLcl) Variable + IF ( ErrStatLcl /= 0 ) THEN + ErrVar%aviFAIL = -1 + ErrVar%ErrMsg = NewLine//' >> A fatal error occurred when parsing data from "' & + //TRIM( FileName )//'".'//NewLine// & + ' >> The variable "'//TRIM( Words(2) )//'" was not assigned valid INTEGER value on line #' & + //TRIM( Int2LStr( CurLine ) )//'.'//NewLine//& + ' >> The text being parsed was :'//NewLine//' "'//TRIM( Line )//'"' + ENDIF + + ENDIF + + IF ( PRESENT(UnEc)) THEN + IF ( UnEc > 0 ) WRITE (UnEc,*) CurLine, Tab, VarName, Tab, Variable + END IF + + END IF + + END subroutine ParseInput_Int_Opt + + !======================================================================= + ! Parse integer input: read line, check that variable name is in line, handle errors + subroutine ParseInput_Dbl_Opt(FileLines, VarName, Variable, FileName, ErrVar, AllowDefault, UnEc) + USE ROSCO_Types, ONLY : ErrorVariables + + CHARACTER(*), INTENT(IN ), DIMENSION(:) :: FileLines ! Input file unit + CHARACTER(*), INTENT(IN ) :: VarName ! Input file unit + CHARACTER(*), INTENT(IN ) :: FileName ! Input file unit + TYPE(ErrorVariables), INTENT(INOUT) :: ErrVar ! Current line of input + REAL(DbKi), INTENT(INOUT) :: Variable ! Variable + Integer(IntKi), OPTIONAL, INTENT(IN ) :: UnEc ! Variable + + + ! Flag (usually control mode) specifying whether default is allowed, 0 - yes, nonzero - no + LOGICAL, OPTIONAL, INTENT(IN ) :: AllowDefault + + INTEGER(IntKi) :: CurLine ! Current line of input + CHARACTER(MaxParamLength) :: Words (2) ! The two "words" parsed from the line + CHARACTER(MaxParamLength) :: VarNameUC + CHARACTER(MaxLineLength) :: Line + INTEGER(IntKi) :: ErrStatLcl ! Error status local to this routine. + INTEGER(IntKi) :: I, VarLineIndex ! Line indexer + LOGICAL :: AllowDefault_, FoundLine + CHARACTER(*), PARAMETER :: RoutineName = 'ParseInput_Dbl_Opt' + + + ! Figure out if we allow default + AllowDefault_ = .TRUE. + if (PRESENT(AllowDefault)) AllowDefault_ = AllowDefault + + ! If we've already failed, don't read anything + IF (ErrVar%aviFAIL >= 0) THEN + + CALL FindLine(FileLines, VarName, FoundLine, Line, CurLine) + + + ! Separate line again + CALL GetWords ( Line, Words, 2 ) + + ! PRINT *, "Line: ", Line + + ! Print warning with default + IF (.NOT. FoundLine) THEN + IF (.NOT. AllowDefault_) THEN + ErrVar%aviFAIL = -1 + ErrVar%ErrMsg = RoutineName//':Missing or default values are not allowed for '//TRIM( VarName )//'. Please check control modes.' + RETURN + ENDIF + + Variable = 0 ! Default of integer inputs is 0 for now + PRINT *, "Did not find "//TRIM( VarName )//" in input file. Using default value of ", Variable + ENDIF + + ! Debugging: show what's being read, turn into Echo later + IF (DEBUG_PARSING) THEN + print *, 'Read: '//TRIM(Words(1))//' and '//TRIM(Words(2)),' on line ', CurLine + END IF + + ! IF We haven't failed already + IF (ErrVar%aviFAIL >= 0 .AND. FoundLine) THEN + + ! Read the variable + READ (Words(1),*,IOSTAT=ErrStatLcl) Variable + IF ( ErrStatLcl /= 0 ) THEN + ErrVar%aviFAIL = -1 + ErrVar%ErrMsg = NewLine//' >> A fatal error occurred when parsing data from "' & + //TRIM( FileName )//'".'//NewLine// & + ' >> The variable "'//TRIM( Words(2) )//'" was not assigned valid INTEGER value on line #' & + //TRIM( Int2LStr( CurLine ) )//'.'//NewLine//& + ' >> The text being parsed was :'//NewLine//' "'//TRIM( Line )//'"' + ENDIF + + ENDIF + + IF ( PRESENT(UnEc)) THEN + IF ( UnEc > 0 ) WRITE (UnEc,*) CurLine, Tab, VarName, Tab, Variable + END IF + + END IF + + END subroutine ParseInput_Dbl_Opt + + !======================================================================= + ! Parse integer input: read line, check that variable name is in line, handle errors + subroutine ParseInput_Str_Opt(FileLines, VarName, Variable, FileName, ErrVar, AllowDefault, UnEc) + USE ROSCO_Types, ONLY : ErrorVariables + + CHARACTER(*), INTENT(IN ), DIMENSION(:) :: FileLines ! Input file unit + CHARACTER(*), INTENT(IN ) :: VarName ! Input file unit + CHARACTER(*), INTENT(IN ) :: FileName ! Input file unit + TYPE(ErrorVariables), INTENT(INOUT) :: ErrVar ! Current line of input + CHARACTER(*), INTENT(INOUT) :: Variable ! Variable + Integer(IntKi), OPTIONAL, INTENT(IN ) :: UnEc ! Variable + + ! Flag (usually control mode) specifying whether default is allowed, 0 - yes, nonzero - no + LOGICAL, OPTIONAL, INTENT(IN ) :: AllowDefault + + INTEGER(IntKi) :: CurLine ! Current line of input + CHARACTER(MaxParamLength) :: Words (2) ! The two "words" parsed from the line + CHARACTER(MaxParamLength) :: VarNameUC + CHARACTER(MaxLineLength) :: Line + INTEGER(IntKi) :: ErrStatLcl ! Error status local to this routine. + INTEGER(IntKi) :: I, VarLineIndex ! Line indexer + LOGICAL :: AllowDefault_, FoundLine + CHARACTER(*), PARAMETER :: RoutineName = 'ParseInput_Str_Opt' + + + ! Figure out if we allow default + AllowDefault_ = .TRUE. + if (PRESENT(AllowDefault)) AllowDefault_ = AllowDefault + + ! If we've already failed, don't read anything + IF (ErrVar%aviFAIL >= 0) THEN + + CALL FindLine(FileLines, VarName, FoundLine, Line, CurLine) + + + ! Separate line again + CALL GetWords ( Line, Words, 2 ) + + ! PRINT *, "Line: ", TRIM(Line) + + ! Print warning with default + IF (.NOT. FoundLine) THEN + IF (.NOT. AllowDefault_) THEN + ErrVar%aviFAIL = -1 + ErrVar%ErrMsg = RoutineName//':Missing or default values are not allowed for '//TRIM( VarName )//'. Please check control modes.' + RETURN + ENDIF + + Variable = 'unused' ! Default of string input is unused for now + PRINT *, "Did not find "//TRIM( VarName )//" in input file. Using default value of ", TRIM(Variable) + ENDIF + + ! Debugging: show what's being read, turn into Echo later + IF (DEBUG_PARSING) THEN + print *, 'Read: '//TRIM(Words(1))//' and '//TRIM(Words(2)),' on line ', CurLine + END IF + + IF (ErrVar%aviFAIL >= 0 .AND. FoundLine) THEN + + ! Read the variable + READ (Words(1),'(A)',IOSTAT=ErrStatLcl) Variable + IF ( ErrStatLcl /= 0 ) THEN + ErrVar%aviFAIL = -1 + ErrVar%ErrMsg = NewLine//' >> A fatal error occurred when parsing data from "' & + //TRIM( FileName )//'".'//NewLine// & + ' >> The variable "'//TRIM( Words(2) )//'" was not assigned valid INTEGER value on line #' & + //TRIM( Int2LStr( CurLine ) )//'.'//NewLine//& + ' >> The text being parsed was :'//NewLine//' "'//TRIM( Line )//'"' + ENDIF + + ENDIF + + IF ( PRESENT(UnEc)) THEN + IF ( UnEc > 0 ) WRITE (UnEc,*) CurLine, Tab, VarName, Tab, Variable + END IF + + END IF + + END subroutine ParseInput_Str_Opt + + !======================================================================= ! Parse double input, this is a copy of ParseInput_Int and a change in the variable definitions subroutine ParseInput_Dbl(Un, CurLine, VarName, FileName, Variable, ErrVar, CheckName) @@ -234,7 +486,7 @@ END subroutine ParseInput_Str !> This subroutine parses the specified line of text for AryLen REAL values. !! Generate an error message if the value is the wrong type. !! Use ParseAry (nwtc_io::parseary) instead of directly calling a specific routine in the generic interface. - SUBROUTINE ParseDbAry ( Un, LineNum, AryName, Ary, AryLen, FileName, ErrVar, CheckName ) + SUBROUTINE ParseDbAry ( Un, LineNum, ParamName, Ary, AryLen, FileName, ErrVar, CheckName ) USE ROSCO_Types, ONLY : ErrorVariables @@ -248,7 +500,7 @@ SUBROUTINE ParseDbAry ( Un, LineNum, AryName, Ary, AryLen, FileName, ErrVar, Che CHARACTER(*), INTENT(IN) :: FileName !< The name of the file being parsed. - CHARACTER(*), INTENT(IN ) :: AryName !< The array name we are trying to fill. + CHARACTER(*), INTENT(IN ) :: ParamName !< The array name we are trying to fill. TYPE(ErrorVariables), INTENT(INOUT) :: ErrVar ! Current line of input @@ -280,10 +532,10 @@ SUBROUTINE ParseDbAry ( Un, LineNum, AryName, Ary, AryLen, FileName, ErrVar, Che IF ( ErrStatLcl /= 0 ) THEN IF ( ALLOCATED(Ary) ) THEN ErrVar%aviFAIL = -1 - ErrVar%ErrMsg = RoutineName//':Error allocating memory for the '//TRIM( AryName )//' array; array was already allocated.' + ErrVar%ErrMsg = RoutineName//':Error allocating memory for the '//TRIM( ParamName )//' array; array was already allocated.' ELSE ErrVar%aviFAIL = -1 - ErrVar%ErrMsg = RoutineName//':Error allocating memory for '//TRIM(Int2LStr( AryLen ))//' characters in the '//TRIM( AryName )//' array.' + ErrVar%ErrMsg = RoutineName//':Error allocating memory for '//TRIM(Int2LStr( AryLen ))//' characters in the '//TRIM( ParamName )//' array.' END IF END IF @@ -313,7 +565,7 @@ SUBROUTINE ParseDbAry ( Un, LineNum, AryName, Ary, AryLen, FileName, ErrVar, Che ! Check that Variable Name is at the end of Words, will also check length of array IF (CheckName_) THEN - CALL ChkParseData ( Words_Ary(AryLen:AryLen+1), AryName, FileName, LineNum, ErrVar ) + CALL ChkParseData ( Words_Ary(AryLen:AryLen+1), ParamName, FileName, LineNum, ErrVar ) END IF ! Read array @@ -322,17 +574,13 @@ SUBROUTINE ParseDbAry ( Un, LineNum, AryName, Ary, AryLen, FileName, ErrVar, Che ErrVar%aviFAIL = -1 ErrVar%ErrMsg = RoutineName//':A fatal error occurred when parsing data from "' & //TRIM( FileName )//'".'//NewLine// & - ' >> The "'//TRIM( AryName )//'" array was not assigned valid REAL values on line #' & + ' >> The "'//TRIM( ParamName )//'" array was not assigned valid REAL values on line #' & //TRIM( Int2LStr( LineNum ) )//'.'//NewLine//' >> The text being parsed was :'//NewLine & //' "'//TRIM( Line )//'"' RETURN CALL Cleanup() ENDIF - ! IF ( PRESENT(UnEc) ) THEN - ! IF ( UnEc > 0 ) WRITE (UnEc,'(A)') TRIM( FileInfo%Lines(LineNum) ) - ! END IF - LineNum = LineNum + 1 CALL Cleanup() ENDIF @@ -361,7 +609,7 @@ END SUBROUTINE ParseDbAry !> This subroutine parses the specified line of text for AryLen INTEGER values. !! Generate an error message if the value is the wrong type. !! Use ParseAry (nwtc_io::parseary) instead of directly calling a specific routine in the generic interface. - SUBROUTINE ParseInAry ( Un, LineNum, AryName, Ary, AryLen, FileName, ErrVar, CheckName ) + SUBROUTINE ParseInAry ( Un, LineNum, ParamName, Ary, AryLen, FileName, ErrVar, CheckName ) USE ROSCO_Types, ONLY : ErrorVariables @@ -375,7 +623,7 @@ SUBROUTINE ParseInAry ( Un, LineNum, AryName, Ary, AryLen, FileName, ErrVar, Che CHARACTER(*), INTENT(IN) :: FileName !< The name of the file being parsed. - CHARACTER(*), INTENT(IN ) :: AryName !< The array name we are trying to fill. + CHARACTER(*), INTENT(IN ) :: ParamName !< The array name we are trying to fill. TYPE(ErrorVariables), INTENT(INOUT) :: ErrVar ! Current line of input @@ -407,10 +655,10 @@ SUBROUTINE ParseInAry ( Un, LineNum, AryName, Ary, AryLen, FileName, ErrVar, Che IF ( ErrStatLcl /= 0 ) THEN IF ( ALLOCATED(Ary) ) THEN ErrVar%aviFAIL = -1 - ErrVar%ErrMsg = RoutineName//':Error allocating memory for the '//TRIM( AryName )//' array; array was already allocated.' + ErrVar%ErrMsg = RoutineName//':Error allocating memory for the '//TRIM( ParamName )//' array; array was already allocated.' ELSE ErrVar%aviFAIL = -1 - ErrVar%ErrMsg = RoutineName//':Error allocating memory for '//TRIM(Int2LStr( AryLen ))//' characters in the '//TRIM( AryName )//' array.' + ErrVar%ErrMsg = RoutineName//':Error allocating memory for '//TRIM(Int2LStr( AryLen ))//' characters in the '//TRIM( ParamName )//' array.' END IF END IF @@ -440,7 +688,7 @@ SUBROUTINE ParseInAry ( Un, LineNum, AryName, Ary, AryLen, FileName, ErrVar, Che ! Check that Variable Name is at the end of Words, will also check length of array IF (CheckName_) THEN - CALL ChkParseData ( Words_Ary(AryLen:AryLen+1), AryName, FileName, LineNum, ErrVar ) + CALL ChkParseData ( Words_Ary(AryLen:AryLen+1), ParamName, FileName, LineNum, ErrVar ) END IF ! Read array @@ -449,7 +697,7 @@ SUBROUTINE ParseInAry ( Un, LineNum, AryName, Ary, AryLen, FileName, ErrVar, Che ErrVar%aviFAIL = -1 ErrVar%ErrMsg = RoutineName//':A fatal error occurred when parsing data from "' & //TRIM( FileName )//'".'//NewLine// & - ' >> The "'//TRIM( AryName )//'" array was not assigned valid REAL values on line #' & + ' >> The "'//TRIM( ParamName )//'" array was not assigned valid REAL values on line #' & //TRIM( Int2LStr( LineNum ) )//'.'//NewLine//' >> The text being parsed was :'//NewLine & //' "'//TRIM( Line )//'"' RETURN @@ -485,6 +733,289 @@ END SUBROUTINE Cleanup END SUBROUTINE ParseInAry !======================================================================= + +!======================================================================= +!> This subroutine parses the specified line of text for AryLen INTEGER values. +!! Generate an error message if the value is the wrong type. +!! Use ParseAry (nwtc_io::parseary) instead of directly calling a specific routine in the generic interface. + SUBROUTINE ParseInAry_Opt( FileLines, ParamName, Ary, AryLen, FileName, ErrVar, AllowDefault, UnEc ) + + USE ROSCO_Types, ONLY : ErrorVariables + + ! Arguments declarations. + CHARACTER(*), INTENT(IN ), DIMENSION(:) :: FileLines ! Input file unit + INTEGER, INTENT(IN ) :: AryLen !< The length of the array to parse. + INTEGER(IntKi), ALLOCATABLE, INTENT(INOUT) :: Ary(:) !< The array to receive the input values. + CHARACTER(*), INTENT(IN) :: FileName !< The name of the file being parsed. + CHARACTER(*), INTENT(IN) :: ParamName !< The array name we are trying to fill. + TYPE(ErrorVariables), INTENT(INOUT) :: ErrVar ! Current line of input + Integer(IntKi), OPTIONAL, INTENT(IN ) :: UnEc ! Variable + LOGICAL, OPTIONAL, INTENT(IN ) :: AllowDefault + + ! Local declarations. + INTEGER(IntKi) :: FinalAryLen !< Final array length, non-input + INTEGER(IntKi) :: LineNum !< The number of the line to parse. + CHARACTER(MaxLineLength) :: Line + INTEGER(IntKi) :: ErrStatLcl ! Error status local to this routine. + INTEGER(IntKi) :: i + + CHARACTER(MaxParamLength), ALLOCATABLE :: Words_Ary (:) ! The array "words" parsed from the line. + CHARACTER(MaxLineLength) :: Debug_String + CHARACTER(*), PARAMETER :: RoutineName = 'ParseInAry_Opt' + CHARACTER(MaxParamLength) :: ParamNameUC + LOGICAL :: AllowDefault_, FoundLine + + ! Figure out if we allow default + AllowDefault_ = .TRUE. + if (PRESENT(AllowDefault)) AllowDefault_ = AllowDefault + + ! If we've already failed, don't read anything + IF (ErrVar%aviFAIL >= 0) THEN + + CALL FindLine(FileLines, ParamName, FoundLine, Line, LineNum, AryLen) + + ! PRINT *, "Line: ", TRIM(Line) + + ! Minimum array length + IF (AryLen < 1) THEN + FinalAryLen = 1 + ELSE + FinalAryLen = AryLen + ENDIF + + ! Allocate array and handle errors + ALLOCATE ( Ary(FinalAryLen) , STAT=ErrStatLcl ) + IF ( ErrStatLcl /= 0 ) THEN + IF ( ALLOCATED(Ary) ) THEN + ErrVar%aviFAIL = -1 + ErrVar%ErrMsg = RoutineName//':Error allocating memory for the '//TRIM( ParamName )//' array; array was already allocated.' + ELSE + ErrVar%aviFAIL = -1 + ErrVar%ErrMsg = RoutineName//':Error allocating memory for '//TRIM(Int2LStr( AryLen ))//' characters in the '//TRIM( ParamName )//' array.' + END IF + END IF + + ! Print warning with default + IF (.NOT. FoundLine) THEN + IF (.NOT. AllowDefault_) THEN + ErrVar%aviFAIL = -1 + ErrVar%ErrMsg = RoutineName//':Missing or default values are not allowed for '//TRIM( ParamName )//'. Please check control modes and array length.' + RETURN + ENDIF + + Ary = 0 ! Default of allocatable arrays is 0 for now + PRINT *, "Did not find "//TRIM( ParamName )//" in input file. Using default value of [", Ary, "]" + ENDIF + + IF (FoundLine) THEN + + ! Allocate words array + ALLOCATE ( Words_Ary( AryLen + 1 ) , STAT=ErrStatLcl ) + IF ( ErrStatLcl /= 0 ) THEN + ErrVar%aviFAIL = -1 + ErrVar%ErrMsg = RoutineName//':Fatal error allocating memory for the Words array.' + CALL Cleanup() + RETURN + ENDIF + + ! Separate line string into AryLen + 1 words, should include variable name + CALL GetWords ( Line, Words_Ary, AryLen + 1 ) + + ! Debug Output + IF (DEBUG_PARSING) THEN + Debug_String = '' + DO i = 1,AryLen+1 + Debug_String = TRIM(Debug_String)//TRIM(Words_Ary(i)) + IF (i < AryLen + 1) THEN + Debug_String = TRIM(Debug_String)//',' + END IF + END DO + print *, 'Read: '//TRIM(Debug_String)//' on line ', LineNum + END IF + + ! Read array + READ (Line,*,IOSTAT=ErrStatLcl) Ary + IF ( ErrStatLcl /= 0 ) THEN + ErrVar%aviFAIL = -1 + ErrVar%ErrMsg = RoutineName//':A fatal error occurred when parsing data from "' & + //TRIM( FileName )//'".'//NewLine// & + ' >> The "'//TRIM( ParamName )//'" array was not assigned valid REAL values on line #' & + //TRIM( Int2LStr( LineNum ) )//'.'//NewLine//' >> The text being parsed was :'//NewLine & + //' "'//TRIM( Line )//'"' + RETURN + CALL Cleanup() + ENDIF + + ENDIF + + IF ( PRESENT(UnEc)) THEN + IF ( UnEc > 0 ) WRITE (UnEc,*) LineNum, Tab, ParamName, Tab, Ary + END IF + + CALL Cleanup() + ENDIF + + RETURN + + !======================================================================= + CONTAINS + !======================================================================= + SUBROUTINE Cleanup ( ) + + ! This subroutine cleans up the parent routine before exiting. + + ! Deallocate the Words array if it had been allocated. + + IF ( ALLOCATED( Words_Ary ) ) DEALLOCATE( Words_Ary ) + + + RETURN + + END SUBROUTINE Cleanup + +END SUBROUTINE ParseInAry_Opt + +!======================================================================= +!> This subroutine parses the specified line of text for AryLen INTEGER values. +!! Generate an error message if the value is the wrong type. +!! Use ParseAry (nwtc_io::parseary) instead of directly calling a specific routine in the generic interface. + SUBROUTINE ParseDbAry_Opt ( FileLines, ParamName, Ary, AryLen, FileName, ErrVar, AllowDefault, UnEc ) + + USE ROSCO_Types, ONLY : ErrorVariables + + ! Arguments declarations. + CHARACTER(*), INTENT(IN ), DIMENSION(:) :: FileLines ! Input file unit + INTEGER, INTENT(IN) :: AryLen !< The length of the array to parse. + REAL(DbKi), ALLOCATABLE, INTENT(INOUT) :: Ary(:) !< The array to receive the input values. + CHARACTER(*), INTENT(IN) :: FileName !< The name of the file being parsed. + CHARACTER(*), INTENT(IN) :: ParamName !< The array name we are trying to fill. + TYPE(ErrorVariables), INTENT(INOUT) :: ErrVar ! Current line of input + LOGICAL, OPTIONAL, INTENT(IN ) :: AllowDefault + Integer(IntKi), OPTIONAL, INTENT(IN ) :: UnEc ! Variable + + ! Local declarations. + INTEGER(IntKi) :: LineNum !< The number of the line to parse. + INTEGER(IntKi) :: FinalAryLen !< Final array length, non-input + CHARACTER(MaxLineLength) :: Line + INTEGER(IntKi) :: ErrStatLcl ! Error status local to this routine. + INTEGER(IntKi) :: i + + CHARACTER(MaxParamLength), ALLOCATABLE :: Words_Ary (:) ! The array "words" parsed from the line. + CHARACTER(MaxLineLength) :: Debug_String + CHARACTER(*), PARAMETER :: RoutineName = 'ParseDbAry_Opt' + CHARACTER(MaxParamLength) :: ParamNameUC, FileLineUC + LOGICAL :: AllowDefault_, FoundLine + + ! Figure out if we allow default + AllowDefault_ = .TRUE. + if (PRESENT(AllowDefault)) AllowDefault_ = AllowDefault + + ! If we've already failed, don't read anything + IF (ErrVar%aviFAIL >= 0) THEN + + CALL FindLine(FileLines, ParamName, FoundLine, Line, LineNum, AryLen) + + ! Minimum array length + IF (AryLen < 1) THEN + FinalAryLen = 1 + ELSE + FinalAryLen = AryLen + ENDIF + + ! Allocate array and handle errors + ALLOCATE ( Ary(FinalAryLen) , STAT=ErrStatLcl ) + IF ( ErrStatLcl /= 0 ) THEN + IF ( ALLOCATED(Ary) ) THEN + ErrVar%aviFAIL = -1 + ErrVar%ErrMsg = RoutineName//':Error allocating memory for the '//TRIM( ParamName )//' array; array was already allocated.' + ELSE + ErrVar%aviFAIL = -1 + ErrVar%ErrMsg = RoutineName//':Error allocating memory for '//TRIM(Int2LStr( AryLen ))//' characters in the '//TRIM( ParamName )//' array.' + END IF + END IF + + ! Print warning with default + IF (.NOT. FoundLine) THEN + IF (.NOT. AllowDefault_) THEN + ErrVar%aviFAIL = -1 + ErrVar%ErrMsg = RoutineName//':Missing or default values are not allowed for '//TRIM( ParamName )//'. Please check control modes and array length.' + RETURN + ENDIF + + Ary = 0 ! Default of allocatable arrays is 0 for now + PRINT *, "Did not find "//TRIM( ParamName )//" in input file. Using default value of [", Ary, "]" + ENDIF + + IF (FoundLine) THEN + + ! Allocate words array + ALLOCATE ( Words_Ary( AryLen + 1 ) , STAT=ErrStatLcl ) + IF ( ErrStatLcl /= 0 ) THEN + ErrVar%aviFAIL = -1 + ErrVar%ErrMsg = RoutineName//':Fatal error allocating memory for the Words array.' + CALL Cleanup() + RETURN + ENDIF + + ! Separate line string into AryLen + 1 words, should include variable name + CALL GetWords ( Line, Words_Ary, AryLen + 1 ) + + ! Debug Output + IF (DEBUG_PARSING) THEN + Debug_String = '' + DO i = 1,AryLen+1 + Debug_String = TRIM(Debug_String)//TRIM(Words_Ary(i)) + IF (i < AryLen + 1) THEN + Debug_String = TRIM(Debug_String)//',' + END IF + END DO + print *, 'Read: '//TRIM(Debug_String)//' on line ', LineNum + END IF + + ! Read array + READ (Line,*,IOSTAT=ErrStatLcl) Ary + IF ( ErrStatLcl /= 0 ) THEN + ErrVar%aviFAIL = -1 + ErrVar%ErrMsg = RoutineName//':A fatal error occurred when parsing data from "' & + //TRIM( FileName )//'".'//NewLine// & + ' >> The "'//TRIM( ParamName )//'" array was not assigned valid REAL values on line #' & + //TRIM( Int2LStr( LineNum ) )//'.'//NewLine//' >> The text being parsed was :'//NewLine & + //' "'//TRIM( Line )//'"' + RETURN + CALL Cleanup() + ENDIF + + ENDIF + + IF ( PRESENT(UnEc)) THEN + IF ( UnEc > 0 ) WRITE (UnEc,*) LineNum, Tab, ParamName, Tab, Ary + END IF + + CALL Cleanup() + ENDIF + + RETURN + + !======================================================================= + CONTAINS + !======================================================================= + SUBROUTINE Cleanup ( ) + + ! This subroutine cleans up the parent routine before exiting. + + ! Deallocate the Words array if it had been allocated. + + IF ( ALLOCATED( Words_Ary ) ) DEALLOCATE( Words_Ary ) + + + RETURN + + END SUBROUTINE Cleanup + +END SUBROUTINE ParseDbAry_Opt + +!======================================================================= + !> This subroutine checks the data to be parsed to make sure it finds !! the expected variable name and an associated value. SUBROUTINE ChkParseData ( Words, ExpVarName, FileName, FileLineNum, ErrVar ) @@ -546,6 +1077,57 @@ SUBROUTINE ChkParseData ( Words, ExpVarName, FileName, FileLineNum, ErrVar ) END SUBROUTINE ChkParseData +SUBROUTINE FindLine(FileLines, ParamName, FoundLine, Line, LineNum, AryLen) + CHARACTER(*), INTENT(IN ), DIMENSION(:) :: FileLines ! Input file unit + CHARACTER(*), INTENT(IN) :: ParamName !< The array name we are trying to fill. + INTEGER(IntKi), INTENT(OUT) :: LineNum !< The number of the line to parse. + LOGICAL, INTENT(OUT) :: FoundLine + INTEGER(IntKi), OPTIONAL, INTENT(IN ) :: AryLen + CHARACTER(MaxLineLength), INTENT(OUT) :: Line + + + CHARACTER(MaxParamLength), ALLOCATABLE :: Words(:) ! The two "words" parsed from the line + + CHARACTER(MaxParamLength) :: ParamNameUC, FileLineUC + INTEGER(IntKi) :: I, WordInd + + IF (.NOT. PRESENT(AryLen)) THEN + WordInd = 2 + ELSE + WordInd = AryLen + 1 + ENDIF + + ALLOCATE(Words(WordInd)) ! TODO: check error + + ! Make name uppercase + ParamNameUC = ParamName + CALL Conv2UC(ParamNameUC) + + ! Search for line in FileLines + FoundLine = .FALSE. + LineNum = 0 + DO I = 1,SIZE(FileLines) + + ! Separate line string into 2 words + CALL GetWords ( FileLines(I), Words, WordInd ) + + ! Make FileLines uppercase + FileLineUC = Words(WordInd) + CALL Conv2UC(FileLineUC) + + ! WRITE(500,*) Words + + ! PRINT *, TRIM(ParamNameUC), '==', TRIM(FileLineUC), '=', TRIM(FileLineUC)==TRIM(ParamNameUC) + + IF (FileLineUC == ParamNameUC) THEN + Line = FileLines(I) + LineNum = I + FoundLine = .TRUE. + END IF + END DO + +END subroutine FindLine + !======================================================================= subroutine ReadEmptyLine(Un,CurLine) INTEGER(IntKi), INTENT(IN ) :: Un ! Input file unit @@ -1037,5 +1619,101 @@ FUNCTION Int2LStr ( Num ) RETURN END FUNCTION Int2LStr +!======================================================================= + + subroutine AddToList(list, element) + ! Credit to: https://stackoverflow.com/questions/28048508/how-to-add-new-element-to-dynamical-array-in-fortran-90 + ! This is set up for integers, will need to make interface for other types + IMPLICIT NONE + + integer :: i, isize + Integer(IntKi), intent(in) :: element + Integer(IntKi), dimension(:), allocatable, intent(inout) :: list + Integer(IntKi), dimension(:), allocatable :: clist + + + if(allocated(list)) then + isize = size(list) + allocate(clist(isize+1)) + do i=1,isize + clist(i) = list(i) + end do + clist(isize+1) = element + + deallocate(list) + call move_alloc(clist, list) + + else + allocate(list(1)) + list(1) = element + end if + + + end subroutine AddToList + + !------------------------------------------------------------------------------------------------------------------------------- + ! Copied from NWTC_IO.f90 + !> This function returns a character string encoded with today's date in the form dd-mmm-ccyy. + FUNCTION CurDate( ) + + ! Function declaration. + + CHARACTER(11) :: CurDate !< 'dd-mmm-yyyy' string with the current date + + + ! Local declarations. + + CHARACTER(8) :: CDate ! String to hold the returned value from the DATE_AND_TIME subroutine call. + + + + ! Call the system date function. + + CALL DATE_AND_TIME ( CDate ) + + + ! Parse out the day. + + CurDate(1:3) = CDate(7:8)//'-' + + + ! Parse out the month. + + SELECT CASE ( CDate(5:6) ) + CASE ( '01' ) + CurDate(4:6) = 'Jan' + CASE ( '02' ) + CurDate(4:6) = 'Feb' + CASE ( '03' ) + CurDate(4:6) = 'Mar' + CASE ( '04' ) + CurDate(4:6) = 'Apr' + CASE ( '05' ) + CurDate(4:6) = 'May' + CASE ( '06' ) + CurDate(4:6) = 'Jun' + CASE ( '07' ) + CurDate(4:6) = 'Jul' + CASE ( '08' ) + CurDate(4:6) = 'Aug' + CASE ( '09' ) + CurDate(4:6) = 'Sep' + CASE ( '10' ) + CurDate(4:6) = 'Oct' + CASE ( '11' ) + CurDate(4:6) = 'Nov' + CASE ( '12' ) + CurDate(4:6) = 'Dec' + END SELECT + + + ! Parse out the year. + + CurDate(7:11) = '-'//CDate(1:4) + + + RETURN + END FUNCTION CurDate + END MODULE ROSCO_Helpers \ No newline at end of file diff --git a/ROSCO/src/ROSCO_IO.f90 b/ROSCO/src/ROSCO_IO.f90 index d465d512..d3b0ee66 100644 --- a/ROSCO/src/ROSCO_IO.f90 +++ b/ROSCO/src/ROSCO_IO.f90 @@ -122,6 +122,72 @@ SUBROUTINE WriteRestartFile(LocalVar, CntrPar, ErrVar, objInst, RootName, size_a WRITE( Un, IOSTAT=ErrStat) LocalVar%Fl_PitCom WRITE( Un, IOSTAT=ErrStat) LocalVar%NACIMU_FA_AccF WRITE( Un, IOSTAT=ErrStat) LocalVar%FA_AccF + WRITE( Un, IOSTAT=ErrStat) LocalVar%PtfmTDX + WRITE( Un, IOSTAT=ErrStat) LocalVar%PtfmTDY + WRITE( Un, IOSTAT=ErrStat) LocalVar%PtfmTDZ + WRITE( Un, IOSTAT=ErrStat) LocalVar%PtfmRDX + WRITE( Un, IOSTAT=ErrStat) LocalVar%PtfmRDY + WRITE( Un, IOSTAT=ErrStat) LocalVar%PtfmRDZ + WRITE( Un, IOSTAT=ErrStat) LocalVar%PtfmTVX + WRITE( Un, IOSTAT=ErrStat) LocalVar%PtfmTVY + WRITE( Un, IOSTAT=ErrStat) LocalVar%PtfmTVZ + WRITE( Un, IOSTAT=ErrStat) LocalVar%PtfmRVX + WRITE( Un, IOSTAT=ErrStat) LocalVar%PtfmRVY + WRITE( Un, IOSTAT=ErrStat) LocalVar%PtfmRVZ + WRITE( Un, IOSTAT=ErrStat) LocalVar%PtfmTAX + WRITE( Un, IOSTAT=ErrStat) LocalVar%PtfmTAY + WRITE( Un, IOSTAT=ErrStat) LocalVar%PtfmTAZ + WRITE( Un, IOSTAT=ErrStat) LocalVar%PtfmRAX + WRITE( Un, IOSTAT=ErrStat) LocalVar%PtfmRAY + WRITE( Un, IOSTAT=ErrStat) LocalVar%PtfmRAZ + WRITE( Un, IOSTAT=ErrStat) LocalVar%CC_DesiredL(1) + WRITE( Un, IOSTAT=ErrStat) LocalVar%CC_DesiredL(2) + WRITE( Un, IOSTAT=ErrStat) LocalVar%CC_DesiredL(3) + WRITE( Un, IOSTAT=ErrStat) LocalVar%CC_DesiredL(4) + WRITE( Un, IOSTAT=ErrStat) LocalVar%CC_DesiredL(5) + WRITE( Un, IOSTAT=ErrStat) LocalVar%CC_DesiredL(6) + WRITE( Un, IOSTAT=ErrStat) LocalVar%CC_DesiredL(7) + WRITE( Un, IOSTAT=ErrStat) LocalVar%CC_DesiredL(8) + WRITE( Un, IOSTAT=ErrStat) LocalVar%CC_DesiredL(9) + WRITE( Un, IOSTAT=ErrStat) LocalVar%CC_DesiredL(10) + WRITE( Un, IOSTAT=ErrStat) LocalVar%CC_DesiredL(11) + WRITE( Un, IOSTAT=ErrStat) LocalVar%CC_DesiredL(12) + WRITE( Un, IOSTAT=ErrStat) LocalVar%CC_ActuatedL(1) + WRITE( Un, IOSTAT=ErrStat) LocalVar%CC_ActuatedL(2) + WRITE( Un, IOSTAT=ErrStat) LocalVar%CC_ActuatedL(3) + WRITE( Un, IOSTAT=ErrStat) LocalVar%CC_ActuatedL(4) + WRITE( Un, IOSTAT=ErrStat) LocalVar%CC_ActuatedL(5) + WRITE( Un, IOSTAT=ErrStat) LocalVar%CC_ActuatedL(6) + WRITE( Un, IOSTAT=ErrStat) LocalVar%CC_ActuatedL(7) + WRITE( Un, IOSTAT=ErrStat) LocalVar%CC_ActuatedL(8) + WRITE( Un, IOSTAT=ErrStat) LocalVar%CC_ActuatedL(9) + WRITE( Un, IOSTAT=ErrStat) LocalVar%CC_ActuatedL(10) + WRITE( Un, IOSTAT=ErrStat) LocalVar%CC_ActuatedL(11) + WRITE( Un, IOSTAT=ErrStat) LocalVar%CC_ActuatedL(12) + WRITE( Un, IOSTAT=ErrStat) LocalVar%CC_ActuatedDL(1) + WRITE( Un, IOSTAT=ErrStat) LocalVar%CC_ActuatedDL(2) + WRITE( Un, IOSTAT=ErrStat) LocalVar%CC_ActuatedDL(3) + WRITE( Un, IOSTAT=ErrStat) LocalVar%CC_ActuatedDL(4) + WRITE( Un, IOSTAT=ErrStat) LocalVar%CC_ActuatedDL(5) + WRITE( Un, IOSTAT=ErrStat) LocalVar%CC_ActuatedDL(6) + WRITE( Un, IOSTAT=ErrStat) LocalVar%CC_ActuatedDL(7) + WRITE( Un, IOSTAT=ErrStat) LocalVar%CC_ActuatedDL(8) + WRITE( Un, IOSTAT=ErrStat) LocalVar%CC_ActuatedDL(9) + WRITE( Un, IOSTAT=ErrStat) LocalVar%CC_ActuatedDL(10) + WRITE( Un, IOSTAT=ErrStat) LocalVar%CC_ActuatedDL(11) + WRITE( Un, IOSTAT=ErrStat) LocalVar%CC_ActuatedDL(12) + WRITE( Un, IOSTAT=ErrStat) LocalVar%StC_Input(1) + WRITE( Un, IOSTAT=ErrStat) LocalVar%StC_Input(2) + WRITE( Un, IOSTAT=ErrStat) LocalVar%StC_Input(3) + WRITE( Un, IOSTAT=ErrStat) LocalVar%StC_Input(4) + WRITE( Un, IOSTAT=ErrStat) LocalVar%StC_Input(5) + WRITE( Un, IOSTAT=ErrStat) LocalVar%StC_Input(6) + WRITE( Un, IOSTAT=ErrStat) LocalVar%StC_Input(7) + WRITE( Un, IOSTAT=ErrStat) LocalVar%StC_Input(8) + WRITE( Un, IOSTAT=ErrStat) LocalVar%StC_Input(9) + WRITE( Un, IOSTAT=ErrStat) LocalVar%StC_Input(10) + WRITE( Un, IOSTAT=ErrStat) LocalVar%StC_Input(11) + WRITE( Un, IOSTAT=ErrStat) LocalVar%StC_Input(12) WRITE( Un, IOSTAT=ErrStat) LocalVar%Flp_Angle(1) WRITE( Un, IOSTAT=ErrStat) LocalVar%Flp_Angle(2) WRITE( Un, IOSTAT=ErrStat) LocalVar%Flp_Angle(3) @@ -154,6 +220,16 @@ SUBROUTINE WriteRestartFile(LocalVar, CntrPar, ErrVar, objInst, RootName, size_a WRITE( Un, IOSTAT=ErrStat) LocalVar%FP%lpf2_OutputSignalLast2 WRITE( Un, IOSTAT=ErrStat) LocalVar%FP%lpf2_InputSignalLast1 WRITE( Un, IOSTAT=ErrStat) LocalVar%FP%lpf2_OutputSignalLast1 + WRITE( Un, IOSTAT=ErrStat) LocalVar%FP%lpfV_a2 + WRITE( Un, IOSTAT=ErrStat) LocalVar%FP%lpfV_a1 + WRITE( Un, IOSTAT=ErrStat) LocalVar%FP%lpfV_a0 + WRITE( Un, IOSTAT=ErrStat) LocalVar%FP%lpfV_b2 + WRITE( Un, IOSTAT=ErrStat) LocalVar%FP%lpfV_b1 + WRITE( Un, IOSTAT=ErrStat) LocalVar%FP%lpfV_b0 + WRITE( Un, IOSTAT=ErrStat) LocalVar%FP%lpfV_InputSignalLast2 + WRITE( Un, IOSTAT=ErrStat) LocalVar%FP%lpfV_OutputSignalLast2 + WRITE( Un, IOSTAT=ErrStat) LocalVar%FP%lpfV_InputSignalLast1 + WRITE( Un, IOSTAT=ErrStat) LocalVar%FP%lpfV_OutputSignalLast1 WRITE( Un, IOSTAT=ErrStat) LocalVar%FP%hpf_InputSignalLast WRITE( Un, IOSTAT=ErrStat) LocalVar%FP%hpf_OutputSignalLast WRITE( Un, IOSTAT=ErrStat) LocalVar%FP%nfs_OutputSignalLast1 @@ -181,6 +257,7 @@ SUBROUTINE WriteRestartFile(LocalVar, CntrPar, ErrVar, objInst, RootName, size_a WRITE( Un, IOSTAT=ErrStat) LocalVar%rlP%LastSignal WRITE( Un, IOSTAT=ErrStat) objInst%instLPF WRITE( Un, IOSTAT=ErrStat) objInst%instSecLPF + WRITE( Un, IOSTAT=ErrStat) objInst%instSecLPFV WRITE( Un, IOSTAT=ErrStat) objInst%instHPF WRITE( Un, IOSTAT=ErrStat) objInst%instNotchSlopes WRITE( Un, IOSTAT=ErrStat) objInst%instNotch @@ -305,6 +382,72 @@ SUBROUTINE ReadRestartFile(avrSWAP, LocalVar, CntrPar, objInst, PerfData, RootNa READ( Un, IOSTAT=ErrStat) LocalVar%Fl_PitCom READ( Un, IOSTAT=ErrStat) LocalVar%NACIMU_FA_AccF READ( Un, IOSTAT=ErrStat) LocalVar%FA_AccF + READ( Un, IOSTAT=ErrStat) LocalVar%PtfmTDX + READ( Un, IOSTAT=ErrStat) LocalVar%PtfmTDY + READ( Un, IOSTAT=ErrStat) LocalVar%PtfmTDZ + READ( Un, IOSTAT=ErrStat) LocalVar%PtfmRDX + READ( Un, IOSTAT=ErrStat) LocalVar%PtfmRDY + READ( Un, IOSTAT=ErrStat) LocalVar%PtfmRDZ + READ( Un, IOSTAT=ErrStat) LocalVar%PtfmTVX + READ( Un, IOSTAT=ErrStat) LocalVar%PtfmTVY + READ( Un, IOSTAT=ErrStat) LocalVar%PtfmTVZ + READ( Un, IOSTAT=ErrStat) LocalVar%PtfmRVX + READ( Un, IOSTAT=ErrStat) LocalVar%PtfmRVY + READ( Un, IOSTAT=ErrStat) LocalVar%PtfmRVZ + READ( Un, IOSTAT=ErrStat) LocalVar%PtfmTAX + READ( Un, IOSTAT=ErrStat) LocalVar%PtfmTAY + READ( Un, IOSTAT=ErrStat) LocalVar%PtfmTAZ + READ( Un, IOSTAT=ErrStat) LocalVar%PtfmRAX + READ( Un, IOSTAT=ErrStat) LocalVar%PtfmRAY + READ( Un, IOSTAT=ErrStat) LocalVar%PtfmRAZ + READ( Un, IOSTAT=ErrStat) LocalVar%CC_DesiredL(1) + READ( Un, IOSTAT=ErrStat) LocalVar%CC_DesiredL(2) + READ( Un, IOSTAT=ErrStat) LocalVar%CC_DesiredL(3) + READ( Un, IOSTAT=ErrStat) LocalVar%CC_DesiredL(4) + READ( Un, IOSTAT=ErrStat) LocalVar%CC_DesiredL(5) + READ( Un, IOSTAT=ErrStat) LocalVar%CC_DesiredL(6) + READ( Un, IOSTAT=ErrStat) LocalVar%CC_DesiredL(7) + READ( Un, IOSTAT=ErrStat) LocalVar%CC_DesiredL(8) + READ( Un, IOSTAT=ErrStat) LocalVar%CC_DesiredL(9) + READ( Un, IOSTAT=ErrStat) LocalVar%CC_DesiredL(10) + READ( Un, IOSTAT=ErrStat) LocalVar%CC_DesiredL(11) + READ( Un, IOSTAT=ErrStat) LocalVar%CC_DesiredL(12) + READ( Un, IOSTAT=ErrStat) LocalVar%CC_ActuatedL(1) + READ( Un, IOSTAT=ErrStat) LocalVar%CC_ActuatedL(2) + READ( Un, IOSTAT=ErrStat) LocalVar%CC_ActuatedL(3) + READ( Un, IOSTAT=ErrStat) LocalVar%CC_ActuatedL(4) + READ( Un, IOSTAT=ErrStat) LocalVar%CC_ActuatedL(5) + READ( Un, IOSTAT=ErrStat) LocalVar%CC_ActuatedL(6) + READ( Un, IOSTAT=ErrStat) LocalVar%CC_ActuatedL(7) + READ( Un, IOSTAT=ErrStat) LocalVar%CC_ActuatedL(8) + READ( Un, IOSTAT=ErrStat) LocalVar%CC_ActuatedL(9) + READ( Un, IOSTAT=ErrStat) LocalVar%CC_ActuatedL(10) + READ( Un, IOSTAT=ErrStat) LocalVar%CC_ActuatedL(11) + READ( Un, IOSTAT=ErrStat) LocalVar%CC_ActuatedL(12) + READ( Un, IOSTAT=ErrStat) LocalVar%CC_ActuatedDL(1) + READ( Un, IOSTAT=ErrStat) LocalVar%CC_ActuatedDL(2) + READ( Un, IOSTAT=ErrStat) LocalVar%CC_ActuatedDL(3) + READ( Un, IOSTAT=ErrStat) LocalVar%CC_ActuatedDL(4) + READ( Un, IOSTAT=ErrStat) LocalVar%CC_ActuatedDL(5) + READ( Un, IOSTAT=ErrStat) LocalVar%CC_ActuatedDL(6) + READ( Un, IOSTAT=ErrStat) LocalVar%CC_ActuatedDL(7) + READ( Un, IOSTAT=ErrStat) LocalVar%CC_ActuatedDL(8) + READ( Un, IOSTAT=ErrStat) LocalVar%CC_ActuatedDL(9) + READ( Un, IOSTAT=ErrStat) LocalVar%CC_ActuatedDL(10) + READ( Un, IOSTAT=ErrStat) LocalVar%CC_ActuatedDL(11) + READ( Un, IOSTAT=ErrStat) LocalVar%CC_ActuatedDL(12) + READ( Un, IOSTAT=ErrStat) LocalVar%StC_Input(1) + READ( Un, IOSTAT=ErrStat) LocalVar%StC_Input(2) + READ( Un, IOSTAT=ErrStat) LocalVar%StC_Input(3) + READ( Un, IOSTAT=ErrStat) LocalVar%StC_Input(4) + READ( Un, IOSTAT=ErrStat) LocalVar%StC_Input(5) + READ( Un, IOSTAT=ErrStat) LocalVar%StC_Input(6) + READ( Un, IOSTAT=ErrStat) LocalVar%StC_Input(7) + READ( Un, IOSTAT=ErrStat) LocalVar%StC_Input(8) + READ( Un, IOSTAT=ErrStat) LocalVar%StC_Input(9) + READ( Un, IOSTAT=ErrStat) LocalVar%StC_Input(10) + READ( Un, IOSTAT=ErrStat) LocalVar%StC_Input(11) + READ( Un, IOSTAT=ErrStat) LocalVar%StC_Input(12) READ( Un, IOSTAT=ErrStat) LocalVar%Flp_Angle(1) READ( Un, IOSTAT=ErrStat) LocalVar%Flp_Angle(2) READ( Un, IOSTAT=ErrStat) LocalVar%Flp_Angle(3) @@ -338,6 +481,16 @@ SUBROUTINE ReadRestartFile(avrSWAP, LocalVar, CntrPar, objInst, PerfData, RootNa READ( Un, IOSTAT=ErrStat) LocalVar%FP%lpf2_OutputSignalLast2 READ( Un, IOSTAT=ErrStat) LocalVar%FP%lpf2_InputSignalLast1 READ( Un, IOSTAT=ErrStat) LocalVar%FP%lpf2_OutputSignalLast1 + READ( Un, IOSTAT=ErrStat) LocalVar%FP%lpfV_a2 + READ( Un, IOSTAT=ErrStat) LocalVar%FP%lpfV_a1 + READ( Un, IOSTAT=ErrStat) LocalVar%FP%lpfV_a0 + READ( Un, IOSTAT=ErrStat) LocalVar%FP%lpfV_b2 + READ( Un, IOSTAT=ErrStat) LocalVar%FP%lpfV_b1 + READ( Un, IOSTAT=ErrStat) LocalVar%FP%lpfV_b0 + READ( Un, IOSTAT=ErrStat) LocalVar%FP%lpfV_InputSignalLast2 + READ( Un, IOSTAT=ErrStat) LocalVar%FP%lpfV_OutputSignalLast2 + READ( Un, IOSTAT=ErrStat) LocalVar%FP%lpfV_InputSignalLast1 + READ( Un, IOSTAT=ErrStat) LocalVar%FP%lpfV_OutputSignalLast1 READ( Un, IOSTAT=ErrStat) LocalVar%FP%hpf_InputSignalLast READ( Un, IOSTAT=ErrStat) LocalVar%FP%hpf_OutputSignalLast READ( Un, IOSTAT=ErrStat) LocalVar%FP%nfs_OutputSignalLast1 @@ -365,6 +518,7 @@ SUBROUTINE ReadRestartFile(avrSWAP, LocalVar, CntrPar, objInst, PerfData, RootNa READ( Un, IOSTAT=ErrStat) LocalVar%rlP%LastSignal READ( Un, IOSTAT=ErrStat) objInst%instLPF READ( Un, IOSTAT=ErrStat) objInst%instSecLPF + READ( Un, IOSTAT=ErrStat) objInst%instSecLPFV READ( Un, IOSTAT=ErrStat) objInst%instHPF READ( Un, IOSTAT=ErrStat) objInst%instNotchSlopes READ( Un, IOSTAT=ErrStat) objInst%instNotch @@ -373,7 +527,7 @@ SUBROUTINE ReadRestartFile(avrSWAP, LocalVar, CntrPar, objInst, PerfData, RootNa Close ( Un ) ENDIF ! Read Parameter files - CALL ReadControlParameterFileSub(CntrPar, zmqVar, LocalVar%ACC_INFILE, LocalVar%ACC_INFILE_SIZE, ErrVar) + CALL ReadControlParameterFileSub(CntrPar, zmqVar, LocalVar%ACC_INFILE, LocalVar%ACC_INFILE_SIZE, RootName, ErrVar) IF (CntrPar%WE_Mode > 0) THEN CALL READCpFile(CntrPar, PerfData, ErrVar) ENDIF @@ -399,6 +553,13 @@ SUBROUTINE Debug(LocalVar, CntrPar, DebugVar, ErrVar, avrSWAP, RootName, size_av CHARACTER(size_avcOUTNAME-1), INTENT(IN) :: RootName ! a Fortran version of the input C string (not considered an array here) [subtract 1 for the C null-character] CHARACTER(200) :: Version ! git version of ROSCO CHARACTER(15), ALLOCATABLE :: DebugOutStrings(:), DebugOutUnits(:) + + ! Avr output writing + INTEGER(IntKi), SAVE, DIMENSION(:), ALLOCATABLE :: avrIndices + INTEGER(IntKi) :: avrBaseLength = 85 + INTEGER(IntKi) :: Ind + CHARACTER(100) :: avrFmt + REAL(DbKi), ALLOCATABLE :: DebugOutData(:) CHARACTER(15), ALLOCATABLE :: LocalVarOutStrings(:) @@ -442,7 +603,7 @@ SUBROUTINE Debug(LocalVar, CntrPar, DebugVar, ErrVar, avrSWAP, RootName, size_av '[rad/s]', '[rad/s]', '[m/s]', '[rad]', '[rad]', & '[N/A]', '[N/A]', '[N/A]', '[N/A]', '[rad/s]', & '[deg]', '[deg]', '[deg]', '[N/A]'] - nLocalVars = 71 + nLocalVars = 93 Allocate(LocalVarOutData(nLocalVars)) Allocate(LocalVarOutStrings(nLocalVars)) LocalVarOutData(1) = LocalVar%iStatus @@ -513,9 +674,31 @@ SUBROUTINE Debug(LocalVar, CntrPar, DebugVar, ErrVar, avrSWAP, RootName, size_av LocalVarOutData(66) = LocalVar%Fl_PitCom LocalVarOutData(67) = LocalVar%NACIMU_FA_AccF LocalVarOutData(68) = LocalVar%FA_AccF - LocalVarOutData(69) = LocalVar%Flp_Angle(1) - LocalVarOutData(70) = LocalVar%RootMyb_Last(1) - LocalVarOutData(71) = LocalVar%ACC_INFILE_SIZE + LocalVarOutData(69) = LocalVar%PtfmTDX + LocalVarOutData(70) = LocalVar%PtfmTDY + LocalVarOutData(71) = LocalVar%PtfmTDZ + LocalVarOutData(72) = LocalVar%PtfmRDX + LocalVarOutData(73) = LocalVar%PtfmRDY + LocalVarOutData(74) = LocalVar%PtfmRDZ + LocalVarOutData(75) = LocalVar%PtfmTVX + LocalVarOutData(76) = LocalVar%PtfmTVY + LocalVarOutData(77) = LocalVar%PtfmTVZ + LocalVarOutData(78) = LocalVar%PtfmRVX + LocalVarOutData(79) = LocalVar%PtfmRVY + LocalVarOutData(80) = LocalVar%PtfmRVZ + LocalVarOutData(81) = LocalVar%PtfmTAX + LocalVarOutData(82) = LocalVar%PtfmTAY + LocalVarOutData(83) = LocalVar%PtfmTAZ + LocalVarOutData(84) = LocalVar%PtfmRAX + LocalVarOutData(85) = LocalVar%PtfmRAY + LocalVarOutData(86) = LocalVar%PtfmRAZ + LocalVarOutData(87) = LocalVar%CC_DesiredL(1) + LocalVarOutData(88) = LocalVar%CC_ActuatedL(1) + LocalVarOutData(89) = LocalVar%CC_ActuatedDL(1) + LocalVarOutData(90) = LocalVar%StC_Input(1) + LocalVarOutData(91) = LocalVar%Flp_Angle(1) + LocalVarOutData(92) = LocalVar%RootMyb_Last(1) + LocalVarOutData(93) = LocalVar%ACC_INFILE_SIZE LocalVarOutStrings = [CHARACTER(15) :: 'iStatus', 'Time', 'DT', 'VS_GenPwr', 'GenSpeed', & 'RotSpeed', 'NacHeading', 'NacVane', 'HorWindV', 'rootMOOP', & 'rootMOOPF', 'BlPitch', 'BlPitchCMeas', 'Azimuth', 'NumBl', & @@ -529,8 +712,12 @@ SUBROUTINE Debug(LocalVar, CntrPar, DebugVar, ErrVar, avrSWAP, RootName, size_av 'TestType', 'VS_MaxTq', 'VS_LastGenTrq', 'VS_LastGenPwr', 'VS_MechGenPwr', & 'VS_SpdErrAr', 'VS_SpdErrBr', 'VS_SpdErr', 'VS_State', 'VS_Rgn3Pitch', & 'WE_Vw', 'WE_Vw_F', 'WE_VwI', 'WE_VwIdot', 'VS_LastGenTrqF', & - 'Fl_PitCom', 'NACIMU_FA_AccF', 'FA_AccF', 'Flp_Angle', 'RootMyb_Last', & - 'ACC_INFILE_SIZE'] + 'Fl_PitCom', 'NACIMU_FA_AccF', 'FA_AccF', 'PtfmTDX', 'PtfmTDY', & + 'PtfmTDZ', 'PtfmRDX', 'PtfmRDY', 'PtfmRDZ', 'PtfmTVX', & + 'PtfmTVY', 'PtfmTVZ', 'PtfmRVX', 'PtfmRVY', 'PtfmRVZ', & + 'PtfmTAX', 'PtfmTAY', 'PtfmTAZ', 'PtfmRAX', 'PtfmRAY', & + 'PtfmRAZ', 'CC_DesiredL', 'CC_ActuatedL', 'CC_ActuatedDL', 'StC_Input', & + 'Flp_Angle', 'RootMyb_Last', 'ACC_INFILE_SIZE'] ! Initialize debug file IF ((LocalVar%iStatus == 0) .OR. (LocalVar%iStatus == -9)) THEN ! .TRUE. if we're on the first call to the DLL IF (CntrPar%LoggingLevel > 0) THEN @@ -550,13 +737,38 @@ SUBROUTINE Debug(LocalVar, CntrPar, DebugVar, ErrVar, avrSWAP, RootName, size_av END IF IF (CntrPar%LoggingLevel > 2) THEN + ! Set avrIndices, start with basic indices + Allocate(avrIndices(avrBaseLength)) + DO Ind = 1, avrBaseLength + avrIndices(Ind) = Ind + END DO + + ! Cable control indices + IF (CntrPar%CC_Mode > 0) THEN + DO Ind = 1, SIZE(CntrPar%CC_GroupIndex) + Call AddToList(avrIndices,CntrPar%CC_GroupIndex(Ind)) + Call AddToList(avrIndices,CntrPar%CC_GroupIndex(Ind)+1) + END DO + END IF + + ! Structural control indices + IF (CntrPar%StC_Mode > 0) THEN + DO Ind = 1, SIZE(CntrPar%StC_GroupIndex) + Call AddToList(avrIndices,CntrPar%StC_GroupIndex(Ind)) + END DO + END IF + + ! Format string + avrFmt = '(A21,'//TRIM(Int2LStr(SIZE(avrIndices)))//'(TR12,"'//'AvrSWAP(",I4,")"))' + CALL GetNewUnit(UnDb3, ErrVar) OPEN(unit=UnDb3, FILE=TRIM(RootName)//'.RO.dbg3') WRITE(UnDb3,'(/////)') - WRITE(UnDb3,'(A,85("'//Tab//'AvrSWAP(",I2,")"))') 'LocalVar%Time ', (i,i=1, 85) - WRITE(UnDb3,'(A,85("'//Tab//'(-)"))') '(s)' + WRITE(UnDb3,avrFmt) 'LocalVar%Time ', (avrIndices) + WRITE(UnDb3,'(A21,'//TRIM(Int2LStr(SIZE(avrIndices)))//'(TR22,"(-)"))') '(s)' END IF END IF + ! Print simulation status, every 10 seconds IF (MODULO(LocalVar%Time, 10.0_DbKi) == 0) THEN WRITE(*, 100) LocalVar%GenSpeedF*RPS2RPM, LocalVar%BlPitch(1)*R2D, avrSWAP(15)/1000.0, LocalVar%WE_Vw @@ -587,7 +799,7 @@ SUBROUTINE Debug(LocalVar, CntrPar, DebugVar, ErrVar, avrSWAP, RootName, size_av END IF IF(CntrPar%LoggingLevel > 2) THEN - WRITE (UnDb3, FmtDat) LocalVar%Time, avrSWAP(1: 85) + WRITE (UnDb3, FmtDat) LocalVar%Time, avrSWAP(avrIndices) END IF END SUBROUTINE Debug diff --git a/ROSCO/src/ROSCO_Types.f90 b/ROSCO/src/ROSCO_Types.f90 index 2c4143bc..3988f93a 100644 --- a/ROSCO/src/ROSCO_Types.f90 +++ b/ROSCO/src/ROSCO_Types.f90 @@ -9,6 +9,7 @@ MODULE ROSCO_Types TYPE, PUBLIC :: ControlParameters INTEGER(IntKi) :: LoggingLevel ! 0 - write no debug files, 1 - write standard output .dbg-file, 2 - write standard output .dbg-file and complete avrSWAP-array .dbg2-file + INTEGER(IntKi) :: Echo ! 0 - no Echo, 1 - Echo input data to .echo INTEGER(IntKi) :: F_LPFType ! Low pass filter on the rotor and generator speed {1 - first-order low-pass filter, 2 - second-order low-pass filter}, [rad/s] INTEGER(IntKi) :: F_NotchType ! Notch on the measured generator speed {0 - disable, 1 - enable} REAL(DbKi) :: F_LPFCornerFreq ! Corner frequency (-3dB point) in the first-order low-pass filter, [rad/s] @@ -123,6 +124,13 @@ MODULE ROSCO_Types INTEGER(IntKi) :: ZMQ_Mode ! Flag for ZeroMQ (0-off, 1-yaw} CHARACTER(256) :: ZMQ_CommAddress ! Comm Address to zeroMQ client REAL(DbKi) :: ZMQ_UpdatePeriod ! Integer for zeromq update frequency + INTEGER(IntKi) :: CC_Mode ! Flag for ZeroMQ (0-off, 1-yaw} + INTEGER(IntKi) :: CC_Group_N ! Number of cable control groups + REAL(DbKi) :: CC_ActTau ! Time constant for line actuator [s] + INTEGER(IntKi), DIMENSION(:), ALLOCATABLE :: CC_GroupIndex ! Cable control group indices + INTEGER(IntKi) :: StC_Mode ! Flag for ZeroMQ (0-off, 1-yaw} + INTEGER(IntKi) :: StC_Group_N ! Number of cable control groups + INTEGER(IntKi), DIMENSION(:), ALLOCATABLE :: StC_GroupIndex ! Cable control group indices REAL(DbKi) :: PC_RtTq99 ! 99% of the rated torque value, using for switching between pitch and torque control, [Nm]. REAL(DbKi) :: VS_MaxOMTq ! Maximum torque at the end of the below-rated region 2, [Nm] REAL(DbKi) :: VS_MinOMTq ! Minimum torque at the beginning of the below-rated region 2, [Nm] @@ -155,6 +163,16 @@ MODULE ROSCO_Types REAL(DbKi), DIMENSION(99) :: lpf2_OutputSignalLast2 ! Second order filter - Previous output 2 REAL(DbKi), DIMENSION(99) :: lpf2_InputSignalLast1 ! Second order filter - Previous input 1 REAL(DbKi), DIMENSION(99) :: lpf2_OutputSignalLast1 ! Second order filter - Previous output 1 + REAL(DbKi), DIMENSION(99) :: lpfV_a2 ! Second order filter - Denominator coefficient 1 + REAL(DbKi), DIMENSION(99) :: lpfV_a1 ! Second order filter - Denominator coefficient 1 + REAL(DbKi), DIMENSION(99) :: lpfV_a0 ! Second order filter - Denominator coefficient 0 + REAL(DbKi), DIMENSION(99) :: lpfV_b2 ! Second order filter - Numerator coefficient 2 + REAL(DbKi), DIMENSION(99) :: lpfV_b1 ! Second order filter - Numerator coefficient 1 + REAL(DbKi), DIMENSION(99) :: lpfV_b0 ! Second order filter - Numerator coefficient 0 + REAL(DbKi), DIMENSION(99) :: lpfV_InputSignalLast2 ! Second order filter - Previous input 2 + REAL(DbKi), DIMENSION(99) :: lpfV_OutputSignalLast2 ! Second order filter - Previous output 2 + REAL(DbKi), DIMENSION(99) :: lpfV_InputSignalLast1 ! Second order filter - Previous input 1 + REAL(DbKi), DIMENSION(99) :: lpfV_OutputSignalLast1 ! Second order filter - Previous output 1 REAL(DbKi), DIMENSION(99) :: hpf_InputSignalLast ! High pass filter - Previous output 1 REAL(DbKi), DIMENSION(99) :: hpf_OutputSignalLast ! High pass filter - Previous output 1 REAL(DbKi), DIMENSION(99) :: nfs_OutputSignalLast1 ! Notch filter slopes previous output 1 @@ -258,6 +276,28 @@ MODULE ROSCO_Types REAL(DbKi) :: Fl_PitCom ! Shutdown, .FALSE. if inactive, .TRUE. if active REAL(DbKi) :: NACIMU_FA_AccF ! None REAL(DbKi) :: FA_AccF ! None + REAL(DbKi) :: PtfmTDX ! Platform motion -- Displacement TDX (m)') + REAL(DbKi) :: PtfmTDY ! Platform motion -- Displacement TDY (m)') + REAL(DbKi) :: PtfmTDZ ! Platform motion -- Displacement TDZ (m)') + REAL(DbKi) :: PtfmRDX ! Platform motion -- Displacement RDX (rad)') + REAL(DbKi) :: PtfmRDY ! Platform motion -- Displacement RDY (rad)') + REAL(DbKi) :: PtfmRDZ ! Platform motion -- Displacement RDZ (rad)') + REAL(DbKi) :: PtfmTVX ! Platform motion -- Velocity TVX (m/s)') + REAL(DbKi) :: PtfmTVY ! Platform motion -- Velocity TVY (m/s)') + REAL(DbKi) :: PtfmTVZ ! Platform motion -- Velocity TVZ (m/s)') + REAL(DbKi) :: PtfmRVX ! Platform motion -- Velocity RVX (rad/s)') + REAL(DbKi) :: PtfmRVY ! Platform motion -- Velocity RVY (rad/s)') + REAL(DbKi) :: PtfmRVZ ! Platform motion -- Velocity RVZ (rad/s)') + REAL(DbKi) :: PtfmTAX ! Platform motion -- Acceleration TAX (m/s^2)') + REAL(DbKi) :: PtfmTAY ! Platform motion -- Acceleration TAY (m/s^2)') + REAL(DbKi) :: PtfmTAZ ! Platform motion -- Acceleration TAZ (m/s^2)') + REAL(DbKi) :: PtfmRAX ! Platform motion -- Acceleration RAX (rad/s^2)') + REAL(DbKi) :: PtfmRAY ! Platform motion -- Acceleration RAY (rad/s^2)') + REAL(DbKi) :: PtfmRAZ ! Platform motion -- Acceleration RAZ (rad/s^2)') + REAL(DbKi) :: CC_DesiredL(12) ! None + REAL(DbKi) :: CC_ActuatedL(12) ! None + REAL(DbKi) :: CC_ActuatedDL(12) ! None + REAL(DbKi) :: StC_Input(12) ! None REAL(DbKi) :: Flp_Angle(3) ! Flap Angle (rad) REAL(DbKi) :: RootMyb_Last(3) ! Last blade root bending moment (Nm) INTEGER(IntKi) :: ACC_INFILE_SIZE ! Length of parameter input filename @@ -272,6 +312,7 @@ MODULE ROSCO_Types TYPE, PUBLIC :: ObjectInstances INTEGER(IntKi) :: instLPF ! Low-pass filter instance INTEGER(IntKi) :: instSecLPF ! Second order low-pass filter instance + INTEGER(IntKi) :: instSecLPFV ! Second order low-pass filter instance INTEGER(IntKi) :: instHPF ! High-pass filter instance INTEGER(IntKi) :: instNotchSlopes ! Notch filter slopes instance INTEGER(IntKi) :: instNotch ! Notch filter instance diff --git a/ROSCO/src/ReadSetParameters.f90 b/ROSCO/src/ReadSetParameters.f90 index 9ba9e80c..a7f912af 100644 --- a/ROSCO/src/ReadSetParameters.f90 +++ b/ROSCO/src/ReadSetParameters.f90 @@ -19,7 +19,6 @@ MODULE ReadSetParameters USE Functions USE SysSubs USE ROSCO_Helpers - IMPLICIT NONE @@ -34,7 +33,7 @@ SUBROUTINE ReadAvrSWAP(avrSWAP, LocalVar, CntrPar) TYPE(ControlParameters), INTENT(IN) :: CntrPar ! Allocate Variables: - INTEGER(IntKi) :: K ! Index used for looping through blades. + INTEGER(IntKi) :: K ! Index used for looping through blades. ! Load variables from calling program (See Appendix A of Bladed User's Guide): LocalVar%iStatus = NINT(avrSWAP(1)) @@ -56,6 +55,32 @@ SUBROUTINE ReadAvrSWAP(avrSWAP, LocalVar, CntrPar) LocalVar%Azimuth = avrSWAP(60) LocalVar%NumBl = NINT(avrSWAP(61)) + ! Platform signals + LocalVar%PtfmTDX = avrSWAP(1001) + LocalVar%PtfmTDY = avrSWAP(1002) + LocalVar%PtfmTDZ = avrSWAP(1003) + LocalVar%PtfmRDX = avrSWAP(1004) + LocalVar%PtfmRDY = avrSWAP(1005) + LocalVar%PtfmRDZ = avrSWAP(1006) + LocalVar%PtfmTVX = avrSWAP(1007) + LocalVar%PtfmTVY = avrSWAP(1008) + LocalVar%PtfmTVZ = avrSWAP(1009) + LocalVar%PtfmRVX = avrSWAP(1010) + LocalVar%PtfmRVY = avrSWAP(1011) + LocalVar%PtfmRVZ = avrSWAP(1012) + LocalVar%PtfmTAX = avrSWAP(1013) + LocalVar%PtfmTAY = avrSWAP(1014) + LocalVar%PtfmTAZ = avrSWAP(1015) + LocalVar%PtfmRAX = avrSWAP(1016) + LocalVar%PtfmRAY = avrSWAP(1017) + LocalVar%PtfmRAZ = avrSWAP(1018) + + ! GenTemp = avrSWAP(1026) + + ! WRITE(1000,*) LocalVar%GenSpeed*RPS2RPM, GenTemp + + + ! --- NJA: usually feedback back the previous pitch command helps for numerical stability, sometimes it does not... IF (LocalVar%iStatus == 0) THEN LocalVar%BlPitch(1) = avrSWAP(4) @@ -88,7 +113,7 @@ SUBROUTINE ReadAvrSWAP(avrSWAP, LocalVar, CntrPar) END SUBROUTINE ReadAvrSWAP ! ----------------------------------------------------------------------------------- ! Define parameters for control actions - SUBROUTINE SetParameters(avrSWAP, accINFILE, size_avcMSG, CntrPar, LocalVar, objInst, PerfData, zmqVar, ErrVar) + SUBROUTINE SetParameters(avrSWAP, accINFILE, size_avcMSG, CntrPar, LocalVar, objInst, PerfData, zmqVar, RootName, ErrVar) USE ROSCO_Types, ONLY : ControlParameters, LocalVariables, ObjectInstances, PerformanceData, ErrorVariables, ZMQ_Variables @@ -102,9 +127,12 @@ SUBROUTINE SetParameters(avrSWAP, accINFILE, size_avcMSG, CntrPar, LocalVar, obj TYPE(PerformanceData), INTENT(INOUT) :: PerfData TYPE(ZMQ_Variables), INTENT(INOUT) :: zmqVar TYPE(ErrorVariables), INTENT(INOUT) :: ErrVar + CHARACTER(NINT(avrSWAP(50))-1), INTENT(IN) :: RootName INTEGER(IntKi) :: K ! Index used for looping through blades. + CHARACTER(1024) :: OL_String ! Open description loop string + INTEGER(IntKi) :: OL_Count ! Number of open loop channels CHARACTER(*), PARAMETER :: RoutineName = 'SetParameters' @@ -119,6 +147,7 @@ SUBROUTINE SetParameters(avrSWAP, accINFILE, size_avcMSG, CntrPar, LocalVar, obj ! Initialize all filter instance counters at 1 objInst%instLPF = 1 objInst%instSecLPF = 1 + objInst%instSecLPFV = 1 objInst%instHPF = 1 objInst%instNotchSlopes = 1 objInst%instNotch = 1 @@ -157,7 +186,7 @@ SUBROUTINE SetParameters(avrSWAP, accINFILE, size_avcMSG, CntrPar, LocalVar, obj LocalVar%ACC_INFILE = accINFILE ! Read Control Parameter File - CALL ReadControlParameterFileSub(CntrPar, zmqVar, accINFILE, NINT(avrSWAP(50)),ErrVar) + CALL ReadControlParameterFileSub(CntrPar, zmqVar, accINFILE, NINT(avrSWAP(50)), RootName, ErrVar) ! If there's been an file reading error, don't continue ! Add RoutineName to error message IF (ErrVar%aviFAIL < 0) THEN @@ -191,6 +220,51 @@ SUBROUTINE SetParameters(avrSWAP, accINFILE, size_avcMSG, CntrPar, LocalVar, obj ! Check validity of input parameters: CALL CheckInputs(LocalVar, CntrPar, avrSWAP, ErrVar, size_avcMSG) + ! Initialize variables + LocalVar%CC_DesiredL = 0 + LocalVar%CC_ActuatedL = 0 + LocalVar%CC_ActuatedDL = 0 + LocalVar%StC_Input = 0 + + ! Initialize open loop control + ! Read open loop input, if desired + IF (CntrPar%OL_Mode == 1) THEN + OL_String = '' ! Display string + OL_Count = 1 + IF (CntrPar%Ind_BldPitch > 0) THEN + OL_String = TRIM(OL_String)//' BldPitch ' + OL_Count = OL_Count + 1 + ENDIF + + IF (CntrPar%Ind_GenTq > 0) THEN + OL_String = TRIM(OL_String)//' GenTq ' + OL_Count = OL_Count + 1 + ENDIF + + IF (CntrPar%Ind_YawRate > 0) THEN + OL_String = TRIM(OL_String)//' YawRate ' + OL_Count = OL_Count + 1 + ENDIF + + PRINT *, 'ROSCO: Implementing open loop control for'//TRIM(OL_String) + CALL Read_OL_Input(CntrPar%OL_Filename,110_IntKi,OL_Count,CntrPar%OL_Channels, ErrVar) + + CntrPar%OL_Breakpoints = CntrPar%OL_Channels(:,CntrPar%Ind_Breakpoint) + + IF (CntrPar%Ind_BldPitch > 0) THEN + CntrPar%OL_BldPitch = CntrPar%OL_Channels(:,CntrPar%Ind_BldPitch) + ENDIF + + IF (CntrPar%Ind_GenTq > 0) THEN + CntrPar%OL_GenTq = CntrPar%OL_Channels(:,CntrPar%Ind_GenTq) + ENDIF + + IF (CntrPar%Ind_YawRate > 0) THEN + CntrPar%OL_YawRate = CntrPar%OL_Channels(:,CntrPar%Ind_YawRate) + ENDIF + END IF + + ! Add RoutineName to error message IF (ErrVar%aviFAIL < 0) THEN ErrVar%ErrMsg = RoutineName//':'//TRIM(ErrVar%ErrMsg) @@ -201,11 +275,12 @@ SUBROUTINE SetParameters(avrSWAP, accINFILE, size_avcMSG, CntrPar, LocalVar, obj zmqVar%ZMQ_Flag = .TRUE. ENDIF + ENDIF END SUBROUTINE SetParameters ! ----------------------------------------------------------------------------------- ! Read all constant control parameters from DISCON.IN parameter file - SUBROUTINE ReadControlParameterFileSub(CntrPar, zmqVar, accINFILE, accINFILE_size,ErrVar)!, accINFILE_size) + SUBROUTINE ReadControlParameterFileSub(CntrPar, zmqVar, accINFILE, accINFILE_size, RootName, ErrVar)!, accINFILE_size) USE, INTRINSIC :: ISO_C_Binding USE ROSCO_Types, ONLY : ControlParameters, ErrorVariables, ZMQ_Variables @@ -214,267 +289,254 @@ SUBROUTINE ReadControlParameterFileSub(CntrPar, zmqVar, accINFILE, accINFILE_siz TYPE(ControlParameters), INTENT(INOUT) :: CntrPar ! Control parameter type TYPE(ErrorVariables), INTENT(INOUT) :: ErrVar ! Control parameter type TYPE(ZMQ_Variables), INTENT(INOUT) :: zmqVar ! Control parameter type + CHARACTER(accINFILE_size), INTENT(IN) :: RootName + INTEGER(IntKi) :: UnControllerParameters ! Unit number to open file - INTEGER(IntKi) :: CurLine - ! INTEGER(IntKi), PARAMETER :: UnControllerParameters = 89 ! Unit number to open file - - CHARACTER(1024) :: OL_String ! Open description loop string - INTEGER(IntKi) :: OL_Count ! Number of open loop channels CHARACTER(1024) :: PriPath ! Path name of the primary DISCON file - + CHARACTER(2048) :: TmpLine ! Path name of the primary DISCON file + INTEGER(IntKi) :: NumLines, IOS, I_LINE, ErrStat + INTEGER(IntKi) :: UnEc + CHARACTER(128) :: EchoFilename ! Input checkpoint file + CHARACTER(MaxLineLength), DIMENSION(:), ALLOCATABLE :: FileLines + CHARACTER(*), PARAMETER :: RoutineName = 'ReadControlParameterFileSub' - CurLine = 1 - ! Get primary path of DISCON.IN file (accINFILE(1) here) CALL GetPath( accINFILE(1), PriPath ) ! Input files will be relative to the path where the primary input file is located. CALL GetNewUnit(UnControllerParameters, ErrVar) OPEN(unit=UnControllerParameters, file=accINFILE(1), status='old', action='read') - - !----------------------- HEADER ------------------------ - CALL ReadEmptyLine(UnControllerParameters,CurLine) - CALL ReadEmptyLine(UnControllerParameters,CurLine) - CALL ReadEmptyLine(UnControllerParameters,CurLine) - !----------------------- DEBUG -------------------------- - CALL ReadEmptyLine(UnControllerParameters,CurLine) + ! Read all lines, first get the number of lines + NumLines = 0 + IOS = 0 + DO WHILE (IOS == 0) ! read the rest of the file (until an error occurs) + NumLines = NumLines + 1 + READ(UnControllerParameters,'(A)',IOSTAT=IOS) TmpLine + END DO !WHILE - CALL ParseInput(UnControllerParameters,CurLine,'LoggingLevel',accINFILE(1),CntrPar%LoggingLevel,ErrVar) + ALLOCATE(FileLines(NumLines)) + REWIND( UnControllerParameters ) - CALL ReadEmptyLine(UnControllerParameters,CurLine) + DO I_LINE = 1,NumLines + READ(UnControllerParameters,'(A)',IOSTAT=IOS) FileLines(I_LINE) + END DO + + !----------------------- DEBUG -------------------------- + CALL ParseInput(FileLines,'LoggingLevel', CntrPar%LoggingLevel, accINFILE(1), ErrVar) + CALL ParseInput(FileLines,'Echo', CntrPar%Echo, accINFILE(1), ErrVar) + IF (ErrVar%aviFAIL < 0) RETURN + + ! Set up echo file + UnEc = 0 + IF (CntrPar%Echo > 0) THEN + EchoFilename = TRIM(RootName)//'.RO.echo' + CALL GetNewUnit(UnEc, ErrVar) + OPEN(unit=UnEc, FILE=TRIM(EchoFilename), IOSTAT=ErrStat, ACTION='WRITE' ) + IF ( ErrStat /= 0 ) THEN + ErrVar%ErrMsg = 'Cannot open file '//TRIM( EchoFilename )//'. Another program may have locked it for writing.' + ErrVar%aviFAIL = 1 + ELSE + WRITE( UnEc, *) 'ROSCO ECHO file' + WRITE( UnEc, *) 'Generated on '//CurDate()//' at '//CurTime()//' using ROSCO-'//TRIM(rosco_version) + WRITE( UnEc, *) NEW_LINE('A') + WRITE( UnEc, *) 'Line Number',Tab,'Parameter',Tab,'Value' + WRITE( UnEc, *) '-----------------------------------------' + ENDIF + ENDIF !----------------- CONTROLLER FLAGS --------------------- - CALL ReadEmptyLine(UnControllerParameters,CurLine) - CALL ParseInput(UnControllerParameters,CurLine,'F_LPFType',accINFILE(1),CntrPar%F_LPFType,ErrVar) - CALL ParseInput(UnControllerParameters,CurLine,'F_NotchType',accINFILE(1),CntrPar%F_NotchType,ErrVar) - CALL ParseInput(UnControllerParameters,CurLine,'IPC_ControlMode',accINFILE(1),CntrPar%IPC_ControlMode,ErrVar) - CALL ParseInput(UnControllerParameters,CurLine,'VS_ControlMode',accINFILE(1),CntrPar%VS_ControlMode,ErrVar) - CALL ParseInput(UnControllerParameters,CurLine,'PC_ControlMode',accINFILE(1),CntrPar%PC_ControlMode,ErrVar) - CALL ParseInput(UnControllerParameters,CurLine,'Y_ControlMode',accINFILE(1),CntrPar%Y_ControlMode,ErrVar) - CALL ParseInput(UnControllerParameters,CurLine,'SS_Mode',accINFILE(1),CntrPar%SS_Mode,ErrVar) - CALL ParseInput(UnControllerParameters,CurLine,'WE_Mode',accINFILE(1),CntrPar%WE_Mode,ErrVar) - CALL ParseInput(UnControllerParameters,CurLine,'PS_Mode',accINFILE(1),CntrPar%PS_Mode,ErrVar) - CALL ParseInput(UnControllerParameters,CurLine,'SD_Mode',accINFILE(1),CntrPar%SD_Mode,ErrVar) - CALL ParseInput(UnControllerParameters,CurLine,'FL_Mode',accINFILE(1),CntrPar%FL_Mode,ErrVar) - CALL ParseInput(UnControllerParameters,CurLine,'TD_Mode',accINFILE(1),CntrPar%TD_Mode,ErrVar) - CALL ParseInput(UnControllerParameters,CurLine,'Flp_Mode',accINFILE(1),CntrPar%Flp_Mode,ErrVar) - CALL ParseInput(UnControllerParameters,CurLine,'OL_Mode',accINFILE(1),CntrPar%OL_Mode,ErrVar) - CALL ParseInput(UnControllerParameters,CurLine,'PA_Mode',accINFILE(1),CntrPar%PA_Mode,ErrVar) - CALL ParseInput(UnControllerParameters,CurLine,'PF_Mode',accINFILE(1),CntrPar%PF_Mode,ErrVar) - CALL ParseInput(UnControllerParameters,CurLine,'Ext_Mode',accINFILE(1),CntrPar%Ext_Mode,ErrVar) - CALL ParseInput(UnControllerParameters,CurLine,'ZMQ_Mode',accINFILE(1), CntrPar%ZMQ_Mode,ErrVar) - - CALL ReadEmptyLine(UnControllerParameters,CurLine) + CALL ParseInput(FileLines,'F_LPFType', CntrPar%F_LPFType, accINFILE(1), ErrVar, UnEc=UnEc) + CALL ParseInput(FileLines,'F_NotchType', CntrPar%F_NotchType, accINFILE(1), ErrVar, UnEc=UnEc) + CALL ParseInput(FileLines,'IPC_ControlMode', CntrPar%IPC_ControlMode, accINFILE(1), ErrVar, UnEc=UnEc) + CALL ParseInput(FileLines,'VS_ControlMode', CntrPar%VS_ControlMode, accINFILE(1), ErrVar, UnEc=UnEc) + CALL ParseInput(FileLines,'PC_ControlMode', CntrPar%PC_ControlMode, accINFILE(1), ErrVar, UnEc=UnEc) + CALL ParseInput(FileLines,'Y_ControlMode', CntrPar%Y_ControlMode, accINFILE(1), ErrVar, UnEc=UnEc) + CALL ParseInput(FileLines,'SS_Mode', CntrPar%SS_Mode, accINFILE(1), ErrVar, UnEc=UnEc) + CALL ParseInput(FileLines,'WE_Mode', CntrPar%WE_Mode, accINFILE(1), ErrVar, UnEc=UnEc) + CALL ParseInput(FileLines,'PS_Mode', CntrPar%PS_Mode, accINFILE(1), ErrVar, UnEc=UnEc) + CALL ParseInput(FileLines,'SD_Mode', CntrPar%SD_Mode, accINFILE(1), ErrVar, UnEc=UnEc) + CALL ParseInput(FileLines,'FL_Mode', CntrPar%FL_Mode, accINFILE(1), ErrVar, UnEc=UnEc) + CALL ParseInput(FileLines,'TD_Mode', CntrPar%TD_Mode, accINFILE(1), ErrVar, UnEc=UnEc) + CALL ParseInput(FileLines,'Flp_Mode', CntrPar%Flp_Mode, accINFILE(1), ErrVar, UnEc=UnEc) + CALL ParseInput(FileLines,'OL_Mode', CntrPar%OL_Mode, accINFILE(1), ErrVar, UnEc=UnEc) + CALL ParseInput(FileLines,'PA_Mode', CntrPar%PA_Mode, accINFILE(1), ErrVar, UnEc=UnEc) + CALL ParseInput(FileLines,'PF_Mode', CntrPar%PF_Mode, accINFILE(1), ErrVar, UnEc=UnEc) + CALL ParseInput(FileLines,'Ext_Mode', CntrPar%Ext_Mode, accINFILE(1), ErrVar, UnEc=UnEc) + CALL ParseInput(FileLines,'ZMQ_Mode', CntrPar%ZMQ_Mode, accINFILE(1), ErrVar, UnEc=UnEc) + CALL ParseInput(FileLines,'CC_Mode', CntrPar%CC_Mode, accINFILE(1), ErrVar, UnEc=UnEc) + CALL ParseInput(FileLines,'StC_Mode', CntrPar%StC_Mode, accINFILE(1), ErrVar, UnEc=UnEc) + IF (ErrVar%aviFAIL < 0) RETURN !----------------- FILTER CONSTANTS --------------------- - CALL ReadEmptyLine(UnControllerParameters,CurLine) - CALL ParseInput(UnControllerParameters,CurLine,'F_LPFCornerFreq',accINFILE(1),CntrPar%F_LPFCornerFreq,ErrVar) - CALL ParseInput(UnControllerParameters,CurLine,'F_LPFDamping',accINFILE(1),CntrPar%F_LPFDamping,ErrVar) - CALL ParseInput(UnControllerParameters,CurLine,'F_NotchCornerFreq',accINFILE(1),CntrPar%F_NotchCornerFreq,ErrVar) - CALL ParseAry(UnControllerParameters, CurLine, 'F_NotchBetaNumDen', CntrPar%F_NotchBetaNumDen, 2, accINFILE(1), ErrVar ) - CALL ParseInput(UnControllerParameters,CurLine,'F_SSCornerFreq',accINFILE(1),CntrPar%F_SSCornerFreq,ErrVar) - CALL ParseInput(UnControllerParameters,CurLine,'F_WECornerFreq',accINFILE(1),CntrPar%F_WECornerFreq,ErrVar) - CALL ParseInput(UnControllerParameters,CurLine,'F_YawErr',accINFILE(1),CntrPar%F_YawErr, ErrVar) - CALL ParseAry(UnControllerParameters, CurLine, 'F_FlCornerFreq', CntrPar%F_FlCornerFreq, 2, accINFILE(1), ErrVar ) - CALL ParseInput(UnControllerParameters,CurLine,'F_FlHighPassFreq',accINFILE(1),CntrPar%F_FlHighPassFreq,ErrVar) - CALL ParseAry(UnControllerParameters, CurLine, 'F_FlpCornerFreq', CntrPar%F_FlpCornerFreq, 2, accINFILE(1), ErrVar ) - CALL ReadEmptyLine(UnControllerParameters,CurLine) + CALL ParseInput(FileLines, 'F_LPFCornerFreq', CntrPar%F_LPFCornerFreq, accINFILE(1), ErrVar, .FALSE., UnEc) + CALL ParseInput(FileLines, 'F_LPFDamping', CntrPar%F_LPFDamping, accINFILE(1), ErrVar, CntrPar%F_LPFType == 1, UnEc) + CALL ParseInput(FileLines, 'F_NotchCornerFreq', CntrPar%F_NotchCornerFreq, accINFILE(1), ErrVar, CntrPar%F_NotchType == 0, UnEc) + CALL ParseAry( FileLines, 'F_NotchBetaNumDen', CntrPar%F_NotchBetaNumDen, 2, accINFILE(1), ErrVar, CntrPar%F_NotchType == 0, UnEc) + CALL ParseInput(FileLines, 'F_SSCornerFreq', CntrPar%F_SSCornerFreq, accINFILE(1), ErrVar, CntrPar%SS_Mode == 0, UnEc) + CALL ParseInput(FileLines, 'F_WECornerFreq', CntrPar%F_WECornerFreq, accINFILE(1), ErrVar, .FALSE., UnEc) + CALL ParseInput(FileLines, 'F_YawErr', CntrPar%F_YawErr, accINFILE(1), ErrVar, CntrPar%Y_ControlMode == 0, UnEc) + CALL ParseAry( FileLines, 'F_FlCornerFreq', CntrPar%F_FlCornerFreq, 2, accINFILE(1), ErrVar, CntrPar%FL_Mode == 0, UnEc) + CALL ParseInput(FileLines, 'F_FlHighPassFreq', CntrPar%F_FlHighPassFreq, accINFILE(1), ErrVar, CntrPar%FL_Mode == 0, UnEc) + CALL ParseAry( FileLines, 'F_FlpCornerFreq', CntrPar%F_FlpCornerFreq, 2, accINFILE(1), ErrVar, CntrPar%Flp_Mode == 0, UnEc) + IF (ErrVar%aviFAIL < 0) RETURN !----------- BLADE PITCH CONTROLLER CONSTANTS ----------- - CALL ReadEmptyLine(UnControllerParameters,CurLine) - CALL ParseInput(UnControllerParameters,CurLine,'PC_GS_n',accINFILE(1),CntrPar%PC_GS_n,ErrVar) - CALL ParseAry(UnControllerParameters, CurLine, 'PC_GS_angles', CntrPar%PC_GS_angles, CntrPar%PC_GS_n, accINFILE(1), ErrVar ) - CALL ParseAry(UnControllerParameters, CurLine, 'PC_GS_KP', CntrPar%PC_GS_KP, CntrPar%PC_GS_n, accINFILE(1), ErrVar ) - CALL ParseAry(UnControllerParameters, CurLine, 'PC_GS_KI', CntrPar%PC_GS_KI, CntrPar%PC_GS_n, accINFILE(1), ErrVar ) - CALL ParseAry(UnControllerParameters, CurLine, 'PC_GS_KD', CntrPar%PC_GS_KD, CntrPar%PC_GS_n, accINFILE(1), ErrVar ) - CALL ParseAry(UnControllerParameters, CurLine, 'PC_GS_TF', CntrPar%PC_GS_TF, CntrPar%PC_GS_n, accINFILE(1), ErrVar ) - CALL ParseInput(UnControllerParameters,CurLine,'PC_MaxPit',accINFILE(1),CntrPar%PC_MaxPit,ErrVar) - CALL ParseInput(UnControllerParameters,CurLine,'PC_MinPit',accINFILE(1),CntrPar%PC_MinPit,ErrVar) - CALL ParseInput(UnControllerParameters,CurLine,'PC_MaxRat',accINFILE(1),CntrPar%PC_MaxRat,ErrVar) - CALL ParseInput(UnControllerParameters,CurLine,'PC_MinRat',accINFILE(1),CntrPar%PC_MinRat,ErrVar) - CALL ParseInput(UnControllerParameters,CurLine,'PC_RefSpd',accINFILE(1),CntrPar%PC_RefSpd,ErrVar) - CALL ParseInput(UnControllerParameters,CurLine,'PC_FinePit',accINFILE(1),CntrPar%PC_FinePit,ErrVar) - CALL ParseInput(UnControllerParameters,CurLine,'PC_Switch',accINFILE(1),CntrPar%PC_Switch,ErrVar) - CALL ReadEmptyLine(UnControllerParameters,CurLine) + CALL ParseInput(FileLines, 'PC_GS_n', CntrPar%PC_GS_n, accINFILE(1), ErrVar, CntrPar%PC_ControlMode == 0, UnEc) + CALL ParseAry( FileLines, 'PC_GS_angles', CntrPar%PC_GS_angles, CntrPar%PC_GS_n, accINFILE(1), ErrVar, CntrPar%PC_ControlMode == 0, UnEc) + CALL ParseAry( FileLines, 'PC_GS_KP', CntrPar%PC_GS_KP, CntrPar%PC_GS_n, accINFILE(1), ErrVar, CntrPar%PC_ControlMode == 0, UnEc) + CALL ParseAry( FileLines, 'PC_GS_KI', CntrPar%PC_GS_KI, CntrPar%PC_GS_n, accINFILE(1), ErrVar, CntrPar%PC_ControlMode == 0, UnEc) + CALL ParseAry( FileLines, 'PC_GS_KD', CntrPar%PC_GS_KD, CntrPar%PC_GS_n, accINFILE(1), ErrVar, CntrPar%PC_ControlMode == 0, UnEc) + CALL ParseAry( FileLines, 'PC_GS_TF', CntrPar%PC_GS_TF, CntrPar%PC_GS_n, accINFILE(1), ErrVar, CntrPar%PC_ControlMode == 0, UnEc) + CALL ParseInput(FileLines, 'PC_MaxPit', CntrPar%PC_MaxPit, accINFILE(1), ErrVar, CntrPar%PC_ControlMode == 0, UnEc) + CALL ParseInput(FileLines, 'PC_MinPit', CntrPar%PC_MinPit, accINFILE(1), ErrVar, CntrPar%PC_ControlMode == 0, UnEc) + CALL ParseInput(FileLines, 'PC_MaxRat', CntrPar%PC_MaxRat, accINFILE(1), ErrVar, CntrPar%PC_ControlMode == 0, UnEc) + CALL ParseInput(FileLines, 'PC_MinRat', CntrPar%PC_MinRat, accINFILE(1), ErrVar, CntrPar%PC_ControlMode == 0, UnEc) + CALL ParseInput(FileLines, 'PC_RefSpd', CntrPar%PC_RefSpd, accINFILE(1), ErrVar, CntrPar%PC_ControlMode == 0, UnEc) + CALL ParseInput(FileLines, 'PC_FinePit', CntrPar%PC_FinePit, accINFILE(1), ErrVar, CntrPar%PC_ControlMode == 0, UnEc) + CALL ParseInput(FileLines, 'PC_Switch', CntrPar%PC_Switch, accINFILE(1), ErrVar, CntrPar%PC_ControlMode == 0, UnEc) + IF (ErrVar%aviFAIL < 0) RETURN !------------------- IPC CONSTANTS ----------------------- - CALL ReadEmptyLine(UnControllerParameters,CurLine) - CALL ParseAry(UnControllerParameters, CurLine, 'IPC_Vramp', CntrPar%IPC_Vramp, 2, accINFILE(1), ErrVar ) - CALL ParseInput(UnControllerParameters,CurLine,'IPC_SatMode',accINFILE(1),CntrPar%IPC_SatMode,ErrVar) - CALL ParseInput(UnControllerParameters,CurLine,'IPC_IntSat',accINFILE(1),CntrPar%IPC_IntSat,ErrVar) - CALL ParseAry(UnControllerParameters, CurLine, 'IPC_KP', CntrPar%IPC_KP, 2, accINFILE(1), ErrVar ) - CALL ParseAry(UnControllerParameters, CurLine, 'IPC_KI', CntrPar%IPC_KI, 2, accINFILE(1), ErrVar ) - CALL ParseAry(UnControllerParameters, CurLine, 'IPC_aziOffset', CntrPar%IPC_aziOffset, 2, accINFILE(1), ErrVar ) - CALL ParseInput(UnControllerParameters,CurLine,'IPC_CornerFreqAct',accINFILE(1),CntrPar%IPC_CornerFreqAct,ErrVar) - CALL ReadEmptyLine(UnControllerParameters,CurLine) + CALL ParseAry( FileLines, 'IPC_Vramp', CntrPar%IPC_Vramp, 2, accINFILE(1), ErrVar, CntrPar%IPC_ControlMode == 0, UnEc) + CALL ParseInput(FileLines, 'IPC_SatMode', CntrPar%IPC_SatMode, accINFILE(1), ErrVar, CntrPar%IPC_ControlMode == 0, UnEc) + CALL ParseInput(FileLines, 'IPC_IntSat', CntrPar%IPC_IntSat, accINFILE(1), ErrVar, CntrPar%IPC_ControlMode == 0, UnEc) + CALL ParseAry( FileLines, 'IPC_KP', CntrPar%IPC_KP, 2, accINFILE(1), ErrVar, CntrPar%IPC_ControlMode == 0, UnEc) + CALL ParseAry( FileLines, 'IPC_KI', CntrPar%IPC_KI, 2, accINFILE(1), ErrVar, CntrPar%IPC_ControlMode == 0, UnEc) + CALL ParseAry( FileLines, 'IPC_aziOffset', CntrPar%IPC_aziOffset, 2, accINFILE(1), ErrVar, CntrPar%IPC_ControlMode == 0, UnEc) + CALL ParseInput(FileLines, 'IPC_CornerFreqAct',CntrPar%IPC_CornerFreqAct, accINFILE(1), ErrVar, CntrPar%IPC_ControlMode == 0, UnEc) + IF (ErrVar%aviFAIL < 0) RETURN !------------ VS TORQUE CONTROL CONSTANTS ---------------- - CALL ReadEmptyLine(UnControllerParameters,CurLine) - CALL ParseInput(UnControllerParameters,CurLine,'VS_GenEff',accINFILE(1),CntrPar%VS_GenEff,ErrVar) - CALL ParseInput(UnControllerParameters,CurLine,'VS_ArSatTq',accINFILE(1),CntrPar%VS_ArSatTq,ErrVar) - CALL ParseInput(UnControllerParameters,CurLine,'VS_MaxRat',accINFILE(1),CntrPar%VS_MaxRat,ErrVar) - CALL ParseInput(UnControllerParameters,CurLine,'VS_MaxTq',accINFILE(1),CntrPar%VS_MaxTq,ErrVar) - CALL ParseInput(UnControllerParameters,CurLine,'VS_MinTq',accINFILE(1),CntrPar%VS_MinTq,ErrVar) - CALL ParseInput(UnControllerParameters,CurLine,'VS_MinOMSpd',accINFILE(1),CntrPar%VS_MinOMSpd,ErrVar) - CALL ParseInput(UnControllerParameters,CurLine,'VS_Rgn2K',accINFILE(1),CntrPar%VS_Rgn2K,ErrVar) - CALL ParseInput(UnControllerParameters,CurLine,'VS_RtPwr',accINFILE(1),CntrPar%VS_RtPwr,ErrVar) - CALL ParseInput(UnControllerParameters,CurLine,'VS_RtTq',accINFILE(1),CntrPar%VS_RtTq,ErrVar) - CALL ParseInput(UnControllerParameters,CurLine,'VS_RefSpd',accINFILE(1),CntrPar%VS_RefSpd,ErrVar) - CALL ParseInput(UnControllerParameters,CurLine,'VS_n',accINFILE(1),CntrPar%VS_n,ErrVar) - CALL ParseAry(UnControllerParameters, CurLine, 'VS_KP', CntrPar%VS_KP, CntrPar%VS_n, accINFILE(1), ErrVar ) - CALL ParseAry(UnControllerParameters, CurLine, 'VS_KI', CntrPar%VS_KI, CntrPar%VS_n, accINFILE(1), ErrVar ) - CALL ParseInput(UnControllerParameters,CurLine,'VS_TSRopt',accINFILE(1),CntrPar%VS_TSRopt,ErrVar) - CALL ReadEmptyLine(UnControllerParameters,CurLine) + CALL ParseInput(FileLines, 'VS_GenEff', CntrPar%VS_GenEff, accINFILE(1), ErrVar, .FALSE., UnEc) + CALL ParseInput(FileLines, 'VS_ArSatTq', CntrPar%VS_ArSatTq, accINFILE(1), ErrVar, CntrPar%VS_ControlMode > 1, UnEc) + CALL ParseInput(FileLines, 'VS_MaxRat', CntrPar%VS_MaxRat, accINFILE(1), ErrVar, CntrPar%VS_ControlMode > 1, UnEc) + CALL ParseInput(FileLines, 'VS_MaxTq', CntrPar%VS_MaxTq, accINFILE(1), ErrVar, .FALSE., UnEc) + CALL ParseInput(FileLines, 'VS_MinTq', CntrPar%VS_MinTq, accINFILE(1), ErrVar, .FALSE., UnEc) + CALL ParseInput(FileLines, 'VS_MinOMSpd', CntrPar%VS_MinOMSpd, accINFILE(1), ErrVar) ! Default 0 is fin, UnEce + CALL ParseInput(FileLines, 'VS_Rgn2K', CntrPar%VS_Rgn2K, accINFILE(1), ErrVar, CntrPar%VS_ControlMode > 1, UnEc) + CALL ParseInput(FileLines, 'VS_RtPwr', CntrPar%VS_RtPwr, accINFILE(1), ErrVar, .FALSE., UnEc) + CALL ParseInput(FileLines, 'VS_RtTq', CntrPar%VS_RtTq, accINFILE(1), ErrVar, .FALSE., UnEc) + CALL ParseInput(FileLines, 'VS_RefSpd', CntrPar%VS_RefSpd, accINFILE(1), ErrVar, .FALSE., UnEc) + CALL ParseInput(FileLines, 'VS_n', CntrPar%VS_n, accINFILE(1), ErrVar, .FALSE., UnEc) + CALL ParseAry( FileLines, 'VS_KP', CntrPar%VS_KP, CntrPar%VS_n, accINFILE(1), ErrVar, .FALSE., UnEc) + CALL ParseAry( FileLines, 'VS_KI', CntrPar%VS_KI, CntrPar%VS_n, accINFILE(1), ErrVar, .FALSE., UnEc) + CALL ParseInput(FileLines, 'VS_TSRopt', CntrPar%VS_TSRopt, accINFILE(1), ErrVar, CntrPar%VS_ControlMode < 2, UnEc) + IF (ErrVar%aviFAIL < 0) RETURN !------- Setpoint Smoother -------------------------------- - CALL ReadEmptyLine(UnControllerParameters,CurLine) - CALL ParseInput(UnControllerParameters,CurLine,'SS_VSGain',accINFILE(1),CntrPar%SS_VSGain,ErrVar) - CALL ParseInput(UnControllerParameters,CurLine,'SS_PCGain',accINFILE(1),CntrPar%SS_PCGain,ErrVar) - CALL ReadEmptyLine(UnControllerParameters,CurLine) + CALL ParseInput(FileLines, 'SS_VSGain', CntrPar%SS_VSGain, accINFILE(1), ErrVar, CntrPar%SS_Mode == 0, UnEc) + CALL ParseInput(FileLines, 'SS_PCGain', CntrPar%SS_PCGain, accINFILE(1), ErrVar, CntrPar%SS_Mode == 0, UnEc) + IF (ErrVar%aviFAIL < 0) RETURN !------------ WIND SPEED ESTIMATOR CONTANTS -------------- - CALL ReadEmptyLine(UnControllerParameters,CurLine) - CALL ParseInput(UnControllerParameters,CurLine,'WE_BladeRadius',accINFILE(1),CntrPar%WE_BladeRadius,ErrVar) - CALL ParseInput(UnControllerParameters,CurLine,'WE_CP_n',accINFILE(1),CntrPar%WE_CP_n,ErrVar) - CALL ParseAry(UnControllerParameters, CurLine, 'WE_CP', CntrPar%WE_CP, CntrPar%WE_CP_n, accINFILE(1), ErrVar, .FALSE. ) - CALL ParseInput(UnControllerParameters,CurLine,'WE_Gamma',accINFILE(1),CntrPar%WE_Gamma,ErrVar) - CALL ParseInput(UnControllerParameters,CurLine,'WE_GearboxRatio',accINFILE(1),CntrPar%WE_GearboxRatio,ErrVar) - CALL ParseInput(UnControllerParameters,CurLine,'WE_Jtot',accINFILE(1),CntrPar%WE_Jtot,ErrVar) - CALL ParseInput(UnControllerParameters,CurLine,'WE_RhoAir',accINFILE(1),CntrPar%WE_RhoAir,ErrVar) - CALL ParseInput(UnControllerParameters,CurLine,'PerfFileName',accINFILE(1),CntrPar%PerfFileName,ErrVar) - CALL ParseAry(UnControllerParameters, CurLine, 'PerfTableSize', CntrPar%PerfTableSize, 2, accINFILE(1), ErrVar ) - CALL ParseInput(UnControllerParameters,CurLine,'WE_FOPoles_N',accINFILE(1),CntrPar%WE_FOPoles_N,ErrVar) - CALL ParseAry(UnControllerParameters, CurLine, 'WE_FOPoles_v', CntrPar%WE_FOPoles_v, CntrPar%WE_FOPoles_N, accINFILE(1), ErrVar ) - CALL ParseAry(UnControllerParameters, CurLine, 'WE_FOPoles', CntrPar%WE_FOPoles, CntrPar%WE_FOPoles_N, accINFILE(1), ErrVar ) - CALL ReadEmptyLine(UnControllerParameters,CurLine) + CALL ParseInput(FileLines, 'WE_BladeRadius', CntrPar%WE_BladeRadius, accINFILE(1), ErrVar, .FALSE., UnEc) + CALL ParseInput(FileLines, 'WE_Gamma', CntrPar%WE_Gamma, accINFILE(1), ErrVar, CntrPar%WE_Mode .NE. 1, UnEc) + CALL ParseInput(FileLines, 'WE_GearboxRatio', CntrPar%WE_GearboxRatio, accINFILE(1), ErrVar, .FALSE., UnEc) + CALL ParseInput(FileLines, 'WE_Jtot', CntrPar%WE_Jtot, accINFILE(1), ErrVar, CntrPar%WE_Mode == 0, UnEc) + CALL ParseInput(FileLines, 'WE_RhoAir', CntrPar%WE_RhoAir, accINFILE(1), ErrVar, CntrPar%WE_Mode .NE. 2, UnEc) + CALL ParseInput(FileLines, 'PerfFileName', CntrPar%PerfFileName, accINFILE(1), ErrVar, CntrPar%WE_Mode == 0, UnEc ) + CALL ParseAry( FileLines, 'PerfTableSize', CntrPar%PerfTableSize, 2, accINFILE(1), ErrVar, CntrPar%WE_Mode == 0, UnEc) + CALL ParseInput(FileLines, 'WE_FOPoles_N', CntrPar%WE_FOPoles_N, accINFILE(1), ErrVar, CntrPar%WE_Mode .NE. 2, UnEc) + CALL ParseAry(FileLines, 'WE_FOPoles_v', CntrPar%WE_FOPoles_v, CntrPar%WE_FOPoles_N, accINFILE(1), ErrVar, CntrPar%WE_Mode .NE. 2, UnEc) + CALL ParseAry(FileLines, 'WE_FOPoles', CntrPar%WE_FOPoles, CntrPar%WE_FOPoles_N, accINFILE(1), ErrVar, CntrPar%WE_Mode .NE. 2, UnEc) + IF (ErrVar%aviFAIL < 0) RETURN + + ! Retired WSE inputs: not used anywhere in code + ! CALL ParseInput(FileLines, 'WE_CP_n',accINFILE(1),CntrPar%WE_CP_n,ErrVar, UnEc) + ! CALL ParseAry( FileLines, 'WE_CP', CntrPar%WE_CP, CntrPar%WE_CP_n, accINFILE(1), ErrVar, .FALSE. , UnEc) !-------------- YAW CONTROLLER CONSTANTS ----------------- - CALL ReadEmptyLine(UnControllerParameters,CurLine) - CALL ParseInput(UnControllerParameters,CurLine,'Y_uSwitch',accINFILE(1),CntrPar%Y_uSwitch,ErrVar) - CALL ParseAry(UnControllerParameters, CurLine, 'Y_ErrThresh', CntrPar%Y_ErrThresh, 2, accINFILE(1), ErrVar ) - CALL ParseInput(UnControllerParameters,CurLine,'Y_Rate',accINFILE(1),CntrPar%Y_Rate,ErrVar) - CALL ParseInput(UnControllerParameters,CurLine,'Y_MErrSet',accINFILE(1),CntrPar%Y_MErrSet,ErrVar) - CALL ParseInput(UnControllerParameters,CurLine,'Y_IPC_IntSat',accINFILE(1),CntrPar%Y_IPC_IntSat,ErrVar) - CALL ParseInput(UnControllerParameters, CurLine,'Y_IPC_KP', accINFILE(1), CntrPar%Y_IPC_KP, ErrVar ) - CALL ParseInput(UnControllerParameters, CurLine,'Y_IPC_KI', accINFILE(1), CntrPar%Y_IPC_KI, ErrVar ) - CALL ReadEmptyLine(UnControllerParameters,CurLine) + CALL ParseInput(FileLines, 'Y_uSwitch', CntrPar%Y_uSwitch, accINFILE(1), ErrVar, CntrPar%Y_ControlMode == 0, UnEc) + CALL ParseAry( FileLines, 'Y_ErrThresh', CntrPar%Y_ErrThresh, 2, accINFILE(1), ErrVar, CntrPar%Y_ControlMode == 0, UnEc) + CALL ParseInput(FileLines, 'Y_Rate', CntrPar%Y_Rate, accINFILE(1), ErrVar, CntrPar%Y_ControlMode == 0, UnEc) + CALL ParseInput(FileLines, 'Y_MErrSet', CntrPar%Y_MErrSet, accINFILE(1), ErrVar, CntrPar%Y_ControlMode == 0, UnEc) + CALL ParseInput(FileLines, 'Y_IPC_IntSat', CntrPar%Y_IPC_IntSat, accINFILE(1), ErrVar, CntrPar%Y_ControlMode == 0, UnEc) + CALL ParseInput(FileLines, 'Y_IPC_KP', CntrPar%Y_IPC_KP, accINFILE(1), ErrVar, CntrPar%Y_ControlMode == 0, UnEc) + CALL ParseInput(FileLines, 'Y_IPC_KI', CntrPar%Y_IPC_KI, accINFILE(1), ErrVar, CntrPar%Y_ControlMode == 0, UnEc) + IF (ErrVar%aviFAIL < 0) RETURN !------------ FORE-AFT TOWER DAMPER CONSTANTS ------------ - CALL ReadEmptyLine(UnControllerParameters,CurLine) - CALL ParseInput(UnControllerParameters,CurLine,'FA_KI',accINFILE(1),CntrPar%FA_KI,ErrVar) - ! Don't check this name until we make an API change - CALL ParseInput(UnControllerParameters,CurLine,'FA_HPFCornerFreq',accINFILE(1),CntrPar%FA_HPFCornerFreq,ErrVar,.FALSE.) - CALL ParseInput(UnControllerParameters,CurLine,'FA_IntSat',accINFILE(1),CntrPar%FA_IntSat,ErrVar) - CALL ReadEmptyLine(UnControllerParameters,CurLine) + CALL ParseInput(FileLines, 'FA_KI', CntrPar%FA_KI, accINFILE(1), ErrVar, .NOT. ((CntrPar%TD_Mode > 0) .OR. (CntrPar%Y_ControlMode == 2)), UnEc) + CALL ParseInput(FileLines, 'FA_HPFCornerFreq', CntrPar%FA_HPFCornerFreq, accINFILE(1), ErrVar, .NOT. ((CntrPar%TD_Mode > 0) .OR. (CntrPar%Y_ControlMode == 2)), UnEc) + CALL ParseInput(FileLines, 'FA_IntSat', CntrPar%FA_IntSat, accINFILE(1), ErrVar, .NOT. ((CntrPar%TD_Mode > 0) .OR. (CntrPar%Y_ControlMode == 2)), UnEc) + IF (ErrVar%aviFAIL < 0) RETURN !------------ PEAK SHAVING ------------ - CALL ReadEmptyLine(UnControllerParameters,CurLine) - CALL ParseInput(UnControllerParameters,CurLine,'PS_BldPitchMin_N',accINFILE(1),CntrPar%PS_BldPitchMin_N,ErrVar) - CALL ParseAry(UnControllerParameters, CurLine, 'PS_WindSpeeds', CntrPar%PS_WindSpeeds, CntrPar%PS_BldPitchMin_N, accINFILE(1), ErrVar ) - CALL ParseAry(UnControllerParameters, CurLine, 'PS_BldPitchMin', CntrPar%PS_BldPitchMin, CntrPar%PS_BldPitchMin_N, accINFILE(1), ErrVar ) - CALL ReadEmptyLine(UnControllerParameters,CurLine) + CALL ParseInput(FileLines, 'PS_BldPitchMin_N', CntrPar%PS_BldPitchMin_N, accINFILE(1), ErrVar, CntrPar%PS_Mode == 0, UnEc) + CALL ParseAry( FileLines, 'PS_WindSpeeds', CntrPar%PS_WindSpeeds, CntrPar%PS_BldPitchMin_N, accINFILE(1), ErrVar, CntrPar%PS_Mode == 0, UnEc) + CALL ParseAry( FileLines, 'PS_BldPitchMin', CntrPar%PS_BldPitchMin, CntrPar%PS_BldPitchMin_N, accINFILE(1), ErrVar, CntrPar%PS_Mode == 0, UnEc) + IF (ErrVar%aviFAIL < 0) RETURN !------------ SHUTDOWN ------------ - CALL ReadEmptyLine(UnControllerParameters,CurLine) - CALL ParseInput(UnControllerParameters,CurLine,'SD_MaxPit',accINFILE(1),CntrPar%SD_MaxPit,ErrVar) - CALL ParseInput(UnControllerParameters,CurLine,'SD_CornerFreq',accINFILE(1),CntrPar%SD_CornerFreq,ErrVar) - CALL ReadEmptyLine(UnControllerParameters,CurLine) + CALL ParseInput(FileLines, 'SD_MaxPit', CntrPar%SD_MaxPit, accINFILE(1), ErrVar, CntrPar%SD_Mode == 0, UnEc) + CALL ParseInput(FileLines, 'SD_CornerFreq', CntrPar%SD_CornerFreq, accINFILE(1), ErrVar, CntrPar%SD_Mode == 0, UnEc) + IF (ErrVar%aviFAIL < 0) RETURN !------------ FLOATING ------------ - CALL ReadEmptyLine(UnControllerParameters,CurLine) - CALL ParseInput(UnControllerParameters,CurLine,'Fl_Kp',accINFILE(1),CntrPar%Fl_Kp,ErrVar) - CALL ReadEmptyLine(UnControllerParameters,CurLine) + CALL ParseInput(FileLines, 'Fl_Kp', CntrPar%Fl_Kp, accINFILE(1), ErrVar, CntrPar%FL_Mode == 0, UnEc) + IF (ErrVar%aviFAIL < 0) RETURN !------------ Flaps ------------ - CALL ReadEmptyLine(UnControllerParameters,CurLine) - CALL ParseInput(UnControllerParameters,CurLine,'Flp_Angle',accINFILE(1),CntrPar%Flp_Angle,ErrVar) - CALL ParseInput(UnControllerParameters,CurLine,'Flp_Kp',accINFILE(1),CntrPar%Flp_Kp,ErrVar) - CALL ParseInput(UnControllerParameters,CurLine,'Flp_Ki',accINFILE(1),CntrPar%Flp_Ki,ErrVar) - CALL ParseInput(UnControllerParameters,CurLine,'Flp_MaxPit',accINFILE(1),CntrPar%Flp_MaxPit,ErrVar) - CALL ReadEmptyLine(UnControllerParameters,CurLine) + CALL ParseInput(FileLines, 'Flp_Angle', CntrPar%Flp_Angle, accINFILE(1), ErrVar, CntrPar%Flp_Mode == 0, UnEc) + CALL ParseInput(FileLines, 'Flp_Kp', CntrPar%Flp_Kp, accINFILE(1), ErrVar, CntrPar%Flp_Mode == 0, UnEc) + CALL ParseInput(FileLines, 'Flp_Ki', CntrPar%Flp_Ki, accINFILE(1), ErrVar, CntrPar%Flp_Mode == 0, UnEc) + CALL ParseInput(FileLines, 'Flp_MaxPit', CntrPar%Flp_MaxPit, accINFILE(1), ErrVar, CntrPar%Flp_Mode == 0, UnEc) + IF (ErrVar%aviFAIL < 0) RETURN !------------ Open loop input ------------ - CALL ReadEmptyLine(UnControllerParameters,CurLine) - CALL ParseInput(UnControllerParameters,CurLine,'OL_Filename',accINFILE(1),CntrPar%OL_Filename,ErrVar) - CALL ParseInput(UnControllerParameters,CurLine,'Ind_Breakpoint',accINFILE(1),CntrPar%Ind_Breakpoint,ErrVar) - CALL ParseInput(UnControllerParameters,CurLine,'Ind_BldPitch',accINFILE(1),CntrPar%Ind_BldPitch,ErrVar) - CALL ParseInput(UnControllerParameters,CurLine,'Ind_GenTq',accINFILE(1),CntrPar%Ind_GenTq,ErrVar) - CALL ParseInput(UnControllerParameters,CurLine,'Ind_YawRate',accINFILE(1),CntrPar%Ind_YawRate,ErrVar) - CALL ReadEmptyLine(UnControllerParameters,CurLine) - + ! Indices can be left 0 by default, checked later + CALL ParseInput(FileLines, 'OL_Filename', CntrPar%OL_Filename, accINFILE(1), ErrVar, CntrPar%OL_Mode == 0, UnEc) + CALL ParseInput(FileLines, 'Ind_Breakpoint', CntrPar%Ind_Breakpoint, accINFILE(1), ErrVar, UnEc=UnEc) + CALL ParseInput(FileLines, 'Ind_BldPitch', CntrPar%Ind_BldPitch, accINFILE(1), ErrVar, UnEc=UnEc) + CALL ParseInput(FileLines, 'Ind_GenTq', CntrPar%Ind_GenTq, accINFILE(1), ErrVar, UnEc=UnEc) + CALL ParseInput(FileLines, 'Ind_YawRate', CntrPar%Ind_YawRate, accINFILE(1), ErrVar, UnEc=UnEc) + IF (ErrVar%aviFAIL < 0) RETURN + !------------ Pitch Actuator Inputs ------------ - CALL ReadEmptyLine(UnControllerParameters,CurLine) - CALL ParseInput(UnControllerParameters,CurLine,'PA_CornerFreq',accINFILE(1),CntrPar%PA_CornerFreq,ErrVar) - CALL ParseInput(UnControllerParameters,CurLine,'PA_Damping',accINFILE(1),CntrPar%PA_Damping,ErrVar) - CALL ReadEmptyLine(UnControllerParameters,CurLine) + CALL ParseInput(FileLines, 'PA_CornerFreq', CntrPar%PA_CornerFreq, accINFILE(1), ErrVar, CntrPar%PA_Mode == 0, UnEc) + CALL ParseInput(FileLines, 'PA_Damping', CntrPar%PA_Damping, accINFILE(1), ErrVar, CntrPar%PA_Mode == 0, UnEc) + IF (ErrVar%aviFAIL < 0) RETURN !------------ Pitch Actuator Faults ------------ - CALL ReadEmptyLine(UnControllerParameters,CurLine) - CALL ParseAry(UnControllerParameters, CurLine,'PF_Offsets', CntrPar%PF_Offsets, 3, accINFILE(1), ErrVar) - CALL ReadEmptyLine(UnControllerParameters,CurLine) - + CALL ParseAry(FileLines, 'PF_Offsets', CntrPar%PF_Offsets, 3, accINFILE(1), ErrVar, CntrPar%PF_Mode == 0, UnEc) + IF (ErrVar%aviFAIL < 0) RETURN + !------------ External control interface ------------ - CALL ReadEmptyLine(UnControllerParameters,CurLine) - CALL ParseInput(UnControllerParameters,CurLine,'DLL_FileName',accINFILE(1),CntrPar%DLL_FileName,ErrVar) - CALL ParseInput(UnControllerParameters,CurLine,'DLL_InFile',accINFILE(1),CntrPar%DLL_InFile,ErrVar) - CALL ParseInput(UnControllerParameters,CurLine,'DLL_ProcName',accINFILE(1),CntrPar%DLL_ProcName,ErrVar) - CALL ReadEmptyLine(UnControllerParameters,CurLine) + CALL ParseInput(FileLines, 'DLL_FileName', CntrPar%DLL_FileName, accINFILE(1), ErrVar, CntrPar%Ext_Mode == 0, UnEc) + CALL ParseInput(FileLines, 'DLL_InFile', CntrPar%DLL_InFile, accINFILE(1), ErrVar, CntrPar%Ext_Mode == 0, UnEc) + CALL ParseInput(FileLines, 'DLL_ProcName', CntrPar%DLL_ProcName, accINFILE(1), ErrVar, CntrPar%Ext_Mode == 0, UnEc) + IF (ErrVar%aviFAIL < 0) RETURN !------------ ZeroMQ ------------ - CALL ReadEmptyLine(UnControllerParameters,CurLine) - CALL ParseInput(UnControllerParameters,CurLine,'ZMQ_CommAddress',accINFILE(1), CntrPar%ZMQ_CommAddress,ErrVar) - CALL ParseInput(UnControllerParameters,CurLine,'ZMQ_UpdatePeriod',accINFILE(1), CntrPar%ZMQ_UpdatePeriod,ErrVar) + CALL ParseInput(FileLines, 'ZMQ_CommAddress', CntrPar%ZMQ_CommAddress, accINFILE(1), ErrVar, CntrPar%ZMQ_Mode == 0, UnEc) + CALL ParseInput(FileLines, 'ZMQ_UpdatePeriod', CntrPar%ZMQ_UpdatePeriod, accINFILE(1), ErrVar, CntrPar%ZMQ_Mode == 0, UnEc) + IF (ErrVar%aviFAIL < 0) RETURN - ! Fix Paths (add relative paths if called from another dir) - IF (PathIsRelative(CntrPar%PerfFileName)) CntrPar%PerfFileName = TRIM(PriPath)//TRIM(CntrPar%PerfFileName) - IF (PathIsRelative(CntrPar%OL_Filename)) CntrPar%OL_Filename = TRIM(PriPath)//TRIM(CntrPar%OL_Filename) - - ! Read open loop input, if desired - IF (CntrPar%OL_Mode == 1) THEN - OL_String = '' ! Display string - OL_Count = 1 - IF (CntrPar%Ind_BldPitch > 0) THEN - OL_String = TRIM(OL_String)//' BldPitch ' - OL_Count = OL_Count + 1 - ENDIF + !------------- Cable Control ----- + CALL ParseInput(FileLines, 'CC_Group_N', CntrPar%CC_Group_N, accINFILE(1), ErrVar, CntrPar%CC_Mode == 0, UnEc) + CALL ParseAry( FileLines, 'CC_GroupIndex', CntrPar%CC_GroupIndex, CntrPar%CC_Group_N, accINFILE(1), ErrVar, CntrPar%CC_Mode == 0, UnEc) + CALL ParseInput(FileLines, 'CC_ActTau', CntrPar%CC_ActTau, accINFILE(1), ErrVar, CntrPar%CC_Mode == 0, UnEc) + IF (ErrVar%aviFAIL < 0) RETURN - IF (CntrPar%Ind_GenTq > 0) THEN - OL_String = TRIM(OL_String)//' GenTq ' - OL_Count = OL_Count + 1 - ENDIF - - IF (CntrPar%Ind_YawRate > 0) THEN - OL_String = TRIM(OL_String)//' YawRate ' - OL_Count = OL_Count + 1 - ENDIF + !------------- StC Control ----- + CALL ParseInput(FileLines, 'StC_Group_N', CntrPar%StC_Group_N, accINFILE(1), ErrVar, CntrPar%StC_Mode == 0, UnEc) + CALL ParseAry( FileLines, 'StC_GroupIndex', CntrPar%StC_GroupIndex, CntrPar%StC_Group_N, accINFILE(1), ErrVar, CntrPar%StC_Mode == 0, UnEc) + IF (ErrVar%aviFAIL < 0) RETURN - PRINT *, 'ROSCO: Implementing open loop control for'//TRIM(OL_String) - CALL Read_OL_Input(CntrPar%OL_Filename,110_IntKi,OL_Count,CntrPar%OL_Channels, ErrVar) + IF (UnEc > 0) CLOSE(UnEc) ! Close echo file - CntrPar%OL_Breakpoints = CntrPar%OL_Channels(:,CntrPar%Ind_Breakpoint) - - IF (CntrPar%Ind_BldPitch > 0) THEN - CntrPar%OL_BldPitch = CntrPar%OL_Channels(:,CntrPar%Ind_BldPitch) - ENDIF - - IF (CntrPar%Ind_GenTq > 0) THEN - CntrPar%OL_GenTq = CntrPar%OL_Channels(:,CntrPar%Ind_GenTq) - ENDIF - - IF (CntrPar%Ind_YawRate > 0) THEN - CntrPar%OL_YawRate = CntrPar%OL_Channels(:,CntrPar%Ind_YawRate) - ENDIF - END IF + !!!!!!!!!!!!!!!!!!!!!!!!!!!!!!! + ! Fix Paths (add relative paths if called from another dir, UnEc) + IF (PathIsRelative(CntrPar%PerfFileName)) CntrPar%PerfFileName = TRIM(PriPath)//TRIM(CntrPar%PerfFileName) + IF (PathIsRelative(CntrPar%OL_Filename)) CntrPar%OL_Filename = TRIM(PriPath)//TRIM(CntrPar%OL_Filename) + ! Convert yaw rate to deg/s CntrPar%Y_Rate = CntrPar%Y_Rate * R2D - ! Debugging outputs (echo someday) - ! write(400,*) CntrPar%OL_YawRate - ! END OF INPUT FILE ! Close Input File @@ -488,6 +550,7 @@ SUBROUTINE ReadControlParameterFileSub(CntrPar, zmqVar, accINFILE, accINFILE_siz !------------------- HOUSEKEEPING ----------------------- CntrPar%PerfFileName = TRIM(CntrPar%PerfFileName) + ! Add RoutineName to error message IF (ErrVar%aviFAIL < 0) THEN @@ -579,6 +642,8 @@ SUBROUTINE CheckInputs(LocalVar, CntrPar, avrSWAP, ErrVar, size_avcMSG) CHARACTER(*), PARAMETER :: RoutineName = 'CheckInputs' ! Local + + INTEGER(IntKi) :: I !.............................................................................................................................. ! Check validity of input parameters: @@ -725,12 +790,6 @@ SUBROUTINE CheckInputs(LocalVar, CntrPar, avrSWAP, ErrVar, size_avcMSG) ErrVar%ErrMsg = 'F_WECornerFreq must be greater than zero.' ENDIF - ! F_FlHighPassFreq - IF (CntrPar%F_FlHighPassFreq <= 0.0) THEN - ErrVar%aviFAIL = -1 - ErrVar%ErrMsg = 'F_FlHighPassFreq must be greater than zero.' - ENDIF - IF (CntrPar%Fl_Mode > 0) THEN ! F_FlCornerFreq(1) (frequency) IF (CntrPar%F_FlCornerFreq(1) <= 0.0) THEN @@ -743,6 +802,12 @@ SUBROUTINE CheckInputs(LocalVar, CntrPar, avrSWAP, ErrVar, size_avcMSG) ErrVar%aviFAIL = -1 ErrVar%ErrMsg = 'F_FlCornerFreq(2) must be greater than zero.' ENDIF + + ! F_FlHighPassFreq + IF (CntrPar%F_FlHighPassFreq <= 0.0) THEN + ErrVar%aviFAIL = -1 + ErrVar%ErrMsg = 'F_FlHighPassFreq must be greater than zero.' + ENDIF ENDIF IF (CntrPar%Flp_Mode > 0) THEN @@ -943,7 +1008,7 @@ SUBROUTINE CheckInputs(LocalVar, CntrPar, avrSWAP, ErrVar, size_avcMSG) ENDIF ! WE_FOPoles_v - IF (.NOT. NonDecreasing(CntrPar%WE_FOPoles_v)) THEN + IF (CntrPar%WE_Mode == 2 .AND. .NOT. NonDecreasing(CntrPar%WE_FOPoles_v)) THEN ErrVar%aviFAIL = -1 write(400,*) CntrPar%WE_FOPoles_v ErrVar%ErrMsg = 'WE_FOPoles_v must be non-decreasing.' @@ -991,12 +1056,26 @@ SUBROUTINE CheckInputs(LocalVar, CntrPar, avrSWAP, ErrVar, size_avcMSG) ENDIF ! --- Open loop control --- - IF (((CntrPar%Ind_Breakpoint) < 0) .OR. & - (CntrPar%Ind_BldPitch < 0) .OR. & - (CntrPar%Ind_GenTq < 0) .OR. & - (CntrPar%Ind_YawRate < 0)) THEN - ErrVar%aviFAIL = -1 - ErrVar%ErrMsg = 'All open loop control indices must be greater than zero' + IF (CntrPar%OL_Mode > 0) THEN + IF (((CntrPar%Ind_Breakpoint) < 0) .OR. & + (CntrPar%Ind_BldPitch < 0) .OR. & + (CntrPar%Ind_GenTq < 0) .OR. & + (CntrPar%Ind_YawRate < 0)) THEN + ErrVar%aviFAIL = -1 + ErrVar%ErrMsg = 'All open loop control indices must be greater than zero' + ENDIF + + IF (CntrPar%Ind_Breakpoint < 1) THEN + ErrVar%aviFAIL = -1 + ErrVar%ErrMsg = 'Ind_Breakpoint must be non-zero if OL_Mode is non-zero' + ENDIF + + IF ((CntrPar%Ind_BldPitch < 1) .AND. & + (CntrPar%Ind_GenTq < 1) .AND. & + (CntrPar%Ind_YawRate < 1)) THEN + ErrVar%aviFAIL = -1 + ErrVar%ErrMsg = 'At least one open loop input channel must be non-zero' + ENDIF ENDIF ! --- Pitch Actuator --- @@ -1014,6 +1093,34 @@ SUBROUTINE CheckInputs(LocalVar, CntrPar, avrSWAP, ErrVar, size_avcMSG) ErrVar%ErrMsg = 'PA_Damping must be greater than 0' END IF END IF + + IF ((CntrPar%CC_Mode < 0) .OR. (CntrPar%CC_Mode > 1)) THEN + ErrVar%aviFAIL = -1 + ErrVar%ErrMsg = 'CC_Mode must be 0 or 1' + END IF + + IF (CntrPar%CC_Mode > 0) THEN + IF (CntrPar%CC_ActTau .LE. 0) THEN + ErrVar%aviFAIL = -1 + ErrVar%ErrMsg = 'CC_ActTau must be greater than 0.' + END IF + + DO I = 1,CntrPar%CC_Group_N + IF (CntrPar%CC_GroupIndex(I) < 2601) THEN + ErrVar%aviFAIL = -1 + ErrVar%ErrMsg = 'CC_GroupIndices must be greater than 2601.' !< Starting index for the cable control + END IF + END DO + END IF + + IF (CntrPar%StC_Mode > 0) THEN + DO I = 1,CntrPar%StC_Group_N + IF (CntrPar%StC_GroupIndex(I) < 2801) THEN + ErrVar%aviFAIL = -1 + ErrVar%ErrMsg = 'StC_GroupIndices must be greater than 2801.' !< Starting index for the cable control + END IF + END DO + END IF diff --git a/ROSCO_testing/ROSCO_testing.py b/ROSCO_testing/ROSCO_testing.py index 55c5d60f..00535118 100644 --- a/ROSCO_testing/ROSCO_testing.py +++ b/ROSCO_testing/ROSCO_testing.py @@ -297,6 +297,7 @@ def ROSCO_Test_heavy(self, more_case_inputs={}, U=[]): iec.D = fastRead.fst_vt['ElastoDyn']['TipRad']*2. iec.z_hub = fastRead.fst_vt['InflowWind']['RefHt'] iec.TMax = self.TMax + iec.TStart = 300 iec.dlc_inputs = {} iec.dlc_inputs['DLC'] = [1.3, 1.4] @@ -339,7 +340,7 @@ def ROSCO_Test_heavy(self, more_case_inputs={}, U=[]): case_inputs[('ServoDyn', 'DLL_FileName')] = {'vals': [self.rosco_path], 'group': 0} case_inputs[("AeroDyn15", "WakeMod")] = {'vals': [1], 'group': 0} - case_inputs[("AeroDyn15", "AFAeroMod")] = {'vals': [2], 'group': 0} + case_inputs[("AeroDyn15", "AFAeroMod")] = {'vals': [1], 'group': 0} case_inputs[("AeroDyn15", "TwrPotent")] = {'vals': [0], 'group': 0} case_inputs[("AeroDyn15", "TwrShadow")] = {'vals': ['False'], 'group': 0} case_inputs[("AeroDyn15", "TwrAero")] = {'vals': ['False'], 'group': 0} diff --git a/ROSCO_toolbox/control_interface.py b/ROSCO_toolbox/control_interface.py index b3ad2777..4d17dba2 100644 --- a/ROSCO_toolbox/control_interface.py +++ b/ROSCO_toolbox/control_interface.py @@ -82,6 +82,8 @@ def init_discon(self): self.avrSWAP[32] = 0 * np.deg2rad(1) self.avrSWAP[33] = 0 * np.deg2rad(1) + self.avrSWAP[27] = 1 # IPC + # Torque initial condition self.avrSWAP[22] = 0 diff --git a/ROSCO_toolbox/controller.py b/ROSCO_toolbox/controller.py index f7cae56a..c780daab 100644 --- a/ROSCO_toolbox/controller.py +++ b/ROSCO_toolbox/controller.py @@ -67,6 +67,8 @@ def __init__(self, controller_params): self.PF_Mode = controller_params['PF_Mode'] self.Ext_Mode = controller_params['Ext_Mode'] self.ZMQ_Mode = controller_params['ZMQ_Mode'] + self.CC_Mode = controller_params['CC_Mode'] + self.StC_Mode = controller_params['StC_Mode'] # Necessary parameters self.U_pc = list_check(controller_params['U_pc'], return_bool=False) diff --git a/ROSCO_toolbox/inputs/toolbox_schema.yaml b/ROSCO_toolbox/inputs/toolbox_schema.yaml index 432785df..da3f21f8 100644 --- a/ROSCO_toolbox/inputs/toolbox_schema.yaml +++ b/ROSCO_toolbox/inputs/toolbox_schema.yaml @@ -99,7 +99,7 @@ properties: type: number description: 0- write no debug files, 1- write standard output .dbg-file, 2- write standard output .dbg-file and complete avrSWAP-array .dbg2-file minimum: 0 - maximum: 2 + maximum: 3 default: 1 F_LPFType: type: number @@ -208,7 +208,19 @@ properties: minimum: 0 maximum: 1 default: 0 - description: External control mode {{0 - not used, 1 - call external dynamic library}} + description: External control mode [0 - not used, 1 - call external dynamic library] + CC_Mode: + type: number + minimum: 0 + maximum: 1 + default: 0 + description: Cable control mode [0- unused, 1- User defined, 2- Position control (not yet implemented)] + StC_Mode: + type: number + minimum: 0 + maximum: 1 + default: 0 + description: Structural control mode [0- unused, 1- User defined] U_pc: type: array description: List of wind speeds to schedule pitch control zeta and omega @@ -468,6 +480,10 @@ properties: LoggingLevel: type: number description: (0- write no debug files, 1- write standard output .dbg-file, 2- write standard output .dbg-file and complete avrSWAP-array .dbg2-file) + Echo: + type: number + description: 0 - no Echo, 1 - Echo input data to .echo + default: 0 F_LPFType: type: number description: 1- first-order low-pass filter, 2- second-order low-pass filter (currently filters generator speed and pitch control signals @@ -864,6 +880,30 @@ properties: type: number description: Pitch angle offsets for each blade (array with length of 3) units: rad + CC_Group_N: + type: number + description: Number of cable control groups + default: 0 + CC_GroupIndex: + type: array + items: + type: number + description: First index for cable control group, should correspond to deltaL + default: [0] + CC_ActTau: + type: number + description: Time constant for line actuator [s] + default: 20 + StC_Group_N: + type: number + description: Number of cable control groups + default: 0 + StC_GroupIndex: + type: array + items: + type: number + description: First index for structural control group, options specified in ServoDyn summary output + default: [0] linmodel_tuning: type: object diff --git a/ROSCO_toolbox/ofTools/case_gen/CaseGen_IEC.py b/ROSCO_toolbox/ofTools/case_gen/CaseGen_IEC.py index 408cb189..d8cdb4ec 100644 --- a/ROSCO_toolbox/ofTools/case_gen/CaseGen_IEC.py +++ b/ROSCO_toolbox/ofTools/case_gen/CaseGen_IEC.py @@ -151,6 +151,9 @@ def execute(self, case_inputs={}): iecwind_ex.setup() _, V_e50, V_e1, V_50, V_1 = iecwind_ex.EWM(0.) + if dlc == 1.4: + case_inputs_i[("AeroDyn15","AFAeroMod")]= {'vals':[1], 'group':0} + if dlc == 5.1: case_inputs_i[("ServoDyn","TPitManS1")] = {'vals':[self.TStart], 'group':0} diff --git a/ROSCO_toolbox/ofTools/case_gen/run_FAST.py b/ROSCO_toolbox/ofTools/case_gen/run_FAST.py index c5b33519..e26c6f86 100644 --- a/ROSCO_toolbox/ofTools/case_gen/run_FAST.py +++ b/ROSCO_toolbox/ofTools/case_gen/run_FAST.py @@ -7,7 +7,7 @@ """ -from ROSCO_toolbox.ofTools.case_gen.runFAST_pywrapper import runFAST_pywrapper, runFAST_pywrapper_batch +from ROSCO_toolbox.ofTools.case_gen.runFAST_pywrapper import runFAST_pywrapper_batch from ROSCO_toolbox.ofTools.case_gen.CaseGen_IEC import CaseGen_IEC from ROSCO_toolbox.ofTools.case_gen.CaseGen_General import CaseGen_General from ROSCO_toolbox.ofTools.case_gen import CaseLibrary as cl @@ -36,6 +36,7 @@ def __init__(self): self.n_cores = 1 self.base_name = '' self.controller_params = {} + self.fst_vt = {} # Directories self.tune_case_dir = '' @@ -170,7 +171,7 @@ def run_FAST(self): fastBatch.FAST_runDirectory = run_dir fastBatch.case_list = case_list fastBatch.case_name_list = case_name_list - fastBatch.debug_level = 2 + fastBatch.fst_vt = self.fst_vt fastBatch.FAST_exe = 'openfast' if MPI: diff --git a/ROSCO_toolbox/ofTools/fast_io/FAST_reader.py b/ROSCO_toolbox/ofTools/fast_io/FAST_reader.py index 2f809f3b..c2c7e156 100644 --- a/ROSCO_toolbox/ofTools/fast_io/FAST_reader.py +++ b/ROSCO_toolbox/ofTools/fast_io/FAST_reader.py @@ -26,6 +26,26 @@ def fix_path(name): new = os.path.join(new, name[i]) return new +def read_array(f,len,array_type=str): + strings = re.split(',| ',f.readline().strip()) + while '' in strings: # remove empties + strings.remove('') + + arr = strings[:len] # select len strings + + if array_type==str: + arr = [ar.replace('"','') for ar in arr] # remove quotes and commas + elif array_type==float: + arr = [float_read(ar) for ar in arr] + elif array_type==int: + arr = [int_read(ar) for ar in arr] + elif array_type==bool: + arr = [bool_read(ar) for ar in arr] + else: + raise Exception(f"read_array with type {str(array_type)} not currently supported") + + return arr + def bool_read(text): # convert true/false strings to boolean if 'default' in text.lower(): @@ -1327,13 +1347,13 @@ def read_ServoDyn(self): # Structural Control f.readline() self.fst_vt['ServoDyn']['NumBStC'] = int(f.readline().split()[0]) - self.fst_vt['ServoDyn']['BStCfiles'] = f.readline().split()[0][1:-1] + self.fst_vt['ServoDyn']['BStCfiles'] = read_array(f,self.fst_vt['ServoDyn']['NumBStC'],str) self.fst_vt['ServoDyn']['NumNStC'] = int(f.readline().split()[0]) - self.fst_vt['ServoDyn']['NStCfiles'] = f.readline().split()[0][1:-1] + self.fst_vt['ServoDyn']['NStCfiles'] = read_array(f,self.fst_vt['ServoDyn']['NumNStC'],str) self.fst_vt['ServoDyn']['NumTStC'] = int(f.readline().split()[0]) - self.fst_vt['ServoDyn']['TStCfiles'] = f.readline().split()[0][1:-1] + self.fst_vt['ServoDyn']['TStCfiles'] = read_array(f,self.fst_vt['ServoDyn']['NumTStC'],str) self.fst_vt['ServoDyn']['NumSStC'] = int(f.readline().split()[0]) - self.fst_vt['ServoDyn']['SStCfiles'] = f.readline().split()[0][1:-1] + self.fst_vt['ServoDyn']['SStCfiles'] = read_array(f,self.fst_vt['ServoDyn']['NumSStC'],str) # Initialize Struct Control trees self.fst_vt['BStC'] = [] * self.fst_vt['ServoDyn']['NumBStC'] @@ -1406,6 +1426,121 @@ def read_ServoDyn(self): f.close() + def read_StC(self,filename): + ''' + return StC vt so it can be appended to fst_vt['XStC'] list + ''' + StC_vt = {} + + with open(os.path.join(self.FAST_directory, filename)) as f: + + f.readline() + f.readline() + f.readline() + StC_vt['Echo'] = bool_read(f.readline().split()[0]) # Echo - Echo input data to .ech (flag) + f.readline() # StC DEGREES OF FREEDOM + StC_vt['StC_DOF_MODE'] = int_read(f.readline().split()[0]) # 4 StC_DOF_MODE - DOF mode (switch) {0: No StC or TLCD DOF; 1: StC_X_DOF, StC_Y_DOF, and/or StC_Z_DOF (three independent StC DOFs); 2: StC_XY_DOF (Omni-Directional StC); 3: TLCD; 4: Prescribed force/moment time series} + StC_vt['StC_X_DOF'] = bool_read(f.readline().split()[0]) # false StC_X_DOF - DOF on or off for StC X (flag) [Used only when StC_DOF_MODE=1] + StC_vt['StC_Y_DOF'] = bool_read(f.readline().split()[0]) # false StC_Y_DOF - DOF on or off for StC Y (flag) [Used only when StC_DOF_MODE=1] + StC_vt['StC_Z_DOF'] = bool_read(f.readline().split()[0]) # false StC_Z_DOF - DOF on or off for StC Z (flag) [Used only when StC_DOF_MODE=1] + f.readline() # StC LOCATION + StC_vt['StC_P_X'] = float_read(f.readline().split()[0]) # -51.75 StC_P_X - At rest X position of StC (m) + StC_vt['StC_P_Y'] = float_read(f.readline().split()[0]) # 0 StC_P_Y - At rest Y position of StC (m) + StC_vt['StC_P_Z'] = float_read(f.readline().split()[0]) # -10 StC_P_Z - At rest Z position of StC (m) + f.readline() # StC INITIAL CONDITIONS + StC_vt['StC_X_DSP'] = float_read(f.readline().split()[0]) # 0 StC_X_DSP - StC X initial displacement (m) [relative to at rest position] + StC_vt['StC_Y_DSP'] = float_read(f.readline().split()[0]) # 0 StC_Y_DSP - StC Y initial displacement (m) [relative to at rest position] + StC_vt['StC_Z_DSP'] = float_read(f.readline().split()[0]) # 0 StC_Z_DSP - StC Z initial displacement (m) [relative to at rest position; used only when StC_DOF_MODE=1 and StC_Z_DOF=TRUE] + StC_vt['StC_Z_PreLd'] = f.readline().split()[0] # "none" StC_Z_PreLd - StC Z prefloat_read(f.readline().split()[0]) #-load (N) {"gravity" to offset for gravity load; "none" or 0 to turn off} [used only when StC_DOF_MODE=1 and StC_Z_DOF=TRUE] + f.readline() # StC CONFIGURATION + StC_vt['StC_X_NSP'] = float_read(f.readline().split()[0]) # 0 StC_X_NSP - Negative stop position (minimum X mass displacement) (m) + StC_vt['StC_X_PSP'] = float_read(f.readline().split()[0]) # 0 StC_X_PSP - Positive stop position (maximum X mass displacement) (m) + StC_vt['StC_Y_PSP'] = float_read(f.readline().split()[0]) # 0 StC_Y_PSP - Positive stop position (maximum Y mass displacement) (m) + StC_vt['StC_Y_NSP'] = float_read(f.readline().split()[0]) # 0 StC_Y_NSP - Negative stop position (minimum Y mass displacement) (m) + StC_vt['StC_Z_PSP'] = float_read(f.readline().split()[0]) # 0 StC_Z_PSP - Positive stop position (maximum Z mass displacement) (m) [used only when StC_DOF_MODE=1 and StC_Z_DOF=TRUE] + StC_vt['StC_Z_NSP'] = float_read(f.readline().split()[0]) # 0 StC_Z_NSP - Negative stop position (minimum Z mass displacement) (m) [used only when StC_DOF_MODE=1 and StC_Z_DOF=TRUE] + f.readline() # StC MASS, STIFFNESS, & DAMPING + StC_vt['StC_X_M'] = float_read(f.readline().split()[0]) # 0 StC_X_M - StC X mass (kg) [must equal StC_Y_M for StC_DOF_MODE = 2] + StC_vt['StC_Y_M'] = float_read(f.readline().split()[0]) # 50 StC_Y_M - StC Y mass (kg) [must equal StC_X_M for StC_DOF_MODE = 2] + StC_vt['StC_Z_M'] = float_read(f.readline().split()[0]) # 0 StC_Z_M - StC Z mass (kg) [used only when StC_DOF_MODE=1 and StC_Z_DOF=TRUE] + StC_vt['StC_XY_M'] = float_read(f.readline().split()[0]) # 0 StC_XY_M - StC XY mass (kg) [used only when StC_DOF_MODE=2] + StC_vt['StC_X_K'] = float_read(f.readline().split()[0]) # 2300 StC_X_K - StC X stiffness (N/m) + StC_vt['StC_Y_K'] = float_read(f.readline().split()[0]) # 2300 StC_Y_K - StC Y stiffness (N/m) + StC_vt['StC_Z_K'] = float_read(f.readline().split()[0]) # 0 StC_Z_K - StC Z stiffness (N/m) [used only when StC_DOF_MODE=1 and StC_Z_DOF=TRUE] + StC_vt['StC_X_C'] = float_read(f.readline().split()[0]) # 35 StC_X_C - StC X damping (N/(m/s)) + StC_vt['StC_Y_C'] = float_read(f.readline().split()[0]) #float_read(f.readline().split()[0]) # 35 StC_Y_C - StC Y damping (N/(m/s)) + StC_vt['StC_Z_C'] = float_read(f.readline().split()[0]) # 0 StC_Z_C - StC Z damping (N/(m/s)) [used only when StC_DOF_MODE=1 and StC_Z_DOF=TRUE] + StC_vt['StC_X_KS'] = float_read(f.readline().split()[0]) # 0 StC_X_KS - Stop spring X stiffness (N/m) + StC_vt['StC_Y_KS'] = float_read(f.readline().split()[0]) # 0 StC_Y_KS - Stop spring Y stiffness (N/m) + StC_vt['StC_Z_KS'] = float_read(f.readline().split()[0]) # 0 StC_Z_KS - Stop spring Z stiffness (N/m) [used only when StC_DOF_MODE=1 and StC_Z_DOF=TRUE] + StC_vt['StC_X_CS'] = float_read(f.readline().split()[0]) # 0 StC_X_CS - Stop spring X damping (N/(m/s)) + StC_vt['StC_Y_CS'] = float_read(f.readline().split()[0]) # 0 StC_Y_CS - Stop spring Y damping (N/(m/s)) + StC_vt['StC_Z_CS'] = float_read(f.readline().split()[0]) # 0 StC_Z_CS - Stop spring Z damping (N/(m/s)) [used only when StC_DOF_MODE=1 and StC_Z_DOF=TRUE] + f.readline() # StC USER-DEFINED SPRING FORCES + StC_vt['Use_F_TBL'] = bool_read(f.readline().split()[0]) # False Use_F_TBL - Use spring force from user-defined table (flag) + StC_vt['NKInpSt'] = int_read(f.readline().split()[0]) # 17 NKInpSt - Number of spring force input stations + + StC_vt['SpringForceTable'] = {} + table = StC_vt['SpringForceTable'] + table['X'] = [None] * StC_vt['NKInpSt'] + table['F_X'] = [None] * StC_vt['NKInpSt'] + table['Y'] = [None] * StC_vt['NKInpSt'] + table['F_Y'] = [None] * StC_vt['NKInpSt'] + table['Z'] = [None] * StC_vt['NKInpSt'] + table['F_Z'] = [None] * StC_vt['NKInpSt'] + + f.readline() + # if StC_vt['Use_F_TBL']: + f.readline() + f.readline() + for i in range(StC_vt['NKInpSt']): + ln = f.readline().split() + table['X'][i] = float(ln[0]) + table['F_X'][i] = float(ln[1]) + table['Y'][i] = float(ln[2]) + table['F_Y'][i] = float(ln[3]) + table['Z'][i] = float(ln[4]) + table['F_Z'][i] = float(ln[5]) + # else: + # # Skip until next section + # data_line = f.readline().strip().split() + # while data_line[0][:3] != '---': + # data_line = f.readline().strip().split() + + # StructCtrl CONTROL, skip this readline() because it already happened + f.readline() + StC_vt['StC_CMODE'] = int_read(f.readline().split()[0]) # 5 StC_CMODE - Control mode (switch) {0:none; 1: Semi-Active Control Mode; 4: Active Control Mode through Simulink (not available); 5: Active Control Mode through Bladed interface} + StC_vt['StC_CChan'] = int_read(f.readline().split()[0]) # 0 StC_CChan - Control channel group (1:10) for stiffness and damping (StC_[XYZ]_K, StC_[XYZ]_C, and StC_[XYZ]_Brake) (specify additional channels for blade instances of StC active control -- one channel per blade) [used only when StC_DOF_MODE=1 or 2, and StC_CMODE=4 or 5] + StC_vt['StC_SA_MODE'] = int_read(f.readline().split()[0]) # 1 StC_SA_MODE - Semi-Active control mode {1: velocity-based ground hook control; 2: Inverse velocity-based ground hook control; 3: displacement-based ground hook control 4: Phase difference Algorithm with Friction Force 5: Phase difference Algorithm with Damping Force} (-) + StC_vt['StC_X_C_LOW'] = float_read(f.readline().split()[0]) # 0 StC_X_C_LOW - StC X low damping for ground hook control + StC_vt['StC_X_C_HIGH'] = float_read(f.readline().split()[0]) # 0 StC_X_C_HIGH - StC X high damping for ground hook control + StC_vt['StC_Y_C_HIGH'] = float_read(f.readline().split()[0]) # 0 StC_Y_C_HIGH - StC Y high damping for ground hook control + StC_vt['StC_Y_C_LOW'] = float_read(f.readline().split()[0]) # 0 StC_Y_C_LOW - StC Y low damping for ground hook control + StC_vt['StC_Z_C_HIGH'] = float_read(f.readline().split()[0]) # 0 StC_Z_C_HIGH - StC Z high damping for ground hook control [used only when StC_DOF_MODE=1 and StC_Z_DOF=TRUE] + StC_vt['StC_Z_C_LOW'] = float_read(f.readline().split()[0]) # 0 StC_Z_C_LOW - StC Z low damping for ground hook control [used only when StC_DOF_MODE=1 and StC_Z_DOF=TRUE] + StC_vt['StC_X_C_BRAKE'] = float_read(f.readline().split()[0]) # 0 StC_X_C_BRAKE - StC X high damping for braking the StC (Don't use it now. should be zero) + StC_vt['StC_Y_C_BRAKE'] = float_read(f.readline().split()[0]) # 0 StC_Y_C_BRAKE - StC Y high damping for braking the StC (Don't use it now. should be zero) + StC_vt['StC_Z_C_BRAKE'] = float_read(f.readline().split()[0]) # 0 StC_Z_C_BRAKE - StC Z high damping for braking the StC (Don't use it now. should be zero) [used only when StC_DOF_MODE=1 and StC_Z_DOF=TRUE] + f.readline() # TLCD + StC_vt['L_X'] = float_read(f.readline().split()[0]) # 7.9325 L_X - X TLCD total length (m) + StC_vt['B_X'] = float_read(f.readline().split()[0]) # 6.5929 B_X - X TLCD horizontal length (m) + StC_vt['area_X'] = float_read(f.readline().split()[0]) # 2.0217 area_X - X TLCD cross-sectional area of vertical column (m^2) + StC_vt['area_ratio_X'] = float_read(f.readline().split()[0]) # 0.913 area_ratio_X - X TLCD cross-sectional area ratio (vertical column area divided by horizontal column area) (-) + StC_vt['headLossCoeff_X'] = float_read(f.readline().split()[0]) # 2.5265 headLossCoeff_X - X TLCD head loss coeff (-) + StC_vt['rho_X'] = float_read(f.readline().split()[0]) # 1000 rho_X - X TLCD liquid density (kg/m^3) + StC_vt['L_Y'] = float_read(f.readline().split()[0]) # 3.5767 L_Y - Y TLCD total length (m) + StC_vt['B_Y'] = float_read(f.readline().split()[0]) # 2.1788 B_Y - Y TLCD horizontal length (m) + StC_vt['area_Y'] = float_read(f.readline().split()[0]) # 1.2252 area_Y - Y TLCD cross-sectional area of vertical column (m^2) + StC_vt['area_ratio_Y'] = float_read(f.readline().split()[0]) # 2.7232 area_ratio_Y - Y TLCD cross-sectional area ratio (vertical column area divided by horizontal column area) (-) + StC_vt['headLossCoeff_Y'] = float_read(f.readline().split()[0]) # 0.6433 headLossCoeff_Y - Y TLCD head loss coeff (-) + StC_vt['rho_Y'] = float_read(f.readline().split()[0]) # 1000 rho_Y - Y TLCD liquid density (kg/m^3) + f.readline() # PRESCRIBED TIME SERIES + StC_vt['PrescribedForcesCoord'] = int_read(f.readline().split()[0]) # 2 PrescribedForcesCoord- Prescribed forces are in global or local coordinates (switch) {1: global; 2: local} + StC_vt['PrescribedForcesFile'] = f.readline().split()[0] # "Bld-TimeForceSeries.dat" PrescribedForcesFile - Time series force and moment (7 columns of time, FX, FY, FZ, MX, MY, MZ) + f.readline() + + return StC_vt + def read_DISCON_in(self): # Read the Bladed style Interface controller input file, intended for ROSCO https://github.com/NREL/ROSCO_toolbox @@ -2213,6 +2348,29 @@ def read_MoorDyn(self, moordyn_file): self.fst_vt['MoorDyn']['Outputs'].append(str(data_line[6])) data_line = f.readline().strip().split() + # read optional control inputs, there are other optional MoorDyn sections/inputs + self.fst_vt['MoorDyn']['ChannelID'] = [] + self.fst_vt['MoorDyn']['Lines_Control'] = [] + if 'CONTROL' in [dl.upper() for dl in data_line]: + f.readline() + f.readline() + data_line = f.readline().strip().split() + while data_line[0][:3] != '---': # OpenFAST searches for ---, so we'll do the same + self.fst_vt['MoorDyn']['ChannelID'].append(int(data_line[0])) + # Line(s) is a list of mooring lines, spaces are allowed between commas + control_lines = [] + for lines in data_line[1:]: + for line in lines.split(','): + control_lines.append(line.strip(',')) + + # Spaces show up in control_lines as '', remove them all + while '' in control_lines: + control_lines.remove('') + + self.fst_vt['MoorDyn']['Lines_Control'].append(control_lines) + data_line = f.readline().strip().split() + + # Solver options, there are a few more optional MoorDyn inputs that can be added line 'CONTROL' self.fst_vt['MoorDyn']['dtM'] = float_read(f.readline().split()[0]) self.fst_vt['MoorDyn']['kbot'] = float_read(f.readline().split()[0]) self.fst_vt['MoorDyn']['cbot'] = float_read(f.readline().split()[0]) @@ -2251,7 +2409,15 @@ def execute(self): if self.fst_vt['Fst']['CompServo'] == 1: self.read_ServoDyn() - # Would read StCs here + # Read StC Files + for StC_file in self.fst_vt['ServoDyn']['BStCfiles']: + self.fst_vt['BStC'].append(self.read_StC(StC_file)) + for StC_file in self.fst_vt['ServoDyn']['NStCfiles']: + self.fst_vt['NStC'].append(self.read_StC(StC_file)) + for StC_file in self.fst_vt['ServoDyn']['TStCfiles']: + self.fst_vt['TStC'].append(self.read_StC(StC_file)) + for StC_file in self.fst_vt['ServoDyn']['SStCfiles']: + self.fst_vt['SStC'].append(self.read_StC(StC_file)) if ROSCO: self.read_DISCON_in() hd_file = os.path.normpath(os.path.join(self.FAST_directory, self.fst_vt['Fst']['HydroFile'])) diff --git a/ROSCO_toolbox/ofTools/fast_io/FAST_writer.py b/ROSCO_toolbox/ofTools/fast_io/FAST_writer.py index 852b3594..8dd91db3 100644 --- a/ROSCO_toolbox/ofTools/fast_io/FAST_writer.py +++ b/ROSCO_toolbox/ofTools/fast_io/FAST_writer.py @@ -1263,13 +1263,13 @@ def write_ServoDyn(self): f.write('{:<22} {:<11} {:}'.format(self.fst_vt['ServoDyn']['AfC_Phase'], 'AfC_phase', '- Phase relative to the blade azimuth (0 is vertical) for for cosine cycling of flap signal (deg) [used only with AfCmode==1]\n')) f.write('---------------------- STRUCTURAL CONTROL ---------------------------------------\n') f.write('{:<22} {:<11} {:}'.format(self.fst_vt['ServoDyn']['NumBStC'], 'NumBStC', '- Number of blade structural controllers (integer)\n')) - f.write('{!s:<22} {:<11} {:}'.format('"' + ''.join(self.fst_vt['ServoDyn']['BStCfiles']) + '"', 'BStCfiles', '- Name of the file for blade tuned mass damper (quoted string) [unused when CompNTMD is false]\n')) + f.write('{!s:<22} {:<11} {:}'.format('"' + '" "'.join(self.fst_vt['ServoDyn']['BStCfiles']) + '"', 'BStCfiles', '- Name of the file for blade tuned mass damper (quoted string) [unused when CompNTMD is false]\n')) f.write('{:<22} {:<11} {:}'.format(self.fst_vt['ServoDyn']['NumNStC'], 'NumNStC', '- Number of nacelle structural controllers (integer)\n')) - f.write('{!s:<22} {:<11} {:}'.format('"' + ''.join(self.fst_vt['ServoDyn']['NStCfiles']) + '"', 'NStCfiles', '- Name of the file for nacelle tuned mass damper (quoted string) [unused when CompNTMD is false]\n')) + f.write('{!s:<22} {:<11} {:}'.format('"' + '" "'.join(self.fst_vt['ServoDyn']['NStCfiles']) + '"', 'NStCfiles', '- Name of the file for nacelle tuned mass damper (quoted string) [unused when CompNTMD is false]\n')) f.write('{:<22} {:<11} {:}'.format(self.fst_vt['ServoDyn']['NumTStC'], 'NumTStC', '- Number of tower structural controllers (integer)\n')) - f.write('{!s:<22} {:<11} {:}'.format('"' + ''.join(self.fst_vt['ServoDyn']['TStCfiles']) + '"', 'TStCfiles', '- Name of the file for tower tuned mass damper (quoted string) [unused when CompNTMD is false]\n')) + f.write('{!s:<22} {:<11} {:}'.format('"' + '" "'.join(self.fst_vt['ServoDyn']['TStCfiles']) + '"', 'TStCfiles', '- Name of the file for tower tuned mass damper (quoted string) [unused when CompNTMD is false]\n')) f.write('{:<22} {:<11} {:}'.format(self.fst_vt['ServoDyn']['NumSStC'], 'NumSStC', '- Number of sbustructure structural controllers (integer)\n')) - f.write('{!s:<22} {:<11} {:}'.format('"' + ''.join(self.fst_vt['ServoDyn']['SStCfiles']) + '"', 'SStCfiles', '- Name of the file for sbustructure tuned mass damper (quoted string) [unused when CompNTMD is false]\n')) + f.write('{!s:<22} {:<11} {:}'.format('"' + '" "'.join(self.fst_vt['ServoDyn']['SStCfiles']) + '"', 'SStCfiles', '- Name of the file for sbustructure tuned mass damper (quoted string) [unused when CompNTMD is false]\n')) f.write('---------------------- CABLE CONTROL ---------------------------------------- \n') f.write('{:<22} {:<11} {:}'.format(self.fst_vt['ServoDyn']['CCmode'], 'CCmode', '- Cable control mode {0- none, 4- user-defined from Simulink/Labview, 5- user-defineAfC_phased from Bladed-style DLL}\n')) f.write('---------------------- BLADED INTERFACE ---------------------------------------- [used only with Bladed Interface]\n') @@ -1977,6 +1977,17 @@ def write_MoorDyn(self): ln.append('{:^11d}'.format(self.fst_vt['MoorDyn']['NumSegs'][i])) ln.append('{:^11}'.format(self.fst_vt['MoorDyn']['Outputs'][i])) f.write(" ".join(ln) + '\n') + + if self.fst_vt['MoorDyn']['ChannelID']: # There are control inputs + f.write('---------------------- CONTROL ---------------------------------------\n') + f.write(" ".join(['{:^11s}'.format(i) for i in ['ChannelID', 'Line(s)']])+'\n') + f.write(" ".join(['{:^11s}'.format(i) for i in ['()', '(,)']])+'\n') + for i_line in range(len(self.fst_vt['MoorDyn']['ChannelID'])): + ln = [] + ln.append('{:^11d}'.format(self.fst_vt['MoorDyn']['ChannelID'][i_line])) + ln.append(','.join(self.fst_vt['MoorDyn']['Lines_Control'][i_line])) + f.write(" ".join(ln) + '\n') + f.write('---------------------- SOLVER OPTIONS ---------------------------------------\n') f.write('{:<22} {:<11} {:}'.format(self.fst_vt['MoorDyn']['dtM'], 'dtM', '- time step to use in mooring integration (s)\n')) f.write('{:<22} {:<11} {:}'.format(self.fst_vt['MoorDyn']['kbot'], 'kbot', '- bottom stiffness (Pa/m)\n')) diff --git a/ROSCO_toolbox/utilities.py b/ROSCO_toolbox/utilities.py index 04cf98f3..b50a6595 100644 --- a/ROSCO_toolbox/utilities.py +++ b/ROSCO_toolbox/utilities.py @@ -27,6 +27,7 @@ import numpy as np import subprocess import ROSCO_toolbox +from wisdem.inputs import load_yaml from wisdem.inputs import load_yaml @@ -58,6 +59,27 @@ def write_DISCON(turbine, controller, param_file='DISCON.IN', txt_filename='Cp_C if not rosco_vt: rosco_vt = DISCON_dict(turbine, controller, txt_filename) + # Get input descriptions from input schema + fname_schema = os.path.join(os.path.dirname(__file__),'inputs/toolbox_schema.yaml') + sch = load_yaml(fname_schema) + + # mode descriptions in main controller_params, might not be needed + mode_descriptions = {} + for input, props in sch['properties']['controller_params']['properties'].items(): + if 'description' in props: + mode_descriptions[input] = props['description'] + + input_descriptions = {} + for input, props in sch['properties']['controller_params']['properties']['DISCON']['properties'].items(): + if 'description' in props: + input_descriptions[input] = props['description'] + + # Tidy inputs, if needed + if not hasattr(rosco_vt['CC_GroupIndex'],'__len__'): + rosco_vt['CC_GroupIndex'] = [rosco_vt['CC_GroupIndex']] # make an array + if not hasattr(rosco_vt['StC_GroupIndex'],'__len__'): + rosco_vt['StC_GroupIndex'] = [rosco_vt['StC_GroupIndex']] + print('Writing new controller parameter file parameter file: %s.' % param_file) # Should be obvious what's going on here... file = open(param_file,'w') @@ -65,10 +87,11 @@ def write_DISCON(turbine, controller, param_file='DISCON.IN', txt_filename='Cp_C file.write('! - File written using ROSCO version {} controller tuning logic on {}\n'.format(ROSCO_toolbox.__version__, now.strftime('%m/%d/%y'))) file.write('\n') file.write('!------- DEBUG ------------------------------------------------------------\n') - file.write('{0:<12d} ! LoggingLevel - {{0: write no debug files, 1: write standard output .dbg-file, 2: LoggingLevel 1 + ROSCO LocalVars (.dbg2) 3: LoggingLevel 2 + complete avrSWAP-array (.dbg3)}}\n'.format(int(rosco_vt['LoggingLevel']))) + file.write('{0:<12d} ! LoggingLevel - (0: write no debug files, 1: write standard output .dbg-file, 2: LoggingLevel 1 + ROSCO LocalVars (.dbg2) 3: LoggingLevel 2 + complete avrSWAP-array (.dbg3))\n'.format(int(rosco_vt['LoggingLevel']))) + file.write('{:<11d} ! Echo - ({})\n'.format(int(rosco_vt['Echo']), input_descriptions['Echo'])) file.write('\n') file.write('!------- CONTROLLER FLAGS -------------------------------------------------\n') - file.write('{0:<12d} ! F_LPFType - {{1: first-order low-pass filter, 2: second-order low-pass filter}}, [rad/s] (currently filters generator speed and pitch control signals\n'.format(int(rosco_vt['F_LPFType']))) + file.write('{0:<12d} ! F_LPFType - (1: first-order low-pass filter, 2: second-order low-pass filter), [rad/s] (currently filters generator speed and pitch control signals\n'.format(int(rosco_vt['F_LPFType']))) file.write('{0:<12d} ! F_NotchType - Notch on the measured generator speed and/or tower fore-aft motion (for floating) {{0: disable, 1: generator speed, 2: tower-top fore-aft motion, 3: generator speed and tower-top fore-aft motion}}\n'.format(int(rosco_vt['F_NotchType']))) file.write('{0:<12d} ! IPC_ControlMode - Turn Individual Pitch Control (IPC) for fatigue load reductions (pitch contribution) {{0: off, 1: 1P reductions, 2: 1P+2P reductions}}\n'.format(int(rosco_vt['IPC_ControlMode']))) file.write('{0:<12d} ! VS_ControlMode - Generator torque control mode in above rated conditions {{0: constant torque, 1: constant power, 2: TSR tracking PI control with constant torque, 3: TSR tracking PI control with constant power}}\n'.format(int(rosco_vt['VS_ControlMode']))) @@ -86,6 +109,8 @@ def write_DISCON(turbine, controller, param_file='DISCON.IN', txt_filename='Cp_C file.write('{0:<12d} ! PF_Mode - Pitch fault mode {{0 - not used, 1 - constant offset on one or more blades}}\n'.format(int(rosco_vt['PF_Mode']))) file.write('{0:<12d} ! Ext_Mode - External control mode {{0 - not used, 1 - call external dynamic library}}\n'.format(int(rosco_vt['Ext_Mode']))) file.write('{0:<12d} ! ZMQ_Mode - Fuse ZeroMQ interface {{0: unused, 1: Yaw Control}}\n'.format(int(rosco_vt['ZMQ_Mode']))) + file.write('{:<12d} ! CC_Mode - {}\n'.format(int(rosco_vt['CC_Mode']),mode_descriptions['CC_Mode'])) + file.write('{:<12d} ! StC_Mode - {}\n'.format(int(rosco_vt['StC_Mode']),mode_descriptions['StC_Mode'])) file.write('\n') file.write('!------- FILTERS ----------------------------------------------------------\n') @@ -217,6 +242,16 @@ def write_DISCON(turbine, controller, param_file='DISCON.IN', txt_filename='Cp_C file.write('!------- ZeroMQ Interface ---------------------------------------------------------\n') file.write('"{}" ! ZMQ_CommAddress - Communication address for ZMQ server, (e.g. "tcp://localhost:5555") \n'.format(rosco_vt['ZMQ_CommAddress'])) file.write('{:<11d} ! ZMQ_UpdatePeriod - Call ZeroMQ every [x] seconds, [s]\n'.format(int(rosco_vt['ZMQ_UpdatePeriod']))) + file.write('\n') + file.write('!------- Cable Control ---------------------------------------------------------\n') + file.write('{:<11d} ! CC_Group_N - {}\n'.format(len(rosco_vt['CC_GroupIndex']), input_descriptions['CC_Group_N'])) + file.write('{:^11s} ! CC_GroupIndex - {}\n'.format(' '.join([f'{int(ind):d}' for ind in rosco_vt['CC_GroupIndex']]), input_descriptions['CC_GroupIndex'])) + file.write('{:<11f} ! CC_ActTau - {}\n'.format(rosco_vt['CC_ActTau'], input_descriptions['CC_ActTau'] )) + file.write('\n') + file.write('!------- Structural Controllers ---------------------------------------------------------\n') + file.write('{:<11d} ! StC_Group_N - {}\n'.format(len(rosco_vt['StC_GroupIndex']), input_descriptions['StC_Group_N'])) + file.write('{:^11s} ! StC_GroupIndex - {}\n'.format(' '.join([f'{int(ind):d}' for ind in rosco_vt['StC_GroupIndex']]), input_descriptions['StC_GroupIndex'])) + file.close() # Write Open loop input @@ -412,6 +447,8 @@ def DISCON_dict(turbine, controller, txt_filename=None): DISCON_dict['PA_Mode'] = int(controller.PA_Mode) DISCON_dict['Ext_Mode'] = int(controller.Ext_Mode) DISCON_dict['ZMQ_Mode'] = int(controller.ZMQ_Mode) + DISCON_dict['CC_Mode'] = int(controller.CC_Mode) + DISCON_dict['StC_Mode'] = int(controller.StC_Mode) # ------- FILTERS ------- DISCON_dict['F_LPFCornerFreq'] = turbine.bld_edgewise_freq * 1/4 DISCON_dict['F_LPFDamping'] = controller.F_LPFDamping diff --git a/Test_Cases/BAR_10/BAR_10_DISCON.IN b/Test_Cases/BAR_10/BAR_10_DISCON.IN index 17875c9c..d915a5c0 100644 --- a/Test_Cases/BAR_10/BAR_10_DISCON.IN +++ b/Test_Cases/BAR_10/BAR_10_DISCON.IN @@ -1,11 +1,12 @@ ! Controller parameter input file for the BAR_10 wind turbine -! - File written using ROSCO version 2.7.0 controller tuning logic on 02/06/23 +! - File written using ROSCO version 2.7.0 controller tuning logic on 02/28/23 !------- DEBUG ------------------------------------------------------------ -1 ! LoggingLevel - {0: write no debug files, 1: write standard output .dbg-file, 2: LoggingLevel 1 + ROSCO LocalVars (.dbg2) 3: LoggingLevel 2 + complete avrSWAP-array (.dbg3)} +1 ! LoggingLevel - (0: write no debug files, 1: write standard output .dbg-file, 2: LoggingLevel 1 + ROSCO LocalVars (.dbg2) 3: LoggingLevel 2 + complete avrSWAP-array (.dbg3)) +0 ! Echo - (0 - no Echo, 1 - Echo input data to .echo) !------- CONTROLLER FLAGS ------------------------------------------------- -2 ! F_LPFType - {1: first-order low-pass filter, 2: second-order low-pass filter}, [rad/s] (currently filters generator speed and pitch control signals +2 ! 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 and/or tower fore-aft motion (for floating) {0: disable, 1: generator speed, 2: tower-top fore-aft motion, 3: generator speed and tower-top fore-aft motion} 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 with constant torque, 3: TSR tracking PI control with constant power} @@ -23,6 +24,8 @@ 0 ! PF_Mode - Pitch fault mode {0 - not used, 1 - constant offset on one or more blades} 0 ! Ext_Mode - External control mode {0 - not used, 1 - call external dynamic library} 0 ! ZMQ_Mode - Fuse ZeroMQ interface {0: unused, 1: Yaw Control} +0 ! CC_Mode - Cable control mode [0- unused, 1- User defined, 2- Position control (not yet implemented)] +0 ! StC_Mode - Structural control mode [0- unused, 1- User defined] !------- FILTERS ---------------------------------------------------------- 0.81771 ! F_LPFCornerFreq - Corner frequency (-3dB point) in the low-pass filters, [rad/s] @@ -148,3 +151,12 @@ !------- ZeroMQ Interface --------------------------------------------------------- "tcp://localhost:5555" ! ZMQ_CommAddress - Communication address for ZMQ server, (e.g. "tcp://localhost:5555") 2 ! ZMQ_UpdatePeriod - Call ZeroMQ every [x] seconds, [s] + +!------- Cable Control --------------------------------------------------------- +1 ! CC_Group_N - Number of cable control groups + 0 ! CC_GroupIndex - First index for cable control group, should correspond to deltaL +20.000000 ! CC_ActTau - Time constant for line actuator [s] + +!------- Structural Controllers --------------------------------------------------------- +1 ! StC_Group_N - Number of cable control groups + 0 ! StC_GroupIndex - First index for structural control group, options specified in ServoDyn summary output diff --git a/Test_Cases/IEA-15-240-RWT-UMaineSemi/DISCON-UMaineSemi.IN b/Test_Cases/IEA-15-240-RWT-UMaineSemi/DISCON-UMaineSemi.IN index 5f55c5ab..30f764c6 100644 --- a/Test_Cases/IEA-15-240-RWT-UMaineSemi/DISCON-UMaineSemi.IN +++ b/Test_Cases/IEA-15-240-RWT-UMaineSemi/DISCON-UMaineSemi.IN @@ -1,11 +1,12 @@ ! Controller parameter input file for the IEA-15-240-RWT-UMaineSemi wind turbine -! - File written using ROSCO version 2.7.0 controller tuning logic on 02/06/23 +! - File written using ROSCO version 2.7.0 controller tuning logic on 02/28/23 !------- DEBUG ------------------------------------------------------------ -2 ! LoggingLevel - {0: write no debug files, 1: write standard output .dbg-file, 2: LoggingLevel 1 + ROSCO LocalVars (.dbg2) 3: LoggingLevel 2 + complete avrSWAP-array (.dbg3)} +2 ! LoggingLevel - (0: write no debug files, 1: write standard output .dbg-file, 2: LoggingLevel 1 + ROSCO LocalVars (.dbg2) 3: LoggingLevel 2 + complete avrSWAP-array (.dbg3)) +0 ! Echo - (0 - no Echo, 1 - Echo input data to .echo) !------- CONTROLLER FLAGS ------------------------------------------------- -2 ! F_LPFType - {1: first-order low-pass filter, 2: second-order low-pass filter}, [rad/s] (currently filters generator speed and pitch control signals +2 ! F_LPFType - (1: first-order low-pass filter, 2: second-order low-pass filter), [rad/s] (currently filters generator speed and pitch control signals 2 ! F_NotchType - Notch on the measured generator speed and/or tower fore-aft motion (for floating) {0: disable, 1: generator speed, 2: tower-top fore-aft motion, 3: generator speed and tower-top fore-aft motion} 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 with constant torque, 3: TSR tracking PI control with constant power} @@ -23,6 +24,8 @@ 0 ! PF_Mode - Pitch fault mode {0 - not used, 1 - constant offset on one or more blades} 0 ! Ext_Mode - External control mode {0 - not used, 1 - call external dynamic library} 0 ! ZMQ_Mode - Fuse ZeroMQ interface {0: unused, 1: Yaw Control} +0 ! CC_Mode - Cable control mode [0- unused, 1- User defined, 2- Position control (not yet implemented)] +0 ! StC_Mode - Structural control mode [0- unused, 1- User defined] !------- FILTERS ---------------------------------------------------------- 1.00810 ! F_LPFCornerFreq - Corner frequency (-3dB point) in the low-pass filters, [rad/s] @@ -148,3 +151,12 @@ !------- ZeroMQ Interface --------------------------------------------------------- "tcp://localhost:5555" ! ZMQ_CommAddress - Communication address for ZMQ server, (e.g. "tcp://localhost:5555") 2 ! ZMQ_UpdatePeriod - Call ZeroMQ every [x] seconds, [s] + +!------- Cable Control --------------------------------------------------------- +1 ! CC_Group_N - Number of cable control groups + 0 ! CC_GroupIndex - First index for cable control group, should correspond to deltaL +20.000000 ! CC_ActTau - Time constant for line actuator [s] + +!------- Structural Controllers --------------------------------------------------------- +1 ! StC_Group_N - Number of cable control groups + 0 ! StC_GroupIndex - First index for structural control group, options specified in ServoDyn summary output diff --git a/Test_Cases/IEA-15-240-RWT-UMaineSemi/StC-Force-Col1.dat b/Test_Cases/IEA-15-240-RWT-UMaineSemi/StC-Force-Col1.dat new file mode 100644 index 00000000..5709eb5f --- /dev/null +++ b/Test_Cases/IEA-15-240-RWT-UMaineSemi/StC-Force-Col1.dat @@ -0,0 +1,95 @@ +------- STRUCTURAL CONTROL (StC) INPUT FILE ---------------------------- +Input file for tuned mass damper, module by Matt Lackner, Meghan Glade, and Semyung Park (UMass) +---------------------- SIMULATION CONTROL -------------------------------------- +True Echo - Echo input data to .ech (flag) +---------------------- StC DEGREES OF FREEDOM ---------------------------------- + 5 StC_DOF_MODE - DOF mode (switch) {0: No StC or TLCD DOF; 1: StC_X_DOF, StC_Y_DOF, and/or StC_Z_DOF (three independent StC DOFs); 2: StC_XY_DOF (Omni-Directional StC); 3: TLCD; 4: Prescribed force/moment time series} +false StC_X_DOF - DOF on or off for StC X (flag) [Used only when StC_DOF_MODE=1] +false StC_Y_DOF - DOF on or off for StC Y (flag) [Used only when StC_DOF_MODE=1] +false StC_Z_DOF - DOF on or off for StC Z (flag) [Used only when StC_DOF_MODE=1] +---------------------- StC LOCATION ------------------------------------------- [relative to the reference origin of component attached to] + -51.75 StC_P_X - At rest X position of StC (m) + 0 StC_P_Y - At rest Y position of StC (m) + -10 StC_P_Z - At rest Z position of StC (m) +---------------------- StC INITIAL CONDITIONS --------------------------------- [used only when StC_DOF_MODE=1 or 2] + 0 StC_X_DSP - StC X initial displacement (m) [relative to at rest position] + 0 StC_Y_DSP - StC Y initial displacement (m) [relative to at rest position] + 0 StC_Z_DSP - StC Z initial displacement (m) [relative to at rest position; used only when StC_DOF_MODE=1 and StC_Z_DOF=TRUE] +"none" StC_Z_PreLd - StC Z pre-load (N) {"gravity" to offset for gravity load; "none" or 0 to turn off} [used only when StC_DOF_MODE=1 and StC_Z_DOF=TRUE] +---------------------- StC CONFIGURATION -------------------------------------- [used only when StC_DOF_MODE=1 or 2] + 0 StC_X_PSP - Positive stop position (maximum X mass displacement) (m) + 0 StC_X_NSP - Negative stop position (minimum X mass displacement) (m) + 0 StC_Y_PSP - Positive stop position (maximum Y mass displacement) (m) + 0 StC_Y_NSP - Negative stop position (minimum Y mass displacement) (m) + 0 StC_Z_PSP - Positive stop position (maximum Z mass displacement) (m) [used only when StC_DOF_MODE=1 and StC_Z_DOF=TRUE] + 0 StC_Z_NSP - Negative stop position (minimum Z mass displacement) (m) [used only when StC_DOF_MODE=1 and StC_Z_DOF=TRUE] +---------------------- StC MASS, STIFFNESS, & DAMPING ------------------------- [used only when StC_DOF_MODE=1 or 2] + 0 StC_X_M - StC X mass (kg) [must equal StC_Y_M for StC_DOF_MODE = 2] + 1 StC_Y_M - StC Y mass (kg) [must equal StC_X_M for StC_DOF_MODE = 2] + 0 StC_Z_M - StC Z mass (kg) [used only when StC_DOF_MODE=1 and StC_Z_DOF=TRUE] + 0 StC_XY_M - StC XY mass (kg) [used only when StC_DOF_MODE=2] + 0 StC_X_K - StC X stiffness (N/m) + 0 StC_Y_K - StC Y stiffness (N/m) + 1e8 StC_Z_K - StC Z stiffness (N/m) [used only when StC_DOF_MODE=1 and StC_Z_DOF=TRUE] + 0 StC_X_C - StC X damping (N/(m/s)) + 0 StC_Y_C - StC Y damping (N/(m/s)) + 100 StC_Z_C - StC Z damping (N/(m/s)) [used only when StC_DOF_MODE=1 and StC_Z_DOF=TRUE] + 0 StC_X_KS - Stop spring X stiffness (N/m) + 0 StC_Y_KS - Stop spring Y stiffness (N/m) + 0 StC_Z_KS - Stop spring Z stiffness (N/m) [used only when StC_DOF_MODE=1 and StC_Z_DOF=TRUE] + 0 StC_X_CS - Stop spring X damping (N/(m/s)) + 0 StC_Y_CS - Stop spring Y damping (N/(m/s)) + 0 StC_Z_CS - Stop spring Z damping (N/(m/s)) [used only when StC_DOF_MODE=1 and StC_Z_DOF=TRUE] +---------------------- StC USER-DEFINED SPRING FORCES ------------------------- [used only when StC_DOF_MODE=1 or 2] +False Use_F_TBL - Use spring force from user-defined table (flag) + 17 NKInpSt - Number of spring force input stations +---------------------- StC SPRING FORCES TABLE -------------------------------- [used only when StC_DOF_MODE=1 or 2] + X F_X Y F_Y Z F_Z + (m) (N) (m) (N) (m) (N) +-6.0000000E+00 -4.8000000E+06 -6.0000000E+00 -4.8000000E+06 -6.0000000E+00 -4.8000000E+06 +-5.0000000E+00 -2.4000000E+06 -5.0000000E+00 -2.4000000E+06 -5.0000000E+00 -2.4000000E+06 +-4.5000000E+00 -1.2000000E+06 -4.5000000E+00 -1.2000000E+06 -4.5000000E+00 -1.2000000E+06 +-4.0000000E+00 -6.0000000E+05 -4.0000000E+00 -6.0000000E+05 -4.0000000E+00 -6.0000000E+05 +-3.5000000E+00 -3.0000000E+05 -3.5000000E+00 -3.0000000E+05 -3.5000000E+00 -3.0000000E+05 +-3.0000000E+00 -1.5000000E+05 -3.0000000E+00 -1.5000000E+05 -3.0000000E+00 -1.5000000E+05 +-2.5000000E+00 -1.0000000E+05 -2.5000000E+00 -1.0000000E+05 -2.5000000E+00 -1.0000000E+05 +-2.0000000E+00 -6.5000000E+04 -2.0000000E+00 -6.5000000E+04 -2.0000000E+00 -6.5000000E+04 + 0.0000000E+00 0.0000000E+00 0.0000000E+00 0.0000000E+00 0.0000000E+00 0.0000000E+00 + 2.0000000E+00 6.5000000E+04 2.0000000E+00 6.5000000E+04 2.0000000E+00 6.5000000E+04 + 2.5000000E+00 1.0000000E+05 2.5000000E+00 1.0000000E+05 2.5000000E+00 1.0000000E+05 + 3.0000000E+00 1.5000000E+05 3.0000000E+00 1.5000000E+05 3.0000000E+00 1.5000000E+05 + 3.5000000E+00 3.0000000E+05 3.5000000E+00 3.0000000E+05 3.5000000E+00 3.0000000E+05 + 4.0000000E+00 6.0000000E+05 4.0000000E+00 6.0000000E+05 4.0000000E+00 6.0000000E+05 + 4.5000000E+00 1.2000000E+06 4.5000000E+00 1.2000000E+06 4.5000000E+00 1.2000000E+06 + 5.0000000E+00 2.4000000E+06 5.0000000E+00 2.4000000E+06 5.0000000E+00 2.4000000E+06 + 6.0000000E+00 4.8000000E+06 6.0000000E+00 4.8000000E+06 6.0000000E+00 4.8000000E+06 +---------------------- StructCtrl CONTROL -------------------------------------------- [used only when StC_DOF_MODE=1 or 2] + 5 StC_CMODE - Control mode (switch) {0:none; 1: Semi-Active Control Mode; 4: Active Control Mode through Simulink (not available); 5: Active Control Mode through Bladed interface} + 1 StC_CChan - Control channel group (1:10) for stiffness and damping (StC_[XYZ]_K, StC_[XYZ]_C, and StC_[XYZ]_Brake) (specify additional channels for blade instances of StC active control -- one channel per blade) [used only when StC_DOF_MODE=1 or 2, and StC_CMODE=4 or 5] + 1 StC_SA_MODE - Semi-Active control mode {1: velocity-based ground hook control; 2: Inverse velocity-based ground hook control; 3: displacement-based ground hook control 4: Phase difference Algorithm with Friction Force 5: Phase difference Algorithm with Damping Force} (-) + 0 StC_X_C_HIGH - StC X high damping for ground hook control + 0 StC_X_C_LOW - StC X low damping for ground hook control + 0 StC_Y_C_HIGH - StC Y high damping for ground hook control + 0 StC_Y_C_LOW - StC Y low damping for ground hook control + 0 StC_Z_C_HIGH - StC Z high damping for ground hook control [used only when StC_DOF_MODE=1 and StC_Z_DOF=TRUE] + 0 StC_Z_C_LOW - StC Z low damping for ground hook control [used only when StC_DOF_MODE=1 and StC_Z_DOF=TRUE] + 0 StC_X_C_BRAKE - StC X high damping for braking the StC (Don't use it now. should be zero) + 0 StC_Y_C_BRAKE - StC Y high damping for braking the StC (Don't use it now. should be zero) + 0 StC_Z_C_BRAKE - StC Z high damping for braking the StC (Don't use it now. should be zero) [used only when StC_DOF_MODE=1 and StC_Z_DOF=TRUE] +---------------------- TLCD --------------------------------------------------- [used only when StC_DOF_MODE=3] + 7.9325 L_X - X TLCD total length (m) + 6.5929 B_X - X TLCD horizontal length (m) + 2.0217 area_X - X TLCD cross-sectional area of vertical column (m^2) + 0.913 area_ratio_X - X TLCD cross-sectional area ratio (vertical column area divided by horizontal column area) (-) + 2.5265 headLossCoeff_X - X TLCD head loss coeff (-) + 1000 rho_X - X TLCD liquid density (kg/m^3) + 3.5767 L_Y - Y TLCD total length (m) + 2.1788 B_Y - Y TLCD horizontal length (m) + 1.2252 area_Y - Y TLCD cross-sectional area of vertical column (m^2) + 2.7232 area_ratio_Y - Y TLCD cross-sectional area ratio (vertical column area divided by horizontal column area) (-) + 0.6433 headLossCoeff_Y - Y TLCD head loss coeff (-) + 1000 rho_Y - Y TLCD liquid density (kg/m^3) +---------------------- PRESCRIBED TIME SERIES --------------------------------- [used only when StC_DOF_MODE=4] + 1 PrescribedForcesCoord- Prescribed forces are in global or local coordinates (switch) {1: global; 2: local} +"Bld-TimeForceSeries.dat" PrescribedForcesFile - Time series force and moment (7 columns of time, FX, FY, FZ, MX, MY, MZ) +------------------------------------------------------------------------------- \ No newline at end of file diff --git a/Test_Cases/IEA-15-240-RWT-UMaineSemi/StC-Force-Col2.dat b/Test_Cases/IEA-15-240-RWT-UMaineSemi/StC-Force-Col2.dat new file mode 100644 index 00000000..83e86cf8 --- /dev/null +++ b/Test_Cases/IEA-15-240-RWT-UMaineSemi/StC-Force-Col2.dat @@ -0,0 +1,95 @@ +------- STRUCTURAL CONTROL (StC) INPUT FILE ---------------------------- +Input file for tuned mass damper, module by Matt Lackner, Meghan Glade, and Semyung Park (UMass) +---------------------- SIMULATION CONTROL -------------------------------------- +True Echo - Echo input data to .ech (flag) +---------------------- StC DEGREES OF FREEDOM ---------------------------------- + 5 StC_DOF_MODE - DOF mode (switch) {0: No StC or TLCD DOF; 1: StC_X_DOF, StC_Y_DOF, and/or StC_Z_DOF (three independent StC DOFs); 2: StC_XY_DOF (Omni-Directional StC); 3: TLCD; 4: Prescribed force/moment time series} +false StC_X_DOF - DOF on or off for StC X (flag) [Used only when StC_DOF_MODE=1] +false StC_Y_DOF - DOF on or off for StC Y (flag) [Used only when StC_DOF_MODE=1] +false StC_Z_DOF - DOF on or off for StC Z (flag) [Used only when StC_DOF_MODE=1] +---------------------- StC LOCATION ------------------------------------------- [relative to the reference origin of component attached to] +25.874997 StC_P_X - At rest X position of StC (m) +44.816815 StC_P_Y - At rest Y position of StC (m) + -10 StC_P_Z - At rest Z position of StC (m) +---------------------- StC INITIAL CONDITIONS --------------------------------- [used only when StC_DOF_MODE=1 or 2] + 0 StC_X_DSP - StC X initial displacement (m) [relative to at rest position] + 0 StC_Y_DSP - StC Y initial displacement (m) [relative to at rest position] + 0 StC_Z_DSP - StC Z initial displacement (m) [relative to at rest position; used only when StC_DOF_MODE=1 and StC_Z_DOF=TRUE] +"none" StC_Z_PreLd - StC Z pre-load (N) {"gravity" to offset for gravity load; "none" or 0 to turn off} [used only when StC_DOF_MODE=1 and StC_Z_DOF=TRUE] +---------------------- StC CONFIGURATION -------------------------------------- [used only when StC_DOF_MODE=1 or 2] + 0 StC_X_PSP - Positive stop position (maximum X mass displacement) (m) + 0 StC_X_NSP - Negative stop position (minimum X mass displacement) (m) + 0 StC_Y_PSP - Positive stop position (maximum Y mass displacement) (m) + 0 StC_Y_NSP - Negative stop position (minimum Y mass displacement) (m) + 0 StC_Z_PSP - Positive stop position (maximum Z mass displacement) (m) [used only when StC_DOF_MODE=1 and StC_Z_DOF=TRUE] + 0 StC_Z_NSP - Negative stop position (minimum Z mass displacement) (m) [used only when StC_DOF_MODE=1 and StC_Z_DOF=TRUE] +---------------------- StC MASS, STIFFNESS, & DAMPING ------------------------- [used only when StC_DOF_MODE=1 or 2] + 0 StC_X_M - StC X mass (kg) [must equal StC_Y_M for StC_DOF_MODE = 2] + 1 StC_Y_M - StC Y mass (kg) [must equal StC_X_M for StC_DOF_MODE = 2] + 0 StC_Z_M - StC Z mass (kg) [used only when StC_DOF_MODE=1 and StC_Z_DOF=TRUE] + 0 StC_XY_M - StC XY mass (kg) [used only when StC_DOF_MODE=2] + 0 StC_X_K - StC X stiffness (N/m) + 0 StC_Y_K - StC Y stiffness (N/m) + 1e8 StC_Z_K - StC Z stiffness (N/m) [used only when StC_DOF_MODE=1 and StC_Z_DOF=TRUE] + 0 StC_X_C - StC X damping (N/(m/s)) + 0 StC_Y_C - StC Y damping (N/(m/s)) + 100 StC_Z_C - StC Z damping (N/(m/s)) [used only when StC_DOF_MODE=1 and StC_Z_DOF=TRUE] + 0 StC_X_KS - Stop spring X stiffness (N/m) + 0 StC_Y_KS - Stop spring Y stiffness (N/m) + 0 StC_Z_KS - Stop spring Z stiffness (N/m) [used only when StC_DOF_MODE=1 and StC_Z_DOF=TRUE] + 0 StC_X_CS - Stop spring X damping (N/(m/s)) + 0 StC_Y_CS - Stop spring Y damping (N/(m/s)) + 0 StC_Z_CS - Stop spring Z damping (N/(m/s)) [used only when StC_DOF_MODE=1 and StC_Z_DOF=TRUE] +---------------------- StC USER-DEFINED SPRING FORCES ------------------------- [used only when StC_DOF_MODE=1 or 2] +False Use_F_TBL - Use spring force from user-defined table (flag) + 17 NKInpSt - Number of spring force input stations +---------------------- StC SPRING FORCES TABLE -------------------------------- [used only when StC_DOF_MODE=1 or 2] + X F_X Y F_Y Z F_Z + (m) (N) (m) (N) (m) (N) +-6.0000000E+00 -4.8000000E+06 -6.0000000E+00 -4.8000000E+06 -6.0000000E+00 -4.8000000E+06 +-5.0000000E+00 -2.4000000E+06 -5.0000000E+00 -2.4000000E+06 -5.0000000E+00 -2.4000000E+06 +-4.5000000E+00 -1.2000000E+06 -4.5000000E+00 -1.2000000E+06 -4.5000000E+00 -1.2000000E+06 +-4.0000000E+00 -6.0000000E+05 -4.0000000E+00 -6.0000000E+05 -4.0000000E+00 -6.0000000E+05 +-3.5000000E+00 -3.0000000E+05 -3.5000000E+00 -3.0000000E+05 -3.5000000E+00 -3.0000000E+05 +-3.0000000E+00 -1.5000000E+05 -3.0000000E+00 -1.5000000E+05 -3.0000000E+00 -1.5000000E+05 +-2.5000000E+00 -1.0000000E+05 -2.5000000E+00 -1.0000000E+05 -2.5000000E+00 -1.0000000E+05 +-2.0000000E+00 -6.5000000E+04 -2.0000000E+00 -6.5000000E+04 -2.0000000E+00 -6.5000000E+04 + 0.0000000E+00 0.0000000E+00 0.0000000E+00 0.0000000E+00 0.0000000E+00 0.0000000E+00 + 2.0000000E+00 6.5000000E+04 2.0000000E+00 6.5000000E+04 2.0000000E+00 6.5000000E+04 + 2.5000000E+00 1.0000000E+05 2.5000000E+00 1.0000000E+05 2.5000000E+00 1.0000000E+05 + 3.0000000E+00 1.5000000E+05 3.0000000E+00 1.5000000E+05 3.0000000E+00 1.5000000E+05 + 3.5000000E+00 3.0000000E+05 3.5000000E+00 3.0000000E+05 3.5000000E+00 3.0000000E+05 + 4.0000000E+00 6.0000000E+05 4.0000000E+00 6.0000000E+05 4.0000000E+00 6.0000000E+05 + 4.5000000E+00 1.2000000E+06 4.5000000E+00 1.2000000E+06 4.5000000E+00 1.2000000E+06 + 5.0000000E+00 2.4000000E+06 5.0000000E+00 2.4000000E+06 5.0000000E+00 2.4000000E+06 + 6.0000000E+00 4.8000000E+06 6.0000000E+00 4.8000000E+06 6.0000000E+00 4.8000000E+06 +---------------------- StructCtrl CONTROL -------------------------------------------- [used only when StC_DOF_MODE=1 or 2] + 5 StC_CMODE - Control mode (switch) {0:none; 1: Semi-Active Control Mode; 4: Active Control Mode through Simulink (not available); 5: Active Control Mode through Bladed interface} + 2 StC_CChan - Control channel group (1:10) for stiffness and damping (StC_[XYZ]_K, StC_[XYZ]_C, and StC_[XYZ]_Brake) (specify additional channels for blade instances of StC active control -- one channel per blade) [used only when StC_DOF_MODE=1 or 2, and StC_CMODE=4 or 5] + 1 StC_SA_MODE - Semi-Active control mode {1: velocity-based ground hook control; 2: Inverse velocity-based ground hook control; 3: displacement-based ground hook control 4: Phase difference Algorithm with Friction Force 5: Phase difference Algorithm with Damping Force} (-) + 0 StC_X_C_HIGH - StC X high damping for ground hook control + 0 StC_X_C_LOW - StC X low damping for ground hook control + 0 StC_Y_C_HIGH - StC Y high damping for ground hook control + 0 StC_Y_C_LOW - StC Y low damping for ground hook control + 0 StC_Z_C_HIGH - StC Z high damping for ground hook control [used only when StC_DOF_MODE=1 and StC_Z_DOF=TRUE] + 0 StC_Z_C_LOW - StC Z low damping for ground hook control [used only when StC_DOF_MODE=1 and StC_Z_DOF=TRUE] + 0 StC_X_C_BRAKE - StC X high damping for braking the StC (Don't use it now. should be zero) + 0 StC_Y_C_BRAKE - StC Y high damping for braking the StC (Don't use it now. should be zero) + 0 StC_Z_C_BRAKE - StC Z high damping for braking the StC (Don't use it now. should be zero) [used only when StC_DOF_MODE=1 and StC_Z_DOF=TRUE] +---------------------- TLCD --------------------------------------------------- [used only when StC_DOF_MODE=3] + 7.9325 L_X - X TLCD total length (m) + 6.5929 B_X - X TLCD horizontal length (m) + 2.0217 area_X - X TLCD cross-sectional area of vertical column (m^2) + 0.913 area_ratio_X - X TLCD cross-sectional area ratio (vertical column area divided by horizontal column area) (-) + 2.5265 headLossCoeff_X - X TLCD head loss coeff (-) + 1000 rho_X - X TLCD liquid density (kg/m^3) + 3.5767 L_Y - Y TLCD total length (m) + 2.1788 B_Y - Y TLCD horizontal length (m) + 1.2252 area_Y - Y TLCD cross-sectional area of vertical column (m^2) + 2.7232 area_ratio_Y - Y TLCD cross-sectional area ratio (vertical column area divided by horizontal column area) (-) + 0.6433 headLossCoeff_Y - Y TLCD head loss coeff (-) + 1000 rho_Y - Y TLCD liquid density (kg/m^3) +---------------------- PRESCRIBED TIME SERIES --------------------------------- [used only when StC_DOF_MODE=4] + 1 PrescribedForcesCoord- Prescribed forces are in global or local coordinates (switch) {1: global; 2: local} +"Bld-TimeForceSeries.dat" PrescribedForcesFile - Time series force and moment (7 columns of time, FX, FY, FZ, MX, MY, MZ) +------------------------------------------------------------------------------- \ No newline at end of file diff --git a/Test_Cases/IEA-15-240-RWT-UMaineSemi/StC-Force-Col3.dat b/Test_Cases/IEA-15-240-RWT-UMaineSemi/StC-Force-Col3.dat new file mode 100644 index 00000000..0488dc80 --- /dev/null +++ b/Test_Cases/IEA-15-240-RWT-UMaineSemi/StC-Force-Col3.dat @@ -0,0 +1,95 @@ +------- STRUCTURAL CONTROL (StC) INPUT FILE ---------------------------- +Input file for tuned mass damper, module by Matt Lackner, Meghan Glade, and Semyung Park (UMass) +---------------------- SIMULATION CONTROL -------------------------------------- +True Echo - Echo input data to .ech (flag) +---------------------- StC DEGREES OF FREEDOM ---------------------------------- + 5 StC_DOF_MODE - DOF mode (switch) {0: No StC or TLCD DOF; 1: StC_X_DOF, StC_Y_DOF, and/or StC_Z_DOF (three independent StC DOFs); 2: StC_XY_DOF (Omni-Directional StC); 3: TLCD; 4: Prescribed force/moment time series} +false StC_X_DOF - DOF on or off for StC X (flag) [Used only when StC_DOF_MODE=1] +false StC_Y_DOF - DOF on or off for StC Y (flag) [Used only when StC_DOF_MODE=1] +false StC_Z_DOF - DOF on or off for StC Z (flag) [Used only when StC_DOF_MODE=1] +---------------------- StC LOCATION ------------------------------------------- [relative to the reference origin of component attached to] +25.874997 StC_P_X - At rest X position of StC (m) +-44.816815 StC_P_Y - At rest Y position of StC (m) + -10 StC_P_Z - At rest Z position of StC (m) +---------------------- StC INITIAL CONDITIONS --------------------------------- [used only when StC_DOF_MODE=1 or 2] + 0 StC_X_DSP - StC X initial displacement (m) [relative to at rest position] + 0 StC_Y_DSP - StC Y initial displacement (m) [relative to at rest position] + 0 StC_Z_DSP - StC Z initial displacement (m) [relative to at rest position; used only when StC_DOF_MODE=1 and StC_Z_DOF=TRUE] +"none" StC_Z_PreLd - StC Z pre-load (N) {"gravity" to offset for gravity load; "none" or 0 to turn off} [used only when StC_DOF_MODE=1 and StC_Z_DOF=TRUE] +---------------------- StC CONFIGURATION -------------------------------------- [used only when StC_DOF_MODE=1 or 2] + 0 StC_X_PSP - Positive stop position (maximum X mass displacement) (m) + 0 StC_X_NSP - Negative stop position (minimum X mass displacement) (m) + 0 StC_Y_PSP - Positive stop position (maximum Y mass displacement) (m) + 0 StC_Y_NSP - Negative stop position (minimum Y mass displacement) (m) + 0 StC_Z_PSP - Positive stop position (maximum Z mass displacement) (m) [used only when StC_DOF_MODE=1 and StC_Z_DOF=TRUE] + 0 StC_Z_NSP - Negative stop position (minimum Z mass displacement) (m) [used only when StC_DOF_MODE=1 and StC_Z_DOF=TRUE] +---------------------- StC MASS, STIFFNESS, & DAMPING ------------------------- [used only when StC_DOF_MODE=1 or 2] + 0 StC_X_M - StC X mass (kg) [must equal StC_Y_M for StC_DOF_MODE = 2] + 1 StC_Y_M - StC Y mass (kg) [must equal StC_X_M for StC_DOF_MODE = 2] + 0 StC_Z_M - StC Z mass (kg) [used only when StC_DOF_MODE=1 and StC_Z_DOF=TRUE] + 0 StC_XY_M - StC XY mass (kg) [used only when StC_DOF_MODE=2] + 0 StC_X_K - StC X stiffness (N/m) + 0 StC_Y_K - StC Y stiffness (N/m) + 1e8 StC_Z_K - StC Z stiffness (N/m) [used only when StC_DOF_MODE=1 and StC_Z_DOF=TRUE] + 0 StC_X_C - StC X damping (N/(m/s)) + 0 StC_Y_C - StC Y damping (N/(m/s)) + 100 StC_Z_C - StC Z damping (N/(m/s)) [used only when StC_DOF_MODE=1 and StC_Z_DOF=TRUE] + 0 StC_X_KS - Stop spring X stiffness (N/m) + 0 StC_Y_KS - Stop spring Y stiffness (N/m) + 0 StC_Z_KS - Stop spring Z stiffness (N/m) [used only when StC_DOF_MODE=1 and StC_Z_DOF=TRUE] + 0 StC_X_CS - Stop spring X damping (N/(m/s)) + 0 StC_Y_CS - Stop spring Y damping (N/(m/s)) + 0 StC_Z_CS - Stop spring Z damping (N/(m/s)) [used only when StC_DOF_MODE=1 and StC_Z_DOF=TRUE] +---------------------- StC USER-DEFINED SPRING FORCES ------------------------- [used only when StC_DOF_MODE=1 or 2] +False Use_F_TBL - Use spring force from user-defined table (flag) + 17 NKInpSt - Number of spring force input stations +---------------------- StC SPRING FORCES TABLE -------------------------------- [used only when StC_DOF_MODE=1 or 2] + X F_X Y F_Y Z F_Z + (m) (N) (m) (N) (m) (N) +-6.0000000E+00 -4.8000000E+06 -6.0000000E+00 -4.8000000E+06 -6.0000000E+00 -4.8000000E+06 +-5.0000000E+00 -2.4000000E+06 -5.0000000E+00 -2.4000000E+06 -5.0000000E+00 -2.4000000E+06 +-4.5000000E+00 -1.2000000E+06 -4.5000000E+00 -1.2000000E+06 -4.5000000E+00 -1.2000000E+06 +-4.0000000E+00 -6.0000000E+05 -4.0000000E+00 -6.0000000E+05 -4.0000000E+00 -6.0000000E+05 +-3.5000000E+00 -3.0000000E+05 -3.5000000E+00 -3.0000000E+05 -3.5000000E+00 -3.0000000E+05 +-3.0000000E+00 -1.5000000E+05 -3.0000000E+00 -1.5000000E+05 -3.0000000E+00 -1.5000000E+05 +-2.5000000E+00 -1.0000000E+05 -2.5000000E+00 -1.0000000E+05 -2.5000000E+00 -1.0000000E+05 +-2.0000000E+00 -6.5000000E+04 -2.0000000E+00 -6.5000000E+04 -2.0000000E+00 -6.5000000E+04 + 0.0000000E+00 0.0000000E+00 0.0000000E+00 0.0000000E+00 0.0000000E+00 0.0000000E+00 + 2.0000000E+00 6.5000000E+04 2.0000000E+00 6.5000000E+04 2.0000000E+00 6.5000000E+04 + 2.5000000E+00 1.0000000E+05 2.5000000E+00 1.0000000E+05 2.5000000E+00 1.0000000E+05 + 3.0000000E+00 1.5000000E+05 3.0000000E+00 1.5000000E+05 3.0000000E+00 1.5000000E+05 + 3.5000000E+00 3.0000000E+05 3.5000000E+00 3.0000000E+05 3.5000000E+00 3.0000000E+05 + 4.0000000E+00 6.0000000E+05 4.0000000E+00 6.0000000E+05 4.0000000E+00 6.0000000E+05 + 4.5000000E+00 1.2000000E+06 4.5000000E+00 1.2000000E+06 4.5000000E+00 1.2000000E+06 + 5.0000000E+00 2.4000000E+06 5.0000000E+00 2.4000000E+06 5.0000000E+00 2.4000000E+06 + 6.0000000E+00 4.8000000E+06 6.0000000E+00 4.8000000E+06 6.0000000E+00 4.8000000E+06 +---------------------- StructCtrl CONTROL -------------------------------------------- [used only when StC_DOF_MODE=1 or 2] + 5 StC_CMODE - Control mode (switch) {0:none; 1: Semi-Active Control Mode; 4: Active Control Mode through Simulink (not available); 5: Active Control Mode through Bladed interface} + 3 StC_CChan - Control channel group (1:10) for stiffness and damping (StC_[XYZ]_K, StC_[XYZ]_C, and StC_[XYZ]_Brake) (specify additional channels for blade instances of StC active control -- one channel per blade) [used only when StC_DOF_MODE=1 or 2, and StC_CMODE=4 or 5] + 1 StC_SA_MODE - Semi-Active control mode {1: velocity-based ground hook control; 2: Inverse velocity-based ground hook control; 3: displacement-based ground hook control 4: Phase difference Algorithm with Friction Force 5: Phase difference Algorithm with Damping Force} (-) + 0 StC_X_C_HIGH - StC X high damping for ground hook control + 0 StC_X_C_LOW - StC X low damping for ground hook control + 0 StC_Y_C_HIGH - StC Y high damping for ground hook control + 0 StC_Y_C_LOW - StC Y low damping for ground hook control + 0 StC_Z_C_HIGH - StC Z high damping for ground hook control [used only when StC_DOF_MODE=1 and StC_Z_DOF=TRUE] + 0 StC_Z_C_LOW - StC Z low damping for ground hook control [used only when StC_DOF_MODE=1 and StC_Z_DOF=TRUE] + 0 StC_X_C_BRAKE - StC X high damping for braking the StC (Don't use it now. should be zero) + 0 StC_Y_C_BRAKE - StC Y high damping for braking the StC (Don't use it now. should be zero) + 0 StC_Z_C_BRAKE - StC Z high damping for braking the StC (Don't use it now. should be zero) [used only when StC_DOF_MODE=1 and StC_Z_DOF=TRUE] +---------------------- TLCD --------------------------------------------------- [used only when StC_DOF_MODE=3] + 7.9325 L_X - X TLCD total length (m) + 6.5929 B_X - X TLCD horizontal length (m) + 2.0217 area_X - X TLCD cross-sectional area of vertical column (m^2) + 0.913 area_ratio_X - X TLCD cross-sectional area ratio (vertical column area divided by horizontal column area) (-) + 2.5265 headLossCoeff_X - X TLCD head loss coeff (-) + 1000 rho_X - X TLCD liquid density (kg/m^3) + 3.5767 L_Y - Y TLCD total length (m) + 2.1788 B_Y - Y TLCD horizontal length (m) + 1.2252 area_Y - Y TLCD cross-sectional area of vertical column (m^2) + 2.7232 area_ratio_Y - Y TLCD cross-sectional area ratio (vertical column area divided by horizontal column area) (-) + 0.6433 headLossCoeff_Y - Y TLCD head loss coeff (-) + 1000 rho_Y - Y TLCD liquid density (kg/m^3) +---------------------- PRESCRIBED TIME SERIES --------------------------------- [used only when StC_DOF_MODE=4] + 1 PrescribedForcesCoord- Prescribed forces are in global or local coordinates (switch) {1: global; 2: local} +"Bld-TimeForceSeries.dat" PrescribedForcesFile - Time series force and moment (7 columns of time, FX, FY, FZ, MX, MY, MZ) +------------------------------------------------------------------------------- \ No newline at end of file diff --git a/Test_Cases/NREL-5MW/DISCON.IN b/Test_Cases/NREL-5MW/DISCON.IN index e3c2ae45..3da89959 100644 --- a/Test_Cases/NREL-5MW/DISCON.IN +++ b/Test_Cases/NREL-5MW/DISCON.IN @@ -1,11 +1,12 @@ ! Controller parameter input file for the NREL-5MW wind turbine -! - File written using ROSCO version 2.7.0 controller tuning logic on 02/06/23 +! - File written using ROSCO version 2.7.0 controller tuning logic on 02/28/23 !------- DEBUG ------------------------------------------------------------ -1 ! LoggingLevel - {0: write no debug files, 1: write standard output .dbg-file, 2: LoggingLevel 1 + ROSCO LocalVars (.dbg2) 3: LoggingLevel 2 + complete avrSWAP-array (.dbg3)} +1 ! LoggingLevel - (0: write no debug files, 1: write standard output .dbg-file, 2: LoggingLevel 1 + ROSCO LocalVars (.dbg2) 3: LoggingLevel 2 + complete avrSWAP-array (.dbg3)) +0 ! Echo - (0 - no Echo, 1 - Echo input data to .echo) !------- 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 +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 and/or tower fore-aft motion (for floating) {0: disable, 1: generator speed, 2: tower-top fore-aft motion, 3: generator speed and tower-top fore-aft motion} 0 ! IPC_ControlMode - Turn Individual Pitch Control (IPC) for fatigue load reductions (pitch contribution) {0: off, 1: 1P reductions, 2: 1P+2P reductions} 3 ! VS_ControlMode - Generator torque control mode in above rated conditions {0: constant torque, 1: constant power, 2: TSR tracking PI control with constant torque, 3: TSR tracking PI control with constant power} @@ -23,6 +24,8 @@ 0 ! PF_Mode - Pitch fault mode {0 - not used, 1 - constant offset on one or more blades} 0 ! Ext_Mode - External control mode {0 - not used, 1 - call external dynamic library} 0 ! ZMQ_Mode - Fuse ZeroMQ interface {0: unused, 1: Yaw Control} +0 ! CC_Mode - Cable control mode [0- unused, 1- User defined, 2- Position control (not yet implemented)] +0 ! StC_Mode - Structural control mode [0- unused, 1- User defined] !------- FILTERS ---------------------------------------------------------- 1.57080 ! F_LPFCornerFreq - Corner frequency (-3dB point) in the low-pass filters, [rad/s] @@ -148,3 +151,12 @@ !------- ZeroMQ Interface --------------------------------------------------------- "tcp://localhost:5555" ! ZMQ_CommAddress - Communication address for ZMQ server, (e.g. "tcp://localhost:5555") 2 ! ZMQ_UpdatePeriod - Call ZeroMQ every [x] seconds, [s] + +!------- Cable Control --------------------------------------------------------- +1 ! CC_Group_N - Number of cable control groups + 0 ! CC_GroupIndex - First index for cable control group, should correspond to deltaL +20.000000 ! CC_ActTau - Time constant for line actuator [s] + +!------- Structural Controllers --------------------------------------------------------- +1 ! StC_Group_N - Number of cable control groups + 0 ! StC_GroupIndex - First index for structural control group, options specified in ServoDyn summary output diff --git a/Tune_Cases/IEA15MW_ballast.yaml b/Tune_Cases/IEA15MW_ballast.yaml new file mode 100644 index 00000000..6bf34418 --- /dev/null +++ b/Tune_Cases/IEA15MW_ballast.yaml @@ -0,0 +1,59 @@ +# --------------------- ROSCO controller tuning input file ------------------- + # Written for use with ROSCO_Toolbox tuning procedures + # Turbine: IEA 15MW Reference Wind Turbine +# ------------------------------ OpenFAST PATH DEFINITIONS ------------------------------ +path_params: + FAST_InputFile: 'IEA-15-240-RWT-UMaineSemi.fst' # Name of *.fst file + FAST_directory: '../Test_Cases/IEA-15-240-RWT-UMaineSemi' # Main OpenFAST model directory, where the *.fst lives + # Optional (but suggested...) + rotor_performance_filename: 'Cp_Ct_Cq.IEA15MW.txt' # Filename for rotor performance text file (if it has been generated by ccblade already) + +# -------------------------------- TURBINE PARAMETERS ----------------------------------- +turbine_params: + rotor_inertia: 310619488. # Rotor inertia [kg m^2], {Available in Elastodyn .sum file} + rated_rotor_speed: 0.7916813478 # Rated rotor speed [rad/s] + v_min: 3. # Cut-in wind speed [m/s] + v_rated: 10.74 # Rated wind speed [m/s] + v_max: 25.0 # Cut-out wind speed [m/s], -- Does not need to be exact (JUST ASSUME FOR NOW) + max_pitch_rate: 0.0349 # Maximum blade pitch rate [rad/s] + max_torque_rate: 4500000. # Maximum torque rate [Nm/s], {~1/4 VS_RtTq/s} + rated_power: 15000000. # Rated Power [W] + bld_edgewise_freq: 4.0324 # Blade edgewise first natural frequency [rad/s] + bld_flapwise_freq: 3.4872 # Blade flapwise first natural frequency [rad/s] + TSR_operational: 9.0 + +#------------------------------- CONTROLLER PARAMETERS ---------------------------------- +controller_params: + # Controller flags + LoggingLevel: 3 # {0: write no debug files, 1: write standard output .dbg-file, 2: write standard output .dbg-file and complete avrSWAP-array .dbg2-file + F_LPFType: 2 # {1: first-order low-pass filter, 2: second-order low-pass filter}, [rad/s] (currently filters generator speed and pitch control signals) + F_NotchType: 0 # Notch on the measured generator speed {0: disable, 1: enable} + IPC_ControlMode: 0 # Turn Individual Pitch Control (IPC) for fatigue load reductions (pitch contribution) {0: off, 1: 1P reductions, 2: 1P+2P reductions} + VS_ControlMode: 2 # Generator torque control mode in above rated conditions {0: constant torque, 1: constant power, 2: TSR tracking PI control} + PC_ControlMode: 1 # Blade pitch control mode {0: No pitch, fix to fine pitch, 1: active PI blade pitch control} + Y_ControlMode: 0 # Yaw control mode {0: no yaw control, 1: yaw rate control, 2: yaw-by-IPC} + SS_Mode: 1 # Setpoint Smoother mode {0: no setpoint smoothing, 1: introduce setpoint smoothing} + WE_Mode: 2 # Wind speed estimator mode {0: One-second low pass filtered hub height wind speed, 1: Immersion and Invariance Estimator (Ortega et al.)} + PS_Mode: 3 # Pitch saturation mode {0: no pitch saturation, 1: peak shaving, 2: Cp-maximizing pitch saturation, 3: peak shaving and Cp-maximizing pitch saturation} + SD_Mode: 0 # Shutdown mode {0: no shutdown procedure, 1: pitch to max pitch at shutdown} + Fl_Mode: 2 # Floating specific feedback mode {0: no nacelle velocity feedback, 1: nacelle velocity feedback} + Flp_Mode: 0 # Flap control mode {0: no flap control, 1: steady state flap angle, 2: Proportional flap control} + PA_Mode: 2 # Pitch actuator mode {0 - not used, 1 - first order filter, 2 - second order filter} + StC_Mode: 1 + # Controller parameters + # U_pc: [14] + zeta_pc: 1.0 # Pitch controller desired damping ratio [-] + omega_pc: 0.2 # Pitch controller desired natural frequency [rad/s] + zeta_vs: 0.85 # Torque controller desired damping ratio [-] + omega_vs: 0.12 # Torque controller desired natural frequency [rad/s] + twr_freq: 3.355 # for semi only! + ptfm_freq: 0.213 # for semi only! + # Optional - these can be defined, but do not need to be + min_pitch: 0.0 # Minimum pitch angle [rad], {default = 0 degrees} + vs_minspd: 0.523598775 # Minimum rotor speed [rad/s], {default = 0 rad/s} + ps_percent: 0.8 # Percent peak shaving [%, <= 1 ], {default = 80%} + PA_CornerFreq: 1.5708 # Pitch actuator natural frequency [rad/s] + PA_Damping: 0.707 # Pitch actuator natural frequency [rad/s] + DISCON: + StC_GroupIndex: [2818, 2838, 2858] + diff --git a/Tune_Cases/IEA15MW_cable.yaml b/Tune_Cases/IEA15MW_cable.yaml new file mode 100644 index 00000000..c17b006b --- /dev/null +++ b/Tune_Cases/IEA15MW_cable.yaml @@ -0,0 +1,59 @@ +# --------------------- ROSCO controller tuning input file ------------------- + # Written for use with ROSCO_Toolbox tuning procedures + # Turbine: IEA 15MW Reference Wind Turbine +# ------------------------------ OpenFAST PATH DEFINITIONS ------------------------------ +path_params: + FAST_InputFile: 'IEA-15-240-RWT-UMaineSemi.fst' # Name of *.fst file + FAST_directory: '../Test_Cases/IEA-15-240-RWT-UMaineSemi' # Main OpenFAST model directory, where the *.fst lives + # Optional (but suggested...) + rotor_performance_filename: 'Cp_Ct_Cq.IEA15MW.txt' # Filename for rotor performance text file (if it has been generated by ccblade already) + +# -------------------------------- TURBINE PARAMETERS ----------------------------------- +turbine_params: + rotor_inertia: 310619488. # Rotor inertia [kg m^2], {Available in Elastodyn .sum file} + rated_rotor_speed: 0.7916813478 # Rated rotor speed [rad/s] + v_min: 3. # Cut-in wind speed [m/s] + v_rated: 10.74 # Rated wind speed [m/s] + v_max: 25.0 # Cut-out wind speed [m/s], -- Does not need to be exact (JUST ASSUME FOR NOW) + max_pitch_rate: 0.0349 # Maximum blade pitch rate [rad/s] + max_torque_rate: 4500000. # Maximum torque rate [Nm/s], {~1/4 VS_RtTq/s} + rated_power: 15000000. # Rated Power [W] + bld_edgewise_freq: 4.0324 # Blade edgewise first natural frequency [rad/s] + bld_flapwise_freq: 3.4872 # Blade flapwise first natural frequency [rad/s] + TSR_operational: 9.0 + +#------------------------------- CONTROLLER PARAMETERS ---------------------------------- +controller_params: + # Controller flags + LoggingLevel: 3 # {0: write no debug files, 1: write standard output .dbg-file, 2: write standard output .dbg-file and complete avrSWAP-array .dbg2-file + F_LPFType: 2 # {1: first-order low-pass filter, 2: second-order low-pass filter}, [rad/s] (currently filters generator speed and pitch control signals) + F_NotchType: 0 # Notch on the measured generator speed {0: disable, 1: enable} + IPC_ControlMode: 0 # Turn Individual Pitch Control (IPC) for fatigue load reductions (pitch contribution) {0: off, 1: 1P reductions, 2: 1P+2P reductions} + VS_ControlMode: 2 # Generator torque control mode in above rated conditions {0: constant torque, 1: constant power, 2: TSR tracking PI control} + PC_ControlMode: 1 # Blade pitch control mode {0: No pitch, fix to fine pitch, 1: active PI blade pitch control} + Y_ControlMode: 0 # Yaw control mode {0: no yaw control, 1: yaw rate control, 2: yaw-by-IPC} + SS_Mode: 1 # Setpoint Smoother mode {0: no setpoint smoothing, 1: introduce setpoint smoothing} + WE_Mode: 2 # Wind speed estimator mode {0: One-second low pass filtered hub height wind speed, 1: Immersion and Invariance Estimator (Ortega et al.)} + PS_Mode: 3 # Pitch saturation mode {0: no pitch saturation, 1: peak shaving, 2: Cp-maximizing pitch saturation, 3: peak shaving and Cp-maximizing pitch saturation} + SD_Mode: 0 # Shutdown mode {0: no shutdown procedure, 1: pitch to max pitch at shutdown} + Fl_Mode: 2 # Floating specific feedback mode {0: no nacelle velocity feedback, 1: nacelle velocity feedback} + Flp_Mode: 0 # Flap control mode {0: no flap control, 1: steady state flap angle, 2: Proportional flap control} + PA_Mode: 2 # Pitch actuator mode {0 - not used, 1 - first order filter, 2 - second order filter} + CC_Mode: 1 + # Controller parameters + # U_pc: [14] + zeta_pc: 1.0 # Pitch controller desired damping ratio [-] + omega_pc: 0.2 # Pitch controller desired natural frequency [rad/s] + zeta_vs: 0.85 # Torque controller desired damping ratio [-] + omega_vs: 0.12 # Torque controller desired natural frequency [rad/s] + twr_freq: 3.355 # for semi only! + ptfm_freq: 0.213 # for semi only! + # Optional - these can be defined, but do not need to be + min_pitch: 0.0 # Minimum pitch angle [rad], {default = 0 degrees} + vs_minspd: 0.523598775 # Minimum rotor speed [rad/s], {default = 0 rad/s} + ps_percent: 0.8 # Percent peak shaving [%, <= 1 ], {default = 80%} + PA_CornerFreq: 1.5708 # Pitch actuator natural frequency [rad/s] + PA_Damping: 0.707 # Pitch actuator natural frequency [rad/s] + DISCON: + CC_GroupIndex: [2601, 2603, 2605] + diff --git a/docs/source/api_change.rst b/docs/source/api_change.rst index f6ad8a57..c3463bf7 100644 --- a/docs/source/api_change.rst +++ b/docs/source/api_change.rst @@ -9,6 +9,34 @@ The changes are tabulated according to the line number, and flag name. The line number corresponds to the resulting line number after all changes are implemented. Thus, be sure to implement each in order so that subsequent line numbers are correct. +2.7.0 to develop +------------------------------- +Optional Inputs +- ROSCO now reads in the whole input file and searches for keywords to set the inputs. Blank spaces and specific ordering are no longer required. +- Input requirements depend on control modes. E.g., open loop inputs are not required if `OL_Mode = 0`` +IPC Saturation Modes +- Added options for saturating the IPC command with the peak shaving limit + +====== ================= ====================================================================================================================================================================================================== +New in ROSCO develop +---------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- +Line Input Name Example Value +====== ================= ====================================================================================================================================================================================================== +6 Echo 0 ! Echo - (0 - no Echo, 1 - Echo input data to .echo) +24 CC_Mode 0 ! CC_Mode - Cable control mode [0- unused, 1- User defined, 2- Position control (not yet implemented)] +28 StC_Mode 0 ! StC_Mode - Structural control mode [0- unused, 1- User defined] +154 Empty Line +155 CC_Section !------- Cable Control --------------------------------------------------------- +156 CC_Group_N 3 ! CC_Group_N - Number of cable control groups +157 CC_GroupIndex 2601 2603 2605 ! CC_GroupIndex - First index for cable control group, should correspond to deltaL +158 CC_ActTau 20.000000 ! CC_ActTau - Time constant for line actuator [s] +159 Empty Line +160 StC_Section !------- Structural Controllers --------------------------------------------------------- +161 StC_Group_N 3 ! StC_Group_N - Number of cable control groups +162 StC_GroupIndex 2818 2838 2858 ! StC_GroupIndex - First index for structural control group, options specified in ServoDyn summary output +====== ================= ====================================================================================================================================================================================================== + + 2.6.0 to 2.7.0 ------------------------------- Pitch Faults diff --git a/docs/source/toolbox_input.rst b/docs/source/toolbox_input.rst index 2c11d648..5b205c70 100644 --- a/docs/source/toolbox_input.rst +++ b/docs/source/toolbox_input.rst @@ -102,7 +102,7 @@ controller_params *Default* = 1 - *Minimum* = 0 *Maximum* = 2 + *Minimum* = 0 *Maximum* = 3 :code:`F_LPFType` : Float @@ -266,8 +266,25 @@ controller_params :code:`Ext_Mode` : Float - External control mode {{0 - not used, 1 - call external dynamic - library}} + External control mode [0 - not used, 1 - call external dynamic + library] + + *Default* = 0 + + *Minimum* = 0 *Maximum* = 1 + + +:code:`CC_Mode` : Float + Cable control mode [0- unused, 1- User defined, 2- Position + control (not yet implemented)] + + *Default* = 0 + + *Minimum* = 0 *Maximum* = 1 + + +:code:`StC_Mode` : Float + Structural control mode [0- unused, 1- User defined] *Default* = 0 @@ -567,6 +584,11 @@ These are pass-through parameters for the DISCON.IN file. Use with caution. write standard output .dbg-file and complete avrSWAP-array .dbg2-file) +:code:`Echo` : Float + 0 - no Echo, 1 - Echo input data to .echo + + *Default* = 0 + :code:`F_LPFType` : Float 1- first-order low-pass filter, 2- second-order low-pass filter (currently filters generator speed and pitch control signals @@ -925,6 +947,32 @@ These are pass-through parameters for the DISCON.IN file. Use with caution. :code:`PF_Offsets` : Array of Floats Pitch angle offsets for each blade (array with length of 3) +:code:`CC_Group_N` : Float + Number of cable control groups + + *Default* = 0 + +:code:`CC_GroupIndex` : Array of Floats + First index for cable control group, should correspond to deltaL + + *Default* = [0] + +:code:`CC_ActTau` : Float + Time constant for line actuator [s] + + *Default* = 20 + +:code:`StC_Group_N` : Float + Number of cable control groups + + *Default* = 0 + +:code:`StC_GroupIndex` : Array of Floats + First index for structural control group, options specified in + ServoDyn summary output + + *Default* = [0] + linmodel_tuning From ca7c44d8e7d85e8fed6b11ab09a9c2822d00e953 Mon Sep 17 00:00:00 2001 From: dzalkind Date: Tue, 7 Mar 2023 16:19:44 -0700 Subject: [PATCH 064/224] Tidy print statements, file writing --- ROSCO_toolbox/ofTools/case_gen/runFAST_pywrapper.py | 1 - ROSCO_toolbox/utilities.py | 10 +++++----- 2 files changed, 5 insertions(+), 6 deletions(-) diff --git a/ROSCO_toolbox/ofTools/case_gen/runFAST_pywrapper.py b/ROSCO_toolbox/ofTools/case_gen/runFAST_pywrapper.py index e347ed7f..886d496b 100644 --- a/ROSCO_toolbox/ofTools/case_gen/runFAST_pywrapper.py +++ b/ROSCO_toolbox/ofTools/case_gen/runFAST_pywrapper.py @@ -229,7 +229,6 @@ def __init__(self): run_dir = os.path.dirname( os.path.dirname( os.path.dirname( os.path.realpath(__file__) ) ) ) + os.sep self.FAST_exe = os.path.join(run_dir, 'local/bin/openfast') # Path to executable - print(self.FAST_exe) # self.FAST_lib = os.path.join(lib_dir, 'libopenfastlib'+libext) self.FAST_InputFile = None self.FAST_directory = None diff --git a/ROSCO_toolbox/utilities.py b/ROSCO_toolbox/utilities.py index c23e9645..5cc936b8 100644 --- a/ROSCO_toolbox/utilities.py +++ b/ROSCO_toolbox/utilities.py @@ -236,11 +236,11 @@ def write_DISCON(turbine, controller, param_file='DISCON.IN', txt_filename='Cp_C file.write('{} ! PF_Offsets - Constant blade pitch offsets for blades 1-3 [rad]\n'.format(''.join('{:<10.8f} '.format(rosco_vt['PF_Offsets'][i]) for i in range(3)))) file.write('\n') file.write('!------- Active Wake Control -----------------------------------------------------\n') - file.write('{0:<12d} ! AWC_NumModes - number of forcing modes\n'.format(int(rosco_vt['AWC_NumModes']))) - file.write('{} ! AWC_n - azimuthal mode number(s) (i.e., the number and direction of the lobes of the wake structure)\n'.format(write_array(rosco_vt['AWC_n'],'<4d'))) - file.write('{} ! AWC_freq - frequency(s) of forcing mode(s) [Hz]\n'.format(write_array(rosco_vt['AWC_freq'],'<6.4f'))) - file.write('{} ! AWC_amp - pitch amplitude(s) of forcing mode(s) (note that AWC_amp specifies the amplitude of each individual mode so that the total amplitude of pitching will be the sum of AWC_amp) [deg]\n'.format(write_array(rosco_vt['AWC_amp'],'<6.4f'))) - file.write('{} ! AWC_clockangle - clocking angle(s) of forcing mode(s) [deg]\n'.format(write_array(rosco_vt['AWC_clockangle'],'<6.4f'))) + file.write('{0:<12d} ! AWC_NumModes - Number of forcing modes\n'.format(int(rosco_vt['AWC_NumModes']))) + file.write('{} ! AWC_n - Azimuthal mode number(s) (i.e., the number and direction of the lobes of the wake structure)\n'.format(write_array(rosco_vt['AWC_n'],'<4d'))) + file.write('{} ! AWC_freq - Frequency(s) of forcing mode(s) [Hz]\n'.format(write_array(rosco_vt['AWC_freq'],'<6.4f'))) + file.write('{} ! AWC_amp - Pitch amplitude(s) of forcing mode(s) (note that AWC_amp specifies the amplitude of each individual mode so that the total amplitude of pitching will be the sum of AWC_amp) [deg]\n'.format(write_array(rosco_vt['AWC_amp'],'<6.4f'))) + file.write('{} ! AWC_clockangle - Clocking angle(s) of forcing mode(s) [deg]\n'.format(write_array(rosco_vt['AWC_clockangle'],'<6.4f'))) file.write('\n') file.write('!------- External Controller Interface -----------------------------------------------------\n') file.write('"{}" ! DLL_FileName - Name/location of the dynamic library in the Bladed-DLL format\n'.format(rosco_vt['DLL_FileName'])) From 4e2a77833e2d860e79904aad37d5c0680025d392 Mon Sep 17 00:00:00 2001 From: dzalkind Date: Tue, 7 Mar 2023 16:32:20 -0700 Subject: [PATCH 065/224] Remove duplicate PF_Offsets input read --- ROSCO/src/ReadSetParameters.f90 | 4 ---- 1 file changed, 4 deletions(-) diff --git a/ROSCO/src/ReadSetParameters.f90 b/ROSCO/src/ReadSetParameters.f90 index b6a2bb81..173b76c7 100644 --- a/ROSCO/src/ReadSetParameters.f90 +++ b/ROSCO/src/ReadSetParameters.f90 @@ -505,10 +505,6 @@ SUBROUTINE ReadControlParameterFileSub(CntrPar, zmqVar, accINFILE, accINFILE_siz CALL ParseAry(FileLines, 'PF_Offsets', CntrPar%PF_Offsets, 3, accINFILE(1), ErrVar, CntrPar%PF_Mode == 0, UnEc) IF (ErrVar%aviFAIL < 0) RETURN - !------------ Pitch Actuator Faults ------------ - CALL ParseAry(FileLines, 'PF_Offsets', CntrPar%PF_Offsets, 3, accINFILE(1), ErrVar, CntrPar%PF_Mode == 0, UnEc) - IF (ErrVar%aviFAIL < 0) RETURN - !------------ AWC input ------------ CALL ParseInput(FileLines, 'AWC_NumModes', CntrPar%AWC_NumModes, accINFILE(1), ErrVar, CntrPar%AWC_Mode == 0, UnEc) CALL ParseAry( FileLines, 'AWC_n', CntrPar%AWC_n, CntrPar%AWC_NumModes, accINFILE(1), ErrVar, CntrPar%AWC_Mode == 0, UnEc) From 74c7fcbfee6aadf86c0677caf1a315b675173467 Mon Sep 17 00:00:00 2001 From: dzalkind Date: Tue, 7 Mar 2023 16:45:53 -0700 Subject: [PATCH 066/224] Rename methods in readme --- Examples/20_active_wake_control.py | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/Examples/20_active_wake_control.py b/Examples/20_active_wake_control.py index 87f81910..84c800a4 100644 --- a/Examples/20_active_wake_control.py +++ b/Examples/20_active_wake_control.py @@ -6,7 +6,7 @@ Active wake control (AWC) with blade pitching is implemented in this example with an adaptation into the rotating frame of the mathematical framework from the classical theory for stability of axisymmetric jets [1], which offers flexibility in specifying the forcing strategy. ----------------------------------------------- -AWC_Mode = 1: Sandia National Laboratories (SNL) method: +AWC_Mode = 1: Complex number method: ----------------------------------------------- The inputs to the controller are: @@ -72,7 +72,7 @@ which is equivlanet to eq 6 above. ----------------------------------------------- -AWC_Mode = 2: National Renewable Energy Laboratory (NREL) implementation: +AWC_Mode = 2: Coleman transform implementation: ----------------------------------------------- The inputs to the controller are: Name Unit Type Range Description From e4d7ec259cec780c8113eecd023f8c6e853ecae9 Mon Sep 17 00:00:00 2001 From: dzalkind Date: Tue, 7 Mar 2023 16:56:07 -0700 Subject: [PATCH 067/224] Tidy input writing, remove `future` references --- ROSCO_testing/ROSCO_testing.py | 1 - .../ofTools/fast_io/read_fast_input.py | 1202 ----------------- Test_Cases/BAR_10/BAR_10_DISCON.IN | 10 +- .../DISCON-UMaineSemi.IN | 10 +- Test_Cases/NREL-5MW/DISCON.IN | 10 +- .../NREL_2p8_127/NREL-2p8-127_DISCON.IN | 10 +- 6 files changed, 20 insertions(+), 1223 deletions(-) delete mode 100644 ROSCO_toolbox/ofTools/fast_io/read_fast_input.py diff --git a/ROSCO_testing/ROSCO_testing.py b/ROSCO_testing/ROSCO_testing.py index 00535118..6eb72716 100644 --- a/ROSCO_testing/ROSCO_testing.py +++ b/ROSCO_testing/ROSCO_testing.py @@ -17,7 +17,6 @@ import glob import multiprocessing as mp -import ROSCO_toolbox.ofTools.fast_io.read_fast_input as fast_io from ROSCO_toolbox.ofTools.fast_io.FAST_reader import InputReader_OpenFAST from ROSCO_toolbox.ofTools.case_gen.CaseGen_IEC import CaseGen_IEC from ROSCO_toolbox.ofTools.case_gen.runFAST_pywrapper import runFAST_pywrapper_batch diff --git a/ROSCO_toolbox/ofTools/fast_io/read_fast_input.py b/ROSCO_toolbox/ofTools/fast_io/read_fast_input.py deleted file mode 100644 index c8b76313..00000000 --- a/ROSCO_toolbox/ofTools/fast_io/read_fast_input.py +++ /dev/null @@ -1,1202 +0,0 @@ -''' -Reads OpenFAST input files. - -Most of this script is copied from: -https://github.com/OpenFAST/python-toolbox/blob/dev/pyFAST/input_output/fast_input_file.py -on 11/05/2020 - -''' - -from __future__ import division -from __future__ import unicode_literals -from __future__ import print_function -from __future__ import absolute_import -from io import open -from builtins import range -from builtins import str -from future import standard_library -standard_library.install_aliases() -from .file import File, WrongFormatError, BrokenFormatError -import os -import numpy as np -import re -import pandas as pd - -from ROSCO_toolbox.utilities import read_DISCON - -__all__ = ['FASTInputFile'] - -TABTYPE_NOT_A_TAB = 0 -TABTYPE_NUM_WITH_HEADER = 1 -TABTYPE_NUM_WITH_HEADERCOM = 2 -TABTYPE_NUM_NO_HEADER = 4 -TABTYPE_NUM_BEAMDYN = 5 -TABTYPE_MIX_WITH_HEADER = 6 -TABTYPE_FIL = 3 -TABTYPE_FMT = 9999 # TODO - -# --------------------------------------------------------------------------------} -# --- INPUT FILE -# --------------------------------------------------------------------------------{ -class FASTInputDeck(): - ''' - Read/write an OpenFAST input file deck. Behaves like a dictionary - ''' - def __init__(self, fst_file): - self.Fst = FASTInputFile(fst_file) - self.path = os.path.dirname(os.path.abspath(fst_file)) - - def load(self): - fst_dict = {} - try: - fst_dict['ElastoDyn'] = self.load_ElastoDyn() - except: - "Error loading {}".format(self.Fst['EDFile'].strip('\'').strip('\"')) - - try: - fst_dict['BDBldFile(1)'] = self.load_BDBldFile1() - except: - "Error loading {}".format(self.Fst['BDBldFile(1)'].strip('\'').strip('\"')) - - try: - fst_dict['BDBldFile(2)'] = self.load_BDBldFile2() - except: - "Error loading {}".format(self.Fst['BDBldFile(2)'].strip('\'').strip('\"')) - - try: - fst_dict['BDBldFile(3)'] = self.load_BDBldFile3() - except: - "Error loading {}".format(self.Fst['BDBldFile(3)'].strip('\'').strip('\"')) - - try: - fst_dict['InflowWind'] = self.load_InflowWind() - except: - "Error loading {}".format(self.Fst['InflowFile'].strip('\'').strip('\"')) - - try: - fst_dict['AeroDyn'] = self.load_AeroDyn() - except: - "Error loading {}".format(self.Fst['AeroFile'].strip('\'').strip('\"')) - - try: - fst_dict['ServoDyn'] = self.load_ServoDyn() - try: - fst_dict['DISCON_in'] = self.load_DISCON() - except: - "Error loading {}".format(self.ServoDyn['DLL_InFile'].strip('\'').strip('\"')) - - except: - "Error loading {}".format(self.Fst['ServoFile'].strip('\'').strip('\"')) - - try: - fst_dict['HydroDyn'] = self.load_HydroDyn() - except: - "Error loading {}".format(self.Fst['HydroFile'].strip('\'').strip('\"')) - - try: - fst_dict['SubDyn'] = self.load_SubDyn() - except: - "Error loading {}".format(self.Fst['SubFile'].strip('\'').strip('\"')) - - try: - fst_dict['MoorDyn'] = self.load_MoorDyn() - except: - "Error loading {}".format(self.Fst['MooringFile'].strip('\'').strip('\"')) - - try: - fst_dict['IceDyn'] = self.load_IceDyn() - except: - "Error loading {}".format(self.Fst['IceFile'].strip('\'').strip('\"')) - - - return fst_dict - - def load_ElastoDyn(self): - ED_fullfile = os.path.join(self.path, self.Fst['EDFile'].strip('\'').strip('\"')) - self.ElastoDyn = FASTInputFile(ED_fullfile) - return self.ElastoDyn - - def load_BDBldFile1(self): - BD1_fullfile = os.path.join(self.path, self.Fst['BDBldFile(1)'].strip('\'').strip('\"')) - self.BD1_fullfile = FASTInputFile(BD1_fullfile) - return self.load_BDBldFile1 - - def load_BDBldFile2(self): - BD2_fullfile = os.path.join(self.path, self.Fst['BDBldFile(2)'].strip('\'').strip('\"')) - self.BD2_fullfile = FASTInputFile(BD2_fullfile) - return self.load_BDBldFile2 - - def load_BDBldFile3(self): - BD3_fullfile = os.path.join(self.path, self.Fst['BDBldFile(3)'].strip('\'').strip('\"')) - self.BD3_fullfile = FASTInputFile(BD3_fullfile) - return self.load_BDBldFile3 - - def load_InflowWind(self): - IF_fullfile = os.path.join(self.path, self.Fst['InflowFile'].strip('\'').strip('\"')) - self.InflowWind = FASTInputFile(IF_fullfile) - return self.InflowWind - - def load_AeroDyn(self): - AF_fullfile = os.path.join(self.path, self.Fst['AeroFile'].strip('\'').strip('\"')) - self.AeroDyn = FASTInputFile(AF_fullfile) - return self.AeroDyn - - def load_ServoDyn(self): - SF_fullfile = os.path.join(self.path, self.Fst['ServoFile'].strip('\'').strip('\"')) - self.ServoDyn = FASTInputFile(SF_fullfile) - return self.ServoDyn - - def load_HydroDyn(self): - HF_fullfile = os.path.join(self.path, self.Fst['HydroFile'].strip('\'').strip('\"')) - self.HydroDyn = FASTInputFile(HF_fullfile) - return self.HydroDyn - - def load_SubDyn(self): - SUBF_fullfile = os.path.join(self.path, self.Fst['SubFile'].strip('\'').strip('\"')) - self.SubDyn = FASTInputFile(SUBF_fullfile) - return self.SubDyn - - def load_MoorDyn(self): - MF_fullfile = os.path.join(self.path, self.Fst['MooringFile'].strip('\'').strip('\"')) - self.MoorDyn = FASTInputFile(MF_fullfile) - return self.MoorDyn - - def load_IceDyn(self): - IceF_fullfile = os.path.join(self.path, self.Fst['IceFile'].strip('\'').strip('\"')) - self.IceDyn = FASTInputFile(IceF_fullfile) - return self.IceDyn - - def load_DISCON(self): # (TODO - Move this out of the ROSCO toolbox and into ofTools) - DISCON_fullfile = os.path.join(self.path, self.ServoDyn['DLL_InFile'].strip('\'').strip('\"')) - self.DISCON_in = read_DISCON(DISCON_fullfile) - return self.DISCON_in - -# --------------------------------------------------------------------------------} -# --- INPUT FILE -# --------------------------------------------------------------------------------{ -class FASTInputFile(File): - """ - Read/write an OpenFAST input file. The object behaves like a dictionary. - - Main methods - ------------ - - read, write, toDataFrame, keys - - Main keys - --------- - The keys correspond to the keys used in the file. For instance for a .fst file: 'DT','TMax' - - Examples - -------- - - filename = 'AeroDyn.dat' - f = FASTInputFile(filename) - f['TwrAero'] = True - f['AirDens'] = 1.225 - f.write('AeroDyn_Changed.dat') - - """ - - @staticmethod - def defaultExtensions(): - return ['.dat','.fst','.txt','.fstf'] - - @staticmethod - def formatName(): - return 'FAST input file' - - def __init__(self, filename=None, **kwargs): - super(FASTInputFile, self).__init__(filename=filename,**kwargs) - - def keys(self): - self.labels = [ d['label'] for d in self.data if not d['isComment'] ] - return self.labels - - def getID(self,label): - i=self.getIDSafe(label) - if i<0: - raise KeyError('Variable `'+ label+'` not found in FAST file:'+self.filename) - else: - return i - def getIDs(self,label): - I=[] - # brute force search - for i in range(len(self.data)): - d = self.data[i] - if d['label'].lower()==label.lower(): - I.append(i) - if len(I)<0: - raise KeyError('Variable `'+ label+'` not found in FAST file:'+self.filename) - else: - return I - - def getIDSafe(self,label): - # brute force search - for i in range(len(self.data)): - d = self.data[i] - if d['label'].lower()==label.lower(): - return i - return -1 - - # Making object an iterator - def __iter__(self): - self.iCurrent=-1 - self.iMax=len(self.data)-1 - return self - - def __next__(self): # Python 2: def next(self) - if self.iCurrent > self.iMax: - raise StopIteration - else: - self.iCurrent += 1 - return self.data[self.iCurrent] - - # Making it behave like a dictionary - def __setitem__(self,key,item): - I = self.getIDs(key) - for i in I: - self.data[i]['value'] = item - - def __getitem__(self,key): - i = self.getID(key) - return self.data[i]['value'] - - def __repr__(self): - s ='Fast input file: {}\n'.format(self.filename) - return s+'\n'.join(['{:15s}: {}'.format(d['label'],d['value']) for i,d in enumerate(self.data)]) - - def addKeyVal(self,key,val,descr=None): - d=getDict() - d['label']=key - d['value']=val - if descr is not None: - d['descr']=descr - self.data.append(d) - - def _read(self): - - # TODO members for BeamDyn with mutliple key point ####### TODO PropSetID is Duplicate SubDyn and used in HydroDyn - NUMTAB_FROM_VAL_DETECT = ['HtFract' , 'TwrElev' , 'BlFract' , 'Genspd_TLU' , 'BlSpn' , 'WndSpeed' , 'HvCoefID' , 'AxCoefID' , 'JointID' , 'Dpth' , 'FillNumM' , 'MGDpth' , 'SimplCd' , 'RNodes' , 'kp_xr' , 'mu1' , 'TwrHtFr' , 'TwrRe' , 'RJointID' , 'IJointID' , 'COSMID' , 'CMJointID' , 'WT_X'] - NUMTAB_FROM_VAL_DIM_VAR = ['NTwInpSt' , 'NumTwrNds' , 'NBlInpSt' , 'DLL_NumTrq' , 'NumBlNds' , 'NumCases' , 'NHvCoef' , 'NAxCoef' , 'NJoints' , 'NCoefDpth' , 'NFillGroups' , 'NMGDepths' , 1 , 'BldNodes' , 'kp_total' , 1 , 'NTwrHt' , 'NTwrRe' , 'NReact' , 'NInterf' , 'NCOSMs' , 'NCmass' , 'NumTurbines'] - NUMTAB_FROM_VAL_VARNAME = ['TowProp' , 'TowProp' , 'BldProp' , 'DLLProp' , 'BldAeroNodes' , 'Cases' , 'HvCoefs' , 'AxCoefs' , 'Joints' , 'DpthProp' , 'FillGroups' , 'MGProp' , 'SmplProp' , 'BldAeroNodes' , 'MemberGeom' , 'DampingCoeffs' , 'TowerProp' , 'TowerRe' , 'BaseReactJoints' , 'InterfaceJoints' , 'MemberCosineMatrix' , 'ConcentratedMasses','WindTurbines'] - NUMTAB_FROM_VAL_NHEADER = [2 , 2 , 2 , 2 , 2 , 2 , 2 , 2 , 2 , 2 , 2 , 2 , 2 , 1 , 2 , 2 , 1 , 1 , 2 , 2 , 2 , 2 ,2] - NUMTAB_FROM_VAL_TYPE = ['num' , 'num' , 'num' , 'num' , 'num' , 'num' , 'num' , 'num' , 'num' , 'num' , 'num' , 'num' , 'num' , 'mix' , 'num' , 'num' , 'num' , 'num' , 'mix' , 'num' , 'num' , 'num' ,'mix'] - NUMTAB_FROM_VAL_DETECT_L = [s.lower() for s in NUMTAB_FROM_VAL_DETECT] - - # NOTE: MJointID1, used by SubDyn and HydroDyn - NUMTAB_FROM_LAB_DETECT = ['NumAlf' , 'F_X' , 'MemberCd1' , 'MJointID1' , 'NOutLoc' , 'NOutCnt' , 'PropD' , 'YoungE' , 'YoungE' ] - NUMTAB_FROM_LAB_DIM_VAR = ['NumAlf' , 'NKInpSt' , 'NCoefMembers' , 'NMembers' , 'NMOutputs' , 'NMOutputs' , 'NPropSets' , 'NPropSets' , 'NXPropSets' ] - NUMTAB_FROM_LAB_VARNAME = ['AFCoeff' , 'TMDspProp' , 'MemberProp' , 'Members' , 'MemberOuts' , 'MemberOuts' , 'MemberSectionProp' , 'MemberSectionProp' , 'MemberSectionProp2' ] - NUMTAB_FROM_LAB_TYPE = ['num' , 'num' , 'num' , 'mix' , 'num' , 'num' , 'num' , 'num' , 'num' ] - NUMTAB_FROM_LAB_DETECT_L = [s.lower() for s in NUMTAB_FROM_LAB_DETECT] - - FILTAB_FROM_LAB_DETECT = ['FoilNm' ,'AFNames'] - FILTAB_FROM_LAB_DIM_VAR = ['NumFoil','NumAFfiles'] - FILTAB_FROM_LAB_VARNAME = ['FoilNm' ,'AFNames'] - FILTAB_FROM_LAB_DETECT_L = [s.lower() for s in FILTAB_FROM_LAB_DETECT] - - self.data = [] - self.module = None - #with open(self.filename, 'r', errors="surrogateescape") as f: - with open(self.filename, 'r', errors="surrogateescape") as f: - lines=f.read().splitlines() - # IF NEEDED> DO THE FOLLOWING FORMATTING: - #lines = [str(l).encode('utf-8').decode('ascii','ignore') for l in f.read().splitlines()] - - # Fast files start with ! or - - #if lines[0][0]!='!' and lines[0][0]!='-': - # raise Exception('Fast file do not start with ! or -, is it the right format?') - - # Special filetypes - if self.detectAndReadExtPtfmSE(lines): - return - if self.detectAndReadAirfoil(lines): - return - - # Parsing line by line, storing each line into a dictionary - i=0 - nComments = 0 - nWrongLabels = 0 - allowSpaceSeparatedList=False - while i0 \ - or line.upper().find('MESH-BASED OUTPUTS')>0 \ - or line.upper().find('OUTPUT CHANNELS' )>0: - # TODO, lazy implementation so far, MAKE SUB FUNCTION - parts = re.match(r'^\W*\w+', line) - if parts: - firstword = parts.group(0).strip() - else: - raise NotImplementedError - remainer = re.sub(r'^\W*\w+\W*', '', line) - # Parsing outlist, and then we continue at a new "i" (to read END etc.) - OutList,i = parseFASTOutList(lines,i+1) - d = getDict() - d['label'] = firstword - d['descr'] = remainer - d['tabType'] = TABTYPE_FIL # TODO - d['value'] = ['']+OutList - self.data.append(d) - if i>=len(lines): - break - - # --- Here we cheat and force an exit of the input file - # The reason for this is that some files have a lot of things after the END, which will result in the file being intepreted as a wrong format due to too many comments - if i+20: - print('>>>Bld Nodal outputs present') - else: - self.data.append(parseFASTInputLine('END of input file (the word "END" must appear in the first 3 columns of this last OutList line)',i+1)) - self.data.append(parseFASTInputLine('---------------------------------------------------------------------------------------',i+2)) - break - elif line.upper().find('SSOUTLIST' )>0: - # SUBDYN Outlist doesn not follow regular format - self.data.append(parseFASTInputLine(line,i)) - # OUTLIST Exception for BeamDyn - OutList,i = parseFASTOutList(lines,i+1) - # TODO - for o in OutList: - d = getDict() - d['isComment'] = True - d['value']=o - self.data.append(d) - # --- Here we cheat and force an exit of the input file - self.data.append(parseFASTInputLine('END of input file (the word "END" must appear in the first 3 columns of this last OutList line)',i+1)) - self.data.append(parseFASTInputLine('---------------------------------------------------------------------------------------',i+2)) - break - - elif line.upper().find('ADDITIONAL STIFFNESS')>0: - # TODO, lazy implementation so far, MAKE SUB FUNCTION - self.data.append(parseFASTInputLine(line,i)) - i +=1 - KDAdd = [] - for _ in range(19): - KDAdd.append(lines[i]) - i +=1 - d = getDict() - d['label'] = 'KDAdd' # TODO - d['tabType'] = TABTYPE_FIL # TODO - d['value'] = KDAdd - self.data.append(d) - if i>=len(lines): - break - elif line.upper().find('DISTRIBUTED PROPERTIES')>0: - self.data.append(parseFASTInputLine(line,i)); - i+=1; - self.readBeamDynProps(lines,i) - return - - # --- Parsing of standard lines: value(s) key comment - line = lines[i] - d = parseFASTInputLine(line,i,allowSpaceSeparatedList) - - # --- Handling of special files - if d['label'].lower()=='kp_total': - # BeamDyn has weird space speparated list around keypoint definition - allowSpaceSeparatedList=True - elif d['label'].lower()=='numcoords': - # TODO, lazy implementation so far, MAKE SUB FUNCTION - if isStr(d['value']): - if d['value'][0]=='@': - # it's a ref to the airfoil coord file - pass - else: - if not strIsInt(d['value']): - raise WrongFormatError('Wrong value of NumCoords') - if int(d['value'])<=0: - pass - else: - self.data.append(d); i+=1; - # 3 comment lines - self.data.append(parseFASTInputLine(lines[i],i)); i+=1; - self.data.append(parseFASTInputLine(lines[i],i)); i+=1; - self.data.append(parseFASTInputLine(lines[i],i)); i+=1; - splits=cleanAfterChar(cleanLine(lines[i]),'!').split() - # Airfoil ref point - try: - pos=[float(splits[0]), float(splits[1])] - except: - raise WrongFormatError('Wrong format while reading coordinates of airfoil reference') - i+=1 - d = getDict() - d['label'] = 'AirfoilRefPoint' - d['value'] = pos - self.data.append(d) - # 2 comment lines - self.data.append(parseFASTInputLine(lines[i],i)); i+=1; - self.data.append(parseFASTInputLine(lines[i],i)); i+=1; - # Table of coordinats itself - d = getDict() - d['label'] = 'AirfoilCoord' - d['tabDimVar'] = 'NumCoords' - d['tabType'] = TABTYPE_NUM_WITH_HEADERCOM - nTabLines = self[d['tabDimVar']]-1 # SOMEHOW ONE DATA POINT LESS - d['value'], d['tabColumnNames'],_ = parseFASTNumTable(self.filename,lines[i:i+nTabLines+1],nTabLines,i,1) - d['tabUnits'] = ['(-)','(-)'] - self.data.append(d) - break - - - - #print('label>',d['label'],'<',type(d['label'])); - #print('value>',d['value'],'<',type(d['value'])); - #print(isStr(d['value'])) - #if isStr(d['value']): - # print(d['value'].lower() in NUMTAB_FROM_VAL_DETECT_L) - - - # --- Handling of tables - if isStr(d['value']) and d['value'].lower() in NUMTAB_FROM_VAL_DETECT_L: - # Table with numerical values, - ii = NUMTAB_FROM_VAL_DETECT_L.index(d['value'].lower()) - tab_type = NUMTAB_FROM_VAL_TYPE[ii] - if tab_type=='num': - d['tabType'] = TABTYPE_NUM_WITH_HEADER - else: - d['tabType'] = TABTYPE_MIX_WITH_HEADER - d['label'] = NUMTAB_FROM_VAL_VARNAME[ii] - d['tabDimVar'] = NUMTAB_FROM_VAL_DIM_VAR[ii] - nHeaders = NUMTAB_FROM_VAL_NHEADER[ii] - nTabLines=0 - if isinstance(d['tabDimVar'],int): - nTabLines = d['tabDimVar'] - else: - nTabLines = self[d['tabDimVar']] - #print('Reading table {} Dimension {} (based on {})'.format(d['label'],nTabLines,d['tabDimVar'])); - d['value'], d['tabColumnNames'], d['tabUnits'] = parseFASTNumTable(self.filename,lines[i:i+nTabLines+nHeaders],nTabLines,i,nHeaders,tableType=tab_type) - i += nTabLines+nHeaders-1 - - # --- Temporary hack for e.g. SubDyn, that has duplicate table, impossible to detect in the current way... - # So we remove the element form the list one read - del NUMTAB_FROM_VAL_DETECT[ii] - del NUMTAB_FROM_VAL_DIM_VAR[ii] - del NUMTAB_FROM_VAL_VARNAME[ii] - del NUMTAB_FROM_VAL_NHEADER[ii] - del NUMTAB_FROM_VAL_TYPE [ii] - del NUMTAB_FROM_VAL_DETECT_L[ii] - - elif isStr(d['label']) and d['label'].lower() in NUMTAB_FROM_LAB_DETECT_L: - ii = NUMTAB_FROM_LAB_DETECT_L.index(d['label'].lower()) - tab_type = NUMTAB_FROM_LAB_TYPE[ii] - # Special case for airfoil data, the table follows NumAlf, so we add d first - if d['label'].lower()=='numalf': - d['tabType']=TABTYPE_NOT_A_TAB - self.data.append(d) - # Creating a new dictionary for the table - d = {'value':None, 'label':'NumAlf', 'isComment':False, 'descr':'', 'tabType':None} - i += 1 - d['label'] = NUMTAB_FROM_LAB_VARNAME[ii] - d['tabDimVar'] = NUMTAB_FROM_LAB_DIM_VAR[ii] - if d['label'].lower()=='afcoeff' : - d['tabType'] = TABTYPE_NUM_WITH_HEADERCOM - else: - if tab_type=='num': - d['tabType'] = TABTYPE_NUM_WITH_HEADER - else: - d['tabType'] = TABTYPE_MIX_WITH_HEADER - nTabLines = self[d['tabDimVar']] - #print('Reading table {} Dimension {} (based on {})'.format(d['label'],nTabLines,d['tabDimVar'])); - d['value'], d['tabColumnNames'], d['tabUnits'] = parseFASTNumTable(self.filename,lines[i:i+nTabLines+2],nTabLines,i,2,tableType=tab_type) - i += nTabLines+1 - - # --- Temporary hack for e.g. SubDyn, that has duplicate table, impossible to detect in the current way... - # So we remove the element form the list one read - del NUMTAB_FROM_LAB_DETECT[ii] - del NUMTAB_FROM_LAB_DIM_VAR[ii] - del NUMTAB_FROM_LAB_VARNAME[ii] - del NUMTAB_FROM_LAB_TYPE [ii] - del NUMTAB_FROM_LAB_DETECT_L[ii] - - elif isStr(d['label']) and d['label'].lower() in FILTAB_FROM_LAB_DETECT_L: - ii = FILTAB_FROM_LAB_DETECT_L.index(d['label'].lower()) - d['label'] = FILTAB_FROM_LAB_VARNAME[ii] - d['tabDimVar'] = FILTAB_FROM_LAB_DIM_VAR[ii] - d['tabType'] = TABTYPE_FIL - nTabLines = self[d['tabDimVar']] - #print('Reading table {} Dimension {} (based on {})'.format(d['label'],nTabLines,d['tabDimVar'])); - d['value'] = parseFASTFilTable(lines[i:i+nTabLines],nTabLines,i) - i += nTabLines-1 - - - - self.data.append(d) - i += 1 - # --- Safety checks - if d['isComment']: - #print(line) - nComments +=1 - else: - if hasSpecialChars(d['label']): - nWrongLabels +=1 - #print('label>',d['label'],'<',type(d['label']),line); - if i>3: # first few lines may be comments, we allow it - #print('Line',i,'Label:',d['label']) - raise WrongFormatError('Special Character found in Label: `{}`'.format(d['label'])) - if len(d['label'])==0: - nWrongLabels +=1 - if nComments>len(lines)*0.35: - #print('Comment fail',nComments,len(lines),self.filename) - raise WrongFormatError('Most lines were read as comments, probably not a FAST Input File') - if nWrongLabels>len(lines)*0.10: - #print('Label fail',nWrongLabels,len(lines),self.filename) - raise WrongFormatError('Too many lines with wrong labels, probably not a FAST Input File') - - # --- PostReading checks - labels = self.keys() - duplicates = set([x for x in labels if labels.count(x) > 1]) - if len(duplicates)>0: - print('[WARN] Duplicate labels found in file: '+self.filename) - print(' Duplicates: '+', '.join(duplicates)) - print(' It\'s strongly recommended to make them unique! ') -# except WrongFormatError as e: -# raise WrongFormatError('Fast File {}: '.format(self.filename)+'\n'+e.args[0]) -# except Exception as e: -# raise e -# # print(e) -# raise Exception('Fast File {}: '.format(self.filename)+'\n'+e.args[0]) - - - def toString(self): - s='' - # Special file formats, TODO subclass - if self.module=='ExtPtfm': - s+='!Comment\n' - s+='!Comment Flex 5 Format\n' - s+='!Dimension: {}\n'.format(self['nDOF']) - s+='!Time increment in simulation: {}\n'.format(self['dt']) - s+='!Total simulation time in file: {}\n'.format(self['T']) - - s+='\n!Mass Matrix\n' - s+='!Dimension: {}\n'.format(self['nDOF']) - s+='\n'.join(''.join('{:16.8e}'.format(x) for x in y) for y in self['MassMatrix']) - - s+='\n\n!Stiffness Matrix\n' - s+='!Dimension: {}\n'.format(self['nDOF']) - s+='\n'.join(''.join('{:16.8e}'.format(x) for x in y) for y in self['StiffnessMatrix']) - - s+='\n\n!Damping Matrix\n' - s+='!Dimension: {}\n'.format(self['nDOF']) - s+='\n'.join(''.join('{:16.8e}'.format(x) for x in y) for y in self['DampingMatrix']) - - s+='\n\n!Loading and Wave Elevation\n' - s+='!Dimension: 1 time column - {} force columns\n'.format(self['nDOF']) - s+='\n'.join(''.join('{:16.8e}'.format(x) for x in y) for y in self['Loading']) - return s - - def toStringVLD(val,lab,descr): - val='{}'.format(val) - lab='{}'.format(lab) - if len(val)<13: - val='{:13s}'.format(val) - if len(lab)<13: - lab='{:13s}'.format(lab) - return val+' '+lab+' - '+descr.strip().strip('-').strip()+'\n' - - for i in range(len(self.data)): - d=self.data[i] - if d['isComment']: - s+='{}'.format(d['value']) - elif d['tabType']==TABTYPE_NOT_A_TAB: - if isinstance(d['value'], list): - sList=', '.join([str(x) for x in d['value']]) - s+='{} {} {}'.format(sList,d['label'],d['descr']) - else: - s+=toStringVLD(d['value'],d['label'],d['descr']).strip() - elif d['tabType']==TABTYPE_NUM_WITH_HEADER: - s+='{}'.format(' '.join(['{:15s}'.format(s) for s in d['tabColumnNames']])) - #s+=d['descr'] # Not ready for that - if d['tabUnits'] is not None: - s+='\n' - s+='{}'.format(' '.join(['{:15s}'.format(s) for s in d['tabUnits']])) - if np.size(d['value'],0) > 0 : - s+='\n' - s+='\n'.join('\t'.join( ('{:15.0f}'.format(x) if int(x)==x else '{:15.8e}'.format(x) ) for x in y) for y in d['value']) - elif d['tabType']==TABTYPE_MIX_WITH_HEADER: - s+='{}'.format(' '.join(['{:15s}'.format(s) for s in d['tabColumnNames']])) - if d['tabUnits'] is not None: - s+='\n' - s+='{}'.format(' '.join(['{:15s}'.format(s) for s in d['tabUnits']])) - if np.size(d['value'],0) > 0 : - s+='\n' - s+='\n'.join('\t'.join('{}'.format(x) for x in y) for y in d['value']) - elif d['tabType']==TABTYPE_NUM_WITH_HEADERCOM: - s+='! {}\n'.format(' '.join(['{:15s}'.format(s) for s in d['tabColumnNames']])) - s+='! {}\n'.format(' '.join(['{:15s}'.format(s) for s in d['tabUnits']])) - s+='\n'.join('\t'.join('{:15.8e}'.format(x) for x in y) for y in d['value']) - elif d['tabType']==TABTYPE_FIL: - #f.write('{} {} {}\n'.format(d['value'][0],d['tabDetect'],d['descr'])) - s+='{} {} {}\n'.format(d['value'][0],d['label'],d['descr']) # TODO? - s+='\n'.join(fil for fil in d['value'][1:]) - else: - raise Exception('Unknown table type for variable {}',d) - if i0: - # Hack for blade files, we add the modes - x=Val[:,0] - Modes=np.zeros((x.shape[0],3)) - Modes[:,0] = x**2 * self['BldFl1Sh(2)'] \ - + x**3 * self['BldFl1Sh(3)'] \ - + x**4 * self['BldFl1Sh(4)'] \ - + x**5 * self['BldFl1Sh(5)'] \ - + x**6 * self['BldFl1Sh(6)'] - Modes[:,1] = x**2 * self['BldFl2Sh(2)'] \ - + x**3 * self['BldFl2Sh(3)'] \ - + x**4 * self['BldFl2Sh(4)'] \ - + x**5 * self['BldFl2Sh(5)'] \ - + x**6 * self['BldFl2Sh(6)'] - Modes[:,2] = x**2 * self['BldEdgSh(2)'] \ - + x**3 * self['BldEdgSh(3)'] \ - + x**4 * self['BldEdgSh(4)'] \ - + x**5 * self['BldEdgSh(5)'] \ - + x**6 * self['BldEdgSh(6)'] - Val = np.hstack((Val,Modes)) - Cols = Cols + ['ShapeFlap1_[-]','ShapeFlap2_[-]','ShapeEdge1_[-]'] - - elif self.getIDSafe('TwFAM1Sh(2)')>0: - # Hack for tower files, we add the modes - x=Val[:,0] - Modes=np.zeros((x.shape[0],4)) - Modes[:,0] = x**2 * self['TwFAM1Sh(2)'] \ - + x**3 * self['TwFAM1Sh(3)'] \ - + x**4 * self['TwFAM1Sh(4)'] \ - + x**5 * self['TwFAM1Sh(5)'] \ - + x**6 * self['TwFAM1Sh(6)'] - Modes[:,1] = x**2 * self['TwFAM2Sh(2)'] \ - + x**3 * self['TwFAM2Sh(3)'] \ - + x**4 * self['TwFAM2Sh(4)'] \ - + x**5 * self['TwFAM2Sh(5)'] \ - + x**6 * self['TwFAM2Sh(6)'] - Modes[:,2] = x**2 * self['TwSSM1Sh(2)'] \ - + x**3 * self['TwSSM1Sh(3)'] \ - + x**4 * self['TwSSM1Sh(4)'] \ - + x**5 * self['TwSSM1Sh(5)'] \ - + x**6 * self['TwSSM1Sh(6)'] - Modes[:,3] = x**2 * self['TwSSM2Sh(2)'] \ - + x**3 * self['TwSSM2Sh(3)'] \ - + x**4 * self['TwSSM2Sh(4)'] \ - + x**5 * self['TwSSM2Sh(5)'] \ - + x**6 * self['TwSSM2Sh(6)'] - Val = np.hstack((Val,Modes)) - Cols = Cols + ['ShapeForeAft1_[-]','ShapeForeAft2_[-]','ShapeSideSide1_[-]','ShapeSideSide2_[-]'] - - name=d['label'] - dfs[name]=pd.DataFrame(data=Val,columns=Cols) - elif d['tabType'] in [TABTYPE_NUM_BEAMDYN]: - data = d['value'] - Cols =['Span'] - Cols+=['K{}{}'.format(i+1,j+1) for i in range(6) for j in range(6)] - Cols+=['M{}{}'.format(i+1,j+1) for i in range(6) for j in range(6)] - # Putting the main terms first - IAll = range(1+36+36) - IMain= [0] + [i*6+i+1 for i in range(6)] + [i*6+i+37 for i in range(6)] - IOrg = IMain + [i for i in range(1+36+36) if i not in IMain] - Cols = [Cols[i] for i in IOrg] - data = data[:,IOrg] - name=d['label'] - dfs[name]=pd.DataFrame(data=data,columns=Cols) - if len(dfs)==1: - dfs=dfs[list(dfs.keys())[0]] - return dfs - -# --------------------------------------------------------------------------------} -# --- SubReaders /detectors -# --------------------------------------------------------------------------------{ - def detectAndReadExtPtfmSE(self,lines): - def readmat(n,m,lines,iStart): - M=np.zeros((n,m)) - for j in np.arange(n): - i=iStart+j - M[j,:]=np.array(lines[i].split()).astype(float) - return M - if len(lines)<10: - return False - if not (lines[0][0]=='!' and lines[1][0]=='!'): - return False - if lines[1].lower().find('flex')<0: - return - if lines[2].lower().find('!dimension')<0: - return - # --- At this stage we assume it's in the proper format - self.module='ExtPtfm' - nDOFCommon = -1 - i=2; - try: - while i0: - if l[0]=='!': - if l.find('!dimension')==0: - self.addKeyVal('nDOF',int(l.split(':')[1])) - nDOFCommon=self['nDOF'] - elif l.find('!time increment')==0: - self.addKeyVal('dt',np.float_(l.split(':')[1])) - elif l.find('!total simulation time')==0: - self.addKeyVal('T',np.float_(l.split(':')[1])) - else: - raise BrokenFormatError('Unexcepted content found on line {}'.format(i)) - i+=1 - except BrokenFormatError as e: - raise e - except: - raise - - - return True - - - - def detectAndReadAirfoil(self,lines): - if len(lines)<14: - return False - # Reading number of tables - L3 = lines[2].strip().split() - if len(L3)<=0: - return False - if not strIsInt(L3[0]): - return False - nTables=int(L3[0]) - # Reading table ID - L4 = lines[3].strip().split() - if len(L4)<=nTables: - return False - TableID=L4[:nTables] - if nTables==1: - TableID=[''] - # Keywords for file format - KW1=lines[12].strip().split() - KW2=lines[13].strip().split() - if len(KW1)>nTables and len(KW2)>nTables: - if KW1[nTables].lower()=='angle' and KW2[nTables].lower()=='minimum': - d = getDict(); d['isComment'] = True; d['value'] = lines[0]; self.data.append(d); - d = getDict(); d['isComment'] = True; d['value'] = lines[1]; self.data.append(d); - for i in range(2,14): - splits = lines[i].split() - #print(splits) - d = getDict() - d['label'] = ' '.join(splits[1:]) # TODO - d['descr'] = ' '.join(splits[1:]) # TODO - d['value'] = float(splits[0]) - self.data.append(d) - #pass - #for i in range(2,14): - nTabLines=0 - while 14+nTabLines0 : - nTabLines +=1 - #data = np.array([lines[i].strip().split() for i in range(14,len(lines)) if len(lines[i])>0]).astype(np.float_) - #data = np.array([lines[i].strip().split() for i in takewhile(lambda x: len(lines[i].strip())>0, range(14,len(lines)-1))]).astype(np.float_) - data = np.array([lines[i].strip().split() for i in range(14,nTabLines+14)]).astype(np.float_) - #print(data) - d = getDict() - d['label'] = 'Polar' - d['tabDimVar'] = nTabLines - d['tabType'] = TABTYPE_NUM_NO_HEADER - d['value'] = data - if np.size(data,1)==1+nTables*3: - d['tabColumnNames'] = ['Alpha']+[n+l for l in TableID for n in ['Cl','Cd','Cm']] - d['tabUnits'] = ['(deg)']+['(-)' , '(-)' , '(-)']*nTables - elif np.size(data,1)==1+nTables*2: - d['tabColumnNames'] = ['Alpha']+[n+l for l in TableID for n in ['Cl','Cd']] - d['tabUnits'] = ['(deg)']+['(-)' , '(-)']*nTables - else: - d['tabColumnNames'] = ['col{}'.format(j) for j in range(np.size(data,1))] - self.data.append(d) - return True - - def readBeamDynProps(self,lines,iStart): - nStations=self['station_total'] - M=np.zeros((nStations,1+36+36)) - i=iStart; - try: - for j in range(nStations): - M[j,0]=float(lines[i]); i+=1; - LL = lines[i:i+6] - M[j,1:37]=np.array((' '.join(lines[i:i+6])).split()).astype(np.float_) - i+=7 - M[j,37:]=np.array((' '.join(lines[i:i+6])).split()).astype(np.float_) - i+=7 - except: - raise WrongFormatError('An error occured while reading section {}/{}'.format(j+1,nStations)) - d = getDict() - d['label'] = 'BeamProperties' - d['descr'] = '' - d['tabType'] = TABTYPE_NUM_BEAMDYN - d['value'] = M - self.data.append(d) - - -# --------------------------------------------------------------------------------} -# --- Helper functions -# --------------------------------------------------------------------------------{ -def isStr(s): - # Python 2 and 3 compatible - # Two options below - # NOTE: all this avoided since we import str from builtins - # --- Version 2 - # isString = False; - # if(isinstance(s, str)): - # isString = True; - # try: - # if(isinstance(s, basestring)): # todo unicode as well - # isString = True; - # except NameError: - # pass; - # return isString - # --- Version 1 - # try: - # basestring # python 2 - # return isinstance(s, basestring) or isinstance(s,unicode) - # except NameError: - # basestring=str #python 3 - # return isinstance(s, str) - return isinstance(s, str) - -def strIsFloat(s): - #return s.replace('.',',1').isdigit() - try: - float(s) - return True - except: - return False - -def strIsBool(s): - return (s.lower() == 'true') or (s.lower() == 'false') - -def strIsInt(s): - s = str(s) - if s[0] in ('-', '+'): - return s[1:].isdigit() - return s.isdigit() - -def hasSpecialChars(s): - # fast allows for parenthesis - # For now we allow for - but that's because of BeamDyn geometry members - return not re.match("^[\"\'a-zA-Z0-9_()-]*$", s) - -def cleanLine(l): - # makes a string single space separated - l = l.replace('\t',' ') - l = ' '.join(l.split()) - l = l.strip() - return l - -def cleanAfterChar(l,c): - # remove whats after a character - n = l.find(c); - if n>0: - return l[:n] - else: - return l - -def getDict(): - return {'value':None, 'label':'', 'isComment':False, 'descr':'', 'tabType':TABTYPE_NOT_A_TAB} - - -def parseFASTInputLine(line_raw,i,allowSpaceSeparatedList=False): - d = getDict() - #print(line_raw) - try: - # preliminary cleaning (Note: loss of formatting) - line = cleanLine(line_raw) - # Comment - if any(line.startswith(c) for c in ['#','!','--','==']) or len(line)==0: - d['isComment']=True - d['value']=line_raw - return d - - # Detecting lists - List=[]; - iComma=line.find(',') - if iComma>0 and iComma<30: - fakeline=line.replace(' ',',') - fakeline=re.sub(',+',',',fakeline) - csplits=fakeline.split(',') - # Splitting based on comma and looping while it's numbers of booleans - ii=0 - s=csplits[ii] - #print(csplits) - while strIsFloat(s) or strIsBool(s) and ii=len(csplits): - raise WrongFormatError('Wrong number of list values') - s = csplits[ii] - #print('[INFO] Line {}: Found list: '.format(i),List) - # Defining value and remaining splits - if len(List)>=2: - d['value']=List - line_remaining=line - # eating line, removing each values - for iii in range(ii): - sValue=csplits[iii] - ipos=line_remaining.find(sValue) - line_remaining = line_remaining[ipos+len(sValue):] - splits=line_remaining.split() - iNext=0 - else: - # It's not a list, we just use space as separators - splits=line.split(' ') - s=splits[0] - - if strIsInt(s): - d['value']=int(s) - if allowSpaceSeparatedList and len(splits)>1: - if strIsInt(splits[1]): - d['value']=splits[0]+ ' '+splits[1] - elif strIsFloat(s): - d['value']=float(s) - elif strIsBool(s): - d['value']=bool(s) - else: - d['value']=s - iNext=1 - #import pdb ; pdb.set_trace(); - - # Extracting label (TODO, for now only second split) - bOK=False - while (not bOK) and iNext comment assumed'.format(i+1)) - d['isComment']=True - d['value']=line_raw - iNext = len(splits)+1 - - # Recombining description - if len(splits)>=iNext+1: - d['descr']=' '.join(splits[iNext:]) - except WrongFormatError as e: - raise WrongFormatError('Line {}: '.format(i+1)+e.args[0]) - except Exception as e: - raise Exception('Line {}: '.format(i+1)+e.args[0]) - - return d - -def parseFASTOutList(lines,iStart): - OutList=[] - i = iStart - MAX=200 - while iMAX : - raise Exception('More that 200 lines found in outlist') - if i>=len(lines): - print('[WARN] End of file reached while reading Outlist') - #i=min(i+1,len(lines)) - return OutList,iStart+len(OutList) - - -def extractWithinParenthesis(s): - mo = re.search(r'\((.*)\)', s) - if mo: - return mo.group(1) - return '' - -def extractWithinBrackets(s): - mo = re.search(r'\((.*)\)', s) - if mo: - return mo.group(1) - return '' - -def detectUnits(s,nRef): - nPOpen=s.count('(') - nPClos=s.count(')') - nBOpen=s.count('[') - nBClos=s.count(']') - - sep='!#@#!' - if (nPOpen == nPClos) and (nPOpen>=nRef): - #that's pretty good - Units=s.replace('(','').replace(')',sep).split(sep)[:-1] - elif (nBOpen == nBClos) and (nBOpen>=nRef): - Units=s.replace('[','').replace(']',sep).split(sep)[:-1] - else: - Units=s.split() - return Units - - -def parseFASTNumTable(filename,lines,n,iStart,nHeaders=2,tableType='num'): - Tab = None - ColNames = None - Units = None - - if len(lines)!=n+nHeaders: - raise BrokenFormatError('Not enough lines in table: {} lines instead of {}\nFile:{}'.format(len(lines)-nHeaders,n,filename)) - - if nHeaders<1: - raise NotImplementedError('Reading FAST tables with no headers not implemented yet') - - try: - if nHeaders>=1: - # Extract column names - i = 0 - sTmp = cleanLine(lines[i]) - sTmp = cleanAfterChar(sTmp,'[') - if sTmp.startswith('!'): - sTmp=sTmp[1:].strip() - ColNames=sTmp.split() - if nHeaders>=2: - # Extract units - i = 1 - sTmp = cleanLine(lines[i]) - if sTmp.startswith('!'): - sTmp=sTmp[1:].strip() - - Units = detectUnits(sTmp,len(ColNames)) - Units = ['({})'.format(u.strip()) for u in Units] - # Forcing user to match number of units and column names - if len(ColNames) != len(Units): - print(ColNames) - print(Units) - raise Exception('Number of column names different from number of units in table') - - nCols=len(ColNames) - - if tableType=='num': - Tab = np.zeros((n, nCols)) - for i in range(nHeaders,n+nHeaders): - l = lines[i].lower() - v = l.split() - if len(v) > nCols: - print('[WARN] {}: Line {}: number of data different from number of column names'.format(filename, iStart+i+1)) - if len(v) < nCols: - raise Exception('Number of data is lower than number of column names') - # Accounting for TRUE FALSE and converting to float - v = [s.replace('true','1').replace('false','0').replace('noprint','0').replace('print','1') for s in v] - v = [float(s) for s in v[0:nCols]] - if len(v) < nCols: - raise Exception('Number of data is lower than number of column names') - Tab[i-nHeaders,:] = v - elif tableType=='mix': - # a mix table contains a mixed of strings and floats - # For now, we are being a bit more relaxed about the number of columns - Tab = np.zeros((n, nCols)).astype(object) - for i in range(nHeaders,n+nHeaders): - l = lines[i] - v = l.split() - if len(v) != nCols: - print('[WARN] {}: Line {}: Number of data is different than number of column names'.format(filename,iStart+1+i)) - v=v[0:min(len(v),nCols)] - Tab[i-nHeaders,0:len(v)] = v - else: - raise Exception('Unknown table type') - - except Exception as e: - raise BrokenFormatError('Line {}: {}'.format(iStart+i+1,e.args[0])) - return Tab, ColNames, Units - - -def parseFASTFilTable(lines,n,iStart): - Tab = [] - try: - i=0 - if len(lines)!=n: - raise WrongFormatError('Not enough lines in table: {} lines instead of {}'.format(len(lines),n)) - for i in range(n): - l = lines[i].split() - #print(l[0].strip()) - Tab.append(l[0].strip()) - - except Exception as e: - raise Exception('Line {}: '.format(iStart+i+1)+e.args[0]) - return Tab - - -if __name__ == "__main__": - B=FASTInFile('BeamDyn_Blade.dat') - - - diff --git a/Test_Cases/BAR_10/BAR_10_DISCON.IN b/Test_Cases/BAR_10/BAR_10_DISCON.IN index 9e99f029..89658226 100644 --- a/Test_Cases/BAR_10/BAR_10_DISCON.IN +++ b/Test_Cases/BAR_10/BAR_10_DISCON.IN @@ -145,11 +145,11 @@ 0.00000000 0.00000000 0.00000000 ! PF_Offsets - Constant blade pitch offsets for blades 1-3 [rad] !------- Active Wake Control ----------------------------------------------------- -1 ! AWC_NumModes - number of forcing modes -1 ! AWC_n - azimuthal mode number(s) (i.e., the number and direction of the lobes of the wake structure) -0.0500 ! AWC_freq - frequency(s) of forcing mode(s) [Hz] -1.0000 ! AWC_amp - pitch amplitude(s) of forcing mode(s) (note that AWC_amp specifies the amplitude of each individual mode so that the total amplitude of pitching will be the sum of AWC_amp) [deg] -0.0000 ! AWC_clockangle - clocking angle(s) of forcing mode(s) [deg] +1 ! AWC_NumModes - Number of forcing modes +1 ! AWC_n - Azimuthal mode number(s) (i.e., the number and direction of the lobes of the wake structure) +0.0500 ! AWC_freq - Frequency(s) of forcing mode(s) [Hz] +1.0000 ! AWC_amp - Pitch amplitude(s) of forcing mode(s) (note that AWC_amp specifies the amplitude of each individual mode so that the total amplitude of pitching will be the sum of AWC_amp) [deg] +0.0000 ! AWC_clockangle - Clocking angle(s) of forcing mode(s) [deg] !------- External Controller Interface ----------------------------------------------------- "unused" ! DLL_FileName - Name/location of the dynamic library in the Bladed-DLL format diff --git a/Test_Cases/IEA-15-240-RWT-UMaineSemi/DISCON-UMaineSemi.IN b/Test_Cases/IEA-15-240-RWT-UMaineSemi/DISCON-UMaineSemi.IN index 65888ca1..d4343d70 100644 --- a/Test_Cases/IEA-15-240-RWT-UMaineSemi/DISCON-UMaineSemi.IN +++ b/Test_Cases/IEA-15-240-RWT-UMaineSemi/DISCON-UMaineSemi.IN @@ -145,11 +145,11 @@ 0.00000000 0.00000000 0.00000000 ! PF_Offsets - Constant blade pitch offsets for blades 1-3 [rad] !------- Active Wake Control ----------------------------------------------------- -1 ! AWC_NumModes - number of forcing modes -1 ! AWC_n - azimuthal mode number(s) (i.e., the number and direction of the lobes of the wake structure) -0.0500 ! AWC_freq - frequency(s) of forcing mode(s) [Hz] -1.0000 ! AWC_amp - pitch amplitude(s) of forcing mode(s) (note that AWC_amp specifies the amplitude of each individual mode so that the total amplitude of pitching will be the sum of AWC_amp) [deg] -0.0000 ! AWC_clockangle - clocking angle(s) of forcing mode(s) [deg] +1 ! AWC_NumModes - Number of forcing modes +1 ! AWC_n - Azimuthal mode number(s) (i.e., the number and direction of the lobes of the wake structure) +0.0500 ! AWC_freq - Frequency(s) of forcing mode(s) [Hz] +1.0000 ! AWC_amp - Pitch amplitude(s) of forcing mode(s) (note that AWC_amp specifies the amplitude of each individual mode so that the total amplitude of pitching will be the sum of AWC_amp) [deg] +0.0000 ! AWC_clockangle - Clocking angle(s) of forcing mode(s) [deg] !------- External Controller Interface ----------------------------------------------------- "unused" ! DLL_FileName - Name/location of the dynamic library in the Bladed-DLL format diff --git a/Test_Cases/NREL-5MW/DISCON.IN b/Test_Cases/NREL-5MW/DISCON.IN index 6fca7eb9..eee6ae75 100644 --- a/Test_Cases/NREL-5MW/DISCON.IN +++ b/Test_Cases/NREL-5MW/DISCON.IN @@ -145,11 +145,11 @@ 0.00000000 0.00000000 0.00000000 ! PF_Offsets - Constant blade pitch offsets for blades 1-3 [rad] !------- Active Wake Control ----------------------------------------------------- -1 ! AWC_NumModes - number of forcing modes -1 ! AWC_n - azimuthal mode number(s) (i.e., the number and direction of the lobes of the wake structure) -0.0500 ! AWC_freq - frequency(s) of forcing mode(s) [Hz] -1.0000 ! AWC_amp - pitch amplitude(s) of forcing mode(s) (note that AWC_amp specifies the amplitude of each individual mode so that the total amplitude of pitching will be the sum of AWC_amp) [deg] -0.0000 ! AWC_clockangle - clocking angle(s) of forcing mode(s) [deg] +1 ! AWC_NumModes - Number of forcing modes +1 ! AWC_n - Azimuthal mode number(s) (i.e., the number and direction of the lobes of the wake structure) +0.0500 ! AWC_freq - Frequency(s) of forcing mode(s) [Hz] +1.0000 ! AWC_amp - Pitch amplitude(s) of forcing mode(s) (note that AWC_amp specifies the amplitude of each individual mode so that the total amplitude of pitching will be the sum of AWC_amp) [deg] +0.0000 ! AWC_clockangle - Clocking angle(s) of forcing mode(s) [deg] !------- External Controller Interface ----------------------------------------------------- "unused" ! DLL_FileName - Name/location of the dynamic library in the Bladed-DLL format diff --git a/Test_Cases/NREL_2p8_127/NREL-2p8-127_DISCON.IN b/Test_Cases/NREL_2p8_127/NREL-2p8-127_DISCON.IN index c37c2670..c068b55b 100644 --- a/Test_Cases/NREL_2p8_127/NREL-2p8-127_DISCON.IN +++ b/Test_Cases/NREL_2p8_127/NREL-2p8-127_DISCON.IN @@ -145,11 +145,11 @@ 0.00000000 0.00000000 0.00000000 ! PF_Offsets - Constant blade pitch offsets for blades 1-3 [rad] !------- Active Wake Control ----------------------------------------------------- -1 ! AWC_NumModes - number of forcing modes -1 ! AWC_n - azimuthal mode number(s) (i.e., the number and direction of the lobes of the wake structure) -0.0500 ! AWC_freq - frequency(s) of forcing mode(s) [Hz] -1.0000 ! AWC_amp - pitch amplitude(s) of forcing mode(s) (note that AWC_amp specifies the amplitude of each individual mode so that the total amplitude of pitching will be the sum of AWC_amp) [deg] -0.0000 ! AWC_clockangle - clocking angle(s) of forcing mode(s) [deg] +1 ! AWC_NumModes - Number of forcing modes +1 ! AWC_n - Azimuthal mode number(s) (i.e., the number and direction of the lobes of the wake structure) +0.0500 ! AWC_freq - Frequency(s) of forcing mode(s) [Hz] +1.0000 ! AWC_amp - Pitch amplitude(s) of forcing mode(s) (note that AWC_amp specifies the amplitude of each individual mode so that the total amplitude of pitching will be the sum of AWC_amp) [deg] +0.0000 ! AWC_clockangle - Clocking angle(s) of forcing mode(s) [deg] !------- External Controller Interface ----------------------------------------------------- "unused" ! DLL_FileName - Name/location of the dynamic library in the Bladed-DLL format From 4194da43fd7b14586fdf8564949ed1fdce064eae Mon Sep 17 00:00:00 2001 From: dzalkind Date: Tue, 7 Mar 2023 17:18:18 -0700 Subject: [PATCH 068/224] Force AWC_n into int --- ROSCO_toolbox/utilities.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ROSCO_toolbox/utilities.py b/ROSCO_toolbox/utilities.py index 5cc936b8..66edc279 100644 --- a/ROSCO_toolbox/utilities.py +++ b/ROSCO_toolbox/utilities.py @@ -237,7 +237,7 @@ def write_DISCON(turbine, controller, param_file='DISCON.IN', txt_filename='Cp_C file.write('\n') file.write('!------- Active Wake Control -----------------------------------------------------\n') file.write('{0:<12d} ! AWC_NumModes - Number of forcing modes\n'.format(int(rosco_vt['AWC_NumModes']))) - file.write('{} ! AWC_n - Azimuthal mode number(s) (i.e., the number and direction of the lobes of the wake structure)\n'.format(write_array(rosco_vt['AWC_n'],'<4d'))) + file.write('{} ! AWC_n - Azimuthal mode number(s) (i.e., the number and direction of the lobes of the wake structure)\n'.format(write_array(int(rosco_vt['AWC_n']),'<4d'))) file.write('{} ! AWC_freq - Frequency(s) of forcing mode(s) [Hz]\n'.format(write_array(rosco_vt['AWC_freq'],'<6.4f'))) file.write('{} ! AWC_amp - Pitch amplitude(s) of forcing mode(s) (note that AWC_amp specifies the amplitude of each individual mode so that the total amplitude of pitching will be the sum of AWC_amp) [deg]\n'.format(write_array(rosco_vt['AWC_amp'],'<6.4f'))) file.write('{} ! AWC_clockangle - Clocking angle(s) of forcing mode(s) [deg]\n'.format(write_array(rosco_vt['AWC_clockangle'],'<6.4f'))) From c1e4be785aa2b59a7fea921101f45fff828977fe Mon Sep 17 00:00:00 2001 From: dzalkind Date: Tue, 7 Mar 2023 17:31:45 -0700 Subject: [PATCH 069/224] Force AWC_n into int better --- ROSCO_toolbox/utilities.py | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/ROSCO_toolbox/utilities.py b/ROSCO_toolbox/utilities.py index 66edc279..532eea3f 100644 --- a/ROSCO_toolbox/utilities.py +++ b/ROSCO_toolbox/utilities.py @@ -79,6 +79,7 @@ def write_DISCON(turbine, controller, param_file='DISCON.IN', txt_filename='Cp_C rosco_vt['CC_GroupIndex'] = [rosco_vt['CC_GroupIndex']] # make an array if not hasattr(rosco_vt['StC_GroupIndex'],'__len__'): rosco_vt['StC_GroupIndex'] = [rosco_vt['StC_GroupIndex']] + rosco_vt['AWC_n'] = [int(awcn) for awcn in rosco_vt['AWC_n']] print('Writing new controller parameter file parameter file: %s.' % param_file) # Should be obvious what's going on here... @@ -237,7 +238,7 @@ def write_DISCON(turbine, controller, param_file='DISCON.IN', txt_filename='Cp_C file.write('\n') file.write('!------- Active Wake Control -----------------------------------------------------\n') file.write('{0:<12d} ! AWC_NumModes - Number of forcing modes\n'.format(int(rosco_vt['AWC_NumModes']))) - file.write('{} ! AWC_n - Azimuthal mode number(s) (i.e., the number and direction of the lobes of the wake structure)\n'.format(write_array(int(rosco_vt['AWC_n']),'<4d'))) + file.write('{} ! AWC_n - Azimuthal mode number(s) (i.e., the number and direction of the lobes of the wake structure)\n'.format(write_array(rosco_vt['AWC_n'],'<4d'))) file.write('{} ! AWC_freq - Frequency(s) of forcing mode(s) [Hz]\n'.format(write_array(rosco_vt['AWC_freq'],'<6.4f'))) file.write('{} ! AWC_amp - Pitch amplitude(s) of forcing mode(s) (note that AWC_amp specifies the amplitude of each individual mode so that the total amplitude of pitching will be the sum of AWC_amp) [deg]\n'.format(write_array(rosco_vt['AWC_amp'],'<6.4f'))) file.write('{} ! AWC_clockangle - Clocking angle(s) of forcing mode(s) [deg]\n'.format(write_array(rosco_vt['AWC_clockangle'],'<6.4f'))) From 5e75601ca5a3b95b43ac472c92f0858b426f2863 Mon Sep 17 00:00:00 2001 From: dzalkind Date: Tue, 7 Mar 2023 17:35:00 -0700 Subject: [PATCH 070/224] Make AWC_n a list, too --- ROSCO_toolbox/utilities.py | 2 ++ 1 file changed, 2 insertions(+) diff --git a/ROSCO_toolbox/utilities.py b/ROSCO_toolbox/utilities.py index 532eea3f..694028a2 100644 --- a/ROSCO_toolbox/utilities.py +++ b/ROSCO_toolbox/utilities.py @@ -79,6 +79,8 @@ def write_DISCON(turbine, controller, param_file='DISCON.IN', txt_filename='Cp_C rosco_vt['CC_GroupIndex'] = [rosco_vt['CC_GroupIndex']] # make an array if not hasattr(rosco_vt['StC_GroupIndex'],'__len__'): rosco_vt['StC_GroupIndex'] = [rosco_vt['StC_GroupIndex']] + if not hasattr(rosco_vt['AWC_n'],'__len__'): + rosco_vt['AWC_n'] = [rosco_vt['AWC_n']] rosco_vt['AWC_n'] = [int(awcn) for awcn in rosco_vt['AWC_n']] print('Writing new controller parameter file parameter file: %s.' % param_file) From de8d228a6bbb7574173a7b2113cc88d7e261b29a Mon Sep 17 00:00:00 2001 From: dzalkind Date: Wed, 8 Mar 2023 12:45:22 -0700 Subject: [PATCH 071/224] Fix input file writing, force into int in write_array --- ROSCO_toolbox/utilities.py | 11 ++++++----- 1 file changed, 6 insertions(+), 5 deletions(-) diff --git a/ROSCO_toolbox/utilities.py b/ROSCO_toolbox/utilities.py index 694028a2..05d42a6c 100644 --- a/ROSCO_toolbox/utilities.py +++ b/ROSCO_toolbox/utilities.py @@ -79,9 +79,6 @@ def write_DISCON(turbine, controller, param_file='DISCON.IN', txt_filename='Cp_C rosco_vt['CC_GroupIndex'] = [rosco_vt['CC_GroupIndex']] # make an array if not hasattr(rosco_vt['StC_GroupIndex'],'__len__'): rosco_vt['StC_GroupIndex'] = [rosco_vt['StC_GroupIndex']] - if not hasattr(rosco_vt['AWC_n'],'__len__'): - rosco_vt['AWC_n'] = [rosco_vt['AWC_n']] - rosco_vt['AWC_n'] = [int(awcn) for awcn in rosco_vt['AWC_n']] print('Writing new controller parameter file parameter file: %s.' % param_file) # Should be obvious what's going on here... @@ -256,12 +253,12 @@ def write_DISCON(turbine, controller, param_file='DISCON.IN', txt_filename='Cp_C file.write('\n') file.write('!------- Cable Control ---------------------------------------------------------\n') file.write('{:<11d} ! CC_Group_N - {}\n'.format(len(rosco_vt['CC_GroupIndex']), input_descriptions['CC_Group_N'])) - file.write('{:^11s} ! CC_GroupIndex - {}\n'.format(' '.join([f'{int(ind):d}' for ind in rosco_vt['CC_GroupIndex']]), input_descriptions['CC_GroupIndex'])) + file.write('{:^11s} ! CC_GroupIndex - {}\n'.format(write_array(rosco_vt['CC_GroupIndex'],'<6d'), input_descriptions['CC_GroupIndex'])) file.write('{:<11f} ! CC_ActTau - {}\n'.format(rosco_vt['CC_ActTau'], input_descriptions['CC_ActTau'] )) file.write('\n') file.write('!------- Structural Controllers ---------------------------------------------------------\n') file.write('{:<11d} ! StC_Group_N - {}\n'.format(len(rosco_vt['StC_GroupIndex']), input_descriptions['StC_Group_N'])) - file.write('{:^11s} ! StC_GroupIndex - {}\n'.format(' '.join([f'{int(ind):d}' for ind in rosco_vt['StC_GroupIndex']]), input_descriptions['StC_GroupIndex'])) + file.write('{:^11s} ! StC_GroupIndex - {}\n'.format(write_array(rosco_vt['StC_GroupIndex'],'<6d'), input_descriptions['StC_GroupIndex'])) file.close() @@ -666,4 +663,8 @@ def write_array(array,format='<.4f'): if not hasattr(array,'__len__'): #not an array array = [array] + # force int if not + if 'd' in format and type(array[0]) != int: + array = [int(a) for a in array] + return ''.join(['{:{}} '.format(item,format) for item in array]) From e1379de0a41db91064182b1240be1dad0d94a4c9 Mon Sep 17 00:00:00 2001 From: dzalkind Date: Wed, 8 Mar 2023 12:46:44 -0700 Subject: [PATCH 072/224] Run ROSCO_testing from anywhere --- .gitignore | 1 + ROSCO_testing/ROSCO_testing.py | 14 ++++++++------ 2 files changed, 9 insertions(+), 6 deletions(-) diff --git a/.gitignore b/.gitignore index e633e4cd..ba1e27c1 100644 --- a/.gitignore +++ b/.gitignore @@ -81,6 +81,7 @@ Examples/*.p # Exclude testing results ROSCO_testing/results/ +ROSCO_testing/testing # Simulink/Matlab temp files *.slxc diff --git a/ROSCO_testing/ROSCO_testing.py b/ROSCO_testing/ROSCO_testing.py index 6eb72716..7ddfea70 100644 --- a/ROSCO_testing/ROSCO_testing.py +++ b/ROSCO_testing/ROSCO_testing.py @@ -544,6 +544,8 @@ def print_results(self,outfiles): if __name__=='__main__': rt = ROSCO_testing() + this_dir = os.path.dirname(__file__) + ## =================== INITIALIZATION =================== # Setup simulation parameters @@ -552,14 +554,14 @@ def print_results(self,outfiles): rt.Turbsim_exe = 'turbsim' # Turbsim executable path # path to compiled ROSCO controller if platform.system() == 'Windows': - rt.rosco_path = os.path.join(os.getcwd(), '../ROSCO/build/libdiscon.dll') + rt.rosco_path = os.path.join(this_dir, '../ROSCO/build/libdiscon.dll') elif platform.system() == 'Darwin': - rt.rosco_path = os.path.join(os.getcwd(), '../ROSCO/build/libdiscon.dylib') + rt.rosco_path = os.path.join(this_dir, '../ROSCO/build/libdiscon.dylib') else: - rt.rosco_path = os.path.join(os.getcwd(), '../ROSCO/build/libdiscon.so') + rt.rosco_path = os.path.join(this_dir, '../ROSCO/build/libdiscon.so') rt.debug_level = 2 # debug level. 0 - no outputs, 1 - minimal outputs, 2 - all outputs rt.overwrite = True # overwite fast sims? - rt.cores = 4 # number of cores if multiprocessings + rt.cores = 1 # number of cores if multiprocessings rt.mpi_run = False # run using mpi rt.mpi_comm_map_down = [] # core mapping for MPI rt.outfile_fmt = 2 # 1 = .txt, 2 = binary, 3 = both @@ -567,7 +569,7 @@ def print_results(self,outfiles): # Setup turbine rt.Turbine_Class = 'I' rt.Turbulence_Class = 'B' - rt.FAST_directory = os.path.join(os.getcwd(), '../Test_Cases/IEA-15-240-RWT-UMaineSemi') + rt.FAST_directory = os.path.join(this_dir, '../Test_Cases/IEA-15-240-RWT-UMaineSemi') rt.FAST_InputFile = 'IEA-15-240-RWT-UMaineSemi.fst' # Additional inputs @@ -583,7 +585,7 @@ def print_results(self,outfiles): case_inputs[('DISCON_in', 'WE_Mode')] = {'vals': [2], 'group': 0} # Wind Speeds - U = [5, 9, 12, 15] + U = [5] # Run test rt.ROSCO_Test_lite(more_case_inputs=case_inputs, U=U) From 2947b4f104d45d2ea926b944ec66aa9089576450 Mon Sep 17 00:00:00 2001 From: dzalkind Date: Wed, 8 Mar 2023 13:25:22 -0700 Subject: [PATCH 073/224] Dylib -> so in Test_Cases --- .../IEA-15-240-RWT-UMaineSemi_ServoDyn.dat | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Test_Cases/IEA-15-240-RWT-UMaineSemi/IEA-15-240-RWT-UMaineSemi_ServoDyn.dat b/Test_Cases/IEA-15-240-RWT-UMaineSemi/IEA-15-240-RWT-UMaineSemi_ServoDyn.dat index b7fdf0f6..51a09d4e 100644 --- a/Test_Cases/IEA-15-240-RWT-UMaineSemi/IEA-15-240-RWT-UMaineSemi_ServoDyn.dat +++ b/Test_Cases/IEA-15-240-RWT-UMaineSemi/IEA-15-240-RWT-UMaineSemi_ServoDyn.dat @@ -74,7 +74,7 @@ True GenTiStp - Method to stop the generator {T: timed usin ---------------------- CABLE CONTROL ------------------------------------------- 0 CCmode - Cable control mode {0: none, 4: user-defined from Simulink/Labview, 5: user-defined from Bladed-style DLL} (switch) ---------------------- BLADED INTERFACE ---------------------------------------- [used only with Bladed Interface] -"../../ROSCO/install/lib/libdiscon.dylib" DLL_FileName - Name/location of the dynamic library {.dll [Windows] or .so [Linux]} in the Bladed-DLL format (-) [used only with Bladed Interface] +"../../ROSCO/install/lib/libdiscon.so" DLL_FileName - Name/location of the dynamic library {.dll [Windows] or .so [Linux]} in the Bladed-DLL format (-) [used only with Bladed Interface] "DISCON-UMaineSemi.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] From cae3f1733af02d19a90010fc0eaf1ffc9dff5672 Mon Sep 17 00:00:00 2001 From: jfrederik-nrel Date: Wed, 15 Mar 2023 14:58:52 -0600 Subject: [PATCH 074/224] Updated AWC input parameters. --- Examples/20_active_wake_control.py | 46 ++++++++++--------- ROSCO/rosco_registry/rosco_types.yaml | 6 ++- ROSCO/src/Controllers.f90 | 2 +- ROSCO/src/ROSCO_Types.f90 | 5 +- ROSCO/src/ReadSetParameters.f90 | 5 +- ROSCO_toolbox/inputs/toolbox_schema.yaml | 12 +++-- ROSCO_toolbox/utilities.py | 11 +++-- Test_Cases/BAR_10/BAR_10_DISCON.IN | 17 +++---- .../DISCON-UMaineSemi.IN | 17 +++---- Test_Cases/NREL-5MW/DISCON.IN | 17 +++---- .../NREL_2p8_127/NREL-2p8-127_DISCON.IN | 17 +++---- 11 files changed, 87 insertions(+), 68 deletions(-) diff --git a/Examples/20_active_wake_control.py b/Examples/20_active_wake_control.py index 84c800a4..6cbcd9a6 100644 --- a/Examples/20_active_wake_control.py +++ b/Examples/20_active_wake_control.py @@ -51,17 +51,17 @@ theta(t) = theta_0(t) + AWC_amp*PI/180 * cos(2*Pi*AWC_freq * t + psi(t)) (eq 6) Note that the inverse multi-blade coordinate (MBC) transformation can also be used to obtain the same result as eq 6. Beginning with Eq. 3 from [2], we have - / \ / \ + / \ / \ | theta_1(t) | | theta_0(t) | | theta_2(t) | = T^-1(psi(t)) * | theta_tilt(t) | (eq 7) | theta_3(t) | | theta_yaw(t) | \ / \ / where - / \ - | 1 cos(psi_1(t)) sin(psi_1(t)) | + / \ + | 1 cos(psi_1(t)) sin(psi_1(t)) | T^-1(psi(t)) = | 1 cos(psi_2(t)) sin(psi_2(t)) | - | 1 cos(psi_3(t)) sin(psi_3(t)) | - \ / + | 1 cos(psi_3(t)) sin(psi_3(t)) | + \ / Multiplying the first row of the top matrix (and dropping the subscript of blade 1) yields: theta(t) = theta_0(t) + theta_tilt(t)*cos(psi(t)) + theta_yaw(t)*sin(psi(t)) (eq 8) @@ -72,23 +72,25 @@ which is equivlanet to eq 6 above. ----------------------------------------------- -AWC_Mode = 2: Coleman transform implementation: +AWC_Mode = 2: Coleman transform method: ----------------------------------------------- The inputs to the controller are: Name Unit Type Range Description AWC_NumModes - Integer [1,2] number of modes for tilt and yaw (1: identical settings for tilt and yaw pitch angles, 2: seperate settings for tilt and yaw moments) - AWC_n - Integer [0,1] IPC-AWC enabled (size = AWC_NumModes. 0: collective pitch AWC [UNDER CONSTRUCTION], 1: IPC-AWC) - AWC_clockangle deg Array of Floats [0,360] clocking angle(s) of tilt and yaw pitch angles (size = AWC_NumModes. If size = 1: phase delay of yaw moment w.r.t. tilt moment) + AWC_harmonic - Integer [0,inf] harmonic(s) to apply in the inverse Coleman transform (size = AWC_NumModes. 0: collective pitch AWC, 1: 1P IPC-AWC, 2: 2P IPC-AWC, etc.) + AWC_clockangle deg Array of Floats [0,360] clocking angle(s) of tilt and yaw pitch angles (size = AWC_NumModes. If size = 1, yaw clockangle = 2*clockangle) AWC_freq Hz Array of Floats [0,inf] frequency(s) of the tilt and yaw ptich angles, respectively (size = AWC_NumModes. If size = 1, both frequencies are assumed identical) AWC_amp deg Array of Floats [0,inf] pitch amplitude(s) of tilt and yaw pitch angles (size = AWC_NumModes. If size = 1, both amplitudes are assumed identical) -Using the inputs mentioned above, the user is able to specify any desired combination of sinusoidal tilt and yaw pitch angles to be tracked by the turbine. +Using the inputs mentioned above, the user is able to specify any desired combination of sinusoidal tilt and yaw modes to be tracked by the turbine. +When a single mode is defined in the inputs, the prescribed tilt and yaw angles are assumed to be identical, except for the phase. The phase difference +between the tilt and yaw angles is taken from the input AWC_clockangle Readers may be familiar with several forcing strategies from literature on active wake control that can be represented as follows: - -collective dynamic induction control: AWC_NumModes = 1, AWC_n = 0 - -helix clockwise [2]: AWC_NumModes = 1, AWC_n = 1, AWC_clockangle = -90 OR AWC_NumModes = 2, AWC_n = 1 1, AWC_clockangle = 0 -90 - -helix counter-clockwise [2]: AWC_NumModes = 1, AWC_n = 1, AWC_clockangle = 90 OR AWC_NumModes = 2, AWC_n = 1 1, AWC_clockangle = 0 90 - -up-and-down: AWC_NumModes = 2, AWC_n = 1 1, AWC_amp = # 0 (where "#" represents the desired amplitude) - -side-to-side: AWC_NumModes = 2, AWC_n = 1 1, AWC_amp = 0 # (where "#" represents the desired amplitude) + -collective dynamic induction control: AWC_NumModes = 1, AWC_harmonic = 0 + -helix clockwise [2]: AWC_NumModes = 1, AWC_harmonic = 1, AWC_clockangle = -90 OR AWC_NumModes = 2, AWC_n = [1 1], AWC_clockangle = [0 -90] + -helix counter-clockwise [2]: AWC_NumModes = 1, AWC_harmonic = 1, AWC_clockangle = 90 OR AWC_NumModes = 2, AWC_n = [1 1], AWC_clockangle = [0 90] + -up-and-down: AWC_NumModes = 2, AWC_harmonic = [1 1], AWC_amp = [# 0] (where "#" represents the desired amplitude) + -side-to-side: AWC_NumModes = 2, AWC_harmonic = [1 1], AWC_amp = [0 #] (where "#" represents the desired amplitude) -other: different combinations of the above can also be specified Calculation methodology: The inputs described above enable the user to specify a desired sinusoidal signal for either the collective pitch (AWC_n = 0) or tilt and yaw pitch @@ -109,15 +111,14 @@ theta_yaw(t) = AWC_amp(2) * sin(2*pi*AWC_freq(2)*t + AWC_clockangle(2)) (eq 4) and / \ - | 1 cos(psi_1(t)) sin(psi_1(t)) | + | 1 cos(psi_1(t)) sin(psi_1(t)) | T^-1(psi(t)) = | 1 cos(psi_2(t)) sin(psi_2(t)) | (eq 5) | 1 cos(psi_3(t)) sin(psi_3(t)) | \ / with psi_k(t) the azimuthal position of blade k at time instant t. Note that if AWC_NumModes = 1, it is assumed that: AWC_amp(2) = AWC_amp(1) AWC_freq(2) = AWC_freq(1) - AWC_clockangle(2) = AWC_clockangle(1) - AWC_clockangle(1) = 0 + AWC_clockangle(2) = 2*AWC_clockangle(1) For more information on this control strategy, the user is referred to [2]. ----------------------------------------------- @@ -138,7 +139,7 @@ import numpy as np # Choose your implementation method -AWC_Mode = 2 # 1 for SNL implementation, 2 for Coleman Transformation implementation +AWC_Mode = 1 # 1 for SNL implementation, 2 for Coleman Transformation implementation #directories this_dir = os.path.dirname(os.path.abspath(__file__)) @@ -171,17 +172,18 @@ def main(): # Set up AWC cases defined above if AWC_Mode == 1: + control_base_case[('DISCON_in','AWC_Mode')] = {'vals': [0,1,1,1,1,1], 'group': 2} control_base_case[('DISCON_in','AWC_NumModes')] = {'vals': [1,1,1,1,2,2], 'group': 2} control_base_case[('DISCON_in','AWC_n')] = {'vals': [[0],[0],[1],[-1],[-1,1], [-1,1]], 'group': 2} control_base_case[('DISCON_in','AWC_freq')] = {'vals': [[0],[0.05],[0.05],[0.05],[0.05,0.05], [0.05,0.05]], 'group': 2} - control_base_case[('DISCON_in','AWC_amp')] = {'vals': [[0],[1.0],[1.0],[1.0],[0.5,0.5], [0.5,0.5]], 'group': 2} + control_base_case[('DISCON_in','AWC_amp')] = {'vals': [[0],[2.5],[2.5],[2.5],[1.25,1.25], [1.25,1.25]], 'group': 2} control_base_case[('DISCON_in','AWC_clockangle')] = {'vals': [[0],[0],[0],[0],[0,0], [90,90]], 'group': 2} elif AWC_Mode == 2: control_base_case[('DISCON_in','AWC_Mode')] = {'vals': [0,2,2,2,2,2], 'group': 2} control_base_case[('DISCON_in','AWC_NumModes')] = {'vals': [1,1,2,2,2,2], 'group': 2} - control_base_case[('DISCON_in','AWC_n')] = {'vals': [[0],[0],[1,1],[1,1],[1,1], [1,1]], 'group': 2} + control_base_case[('DISCON_in','AWC_harmonic')] = {'vals': [[0],[0],[1,1],[1,1],[1,1], [1,1]], 'group': 2} control_base_case[('DISCON_in','AWC_freq')] = {'vals': [[0],[0.05],[0.05,0.05],[0.05,0.05],[0.05,0.05], [0.05,0.05]], 'group': 2} - control_base_case[('DISCON_in','AWC_amp')] = {'vals': [[0],[1.0],[1.0,1.0],[1.0,1.0],[1.0,0.0], [0.0,1.0]], 'group': 2} + control_base_case[('DISCON_in','AWC_amp')] = {'vals': [[0],[2.5],[2.5,2.5],[2.5,2.5],[2.5,0.0], [0.0,2.5]], 'group': 2} control_base_case[('DISCON_in','AWC_clockangle')] = {'vals': [[0],[0],[0,-90],[0,90],[0,0], [180,180]], 'group': 2} # simulation set up @@ -189,7 +191,7 @@ def main(): r.tuning_yaml = parameter_filename r.wind_case_fcn = cl.power_curve # single step wind input r.wind_case_opts = { - 'U': [6], # from 10 to 15 m/s + 'U': [14], # from 10 to 15 m/s 'TMax': 100, } r.case_inputs = control_base_case diff --git a/ROSCO/rosco_registry/rosco_types.yaml b/ROSCO/rosco_registry/rosco_types.yaml index 6b8529d7..336fa2a8 100644 --- a/ROSCO/rosco_registry/rosco_types.yaml +++ b/ROSCO/rosco_registry/rosco_types.yaml @@ -453,7 +453,7 @@ ControlParameters: # Active wake control AWC_Mode: <<: *integer - description: Active wake control mode [0 - unused, 1 - SNL method] + description: Active wake control mode [0 - unused, 1 - complex number method, 2 - Coleman transform method] AWC_NumModes: <<: *integer description: AWC- Number of modes to include [-] @@ -461,6 +461,10 @@ ControlParameters: <<: *integer allocatable: True description: AWC azimuthal mode [-] + AWC_harmonic: + <<: *integer + allocatable: True + description: AWC AWC Coleman transform harmonic [-] AWC_freq: <<: *real allocatable: True diff --git a/ROSCO/src/Controllers.f90 b/ROSCO/src/Controllers.f90 index eafc70ca..c66d9395 100644 --- a/ROSCO/src/Controllers.f90 +++ b/ROSCO/src/Controllers.f90 @@ -665,7 +665,7 @@ SUBROUTINE ActiveWakeControl(CntrPar, LocalVar, DebugVar) IF (CntrPar%AWC_NumModes == 1) THEN AWC_TiltYaw(2) = PI/180*CntrPar%AWC_amp(1)*cos(LocalVar%Time*2*PI*CntrPar%AWC_freq(1) + 2*CntrPar%AWC_clockangle(1)*PI/180) ENDIF - CALL ColemanTransformInverse(AWC_TiltYaw(1), AWC_TiltYaw(2), LocalVar%Azimuth, CntrPar%AWC_n(Imode), 0.0, AWC_angle) + CALL ColemanTransformInverse(AWC_TiltYaw(1), AWC_TiltYaw(2), LocalVar%Azimuth, CntrPar%AWC_harmonic(Imode), 0.0, AWC_angle) DO K = 1,LocalVar%NumBl ! Loop through all blades, apply AWC_angle LocalVar%PitCom(K) = LocalVar%PitCom(K) + AWC_angle(K) diff --git a/ROSCO/src/ROSCO_Types.f90 b/ROSCO/src/ROSCO_Types.f90 index 737c8ff8..ea948cb4 100644 --- a/ROSCO/src/ROSCO_Types.f90 +++ b/ROSCO/src/ROSCO_Types.f90 @@ -115,9 +115,10 @@ MODULE ROSCO_Types INTEGER(IntKi) :: PA_Mode ! Pitch actuator mode {0 - not used, 1 - first order filter, 2 - second order filter} REAL(DbKi) :: PA_CornerFreq ! Pitch actuator bandwidth/cut-off frequency [rad/s] REAL(DbKi) :: PA_Damping ! Pitch actuator damping ratio [-, unused if PA_Mode = 1] - INTEGER(IntKi) :: AWC_Mode ! Active wake control mode [0 - unused, 1 - SNL method, 2 - NREL method] + INTEGER(IntKi) :: AWC_Mode ! Active wake control mode [0 - unused, 1 - complex number method, 2 - Coleman transform method] INTEGER(IntKi) :: AWC_NumModes ! AWC- Number of modes to include [-] - INTEGER(IntKi), DIMENSION(:), ALLOCATABLE :: AWC_n ! AWC azimuthal mode [-] + INTEGER(IntKi), DIMENSION(:), ALLOCATABLE :: AWC_n ! AWC azimuthal mode [-] (only used in complex number method) + INTEGER(IntKi), DIMENSION(:), ALLOCATABLE :: AWC_harmonic ! AWC azimuthal mode [-] (only used in Coleman transform method) REAL(DbKi), DIMENSION(:), ALLOCATABLE :: AWC_freq ! AWC frequency [Hz] REAL(DbKi), DIMENSION(:), ALLOCATABLE :: AWC_amp ! AWC amplitude [deg] REAL(DbKi), DIMENSION(:), ALLOCATABLE :: AWC_clockangle ! AWC clocking angle [deg] diff --git a/ROSCO/src/ReadSetParameters.f90 b/ROSCO/src/ReadSetParameters.f90 index 173b76c7..40a239d4 100644 --- a/ROSCO/src/ReadSetParameters.f90 +++ b/ROSCO/src/ReadSetParameters.f90 @@ -364,7 +364,7 @@ SUBROUTINE ReadControlParameterFileSub(CntrPar, zmqVar, accINFILE, accINFILE_siz CALL ParseInput(FileLines,'OL_Mode', CntrPar%OL_Mode, accINFILE(1), ErrVar, UnEc=UnEc) CALL ParseInput(FileLines,'PA_Mode', CntrPar%PA_Mode, accINFILE(1), ErrVar, UnEc=UnEc) CALL ParseInput(FileLines,'PF_Mode', CntrPar%PF_Mode, accINFILE(1), ErrVar, UnEc=UnEc) - CALL ParseInput(FileLines,'AWC_Mode', CntrPar%AWC_Mode, accINFILE(1), ErrVar, UnEc=UnEc) + CALL ParseInput(FileLines,'AWC_Mode', CntrPar%AWC_Mode, accINFILE(1), ErrVar, UnEc=UnEc) CALL ParseInput(FileLines,'Ext_Mode', CntrPar%Ext_Mode, accINFILE(1), ErrVar, UnEc=UnEc) CALL ParseInput(FileLines,'ZMQ_Mode', CntrPar%ZMQ_Mode, accINFILE(1), ErrVar, UnEc=UnEc) CALL ParseInput(FileLines,'CC_Mode', CntrPar%CC_Mode, accINFILE(1), ErrVar, UnEc=UnEc) @@ -507,7 +507,8 @@ SUBROUTINE ReadControlParameterFileSub(CntrPar, zmqVar, accINFILE, accINFILE_siz !------------ AWC input ------------ CALL ParseInput(FileLines, 'AWC_NumModes', CntrPar%AWC_NumModes, accINFILE(1), ErrVar, CntrPar%AWC_Mode == 0, UnEc) - CALL ParseAry( FileLines, 'AWC_n', CntrPar%AWC_n, CntrPar%AWC_NumModes, accINFILE(1), ErrVar, CntrPar%AWC_Mode == 0, UnEc) + CALL ParseAry( FileLines, 'AWC_n', CntrPar%AWC_n, CntrPar%AWC_NumModes, accINFILE(1), ErrVar, CntrPar%AWC_Mode /= 1, UnEc) + CALL ParseAry( FileLines, 'AWC_harmonic', CntrPar%AWC_harmonic, CntrPar%AWC_NumModes, accINFILE(1), ErrVar, CntrPar%AWC_Mode < 2, UnEc) CALL ParseAry( FileLines, 'AWC_freq', CntrPar%AWC_freq, CntrPar%AWC_NumModes, accINFILE(1), ErrVar, CntrPar%AWC_Mode == 0, UnEc) CALL ParseAry( FileLines, 'AWC_amp', CntrPar%AWC_amp, CntrPar%AWC_NumModes, accINFILE(1), ErrVar, CntrPar%AWC_Mode == 0, UnEc) CALL ParseAry( FileLines, 'AWC_clockangle', CntrPar%AWC_clockangle, CntrPar%AWC_NumModes, accINFILE(1), ErrVar, CntrPar%AWC_Mode == 0, UnEc) diff --git a/ROSCO_toolbox/inputs/toolbox_schema.yaml b/ROSCO_toolbox/inputs/toolbox_schema.yaml index 8c1cd719..16fa7ae5 100644 --- a/ROSCO_toolbox/inputs/toolbox_schema.yaml +++ b/ROSCO_toolbox/inputs/toolbox_schema.yaml @@ -916,17 +916,23 @@ properties: minimum: 0 maximum: 2 default: 0 - description: Active wake control mode {0 - not used, 1 - SNL method, 2 - NREL method} + description: Active wake control mode {0 - not used, 1 - complex number method, 2 - Coleman transformation method} AWC_NumModes: type: number - description: Number of AWC modes (only used in SNL method) + description: Number of AWC modes units: rad default: 1 AWC_n: type: array items: type: number - description: AWC azimuthal number (only used in SNL method) + description: AWC azimuthal number (only used in complex number method) + default: [1] + AWC_harmonic: + type: array + items: + type: number + description: AWC Coleman transform harmonic (only used in Coleman transform method) default: [1] AWC_freq: type: array diff --git a/ROSCO_toolbox/utilities.py b/ROSCO_toolbox/utilities.py index 05d42a6c..5f573a86 100644 --- a/ROSCO_toolbox/utilities.py +++ b/ROSCO_toolbox/utilities.py @@ -107,7 +107,7 @@ def write_DISCON(turbine, controller, param_file='DISCON.IN', txt_filename='Cp_C file.write('{0:<12d} ! OL_Mode - Open loop control mode {{0: no open loop control, 1: open loop control vs. time}}\n'.format(int(rosco_vt['OL_Mode']))) file.write('{0:<12d} ! PA_Mode - Pitch actuator mode {{0 - not used, 1 - first order filter, 2 - second order filter}}\n'.format(int(rosco_vt['PA_Mode']))) file.write('{0:<12d} ! PF_Mode - Pitch fault mode {{0 - not used, 1 - constant offset on one or more blades}}\n'.format(int(rosco_vt['PF_Mode']))) - file.write('{0:<12d} ! AWC_Mode - Active wake control {{0 - not used, 1 - complex number method, 2 - coleman transform method}}\n'.format(int(rosco_vt['AWC_Mode']))) + file.write('{0:<12d} ! AWC_Mode - Active wake control {{0 - not used, 1 - complex number method, 2 - Coleman transform method}}\n'.format(int(rosco_vt['AWC_Mode']))) file.write('{0:<12d} ! Ext_Mode - External control mode {{0 - not used, 1 - call external dynamic library}}\n'.format(int(rosco_vt['Ext_Mode']))) file.write('{0:<12d} ! ZMQ_Mode - Fuse ZeroMQ interface {{0: unused, 1: Yaw Control}}\n'.format(int(rosco_vt['ZMQ_Mode']))) file.write('{:<12d} ! CC_Mode - {}\n'.format(int(rosco_vt['CC_Mode']),mode_descriptions['CC_Mode'])) @@ -236,11 +236,12 @@ def write_DISCON(turbine, controller, param_file='DISCON.IN', txt_filename='Cp_C file.write('{} ! PF_Offsets - Constant blade pitch offsets for blades 1-3 [rad]\n'.format(''.join('{:<10.8f} '.format(rosco_vt['PF_Offsets'][i]) for i in range(3)))) file.write('\n') file.write('!------- Active Wake Control -----------------------------------------------------\n') - file.write('{0:<12d} ! AWC_NumModes - Number of forcing modes\n'.format(int(rosco_vt['AWC_NumModes']))) - file.write('{} ! AWC_n - Azimuthal mode number(s) (i.e., the number and direction of the lobes of the wake structure)\n'.format(write_array(rosco_vt['AWC_n'],'<4d'))) + file.write('{0:<12d} ! AWC_NumModes - Number of user-defined AWC forcing modes \n'.format(int(rosco_vt['AWC_NumModes']))) + file.write('{} ! AWC_n - Azimuthal mode number(s) (i.e., the number and direction of the lobes of the wake structure)\n'.format(write_array(rosco_vt['AWC_n'],'<4d'))) + file.write('{} ! AWC_harmonic - Harmonic(s) to apply in the AWC Inverse Coleman Transformation (only used when AWC_Mode = 2)\n'.format(write_array(rosco_vt['AWC_harmonic'],'<4d'))) file.write('{} ! AWC_freq - Frequency(s) of forcing mode(s) [Hz]\n'.format(write_array(rosco_vt['AWC_freq'],'<6.4f'))) - file.write('{} ! AWC_amp - Pitch amplitude(s) of forcing mode(s) (note that AWC_amp specifies the amplitude of each individual mode so that the total amplitude of pitching will be the sum of AWC_amp) [deg]\n'.format(write_array(rosco_vt['AWC_amp'],'<6.4f'))) - file.write('{} ! AWC_clockangle - Clocking angle(s) of forcing mode(s) [deg]\n'.format(write_array(rosco_vt['AWC_clockangle'],'<6.4f'))) + file.write('{} ! AWC_amp - Pitch amplitude(s) of individual forcing mode(s) [deg]\n'.format(write_array(rosco_vt['AWC_amp'],'<6.4f'))) + file.write('{} ! AWC_clockangle - Initial angle(s) of forcing mode(s) [deg]\n'.format(write_array(rosco_vt['AWC_clockangle'],'<6.4f'))) file.write('\n') file.write('!------- External Controller Interface -----------------------------------------------------\n') file.write('"{}" ! DLL_FileName - Name/location of the dynamic library in the Bladed-DLL format\n'.format(rosco_vt['DLL_FileName'])) diff --git a/Test_Cases/BAR_10/BAR_10_DISCON.IN b/Test_Cases/BAR_10/BAR_10_DISCON.IN index 89658226..c117d7cf 100644 --- a/Test_Cases/BAR_10/BAR_10_DISCON.IN +++ b/Test_Cases/BAR_10/BAR_10_DISCON.IN @@ -1,5 +1,5 @@ ! Controller parameter input file for the BAR_10 wind turbine -! - File written using ROSCO version 2.7.0 controller tuning logic on 03/07/23 +! - File written using ROSCO version 2.7.0 controller tuning logic on 03/15/23 !------- DEBUG ------------------------------------------------------------ 1 ! LoggingLevel - (0: write no debug files, 1: write standard output .dbg-file, 2: LoggingLevel 1 + ROSCO LocalVars (.dbg2) 3: LoggingLevel 2 + complete avrSWAP-array (.dbg3)) @@ -22,7 +22,7 @@ 0 ! OL_Mode - Open loop control mode {0: no open loop control, 1: open loop control vs. time} 0 ! PA_Mode - Pitch actuator mode {0 - not used, 1 - first order filter, 2 - second order filter} 0 ! PF_Mode - Pitch fault mode {0 - not used, 1 - constant offset on one or more blades} -0 ! AWC_Mode - Active wake control {0 - not used, 1 - complex number method, 2 - coleman transform method} +0 ! AWC_Mode - Active wake control {0 - not used, 1 - complex number method, 2 - Coleman transform method} 0 ! Ext_Mode - External control mode {0 - not used, 1 - call external dynamic library} 0 ! ZMQ_Mode - Fuse ZeroMQ interface {0: unused, 1: Yaw Control} 0 ! CC_Mode - Cable control mode [0- unused, 1- User defined, 2- Position control (not yet implemented)] @@ -145,11 +145,12 @@ 0.00000000 0.00000000 0.00000000 ! PF_Offsets - Constant blade pitch offsets for blades 1-3 [rad] !------- Active Wake Control ----------------------------------------------------- -1 ! AWC_NumModes - Number of forcing modes -1 ! AWC_n - Azimuthal mode number(s) (i.e., the number and direction of the lobes of the wake structure) +1 ! AWC_NumModes - Number of user-defined AWC forcing modes +1 ! AWC_n - Azimuthal mode number(s) (i.e., the number and direction of the lobes of the wake structure) +1 ! AWC_harmonic - Harmonic(s) to apply in the AWC Inverse Coleman Transformation (only used when AWC_Mode = 2) 0.0500 ! AWC_freq - Frequency(s) of forcing mode(s) [Hz] -1.0000 ! AWC_amp - Pitch amplitude(s) of forcing mode(s) (note that AWC_amp specifies the amplitude of each individual mode so that the total amplitude of pitching will be the sum of AWC_amp) [deg] -0.0000 ! AWC_clockangle - Clocking angle(s) of forcing mode(s) [deg] +1.0000 ! AWC_amp - Pitch amplitude(s) of individual forcing mode(s) [deg] +0.0000 ! AWC_clockangle - Initial angle(s) of forcing mode(s) [deg] !------- External Controller Interface ----------------------------------------------------- "unused" ! DLL_FileName - Name/location of the dynamic library in the Bladed-DLL format @@ -162,9 +163,9 @@ !------- Cable Control --------------------------------------------------------- 1 ! CC_Group_N - Number of cable control groups - 0 ! CC_GroupIndex - First index for cable control group, should correspond to deltaL + 0 ! CC_GroupIndex - First index for cable control group, should correspond to deltaL 20.000000 ! CC_ActTau - Time constant for line actuator [s] !------- Structural Controllers --------------------------------------------------------- 1 ! StC_Group_N - Number of cable control groups - 0 ! StC_GroupIndex - First index for structural control group, options specified in ServoDyn summary output + 0 ! StC_GroupIndex - First index for structural control group, options specified in ServoDyn summary output diff --git a/Test_Cases/IEA-15-240-RWT-UMaineSemi/DISCON-UMaineSemi.IN b/Test_Cases/IEA-15-240-RWT-UMaineSemi/DISCON-UMaineSemi.IN index d4343d70..303c8482 100644 --- a/Test_Cases/IEA-15-240-RWT-UMaineSemi/DISCON-UMaineSemi.IN +++ b/Test_Cases/IEA-15-240-RWT-UMaineSemi/DISCON-UMaineSemi.IN @@ -1,5 +1,5 @@ ! Controller parameter input file for the IEA-15-240-RWT-UMaineSemi wind turbine -! - File written using ROSCO version 2.7.0 controller tuning logic on 03/07/23 +! - File written using ROSCO version 2.7.0 controller tuning logic on 03/15/23 !------- DEBUG ------------------------------------------------------------ 2 ! LoggingLevel - (0: write no debug files, 1: write standard output .dbg-file, 2: LoggingLevel 1 + ROSCO LocalVars (.dbg2) 3: LoggingLevel 2 + complete avrSWAP-array (.dbg3)) @@ -22,7 +22,7 @@ 0 ! OL_Mode - Open loop control mode {0: no open loop control, 1: open loop control vs. time} 2 ! PA_Mode - Pitch actuator mode {0 - not used, 1 - first order filter, 2 - second order filter} 0 ! PF_Mode - Pitch fault mode {0 - not used, 1 - constant offset on one or more blades} -0 ! AWC_Mode - Active wake control {0 - not used, 1 - complex number method, 2 - coleman transform method} +0 ! AWC_Mode - Active wake control {0 - not used, 1 - complex number method, 2 - Coleman transform method} 0 ! Ext_Mode - External control mode {0 - not used, 1 - call external dynamic library} 0 ! ZMQ_Mode - Fuse ZeroMQ interface {0: unused, 1: Yaw Control} 0 ! CC_Mode - Cable control mode [0- unused, 1- User defined, 2- Position control (not yet implemented)] @@ -145,11 +145,12 @@ 0.00000000 0.00000000 0.00000000 ! PF_Offsets - Constant blade pitch offsets for blades 1-3 [rad] !------- Active Wake Control ----------------------------------------------------- -1 ! AWC_NumModes - Number of forcing modes -1 ! AWC_n - Azimuthal mode number(s) (i.e., the number and direction of the lobes of the wake structure) +1 ! AWC_NumModes - Number of user-defined AWC forcing modes +1 ! AWC_n - Azimuthal mode number(s) (i.e., the number and direction of the lobes of the wake structure) +1 ! AWC_harmonic - Harmonic(s) to apply in the AWC Inverse Coleman Transformation (only used when AWC_Mode = 2) 0.0500 ! AWC_freq - Frequency(s) of forcing mode(s) [Hz] -1.0000 ! AWC_amp - Pitch amplitude(s) of forcing mode(s) (note that AWC_amp specifies the amplitude of each individual mode so that the total amplitude of pitching will be the sum of AWC_amp) [deg] -0.0000 ! AWC_clockangle - Clocking angle(s) of forcing mode(s) [deg] +1.0000 ! AWC_amp - Pitch amplitude(s) of individual forcing mode(s) [deg] +0.0000 ! AWC_clockangle - Initial angle(s) of forcing mode(s) [deg] !------- External Controller Interface ----------------------------------------------------- "unused" ! DLL_FileName - Name/location of the dynamic library in the Bladed-DLL format @@ -162,9 +163,9 @@ !------- Cable Control --------------------------------------------------------- 1 ! CC_Group_N - Number of cable control groups - 0 ! CC_GroupIndex - First index for cable control group, should correspond to deltaL + 0 ! CC_GroupIndex - First index for cable control group, should correspond to deltaL 20.000000 ! CC_ActTau - Time constant for line actuator [s] !------- Structural Controllers --------------------------------------------------------- 1 ! StC_Group_N - Number of cable control groups - 0 ! StC_GroupIndex - First index for structural control group, options specified in ServoDyn summary output + 0 ! StC_GroupIndex - First index for structural control group, options specified in ServoDyn summary output diff --git a/Test_Cases/NREL-5MW/DISCON.IN b/Test_Cases/NREL-5MW/DISCON.IN index eee6ae75..a386ba46 100644 --- a/Test_Cases/NREL-5MW/DISCON.IN +++ b/Test_Cases/NREL-5MW/DISCON.IN @@ -1,5 +1,5 @@ ! Controller parameter input file for the NREL-5MW wind turbine -! - File written using ROSCO version 2.7.0 controller tuning logic on 03/07/23 +! - File written using ROSCO version 2.7.0 controller tuning logic on 03/15/23 !------- DEBUG ------------------------------------------------------------ 1 ! LoggingLevel - (0: write no debug files, 1: write standard output .dbg-file, 2: LoggingLevel 1 + ROSCO LocalVars (.dbg2) 3: LoggingLevel 2 + complete avrSWAP-array (.dbg3)) @@ -22,7 +22,7 @@ 0 ! OL_Mode - Open loop control mode {0: no open loop control, 1: open loop control vs. time} 0 ! PA_Mode - Pitch actuator mode {0 - not used, 1 - first order filter, 2 - second order filter} 0 ! PF_Mode - Pitch fault mode {0 - not used, 1 - constant offset on one or more blades} -0 ! AWC_Mode - Active wake control {0 - not used, 1 - complex number method, 2 - coleman transform method} +0 ! AWC_Mode - Active wake control {0 - not used, 1 - complex number method, 2 - Coleman transform method} 0 ! Ext_Mode - External control mode {0 - not used, 1 - call external dynamic library} 0 ! ZMQ_Mode - Fuse ZeroMQ interface {0: unused, 1: Yaw Control} 0 ! CC_Mode - Cable control mode [0- unused, 1- User defined, 2- Position control (not yet implemented)] @@ -145,11 +145,12 @@ 0.00000000 0.00000000 0.00000000 ! PF_Offsets - Constant blade pitch offsets for blades 1-3 [rad] !------- Active Wake Control ----------------------------------------------------- -1 ! AWC_NumModes - Number of forcing modes -1 ! AWC_n - Azimuthal mode number(s) (i.e., the number and direction of the lobes of the wake structure) +1 ! AWC_NumModes - Number of user-defined AWC forcing modes +1 ! AWC_n - Azimuthal mode number(s) (i.e., the number and direction of the lobes of the wake structure) +1 ! AWC_harmonic - Harmonic(s) to apply in the AWC Inverse Coleman Transformation (only used when AWC_Mode = 2) 0.0500 ! AWC_freq - Frequency(s) of forcing mode(s) [Hz] -1.0000 ! AWC_amp - Pitch amplitude(s) of forcing mode(s) (note that AWC_amp specifies the amplitude of each individual mode so that the total amplitude of pitching will be the sum of AWC_amp) [deg] -0.0000 ! AWC_clockangle - Clocking angle(s) of forcing mode(s) [deg] +1.0000 ! AWC_amp - Pitch amplitude(s) of individual forcing mode(s) [deg] +0.0000 ! AWC_clockangle - Initial angle(s) of forcing mode(s) [deg] !------- External Controller Interface ----------------------------------------------------- "unused" ! DLL_FileName - Name/location of the dynamic library in the Bladed-DLL format @@ -162,9 +163,9 @@ !------- Cable Control --------------------------------------------------------- 1 ! CC_Group_N - Number of cable control groups - 0 ! CC_GroupIndex - First index for cable control group, should correspond to deltaL + 0 ! CC_GroupIndex - First index for cable control group, should correspond to deltaL 20.000000 ! CC_ActTau - Time constant for line actuator [s] !------- Structural Controllers --------------------------------------------------------- 1 ! StC_Group_N - Number of cable control groups - 0 ! StC_GroupIndex - First index for structural control group, options specified in ServoDyn summary output + 0 ! StC_GroupIndex - First index for structural control group, options specified in ServoDyn summary output diff --git a/Test_Cases/NREL_2p8_127/NREL-2p8-127_DISCON.IN b/Test_Cases/NREL_2p8_127/NREL-2p8-127_DISCON.IN index c068b55b..aa8b7d9c 100644 --- a/Test_Cases/NREL_2p8_127/NREL-2p8-127_DISCON.IN +++ b/Test_Cases/NREL_2p8_127/NREL-2p8-127_DISCON.IN @@ -1,5 +1,5 @@ ! Controller parameter input file for the NREL-2p8-127 wind turbine -! - File written using ROSCO version 2.7.0 controller tuning logic on 03/07/23 +! - File written using ROSCO version 2.7.0 controller tuning logic on 03/15/23 !------- DEBUG ------------------------------------------------------------ 1 ! LoggingLevel - (0: write no debug files, 1: write standard output .dbg-file, 2: LoggingLevel 1 + ROSCO LocalVars (.dbg2) 3: LoggingLevel 2 + complete avrSWAP-array (.dbg3)) @@ -22,7 +22,7 @@ 0 ! OL_Mode - Open loop control mode {0: no open loop control, 1: open loop control vs. time} 0 ! PA_Mode - Pitch actuator mode {0 - not used, 1 - first order filter, 2 - second order filter} 0 ! PF_Mode - Pitch fault mode {0 - not used, 1 - constant offset on one or more blades} -0 ! AWC_Mode - Active wake control {0 - not used, 1 - complex number method, 2 - coleman transform method} +0 ! AWC_Mode - Active wake control {0 - not used, 1 - complex number method, 2 - Coleman transform method} 0 ! Ext_Mode - External control mode {0 - not used, 1 - call external dynamic library} 0 ! ZMQ_Mode - Fuse ZeroMQ interface {0: unused, 1: Yaw Control} 0 ! CC_Mode - Cable control mode [0- unused, 1- User defined, 2- Position control (not yet implemented)] @@ -145,11 +145,12 @@ 0.00000000 0.00000000 0.00000000 ! PF_Offsets - Constant blade pitch offsets for blades 1-3 [rad] !------- Active Wake Control ----------------------------------------------------- -1 ! AWC_NumModes - Number of forcing modes -1 ! AWC_n - Azimuthal mode number(s) (i.e., the number and direction of the lobes of the wake structure) +1 ! AWC_NumModes - Number of user-defined AWC forcing modes +1 ! AWC_n - Azimuthal mode number(s) (i.e., the number and direction of the lobes of the wake structure) +1 ! AWC_harmonic - Harmonic(s) to apply in the AWC Inverse Coleman Transformation (only used when AWC_Mode = 2) 0.0500 ! AWC_freq - Frequency(s) of forcing mode(s) [Hz] -1.0000 ! AWC_amp - Pitch amplitude(s) of forcing mode(s) (note that AWC_amp specifies the amplitude of each individual mode so that the total amplitude of pitching will be the sum of AWC_amp) [deg] -0.0000 ! AWC_clockangle - Clocking angle(s) of forcing mode(s) [deg] +1.0000 ! AWC_amp - Pitch amplitude(s) of individual forcing mode(s) [deg] +0.0000 ! AWC_clockangle - Initial angle(s) of forcing mode(s) [deg] !------- External Controller Interface ----------------------------------------------------- "unused" ! DLL_FileName - Name/location of the dynamic library in the Bladed-DLL format @@ -162,9 +163,9 @@ !------- Cable Control --------------------------------------------------------- 1 ! CC_Group_N - Number of cable control groups - 0 ! CC_GroupIndex - First index for cable control group, should correspond to deltaL + 0 ! CC_GroupIndex - First index for cable control group, should correspond to deltaL 20.000000 ! CC_ActTau - Time constant for line actuator [s] !------- Structural Controllers --------------------------------------------------------- 1 ! StC_Group_N - Number of cable control groups - 0 ! StC_GroupIndex - First index for structural control group, options specified in ServoDyn summary output + 0 ! StC_GroupIndex - First index for structural control group, options specified in ServoDyn summary output From bd4d7d5d90abec10e28c42a142701aa10e89ea38 Mon Sep 17 00:00:00 2001 From: jfrederik-nrel Date: Thu, 16 Mar 2023 16:31:25 -0600 Subject: [PATCH 075/224] Added checks for AWC inputs. --- Examples/20_active_wake_control.py | 2 +- ROSCO/src/ReadSetParameters.f90 | 36 ++++++++++++++++++++++++++++++ 2 files changed, 37 insertions(+), 1 deletion(-) diff --git a/Examples/20_active_wake_control.py b/Examples/20_active_wake_control.py index 6cbcd9a6..bbb64244 100644 --- a/Examples/20_active_wake_control.py +++ b/Examples/20_active_wake_control.py @@ -78,7 +78,7 @@ Name Unit Type Range Description AWC_NumModes - Integer [1,2] number of modes for tilt and yaw (1: identical settings for tilt and yaw pitch angles, 2: seperate settings for tilt and yaw moments) AWC_harmonic - Integer [0,inf] harmonic(s) to apply in the inverse Coleman transform (size = AWC_NumModes. 0: collective pitch AWC, 1: 1P IPC-AWC, 2: 2P IPC-AWC, etc.) - AWC_clockangle deg Array of Floats [0,360] clocking angle(s) of tilt and yaw pitch angles (size = AWC_NumModes. If size = 1, yaw clockangle = 2*clockangle) + AWC_clockangle deg Array of Floats [-360,360] clocking angle(s) of tilt and yaw pitch angles (size = AWC_NumModes. If size = 1, yaw clockangle = 2*clockangle) AWC_freq Hz Array of Floats [0,inf] frequency(s) of the tilt and yaw ptich angles, respectively (size = AWC_NumModes. If size = 1, both frequencies are assumed identical) AWC_amp deg Array of Floats [0,inf] pitch amplitude(s) of tilt and yaw pitch angles (size = AWC_NumModes. If size = 1, both amplitudes are assumed identical) diff --git a/ROSCO/src/ReadSetParameters.f90 b/ROSCO/src/ReadSetParameters.f90 index 40a239d4..32d9de8d 100644 --- a/ROSCO/src/ReadSetParameters.f90 +++ b/ROSCO/src/ReadSetParameters.f90 @@ -1104,6 +1104,42 @@ SUBROUTINE CheckInputs(LocalVar, CntrPar, avrSWAP, ErrVar, size_avcMSG) END IF END IF + ! --- Active Wake Control --- + IF (CntrPar%AWC_Mode > 0) THEN + IF (CntrPar%AWC_freq < 0) THEN + ErrVar%aviFAIL = -1 + ErrVar%ErrMsg = 'AWC_freq cannot be smaller than 0' + END IF + IF (CntrPar%AWC_amp < 0) THEN + ErrVar%aviFAIL = -1 + ErrVar%ErrMsg = 'AWC_amp cannot be smaller than 0' + END IF + IF (CntrPar%AWC_Mode == 1) THEN + IF ((CntrPar%AWC_clockangle > 360) .OR. (CntrPar%AWC_clockangle < 0)) THEN + ErrVar%aviFAIL = -1 + ErrVar%ErrMsg = 'AWC_clockangle must be between -360 and 360' + END IF + IF (CntrPar%AWC_NumModes < 0) THEN + ErrVar%aviFAIL = -1 + ErrVar%ErrMsg = 'AWC_NumModes must be a positive integer if AWC_Mode = 1' + END IF + END IF + IF (CntrPar%AWC_Mode == 2) THEN + IF ((CntrPar%AWC_clockangle > 360) .OR. (CntrPar%AWC_clockangle < -360)) THEN + ErrVar%aviFAIL = -1 + ErrVar%ErrMsg = 'AWC_clockangle must be between -360 and 360' + END IF + IF ((CntrPar%AWC_NumModes > 2) .OR. (CntrPar%AWC_NumModes < 1)) THEN + ErrVar%aviFAIL = -1 + ErrVar%ErrMsg = 'AWC_NumModes must be either 1 or 2 if AWC_Mode = 2' + END IF + IF (CntrPar%AWC_harmonic < 0) THEN + ErrVar%aviFAIL = -1 + ErrVar%ErrMsg = 'AWC_harmonic must be a positive integer' + END IF + END IF + END IF + IF ((CntrPar%CC_Mode < 0) .OR. (CntrPar%CC_Mode > 1)) THEN ErrVar%aviFAIL = -1 ErrVar%ErrMsg = 'CC_Mode must be 0 or 1' From 1e25c88ae60d243544ddb1a2ca3dfe5219a6c7ea Mon Sep 17 00:00:00 2001 From: jfrederik-nrel Date: Thu, 16 Mar 2023 16:52:33 -0600 Subject: [PATCH 076/224] Fixed bug in added AWC input checks. --- ROSCO/src/ReadSetParameters.f90 | 46 ++++++++++++++---------- ROSCO_toolbox/inputs/toolbox_schema.yaml | 2 +- 2 files changed, 28 insertions(+), 20 deletions(-) diff --git a/ROSCO/src/ReadSetParameters.f90 b/ROSCO/src/ReadSetParameters.f90 index 32d9de8d..36b08ef3 100644 --- a/ROSCO/src/ReadSetParameters.f90 +++ b/ROSCO/src/ReadSetParameters.f90 @@ -648,6 +648,7 @@ SUBROUTINE CheckInputs(LocalVar, CntrPar, avrSWAP, ErrVar, size_avcMSG) TYPE(LocalVariables), INTENT(IN ) :: LocalVar TYPE(ErrorVariables), INTENT(INOUT) :: ErrVar INTEGER(IntKi), INTENT(IN ) :: size_avcMSG + INTEGER(IntKi) :: Imode ! Index used for looping through AWC modes REAL(ReKi), INTENT(IN ) :: avrSWAP(*) ! The swap array, used to pass data to, and receive data from, the DLL controller. CHARACTER(*), PARAMETER :: RoutineName = 'CheckInputs' @@ -1106,37 +1107,44 @@ SUBROUTINE CheckInputs(LocalVar, CntrPar, avrSWAP, ErrVar, size_avcMSG) ! --- Active Wake Control --- IF (CntrPar%AWC_Mode > 0) THEN - IF (CntrPar%AWC_freq < 0) THEN + IF (CntrPar%AWC_NumModes < 0) THEN ErrVar%aviFAIL = -1 - ErrVar%ErrMsg = 'AWC_freq cannot be smaller than 0' + ErrVar%ErrMsg = 'AWC_NumModes must be a positive integer if AWC_Mode = 1' END IF - IF (CntrPar%AWC_amp < 0) THEN - ErrVar%aviFAIL = -1 - ErrVar%ErrMsg = 'AWC_amp cannot be smaller than 0' - END IF - IF (CntrPar%AWC_Mode == 1) THEN - IF ((CntrPar%AWC_clockangle > 360) .OR. (CntrPar%AWC_clockangle < 0)) THEN + DO Imode = 1,CntrPar%AWC_NumModes + IF (CntrPar%AWC_freq(Imode) < 0.0) THEN ErrVar%aviFAIL = -1 - ErrVar%ErrMsg = 'AWC_clockangle must be between -360 and 360' + ErrVar%ErrMsg = 'AWC_freq cannot be smaller than 0' END IF - IF (CntrPar%AWC_NumModes < 0) THEN + IF (CntrPar%AWC_amp(Imode) < 0.0) THEN ErrVar%aviFAIL = -1 - ErrVar%ErrMsg = 'AWC_NumModes must be a positive integer if AWC_Mode = 1' + ErrVar%ErrMsg = 'AWC_amp cannot be smaller than 0' END IF + END DO + IF (CntrPar%AWC_Mode == 1) THEN + DO Imode = 1,CntrPar%AWC_NumModes + IF ((CntrPar%AWC_clockangle(Imode) > 360.0) .OR. (CntrPar%AWC_clockangle(Imode) < 0.0)) THEN + ErrVar%aviFAIL = -1 + ErrVar%ErrMsg = 'AWC_clockangle must be between 0 and 360 in AWC_Mode = 1' + END IF + END DO END IF + IF (CntrPar%AWC_Mode == 2) THEN - IF ((CntrPar%AWC_clockangle > 360) .OR. (CntrPar%AWC_clockangle < -360)) THEN - ErrVar%aviFAIL = -1 - ErrVar%ErrMsg = 'AWC_clockangle must be between -360 and 360' - END IF IF ((CntrPar%AWC_NumModes > 2) .OR. (CntrPar%AWC_NumModes < 1)) THEN ErrVar%aviFAIL = -1 ErrVar%ErrMsg = 'AWC_NumModes must be either 1 or 2 if AWC_Mode = 2' END IF - IF (CntrPar%AWC_harmonic < 0) THEN - ErrVar%aviFAIL = -1 - ErrVar%ErrMsg = 'AWC_harmonic must be a positive integer' - END IF + DO Imode = 1,CntrPar%AWC_NumModes + IF ((CntrPar%AWC_clockangle(Imode) > 360.0) .OR. (CntrPar%AWC_clockangle(Imode) < -360.0)) THEN + ErrVar%aviFAIL = -1 + ErrVar%ErrMsg = 'AWC_clockangle must be between -360 and 360 in AWC_Mode = 2' + END IF + IF (CntrPar%AWC_harmonic(Imode) < 0) THEN + ErrVar%aviFAIL = -1 + ErrVar%ErrMsg = 'AWC_harmonic must be a positive integer' + END IF + END DO END IF END IF diff --git a/ROSCO_toolbox/inputs/toolbox_schema.yaml b/ROSCO_toolbox/inputs/toolbox_schema.yaml index 16fa7ae5..c5d08c74 100644 --- a/ROSCO_toolbox/inputs/toolbox_schema.yaml +++ b/ROSCO_toolbox/inputs/toolbox_schema.yaml @@ -931,7 +931,7 @@ properties: AWC_harmonic: type: array items: - type: number + type: integer description: AWC Coleman transform harmonic (only used in Coleman transform method) default: [1] AWC_freq: From 50f4191192c7aadaa425abcd34541242a4a2f337 Mon Sep 17 00:00:00 2001 From: dzalkind Date: Mon, 20 Mar 2023 14:06:21 -0600 Subject: [PATCH 077/224] Update error message --- ROSCO/src/ReadSetParameters.f90 | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/ROSCO/src/ReadSetParameters.f90 b/ROSCO/src/ReadSetParameters.f90 index 36b08ef3..85d79c80 100644 --- a/ROSCO/src/ReadSetParameters.f90 +++ b/ROSCO/src/ReadSetParameters.f90 @@ -1114,11 +1114,11 @@ SUBROUTINE CheckInputs(LocalVar, CntrPar, avrSWAP, ErrVar, size_avcMSG) DO Imode = 1,CntrPar%AWC_NumModes IF (CntrPar%AWC_freq(Imode) < 0.0) THEN ErrVar%aviFAIL = -1 - ErrVar%ErrMsg = 'AWC_freq cannot be smaller than 0' + ErrVar%ErrMsg = 'AWC_freq cannot be less than 0' END IF IF (CntrPar%AWC_amp(Imode) < 0.0) THEN ErrVar%aviFAIL = -1 - ErrVar%ErrMsg = 'AWC_amp cannot be smaller than 0' + ErrVar%ErrMsg = 'AWC_amp cannot be less than 0' END IF END DO IF (CntrPar%AWC_Mode == 1) THEN From 50bd08c19430819b7e662297d79184db76303265 Mon Sep 17 00:00:00 2001 From: dzalkind Date: Mon, 20 Mar 2023 14:32:31 -0600 Subject: [PATCH 078/224] Tidy up IPC, allow AWC and IPC with warning --- ROSCO/rosco_registry/rosco_types.yaml | 18 ++++ ROSCO/src/Controllers.f90 | 32 +++--- ROSCO/src/ROSCO_IO.f90 | 146 +++++++++++++++----------- ROSCO/src/ROSCO_Types.f90 | 12 ++- ROSCO/src/ReadSetParameters.f90 | 5 + 5 files changed, 129 insertions(+), 84 deletions(-) diff --git a/ROSCO/rosco_registry/rosco_types.yaml b/ROSCO/rosco_registry/rosco_types.yaml index 336fa2a8..d2d5fa60 100644 --- a/ROSCO/rosco_registry/rosco_types.yaml +++ b/ROSCO/rosco_registry/rosco_types.yaml @@ -955,6 +955,24 @@ LocalVariables: IPC_AxisYaw_2P: <<: *real description: Integral of quadrature, 2P + axisTilt_1P: + <<: *real + description: Tilt moment, 1P + axisYaw_1P: + <<: *real + description: Yaw moment, 1P + axisYawF_1P: + <<: *real + description: Filtered yaw moment, 1P + axisTilt_2P: + <<: *real + description: Tilt moment, 2P + axisYaw_2P: + <<: *real + description: Yaw moment, 2P + axisYawF_2P: + <<: *real + description: Filtered yaw moment, 2P IPC_KI: <<: *real description: Integral gain for IPC, after ramp [-] diff --git a/ROSCO/src/Controllers.f90 b/ROSCO/src/Controllers.f90 index c66d9395..ed45f97f 100644 --- a/ROSCO/src/Controllers.f90 +++ b/ROSCO/src/Controllers.f90 @@ -398,8 +398,6 @@ SUBROUTINE IPC(CntrPar, LocalVar, objInst, DebugVar, ErrVar) ! Local variables REAL(DbKi) :: PitComIPC(3), PitComIPCF(3), PitComIPC_1P(3), PitComIPC_2P(3) INTEGER(IntKi) :: i, K ! Integer used to loop through gains and turbine blades - REAL(DbKi) :: axisTilt_1P, axisYaw_1P, axisYawF_1P ! Direct axis and quadrature axis outputted by Coleman transform, 1P - REAL(DbKi) :: axisTilt_2P, axisYaw_2P, axisYawF_2P ! Direct axis and quadrature axis outputted by Coleman transform, 1P REAL(DbKi) :: axisYawIPC_1P ! IPC contribution with yaw-by-IPC component REAL(DbKi) :: Y_MErr, Y_MErrF, Y_MErrF_IPC ! Unfiltered and filtered yaw alignment error [rad] REAL(DbKi) :: AWC_YawAmp ! Yaw amplitude for AWC @@ -410,8 +408,8 @@ SUBROUTINE IPC(CntrPar, LocalVar, objInst, DebugVar, ErrVar) ! Body ! Pass rootMOOPs through the Coleman transform to get the tilt and yaw moment axis - CALL ColemanTransform(LocalVar%rootMOOPF, LocalVar%Azimuth, NP_1, axisTilt_1P, axisYaw_1P) - CALL ColemanTransform(LocalVar%rootMOOPF, LocalVar%Azimuth, NP_2, axisTilt_2P, axisYaw_2P) + CALL ColemanTransform(LocalVar%rootMOOPF, LocalVar%Azimuth, NP_1, LocalVar%axisTilt_1P, LocalVar%axisYaw_1P) + CALL ColemanTransform(LocalVar%rootMOOPF, LocalVar%Azimuth, NP_2, LocalVar%axisTilt_2P, LocalVar%axisYaw_2P) ! High-pass filter the MBC yaw component and filter yaw alignment error, and compute the yaw-by-IPC contribution IF (CntrPar%Y_ControlMode == 2) THEN @@ -419,7 +417,7 @@ SUBROUTINE IPC(CntrPar, LocalVar, objInst, DebugVar, ErrVar) Y_MErrF = LPFilter(Y_MErr, LocalVar%DT, CntrPar%F_YawErr, LocalVar%FP, LocalVar%iStatus, LocalVar%restart, objInst%instSecLPF) Y_MErrF_IPC = PIController(Y_MErrF, CntrPar%Y_IPC_KP, CntrPar%Y_IPC_KI, -CntrPar%Y_IPC_IntSat, CntrPar%Y_IPC_IntSat, LocalVar%DT, 0.0_DbKi, LocalVar%piP, LocalVar%restart, objInst%instPI) ELSE - axisYawF_1P = axisYaw_1P + LocalVar%axisYawF_1P = LocalVar%axisYaw_1P Y_MErrF = 0.0 Y_MErrF_IPC = 0.0 END IF @@ -442,21 +440,26 @@ SUBROUTINE IPC(CntrPar, LocalVar, objInst, DebugVar, ErrVar) ENDIF ! Integrate the signal and multiply with the IPC gain - IF ((CntrPar%IPC_ControlMode >= 1) .AND. ((CntrPar%Y_ControlMode /= 2) .AND. (CntrPar%AWC_Mode == 0))) THEN ! IPC disabled if AWC is on (add warning?) - LocalVar%IPC_axisTilt_1P = PIController(axisTilt_1P, LocalVar%IPC_KP(1), LocalVar%IPC_KI(1), -LocalVar%IPC_IntSat, LocalVar%IPC_IntSat, LocalVar%DT, 0.0_DbKi, LocalVar%piP, LocalVar%restart, objInst%instPI) - LocalVar%IPC_axisYaw_1P = PIController(axisYawF_1P, LocalVar%IPC_KP(1), LocalVar%IPC_KI(1), -LocalVar%IPC_IntSat, LocalVar%IPC_IntSat, LocalVar%DT, 0.0_DbKi, LocalVar%piP, LocalVar%restart, objInst%instPI) + IF (CntrPar%IPC_ControlMode >= 1 .AND. CntrPar%Y_ControlMode /= 2) THEN ! IPC disabled if AWC is on (add warning?) + LocalVar%IPC_axisTilt_1P = PIController(LocalVar%axisTilt_1P, LocalVar%IPC_KP(1), LocalVar%IPC_KI(1), -LocalVar%IPC_IntSat, LocalVar%IPC_IntSat, LocalVar%DT, 0.0_DbKi, LocalVar%piP, LocalVar%restart, objInst%instPI) + LocalVar%IPC_axisYaw_1P = PIController(LocalVar%axisYawF_1P, LocalVar%IPC_KP(1), LocalVar%IPC_KI(1), -LocalVar%IPC_IntSat, LocalVar%IPC_IntSat, LocalVar%DT, 0.0_DbKi, LocalVar%piP, LocalVar%restart, objInst%instPI) IF (CntrPar%IPC_ControlMode >= 2) THEN - LocalVar%IPC_axisTilt_2P = PIController(axisTilt_2P, LocalVar%IPC_KP(2), LocalVar%IPC_KI(2), -LocalVar%IPC_IntSat, LocalVar%IPC_IntSat, LocalVar%DT, 0.0_DbKi, LocalVar%piP, LocalVar%restart, objInst%instPI) - LocalVar%IPC_axisYaw_2P = PIController(axisYawF_2P, LocalVar%IPC_KP(2), LocalVar%IPC_KI(2), -LocalVar%IPC_IntSat, LocalVar%IPC_IntSat, LocalVar%DT, 0.0_DbKi, LocalVar%piP, LocalVar%restart, objInst%instPI) + LocalVar%IPC_axisTilt_2P = PIController(LocalVar%axisTilt_2P, LocalVar%IPC_KP(2), LocalVar%IPC_KI(2), -LocalVar%IPC_IntSat, LocalVar%IPC_IntSat, LocalVar%DT, 0.0_DbKi, LocalVar%piP, LocalVar%restart, objInst%instPI) + LocalVar%IPC_axisYaw_2P = PIController(LocalVar%axisYawF_2P, LocalVar%IPC_KP(2), LocalVar%IPC_KI(2), -LocalVar%IPC_IntSat, LocalVar%IPC_IntSat, LocalVar%DT, 0.0_DbKi, LocalVar%piP, LocalVar%restart, objInst%instPI) END IF + ELSE + LocalVar%IPC_axisTilt_1P = 0.0 + LocalVar%IPC_axisYaw_1P = 0.0 + LocalVar%IPC_axisTilt_2P = 0.0 + LocalVar%IPC_axisYaw_2P = 0.0 ENDIF ! Add the yaw-by-IPC contribution axisYawIPC_1P = LocalVar%IPC_axisYaw_1P + Y_MErrF_IPC ! Pass direct and quadrature axis through the inverse Coleman transform to get the commanded pitch angles - CALL ColemanTransformInverse(LocalVar%IPC_axisTilt_1P, axisYawIPC_1P, LocalVar%Azimuth, CntrPar%AWC_n(1), CntrPar%IPC_aziOffset(1), PitComIPC_1P) + CALL ColemanTransformInverse(LocalVar%IPC_axisTilt_1P, axisYawIPC_1P, LocalVar%Azimuth, NP_1, CntrPar%IPC_aziOffset(1), PitComIPC_1P) CALL ColemanTransformInverse(LocalVar%IPC_axisTilt_2P, LocalVar%IPC_axisYaw_2P, LocalVar%Azimuth, NP_2, CntrPar%IPC_aziOffset(2), PitComIPC_2P) ! Sum nP IPC contributions and store to LocalVar data type @@ -473,13 +476,6 @@ SUBROUTINE IPC(CntrPar, LocalVar, objInst, DebugVar, ErrVar) LocalVar%IPC_PitComF(K) = PitComIPCF(K) END DO - ! debugging - DebugVar%axisTilt_1P = axisTilt_1P - DebugVar%axisYaw_1P = axisYaw_1P - DebugVar%axisTilt_2P = LocalVar%IPC_axisTilt_2P - DebugVar%axisYaw_2P = LocalVar%IPC_axisYaw_2P - - ! Add RoutineName to error message IF (ErrVar%aviFAIL < 0) THEN diff --git a/ROSCO/src/ROSCO_IO.f90 b/ROSCO/src/ROSCO_IO.f90 index 834f3dca..195e7abf 100644 --- a/ROSCO/src/ROSCO_IO.f90 +++ b/ROSCO/src/ROSCO_IO.f90 @@ -90,6 +90,12 @@ SUBROUTINE WriteRestartFile(LocalVar, CntrPar, ErrVar, objInst, RootName, size_a WRITE( Un, IOSTAT=ErrStat) LocalVar%IPC_AxisYaw_1P WRITE( Un, IOSTAT=ErrStat) LocalVar%IPC_AxisTilt_2P WRITE( Un, IOSTAT=ErrStat) LocalVar%IPC_AxisYaw_2P + WRITE( Un, IOSTAT=ErrStat) LocalVar%axisTilt_1P + WRITE( Un, IOSTAT=ErrStat) LocalVar%axisYaw_1P + WRITE( Un, IOSTAT=ErrStat) LocalVar%axisYawF_1P + WRITE( Un, IOSTAT=ErrStat) LocalVar%axisTilt_2P + WRITE( Un, IOSTAT=ErrStat) LocalVar%axisYaw_2P + WRITE( Un, IOSTAT=ErrStat) LocalVar%axisYawF_2P WRITE( Un, IOSTAT=ErrStat) LocalVar%IPC_KI(1) WRITE( Un, IOSTAT=ErrStat) LocalVar%IPC_KI(2) WRITE( Un, IOSTAT=ErrStat) LocalVar%IPC_KP(1) @@ -353,6 +359,12 @@ SUBROUTINE ReadRestartFile(avrSWAP, LocalVar, CntrPar, objInst, PerfData, RootNa READ( Un, IOSTAT=ErrStat) LocalVar%IPC_AxisYaw_1P READ( Un, IOSTAT=ErrStat) LocalVar%IPC_AxisTilt_2P READ( Un, IOSTAT=ErrStat) LocalVar%IPC_AxisYaw_2P + READ( Un, IOSTAT=ErrStat) LocalVar%axisTilt_1P + READ( Un, IOSTAT=ErrStat) LocalVar%axisYaw_1P + READ( Un, IOSTAT=ErrStat) LocalVar%axisYawF_1P + READ( Un, IOSTAT=ErrStat) LocalVar%axisTilt_2P + READ( Un, IOSTAT=ErrStat) LocalVar%axisYaw_2P + READ( Un, IOSTAT=ErrStat) LocalVar%axisYawF_2P READ( Un, IOSTAT=ErrStat) LocalVar%IPC_KI(1) READ( Un, IOSTAT=ErrStat) LocalVar%IPC_KI(2) READ( Un, IOSTAT=ErrStat) LocalVar%IPC_KP(1) @@ -609,7 +621,7 @@ SUBROUTINE Debug(LocalVar, CntrPar, DebugVar, ErrVar, avrSWAP, RootName, size_av '[rad/s]', '[rad/s]', '[m/s]', '[rad]', '[rad]', & '[N/A]', '[N/A]', '[N/A]', '[N/A]', '[rad/s]', & '[deg]', '[deg]', '[deg]', '[N/A]'] - nLocalVars = 94 + nLocalVars = 100 Allocate(LocalVarOutData(nLocalVars)) Allocate(LocalVarOutStrings(nLocalVars)) LocalVarOutData(1) = LocalVar%iStatus @@ -655,57 +667,63 @@ SUBROUTINE Debug(LocalVar, CntrPar, DebugVar, ErrVar, avrSWAP, RootName, size_av LocalVarOutData(41) = LocalVar%IPC_AxisYaw_1P LocalVarOutData(42) = LocalVar%IPC_AxisTilt_2P LocalVarOutData(43) = LocalVar%IPC_AxisYaw_2P - LocalVarOutData(44) = LocalVar%IPC_KI(1) - LocalVarOutData(45) = LocalVar%IPC_KP(1) - LocalVarOutData(46) = LocalVar%IPC_IntSat - LocalVarOutData(47) = LocalVar%PC_State - LocalVarOutData(48) = LocalVar%PitCom(1) - LocalVarOutData(49) = LocalVar%PitComAct(1) - LocalVarOutData(50) = LocalVar%SS_DelOmegaF - LocalVarOutData(51) = LocalVar%TestType - LocalVarOutData(52) = LocalVar%VS_MaxTq - LocalVarOutData(53) = LocalVar%VS_LastGenTrq - LocalVarOutData(54) = LocalVar%VS_LastGenPwr - LocalVarOutData(55) = LocalVar%VS_MechGenPwr - LocalVarOutData(56) = LocalVar%VS_SpdErrAr - LocalVarOutData(57) = LocalVar%VS_SpdErrBr - LocalVarOutData(58) = LocalVar%VS_SpdErr - LocalVarOutData(59) = LocalVar%VS_State - LocalVarOutData(60) = LocalVar%VS_Rgn3Pitch - LocalVarOutData(61) = LocalVar%WE_Vw - LocalVarOutData(62) = LocalVar%WE_Vw_F - LocalVarOutData(63) = LocalVar%WE_VwI - LocalVarOutData(64) = LocalVar%WE_VwIdot - LocalVarOutData(65) = LocalVar%VS_LastGenTrqF - LocalVarOutData(66) = LocalVar%Fl_PitCom - LocalVarOutData(67) = LocalVar%NACIMU_FA_AccF - LocalVarOutData(68) = LocalVar%FA_AccF - LocalVarOutData(69) = LocalVar%PtfmTDX - LocalVarOutData(70) = LocalVar%PtfmTDY - LocalVarOutData(71) = LocalVar%PtfmTDZ - LocalVarOutData(72) = LocalVar%PtfmRDX - LocalVarOutData(73) = LocalVar%PtfmRDY - LocalVarOutData(74) = LocalVar%PtfmRDZ - LocalVarOutData(75) = LocalVar%PtfmTVX - LocalVarOutData(76) = LocalVar%PtfmTVY - LocalVarOutData(77) = LocalVar%PtfmTVZ - LocalVarOutData(78) = LocalVar%PtfmRVX - LocalVarOutData(79) = LocalVar%PtfmRVY - LocalVarOutData(80) = LocalVar%PtfmRVZ - LocalVarOutData(81) = LocalVar%PtfmTAX - LocalVarOutData(82) = LocalVar%PtfmTAY - LocalVarOutData(83) = LocalVar%PtfmTAZ - LocalVarOutData(84) = LocalVar%PtfmRAX - LocalVarOutData(85) = LocalVar%PtfmRAY - LocalVarOutData(86) = LocalVar%PtfmRAZ - LocalVarOutData(87) = LocalVar%CC_DesiredL(1) - LocalVarOutData(88) = LocalVar%CC_ActuatedL(1) - LocalVarOutData(89) = LocalVar%CC_ActuatedDL(1) - LocalVarOutData(90) = LocalVar%StC_Input(1) - LocalVarOutData(91) = LocalVar%Flp_Angle(1) - LocalVarOutData(92) = LocalVar%RootMyb_Last(1) - LocalVarOutData(93) = LocalVar%ACC_INFILE_SIZE - LocalVarOutData(94) = LocalVar%AWC_complexangle(1) + LocalVarOutData(44) = LocalVar%axisTilt_1P + LocalVarOutData(45) = LocalVar%axisYaw_1P + LocalVarOutData(46) = LocalVar%axisYawF_1P + LocalVarOutData(47) = LocalVar%axisTilt_2P + LocalVarOutData(48) = LocalVar%axisYaw_2P + LocalVarOutData(49) = LocalVar%axisYawF_2P + LocalVarOutData(50) = LocalVar%IPC_KI(1) + LocalVarOutData(51) = LocalVar%IPC_KP(1) + LocalVarOutData(52) = LocalVar%IPC_IntSat + LocalVarOutData(53) = LocalVar%PC_State + LocalVarOutData(54) = LocalVar%PitCom(1) + LocalVarOutData(55) = LocalVar%PitComAct(1) + LocalVarOutData(56) = LocalVar%SS_DelOmegaF + LocalVarOutData(57) = LocalVar%TestType + LocalVarOutData(58) = LocalVar%VS_MaxTq + LocalVarOutData(59) = LocalVar%VS_LastGenTrq + LocalVarOutData(60) = LocalVar%VS_LastGenPwr + LocalVarOutData(61) = LocalVar%VS_MechGenPwr + LocalVarOutData(62) = LocalVar%VS_SpdErrAr + LocalVarOutData(63) = LocalVar%VS_SpdErrBr + LocalVarOutData(64) = LocalVar%VS_SpdErr + LocalVarOutData(65) = LocalVar%VS_State + LocalVarOutData(66) = LocalVar%VS_Rgn3Pitch + LocalVarOutData(67) = LocalVar%WE_Vw + LocalVarOutData(68) = LocalVar%WE_Vw_F + LocalVarOutData(69) = LocalVar%WE_VwI + LocalVarOutData(70) = LocalVar%WE_VwIdot + LocalVarOutData(71) = LocalVar%VS_LastGenTrqF + LocalVarOutData(72) = LocalVar%Fl_PitCom + LocalVarOutData(73) = LocalVar%NACIMU_FA_AccF + LocalVarOutData(74) = LocalVar%FA_AccF + LocalVarOutData(75) = LocalVar%PtfmTDX + LocalVarOutData(76) = LocalVar%PtfmTDY + LocalVarOutData(77) = LocalVar%PtfmTDZ + LocalVarOutData(78) = LocalVar%PtfmRDX + LocalVarOutData(79) = LocalVar%PtfmRDY + LocalVarOutData(80) = LocalVar%PtfmRDZ + LocalVarOutData(81) = LocalVar%PtfmTVX + LocalVarOutData(82) = LocalVar%PtfmTVY + LocalVarOutData(83) = LocalVar%PtfmTVZ + LocalVarOutData(84) = LocalVar%PtfmRVX + LocalVarOutData(85) = LocalVar%PtfmRVY + LocalVarOutData(86) = LocalVar%PtfmRVZ + LocalVarOutData(87) = LocalVar%PtfmTAX + LocalVarOutData(88) = LocalVar%PtfmTAY + LocalVarOutData(89) = LocalVar%PtfmTAZ + LocalVarOutData(90) = LocalVar%PtfmRAX + LocalVarOutData(91) = LocalVar%PtfmRAY + LocalVarOutData(92) = LocalVar%PtfmRAZ + LocalVarOutData(93) = LocalVar%CC_DesiredL(1) + LocalVarOutData(94) = LocalVar%CC_ActuatedL(1) + LocalVarOutData(95) = LocalVar%CC_ActuatedDL(1) + LocalVarOutData(96) = LocalVar%StC_Input(1) + LocalVarOutData(97) = LocalVar%Flp_Angle(1) + LocalVarOutData(98) = LocalVar%RootMyb_Last(1) + LocalVarOutData(99) = LocalVar%ACC_INFILE_SIZE + LocalVarOutData(100) = LocalVar%AWC_complexangle(1) LocalVarOutStrings = [CHARACTER(15) :: 'iStatus', 'Time', 'DT', 'VS_GenPwr', 'GenSpeed', & 'RotSpeed', 'NacHeading', 'NacVane', 'HorWindV', 'rootMOOP', & 'rootMOOPF', 'BlPitch', 'BlPitchCMeas', 'Azimuth', 'NumBl', & @@ -714,17 +732,19 @@ SUBROUTINE Debug(LocalVar, CntrPar, DebugVar, ErrVar, avrSWAP, RootName, size_av 'GenBrTq', 'IPC_PitComF', 'PC_KP', 'PC_KI', 'PC_KD', & 'PC_TF', 'PC_MaxPit', 'PC_MinPit', 'PC_PitComT', 'PC_PitComT_Last', & 'PC_PitComTF', 'PC_PitComT_IPC', 'PC_PwrErr', 'PC_SpdErr', 'IPC_AxisTilt_1P', & - 'IPC_AxisYaw_1P', 'IPC_AxisTilt_2P', 'IPC_AxisYaw_2P', 'IPC_KI', 'IPC_KP', & - 'IPC_IntSat', 'PC_State', 'PitCom', 'PitComAct', 'SS_DelOmegaF', & - 'TestType', 'VS_MaxTq', 'VS_LastGenTrq', 'VS_LastGenPwr', 'VS_MechGenPwr', & - 'VS_SpdErrAr', 'VS_SpdErrBr', 'VS_SpdErr', 'VS_State', 'VS_Rgn3Pitch', & - 'WE_Vw', 'WE_Vw_F', 'WE_VwI', 'WE_VwIdot', 'VS_LastGenTrqF', & - 'Fl_PitCom', 'NACIMU_FA_AccF', 'FA_AccF', 'PtfmTDX', 'PtfmTDY', & - 'PtfmTDZ', 'PtfmRDX', 'PtfmRDY', 'PtfmRDZ', 'PtfmTVX', & - 'PtfmTVY', 'PtfmTVZ', 'PtfmRVX', 'PtfmRVY', 'PtfmRVZ', & - 'PtfmTAX', 'PtfmTAY', 'PtfmTAZ', 'PtfmRAX', 'PtfmRAY', & - 'PtfmRAZ', 'CC_DesiredL', 'CC_ActuatedL', 'CC_ActuatedDL', 'StC_Input', & - 'Flp_Angle', 'RootMyb_Last', 'ACC_INFILE_SIZE', 'AWC_complexangle'] + 'IPC_AxisYaw_1P', 'IPC_AxisTilt_2P', 'IPC_AxisYaw_2P', 'axisTilt_1P', 'axisYaw_1P', & + 'axisYawF_1P', 'axisTilt_2P', 'axisYaw_2P', 'axisYawF_2P', 'IPC_KI', & + 'IPC_KP', 'IPC_IntSat', 'PC_State', 'PitCom', 'PitComAct', & + 'SS_DelOmegaF', 'TestType', 'VS_MaxTq', 'VS_LastGenTrq', 'VS_LastGenPwr', & + 'VS_MechGenPwr', 'VS_SpdErrAr', 'VS_SpdErrBr', 'VS_SpdErr', 'VS_State', & + 'VS_Rgn3Pitch', 'WE_Vw', 'WE_Vw_F', 'WE_VwI', 'WE_VwIdot', & + 'VS_LastGenTrqF', 'Fl_PitCom', 'NACIMU_FA_AccF', 'FA_AccF', 'PtfmTDX', & + 'PtfmTDY', 'PtfmTDZ', 'PtfmRDX', 'PtfmRDY', 'PtfmRDZ', & + 'PtfmTVX', 'PtfmTVY', 'PtfmTVZ', 'PtfmRVX', 'PtfmRVY', & + 'PtfmRVZ', 'PtfmTAX', 'PtfmTAY', 'PtfmTAZ', 'PtfmRAX', & + 'PtfmRAY', 'PtfmRAZ', 'CC_DesiredL', 'CC_ActuatedL', 'CC_ActuatedDL', & + 'StC_Input', 'Flp_Angle', 'RootMyb_Last', 'ACC_INFILE_SIZE', 'AWC_complexangle' & + ] ! Initialize debug file IF ((LocalVar%iStatus == 0) .OR. (LocalVar%iStatus == -9)) THEN ! .TRUE. if we're on the first call to the DLL IF (CntrPar%LoggingLevel > 0) THEN diff --git a/ROSCO/src/ROSCO_Types.f90 b/ROSCO/src/ROSCO_Types.f90 index ea948cb4..987f1a6c 100644 --- a/ROSCO/src/ROSCO_Types.f90 +++ b/ROSCO/src/ROSCO_Types.f90 @@ -115,10 +115,10 @@ MODULE ROSCO_Types INTEGER(IntKi) :: PA_Mode ! Pitch actuator mode {0 - not used, 1 - first order filter, 2 - second order filter} REAL(DbKi) :: PA_CornerFreq ! Pitch actuator bandwidth/cut-off frequency [rad/s] REAL(DbKi) :: PA_Damping ! Pitch actuator damping ratio [-, unused if PA_Mode = 1] - INTEGER(IntKi) :: AWC_Mode ! Active wake control mode [0 - unused, 1 - complex number method, 2 - Coleman transform method] + INTEGER(IntKi) :: AWC_Mode ! Active wake control mode [0 - unused, 1 - SNL method, 2 - NREL method] INTEGER(IntKi) :: AWC_NumModes ! AWC- Number of modes to include [-] - INTEGER(IntKi), DIMENSION(:), ALLOCATABLE :: AWC_n ! AWC azimuthal mode [-] (only used in complex number method) - INTEGER(IntKi), DIMENSION(:), ALLOCATABLE :: AWC_harmonic ! AWC azimuthal mode [-] (only used in Coleman transform method) + INTEGER(IntKi), DIMENSION(:), ALLOCATABLE :: AWC_n ! AWC azimuthal mode [-] + INTEGER(IntKi), DIMENSION(:), ALLOCATABLE :: AWC_harmonic ! AWC AWC Coleman transform harmonic [-] REAL(DbKi), DIMENSION(:), ALLOCATABLE :: AWC_freq ! AWC frequency [Hz] REAL(DbKi), DIMENSION(:), ALLOCATABLE :: AWC_amp ! AWC amplitude [deg] REAL(DbKi), DIMENSION(:), ALLOCATABLE :: AWC_clockangle ! AWC clocking angle [deg] @@ -257,6 +257,12 @@ MODULE ROSCO_Types REAL(DbKi) :: IPC_AxisYaw_1P ! Integral of quadrature, 1P REAL(DbKi) :: IPC_AxisTilt_2P ! Integral of the direct axis, 2P REAL(DbKi) :: IPC_AxisYaw_2P ! Integral of quadrature, 2P + REAL(DbKi) :: axisTilt_1P ! Tilt moment, 1P + REAL(DbKi) :: axisYaw_1P ! Yaw moment, 1P + REAL(DbKi) :: axisYawF_1P ! Filtered yaw moment, 1P + REAL(DbKi) :: axisTilt_2P ! Tilt moment, 2P + REAL(DbKi) :: axisYaw_2P ! Yaw moment, 2P + REAL(DbKi) :: axisYawF_2P ! Filtered yaw moment, 2P REAL(DbKi) :: IPC_KI(2) ! Integral gain for IPC, after ramp [-] REAL(DbKi) :: IPC_KP(2) ! Proportional gain for IPC, after ramp [-] REAL(DbKi) :: IPC_IntSat ! Integrator saturation (maximum signal amplitude contrbution to pitch from IPC) diff --git a/ROSCO/src/ReadSetParameters.f90 b/ROSCO/src/ReadSetParameters.f90 index 85d79c80..dcaecbc1 100644 --- a/ROSCO/src/ReadSetParameters.f90 +++ b/ROSCO/src/ReadSetParameters.f90 @@ -1089,6 +1089,11 @@ SUBROUTINE CheckInputs(LocalVar, CntrPar, avrSWAP, ErrVar, size_avcMSG) ENDIF ENDIF + ! ---- AWC vs. IPC + IF (CntrPar%AWC_Mode > 0 .AND. CntrPar%IPC_ControlMode > 0) THEN + PRINT *, "ROSCO WARNING: Individual pitch control and active wake control are both enabled. Performance may be compromised." + ENDIF + ! --- Pitch Actuator --- IF (CntrPar%PA_Mode > 0) THEN IF ((CntrPar%PA_Mode < 0) .OR. (CntrPar%PA_Mode > 2)) THEN From e02379d93f9a281348e6d14de1ffb5391bdde952 Mon Sep 17 00:00:00 2001 From: dzalkind Date: Mon, 20 Mar 2023 14:34:27 -0600 Subject: [PATCH 079/224] Remove AWC references from IPC --- ROSCO/src/Controllers.f90 | 3 --- 1 file changed, 3 deletions(-) diff --git a/ROSCO/src/Controllers.f90 b/ROSCO/src/Controllers.f90 index ed45f97f..9e9b9cdd 100644 --- a/ROSCO/src/Controllers.f90 +++ b/ROSCO/src/Controllers.f90 @@ -400,9 +400,6 @@ SUBROUTINE IPC(CntrPar, LocalVar, objInst, DebugVar, ErrVar) INTEGER(IntKi) :: i, K ! Integer used to loop through gains and turbine blades REAL(DbKi) :: axisYawIPC_1P ! IPC contribution with yaw-by-IPC component REAL(DbKi) :: Y_MErr, Y_MErrF, Y_MErrF_IPC ! Unfiltered and filtered yaw alignment error [rad] - REAL(DbKi) :: AWC_YawAmp ! Yaw amplitude for AWC - REAL(DbKi) :: AWC_TiltAngle, AWC_YawAngle ! Tilt and yaw initial phase angle for AWC - REAL(DbKi) :: AWC_YawFreq ! Yaw frequency for AWC CHARACTER(*), PARAMETER :: RoutineName = 'IPC' From 3851a6baf47f2e0663d737e56eacbeb67870e252 Mon Sep 17 00:00:00 2001 From: dzalkind Date: Mon, 20 Mar 2023 14:37:49 -0600 Subject: [PATCH 080/224] Remove lingering comment --- ROSCO/src/Controllers.f90 | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ROSCO/src/Controllers.f90 b/ROSCO/src/Controllers.f90 index 9e9b9cdd..52743f35 100644 --- a/ROSCO/src/Controllers.f90 +++ b/ROSCO/src/Controllers.f90 @@ -437,7 +437,7 @@ SUBROUTINE IPC(CntrPar, LocalVar, objInst, DebugVar, ErrVar) ENDIF ! Integrate the signal and multiply with the IPC gain - IF (CntrPar%IPC_ControlMode >= 1 .AND. CntrPar%Y_ControlMode /= 2) THEN ! IPC disabled if AWC is on (add warning?) + IF (CntrPar%IPC_ControlMode >= 1 .AND. CntrPar%Y_ControlMode /= 2) THEN LocalVar%IPC_axisTilt_1P = PIController(LocalVar%axisTilt_1P, LocalVar%IPC_KP(1), LocalVar%IPC_KI(1), -LocalVar%IPC_IntSat, LocalVar%IPC_IntSat, LocalVar%DT, 0.0_DbKi, LocalVar%piP, LocalVar%restart, objInst%instPI) LocalVar%IPC_axisYaw_1P = PIController(LocalVar%axisYawF_1P, LocalVar%IPC_KP(1), LocalVar%IPC_KI(1), -LocalVar%IPC_IntSat, LocalVar%IPC_IntSat, LocalVar%DT, 0.0_DbKi, LocalVar%piP, LocalVar%restart, objInst%instPI) From 9d7e18de494ac532a86c85132acd3c48feeb10f1 Mon Sep 17 00:00:00 2001 From: dzalkind Date: Mon, 20 Mar 2023 14:38:04 -0600 Subject: [PATCH 081/224] Tidy file writing --- ROSCO_toolbox/utilities.py | 10 +++++----- Test_Cases/BAR_10/BAR_10_DISCON.IN | 12 ++++++------ .../IEA-15-240-RWT-UMaineSemi/DISCON-UMaineSemi.IN | 12 ++++++------ Test_Cases/NREL-5MW/DISCON.IN | 12 ++++++------ Test_Cases/NREL_2p8_127/NREL-2p8-127_DISCON.IN | 12 ++++++------ 5 files changed, 29 insertions(+), 29 deletions(-) diff --git a/ROSCO_toolbox/utilities.py b/ROSCO_toolbox/utilities.py index 5f573a86..b15b46e2 100644 --- a/ROSCO_toolbox/utilities.py +++ b/ROSCO_toolbox/utilities.py @@ -237,11 +237,11 @@ def write_DISCON(turbine, controller, param_file='DISCON.IN', txt_filename='Cp_C file.write('\n') file.write('!------- Active Wake Control -----------------------------------------------------\n') file.write('{0:<12d} ! AWC_NumModes - Number of user-defined AWC forcing modes \n'.format(int(rosco_vt['AWC_NumModes']))) - file.write('{} ! AWC_n - Azimuthal mode number(s) (i.e., the number and direction of the lobes of the wake structure)\n'.format(write_array(rosco_vt['AWC_n'],'<4d'))) - file.write('{} ! AWC_harmonic - Harmonic(s) to apply in the AWC Inverse Coleman Transformation (only used when AWC_Mode = 2)\n'.format(write_array(rosco_vt['AWC_harmonic'],'<4d'))) - file.write('{} ! AWC_freq - Frequency(s) of forcing mode(s) [Hz]\n'.format(write_array(rosco_vt['AWC_freq'],'<6.4f'))) - file.write('{} ! AWC_amp - Pitch amplitude(s) of individual forcing mode(s) [deg]\n'.format(write_array(rosco_vt['AWC_amp'],'<6.4f'))) - file.write('{} ! AWC_clockangle - Initial angle(s) of forcing mode(s) [deg]\n'.format(write_array(rosco_vt['AWC_clockangle'],'<6.4f'))) + file.write('{} ! AWC_n - Azimuthal mode number(s) (i.e., the number and direction of the lobes of the wake structure)\n'.format(write_array(rosco_vt['AWC_n'],'<4d'))) + file.write('{} ! AWC_harmonic - Harmonic(s) to apply in the AWC Inverse Coleman Transformation (only used when AWC_Mode = 2)\n'.format(write_array(rosco_vt['AWC_harmonic'],'<4d'))) + file.write('{} ! AWC_freq - Frequency(s) of forcing mode(s) [Hz]\n'.format(write_array(rosco_vt['AWC_freq'],'<6.4f'))) + file.write('{} ! AWC_amp - Pitch amplitude(s) of individual forcing mode(s) [deg]\n'.format(write_array(rosco_vt['AWC_amp'],'<6.4f'))) + file.write('{} ! AWC_clockangle - Initial angle(s) of forcing mode(s) [deg]\n'.format(write_array(rosco_vt['AWC_clockangle'],'<6.4f'))) file.write('\n') file.write('!------- External Controller Interface -----------------------------------------------------\n') file.write('"{}" ! DLL_FileName - Name/location of the dynamic library in the Bladed-DLL format\n'.format(rosco_vt['DLL_FileName'])) diff --git a/Test_Cases/BAR_10/BAR_10_DISCON.IN b/Test_Cases/BAR_10/BAR_10_DISCON.IN index c117d7cf..6bdb4e12 100644 --- a/Test_Cases/BAR_10/BAR_10_DISCON.IN +++ b/Test_Cases/BAR_10/BAR_10_DISCON.IN @@ -1,5 +1,5 @@ ! Controller parameter input file for the BAR_10 wind turbine -! - File written using ROSCO version 2.7.0 controller tuning logic on 03/15/23 +! - File written using ROSCO version 2.7.0 controller tuning logic on 03/20/23 !------- DEBUG ------------------------------------------------------------ 1 ! LoggingLevel - (0: write no debug files, 1: write standard output .dbg-file, 2: LoggingLevel 1 + ROSCO LocalVars (.dbg2) 3: LoggingLevel 2 + complete avrSWAP-array (.dbg3)) @@ -146,11 +146,11 @@ !------- Active Wake Control ----------------------------------------------------- 1 ! AWC_NumModes - Number of user-defined AWC forcing modes -1 ! AWC_n - Azimuthal mode number(s) (i.e., the number and direction of the lobes of the wake structure) -1 ! AWC_harmonic - Harmonic(s) to apply in the AWC Inverse Coleman Transformation (only used when AWC_Mode = 2) -0.0500 ! AWC_freq - Frequency(s) of forcing mode(s) [Hz] -1.0000 ! AWC_amp - Pitch amplitude(s) of individual forcing mode(s) [deg] -0.0000 ! AWC_clockangle - Initial angle(s) of forcing mode(s) [deg] +1 ! AWC_n - Azimuthal mode number(s) (i.e., the number and direction of the lobes of the wake structure) +1 ! AWC_harmonic - Harmonic(s) to apply in the AWC Inverse Coleman Transformation (only used when AWC_Mode = 2) +0.0500 ! AWC_freq - Frequency(s) of forcing mode(s) [Hz] +1.0000 ! AWC_amp - Pitch amplitude(s) of individual forcing mode(s) [deg] +0.0000 ! AWC_clockangle - Initial angle(s) of forcing mode(s) [deg] !------- External Controller Interface ----------------------------------------------------- "unused" ! DLL_FileName - Name/location of the dynamic library in the Bladed-DLL format diff --git a/Test_Cases/IEA-15-240-RWT-UMaineSemi/DISCON-UMaineSemi.IN b/Test_Cases/IEA-15-240-RWT-UMaineSemi/DISCON-UMaineSemi.IN index 303c8482..078319ac 100644 --- a/Test_Cases/IEA-15-240-RWT-UMaineSemi/DISCON-UMaineSemi.IN +++ b/Test_Cases/IEA-15-240-RWT-UMaineSemi/DISCON-UMaineSemi.IN @@ -1,5 +1,5 @@ ! Controller parameter input file for the IEA-15-240-RWT-UMaineSemi wind turbine -! - File written using ROSCO version 2.7.0 controller tuning logic on 03/15/23 +! - File written using ROSCO version 2.7.0 controller tuning logic on 03/20/23 !------- DEBUG ------------------------------------------------------------ 2 ! LoggingLevel - (0: write no debug files, 1: write standard output .dbg-file, 2: LoggingLevel 1 + ROSCO LocalVars (.dbg2) 3: LoggingLevel 2 + complete avrSWAP-array (.dbg3)) @@ -146,11 +146,11 @@ !------- Active Wake Control ----------------------------------------------------- 1 ! AWC_NumModes - Number of user-defined AWC forcing modes -1 ! AWC_n - Azimuthal mode number(s) (i.e., the number and direction of the lobes of the wake structure) -1 ! AWC_harmonic - Harmonic(s) to apply in the AWC Inverse Coleman Transformation (only used when AWC_Mode = 2) -0.0500 ! AWC_freq - Frequency(s) of forcing mode(s) [Hz] -1.0000 ! AWC_amp - Pitch amplitude(s) of individual forcing mode(s) [deg] -0.0000 ! AWC_clockangle - Initial angle(s) of forcing mode(s) [deg] +1 ! AWC_n - Azimuthal mode number(s) (i.e., the number and direction of the lobes of the wake structure) +1 ! AWC_harmonic - Harmonic(s) to apply in the AWC Inverse Coleman Transformation (only used when AWC_Mode = 2) +0.0500 ! AWC_freq - Frequency(s) of forcing mode(s) [Hz] +1.0000 ! AWC_amp - Pitch amplitude(s) of individual forcing mode(s) [deg] +0.0000 ! AWC_clockangle - Initial angle(s) of forcing mode(s) [deg] !------- External Controller Interface ----------------------------------------------------- "unused" ! DLL_FileName - Name/location of the dynamic library in the Bladed-DLL format diff --git a/Test_Cases/NREL-5MW/DISCON.IN b/Test_Cases/NREL-5MW/DISCON.IN index a386ba46..60775ec0 100644 --- a/Test_Cases/NREL-5MW/DISCON.IN +++ b/Test_Cases/NREL-5MW/DISCON.IN @@ -1,5 +1,5 @@ ! Controller parameter input file for the NREL-5MW wind turbine -! - File written using ROSCO version 2.7.0 controller tuning logic on 03/15/23 +! - File written using ROSCO version 2.7.0 controller tuning logic on 03/20/23 !------- DEBUG ------------------------------------------------------------ 1 ! LoggingLevel - (0: write no debug files, 1: write standard output .dbg-file, 2: LoggingLevel 1 + ROSCO LocalVars (.dbg2) 3: LoggingLevel 2 + complete avrSWAP-array (.dbg3)) @@ -146,11 +146,11 @@ !------- Active Wake Control ----------------------------------------------------- 1 ! AWC_NumModes - Number of user-defined AWC forcing modes -1 ! AWC_n - Azimuthal mode number(s) (i.e., the number and direction of the lobes of the wake structure) -1 ! AWC_harmonic - Harmonic(s) to apply in the AWC Inverse Coleman Transformation (only used when AWC_Mode = 2) -0.0500 ! AWC_freq - Frequency(s) of forcing mode(s) [Hz] -1.0000 ! AWC_amp - Pitch amplitude(s) of individual forcing mode(s) [deg] -0.0000 ! AWC_clockangle - Initial angle(s) of forcing mode(s) [deg] +1 ! AWC_n - Azimuthal mode number(s) (i.e., the number and direction of the lobes of the wake structure) +1 ! AWC_harmonic - Harmonic(s) to apply in the AWC Inverse Coleman Transformation (only used when AWC_Mode = 2) +0.0500 ! AWC_freq - Frequency(s) of forcing mode(s) [Hz] +1.0000 ! AWC_amp - Pitch amplitude(s) of individual forcing mode(s) [deg] +0.0000 ! AWC_clockangle - Initial angle(s) of forcing mode(s) [deg] !------- External Controller Interface ----------------------------------------------------- "unused" ! DLL_FileName - Name/location of the dynamic library in the Bladed-DLL format diff --git a/Test_Cases/NREL_2p8_127/NREL-2p8-127_DISCON.IN b/Test_Cases/NREL_2p8_127/NREL-2p8-127_DISCON.IN index aa8b7d9c..1622aa25 100644 --- a/Test_Cases/NREL_2p8_127/NREL-2p8-127_DISCON.IN +++ b/Test_Cases/NREL_2p8_127/NREL-2p8-127_DISCON.IN @@ -1,5 +1,5 @@ ! Controller parameter input file for the NREL-2p8-127 wind turbine -! - File written using ROSCO version 2.7.0 controller tuning logic on 03/15/23 +! - File written using ROSCO version 2.7.0 controller tuning logic on 03/20/23 !------- DEBUG ------------------------------------------------------------ 1 ! LoggingLevel - (0: write no debug files, 1: write standard output .dbg-file, 2: LoggingLevel 1 + ROSCO LocalVars (.dbg2) 3: LoggingLevel 2 + complete avrSWAP-array (.dbg3)) @@ -146,11 +146,11 @@ !------- Active Wake Control ----------------------------------------------------- 1 ! AWC_NumModes - Number of user-defined AWC forcing modes -1 ! AWC_n - Azimuthal mode number(s) (i.e., the number and direction of the lobes of the wake structure) -1 ! AWC_harmonic - Harmonic(s) to apply in the AWC Inverse Coleman Transformation (only used when AWC_Mode = 2) -0.0500 ! AWC_freq - Frequency(s) of forcing mode(s) [Hz] -1.0000 ! AWC_amp - Pitch amplitude(s) of individual forcing mode(s) [deg] -0.0000 ! AWC_clockangle - Initial angle(s) of forcing mode(s) [deg] +1 ! AWC_n - Azimuthal mode number(s) (i.e., the number and direction of the lobes of the wake structure) +1 ! AWC_harmonic - Harmonic(s) to apply in the AWC Inverse Coleman Transformation (only used when AWC_Mode = 2) +0.0500 ! AWC_freq - Frequency(s) of forcing mode(s) [Hz] +1.0000 ! AWC_amp - Pitch amplitude(s) of individual forcing mode(s) [deg] +0.0000 ! AWC_clockangle - Initial angle(s) of forcing mode(s) [deg] !------- External Controller Interface ----------------------------------------------------- "unused" ! DLL_FileName - Name/location of the dynamic library in the Bladed-DLL format From 7f12c9c922119776ec7a92180ab02a6904cf6cb1 Mon Sep 17 00:00:00 2001 From: dzalkind Date: Mon, 20 Mar 2023 14:42:38 -0600 Subject: [PATCH 082/224] Clean up comments --- ROSCO/src/Controllers.f90 | 2 -- 1 file changed, 2 deletions(-) diff --git a/ROSCO/src/Controllers.f90 b/ROSCO/src/Controllers.f90 index 52743f35..c966ac20 100644 --- a/ROSCO/src/Controllers.f90 +++ b/ROSCO/src/Controllers.f90 @@ -42,8 +42,6 @@ SUBROUTINE PitchControl(avrSWAP, CntrPar, LocalVar, objInst, DebugVar, ErrVar) CHARACTER(*), PARAMETER :: RoutineName = 'PitchControl' - ! Local - ! ------- Blade Pitch Controller -------- ! Load PC State IF (LocalVar%PC_State == 1) THEN ! PI BldPitch control From 8e4cf8b24e67ab0dded3bc814f1faa984d38c0c4 Mon Sep 17 00:00:00 2001 From: dzalkind Date: Mon, 20 Mar 2023 16:00:16 -0600 Subject: [PATCH 083/224] Allow more than 99 local variables in dbg2 --- ROSCO/rosco_registry/write_registry.py | 17 ++++++++++------- ROSCO/src/ROSCO_IO.f90 | 13 +++++++------ 2 files changed, 17 insertions(+), 13 deletions(-) diff --git a/ROSCO/rosco_registry/write_registry.py b/ROSCO/rosco_registry/write_registry.py index a20b96c4..2f31b400 100644 --- a/ROSCO/rosco_registry/write_registry.py +++ b/ROSCO/rosco_registry/write_registry.py @@ -183,7 +183,7 @@ def write_roscoio(yfile): file.write(' INTEGER(IntKi), INTENT(IN) :: size_avcOUTNAME\n') file.write(' INTEGER(IntKi) :: I , nDebugOuts, nLocalVars ! Generic index.\n') file.write(' CHARACTER(1), PARAMETER :: Tab = CHAR(9) ! The tab character.\n') - file.write(' CHARACTER(29), PARAMETER :: FmtDat = "(F20.5,TR5,99(ES20.5E2,TR5:))" ! The format of the debugging data\n') + file.write(' CHARACTER(100) :: FmtDat ! The format of the debugging data\n') file.write(' INTEGER(IntKi), SAVE :: UnDb ! I/O unit for the debugging information\n') file.write(' INTEGER(IntKi), SAVE :: UnDb2 ! I/O unit for the debugging information, avrSWAP\n') file.write(' INTEGER(IntKi), SAVE :: UnDb3 ! I/O unit for the debugging information, avrSWAP\n') @@ -246,7 +246,9 @@ def write_roscoio(yfile): for lv_idx, localvar in enumerate(reg['LocalVariables']): if reg['LocalVariables'][localvar]['type'] in ['integer', 'real', 'complex']: lv_strings.append(localvar) - file.write(' nLocalVars = {}\n'.format(len(lv_strings))) + + n_lv_outputs = len(lv_strings) + file.write(' nLocalVars = {}\n'.format(n_lv_outputs)) file.write(' Allocate(LocalVarOutData(nLocalVars))\n') file.write(' Allocate(LocalVarOutStrings(nLocalVars))\n') @@ -287,8 +289,8 @@ def write_roscoio(yfile): file.write(" CALL GetNewUnit(UnDb2, ErrVar)\n") file.write(" OPEN(unit=UnDb2, FILE=TRIM(RootName)//'.RO.dbg2')\n") file.write(" WRITE(UnDb2, *) 'Generated on '//CurDate()//' at '//CurTime()//' using ROSCO-'//TRIM(rosco_version)\n") - file.write(" WRITE(UnDb2, '(99(a20,TR5:))') 'Time', LocalVarOutStrings\n") - file.write(" WRITE(UnDb2, '(99(a20,TR5:))')\n") + file.write(f" WRITE(UnDb2, '({n_lv_outputs+1}(a20,TR5:))') 'Time', LocalVarOutStrings\n") + file.write(f" WRITE(UnDb2, '({n_lv_outputs+1}(a20,TR5:))')\n") file.write(" END IF\n") file.write("\n") # avrSWAP debug @@ -347,16 +349,17 @@ def write_roscoio(yfile): file.write(" END DO\n") file.write(" \n") file.write(" ! Write debug files\n") + file.write(f' FmtDat = "(F20.5,TR5,{n_lv_outputs}(ES20.5E2,TR5:))" ! The format of the debugging data\n') file.write(" IF(CntrPar%LoggingLevel > 0) THEN\n") - file.write(" WRITE (UnDb, FmtDat) LocalVar%Time, DebugOutData\n") + file.write(" WRITE (UnDb, TRIM(FmtDat)) LocalVar%Time, DebugOutData\n") file.write(" END IF\n") file.write("\n") file.write(" IF(CntrPar%LoggingLevel > 1) THEN\n") - file.write(" WRITE (UnDb2, FmtDat) LocalVar%Time, LocalVarOutData\n") + file.write(" WRITE (UnDb2, TRIM(FmtDat)) LocalVar%Time, LocalVarOutData\n") file.write(" END IF\n") file.write("\n") file.write(" IF(CntrPar%LoggingLevel > 2) THEN\n") - file.write(" WRITE (UnDb3, FmtDat) LocalVar%Time, avrSWAP(avrIndices)\n") + file.write(" WRITE (UnDb3, TRIM(FmtDat)) LocalVar%Time, avrSWAP(avrIndices)\n") file.write(" END IF\n") file.write("\n") file.write("END SUBROUTINE Debug\n") diff --git a/ROSCO/src/ROSCO_IO.f90 b/ROSCO/src/ROSCO_IO.f90 index 195e7abf..5f53a1ce 100644 --- a/ROSCO/src/ROSCO_IO.f90 +++ b/ROSCO/src/ROSCO_IO.f90 @@ -563,7 +563,7 @@ SUBROUTINE Debug(LocalVar, CntrPar, DebugVar, ErrVar, avrSWAP, RootName, size_av INTEGER(IntKi), INTENT(IN) :: size_avcOUTNAME INTEGER(IntKi) :: I , nDebugOuts, nLocalVars ! Generic index. CHARACTER(1), PARAMETER :: Tab = CHAR(9) ! The tab character. - CHARACTER(29), PARAMETER :: FmtDat = "(F20.5,TR5,99(ES20.5E2,TR5:))" ! The format of the debugging data + CHARACTER(100) :: FmtDat ! The format of the debugging data INTEGER(IntKi), SAVE :: UnDb ! I/O unit for the debugging information INTEGER(IntKi), SAVE :: UnDb2 ! I/O unit for the debugging information, avrSWAP INTEGER(IntKi), SAVE :: UnDb3 ! I/O unit for the debugging information, avrSWAP @@ -759,8 +759,8 @@ SUBROUTINE Debug(LocalVar, CntrPar, DebugVar, ErrVar, avrSWAP, RootName, size_av CALL GetNewUnit(UnDb2, ErrVar) OPEN(unit=UnDb2, FILE=TRIM(RootName)//'.RO.dbg2') WRITE(UnDb2, *) 'Generated on '//CurDate()//' at '//CurTime()//' using ROSCO-'//TRIM(rosco_version) - WRITE(UnDb2, '(99(a20,TR5:))') 'Time', LocalVarOutStrings - WRITE(UnDb2, '(99(a20,TR5:))') + WRITE(UnDb2, '(101(a20,TR5:))') 'Time', LocalVarOutStrings + WRITE(UnDb2, '(101(a20,TR5:))') END IF IF (CntrPar%LoggingLevel > 2) THEN @@ -817,16 +817,17 @@ SUBROUTINE Debug(LocalVar, CntrPar, DebugVar, ErrVar, avrSWAP, RootName, size_av END DO ! Write debug files + FmtDat = "(F20.5,TR5,100(ES20.5E2,TR5:))" ! The format of the debugging data IF(CntrPar%LoggingLevel > 0) THEN - WRITE (UnDb, FmtDat) LocalVar%Time, DebugOutData + WRITE (UnDb, TRIM(FmtDat)) LocalVar%Time, DebugOutData END IF IF(CntrPar%LoggingLevel > 1) THEN - WRITE (UnDb2, FmtDat) LocalVar%Time, LocalVarOutData + WRITE (UnDb2, TRIM(FmtDat)) LocalVar%Time, LocalVarOutData END IF IF(CntrPar%LoggingLevel > 2) THEN - WRITE (UnDb3, FmtDat) LocalVar%Time, avrSWAP(avrIndices) + WRITE (UnDb3, TRIM(FmtDat)) LocalVar%Time, avrSWAP(avrIndices) END IF END SUBROUTINE Debug From bc33417604bc011586e3b0c3683f4720c6c929aa Mon Sep 17 00:00:00 2001 From: jfrederik-nrel <120053750+jfrederik-nrel@users.noreply.github.com> Date: Mon, 20 Mar 2023 16:58:47 -0600 Subject: [PATCH 084/224] Update api_change.rst Added AWC inputs --- docs/source/api_change.rst | 31 +++++++++++++++++++++---------- 1 file changed, 21 insertions(+), 10 deletions(-) diff --git a/docs/source/api_change.rst b/docs/source/api_change.rst index c3463bf7..0dc00253 100644 --- a/docs/source/api_change.rst +++ b/docs/source/api_change.rst @@ -16,6 +16,8 @@ Optional Inputs - Input requirements depend on control modes. E.g., open loop inputs are not required if `OL_Mode = 0`` IPC Saturation Modes - Added options for saturating the IPC command with the peak shaving limit +Active wake control +- Added Active Wake Control (AWC) implementation ====== ================= ====================================================================================================================================================================================================== New in ROSCO develop @@ -24,16 +26,25 @@ Line Input Name Example Value ====== ================= ====================================================================================================================================================================================================== 6 Echo 0 ! Echo - (0 - no Echo, 1 - Echo input data to .echo) 24 CC_Mode 0 ! CC_Mode - Cable control mode [0- unused, 1- User defined, 2- Position control (not yet implemented)] -28 StC_Mode 0 ! StC_Mode - Structural control mode [0- unused, 1- User defined] -154 Empty Line -155 CC_Section !------- Cable Control --------------------------------------------------------- -156 CC_Group_N 3 ! CC_Group_N - Number of cable control groups -157 CC_GroupIndex 2601 2603 2605 ! CC_GroupIndex - First index for cable control group, should correspond to deltaL -158 CC_ActTau 20.000000 ! CC_ActTau - Time constant for line actuator [s] -159 Empty Line -160 StC_Section !------- Structural Controllers --------------------------------------------------------- -161 StC_Group_N 3 ! StC_Group_N - Number of cable control groups -162 StC_GroupIndex 2818 2838 2858 ! StC_GroupIndex - First index for structural control group, options specified in ServoDyn summary output +25 AWC_Mode 0 ! AWC_Mode - Active wake control mode [0 - not used, 1 - complex number method, 2 - Coleman transform method] +29 StC_Mode 0 ! StC_Mode - Structural control mode [0- unused, 1- User defined] +146 Empty Line +147 AWC_Section !------- Active Wake Control ----------------------------------------------------- +148 AWC_NumModes 1 ! AWC_NumModes - AWC- Number of modes to include [-] +149 AWC_n 1 ! AWC_n - AWC azimuthal mode [-] (only used in complex number method) +150 AWC_harmonic 1 ! AWC_harmonic - AWC Coleman transform harmonic [-] (only used in Coleman transform method) +151 AWC_NumModes 0.03 ! AWC_freq - AWC frequency [Hz] +152 AWC_NumModes 2.0 ! AWC_amp - AWC amplitude [deg] +153 AWC_NumModes 0.0 ! AWC_clockangle - AWC clock angle [deg] +163 Empty Line +164 CC_Section !------- Cable Control --------------------------------------------------------- +165 CC_Group_N 3 ! CC_Group_N - Number of cable control groups +166 CC_GroupIndex 2601 2603 2605 ! CC_GroupIndex - First index for cable control group, should correspond to deltaL +167 CC_ActTau 20.000000 ! CC_ActTau - Time constant for line actuator [s] +168 Empty Line +169 StC_Section !------- Structural Controllers --------------------------------------------------------- +170 StC_Group_N 3 ! StC_Group_N - Number of cable control groups +171 StC_GroupIndex 2818 2838 2858 ! StC_GroupIndex - First index for structural control group, options specified in ServoDyn summary output ====== ================= ====================================================================================================================================================================================================== From 728c61da3bbe3ff09847fab5438d8d92a906285e Mon Sep 17 00:00:00 2001 From: kbrown1snl <66843135+kbrown1snl@users.noreply.github.com> Date: Mon, 27 Mar 2023 14:14:27 -0600 Subject: [PATCH 085/224] Update 20_active_wake_control.py --- Examples/20_active_wake_control.py | 74 +++++++++++++++++++----------- 1 file changed, 48 insertions(+), 26 deletions(-) diff --git a/Examples/20_active_wake_control.py b/Examples/20_active_wake_control.py index bbb64244..c67555d8 100644 --- a/Examples/20_active_wake_control.py +++ b/Examples/20_active_wake_control.py @@ -3,41 +3,46 @@ Run openfast with ROSCO and active wake control ----------------------------------------------- Set up and run simulation with AWC, check outputs -Active wake control (AWC) with blade pitching is implemented in this example with an adaptation into the rotating frame of the mathematical framework from the classical theory for stability of axisymmetric jets [1], which offers flexibility in specifying the forcing strategy. +Active wake control (AWC) with blade pitching is implemented in this example with two approaches as detailed below: ----------------------------------------------- -AWC_Mode = 1: Complex number method: +AWC_Mode = 1: Normal mode method: ----------------------------------------------- +The normal mode method is an adaptation into the rotating frame of the mathematical framework from the classical theory for stability of axisymmetric jets [1], which offers flexibility in specifying the forcing strategy. The inputs to the controller are: Name Unit Type Range Description - AWC_NumModes - Integer [0,inf] number of forcing modes + AWC_NumModes - Integer [0,inf] number of forcing modes AWC_n - Integer [-inf,inf] azimuthal mode number(s) (i.e., the azimuthal mode number relates to the number and direction of the lobes of the wake structure according to the classical spatio-temporal Fourier decomposition of an arbitrary quantity q, sigma{sigma{q*exp(i*n*theta)*exp(i*omega*time)}}. For the case of a non-time-varying flow (i.e., where omega = 0), the azimuthal mode number specifies the number of cycles of blade pitch oscillation per one rotation around the rotor azimuth.) - AWC_clockangle deg Float [0,360] clocking angle(s) of forcing mode(s) + AWC_clockangle deg Float [0,360] clocking angle(s) of forcing mode(s) AWC_freq Hz Float [0,inf] frequency(s) of forcing mode(s) AWC_amp deg Float [0,inf] pitch amplitude(s) of forcing mode(s) (note that AWC_amp specifies the amplitude of each individual mode so that the total amplitude of pitching will be the sum of AWC_amp) + The latter two inputs may be specified based on the expected inflow while the former three inputs determine the type of active wake control to be used. + Readers may be familiar with several forcing strategies from literature on active wake control that can be represented as follows: -collective dynamic induction control: AWC_NumModes = 1, AWC_n = 0, AWC_clockangle = 0 - -helix clockwise [2]: AWC_NumModes = 1, AWC_n = 1, AWC_clockangle = 0 - -helix counter-clockwise [2]: AWC_NumModes = 1, AWC_n = -1, AWC_clockangle = 0 - -up-and-down: AWC_NumModes = 2, AWC_n = -1 1, AWC_clockangle = 0 0 - -side-to-side: AWC_NumModes = 2, AWC_n = -1 1, AWC_clockangle = 90 90 - -other: Higher-order modes or different combinations of the above can also be specified - Calculation methodology: + -helix clockwise [2]: AWC_NumModes = 1, AWC_n = 1, AWC_clockangle = 0 + -helix counter-clockwise [2]: AWC_NumModes = 1, AWC_n = -1, AWC_clockangle = 0 + -up-and-down: AWC_NumModes = 2, AWC_n = -1 1, AWC_clockangle = 0 0 + -side-to-side: AWC_NumModes = 2, AWC_n = -1 1, AWC_clockangle = 90 90 + -other: Higher-order modes or different combinations of the above can also be specified + + These strategies are implemented using the following calculation methodology: For each blade, we compute the total phase angle of blade pitch excursion according to: - AWC_angle(t) = 2*Pi*AWC_freq * t - AWC_n * (psi(t) + phi + AWC_clockangle*PI/180) (eq 1) + AWC_angle(t) = 2*Pi*AWC_freq * t - AWC_n * (psi(t) + phi + AWC_clockangle*PI/180) (eq 1) where t is time phi(t) is the angular offset of the given blade in the rotor plane relative to blade 1 psi is the angle of blade 1 in the rotor plane from top-dead center Next, the phase angle is converted into the complex pitch amplitude: - AWC_complexangle(t) = AWC_amp*PI/180 * EXP(i * AWC_angle(t)) (eq 2) + AWC_complexangle(t) = AWC_amp*PI/180 * EXP(i * AWC_angle(t)) (eq 2) where i is the square root of -1 Note that if AWC_NumModes>1, then eq 1 and 2 are computed for each additional mode, and AWC_complexangle becomes a summation over all modes for each blade. + Finally, the real pitch amplitude, theta(t), to be passed to the next step of the controller is calculated: - theta(t) = theta_0(t) + REAL(AWC_complexangle(t)) (eq 3) + theta(t) = theta_0(t) + REAL(AWC_complexangle(t)) (eq 3) where theta_0(t) is the controller's nominal pitch command Rearranging for ease of viewing: @@ -45,35 +50,44 @@ theta(t) = theta_0(t) + REAL(AWC_amp*PI/180 * EXP(i * (2*Pi*AWC_freq * t - AWC_n * (psi(t) + phi + AWC_clockangle*PI/180)))) (eq 4) Applying Euler's formula and carrying out the REAL operator: - theta(t) = theta_0(t) + AWC_amp*PI/180 * cos(2*Pi*AWC_freq * t - AWC_n * (psi(t) + phi + AWC_clockangle*PI/180)) (eq 5) + theta(t) = theta_0(t) + AWC_amp*PI/180 * cos(2*Pi*AWC_freq * t - AWC_n * (psi(t) + phi + AWC_clockangle*PI/180)) (eq 5) + As an example, we can set parameters to produce the counter-clockwise helix pattern from [2] using AWC_NumModes = 1, AWC_n = -1, and AWC_clockangle = 0: For blade 1, eq 5 becomes: - theta(t) = theta_0(t) + AWC_amp*PI/180 * cos(2*Pi*AWC_freq * t + psi(t)) (eq 6) + theta(t) = theta_0(t) + AWC_amp*PI/180 * cos(2*Pi*AWC_freq * t + psi(t)) (eq 6) + Note that the inverse multi-blade coordinate (MBC) transformation can also be used to obtain the same result as eq 6. Beginning with Eq. 3 from [2], we have + / \ / \ | theta_1(t) | | theta_0(t) | - | theta_2(t) | = T^-1(psi(t)) * | theta_tilt(t) | (eq 7) + | theta_2(t) | = T^-1(psi(t)) * | theta_tilt(t) | (eq 7) | theta_3(t) | | theta_yaw(t) | \ / \ / + where + / \ | 1 cos(psi_1(t)) sin(psi_1(t)) | T^-1(psi(t)) = | 1 cos(psi_2(t)) sin(psi_2(t)) | | 1 cos(psi_3(t)) sin(psi_3(t)) | \ / + Multiplying the first row of the top matrix (and dropping the subscript of blade 1) yields: - theta(t) = theta_0(t) + theta_tilt(t)*cos(psi(t)) + theta_yaw(t)*sin(psi(t)) (eq 8) + theta(t) = theta_0(t) + theta_tilt(t)*cos(psi(t)) + theta_yaw(t)*sin(psi(t)) (eq 8) Setting theta_tilt(t) = AWC_amp*PI/180 * cos(2*Pi*AWC_freq * t) and theta_yaw(t) = -AWC_amp*PI/180 * sin(2*Pi*AWC_freq * t) gives: - theta(t) = theta_0(t) + (AWC_amp*PI/180 * cos(2*Pi*AWC_freq * t))*cos(psi(t)) - (AWC_amp*PI/180 * sin(2*Pi*AWC_freq * t))*sin(psi(t)) (eq 9) + theta(t) = theta_0(t) + (AWC_amp*PI/180 * cos(2*Pi*AWC_freq * t))*cos(psi(t)) - (AWC_amp*PI/180 * sin(2*Pi*AWC_freq * t))*sin(psi(t)) (eq 9) + Applying a Ptolemy identity gives: - theta(t) = theta_0(t) + AWC_amp*PI/180 * cos(2*Pi*AWC_freq * t + psi(t)) (eq 10) + theta(t) = theta_0(t) + AWC_amp*PI/180 * cos(2*Pi*AWC_freq * t + psi(t)) (eq 10) which is equivlanet to eq 6 above. ----------------------------------------------- AWC_Mode = 2: Coleman transform method: ----------------------------------------------- +A second method is the Coleman transform method. + The inputs to the controller are: Name Unit Type Range Description AWC_NumModes - Integer [1,2] number of modes for tilt and yaw (1: identical settings for tilt and yaw pitch angles, 2: seperate settings for tilt and yaw moments) @@ -84,7 +98,8 @@ Using the inputs mentioned above, the user is able to specify any desired combination of sinusoidal tilt and yaw modes to be tracked by the turbine. When a single mode is defined in the inputs, the prescribed tilt and yaw angles are assumed to be identical, except for the phase. The phase difference -between the tilt and yaw angles is taken from the input AWC_clockangle +between the tilt and yaw angles is taken from the input AWC_clockangle. + Readers may be familiar with several forcing strategies from literature on active wake control that can be represented as follows: -collective dynamic induction control: AWC_NumModes = 1, AWC_harmonic = 0 -helix clockwise [2]: AWC_NumModes = 1, AWC_harmonic = 1, AWC_clockangle = -90 OR AWC_NumModes = 2, AWC_n = [1 1], AWC_clockangle = [0 -90] @@ -92,33 +107,40 @@ -up-and-down: AWC_NumModes = 2, AWC_harmonic = [1 1], AWC_amp = [# 0] (where "#" represents the desired amplitude) -side-to-side: AWC_NumModes = 2, AWC_harmonic = [1 1], AWC_amp = [0 #] (where "#" represents the desired amplitude) -other: different combinations of the above can also be specified - Calculation methodology: + + These strategies are implemented using the following calculation methodology: The inputs described above enable the user to specify a desired sinusoidal signal for either the collective pitch (AWC_n = 0) or tilt and yaw pitch angles (AWC_n = 1). These AWC pitch angles are defined as: - AWC_angle(t) = AWC_amp * sin(2*pi*AWC_freq*t + AWC_clockangle) (eq 1) + AWC_angle(t) = AWC_amp * sin(2*pi*AWC_freq*t + AWC_clockangle) (eq 1) In case of collective pitch AWC, this signal is directly superimposed on the regular pitch control signal. In case of IPC-based AWC, the reference tilt and yaw pitch angles theta are transformed to the rotating frame (i.e., pitch angles theta_k(t) for all individual blades) using the inverse MBC transformation: + / \ / \ | theta_1(t) | | theta_0(t) | - | theta_2(t) | = T^-1(psi(t)) * | theta_tilt(t) | (eq 2) + | theta_2(t) | = T^-1(psi(t)) * | theta_tilt(t) | (eq 2) | theta_3(t) | | theta_yaw(t) | \ / \ / + where - theta_tilt(t) = AWC_amp(1) * sin(2*pi*AWC_freq(1)*t + AWC_clockangle(1)) (eq 3) - theta_yaw(t) = AWC_amp(2) * sin(2*pi*AWC_freq(2)*t + AWC_clockangle(2)) (eq 4) + + theta_tilt(t) = AWC_amp(1) * sin(2*pi*AWC_freq(1)*t + AWC_clockangle(1)) (eq 3) + theta_yaw(t) = AWC_amp(2) * sin(2*pi*AWC_freq(2)*t + AWC_clockangle(2)) (eq 4) + and / \ | 1 cos(psi_1(t)) sin(psi_1(t)) | - T^-1(psi(t)) = | 1 cos(psi_2(t)) sin(psi_2(t)) | (eq 5) + T^-1(psi(t)) = | 1 cos(psi_2(t)) sin(psi_2(t)) | (eq 5) | 1 cos(psi_3(t)) sin(psi_3(t)) | \ / + with psi_k(t) the azimuthal position of blade k at time instant t. Note that if AWC_NumModes = 1, it is assumed that: AWC_amp(2) = AWC_amp(1) AWC_freq(2) = AWC_freq(1) AWC_clockangle(2) = 2*AWC_clockangle(1) + For more information on this control strategy, the user is referred to [2]. ----------------------------------------------- From 90c40416b44bc2fe349545639282899e8dd15551 Mon Sep 17 00:00:00 2001 From: dzalkind Date: Thu, 30 Mar 2023 16:40:14 -0600 Subject: [PATCH 086/224] Add optimized NREL2p8 controller input --- .../NREL_2p8_127/NREL-2p8-127_DISCON.IN | 14 +-- Tune_Cases/NREL2p8.yaml | 116 ++++++++++-------- 2 files changed, 71 insertions(+), 59 deletions(-) diff --git a/Test_Cases/NREL_2p8_127/NREL-2p8-127_DISCON.IN b/Test_Cases/NREL_2p8_127/NREL-2p8-127_DISCON.IN index 1622aa25..60215d61 100644 --- a/Test_Cases/NREL_2p8_127/NREL-2p8-127_DISCON.IN +++ b/Test_Cases/NREL_2p8_127/NREL-2p8-127_DISCON.IN @@ -1,5 +1,5 @@ ! Controller parameter input file for the NREL-2p8-127 wind turbine -! - File written using ROSCO version 2.7.0 controller tuning logic on 03/20/23 +! - File written using ROSCO version 2.7.0 controller tuning logic on 03/30/23 !------- DEBUG ------------------------------------------------------------ 1 ! LoggingLevel - (0: write no debug files, 1: write standard output .dbg-file, 2: LoggingLevel 1 + ROSCO LocalVars (.dbg2) 3: LoggingLevel 2 + complete avrSWAP-array (.dbg3)) @@ -9,7 +9,7 @@ 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 and/or tower fore-aft motion (for floating) {0: disable, 1: generator speed, 2: tower-top fore-aft motion, 3: generator speed and tower-top fore-aft motion} 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 with constant torque, 3: TSR tracking PI control with constant power} +3 ! VS_ControlMode - Generator torque control mode in above rated conditions {0: constant torque, 1: constant power, 2: TSR tracking PI control with constant torque, 3: TSR tracking PI control with constant power} 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} @@ -43,8 +43,8 @@ !------- BLADE PITCH CONTROL ---------------------------------------------- 30 ! PC_GS_n - Amount of gain-scheduling table entries 0.075990 0.104503 0.127446 0.147544 0.164940 0.181678 0.197073 0.211624 0.225753 0.238993 0.252021 0.264458 0.276515 0.288229 0.299596 0.310932 0.321646 0.332112 0.342584 0.353105 0.363012 0.373072 0.382733 0.392195 0.401619 0.411107 0.420504 0.429096 0.437752 0.446357 ! PC_GS_angles - Gain-schedule table: pitch angles [rad]. --0.035909 -0.032382 -0.029436 -0.026938 -0.024792 -0.022930 -0.021299 -0.019858 -0.018575 -0.017426 -0.016392 -0.015455 -0.014603 -0.013824 -0.013110 -0.012453 -0.011846 -0.011283 -0.010761 -0.010274 -0.009820 -0.009395 -0.008996 -0.008621 -0.008269 -0.007936 -0.007622 -0.007325 -0.007043 -0.006775 ! PC_GS_KP - Gain-schedule table: pitch controller kp gains [s]. --0.015528 -0.014136 -0.012973 -0.011987 -0.011140 -0.010405 -0.009760 -0.009191 -0.008685 -0.008232 -0.007823 -0.007453 -0.007117 -0.006810 -0.006528 -0.006268 -0.006028 -0.005806 -0.005600 -0.005408 -0.005229 -0.005061 -0.004904 -0.004756 -0.004616 -0.004485 -0.004361 -0.004244 -0.004132 -0.004027 ! PC_GS_KI - Gain-schedule table: pitch controller ki gains [-]. +-0.024441 -0.021943 -0.019855 -0.018085 -0.016566 -0.015246 -0.014091 -0.013070 -0.012161 -0.011347 -0.010614 -0.009951 -0.009347 -0.008795 -0.008289 -0.007824 -0.007394 -0.006995 -0.006625 -0.006280 -0.005958 -0.005657 -0.005375 -0.005109 -0.004860 -0.004624 -0.004401 -0.004191 -0.003991 -0.003802 ! PC_GS_KP - Gain-schedule table: pitch controller kp gains [s]. +-0.000804 -0.000732 -0.000672 -0.000621 -0.000577 -0.000539 -0.000505 -0.000476 -0.000450 -0.000426 -0.000405 -0.000386 -0.000369 -0.000353 -0.000338 -0.000325 -0.000312 -0.000301 -0.000290 -0.000280 -0.000271 -0.000262 -0.000254 -0.000246 -0.000239 -0.000232 -0.000226 -0.000220 -0.000214 -0.000209 ! PC_GS_KI - Gain-schedule table: pitch controller ki gains [-]. 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 ! PC_GS_KD - Gain-schedule table: pitch controller kd gains 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 ! PC_GS_TF - Gain-schedule table: pitch controller tf gains (derivative filter) 1.570000000000 ! PC_MaxPit - Maximum physical pitch limit, [rad]. @@ -76,7 +76,7 @@ 24248.54567000 ! VS_RtTq - Rated torque, [Nm]. 122.9096700000 ! VS_RefSpd - Rated generator speed [rad/s] 1 ! VS_n - Number of generator PI torque controller gains --591.445280000 ! VS_KP - Proportional gain for generator PI torque controller [-]. (Only used in the transitional 2.5 region if VS_ControlMode =/ 2) +-600.450450000 ! VS_KP - Proportional gain for generator PI torque controller [-]. (Only used in the transitional 2.5 region if VS_ControlMode =/ 2) -85.3230300000 ! VS_KI - Integral gain for generator PI torque controller [s]. (Only used in the transitional 2.5 region if VS_ControlMode =/ 2) 8.25 ! VS_TSRopt - Power-maximizing region 2 tip-speed-ratio [rad]. @@ -96,7 +96,7 @@ 30 30 ! PerfTableSize - Size of rotor performance tables, first number refers to number of blade pitch angles, second number referse to number of tip-speed ratios 60 ! WE_FOPoles_N - Number of first-order system poles used in EKF 3.0000 3.2897 3.5793 3.8690 4.1586 4.4483 4.7379 5.0276 5.3172 5.6069 5.8966 6.1862 6.4759 6.7655 7.0552 7.3448 7.6345 7.9241 8.2138 8.5034 8.7931 9.0828 9.3724 9.6621 9.9517 10.2414 10.5310 10.8207 11.1103 11.4000 11.8533 12.3067 12.7600 13.2133 13.6667 14.1200 14.5733 15.0267 15.4800 15.9333 16.3867 16.8400 17.2933 17.7467 18.2000 18.6533 19.1067 19.5600 20.0133 20.4667 20.9200 21.3733 21.8267 22.2800 22.7333 23.1867 23.6400 24.0933 24.5467 25.0000 ! WE_FOPoles_v - Wind speeds corresponding to first-order system poles [m/s] --0.00983687 -0.01078664 -0.01173641 -0.01268617 -0.01363594 -0.01458571 -0.01553547 -0.01648524 -0.01743501 -0.01838477 -0.01933454 -0.02028431 -0.02123407 -0.02218384 -0.02313361 -0.02408338 -0.02503314 -0.02598291 -0.02693268 -0.02788244 -0.02883221 -0.02978198 -0.03073174 -0.03168151 -0.03117792 -0.02980777 -0.02737033 -0.02372966 -0.01842478 -0.01325506 -0.02209033 -0.02677213 -0.03094759 -0.03700125 -0.04188805 -0.04820630 -0.05390840 -0.06043728 -0.06624359 -0.07295380 -0.07986166 -0.08646363 -0.09412176 -0.10174417 -0.10913837 -0.11728247 -0.12497467 -0.13271621 -0.14189107 -0.15083268 -0.15981675 -0.16948290 -0.17870908 -0.18789884 -0.19750668 -0.20786563 -0.21788705 -0.22660607 -0.23612135 -0.24537696 ! WE_FOPoles - First order system poles [1/s] +-0.01246409 -0.01366752 -0.01487095 -0.01607438 -0.01727781 -0.01848123 -0.01968466 -0.02088809 -0.02209152 -0.02329495 -0.02449838 -0.02570181 -0.02690524 -0.02810867 -0.02931210 -0.03051553 -0.03171896 -0.03292239 -0.03412582 -0.03532924 -0.03653267 -0.03773610 -0.03893953 -0.04014296 -0.03876534 -0.03527029 -0.03014051 -0.02417865 -0.01714772 -0.00815401 0.00419449 -0.00048731 -0.00466276 -0.01071643 -0.01560323 -0.02192148 -0.02762358 -0.03415246 -0.03995877 -0.04666898 -0.05357684 -0.06017881 -0.06783693 -0.07545934 -0.08285355 -0.09099765 -0.09868985 -0.10643139 -0.11560625 -0.12454786 -0.13353192 -0.14319807 -0.15242426 -0.16161402 -0.17122186 -0.18158081 -0.19160223 -0.20032125 -0.20983653 -0.21909214 ! WE_FOPoles - First order system poles [1/s] !------- YAW CONTROL ------------------------------------------------------ 0.00000 ! Y_uSwitch - Wind speed to switch between Y_ErrThresh. If zero, only the second value of Y_ErrThresh is used [m/s] @@ -115,7 +115,7 @@ !------- MINIMUM PITCH SATURATION ------------------------------------------- 60 ! PS_BldPitchMin_N - Number of values in minimum blade pitch lookup table (should equal number of values in PS_WindSpeeds and PS_BldPitchMin) 3.0000 3.2897 3.5793 3.8690 4.1586 4.4483 4.7379 5.0276 5.3172 5.6069 5.8966 6.1862 6.4759 6.7655 7.0552 7.3448 7.6345 7.9241 8.2138 8.5034 8.7931 9.0828 9.3724 9.6621 9.9517 10.2414 10.5310 10.8207 11.1103 11.4000 11.8533 12.3067 12.7600 13.2133 13.6667 14.1200 14.5733 15.0267 15.4800 15.9333 16.3867 16.8400 17.2933 17.7467 18.2000 18.6533 19.1067 19.5600 20.0133 20.4667 20.9200 21.3733 21.8267 22.2800 22.7333 23.1867 23.6400 24.0933 24.5467 25.0000 ! PS_WindSpeeds - Wind speeds corresponding to minimum blade pitch angles [m/s] -0.01815283 0.01815283 0.01815283 0.01815283 0.01815283 0.01815283 0.01815283 0.01815283 0.01815283 0.01815283 0.01815283 0.01815283 0.01815283 0.01815283 0.01815283 0.01815283 0.01815283 0.01815283 0.01815283 0.01815283 0.01815283 0.01815283 0.01815283 0.03053884 0.04218924 0.05108100 0.05966213 0.06767357 0.07535561 0.08307338 0.09451116 0.10543602 0.11614542 0.12637321 0.13629489 0.14608659 0.15527593 0.16453742 0.17355159 0.18260256 0.19157236 0.20062149 0.20959308 0.21828530 0.22728389 0.23591357 0.24440042 0.25300395 0.26169197 0.27041514 0.27864678 0.28689031 0.29519526 0.30342802 0.31179547 0.32018758 0.32842343 0.33656456 0.34455345 0.35267496 ! PS_BldPitchMin - Minimum blade pitch angles [rad] +0.00000000 0.00000000 0.00000000 0.00000000 0.00000000 0.00000000 0.00000000 0.00000000 0.00000000 0.00000000 0.00000000 0.00000000 0.00000000 0.00000000 0.00000000 0.00000000 0.00000000 0.00000000 0.00000000 0.00000000 0.00000000 0.00000000 0.00000000 0.01902632 0.03121162 0.04101621 0.04957537 0.05812141 0.06604528 0.07366393 0.08564088 0.09644430 0.10731742 0.11740081 0.12723365 0.13691718 0.14655371 0.15552079 0.16457871 0.17358206 0.18261499 0.19163393 0.20072294 0.20968649 0.21849678 0.22748802 0.23597095 0.24444734 0.25312967 0.26178025 0.27046099 0.27863869 0.28691931 0.29527580 0.30349928 0.31191439 0.32017189 0.32834804 0.33653924 0.34452172 ! PS_BldPitchMin - Minimum blade pitch angles [rad] !------- SHUTDOWN ----------------------------------------------------------- 0.436300000000 ! SD_MaxPit - Maximum blade pitch angle to initiate shutdown, [rad] diff --git a/Tune_Cases/NREL2p8.yaml b/Tune_Cases/NREL2p8.yaml index 0c3bcd04..be044a18 100644 --- a/Tune_Cases/NREL2p8.yaml +++ b/Tune_Cases/NREL2p8.yaml @@ -1,53 +1,65 @@ ---- # ---------------------NREL Generic controller tuning input file ------------------- - # Written for use with ROSCO_Toolbox tuning procedures - # Turbine: NREL 5MW Reference Wind Turbine -# ------------------------------ OpenFAST PATH DEFINITIONS ------------------------------ -path_params: - FAST_InputFile: 'NREL-2p8-127.fst' # Name of *.fst file - FAST_directory: '../Test_Cases/NREL_2p8_127' # Main OpenFAST model directory, where the *.fst lives - # Optional - rotor_performance_filename: 'NREL-2p8-127_Cp_Ct_Cq.txt' # Filename for rotor performance text file (if it has been generated by ccblade already) - -# -------------------------------- TURBINE PARAMETERS ----------------------------------- -turbine_params: - rotor_inertia: 19858184.000 # Rotor inertia [kg m^2], {Available in Elastodyn .sum file} - rated_rotor_speed: 1.26711 # Rated rotor speed [rad/s] - v_min: 3.0 # Cut-in wind speed [m/s] - v_rated: 11.4 # Rated wind speed [m/s] - v_max: 25.0 # Cut-out wind speed [m/s], -- Does not need to be exact (JUST ASSUME FOR NOW) - max_pitch_rate: 0.1745 # Maximum blade pitch rate [rad/s] - max_torque_rate: 1500000. # Maximum torque rate [Nm/s], {~1/4 VS_RtTq/s} - rated_power: 2800000. # Rated Power [W] - bld_edgewise_freq: 8.2831853 # Blade edgewise first natural frequency [rad/s] - bld_flapwise_freq: 0.0 # Blade flapwise first natural frequency [rad/s] - # Optional - # TSR_operational: # None # Desired below-rated operational tip speed ratio (Cp-maximizing TSR is used if not defined) -#------------------------------- CONTROLLER PARAMETERS ---------------------------------- +path_params: {FAST_InputFile: NREL-2p8-127.fst, FAST_directory: ../Test_Cases/NREL_2p8_127, rotor_performance_filename: NREL-2p8-127_Cp_Ct_Cq.txt} controller_params: - # Controller flags - LoggingLevel: 1 # {0: write no debug files, 1: write standard output .dbg-file, 2: write standard output .dbg-file and complete avrSWAP-array .dbg2-file - F_LPFType: 1 # {1: first-order low-pass filter, 2: second-order low-pass filter}, [rad/s] (currently filters generator speed and pitch control signals) - F_NotchType: 0 # Notch filter on generator speed and/or tower fore-aft motion (for floating) {0: disable, 1: generator speed, 2: tower-top fore-aft motion, 3: generator speed and tower-top fore-aft motion} - IPC_ControlMode: 0 # Turn Individual Pitch Control (IPC) for fatigue load reductions (pitch contribution) {0: off, 1: 1P reductions, 2: 1P+2P reductions} - VS_ControlMode: 2 # Generator torque control mode in above rated conditions {0: constant torque, 1: constant power, 2: TSR tracking PI control} - PC_ControlMode: 1 # Blade pitch control mode {0: No pitch, fix to fine pitch, 1: active PI blade pitch control} - Y_ControlMode: 0 # Yaw control mode {0: no yaw control, 1: yaw rate control, 2: yaw-by-IPC} - SS_Mode: 1 # Setpoint Smoother mode {0: no setpoint smoothing, 1: introduce setpoint smoothing} - WE_Mode: 2 # Wind speed estimator mode {0: One-second low pass filtered hub height wind speed, 1: Immersion and Invariance Estimator (Ortega et al.)} - PS_Mode: 1 # Pitch saturation mode {0: no pitch saturation, 1: peak shaving, 2: Cp-maximizing pitch saturation, 3: peak shaving and Cp-maximizing pitch saturation} - SD_Mode: 0 # Shutdown mode {0: no shutdown procedure, 1: pitch to max pitch at shutdown} - Fl_Mode: 0 # Floating specific feedback mode {0: no nacelle velocity feedback, 1: nacelle velocity feedback} - Flp_Mode: 0 # Flap control mode {0: no flap control, 1: steady state flap angle, 2: Proportional flap control} - # Controller parameters - zeta_pc: 0.7 # Pitch controller desired damping ratio [-] - omega_pc: 0.6 # Pitch controller desired natural frequency [rad/s] - zeta_vs: 0.465 # Torque controller desired damping ratio [-] - omega_vs: 0.11 # Torque controller desired natural frequency [rad/s] - twr_freq: 0.4499 # Tower natural frequency [rad/s] - ptfm_freq: 0.2325 # Platform natural frequency [rad/s] (OC4Hywind Parameters, here) - # Optional - ps_percent: 0.80 # Percent peak shaving [%, <= 1 ], {default = 80%} - sd_maxpit: 0.4363 # Maximum blade pitch angle to initiate shutdown [rad], {default = bld pitch at v_max} - DISCON: - PC_MinPit: -0.17453290000 - PC_FinePit: 0.0 + LoggingLevel: 1 + F_LPFType: 1 + F_NotchType: 0 + IPC_ControlMode: 0 + VS_ControlMode: 3 + PC_ControlMode: 1 + Y_ControlMode: 0 + SS_Mode: 1 + WE_Mode: 2 + PS_Mode: 1 + SD_Mode: 0 + Fl_Mode: 0 + Flp_Mode: 0 + zeta_pc: [2.0062413749856227] + omega_pc: [0.13653659182284006] + zeta_vs: 0.465 + omega_vs: 0.11 + twr_freq: 0.4499 + ptfm_freq: 0.2 + ps_percent: 0.8 + sd_maxpit: 0.4363 + DISCON: {PC_MinPit: -0.1745329, PC_FinePit: 0.0, DLL_FileName: unused, DLL_InFile: unused, DLL_ProcName: DISCON} + TD_Mode: 0 + PwC_Mode: 0 + ZMQ_Mode: 0 + PA_Mode: 0 + Ext_Mode: 0 + U_pc: [12] + interp_type: sigma + max_pitch: 1.57 + min_pitch: 0.0 + vs_minspd: 0.0 + ss_vsgain: 1.0 + ss_pcgain: 0.001 + flp_maxpit: 0.1745 + WS_GS_n: 60 + PC_GS_n: 30 + tune_Fl: true + max_torque_factor: 1.1 + IPC_Kp1p: 0.0 + IPC_Kp2p: 0.0 + IPC_Ki1p: 0.0 + IPC_Ki2p: 0.0 + IPC_Vramp: [0.0, 0.0] + filter_params: {f_we_cornerfreq: 0.20944, f_fl_highpassfreq: 0.01042, f_ss_cornerfreq: 0.6283, f_yawerr: 0.17952, f_sd_cornerfreq: 0.41888} + open_loop: {flag: false, filename: unused, OL_Ind_Breakpoint: 1, OL_Ind_BldPitch: 0, OL_Ind_GenTq: 0, OL_Ind_YawRate: 0} + PA_CornerFreq: 3.14 + PA_Damping: 0.707 + linmodel_tuning: + type: none + linfile_path: none + lintune_outpath: lintune_outfiles + load_parallel: false + stability_margin: 0.1 + omega_pc: {} + flag: true + tuning_yaml: /home/dzalkind/Tools/ROSCO/Tune_Cases/NREL2p8.yaml + n_pitch: 30 + n_tsr: 30 + n_U: 1 + omega_flp: 0.0 + zeta_flp: 0.0 +turbine_params: {rotor_inertia: 19858184.0, rated_rotor_speed: 1.26711, v_min: 3.0, v_rated: 11.4, v_max: 25.0, max_pitch_rate: 0.1745, max_torque_rate: 1500000.0, rated_power: 2800000.0, bld_edgewise_freq: 8.2831853, bld_flapwise_freq: 0.0, TSR_operational: 0} From 5afb385bd86d1309eb64290c2b86553bad611736 Mon Sep 17 00:00:00 2001 From: dzalkind Date: Mon, 3 Apr 2023 15:22:46 -0600 Subject: [PATCH 087/224] Parallelize output processing --- .../ofTools/fast_io/output_processing.py | 115 +++++++++++++++--- 1 file changed, 95 insertions(+), 20 deletions(-) diff --git a/ROSCO_toolbox/ofTools/fast_io/output_processing.py b/ROSCO_toolbox/ofTools/fast_io/output_processing.py index 266a9da2..ef3684b1 100644 --- a/ROSCO_toolbox/ofTools/fast_io/output_processing.py +++ b/ROSCO_toolbox/ofTools/fast_io/output_processing.py @@ -15,6 +15,7 @@ from matplotlib import transforms from itertools import takewhile import struct +import multiprocessing as mp from ROSCO_toolbox.ofTools.util import spectral @@ -39,7 +40,7 @@ def __init__(self, filenames=[], cases=None, tmin=None, tmax=None, verbose=False if len(filenames) > 0: self.load_fast_out(filenames, tmin=tmin, tmax=tmax, verbose=verbose) - def load_fast_out(self, filenames, tmin=None, tmax=None, verbose=False): + def load_fast_out(self, filenames, tmin=None, tmax=None, verbose=False, max_cores=4): """Load a FAST binary or ascii output file Parameters @@ -52,6 +53,8 @@ def load_fast_out(self, filenames, tmin=None, tmax=None, verbose=False): final data to trim output data to verbose : bool, optional Print updates + max_cores: int, optional + Maximum number of cores to use for loading outputs in parallel Returns ------- @@ -60,30 +63,30 @@ def load_fast_out(self, filenames, tmin=None, tmax=None, verbose=False): """ if type(filenames) is str: filenames = [filenames] + + cores = min(len(filenames), max_cores) - # data = [] - # info = [] try: self.fastout except AttributeError: self.fastout = [] - for i, filename in enumerate(filenames): - assert os.path.isfile(filename), "File, %s, does not exists" % filename - with open(filename, 'r') as f: - if verbose: - print('Loading data from {}'.format(filename)) - try: - f.readline() - except UnicodeDecodeError: - data, info = load_binary_output(filename) - else: - data, info = load_ascii_output(filename) - - # Build dictionary - fast_data = dict(zip(info['channels'],data.T)) - fast_data['meta'] = info - fast_data['meta']['filename'] = filename - self.fastout.append(fast_data) + + inputs = [] + for filename in filenames: + inp = {} + inp['filename'] = filename + inp['verbose'] = verbose + inputs.append(inp) + + if cores > 1: + pool = mp.Pool(cores) + self.fastout = pool.map(self._load_fast_data, inputs) + pool.close() + pool.join() + else: + for inp in inputs: + fast_data = self._load_fast_data(inp) + self.fastout.append(fast_data) # Trim outputs if (tmin) or (tmax): @@ -91,6 +94,28 @@ def load_fast_out(self, filenames, tmin=None, tmax=None, verbose=False): # return fastout return self.fastout + + def _load_fast_data(self,input): + # Unpack + filename = input['filename'] + verbose = input['verbose'] + + assert os.path.isfile(filename), "File, %s, does not exists" % filename + with open(filename, 'r') as f: + if verbose: + print('Loading data from {}'.format(filename)) + try: + f.readline() + except UnicodeDecodeError: + data, info = load_binary_output(filename) + else: + data, info = load_ascii_output(filename) + + # Build dictionary + fast_data = dict(zip(info['channels'],data.T)) + fast_data['meta'] = info + fast_data['meta']['filename'] = filename + return fast_data def plot_fast_out(self, fastout=None, cases=None, showplot=True, fignum=None, xlim=None): ''' @@ -581,3 +606,53 @@ def trim_output(fast_data, tmin=None, tmax=None, verbose=False): return fast_data + + +if __name__ == "__main__": + outfiles = [ + '/Users/dzalkind/Tools/ROSCO3/outputs/IPC_tune_1/NREL2p8/turb_bts/sweep_ipc_gains/NREL2p8_0.out', + '/Users/dzalkind/Tools/ROSCO3/outputs/IPC_tune_1/NREL2p8/turb_bts/sweep_ipc_gains/NREL2p8_1.out', + '/Users/dzalkind/Tools/ROSCO3/outputs/IPC_tune_1/NREL2p8/turb_bts/sweep_ipc_gains/NREL2p8_2.out', + '/Users/dzalkind/Tools/ROSCO3/outputs/IPC_tune_1/NREL2p8/turb_bts/sweep_ipc_gains/NREL2p8_3.out' + ] + + plt.rcParams["figure.figsize"] = [9,12] + + ROSCO = False + ROSCO2 = False + + # Define Plot cases + cases = {} + cases['Gen. Speed Sigs.'] = ['Wind1VelX','BldPitch1', 'GenTq', 'GenSpeed','TwrBsMyt','GenPwr','RootMyb1']#,'PtfmPitch','PtfmYaw','NacYaw'] + + op = output_processing() + op_RO = output_processing() + op_RO2 = output_processing() + + fast_out = [] + fast_out = op.load_fast_out(outfiles, tmin=0) + if ROSCO: + # Rosco outfiles + r_outfiles = [out.split('.out')[0] + '.RO.dbg' for out in outfiles] + rosco_out = op_RO.load_fast_out(r_outfiles, tmin=0) + + if ROSCO2: + r_outfiles = [out.split('.out')[0] + '.RO.dbg2' for out in outfiles] + rosco_out2 = op_RO2.load_fast_out(r_outfiles, tmin=0) + + # Combine outputs + if ROSCO: + comb_out = [None] * len(fast_out) + for i, (r_out, f_out) in enumerate(zip(rosco_out,fast_out)): + r_out.update(f_out) + comb_out[i] = r_out + if ROSCO2: + for i, (r_out2, f_out) in enumerate(zip(rosco_out2,comb_out)): + r_out2.update(f_out) + comb_out[i] = r_out2 + else: + comb_out = fast_out + + + # Plot + fig, ax = op.plot_fast_out(comb_out,cases, showplot=True) From fbb44c4b2cc598ad4da3edf1bd034adf05e172a3 Mon Sep 17 00:00:00 2001 From: dzalkind Date: Mon, 3 Apr 2023 15:23:00 -0600 Subject: [PATCH 088/224] Add IPC gain to NREL2p8 --- Tune_Cases/NREL2p8.yaml | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/Tune_Cases/NREL2p8.yaml b/Tune_Cases/NREL2p8.yaml index be044a18..7f71935e 100644 --- a/Tune_Cases/NREL2p8.yaml +++ b/Tune_Cases/NREL2p8.yaml @@ -3,7 +3,7 @@ controller_params: LoggingLevel: 1 F_LPFType: 1 F_NotchType: 0 - IPC_ControlMode: 0 + IPC_ControlMode: 1 VS_ControlMode: 3 PC_ControlMode: 1 Y_ControlMode: 0 @@ -41,7 +41,7 @@ controller_params: max_torque_factor: 1.1 IPC_Kp1p: 0.0 IPC_Kp2p: 0.0 - IPC_Ki1p: 0.0 + IPC_Ki1p: 5.2e-9 IPC_Ki2p: 0.0 IPC_Vramp: [0.0, 0.0] filter_params: {f_we_cornerfreq: 0.20944, f_fl_highpassfreq: 0.01042, f_ss_cornerfreq: 0.6283, f_yawerr: 0.17952, f_sd_cornerfreq: 0.41888} From 52e37086749347c847c0c29170a052662dc4c7cb Mon Sep 17 00:00:00 2001 From: dzalkind Date: Mon, 3 Apr 2023 15:58:54 -0600 Subject: [PATCH 089/224] Finish merge with inputs and registry --- ROSCO/src/ROSCO_IO.f90 | 183 +++++++++--------- ROSCO/src/ReadSetParameters.f90 | 8 +- Test_Cases/BAR_10/BAR_10_DISCON.IN | 20 +- .../DISCON-UMaineSemi.IN | 20 +- Test_Cases/NREL-5MW/DISCON.IN | 20 +- 5 files changed, 137 insertions(+), 114 deletions(-) diff --git a/ROSCO/src/ROSCO_IO.f90 b/ROSCO/src/ROSCO_IO.f90 index d3b0ee66..7942c3b0 100644 --- a/ROSCO/src/ROSCO_IO.f90 +++ b/ROSCO/src/ROSCO_IO.f90 @@ -64,6 +64,8 @@ SUBROUTINE WriteRestartFile(LocalVar, CntrPar, ErrVar, objInst, RootName, size_a WRITE( Un, IOSTAT=ErrStat) LocalVar%FA_PitCom(2) WRITE( Un, IOSTAT=ErrStat) LocalVar%FA_PitCom(3) WRITE( Un, IOSTAT=ErrStat) LocalVar%RotSpeedF + WRITE( Un, IOSTAT=ErrStat) LocalVar%VS_RefSpd + WRITE( Un, IOSTAT=ErrStat) LocalVar%PC_RefSpd WRITE( Un, IOSTAT=ErrStat) LocalVar%GenSpeedF WRITE( Un, IOSTAT=ErrStat) LocalVar%GenTq WRITE( Un, IOSTAT=ErrStat) LocalVar%GenTqMeas @@ -324,6 +326,8 @@ SUBROUTINE ReadRestartFile(avrSWAP, LocalVar, CntrPar, objInst, PerfData, RootNa READ( Un, IOSTAT=ErrStat) LocalVar%FA_PitCom(2) READ( Un, IOSTAT=ErrStat) LocalVar%FA_PitCom(3) READ( Un, IOSTAT=ErrStat) LocalVar%RotSpeedF + READ( Un, IOSTAT=ErrStat) LocalVar%VS_RefSpd + READ( Un, IOSTAT=ErrStat) LocalVar%PC_RefSpd READ( Un, IOSTAT=ErrStat) LocalVar%GenSpeedF READ( Un, IOSTAT=ErrStat) LocalVar%GenTq READ( Un, IOSTAT=ErrStat) LocalVar%GenTqMeas @@ -603,7 +607,7 @@ SUBROUTINE Debug(LocalVar, CntrPar, DebugVar, ErrVar, avrSWAP, RootName, size_av '[rad/s]', '[rad/s]', '[m/s]', '[rad]', '[rad]', & '[N/A]', '[N/A]', '[N/A]', '[N/A]', '[rad/s]', & '[deg]', '[deg]', '[deg]', '[N/A]'] - nLocalVars = 93 + nLocalVars = 95 Allocate(LocalVarOutData(nLocalVars)) Allocate(LocalVarOutStrings(nLocalVars)) LocalVarOutData(1) = LocalVar%iStatus @@ -627,97 +631,100 @@ SUBROUTINE Debug(LocalVar, CntrPar, DebugVar, ErrVar, avrSWAP, RootName, size_av LocalVarOutData(19) = LocalVar%FA_AccHPFI LocalVarOutData(20) = LocalVar%FA_PitCom(1) LocalVarOutData(21) = LocalVar%RotSpeedF - LocalVarOutData(22) = LocalVar%GenSpeedF - LocalVarOutData(23) = LocalVar%GenTq - LocalVarOutData(24) = LocalVar%GenTqMeas - LocalVarOutData(25) = LocalVar%GenArTq - LocalVarOutData(26) = LocalVar%GenBrTq - LocalVarOutData(27) = LocalVar%IPC_PitComF(1) - LocalVarOutData(28) = LocalVar%PC_KP - LocalVarOutData(29) = LocalVar%PC_KI - LocalVarOutData(30) = LocalVar%PC_KD - LocalVarOutData(31) = LocalVar%PC_TF - LocalVarOutData(32) = LocalVar%PC_MaxPit - LocalVarOutData(33) = LocalVar%PC_MinPit - LocalVarOutData(34) = LocalVar%PC_PitComT - LocalVarOutData(35) = LocalVar%PC_PitComT_Last - LocalVarOutData(36) = LocalVar%PC_PitComTF - LocalVarOutData(37) = LocalVar%PC_PitComT_IPC(1) - LocalVarOutData(38) = LocalVar%PC_PwrErr - LocalVarOutData(39) = LocalVar%PC_SpdErr - LocalVarOutData(40) = LocalVar%IPC_AxisTilt_1P - LocalVarOutData(41) = LocalVar%IPC_AxisYaw_1P - LocalVarOutData(42) = LocalVar%IPC_AxisTilt_2P - LocalVarOutData(43) = LocalVar%IPC_AxisYaw_2P - LocalVarOutData(44) = LocalVar%IPC_KI(1) - LocalVarOutData(45) = LocalVar%IPC_KP(1) - LocalVarOutData(46) = LocalVar%IPC_IntSat - LocalVarOutData(47) = LocalVar%PC_State - LocalVarOutData(48) = LocalVar%PitCom(1) - LocalVarOutData(49) = LocalVar%PitComAct(1) - LocalVarOutData(50) = LocalVar%SS_DelOmegaF - LocalVarOutData(51) = LocalVar%TestType - LocalVarOutData(52) = LocalVar%VS_MaxTq - LocalVarOutData(53) = LocalVar%VS_LastGenTrq - LocalVarOutData(54) = LocalVar%VS_LastGenPwr - LocalVarOutData(55) = LocalVar%VS_MechGenPwr - LocalVarOutData(56) = LocalVar%VS_SpdErrAr - LocalVarOutData(57) = LocalVar%VS_SpdErrBr - LocalVarOutData(58) = LocalVar%VS_SpdErr - LocalVarOutData(59) = LocalVar%VS_State - LocalVarOutData(60) = LocalVar%VS_Rgn3Pitch - LocalVarOutData(61) = LocalVar%WE_Vw - LocalVarOutData(62) = LocalVar%WE_Vw_F - LocalVarOutData(63) = LocalVar%WE_VwI - LocalVarOutData(64) = LocalVar%WE_VwIdot - LocalVarOutData(65) = LocalVar%VS_LastGenTrqF - LocalVarOutData(66) = LocalVar%Fl_PitCom - LocalVarOutData(67) = LocalVar%NACIMU_FA_AccF - LocalVarOutData(68) = LocalVar%FA_AccF - LocalVarOutData(69) = LocalVar%PtfmTDX - LocalVarOutData(70) = LocalVar%PtfmTDY - LocalVarOutData(71) = LocalVar%PtfmTDZ - LocalVarOutData(72) = LocalVar%PtfmRDX - LocalVarOutData(73) = LocalVar%PtfmRDY - LocalVarOutData(74) = LocalVar%PtfmRDZ - LocalVarOutData(75) = LocalVar%PtfmTVX - LocalVarOutData(76) = LocalVar%PtfmTVY - LocalVarOutData(77) = LocalVar%PtfmTVZ - LocalVarOutData(78) = LocalVar%PtfmRVX - LocalVarOutData(79) = LocalVar%PtfmRVY - LocalVarOutData(80) = LocalVar%PtfmRVZ - LocalVarOutData(81) = LocalVar%PtfmTAX - LocalVarOutData(82) = LocalVar%PtfmTAY - LocalVarOutData(83) = LocalVar%PtfmTAZ - LocalVarOutData(84) = LocalVar%PtfmRAX - LocalVarOutData(85) = LocalVar%PtfmRAY - LocalVarOutData(86) = LocalVar%PtfmRAZ - LocalVarOutData(87) = LocalVar%CC_DesiredL(1) - LocalVarOutData(88) = LocalVar%CC_ActuatedL(1) - LocalVarOutData(89) = LocalVar%CC_ActuatedDL(1) - LocalVarOutData(90) = LocalVar%StC_Input(1) - LocalVarOutData(91) = LocalVar%Flp_Angle(1) - LocalVarOutData(92) = LocalVar%RootMyb_Last(1) - LocalVarOutData(93) = LocalVar%ACC_INFILE_SIZE + LocalVarOutData(22) = LocalVar%VS_RefSpd + LocalVarOutData(23) = LocalVar%PC_RefSpd + LocalVarOutData(24) = LocalVar%GenSpeedF + LocalVarOutData(25) = LocalVar%GenTq + LocalVarOutData(26) = LocalVar%GenTqMeas + LocalVarOutData(27) = LocalVar%GenArTq + LocalVarOutData(28) = LocalVar%GenBrTq + LocalVarOutData(29) = LocalVar%IPC_PitComF(1) + LocalVarOutData(30) = LocalVar%PC_KP + LocalVarOutData(31) = LocalVar%PC_KI + LocalVarOutData(32) = LocalVar%PC_KD + LocalVarOutData(33) = LocalVar%PC_TF + LocalVarOutData(34) = LocalVar%PC_MaxPit + LocalVarOutData(35) = LocalVar%PC_MinPit + LocalVarOutData(36) = LocalVar%PC_PitComT + LocalVarOutData(37) = LocalVar%PC_PitComT_Last + LocalVarOutData(38) = LocalVar%PC_PitComTF + LocalVarOutData(39) = LocalVar%PC_PitComT_IPC(1) + LocalVarOutData(40) = LocalVar%PC_PwrErr + LocalVarOutData(41) = LocalVar%PC_SpdErr + LocalVarOutData(42) = LocalVar%IPC_AxisTilt_1P + LocalVarOutData(43) = LocalVar%IPC_AxisYaw_1P + LocalVarOutData(44) = LocalVar%IPC_AxisTilt_2P + LocalVarOutData(45) = LocalVar%IPC_AxisYaw_2P + LocalVarOutData(46) = LocalVar%IPC_KI(1) + LocalVarOutData(47) = LocalVar%IPC_KP(1) + LocalVarOutData(48) = LocalVar%IPC_IntSat + LocalVarOutData(49) = LocalVar%PC_State + LocalVarOutData(50) = LocalVar%PitCom(1) + LocalVarOutData(51) = LocalVar%PitComAct(1) + LocalVarOutData(52) = LocalVar%SS_DelOmegaF + LocalVarOutData(53) = LocalVar%TestType + LocalVarOutData(54) = LocalVar%VS_MaxTq + LocalVarOutData(55) = LocalVar%VS_LastGenTrq + LocalVarOutData(56) = LocalVar%VS_LastGenPwr + LocalVarOutData(57) = LocalVar%VS_MechGenPwr + LocalVarOutData(58) = LocalVar%VS_SpdErrAr + LocalVarOutData(59) = LocalVar%VS_SpdErrBr + LocalVarOutData(60) = LocalVar%VS_SpdErr + LocalVarOutData(61) = LocalVar%VS_State + LocalVarOutData(62) = LocalVar%VS_Rgn3Pitch + LocalVarOutData(63) = LocalVar%WE_Vw + LocalVarOutData(64) = LocalVar%WE_Vw_F + LocalVarOutData(65) = LocalVar%WE_VwI + LocalVarOutData(66) = LocalVar%WE_VwIdot + LocalVarOutData(67) = LocalVar%VS_LastGenTrqF + LocalVarOutData(68) = LocalVar%Fl_PitCom + LocalVarOutData(69) = LocalVar%NACIMU_FA_AccF + LocalVarOutData(70) = LocalVar%FA_AccF + LocalVarOutData(71) = LocalVar%PtfmTDX + LocalVarOutData(72) = LocalVar%PtfmTDY + LocalVarOutData(73) = LocalVar%PtfmTDZ + LocalVarOutData(74) = LocalVar%PtfmRDX + LocalVarOutData(75) = LocalVar%PtfmRDY + LocalVarOutData(76) = LocalVar%PtfmRDZ + LocalVarOutData(77) = LocalVar%PtfmTVX + LocalVarOutData(78) = LocalVar%PtfmTVY + LocalVarOutData(79) = LocalVar%PtfmTVZ + LocalVarOutData(80) = LocalVar%PtfmRVX + LocalVarOutData(81) = LocalVar%PtfmRVY + LocalVarOutData(82) = LocalVar%PtfmRVZ + LocalVarOutData(83) = LocalVar%PtfmTAX + LocalVarOutData(84) = LocalVar%PtfmTAY + LocalVarOutData(85) = LocalVar%PtfmTAZ + LocalVarOutData(86) = LocalVar%PtfmRAX + LocalVarOutData(87) = LocalVar%PtfmRAY + LocalVarOutData(88) = LocalVar%PtfmRAZ + LocalVarOutData(89) = LocalVar%CC_DesiredL(1) + LocalVarOutData(90) = LocalVar%CC_ActuatedL(1) + LocalVarOutData(91) = LocalVar%CC_ActuatedDL(1) + LocalVarOutData(92) = LocalVar%StC_Input(1) + LocalVarOutData(93) = LocalVar%Flp_Angle(1) + LocalVarOutData(94) = LocalVar%RootMyb_Last(1) + LocalVarOutData(95) = LocalVar%ACC_INFILE_SIZE LocalVarOutStrings = [CHARACTER(15) :: 'iStatus', 'Time', 'DT', 'VS_GenPwr', 'GenSpeed', & 'RotSpeed', 'NacHeading', 'NacVane', 'HorWindV', 'rootMOOP', & 'rootMOOPF', 'BlPitch', 'BlPitchCMeas', 'Azimuth', 'NumBl', & 'FA_Acc', 'NacIMU_FA_Acc', 'FA_AccHPF', 'FA_AccHPFI', 'FA_PitCom', & - 'RotSpeedF', 'GenSpeedF', 'GenTq', 'GenTqMeas', 'GenArTq', & - 'GenBrTq', 'IPC_PitComF', 'PC_KP', 'PC_KI', 'PC_KD', & - 'PC_TF', 'PC_MaxPit', 'PC_MinPit', 'PC_PitComT', 'PC_PitComT_Last', & - 'PC_PitComTF', 'PC_PitComT_IPC', 'PC_PwrErr', 'PC_SpdErr', 'IPC_AxisTilt_1P', & - 'IPC_AxisYaw_1P', 'IPC_AxisTilt_2P', 'IPC_AxisYaw_2P', 'IPC_KI', 'IPC_KP', & - 'IPC_IntSat', 'PC_State', 'PitCom', 'PitComAct', 'SS_DelOmegaF', & - 'TestType', 'VS_MaxTq', 'VS_LastGenTrq', 'VS_LastGenPwr', 'VS_MechGenPwr', & - 'VS_SpdErrAr', 'VS_SpdErrBr', 'VS_SpdErr', 'VS_State', 'VS_Rgn3Pitch', & - 'WE_Vw', 'WE_Vw_F', 'WE_VwI', 'WE_VwIdot', 'VS_LastGenTrqF', & - 'Fl_PitCom', 'NACIMU_FA_AccF', 'FA_AccF', 'PtfmTDX', 'PtfmTDY', & - 'PtfmTDZ', 'PtfmRDX', 'PtfmRDY', 'PtfmRDZ', 'PtfmTVX', & - 'PtfmTVY', 'PtfmTVZ', 'PtfmRVX', 'PtfmRVY', 'PtfmRVZ', & - 'PtfmTAX', 'PtfmTAY', 'PtfmTAZ', 'PtfmRAX', 'PtfmRAY', & - 'PtfmRAZ', 'CC_DesiredL', 'CC_ActuatedL', 'CC_ActuatedDL', 'StC_Input', & - 'Flp_Angle', 'RootMyb_Last', 'ACC_INFILE_SIZE'] + 'RotSpeedF', 'VS_RefSpd', 'PC_RefSpd', 'GenSpeedF', 'GenTq', & + 'GenTqMeas', 'GenArTq', 'GenBrTq', 'IPC_PitComF', 'PC_KP', & + 'PC_KI', 'PC_KD', 'PC_TF', 'PC_MaxPit', 'PC_MinPit', & + 'PC_PitComT', 'PC_PitComT_Last', 'PC_PitComTF', 'PC_PitComT_IPC', 'PC_PwrErr', & + 'PC_SpdErr', 'IPC_AxisTilt_1P', 'IPC_AxisYaw_1P', 'IPC_AxisTilt_2P', 'IPC_AxisYaw_2P', & + 'IPC_KI', 'IPC_KP', 'IPC_IntSat', 'PC_State', 'PitCom', & + 'PitComAct', 'SS_DelOmegaF', 'TestType', 'VS_MaxTq', 'VS_LastGenTrq', & + 'VS_LastGenPwr', 'VS_MechGenPwr', 'VS_SpdErrAr', 'VS_SpdErrBr', 'VS_SpdErr', & + 'VS_State', 'VS_Rgn3Pitch', 'WE_Vw', 'WE_Vw_F', 'WE_VwI', & + 'WE_VwIdot', 'VS_LastGenTrqF', 'Fl_PitCom', 'NACIMU_FA_AccF', 'FA_AccF', & + 'PtfmTDX', 'PtfmTDY', 'PtfmTDZ', 'PtfmRDX', 'PtfmRDY', & + 'PtfmRDZ', 'PtfmTVX', 'PtfmTVY', 'PtfmTVZ', 'PtfmRVX', & + 'PtfmRVY', 'PtfmRVZ', 'PtfmTAX', 'PtfmTAY', 'PtfmTAZ', & + 'PtfmRAX', 'PtfmRAY', 'PtfmRAZ', 'CC_DesiredL', 'CC_ActuatedL', & + 'CC_ActuatedDL', 'StC_Input', 'Flp_Angle', 'RootMyb_Last', 'ACC_INFILE_SIZE' & + ] ! Initialize debug file IF ((LocalVar%iStatus == 0) .OR. (LocalVar%iStatus == -9)) THEN ! .TRUE. if we're on the first call to the DLL IF (CntrPar%LoggingLevel > 0) THEN diff --git a/ROSCO/src/ReadSetParameters.f90 b/ROSCO/src/ReadSetParameters.f90 index 701d8590..4f1a8548 100644 --- a/ROSCO/src/ReadSetParameters.f90 +++ b/ROSCO/src/ReadSetParameters.f90 @@ -433,11 +433,9 @@ SUBROUTINE ReadControlParameterFileSub(CntrPar, zmqVar, accINFILE, accINFILE_siz IF (ErrVar%aviFAIL < 0) RETURN !------------ POWER REFERENCE TRACKING SETPOINTS -------------- - CALL ReadEmptyLine(UnControllerParameters,CurLine) - CALL ParseInput(UnControllerParameters,CurLine,'PRC_n',accINFILE(1),CntrPar%PRC_n,ErrVar) - CALL ParseAry(UnControllerParameters, CurLine, 'PRC_WindSpeeds', CntrPar%PRC_WindSpeeds, CntrPar%PRC_n, accINFILE(1), ErrVar ) - CALL ParseAry(UnControllerParameters, CurLine, 'PRC_RotorSpeeds', CntrPar%PRC_RotorSpeeds, CntrPar%PRC_n, accINFILE(1), ErrVar ) - CALL ReadEmptyLine(UnControllerParameters,CurLine) + CALL ParseInput(FileLines, 'PRC_n', CntrPar%PRC_n, accINFILE(1), ErrVar, CntrPar%PRC_Mode == 0) + CALL ParseAry( FileLines, 'PRC_WindSpeeds', CntrPar%PRC_WindSpeeds, CntrPar%PRC_n, accINFILE(1), ErrVar, CntrPar%PRC_Mode == 0) + CALL ParseAry( FileLines, 'PRC_RotorSpeeds', CntrPar%PRC_RotorSpeeds, CntrPar%PRC_n, accINFILE(1), ErrVar, CntrPar%PRC_Mode == 0) !------------ WIND SPEED ESTIMATOR CONTANTS -------------- CALL ParseInput(FileLines, 'WE_BladeRadius', CntrPar%WE_BladeRadius, accINFILE(1), ErrVar, .FALSE., UnEc) diff --git a/Test_Cases/BAR_10/BAR_10_DISCON.IN b/Test_Cases/BAR_10/BAR_10_DISCON.IN index d915a5c0..c4e7f81f 100644 --- a/Test_Cases/BAR_10/BAR_10_DISCON.IN +++ b/Test_Cases/BAR_10/BAR_10_DISCON.IN @@ -1,5 +1,5 @@ ! Controller parameter input file for the BAR_10 wind turbine -! - File written using ROSCO version 2.7.0 controller tuning logic on 02/28/23 +! - File written using ROSCO version 2.7.0 controller tuning logic on 04/03/23 !------- DEBUG ------------------------------------------------------------ 1 ! LoggingLevel - (0: write no debug files, 1: write standard output .dbg-file, 2: LoggingLevel 1 + ROSCO LocalVars (.dbg2) 3: LoggingLevel 2 + complete avrSWAP-array (.dbg3)) @@ -13,6 +13,7 @@ 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} +0 ! PRC_Mode - Power reference tracking mode{0: use standard rotor speed set points, 1: use PRC rotor speed setpoints} 2 ! WE_Mode - Wind speed estimator mode {0: One-second low pass filtered hub height wind speed, 1: Immersion and Invariance Estimator, 2: Extended Kalman Filter} 1 ! PS_Mode - Pitch saturation mode {0: no pitch saturation, 1: implement pitch saturation} 0 ! SD_Mode - Shutdown mode {0: no shutdown procedure, 1: pitch to max pitch at shutdown} @@ -83,6 +84,11 @@ 1.00000 ! SS_VSGain - Variable speed torque controller setpoint smoother gain, [-]. 0.00100 ! SS_PCGain - Collective pitch controller setpoint smoother gain, [-]. +!------- POWER REFERENCE TRACKING -------------------------------------- +2 ! PRC_n - Number of elements in PRC_WindSpeeds and PRC_RotorSpeeds array +3.000 25.000 ! PRC_WindSpeeds - Array of wind speeds used in rotor speed vs. wind speed lookup table [m/s]. +0.792 0.792 ! PRC_RotorSpeeds - Array of rotor speeds corresponding to PRC_WindSpeeds [rad/s]. + !------- WIND SPEED ESTIMATOR --------------------------------------------- 102.996 ! WE_BladeRadius - Blade length (distance from hub center to blade tip), [m] 1 ! WE_CP_n - Amount of parameters in the Cp array @@ -113,8 +119,8 @@ !------- MINIMUM PITCH SATURATION ------------------------------------------- 60 ! PS_BldPitchMin_N - Number of values in minimum blade pitch lookup table (should equal number of values in PS_WindSpeeds and PS_BldPitchMin) -3.0000 3.1818 3.3637 3.5455 3.7274 3.9092 4.0911 4.2729 4.4548 4.6366 4.8185 5.0003 5.1822 5.3640 5.5459 5.7277 5.9096 6.0914 6.2732 6.4551 6.6369 6.8188 7.0006 7.1825 7.3643 7.5462 7.7280 7.9099 8.0917 8.2736 8.8311 9.3887 9.9462 10.5038 11.0613 11.6188 12.1764 12.7339 13.2915 13.8490 14.4066 14.9641 15.5217 16.0792 16.6368 17.1943 17.7519 18.3094 18.8670 19.4245 19.9821 20.5396 21.0972 21.6547 22.2123 22.7698 23.3274 23.8849 24.4425 25.0000 ! PS_WindSpeeds - Wind speeds corresponding to minimum blade pitch angles [m/s] --0.01505486 -0.01505486 -0.01505486 -0.01505486 -0.01505486 -0.01505486 -0.01505486 -0.01505486 -0.01505486 -0.01505486 -0.01505486 -0.01505486 -0.01505486 -0.01505486 -0.01505486 -0.01505486 -0.01505486 -0.01505486 -0.01505486 -0.01505486 -0.01505486 -0.01505486 -0.01505486 -0.01505486 -0.01247538 0.00009416 0.01064594 0.02025612 0.02875892 0.04130468 0.05575026 0.06941162 0.08245994 0.09516301 0.10759186 0.11974680 0.13166674 0.14343508 0.15503135 0.16644975 0.17776272 0.18893241 0.19997037 0.21092550 0.22173526 0.23245676 0.24309225 0.25359679 0.26404201 0.27436979 0.28461736 0.29478565 0.30484212 0.31485020 0.32473305 0.33456481 0.34429551 0.35395031 0.36352600 0.37300643 ! PS_BldPitchMin - Minimum blade pitch angles [rad] +3.000 3.182 3.364 3.546 3.727 3.909 4.091 4.273 4.455 4.637 4.818 5.000 5.182 5.364 5.546 5.728 5.910 6.091 6.273 6.455 6.637 6.819 7.001 7.182 7.364 7.546 7.728 7.910 8.092 8.274 8.831 9.389 9.946 10.504 11.061 11.619 12.176 12.734 13.291 13.849 14.407 14.964 15.522 16.079 16.637 17.194 17.752 18.309 18.867 19.425 19.982 20.540 21.097 21.655 22.212 22.770 23.327 23.885 24.442 25.000 ! PS_WindSpeeds - Wind speeds corresponding to minimum blade pitch angles [m/s] +-0.015 -0.015 -0.015 -0.015 -0.015 -0.015 -0.015 -0.015 -0.015 -0.015 -0.015 -0.015 -0.015 -0.015 -0.015 -0.015 -0.015 -0.015 -0.015 -0.015 -0.015 -0.015 -0.015 -0.015 -0.012 0.000 0.011 0.020 0.029 0.041 0.056 0.069 0.082 0.095 0.108 0.120 0.132 0.143 0.155 0.166 0.178 0.189 0.200 0.211 0.222 0.232 0.243 0.254 0.264 0.274 0.285 0.295 0.305 0.315 0.325 0.335 0.344 0.354 0.364 0.373 ! PS_BldPitchMin - Minimum blade pitch angles [rad] !------- SHUTDOWN ----------------------------------------------------------- 0.698100000000 ! SD_MaxPit - Maximum blade pitch angle to initiate shutdown, [rad] @@ -153,10 +159,10 @@ 2 ! ZMQ_UpdatePeriod - Call ZeroMQ every [x] seconds, [s] !------- Cable Control --------------------------------------------------------- -1 ! CC_Group_N - Number of cable control groups +1 ! CC_Group_N - Number of cable control groups 0 ! CC_GroupIndex - First index for cable control group, should correspond to deltaL -20.000000 ! CC_ActTau - Time constant for line actuator [s] +20.000000 ! CC_ActTau - Time constant for line actuator [s] !------- Structural Controllers --------------------------------------------------------- -1 ! StC_Group_N - Number of cable control groups - 0 ! StC_GroupIndex - First index for structural control group, options specified in ServoDyn summary output +1 ! StC_Group_N - Number of cable control groups + 0 ! StC_GroupIndex - First index for structural control group, options specified in ServoDyn summary output diff --git a/Test_Cases/IEA-15-240-RWT-UMaineSemi/DISCON-UMaineSemi.IN b/Test_Cases/IEA-15-240-RWT-UMaineSemi/DISCON-UMaineSemi.IN index 30f764c6..6f0bb86b 100644 --- a/Test_Cases/IEA-15-240-RWT-UMaineSemi/DISCON-UMaineSemi.IN +++ b/Test_Cases/IEA-15-240-RWT-UMaineSemi/DISCON-UMaineSemi.IN @@ -1,5 +1,5 @@ ! Controller parameter input file for the IEA-15-240-RWT-UMaineSemi wind turbine -! - File written using ROSCO version 2.7.0 controller tuning logic on 02/28/23 +! - File written using ROSCO version 2.7.0 controller tuning logic on 04/03/23 !------- DEBUG ------------------------------------------------------------ 2 ! LoggingLevel - (0: write no debug files, 1: write standard output .dbg-file, 2: LoggingLevel 1 + ROSCO LocalVars (.dbg2) 3: LoggingLevel 2 + complete avrSWAP-array (.dbg3)) @@ -13,6 +13,7 @@ 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} +0 ! PRC_Mode - Power reference tracking mode{0: use standard rotor speed set points, 1: use PRC rotor speed setpoints} 2 ! WE_Mode - Wind speed estimator mode {0: One-second low pass filtered hub height wind speed, 1: Immersion and Invariance Estimator, 2: Extended Kalman Filter} 1 ! PS_Mode - Pitch saturation mode {0: no pitch saturation, 1: implement pitch saturation} 0 ! SD_Mode - Shutdown mode {0: no shutdown procedure, 1: pitch to max pitch at shutdown} @@ -83,6 +84,11 @@ 1.00000 ! SS_VSGain - Variable speed torque controller setpoint smoother gain, [-]. 0.00100 ! SS_PCGain - Collective pitch controller setpoint smoother gain, [-]. +!------- POWER REFERENCE TRACKING -------------------------------------- +2 ! PRC_n - Number of elements in PRC_WindSpeeds and PRC_RotorSpeeds array +3.000 25.000 ! PRC_WindSpeeds - Array of wind speeds used in rotor speed vs. wind speed lookup table [m/s]. +0.792 0.792 ! PRC_RotorSpeeds - Array of rotor speeds corresponding to PRC_WindSpeeds [rad/s]. + !------- WIND SPEED ESTIMATOR --------------------------------------------- 120.000 ! WE_BladeRadius - Blade length (distance from hub center to blade tip), [m] 1 ! WE_CP_n - Amount of parameters in the Cp array @@ -113,8 +119,8 @@ !------- MINIMUM PITCH SATURATION ------------------------------------------- 60 ! PS_BldPitchMin_N - Number of values in minimum blade pitch lookup table (should equal number of values in PS_WindSpeeds and PS_BldPitchMin) -3.0000 3.2669 3.5338 3.8007 4.0676 4.3345 4.6014 4.8683 5.1352 5.4021 5.6690 5.9359 6.2028 6.4697 6.7366 7.0034 7.2703 7.5372 7.8041 8.0710 8.3379 8.6048 8.8717 9.1386 9.4055 9.6724 9.9393 10.2062 10.4731 10.7400 11.2153 11.6907 12.1660 12.6413 13.1167 13.5920 14.0673 14.5427 15.0180 15.4933 15.9687 16.4440 16.9193 17.3947 17.8700 18.3453 18.8207 19.2960 19.7713 20.2467 20.7220 21.1973 21.6727 22.1480 22.6233 23.0987 23.5740 24.0493 24.5247 25.0000 ! PS_WindSpeeds - Wind speeds corresponding to minimum blade pitch angles [m/s] -0.05997374 0.05997374 0.05997374 0.05997374 0.05997374 0.05995230 0.05568017 0.05139305 0.04630957 0.04053154 0.03444871 0.02774193 0.02083682 0.01377992 0.00660717 0.00000000 0.00000000 0.00000000 0.00000000 0.00000000 0.00000000 0.00000000 0.00000000 0.00000000 0.00000000 0.00798358 0.02222567 0.03475505 0.04563791 0.05328450 0.06405592 0.07436594 0.08427713 0.09385932 0.10323575 0.11234777 0.12134295 0.13011531 0.13881511 0.14732690 0.15578898 0.16409463 0.17235500 0.18049466 0.18858365 0.19658691 0.20452181 0.21241204 0.22021131 0.22800500 0.23567545 0.24336643 0.25094186 0.25851588 0.26602564 0.27348266 0.28093357 0.28828297 0.29566389 0.30293290 ! PS_BldPitchMin - Minimum blade pitch angles [rad] +3.000 3.267 3.534 3.801 4.068 4.334 4.601 4.868 5.135 5.402 5.669 5.936 6.203 6.470 6.737 7.003 7.270 7.537 7.804 8.071 8.338 8.605 8.872 9.139 9.406 9.672 9.939 10.206 10.473 10.740 11.215 11.691 12.166 12.641 13.117 13.592 14.067 14.543 15.018 15.493 15.969 16.444 16.919 17.395 17.870 18.345 18.821 19.296 19.771 20.247 20.722 21.197 21.673 22.148 22.623 23.099 23.574 24.049 24.525 25.000 ! PS_WindSpeeds - Wind speeds corresponding to minimum blade pitch angles [m/s] +0.060 0.060 0.060 0.060 0.060 0.060 0.056 0.051 0.046 0.041 0.034 0.028 0.021 0.014 0.007 0.000 0.000 0.000 0.000 0.000 0.000 0.000 0.000 0.000 0.000 0.008 0.022 0.035 0.046 0.053 0.064 0.074 0.084 0.094 0.103 0.112 0.121 0.130 0.139 0.147 0.156 0.164 0.172 0.180 0.189 0.197 0.205 0.212 0.220 0.228 0.236 0.243 0.251 0.259 0.266 0.273 0.281 0.288 0.296 0.303 ! PS_BldPitchMin - Minimum blade pitch angles [rad] !------- SHUTDOWN ----------------------------------------------------------- 0.698100000000 ! SD_MaxPit - Maximum blade pitch angle to initiate shutdown, [rad] @@ -153,10 +159,10 @@ 2 ! ZMQ_UpdatePeriod - Call ZeroMQ every [x] seconds, [s] !------- Cable Control --------------------------------------------------------- -1 ! CC_Group_N - Number of cable control groups +1 ! CC_Group_N - Number of cable control groups 0 ! CC_GroupIndex - First index for cable control group, should correspond to deltaL -20.000000 ! CC_ActTau - Time constant for line actuator [s] +20.000000 ! CC_ActTau - Time constant for line actuator [s] !------- Structural Controllers --------------------------------------------------------- -1 ! StC_Group_N - Number of cable control groups - 0 ! StC_GroupIndex - First index for structural control group, options specified in ServoDyn summary output +1 ! StC_Group_N - Number of cable control groups + 0 ! StC_GroupIndex - First index for structural control group, options specified in ServoDyn summary output diff --git a/Test_Cases/NREL-5MW/DISCON.IN b/Test_Cases/NREL-5MW/DISCON.IN index 3da89959..759dc694 100644 --- a/Test_Cases/NREL-5MW/DISCON.IN +++ b/Test_Cases/NREL-5MW/DISCON.IN @@ -1,5 +1,5 @@ ! Controller parameter input file for the NREL-5MW wind turbine -! - File written using ROSCO version 2.7.0 controller tuning logic on 02/28/23 +! - File written using ROSCO version 2.7.0 controller tuning logic on 04/03/23 !------- DEBUG ------------------------------------------------------------ 1 ! LoggingLevel - (0: write no debug files, 1: write standard output .dbg-file, 2: LoggingLevel 1 + ROSCO LocalVars (.dbg2) 3: LoggingLevel 2 + complete avrSWAP-array (.dbg3)) @@ -13,6 +13,7 @@ 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} +0 ! PRC_Mode - Power reference tracking mode{0: use standard rotor speed set points, 1: use PRC rotor speed setpoints} 2 ! WE_Mode - Wind speed estimator mode {0: One-second low pass filtered hub height wind speed, 1: Immersion and Invariance Estimator, 2: Extended Kalman Filter} 1 ! PS_Mode - Pitch saturation mode {0: no pitch saturation, 1: implement pitch saturation} 0 ! SD_Mode - Shutdown mode {0: no shutdown procedure, 1: pitch to max pitch at shutdown} @@ -83,6 +84,11 @@ 1.00000 ! SS_VSGain - Variable speed torque controller setpoint smoother gain, [-]. 0.00100 ! SS_PCGain - Collective pitch controller setpoint smoother gain, [-]. +!------- POWER REFERENCE TRACKING -------------------------------------- +2 ! PRC_n - Number of elements in PRC_WindSpeeds and PRC_RotorSpeeds array +3.000 25.000 ! PRC_WindSpeeds - Array of wind speeds used in rotor speed vs. wind speed lookup table [m/s]. +0.792 0.792 ! PRC_RotorSpeeds - Array of rotor speeds corresponding to PRC_WindSpeeds [rad/s]. + !------- WIND SPEED ESTIMATOR --------------------------------------------- 63.000 ! WE_BladeRadius - Blade length (distance from hub center to blade tip), [m] 1 ! WE_CP_n - Amount of parameters in the Cp array @@ -113,8 +119,8 @@ !------- MINIMUM PITCH SATURATION ------------------------------------------- 60 ! PS_BldPitchMin_N - Number of values in minimum blade pitch lookup table (should equal number of values in PS_WindSpeeds and PS_BldPitchMin) -3.0000 3.2897 3.5793 3.8690 4.1586 4.4483 4.7379 5.0276 5.3172 5.6069 5.8966 6.1862 6.4759 6.7655 7.0552 7.3448 7.6345 7.9241 8.2138 8.5034 8.7931 9.0828 9.3724 9.6621 9.9517 10.2414 10.5310 10.8207 11.1103 11.4000 11.8533 12.3067 12.7600 13.2133 13.6667 14.1200 14.5733 15.0267 15.4800 15.9333 16.3867 16.8400 17.2933 17.7467 18.2000 18.6533 19.1067 19.5600 20.0133 20.4667 20.9200 21.3733 21.8267 22.2800 22.7333 23.1867 23.6400 24.0933 24.5467 25.0000 ! PS_WindSpeeds - Wind speeds corresponding to minimum blade pitch angles [m/s] -0.00088027 0.00088027 0.00088027 0.00088027 0.00088027 0.00088027 0.00088027 0.00088027 0.00088027 0.00088027 0.00088027 0.00088027 0.00088027 0.00088027 0.00088027 0.00088027 0.00088027 0.00088027 0.00088027 0.00088027 0.00088027 0.00088027 0.00088027 0.00088027 0.00088027 0.01116187 0.02310060 0.03164156 0.03968639 0.04741131 0.05899071 0.07019329 0.08090119 0.09141661 0.10169361 0.11174124 0.12170066 0.13137494 0.14103377 0.15048120 0.15989580 0.16913227 0.17831010 0.18739638 0.19643591 0.20537011 0.21419674 0.22293719 0.23161365 0.24025975 0.24885012 0.25735704 0.26578040 0.27407178 0.28233051 0.29047594 0.29867838 0.30674517 0.31490089 0.32284411 ! PS_BldPitchMin - Minimum blade pitch angles [rad] +3.000 3.290 3.579 3.869 4.159 4.448 4.738 5.028 5.317 5.607 5.897 6.186 6.476 6.766 7.055 7.345 7.634 7.924 8.214 8.503 8.793 9.083 9.372 9.662 9.952 10.241 10.531 10.821 11.110 11.400 11.853 12.307 12.760 13.213 13.667 14.120 14.573 15.027 15.480 15.933 16.387 16.840 17.293 17.747 18.200 18.653 19.107 19.560 20.013 20.467 20.920 21.373 21.827 22.280 22.733 23.187 23.640 24.093 24.547 25.000 ! PS_WindSpeeds - Wind speeds corresponding to minimum blade pitch angles [m/s] +0.001 0.001 0.001 0.001 0.001 0.001 0.001 0.001 0.001 0.001 0.001 0.001 0.001 0.001 0.001 0.001 0.001 0.001 0.001 0.001 0.001 0.001 0.001 0.001 0.001 0.011 0.023 0.032 0.040 0.047 0.059 0.070 0.081 0.091 0.102 0.112 0.122 0.131 0.141 0.150 0.160 0.169 0.178 0.187 0.196 0.205 0.214 0.223 0.232 0.240 0.249 0.257 0.266 0.274 0.282 0.290 0.299 0.307 0.315 0.323 ! PS_BldPitchMin - Minimum blade pitch angles [rad] !------- SHUTDOWN ----------------------------------------------------------- 0.436300000000 ! SD_MaxPit - Maximum blade pitch angle to initiate shutdown, [rad] @@ -153,10 +159,10 @@ 2 ! ZMQ_UpdatePeriod - Call ZeroMQ every [x] seconds, [s] !------- Cable Control --------------------------------------------------------- -1 ! CC_Group_N - Number of cable control groups +1 ! CC_Group_N - Number of cable control groups 0 ! CC_GroupIndex - First index for cable control group, should correspond to deltaL -20.000000 ! CC_ActTau - Time constant for line actuator [s] +20.000000 ! CC_ActTau - Time constant for line actuator [s] !------- Structural Controllers --------------------------------------------------------- -1 ! StC_Group_N - Number of cable control groups - 0 ! StC_GroupIndex - First index for structural control group, options specified in ServoDyn summary output +1 ! StC_Group_N - Number of cable control groups + 0 ! StC_GroupIndex - First index for structural control group, options specified in ServoDyn summary output From 1e38c90d71767991703e38f89d1c37f892815f36 Mon Sep 17 00:00:00 2001 From: dzalkind Date: Mon, 3 Apr 2023 16:18:44 -0600 Subject: [PATCH 090/224] Update IPC example for testing sat modes --- Examples/12_tune_ipc.py | 153 ++++++------------ ROSCO_toolbox/ofTools/case_gen/CaseLibrary.py | 40 ++++- ROSCO_toolbox/ofTools/case_gen/HH_WindFile.py | 26 ++- Tune_Cases/NREL2p8.yaml | 2 +- 4 files changed, 116 insertions(+), 105 deletions(-) diff --git a/Examples/12_tune_ipc.py b/Examples/12_tune_ipc.py index d4040a68..e435becf 100644 --- a/Examples/12_tune_ipc.py +++ b/Examples/12_tune_ipc.py @@ -14,105 +14,58 @@ import matplotlib.pyplot as plt # ROSCO toolbox modules -from ROSCO_toolbox import controller as ROSCO_controller -from ROSCO_toolbox import turbine as ROSCO_turbine -from ROSCO_toolbox.utilities import DISCON_dict from ROSCO_toolbox.ofTools.fast_io import output_processing -from ROSCO_toolbox.inputs.validation import load_rosco_yaml -from ROSCO_toolbox.ofTools.case_gen.CaseLibrary import set_channels -from ROSCO_toolbox.ofTools.case_gen.runFAST_pywrapper import runFAST_pywrapper_batch -from ROSCO_toolbox.ofTools.case_gen.CaseGen_General import CaseGen_General - - - -this_dir = os.path.dirname(os.path.abspath(__file__)) -rosco_dir = os.path.dirname(this_dir) -example_out_dir = os.path.join(this_dir,'examples_out') -example_name = '12_ipc_sim' -run_dir = os.path.join(example_out_dir, example_name) - -# Load yaml file (Open Loop Case) -parameter_filename = os.path.join(rosco_dir,'Tune_Cases/BAR.yaml') - -inps = load_rosco_yaml(parameter_filename) -path_params = inps['path_params'] -turbine_params = inps['turbine_params'] -controller_params = inps['controller_params'] - -# Turn flaps off and IPC on -controller_params['Flp_Mode'] = 0 -controller_params['IPC_ControlMode'] = 1 - -# Instantiate turbine, and controller -turbine = ROSCO_turbine.Turbine(turbine_params) -controller = ROSCO_controller.Controller(controller_params) - -# Load turbine data from OpenFAST and rotor performance text file -turbine.load_from_fast( - path_params['FAST_InputFile'], - os.path.join(this_dir, path_params['FAST_directory']) - ) -# Tune controller -controller.tune_controller(turbine) - -# Set rosco_dll -if platform.system() == 'Windows': - rosco_dll = os.path.join(rosco_dir, 'ROSCO/build/libdiscon.dll') -elif platform.system() == 'Darwin': - rosco_dll = os.path.join(rosco_dir, 'ROSCO/build/libdiscon.dylib') -else: - rosco_dll = os.path.join(rosco_dir, 'ROSCO/build/libdiscon.so') - -case_inputs = {} -case_inputs[('ServoDyn','DLL_FileName')] = {'vals': [rosco_dll], 'group': 0} -case_inputs[('ServoDyn','Ptch_Cntrl')] = {'vals': [1], 'group': 0} - -# Apply all discon variables as case inputs -discon_vt = DISCON_dict( - turbine, - controller, - txt_filename=os.path.join(this_dir,path_params['FAST_directory'],path_params['rotor_performance_filename']) - ) - -for discon_input in discon_vt: - case_inputs[('DISCON_in',discon_input)] = {'vals': [discon_vt[discon_input]], 'group': 0} - -# Generate cases -if not os.path.exists(run_dir): - os.makedirs(run_dir) - -case_list, case_name_list = CaseGen_General(case_inputs, dir_matrix=run_dir, namebase='ipc_example') -channels = set_channels() -channels['BldPitch2'] = True -channels['BldPitch3'] = True - -# Run FAST cases -fastBatch = runFAST_pywrapper_batch() - -fastBatch.FAST_directory = os.path.realpath(os.path.join(rosco_dir,'Tune_Cases',path_params['FAST_directory'])) -fastBatch.FAST_InputFile = path_params['FAST_InputFile'] -fastBatch.channels = channels -fastBatch.FAST_runDirectory = run_dir -fastBatch.case_list = case_list -fastBatch.case_name_list = case_name_list -fastBatch.debug_level = 2 -fastBatch.FAST_exe = 'openfast' - -fastBatch.run_serial() - - -# # Define Plot cases -cases = {} -cases['Baseline'] = ['Wind1VelX', ('BldPitch1', 'BldPitch2', 'BldPitch3'), 'RootMyc1', 'RotSpeed'] - -out_file = os.path.join(example_out_dir,example_name,'ipc_example_0.outb') -op = output_processing.output_processing() -fastout = op.load_fast_out(out_file, tmin=0) -fig, ax = op.plot_fast_out(cases=cases,showplot=False) -if False: - plt.show() -else: - fig[0].savefig(os.path.join(example_out_dir,'13_ipc_FAST_Out.png')) - - +from ROSCO_toolbox.ofTools.case_gen.run_FAST import run_FAST_ROSCO +from ROSCO_toolbox.ofTools.case_gen import CaseLibrary as cl + +def main(): + this_dir = os.path.dirname(os.path.abspath(__file__)) + rosco_dir = os.path.dirname(this_dir) + example_out_dir = os.path.join(this_dir,'examples_out') + example_name = '12_ipc_sim' + run_dir = os.path.join(example_out_dir, example_name) + + # Load yaml file (Open Loop Case) + parameter_filename = os.path.join(rosco_dir,'Tune_Cases/NREL2p8.yaml') + + case_inputs = {} + case_inputs[('ServoDyn','Ptch_Cntrl')] = {'vals': [1], 'group': 0} + case_inputs[('DISCON_in','IPC_SatMode')] = {'vals': [0,1,2,3], 'group': 1} + + + + # simulation set up + r = run_FAST_ROSCO() + r.tuning_yaml = parameter_filename + r.wind_case_fcn = cl.ramp # single step wind input + r.wind_case_opts = { + 'U_start': 11, # from 10 to 15 m/s + 'U_end': 9, + 't_start': 100, + 't_end': 400, + 'both_dir': True, + 'vert_shear': 0.2 + } + r.case_inputs = case_inputs + r.save_dir = run_dir + r.rosco_dir = rosco_dir + r.n_cores = 4 + r.run_FAST() + + + # # Define Plot cases + cases = {} + cases['Baseline'] = ['Wind1VelX', 'BldPitch1', 'RootMyc1', 'RotSpeed'] + + out_files = [os.path.join(example_out_dir,example_name,f'NREL2p8/ramp/base/NREL2p8_{i_case}.outb') for i_case in range(4)] + op = output_processing.output_processing() + fastout = op.load_fast_out(out_files, tmin=0) + fig, ax = op.plot_fast_out(cases=cases,showplot=False) + if False: + plt.show() + else: + fig[0].savefig(os.path.join(example_out_dir,'12_ipc_FAST_Out.png')) + +if __name__=="__main__": + main() diff --git a/ROSCO_toolbox/ofTools/case_gen/CaseLibrary.py b/ROSCO_toolbox/ofTools/case_gen/CaseLibrary.py index d1aa7809..e6aef0bf 100644 --- a/ROSCO_toolbox/ofTools/case_gen/CaseLibrary.py +++ b/ROSCO_toolbox/ofTools/case_gen/CaseLibrary.py @@ -363,6 +363,42 @@ def user_hh(**wind_case_opts): case_inputs[("InflowWind","Filename_Uni")] = {'vals':wind_case_opts['wind_filenames'], 'group':1} return case_inputs + +def ramp(**wind_case_opts): + U_start = wind_case_opts.get('U_start',8.) + U_end = wind_case_opts.get('U_end',15.) + t_start = wind_case_opts.get('t_start',100.) + t_end = wind_case_opts.get('t_end',400.) + vert_shear = wind_case_opts.get('vert_shear',.2) + both_dir = wind_case_opts.get('both_dir',False) # ramp up and down + + # Make Default step wind object + hh_wind = HH_WindFile() + hh_wind.t_max = t_end + hh_wind.filename = os.path.join(wind_case_opts['run_dir'],'ramp.hh') + + # Step Wind Setup + if both_dir: + hh_wind.time = [0, t_start, (t_start + t_end) / 2, t_end] + hh_wind.wind_speed = [U_start, U_start, U_end, U_start] + else: + hh_wind.time = [0, t_start, t_end] + hh_wind.wind_speed = [U_start, U_start, U_end] + + hh_wind.vert_shear = [vert_shear] * len(hh_wind.time) + + hh_wind.resample() + hh_wind.write() + + case_inputs = base_op_case() + case_inputs[("Fst","TMax")] = {'vals':[t_end], 'group':0} + case_inputs[("InflowWind","WindType")] = {'vals':[2], 'group':0} + case_inputs[("InflowWind","Filename_Uni")] = {'vals':[hh_wind.filename], 'group':0} + + return case_inputs + + + ############################################################################################## # @@ -432,9 +468,9 @@ def sweep_pitch_act(start_group, **control_sweep_opts): def sweep_ipc_gains(start_group, **control_sweep_opts): case_inputs_control = {} - kis = np.linspace(0,1,6).tolist() + kis = np.linspace(0,1,8).tolist() # kis = [0.,0.6,1.2,1.8,2.4,3.] - KIs = [[ki * 6e-9,0.] for ki in kis] + KIs = [[ki * 12e-9,0.] for ki in kis] case_inputs_control[('DISCON_in','IPC_ControlMode')] = {'vals': [1], 'group': 0} # case_inputs_control[('DISCON_in','IPC_KI')] = {'vals': [[0.,0.],[1e-8,0.]], 'group': start_group} case_inputs_control[('DISCON_in','IPC_KI')] = {'vals': KIs, 'group': start_group} diff --git a/ROSCO_toolbox/ofTools/case_gen/HH_WindFile.py b/ROSCO_toolbox/ofTools/case_gen/HH_WindFile.py index a74205ce..54ed2ff5 100644 --- a/ROSCO_toolbox/ofTools/case_gen/HH_WindFile.py +++ b/ROSCO_toolbox/ofTools/case_gen/HH_WindFile.py @@ -44,16 +44,38 @@ def __init__(self,**kwargs): super(HH_WindFile, self).__init__() + def resample(self): + # Using time index, check if constant, otherwise throw a warning + if len(set(self.wind_dir)) != 1: # all same + print('ROSCO Warning: all wind_dir elements not equal in resample') + if len(set(self.vert_speed)) != 1: # all same + print('ROSCO Warning: all vert_speed elements not equal in resample') + if len(set(self.horiz_shear)) != 1: # all same + print('ROSCO Warning: all horiz_shear elements not equal in resample') + if len(set(self.vert_shear)) != 1: # all same + print('ROSCO Warning: all vert_shear elements not equal in resample') + if len(set(self.linv_shear)) != 1: # all same + print('ROSCO Warning: all linv_shear elements not equal in resample') + if len(set(self.gust_speed)) != 1: # all same + print('ROSCO Warning: all gust_speed elements not equal in resample') + + self.wind_dir = len(self.time) * [self.wind_dir[0]] + self.vert_speed = len(self.time) * [self.vert_speed[0]] + self.horiz_shear = len(self.time) * [self.horiz_shear[0]] + self.vert_shear = len(self.time) * [self.vert_shear[0]] + self.linv_shear = len(self.time) * [self.linv_shear[0]] + self.gust_speed = len(self.time) * [self.gust_speed[0]] + def write(self): if not os.path.isdir(os.path.dirname(self.filename)): os.makedirs(os.path.dirname(self.filename)) with open(self.filename,'w') as f: f.write('!\tTime\tWind Speed\tWind Dir\tVert. Spd.\tHoriz. Shr.\t Vert. Shr.\t LinV. Shr.\tGust Speed\n') - for t, ws, wd, vs, hs, vs, ls, gs in zip(self.time,self.wind_speed,self.wind_dir,self.vert_speed, \ + for t, ws, wd, vsp, hs, vsh, ls, gs in zip(self.time,self.wind_speed,self.wind_dir,self.vert_speed, \ self.horiz_shear, self.vert_shear, self.linv_shear, self.gust_speed): f.write('{:6.6f}\t{:6.6f}\t{:6.6f}\t{:6.6f}\t{:6.6f}\t{:6.6f}\t{:6.6f}\t{:6.6f}\n'.format( - t,ws,wd,vs,hs,vs,ls,gs)) + t,ws,wd,vsp,hs,vsh,ls,gs)) def plot(self): diff --git a/Tune_Cases/NREL2p8.yaml b/Tune_Cases/NREL2p8.yaml index 7f71935e..bbba19a2 100644 --- a/Tune_Cases/NREL2p8.yaml +++ b/Tune_Cases/NREL2p8.yaml @@ -1,6 +1,6 @@ path_params: {FAST_InputFile: NREL-2p8-127.fst, FAST_directory: ../Test_Cases/NREL_2p8_127, rotor_performance_filename: NREL-2p8-127_Cp_Ct_Cq.txt} controller_params: - LoggingLevel: 1 + LoggingLevel: 2 F_LPFType: 1 F_NotchType: 0 IPC_ControlMode: 1 From e49f3837d8da327ca78f40f12241e21615fdd75d Mon Sep 17 00:00:00 2001 From: dzalkind Date: Mon, 3 Apr 2023 16:19:48 -0600 Subject: [PATCH 091/224] Add latest plot_FAST notebook --- ROSCO_toolbox/ofTools/fast_io/plot_FAST.ipynb | 455 +++++------------- 1 file changed, 132 insertions(+), 323 deletions(-) diff --git a/ROSCO_toolbox/ofTools/fast_io/plot_FAST.ipynb b/ROSCO_toolbox/ofTools/fast_io/plot_FAST.ipynb index 4e64a191..52fe840c 100644 --- a/ROSCO_toolbox/ofTools/fast_io/plot_FAST.ipynb +++ b/ROSCO_toolbox/ofTools/fast_io/plot_FAST.ipynb @@ -9,7 +9,7 @@ }, { "cell_type": "code", - "execution_count": 2, + "execution_count": 1, "metadata": {}, "outputs": [], "source": [ @@ -50,27 +50,15 @@ }, { "cell_type": "code", - "execution_count": 3, + "execution_count": 13, "metadata": {}, "outputs": [], "source": [ "outfiles = [\n", - "# '/Users/dzalkind/Tools/WEIS-1/outputs/iea15mw/iea15mw_00.outb',\n", - "# '/Users/dzalkind/Tools/WEIS-1/outputs/iea15mw/iea15mw_01.outb',\n", - "# '/Users/dzalkind/Tools/WEIS-1/outputs/iea15mw/iea15mw_02.outb',\n", - "# '/Users/dzalkind/Tools/WEIS-1/outputs/iea15mw/iea15mw_08.outb',\n", - "# '/Users/dzalkind/Tools/ROSCO_toolbox/Examples/examples_out/13_Simulink_Test/OL_Test_1.SFunc.outb',\n", - " '/Users/dzalkind/Projects/FOCAL/IEA15MW_FOCAL/power_curve/base/IEA15MW_FOCAL_07.outb',\n", - "# '/Users/dzalkind/Tools/WEIS-3/results/UMaine-Semi/DISCON/IB_NTM_Raft/iea15mw_1.outb',\n", - "# '/Users/dzalkind/Tools/WEIS-3/results/UMaine-Semi/DISCON/IB_NTM_Raft/iea15mw_2.outb',\n", - "# '/Users/dzalkind/Tools/WEIS-3/results/CT-semi/ntm_long/DISCON-CT-semi/iea15mw_13.outb',\n", - "# '/Users/dzalkind/Tools/WEIS-4/optimizations/both_debug_nowrapper/NREL5MW_OC3_spar_IEC_0.outb',\n", - "# '/Users/dzalkind/Tools/WEIS-4/optimizations/outputs_opt_both_debug/NREL5MW_OC3_spar_IEC_0.outb',\n", - "# '/Users/dzalkind/Tools/WEIS-4/optimizations/outputs_opt_both_debug2/NREL5MW_OC3_spar_IEC_0.outb',\n", - "# '/Users/dzalkind/Tools/WEIS-4/optimizations/outputs_opt_both_debug3/NREL5MW_OC3_spar_IEC_0.outb',\n", - "# '/Users/dzalkind/Tools/WEIS-4/optimizations/outputs_opt_both_debug4/NREL5MW_OC3_spar_IEC_0.outb',\n", - "# '/Users/dzalkind/Tools/WEIS-3/sowfa_debug/rotor_sweep/c_001_sp6_h150_D240_oR2_yaw_base/IEA-15-240-RWT-Monopile.2.T2.out',\n", - "# '/Users/dzalkind/Tools/WEIS-3/results/CT-barge/DISCON-CT-barge_hiBW/simp/step_1.outb',\n", + " # '/Users/dzalkind/Tools/ROSCO3/Examples/examples_out/12_ipc_sim/NREL2p8/ramp/base/NREL2p8_0.out',\n", + " # '/Users/dzalkind/Tools/ROSCO3/Examples/examples_out/12_ipc_sim/NREL2p8/ramp/base/NREL2p8_1.out',\n", + " # '/Users/dzalkind/Tools/ROSCO3/Examples/examples_out/12_ipc_sim/NREL2p8/ramp/base/NREL2p8_2.out',\n", + " '/Users/dzalkind/Tools/ROSCO3/Examples/examples_out/12_ipc_sim/NREL2p8/ramp/base/NREL2p8_3.out',\n", "]\n", "\n", "# outfiles" @@ -78,76 +66,14 @@ }, { "cell_type": "code", - "execution_count": 6, + "execution_count": 25, "metadata": {}, "outputs": [ - { - "name": "stdout", - "output_type": "stream", - "text": [ - "Wind1VelX is not available as an output channel.\n", - "BldPitch1 is not available as an output channel.\n", - "GenTq is not available as an output channel.\n", - "TwrBsMyt is not available as an output channel.\n", - "GenPwr is not available as an output channel.\n", - "RotThrust is not available as an output channel.\n", - "Fl_Pitcom is not available as an output channel.\n", - "PC_MinPit is not available as an output channel.\n", - "WE_Vw is not available as an output channel.\n", - "RtVAvgxh is not available as an output channel.\n", - "BldPitch1 is not available as an output channel.\n", - "PtfmSurge is not available as an output channel.\n", - "PtfmSway is not available as an output channel.\n", - "PtfmHeave is not available as an output channel.\n", - "PtfmPitch is not available as an output channel.\n", - "PtfmRoll is not available as an output channel.\n", - "PtfmYaw is not available as an output channel.\n", - "RtVAvgxh is not available as an output channel.\n", - "BldPitch1 is not available as an output channel.\n", - "RotThrust is not available as an output channel.\n" - ] - }, - { - "data": { - "image/png": "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\n", - "text/plain": [ - "
" - ] - }, - "metadata": { - "needs_background": "light" - }, - "output_type": "display_data" - }, - { - "data": { - "image/png": "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\n", - "text/plain": [ - "
" - ] - }, - "metadata": { - "needs_background": "light" - }, - "output_type": "display_data" - }, - { - "data": { - "image/png": "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\n", - "text/plain": [ - "
" - ] - }, - "metadata": { - "needs_background": "light" - }, - "output_type": "display_data" - }, { "data": { - "image/png": "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\n", + "image/png": "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\n", "text/plain": [ - "
" + "
" ] }, "metadata": { @@ -158,27 +84,45 @@ ], "source": [ "output_ext = '.out'\n", - "plt.rcParams[\"figure.figsize\"] = [9,7]\n", + "plt.rcParams[\"figure.figsize\"] = [9,12]\n", "\n", "ROSCO = True\n", + "ROSCO2 = True\n", "\n", "# Define Plot cases \n", "cases = {}\n", - "cases['Gen. Speed Sigs.'] = ['Wind1VelX', 'BldPitch1', 'GenTq', 'GenSpeed','TwrBsMyt','GenPwr','RotThrust']#,'PtfmPitch','PtfmYaw','NacYaw']\n", - "# cases['Debug'] = ['IPDefl1','OoPDefl1','Azimuth','RotTorq']#,'PtfmPitch','PtfmYaw','NacYaw']\n", - "cases['Plt. Control Sigs.'] = ['RtVAvgxh', 'BldPitch1', 'Fl_Pitcom', 'PC_MinPit','WE_Vw']\n", - "cases['Platform Motion'] = ['PtfmSurge', 'PtfmSway', 'PtfmHeave', 'PtfmPitch','PtfmRoll','PtfmYaw']\n", - "cases['Rot Thrust'] = ['RtVAvgxh','BldPitch1','RotThrust']\n", + "# cases['Gen. Speed Sigs.'] = ['Wind1VelX', 'BldPitch1', 'GenTq', 'GenSpeed','TwrBsMyt','GenPwr','RootMyb1']#,'PtfmPitch','PtfmYaw','NacYaw']\n", + "cases['Gen. Speed Sigs.'] = ['Wind1VelX','BldPitch1', 'GenTq', 'GenSpeed','TwrBsMyt','GenPwr','RootMyb1']#,'PtfmPitch','PtfmYaw','NacYaw']\n", + "# # cases['Debug'] = ['IPDefl1','OoPDefl1','Azimuth','RotTorq']#,'PtfmPitch','PtfmYaw','NacYaw']\n", + "# cases['Plt. Control Sigs.'] = ['Fl_PitCom', 'PC_MinPit']\n", + "# cases['Platform Motion'] = ['PtfmSurge', 'PtfmSway', 'PtfmHeave', 'PtfmPitch','PtfmRoll','PtfmYaw']\n", + "# # cases['Tower Loads'] = ['TwrBsFxt','TwrBsFyt', 'TwrBsFzt', 'TwrBsMxt', 'TwrBsMyt','TwrBsMzt']\n", + "# # cases['Rot Thrust'] = ['RtVAvgxh','BldPitch1','RotThrust']\n", + "# cases['IPC'] = ['PitCom','PitComAct']\n", + "# # cases['IPC'] = ['PtfmYaw','YawBrMzp','YawBrMyp']\n", + "\n", + "# cases['Gen. Speed Sigs.'] = ['Wind1VelX', 'GenPwr', 'RotSpeed', 'GenSpeed', 'GenTq', 'BldPitch1','B1RootMyr'] #, 'PtfmPitch','PtfmYaw'] #,'PtfmPitch','PtfmYaw','NacYaw']\n", + "# cases['Rot. Pos'] = ['RotSpeed',('BldPitch1','BldPitch2','BldPitch3'),'GenTq','Azimuth']\n", + "# cases['Rotor Position'] = ['AzError','GenTqAz','Azimuth','AzUnwrapped','OL_Azimuth']\n", + "# cases['Aero'] = [\"B1N3Alpha\",\"B1N3Cd\",\"B1N3Cl\"]\n", + "\n", "\n", "op = output_processing.output_processing()\n", + "op_RO = output_processing.output_processing()\n", + "op_RO2 = output_processing.output_processing()\n", + "\n", "\n", - "# Rosco outfiles\n", - "r_outfiles = [out.split('.out')[0] + '.RO.dbg' for out in outfiles]\n", "\n", "fast_out = []\n", "fast_out = op.load_fast_out(outfiles, tmin=0)\n", "if ROSCO:\n", - " rosco_out = op.load_fast_out(r_outfiles, tmin=0)\n", + " # Rosco outfiles\n", + " r_outfiles = [out.split('.out')[0] + '.RO.dbg' for out in outfiles]\n", + " rosco_out = op_RO.load_fast_out(r_outfiles, tmin=0)\n", + " \n", + " if ROSCO2:\n", + " r_outfiles = [out.split('.out')[0] + '.RO.dbg2' for out in outfiles]\n", + " rosco_out2 = op_RO2.load_fast_out(r_outfiles, tmin=0)\n", " \n", "# Combine outputs\n", "if ROSCO:\n", @@ -186,6 +130,10 @@ " for i, (r_out, f_out) in enumerate(zip(rosco_out,fast_out)):\n", " r_out.update(f_out)\n", " comb_out[i] = r_out\n", + " if ROSCO2:\n", + " for i, (r_out2, f_out) in enumerate(zip(rosco_out2,comb_out)):\n", + " r_out2.update(f_out)\n", + " comb_out[i] = r_out2\n", "else:\n", " comb_out = fast_out\n", "\n", @@ -202,7 +150,97 @@ " save_fig_dir = '/Users/dzalkind/Projects/CarbonTrust/Deliverables'\n", " for f in fig:\n", " f.savefig(os.path.join(save_fig_dir,'ts'+str(i_fig)))\n", - " i_fig += 1" + " i_fig += 1\n", + "\n", + "output_ext = '.out'\n", + "plt.rcParams[\"figure.figsize\"] = [9,7]\n", + "\n" + ] + }, + { + "cell_type": "code", + "execution_count": 70, + "metadata": {}, + "outputs": [ + { + "data": { + "text/plain": [ + "array([14.97, 15. , 15.02, ..., 90. , 90. , 90. ])" + ] + }, + "execution_count": 70, + "metadata": {}, + "output_type": "execute_result" + } + ], + "source": [ + "fast_out[1]['PtfmHeave'].mean()\n", + "\n", + "fast_out[0]['BldPitch1']" + ] + }, + { + "cell_type": "code", + "execution_count": 16, + "metadata": { + "tags": [] + }, + "outputs": [ + { + "data": { + "text/plain": [ + "[]" + ] + }, + "execution_count": 16, + "metadata": {}, + "output_type": "execute_result" + }, + { + "data": { + "image/png": "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\n", + "text/plain": [ + "
" + ] + }, + "metadata": { + "needs_background": "light" + }, + "output_type": "display_data" + } + ], + "source": [ + "\n", + "ind = comb_out[0]['Time'] > 120\n", + "a = np.array([co['RootMyb1'][ind].std() for co in comb_out])\n", + "b = np.array([co['BldPitch1'][ind].std() for co in comb_out])\n", + "\n", + "fig, axs = plt.subplots(2,1)\n", + "axs[0].plot(a)\n", + "axs[1].plot(b)\n", + "\n" + ] + }, + { + "cell_type": "code", + "execution_count": 33, + "metadata": { + "tags": [] + }, + "outputs": [ + { + "data": { + "text/plain": [ + "360" + ] + }, + "execution_count": 33, + "metadata": {}, + "output_type": "execute_result" + } + ], + "source": [ + "18*20\n" ] }, { @@ -433,93 +471,6 @@ "df" ] }, - { - "cell_type": "code", - "execution_count": 27, - "metadata": {}, - "outputs": [ - { - "data": { - "text/plain": [ - "{'Time': array([0.00000e+00, 1.30000e-02, 2.50000e-02, ..., 7.99975e+02,\n", - " 7.99987e+02, 8.00000e+02]),\n", - " 'FA_AccF': array([ 0.000e+00, 1.264e-23, -8.574e-23, ..., -9.656e-17, -9.670e-17,\n", - " -9.684e-17]),\n", - " 'FA_AccR': array([-0.000e+00, 7.226e-18, -7.774e-17, ..., -3.648e-17, 2.417e-17,\n", - " 2.873e-17]),\n", - " 'RotSpeed': array([0.6132, 0.6131, 0.613 , ..., 0.5879, 0.5878, 0.5878]),\n", - " 'RotSpeedF': array([0.6132, 0.6132, 0.6132, ..., 0.5932, 0.5932, 0.5931]),\n", - " 'GenSpeed': array([0.6132, 0.6131, 0.613 , ..., 0.5879, 0.5878, 0.5878]),\n", - " 'GenSpeedF': array([0.6132, 0.6132, 0.6132, ..., 0.5932, 0.5932, 0.5931]),\n", - " 'FA_Acc': array([0., 0., 0., ..., 0., 0., 0.]),\n", - " 'Fl_Pitcom': array([-0.000e+00, 1.481e-24, -8.567e-24, ..., 4.151e-13, 4.151e-13,\n", - " 4.151e-13]),\n", - " 'PC_MinPit': array([0., 0., 0., ..., 0., 0., 0.]),\n", - " 'SS_dOmF': array([-0.0007917, -0.0007917, -0.0007901, ..., -0.0004443, -0.0004443,\n", - " -0.0004444]),\n", - " 'WE_Vw': array([8.963, 8.963, 8.963, ..., 7.916, 7.916, 7.916]),\n", - " 'WE_b': array([0.000e+00, 0.000e+00, 2.101e-28, ..., 2.392e-11, 2.392e-11,\n", - " 2.392e-11]),\n", - " 'WE_t': array([13140000., 13140000., 13140000., ..., 11480000., 11470000.,\n", - " 11470000.]),\n", - " 'WE_w': array([0.6132, 0.6132, 0.6132, ..., 0.5932, 0.5932, 0.5931]),\n", - " 'WE_Vm': array([8.963, 8.963, 8.963, ..., 7.981, 7.98 , 7.98 ]),\n", - " 'WE_Vt': array([ 0.000e+00, -2.132e-13, -8.994e-09, ..., -6.438e-02, -6.455e-02,\n", - " -6.472e-02]),\n", - " 'WE_lambda': array([8.21 , 8.209, 8.208, ..., 8.911, 8.911, 8.91 ]),\n", - " 'WE_Cp': array([0.25 , 0.4574, 0.4574, ..., 0.4622, 0.4622, 0.4622]),\n", - " 'meta': {'name': 'iea15mw_0.RO',\n", - " 'description': [' Generated on 22-Jun-2021 at 17:43:27 using ROSCO-v2.1.1-43-g22b65089\\n'],\n", - " 'channels': ['Time',\n", - " 'FA_AccF',\n", - " 'FA_AccR',\n", - " 'RotSpeed',\n", - " 'RotSpeedF',\n", - " 'GenSpeed',\n", - " 'GenSpeedF',\n", - " 'FA_Acc',\n", - " 'Fl_Pitcom',\n", - " 'PC_MinPit',\n", - " 'SS_dOmF',\n", - " 'WE_Vw',\n", - " 'WE_b',\n", - " 'WE_t',\n", - " 'WE_w',\n", - " 'WE_Vm',\n", - " 'WE_Vt',\n", - " 'WE_lambda',\n", - " 'WE_Cp'],\n", - " 'attribute_units': ['sec',\n", - " 'm/s',\n", - " 'rad/s^2',\n", - " 'rad/s',\n", - " 'rad/s',\n", - " 'rad/s',\n", - " 'rad/s',\n", - " 'm/s^2',\n", - " 'rad',\n", - " 'rad',\n", - " 'rad/s',\n", - " 'rad',\n", - " 'deg',\n", - " 'Nm',\n", - " 'rad/s',\n", - " 'm/s',\n", - " 'm/s',\n", - " 'rad/s',\n", - " '-'],\n", - " 'filename': '/Users/dzalkind/Tools/WEIS-3/results/UMaine-Semi/DISCON/IB_NTM_Raft/iea15mw_0.RO.dbg'}}" - ] - }, - "execution_count": 27, - "metadata": {}, - "output_type": "execute_result" - } - ], - "source": [ - "fast_out[3]" - ] - }, { "cell_type": "code", "execution_count": 11, @@ -561,148 +512,6 @@ "\n", "# op" ] - }, - { - "cell_type": "code", - "execution_count": 48, - "metadata": {}, - "outputs": [], - "source": [ - "# ret" - ] - }, - { - "cell_type": "code", - "execution_count": 49, - "metadata": {}, - "outputs": [ - { - "data": { - "text/plain": [ - "94.73684210526316" - ] - }, - "execution_count": 49, - "metadata": {}, - "output_type": "execute_result" - } - ], - "source": [ - "1/2e-3\n", - "\n", - "3600/38\n" - ] - }, - { - "cell_type": "code", - "execution_count": 50, - "metadata": {}, - "outputs": [ - { - "data": { - "text/plain": [ - "1.9752718440907233" - ] - }, - "execution_count": 50, - "metadata": {}, - "output_type": "execute_result" - }, - { - "data": { - "image/png": "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\n", - "text/plain": [ - "
" - ] - }, - "metadata": { - "needs_background": "light" - }, - "output_type": "display_data" - } - ], - "source": [ - "yaw_fast = fast_out[0]['PtfmYaw']\n", - "amp = np.std(yaw_fast) * np.sqrt(2)\n", - "\n", - "\n", - "per = 3600/38\n", - "\n", - "tt = fast_out[0]['Time']\n", - "\n", - "yaw_sowfa = amp * np.sin(2 * np.pi / per * tt)\n", - "\n", - "\n", - "plt.plot(tt,yaw_fast,tt,yaw_sowfa)\n", - "\n", - "np.min(yaw_fast)\n", - "\n", - "amp" - ] - }, - { - "cell_type": "code", - "execution_count": null, - "metadata": {}, - "outputs": [], - "source": [] - }, - { - "cell_type": "code", - "execution_count": 51, - "metadata": {}, - "outputs": [ - { - "data": { - "text/plain": [ - "'/Users/dzalkind/Tools/WEIS-3/pCrunch/HPC_tools/eagle2local_sim_inp.sh /Users/dzalkind/Tools/WEIS-3/results/CT-semi/ntm_long/DISCON-CT-semi/ iea15mw_07'" - ] - }, - "execution_count": 51, - "metadata": {}, - "output_type": "execute_result" - } - ], - "source": [ - "# pull from eagle if necessary\n", - "pull_script = '/Users/dzalkind/Tools/WEIS-3/pCrunch/HPC_tools/eagle2local_sim_inp.sh'\n", - "\n", - "\n", - "basedir = outfiles[0].split('/')[1]\n", - "# if basedir == 'scratch':\n", - " \n", - "temp = outfiles[0].split('/')\n", - "filedir = '/'.join(temp[:-1]) + '/'\n", - "\n", - "namebase = temp[-1].split('.')[0]\n", - "search_str = namebase + '*'\n", - "\n", - "shell_cmd = pull_script + ' ' + filedir + ' ' + namebase\n", - "\n", - "shell_cmd\n", - "# ret = subprocess.call(pull_script,shell=True)\n" - ] - }, - { - "cell_type": "code", - "execution_count": null, - "metadata": {}, - "outputs": [], - "source": [] - }, - { - "cell_type": "code", - "execution_count": null, - "metadata": {}, - "outputs": [], - "source": [] - }, - { - "cell_type": "code", - "execution_count": null, - "metadata": {}, - "outputs": [], - "source": [] } ], "metadata": { @@ -721,7 +530,7 @@ "name": "python", "nbconvert_exporter": "python", "pygments_lexer": "ipython3", - "version": "3.8.6" + "version": "3.8.13" } }, "nbformat": 4, From 9e5fd58cd55b6dd57d02bfd694dfe93a5c582533 Mon Sep 17 00:00:00 2001 From: dzalkind Date: Mon, 3 Apr 2023 16:24:16 -0600 Subject: [PATCH 092/224] Add PRC example --- Examples/24_power_ref_control.py | 98 ++++++++++++++++++++++++++++++++ 1 file changed, 98 insertions(+) create mode 100644 Examples/24_power_ref_control.py diff --git a/Examples/24_power_ref_control.py b/Examples/24_power_ref_control.py new file mode 100644 index 00000000..d6e8ee3a --- /dev/null +++ b/Examples/24_power_ref_control.py @@ -0,0 +1,98 @@ +''' +----------- 24_outdata_in_control ------------------------ +Run openfast with ROSCO and cable control +----------------------------------------------- + +Set up and run simulation with pitch offsets, check outputs + +''' + +import os, platform +from ROSCO_toolbox.ofTools.case_gen.run_FAST import run_FAST_ROSCO +from ROSCO_toolbox.ofTools.case_gen import CaseLibrary as cl +from ROSCO_toolbox.ofTools.fast_io import output_processing +from ROSCO_toolbox.tune import yaml_to_objs +import numpy as np +from ROSCO_toolbox.ofTools.fast_io.FAST_reader import InputReader_OpenFAST +from ROSCO_toolbox.ofTools.fast_io.FAST_writer import InputWriter_OpenFAST +from ROSCO_toolbox.inputs.validation import load_rosco_yaml +import matplotlib.pyplot as plt + +''' +Set reference rotor speed as a function of wind speed (estimate in ROSCO) + +''' + + +#directories +this_dir = os.path.dirname(os.path.abspath(__file__)) +rosco_dir = os.path.dirname(this_dir) +example_out_dir = os.path.join(this_dir,'examples_out') +os.makedirs(example_out_dir,exist_ok=True) + +if platform.system() == 'Windows': + lib_name = os.path.realpath(os.path.join(this_dir, '../ROSCO/build/libdiscon.dll')) +elif platform.system() == 'Darwin': + lib_name = os.path.realpath(os.path.join(this_dir, '../ROSCO/build/libdiscon.dylib')) +else: + lib_name = os.path.realpath(os.path.join(this_dir, '../ROSCO/build/libdiscon.so')) + + +def main(): + + # Input yaml and output directory + parameter_filename = os.path.join(rosco_dir,'Tune_Cases/IEA15MW.yaml') + run_dir = os.path.join(example_out_dir,'24_PRC_0') + os.makedirs(run_dir,exist_ok=True) + + + # Create rotor speed table + controller, turbine, path_params = yaml_to_objs(parameter_filename) + + + # plot original ops + plt.plot(controller.v,controller.omega_op) + + + omega = controller.omega_op + v = controller.v + + # Hold near rated rotor speed, for testing setpoint smoother + near_rated = np.bitwise_and(v > 9, v < 13) + first_near_rated_ind = np.where(near_rated)[0][0] + omega[near_rated] = omega[first_near_rated_ind] + + # add high wind ride-through + v_hwrt = [50] # m/s + omega_hwrt = [0.3] # rad/s + v = np.r_[v,v_hwrt] + omega = np.r_[omega,omega_hwrt] + + # plot new lookup + plt.plot(v,omega,linestyle='--') + + + # simulation set up + r = run_FAST_ROSCO() + r.tuning_yaml = parameter_filename + r.wind_case_fcn = cl.simp_step # single step wind input + r.wind_case_fcn = cl.power_curve + r.wind_case_opts = { + 'U': [9], + 'T_max': 100, + } + r.case_inputs = {} + r.save_dir = run_dir + # r.controller_params = { + # 'OD_Mode': 1, + # 'DISCON': { + # 'Echo': True, + # }} # Use OutData in control + r.rosco_dir = rosco_dir + + r.run_FAST() + + + +if __name__=="__main__": + main() \ No newline at end of file From 099532bc77e06d8d288b8d5dea2ffa2b8c44ea9e Mon Sep 17 00:00:00 2001 From: dzalkind Date: Mon, 3 Apr 2023 16:25:56 -0600 Subject: [PATCH 093/224] Finish merge with awc inputs and registry --- ROSCO/src/ROSCO_IO.f90 | 206 +++++++++--------- Test_Cases/BAR_10/BAR_10_DISCON.IN | 12 +- .../DISCON-UMaineSemi.IN | 12 +- Test_Cases/NREL-5MW/DISCON.IN | 12 +- .../NREL_2p8_127/NREL-2p8-127_DISCON.IN | 18 +- 5 files changed, 145 insertions(+), 115 deletions(-) diff --git a/ROSCO/src/ROSCO_IO.f90 b/ROSCO/src/ROSCO_IO.f90 index 5f53a1ce..6a4911f5 100644 --- a/ROSCO/src/ROSCO_IO.f90 +++ b/ROSCO/src/ROSCO_IO.f90 @@ -64,6 +64,8 @@ SUBROUTINE WriteRestartFile(LocalVar, CntrPar, ErrVar, objInst, RootName, size_a WRITE( Un, IOSTAT=ErrStat) LocalVar%FA_PitCom(2) WRITE( Un, IOSTAT=ErrStat) LocalVar%FA_PitCom(3) WRITE( Un, IOSTAT=ErrStat) LocalVar%RotSpeedF + WRITE( Un, IOSTAT=ErrStat) LocalVar%VS_RefSpd + WRITE( Un, IOSTAT=ErrStat) LocalVar%PC_RefSpd WRITE( Un, IOSTAT=ErrStat) LocalVar%GenSpeedF WRITE( Un, IOSTAT=ErrStat) LocalVar%GenTq WRITE( Un, IOSTAT=ErrStat) LocalVar%GenTqMeas @@ -333,6 +335,8 @@ SUBROUTINE ReadRestartFile(avrSWAP, LocalVar, CntrPar, objInst, PerfData, RootNa READ( Un, IOSTAT=ErrStat) LocalVar%FA_PitCom(2) READ( Un, IOSTAT=ErrStat) LocalVar%FA_PitCom(3) READ( Un, IOSTAT=ErrStat) LocalVar%RotSpeedF + READ( Un, IOSTAT=ErrStat) LocalVar%VS_RefSpd + READ( Un, IOSTAT=ErrStat) LocalVar%PC_RefSpd READ( Un, IOSTAT=ErrStat) LocalVar%GenSpeedF READ( Un, IOSTAT=ErrStat) LocalVar%GenTq READ( Un, IOSTAT=ErrStat) LocalVar%GenTqMeas @@ -621,7 +625,7 @@ SUBROUTINE Debug(LocalVar, CntrPar, DebugVar, ErrVar, avrSWAP, RootName, size_av '[rad/s]', '[rad/s]', '[m/s]', '[rad]', '[rad]', & '[N/A]', '[N/A]', '[N/A]', '[N/A]', '[rad/s]', & '[deg]', '[deg]', '[deg]', '[N/A]'] - nLocalVars = 100 + nLocalVars = 102 Allocate(LocalVarOutData(nLocalVars)) Allocate(LocalVarOutStrings(nLocalVars)) LocalVarOutData(1) = LocalVar%iStatus @@ -645,106 +649,108 @@ SUBROUTINE Debug(LocalVar, CntrPar, DebugVar, ErrVar, avrSWAP, RootName, size_av LocalVarOutData(19) = LocalVar%FA_AccHPFI LocalVarOutData(20) = LocalVar%FA_PitCom(1) LocalVarOutData(21) = LocalVar%RotSpeedF - LocalVarOutData(22) = LocalVar%GenSpeedF - LocalVarOutData(23) = LocalVar%GenTq - LocalVarOutData(24) = LocalVar%GenTqMeas - LocalVarOutData(25) = LocalVar%GenArTq - LocalVarOutData(26) = LocalVar%GenBrTq - LocalVarOutData(27) = LocalVar%IPC_PitComF(1) - LocalVarOutData(28) = LocalVar%PC_KP - LocalVarOutData(29) = LocalVar%PC_KI - LocalVarOutData(30) = LocalVar%PC_KD - LocalVarOutData(31) = LocalVar%PC_TF - LocalVarOutData(32) = LocalVar%PC_MaxPit - LocalVarOutData(33) = LocalVar%PC_MinPit - LocalVarOutData(34) = LocalVar%PC_PitComT - LocalVarOutData(35) = LocalVar%PC_PitComT_Last - LocalVarOutData(36) = LocalVar%PC_PitComTF - LocalVarOutData(37) = LocalVar%PC_PitComT_IPC(1) - LocalVarOutData(38) = LocalVar%PC_PwrErr - LocalVarOutData(39) = LocalVar%PC_SpdErr - LocalVarOutData(40) = LocalVar%IPC_AxisTilt_1P - LocalVarOutData(41) = LocalVar%IPC_AxisYaw_1P - LocalVarOutData(42) = LocalVar%IPC_AxisTilt_2P - LocalVarOutData(43) = LocalVar%IPC_AxisYaw_2P - LocalVarOutData(44) = LocalVar%axisTilt_1P - LocalVarOutData(45) = LocalVar%axisYaw_1P - LocalVarOutData(46) = LocalVar%axisYawF_1P - LocalVarOutData(47) = LocalVar%axisTilt_2P - LocalVarOutData(48) = LocalVar%axisYaw_2P - LocalVarOutData(49) = LocalVar%axisYawF_2P - LocalVarOutData(50) = LocalVar%IPC_KI(1) - LocalVarOutData(51) = LocalVar%IPC_KP(1) - LocalVarOutData(52) = LocalVar%IPC_IntSat - LocalVarOutData(53) = LocalVar%PC_State - LocalVarOutData(54) = LocalVar%PitCom(1) - LocalVarOutData(55) = LocalVar%PitComAct(1) - LocalVarOutData(56) = LocalVar%SS_DelOmegaF - LocalVarOutData(57) = LocalVar%TestType - LocalVarOutData(58) = LocalVar%VS_MaxTq - LocalVarOutData(59) = LocalVar%VS_LastGenTrq - LocalVarOutData(60) = LocalVar%VS_LastGenPwr - LocalVarOutData(61) = LocalVar%VS_MechGenPwr - LocalVarOutData(62) = LocalVar%VS_SpdErrAr - LocalVarOutData(63) = LocalVar%VS_SpdErrBr - LocalVarOutData(64) = LocalVar%VS_SpdErr - LocalVarOutData(65) = LocalVar%VS_State - LocalVarOutData(66) = LocalVar%VS_Rgn3Pitch - LocalVarOutData(67) = LocalVar%WE_Vw - LocalVarOutData(68) = LocalVar%WE_Vw_F - LocalVarOutData(69) = LocalVar%WE_VwI - LocalVarOutData(70) = LocalVar%WE_VwIdot - LocalVarOutData(71) = LocalVar%VS_LastGenTrqF - LocalVarOutData(72) = LocalVar%Fl_PitCom - LocalVarOutData(73) = LocalVar%NACIMU_FA_AccF - LocalVarOutData(74) = LocalVar%FA_AccF - LocalVarOutData(75) = LocalVar%PtfmTDX - LocalVarOutData(76) = LocalVar%PtfmTDY - LocalVarOutData(77) = LocalVar%PtfmTDZ - LocalVarOutData(78) = LocalVar%PtfmRDX - LocalVarOutData(79) = LocalVar%PtfmRDY - LocalVarOutData(80) = LocalVar%PtfmRDZ - LocalVarOutData(81) = LocalVar%PtfmTVX - LocalVarOutData(82) = LocalVar%PtfmTVY - LocalVarOutData(83) = LocalVar%PtfmTVZ - LocalVarOutData(84) = LocalVar%PtfmRVX - LocalVarOutData(85) = LocalVar%PtfmRVY - LocalVarOutData(86) = LocalVar%PtfmRVZ - LocalVarOutData(87) = LocalVar%PtfmTAX - LocalVarOutData(88) = LocalVar%PtfmTAY - LocalVarOutData(89) = LocalVar%PtfmTAZ - LocalVarOutData(90) = LocalVar%PtfmRAX - LocalVarOutData(91) = LocalVar%PtfmRAY - LocalVarOutData(92) = LocalVar%PtfmRAZ - LocalVarOutData(93) = LocalVar%CC_DesiredL(1) - LocalVarOutData(94) = LocalVar%CC_ActuatedL(1) - LocalVarOutData(95) = LocalVar%CC_ActuatedDL(1) - LocalVarOutData(96) = LocalVar%StC_Input(1) - LocalVarOutData(97) = LocalVar%Flp_Angle(1) - LocalVarOutData(98) = LocalVar%RootMyb_Last(1) - LocalVarOutData(99) = LocalVar%ACC_INFILE_SIZE - LocalVarOutData(100) = LocalVar%AWC_complexangle(1) + LocalVarOutData(22) = LocalVar%VS_RefSpd + LocalVarOutData(23) = LocalVar%PC_RefSpd + LocalVarOutData(24) = LocalVar%GenSpeedF + LocalVarOutData(25) = LocalVar%GenTq + LocalVarOutData(26) = LocalVar%GenTqMeas + LocalVarOutData(27) = LocalVar%GenArTq + LocalVarOutData(28) = LocalVar%GenBrTq + LocalVarOutData(29) = LocalVar%IPC_PitComF(1) + LocalVarOutData(30) = LocalVar%PC_KP + LocalVarOutData(31) = LocalVar%PC_KI + LocalVarOutData(32) = LocalVar%PC_KD + LocalVarOutData(33) = LocalVar%PC_TF + LocalVarOutData(34) = LocalVar%PC_MaxPit + LocalVarOutData(35) = LocalVar%PC_MinPit + LocalVarOutData(36) = LocalVar%PC_PitComT + LocalVarOutData(37) = LocalVar%PC_PitComT_Last + LocalVarOutData(38) = LocalVar%PC_PitComTF + LocalVarOutData(39) = LocalVar%PC_PitComT_IPC(1) + LocalVarOutData(40) = LocalVar%PC_PwrErr + LocalVarOutData(41) = LocalVar%PC_SpdErr + LocalVarOutData(42) = LocalVar%IPC_AxisTilt_1P + LocalVarOutData(43) = LocalVar%IPC_AxisYaw_1P + LocalVarOutData(44) = LocalVar%IPC_AxisTilt_2P + LocalVarOutData(45) = LocalVar%IPC_AxisYaw_2P + LocalVarOutData(46) = LocalVar%axisTilt_1P + LocalVarOutData(47) = LocalVar%axisYaw_1P + LocalVarOutData(48) = LocalVar%axisYawF_1P + LocalVarOutData(49) = LocalVar%axisTilt_2P + LocalVarOutData(50) = LocalVar%axisYaw_2P + LocalVarOutData(51) = LocalVar%axisYawF_2P + LocalVarOutData(52) = LocalVar%IPC_KI(1) + LocalVarOutData(53) = LocalVar%IPC_KP(1) + LocalVarOutData(54) = LocalVar%IPC_IntSat + LocalVarOutData(55) = LocalVar%PC_State + LocalVarOutData(56) = LocalVar%PitCom(1) + LocalVarOutData(57) = LocalVar%PitComAct(1) + LocalVarOutData(58) = LocalVar%SS_DelOmegaF + LocalVarOutData(59) = LocalVar%TestType + LocalVarOutData(60) = LocalVar%VS_MaxTq + LocalVarOutData(61) = LocalVar%VS_LastGenTrq + LocalVarOutData(62) = LocalVar%VS_LastGenPwr + LocalVarOutData(63) = LocalVar%VS_MechGenPwr + LocalVarOutData(64) = LocalVar%VS_SpdErrAr + LocalVarOutData(65) = LocalVar%VS_SpdErrBr + LocalVarOutData(66) = LocalVar%VS_SpdErr + LocalVarOutData(67) = LocalVar%VS_State + LocalVarOutData(68) = LocalVar%VS_Rgn3Pitch + LocalVarOutData(69) = LocalVar%WE_Vw + LocalVarOutData(70) = LocalVar%WE_Vw_F + LocalVarOutData(71) = LocalVar%WE_VwI + LocalVarOutData(72) = LocalVar%WE_VwIdot + LocalVarOutData(73) = LocalVar%VS_LastGenTrqF + LocalVarOutData(74) = LocalVar%Fl_PitCom + LocalVarOutData(75) = LocalVar%NACIMU_FA_AccF + LocalVarOutData(76) = LocalVar%FA_AccF + LocalVarOutData(77) = LocalVar%PtfmTDX + LocalVarOutData(78) = LocalVar%PtfmTDY + LocalVarOutData(79) = LocalVar%PtfmTDZ + LocalVarOutData(80) = LocalVar%PtfmRDX + LocalVarOutData(81) = LocalVar%PtfmRDY + LocalVarOutData(82) = LocalVar%PtfmRDZ + LocalVarOutData(83) = LocalVar%PtfmTVX + LocalVarOutData(84) = LocalVar%PtfmTVY + LocalVarOutData(85) = LocalVar%PtfmTVZ + LocalVarOutData(86) = LocalVar%PtfmRVX + LocalVarOutData(87) = LocalVar%PtfmRVY + LocalVarOutData(88) = LocalVar%PtfmRVZ + LocalVarOutData(89) = LocalVar%PtfmTAX + LocalVarOutData(90) = LocalVar%PtfmTAY + LocalVarOutData(91) = LocalVar%PtfmTAZ + LocalVarOutData(92) = LocalVar%PtfmRAX + LocalVarOutData(93) = LocalVar%PtfmRAY + LocalVarOutData(94) = LocalVar%PtfmRAZ + LocalVarOutData(95) = LocalVar%CC_DesiredL(1) + LocalVarOutData(96) = LocalVar%CC_ActuatedL(1) + LocalVarOutData(97) = LocalVar%CC_ActuatedDL(1) + LocalVarOutData(98) = LocalVar%StC_Input(1) + LocalVarOutData(99) = LocalVar%Flp_Angle(1) + LocalVarOutData(100) = LocalVar%RootMyb_Last(1) + LocalVarOutData(101) = LocalVar%ACC_INFILE_SIZE + LocalVarOutData(102) = LocalVar%AWC_complexangle(1) LocalVarOutStrings = [CHARACTER(15) :: 'iStatus', 'Time', 'DT', 'VS_GenPwr', 'GenSpeed', & 'RotSpeed', 'NacHeading', 'NacVane', 'HorWindV', 'rootMOOP', & 'rootMOOPF', 'BlPitch', 'BlPitchCMeas', 'Azimuth', 'NumBl', & 'FA_Acc', 'NacIMU_FA_Acc', 'FA_AccHPF', 'FA_AccHPFI', 'FA_PitCom', & - 'RotSpeedF', 'GenSpeedF', 'GenTq', 'GenTqMeas', 'GenArTq', & - 'GenBrTq', 'IPC_PitComF', 'PC_KP', 'PC_KI', 'PC_KD', & - 'PC_TF', 'PC_MaxPit', 'PC_MinPit', 'PC_PitComT', 'PC_PitComT_Last', & - 'PC_PitComTF', 'PC_PitComT_IPC', 'PC_PwrErr', 'PC_SpdErr', 'IPC_AxisTilt_1P', & - 'IPC_AxisYaw_1P', 'IPC_AxisTilt_2P', 'IPC_AxisYaw_2P', 'axisTilt_1P', 'axisYaw_1P', & - 'axisYawF_1P', 'axisTilt_2P', 'axisYaw_2P', 'axisYawF_2P', 'IPC_KI', & - 'IPC_KP', 'IPC_IntSat', 'PC_State', 'PitCom', 'PitComAct', & - 'SS_DelOmegaF', 'TestType', 'VS_MaxTq', 'VS_LastGenTrq', 'VS_LastGenPwr', & - 'VS_MechGenPwr', 'VS_SpdErrAr', 'VS_SpdErrBr', 'VS_SpdErr', 'VS_State', & - 'VS_Rgn3Pitch', 'WE_Vw', 'WE_Vw_F', 'WE_VwI', 'WE_VwIdot', & - 'VS_LastGenTrqF', 'Fl_PitCom', 'NACIMU_FA_AccF', 'FA_AccF', 'PtfmTDX', & - 'PtfmTDY', 'PtfmTDZ', 'PtfmRDX', 'PtfmRDY', 'PtfmRDZ', & - 'PtfmTVX', 'PtfmTVY', 'PtfmTVZ', 'PtfmRVX', 'PtfmRVY', & - 'PtfmRVZ', 'PtfmTAX', 'PtfmTAY', 'PtfmTAZ', 'PtfmRAX', & - 'PtfmRAY', 'PtfmRAZ', 'CC_DesiredL', 'CC_ActuatedL', 'CC_ActuatedDL', & - 'StC_Input', 'Flp_Angle', 'RootMyb_Last', 'ACC_INFILE_SIZE', 'AWC_complexangle' & - ] + 'RotSpeedF', 'VS_RefSpd', 'PC_RefSpd', 'GenSpeedF', 'GenTq', & + 'GenTqMeas', 'GenArTq', 'GenBrTq', 'IPC_PitComF', 'PC_KP', & + 'PC_KI', 'PC_KD', 'PC_TF', 'PC_MaxPit', 'PC_MinPit', & + 'PC_PitComT', 'PC_PitComT_Last', 'PC_PitComTF', 'PC_PitComT_IPC', 'PC_PwrErr', & + 'PC_SpdErr', 'IPC_AxisTilt_1P', 'IPC_AxisYaw_1P', 'IPC_AxisTilt_2P', 'IPC_AxisYaw_2P', & + 'axisTilt_1P', 'axisYaw_1P', 'axisYawF_1P', 'axisTilt_2P', 'axisYaw_2P', & + 'axisYawF_2P', 'IPC_KI', 'IPC_KP', 'IPC_IntSat', 'PC_State', & + 'PitCom', 'PitComAct', 'SS_DelOmegaF', 'TestType', 'VS_MaxTq', & + 'VS_LastGenTrq', 'VS_LastGenPwr', 'VS_MechGenPwr', 'VS_SpdErrAr', 'VS_SpdErrBr', & + 'VS_SpdErr', 'VS_State', 'VS_Rgn3Pitch', 'WE_Vw', 'WE_Vw_F', & + 'WE_VwI', 'WE_VwIdot', 'VS_LastGenTrqF', 'Fl_PitCom', 'NACIMU_FA_AccF', & + 'FA_AccF', 'PtfmTDX', 'PtfmTDY', 'PtfmTDZ', 'PtfmRDX', & + 'PtfmRDY', 'PtfmRDZ', 'PtfmTVX', 'PtfmTVY', 'PtfmTVZ', & + 'PtfmRVX', 'PtfmRVY', 'PtfmRVZ', 'PtfmTAX', 'PtfmTAY', & + 'PtfmTAZ', 'PtfmRAX', 'PtfmRAY', 'PtfmRAZ', 'CC_DesiredL', & + 'CC_ActuatedL', 'CC_ActuatedDL', 'StC_Input', 'Flp_Angle', 'RootMyb_Last', & + 'ACC_INFILE_SIZE', 'AWC_complexangle'] ! Initialize debug file IF ((LocalVar%iStatus == 0) .OR. (LocalVar%iStatus == -9)) THEN ! .TRUE. if we're on the first call to the DLL IF (CntrPar%LoggingLevel > 0) THEN @@ -759,8 +765,8 @@ SUBROUTINE Debug(LocalVar, CntrPar, DebugVar, ErrVar, avrSWAP, RootName, size_av CALL GetNewUnit(UnDb2, ErrVar) OPEN(unit=UnDb2, FILE=TRIM(RootName)//'.RO.dbg2') WRITE(UnDb2, *) 'Generated on '//CurDate()//' at '//CurTime()//' using ROSCO-'//TRIM(rosco_version) - WRITE(UnDb2, '(101(a20,TR5:))') 'Time', LocalVarOutStrings - WRITE(UnDb2, '(101(a20,TR5:))') + WRITE(UnDb2, '(103(a20,TR5:))') 'Time', LocalVarOutStrings + WRITE(UnDb2, '(103(a20,TR5:))') END IF IF (CntrPar%LoggingLevel > 2) THEN @@ -817,7 +823,7 @@ SUBROUTINE Debug(LocalVar, CntrPar, DebugVar, ErrVar, avrSWAP, RootName, size_av END DO ! Write debug files - FmtDat = "(F20.5,TR5,100(ES20.5E2,TR5:))" ! The format of the debugging data + FmtDat = "(F20.5,TR5,102(ES20.5E2,TR5:))" ! The format of the debugging data IF(CntrPar%LoggingLevel > 0) THEN WRITE (UnDb, TRIM(FmtDat)) LocalVar%Time, DebugOutData END IF diff --git a/Test_Cases/BAR_10/BAR_10_DISCON.IN b/Test_Cases/BAR_10/BAR_10_DISCON.IN index 6bdb4e12..c0f3cc01 100644 --- a/Test_Cases/BAR_10/BAR_10_DISCON.IN +++ b/Test_Cases/BAR_10/BAR_10_DISCON.IN @@ -1,5 +1,5 @@ ! Controller parameter input file for the BAR_10 wind turbine -! - File written using ROSCO version 2.7.0 controller tuning logic on 03/20/23 +! - File written using ROSCO version 2.7.0 controller tuning logic on 04/03/23 !------- DEBUG ------------------------------------------------------------ 1 ! LoggingLevel - (0: write no debug files, 1: write standard output .dbg-file, 2: LoggingLevel 1 + ROSCO LocalVars (.dbg2) 3: LoggingLevel 2 + complete avrSWAP-array (.dbg3)) @@ -13,6 +13,7 @@ 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} +0 ! PRC_Mode - Power reference tracking mode{0: use standard rotor speed set points, 1: use PRC rotor speed setpoints} 2 ! WE_Mode - Wind speed estimator mode {0: One-second low pass filtered hub height wind speed, 1: Immersion and Invariance Estimator, 2: Extended Kalman Filter} 1 ! PS_Mode - Pitch saturation mode {0: no pitch saturation, 1: implement pitch saturation} 0 ! SD_Mode - Shutdown mode {0: no shutdown procedure, 1: pitch to max pitch at shutdown} @@ -84,6 +85,11 @@ 1.00000 ! SS_VSGain - Variable speed torque controller setpoint smoother gain, [-]. 0.00100 ! SS_PCGain - Collective pitch controller setpoint smoother gain, [-]. +!------- POWER REFERENCE TRACKING -------------------------------------- +2 ! PRC_n - Number of elements in PRC_WindSpeeds and PRC_RotorSpeeds array +3.000 25.000 ! PRC_WindSpeeds - Array of wind speeds used in rotor speed vs. wind speed lookup table [m/s]. +0.792 0.792 ! PRC_RotorSpeeds - Array of rotor speeds corresponding to PRC_WindSpeeds [rad/s]. + !------- WIND SPEED ESTIMATOR --------------------------------------------- 102.996 ! WE_BladeRadius - Blade length (distance from hub center to blade tip), [m] 1 ! WE_CP_n - Amount of parameters in the Cp array @@ -114,8 +120,8 @@ !------- MINIMUM PITCH SATURATION ------------------------------------------- 60 ! PS_BldPitchMin_N - Number of values in minimum blade pitch lookup table (should equal number of values in PS_WindSpeeds and PS_BldPitchMin) -3.0000 3.1818 3.3637 3.5455 3.7274 3.9092 4.0911 4.2729 4.4548 4.6366 4.8185 5.0003 5.1822 5.3640 5.5459 5.7277 5.9096 6.0914 6.2732 6.4551 6.6369 6.8188 7.0006 7.1825 7.3643 7.5462 7.7280 7.9099 8.0917 8.2736 8.8311 9.3887 9.9462 10.5038 11.0613 11.6188 12.1764 12.7339 13.2915 13.8490 14.4066 14.9641 15.5217 16.0792 16.6368 17.1943 17.7519 18.3094 18.8670 19.4245 19.9821 20.5396 21.0972 21.6547 22.2123 22.7698 23.3274 23.8849 24.4425 25.0000 ! PS_WindSpeeds - Wind speeds corresponding to minimum blade pitch angles [m/s] --0.01505486 -0.01505486 -0.01505486 -0.01505486 -0.01505486 -0.01505486 -0.01505486 -0.01505486 -0.01505486 -0.01505486 -0.01505486 -0.01505486 -0.01505486 -0.01505486 -0.01505486 -0.01505486 -0.01505486 -0.01505486 -0.01505486 -0.01505486 -0.01505486 -0.01505486 -0.01505486 -0.01505486 -0.01247538 0.00009416 0.01064594 0.02025612 0.02875892 0.04130468 0.05575026 0.06941162 0.08245994 0.09516301 0.10759186 0.11974680 0.13166674 0.14343508 0.15503135 0.16644975 0.17776272 0.18893241 0.19997037 0.21092550 0.22173526 0.23245676 0.24309225 0.25359679 0.26404201 0.27436979 0.28461736 0.29478565 0.30484212 0.31485020 0.32473305 0.33456481 0.34429551 0.35395031 0.36352600 0.37300643 ! PS_BldPitchMin - Minimum blade pitch angles [rad] +3.000 3.182 3.364 3.546 3.727 3.909 4.091 4.273 4.455 4.637 4.818 5.000 5.182 5.364 5.546 5.728 5.910 6.091 6.273 6.455 6.637 6.819 7.001 7.182 7.364 7.546 7.728 7.910 8.092 8.274 8.831 9.389 9.946 10.504 11.061 11.619 12.176 12.734 13.291 13.849 14.407 14.964 15.522 16.079 16.637 17.194 17.752 18.309 18.867 19.425 19.982 20.540 21.097 21.655 22.212 22.770 23.327 23.885 24.442 25.000 ! PS_WindSpeeds - Wind speeds corresponding to minimum blade pitch angles [m/s] +-0.015 -0.015 -0.015 -0.015 -0.015 -0.015 -0.015 -0.015 -0.015 -0.015 -0.015 -0.015 -0.015 -0.015 -0.015 -0.015 -0.015 -0.015 -0.015 -0.015 -0.015 -0.015 -0.015 -0.015 -0.012 0.000 0.011 0.020 0.029 0.041 0.056 0.069 0.082 0.095 0.108 0.120 0.132 0.143 0.155 0.166 0.178 0.189 0.200 0.211 0.222 0.232 0.243 0.254 0.264 0.274 0.285 0.295 0.305 0.315 0.325 0.335 0.344 0.354 0.364 0.373 ! PS_BldPitchMin - Minimum blade pitch angles [rad] !------- SHUTDOWN ----------------------------------------------------------- 0.698100000000 ! SD_MaxPit - Maximum blade pitch angle to initiate shutdown, [rad] diff --git a/Test_Cases/IEA-15-240-RWT-UMaineSemi/DISCON-UMaineSemi.IN b/Test_Cases/IEA-15-240-RWT-UMaineSemi/DISCON-UMaineSemi.IN index 078319ac..0c06ce7c 100644 --- a/Test_Cases/IEA-15-240-RWT-UMaineSemi/DISCON-UMaineSemi.IN +++ b/Test_Cases/IEA-15-240-RWT-UMaineSemi/DISCON-UMaineSemi.IN @@ -1,5 +1,5 @@ ! Controller parameter input file for the IEA-15-240-RWT-UMaineSemi wind turbine -! - File written using ROSCO version 2.7.0 controller tuning logic on 03/20/23 +! - File written using ROSCO version 2.7.0 controller tuning logic on 04/03/23 !------- DEBUG ------------------------------------------------------------ 2 ! LoggingLevel - (0: write no debug files, 1: write standard output .dbg-file, 2: LoggingLevel 1 + ROSCO LocalVars (.dbg2) 3: LoggingLevel 2 + complete avrSWAP-array (.dbg3)) @@ -13,6 +13,7 @@ 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} +0 ! PRC_Mode - Power reference tracking mode{0: use standard rotor speed set points, 1: use PRC rotor speed setpoints} 2 ! WE_Mode - Wind speed estimator mode {0: One-second low pass filtered hub height wind speed, 1: Immersion and Invariance Estimator, 2: Extended Kalman Filter} 1 ! PS_Mode - Pitch saturation mode {0: no pitch saturation, 1: implement pitch saturation} 0 ! SD_Mode - Shutdown mode {0: no shutdown procedure, 1: pitch to max pitch at shutdown} @@ -84,6 +85,11 @@ 1.00000 ! SS_VSGain - Variable speed torque controller setpoint smoother gain, [-]. 0.00100 ! SS_PCGain - Collective pitch controller setpoint smoother gain, [-]. +!------- POWER REFERENCE TRACKING -------------------------------------- +2 ! PRC_n - Number of elements in PRC_WindSpeeds and PRC_RotorSpeeds array +3.000 25.000 ! PRC_WindSpeeds - Array of wind speeds used in rotor speed vs. wind speed lookup table [m/s]. +0.792 0.792 ! PRC_RotorSpeeds - Array of rotor speeds corresponding to PRC_WindSpeeds [rad/s]. + !------- WIND SPEED ESTIMATOR --------------------------------------------- 120.000 ! WE_BladeRadius - Blade length (distance from hub center to blade tip), [m] 1 ! WE_CP_n - Amount of parameters in the Cp array @@ -114,8 +120,8 @@ !------- MINIMUM PITCH SATURATION ------------------------------------------- 60 ! PS_BldPitchMin_N - Number of values in minimum blade pitch lookup table (should equal number of values in PS_WindSpeeds and PS_BldPitchMin) -3.0000 3.2669 3.5338 3.8007 4.0676 4.3345 4.6014 4.8683 5.1352 5.4021 5.6690 5.9359 6.2028 6.4697 6.7366 7.0034 7.2703 7.5372 7.8041 8.0710 8.3379 8.6048 8.8717 9.1386 9.4055 9.6724 9.9393 10.2062 10.4731 10.7400 11.2153 11.6907 12.1660 12.6413 13.1167 13.5920 14.0673 14.5427 15.0180 15.4933 15.9687 16.4440 16.9193 17.3947 17.8700 18.3453 18.8207 19.2960 19.7713 20.2467 20.7220 21.1973 21.6727 22.1480 22.6233 23.0987 23.5740 24.0493 24.5247 25.0000 ! PS_WindSpeeds - Wind speeds corresponding to minimum blade pitch angles [m/s] -0.05997374 0.05997374 0.05997374 0.05997374 0.05997374 0.05995230 0.05568017 0.05139305 0.04630957 0.04053154 0.03444871 0.02774193 0.02083682 0.01377992 0.00660717 0.00000000 0.00000000 0.00000000 0.00000000 0.00000000 0.00000000 0.00000000 0.00000000 0.00000000 0.00000000 0.00798358 0.02222567 0.03475505 0.04563791 0.05328450 0.06405592 0.07436594 0.08427713 0.09385932 0.10323575 0.11234777 0.12134295 0.13011531 0.13881511 0.14732690 0.15578898 0.16409463 0.17235500 0.18049466 0.18858365 0.19658691 0.20452181 0.21241204 0.22021131 0.22800500 0.23567545 0.24336643 0.25094186 0.25851588 0.26602564 0.27348266 0.28093357 0.28828297 0.29566389 0.30293290 ! PS_BldPitchMin - Minimum blade pitch angles [rad] +3.000 3.267 3.534 3.801 4.068 4.334 4.601 4.868 5.135 5.402 5.669 5.936 6.203 6.470 6.737 7.003 7.270 7.537 7.804 8.071 8.338 8.605 8.872 9.139 9.406 9.672 9.939 10.206 10.473 10.740 11.215 11.691 12.166 12.641 13.117 13.592 14.067 14.543 15.018 15.493 15.969 16.444 16.919 17.395 17.870 18.345 18.821 19.296 19.771 20.247 20.722 21.197 21.673 22.148 22.623 23.099 23.574 24.049 24.525 25.000 ! PS_WindSpeeds - Wind speeds corresponding to minimum blade pitch angles [m/s] +0.060 0.060 0.060 0.060 0.060 0.060 0.056 0.051 0.046 0.041 0.034 0.028 0.021 0.014 0.007 0.000 0.000 0.000 0.000 0.000 0.000 0.000 0.000 0.000 0.000 0.008 0.022 0.035 0.046 0.053 0.064 0.074 0.084 0.094 0.103 0.112 0.121 0.130 0.139 0.147 0.156 0.164 0.172 0.180 0.189 0.197 0.205 0.212 0.220 0.228 0.236 0.243 0.251 0.259 0.266 0.273 0.281 0.288 0.296 0.303 ! PS_BldPitchMin - Minimum blade pitch angles [rad] !------- SHUTDOWN ----------------------------------------------------------- 0.698100000000 ! SD_MaxPit - Maximum blade pitch angle to initiate shutdown, [rad] diff --git a/Test_Cases/NREL-5MW/DISCON.IN b/Test_Cases/NREL-5MW/DISCON.IN index 60775ec0..fa0132b9 100644 --- a/Test_Cases/NREL-5MW/DISCON.IN +++ b/Test_Cases/NREL-5MW/DISCON.IN @@ -1,5 +1,5 @@ ! Controller parameter input file for the NREL-5MW wind turbine -! - File written using ROSCO version 2.7.0 controller tuning logic on 03/20/23 +! - File written using ROSCO version 2.7.0 controller tuning logic on 04/03/23 !------- DEBUG ------------------------------------------------------------ 1 ! LoggingLevel - (0: write no debug files, 1: write standard output .dbg-file, 2: LoggingLevel 1 + ROSCO LocalVars (.dbg2) 3: LoggingLevel 2 + complete avrSWAP-array (.dbg3)) @@ -13,6 +13,7 @@ 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} +0 ! PRC_Mode - Power reference tracking mode{0: use standard rotor speed set points, 1: use PRC rotor speed setpoints} 2 ! WE_Mode - Wind speed estimator mode {0: One-second low pass filtered hub height wind speed, 1: Immersion and Invariance Estimator, 2: Extended Kalman Filter} 1 ! PS_Mode - Pitch saturation mode {0: no pitch saturation, 1: implement pitch saturation} 0 ! SD_Mode - Shutdown mode {0: no shutdown procedure, 1: pitch to max pitch at shutdown} @@ -84,6 +85,11 @@ 1.00000 ! SS_VSGain - Variable speed torque controller setpoint smoother gain, [-]. 0.00100 ! SS_PCGain - Collective pitch controller setpoint smoother gain, [-]. +!------- POWER REFERENCE TRACKING -------------------------------------- +2 ! PRC_n - Number of elements in PRC_WindSpeeds and PRC_RotorSpeeds array +3.000 25.000 ! PRC_WindSpeeds - Array of wind speeds used in rotor speed vs. wind speed lookup table [m/s]. +0.792 0.792 ! PRC_RotorSpeeds - Array of rotor speeds corresponding to PRC_WindSpeeds [rad/s]. + !------- WIND SPEED ESTIMATOR --------------------------------------------- 63.000 ! WE_BladeRadius - Blade length (distance from hub center to blade tip), [m] 1 ! WE_CP_n - Amount of parameters in the Cp array @@ -114,8 +120,8 @@ !------- MINIMUM PITCH SATURATION ------------------------------------------- 60 ! PS_BldPitchMin_N - Number of values in minimum blade pitch lookup table (should equal number of values in PS_WindSpeeds and PS_BldPitchMin) -3.0000 3.2897 3.5793 3.8690 4.1586 4.4483 4.7379 5.0276 5.3172 5.6069 5.8966 6.1862 6.4759 6.7655 7.0552 7.3448 7.6345 7.9241 8.2138 8.5034 8.7931 9.0828 9.3724 9.6621 9.9517 10.2414 10.5310 10.8207 11.1103 11.4000 11.8533 12.3067 12.7600 13.2133 13.6667 14.1200 14.5733 15.0267 15.4800 15.9333 16.3867 16.8400 17.2933 17.7467 18.2000 18.6533 19.1067 19.5600 20.0133 20.4667 20.9200 21.3733 21.8267 22.2800 22.7333 23.1867 23.6400 24.0933 24.5467 25.0000 ! PS_WindSpeeds - Wind speeds corresponding to minimum blade pitch angles [m/s] -0.00088027 0.00088027 0.00088027 0.00088027 0.00088027 0.00088027 0.00088027 0.00088027 0.00088027 0.00088027 0.00088027 0.00088027 0.00088027 0.00088027 0.00088027 0.00088027 0.00088027 0.00088027 0.00088027 0.00088027 0.00088027 0.00088027 0.00088027 0.00088027 0.00088027 0.01116187 0.02310060 0.03164156 0.03968639 0.04741131 0.05899071 0.07019329 0.08090119 0.09141661 0.10169361 0.11174124 0.12170066 0.13137494 0.14103377 0.15048120 0.15989580 0.16913227 0.17831010 0.18739638 0.19643591 0.20537011 0.21419674 0.22293719 0.23161365 0.24025975 0.24885012 0.25735704 0.26578040 0.27407178 0.28233051 0.29047594 0.29867838 0.30674517 0.31490089 0.32284411 ! PS_BldPitchMin - Minimum blade pitch angles [rad] +3.000 3.290 3.579 3.869 4.159 4.448 4.738 5.028 5.317 5.607 5.897 6.186 6.476 6.766 7.055 7.345 7.634 7.924 8.214 8.503 8.793 9.083 9.372 9.662 9.952 10.241 10.531 10.821 11.110 11.400 11.853 12.307 12.760 13.213 13.667 14.120 14.573 15.027 15.480 15.933 16.387 16.840 17.293 17.747 18.200 18.653 19.107 19.560 20.013 20.467 20.920 21.373 21.827 22.280 22.733 23.187 23.640 24.093 24.547 25.000 ! PS_WindSpeeds - Wind speeds corresponding to minimum blade pitch angles [m/s] +0.001 0.001 0.001 0.001 0.001 0.001 0.001 0.001 0.001 0.001 0.001 0.001 0.001 0.001 0.001 0.001 0.001 0.001 0.001 0.001 0.001 0.001 0.001 0.001 0.001 0.011 0.023 0.032 0.040 0.047 0.059 0.070 0.081 0.091 0.102 0.112 0.122 0.131 0.141 0.150 0.160 0.169 0.178 0.187 0.196 0.205 0.214 0.223 0.232 0.240 0.249 0.257 0.266 0.274 0.282 0.290 0.299 0.307 0.315 0.323 ! PS_BldPitchMin - Minimum blade pitch angles [rad] !------- SHUTDOWN ----------------------------------------------------------- 0.436300000000 ! SD_MaxPit - Maximum blade pitch angle to initiate shutdown, [rad] diff --git a/Test_Cases/NREL_2p8_127/NREL-2p8-127_DISCON.IN b/Test_Cases/NREL_2p8_127/NREL-2p8-127_DISCON.IN index 60215d61..7a60801d 100644 --- a/Test_Cases/NREL_2p8_127/NREL-2p8-127_DISCON.IN +++ b/Test_Cases/NREL_2p8_127/NREL-2p8-127_DISCON.IN @@ -1,18 +1,19 @@ ! Controller parameter input file for the NREL-2p8-127 wind turbine -! - File written using ROSCO version 2.7.0 controller tuning logic on 03/30/23 +! - File written using ROSCO version 2.7.0 controller tuning logic on 04/03/23 !------- DEBUG ------------------------------------------------------------ -1 ! LoggingLevel - (0: write no debug files, 1: write standard output .dbg-file, 2: LoggingLevel 1 + ROSCO LocalVars (.dbg2) 3: LoggingLevel 2 + complete avrSWAP-array (.dbg3)) +2 ! LoggingLevel - (0: write no debug files, 1: write standard output .dbg-file, 2: LoggingLevel 1 + ROSCO LocalVars (.dbg2) 3: LoggingLevel 2 + complete avrSWAP-array (.dbg3)) 0 ! Echo - (0 - no Echo, 1 - Echo input data to .echo) !------- 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 and/or tower fore-aft motion (for floating) {0: disable, 1: generator speed, 2: tower-top fore-aft motion, 3: generator speed and tower-top fore-aft motion} -0 ! IPC_ControlMode - Turn Individual Pitch Control (IPC) for fatigue load reductions (pitch contribution) {0: off, 1: 1P reductions, 2: 1P+2P reductions} +1 ! IPC_ControlMode - Turn Individual Pitch Control (IPC) for fatigue load reductions (pitch contribution) {0: off, 1: 1P reductions, 2: 1P+2P reductions} 3 ! VS_ControlMode - Generator torque control mode in above rated conditions {0: constant torque, 1: constant power, 2: TSR tracking PI control with constant torque, 3: TSR tracking PI control with constant power} 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} +0 ! PRC_Mode - Power reference tracking mode{0: use standard rotor speed set points, 1: use PRC rotor speed setpoints} 2 ! WE_Mode - Wind speed estimator mode {0: One-second low pass filtered hub height wind speed, 1: Immersion and Invariance Estimator, 2: Extended Kalman Filter} 1 ! PS_Mode - Pitch saturation mode {0: no pitch saturation, 1: implement pitch saturation} 0 ! SD_Mode - Shutdown mode {0: no shutdown procedure, 1: pitch to max pitch at shutdown} @@ -60,7 +61,7 @@ 2 ! IPC_SatMode - IPC Saturation method (0 - no saturation (except by PC_MinPit), 1 - saturate by PS_BldPitchMin, 2 - saturate sotfly (full IPC cycle) by PC_MinPit, 3 - saturate softly by PS_BldPitchMin) 0.3 ! IPC_IntSat - Integrator saturation (maximum signal amplitude contribution to pitch from IPC), [rad] 0.000e+00 0.000e+00 ! IPC_KP - Proportional gain for the individual pitch controller: first parameter for 1P reductions, second for 2P reductions, [-] -0.000e+00 0.000e+00 ! IPC_KI - Integral gain for the individual pitch controller: first parameter for 1P reductions, second for 2P reductions, [-] +5.200e-09 0.000e+00 ! IPC_KI - Integral gain for the individual pitch controller: first parameter for 1P reductions, second for 2P reductions, [-] 0.000000 0.000000 ! 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] @@ -84,6 +85,11 @@ 1.00000 ! SS_VSGain - Variable speed torque controller setpoint smoother gain, [-]. 0.00100 ! SS_PCGain - Collective pitch controller setpoint smoother gain, [-]. +!------- POWER REFERENCE TRACKING -------------------------------------- +2 ! PRC_n - Number of elements in PRC_WindSpeeds and PRC_RotorSpeeds array +3.000 25.000 ! PRC_WindSpeeds - Array of wind speeds used in rotor speed vs. wind speed lookup table [m/s]. +0.792 0.792 ! PRC_RotorSpeeds - Array of rotor speeds corresponding to PRC_WindSpeeds [rad/s]. + !------- WIND SPEED ESTIMATOR --------------------------------------------- 63.457 ! WE_BladeRadius - Blade length (distance from hub center to blade tip), [m] 1 ! WE_CP_n - Amount of parameters in the Cp array @@ -114,8 +120,8 @@ !------- MINIMUM PITCH SATURATION ------------------------------------------- 60 ! PS_BldPitchMin_N - Number of values in minimum blade pitch lookup table (should equal number of values in PS_WindSpeeds and PS_BldPitchMin) -3.0000 3.2897 3.5793 3.8690 4.1586 4.4483 4.7379 5.0276 5.3172 5.6069 5.8966 6.1862 6.4759 6.7655 7.0552 7.3448 7.6345 7.9241 8.2138 8.5034 8.7931 9.0828 9.3724 9.6621 9.9517 10.2414 10.5310 10.8207 11.1103 11.4000 11.8533 12.3067 12.7600 13.2133 13.6667 14.1200 14.5733 15.0267 15.4800 15.9333 16.3867 16.8400 17.2933 17.7467 18.2000 18.6533 19.1067 19.5600 20.0133 20.4667 20.9200 21.3733 21.8267 22.2800 22.7333 23.1867 23.6400 24.0933 24.5467 25.0000 ! PS_WindSpeeds - Wind speeds corresponding to minimum blade pitch angles [m/s] -0.00000000 0.00000000 0.00000000 0.00000000 0.00000000 0.00000000 0.00000000 0.00000000 0.00000000 0.00000000 0.00000000 0.00000000 0.00000000 0.00000000 0.00000000 0.00000000 0.00000000 0.00000000 0.00000000 0.00000000 0.00000000 0.00000000 0.00000000 0.01902632 0.03121162 0.04101621 0.04957537 0.05812141 0.06604528 0.07366393 0.08564088 0.09644430 0.10731742 0.11740081 0.12723365 0.13691718 0.14655371 0.15552079 0.16457871 0.17358206 0.18261499 0.19163393 0.20072294 0.20968649 0.21849678 0.22748802 0.23597095 0.24444734 0.25312967 0.26178025 0.27046099 0.27863869 0.28691931 0.29527580 0.30349928 0.31191439 0.32017189 0.32834804 0.33653924 0.34452172 ! PS_BldPitchMin - Minimum blade pitch angles [rad] +3.000 3.290 3.579 3.869 4.159 4.448 4.738 5.028 5.317 5.607 5.897 6.186 6.476 6.766 7.055 7.345 7.634 7.924 8.214 8.503 8.793 9.083 9.372 9.662 9.952 10.241 10.531 10.821 11.110 11.400 11.853 12.307 12.760 13.213 13.667 14.120 14.573 15.027 15.480 15.933 16.387 16.840 17.293 17.747 18.200 18.653 19.107 19.560 20.013 20.467 20.920 21.373 21.827 22.280 22.733 23.187 23.640 24.093 24.547 25.000 ! PS_WindSpeeds - Wind speeds corresponding to minimum blade pitch angles [m/s] +0.000 0.000 0.000 0.000 0.000 0.000 0.000 0.000 0.000 0.000 0.000 0.000 0.000 0.000 0.000 0.000 0.000 0.000 0.000 0.000 0.000 0.000 0.000 0.019 0.031 0.041 0.050 0.058 0.066 0.074 0.086 0.096 0.107 0.117 0.127 0.137 0.147 0.156 0.165 0.174 0.183 0.192 0.201 0.210 0.218 0.227 0.236 0.244 0.253 0.262 0.270 0.279 0.287 0.295 0.303 0.312 0.320 0.328 0.337 0.345 ! PS_BldPitchMin - Minimum blade pitch angles [rad] !------- SHUTDOWN ----------------------------------------------------------- 0.436300000000 ! SD_MaxPit - Maximum blade pitch angle to initiate shutdown, [rad] From 5a7046f70f7a5305c02ced2aa78bccc23d14b366 Mon Sep 17 00:00:00 2001 From: dzalkind <65573423+dzalkind@users.noreply.github.com> Date: Mon, 3 Apr 2023 17:50:16 -0600 Subject: [PATCH 094/224] Active Wake Control (#230) * AWC First Version, collected changes * Add AWC parameters to registry, regenerate types * Apply DbKi to COMPLEX * Re-organize AWC pitch contribution, before actuator * Separate contribution to PitCom from mode calculation * Make AWC_complexangle a LocalVar for logging * Removed duplicate pitch assignment and removed MinPitch mods for AWC * Fixes to readsetparams and awc location * Adding NREL 2.8 127 for AWC testing * Add case generation updates * Add initial AWC example, needs OF3.4 * Add AWC_Mode and move AWC into subroutine * Update example to point to correct inputs * Remove LocalVar%PC_MinPit = CntrPar%PC_MinPit, breaking setpoint smoother * Set min pitch for AWC * Tidy up input additions * Update other DISCONs * Add AWC to toolbox schema * Tidy example * Update AWC example with instructions/theory * Formatting fixes * Prep for more modes * Update 20_active_wake_control.py * Fix units in schema * Test all AWC cases in example 20 * Tidy up DISCON file writing * Revert setup directory * Update 20_active_wake_control.py Documentation update: -added type of input, either integer or float -added suggested ranges for input variables (only one of these ranges is a hard rule that might break something if not followed, which is that AWC_NumModes>=0) -added more description of what the azimuthal mode number is Note to Dan: I didn't follow exactly if the units in the code changed between rad and deg - can you check that the units in rows 14-16 are correct? Also, let's have Lawrence review these additions. * Update NREL-2p8-127_DISCON.IN Updating units. * Update Controllers.f90 Update units. * Update ROSCO_Types.f90 Update units. * Update ReadSetParameters.f90 Update units. * Update 20_active_wake_control.py Update units and documentation. * Update toolbox_schema.yaml Update units. * Update utilities.py Update AWC descriptions and units. * Update rosco_types.yaml Update AWC units. * Added NREL-developed AWC-implementation * Undo unintentional changes to wrie_registry.py * Fix file writing in AWC section * Update all DISCONs * Add 20_awc to test_examples * Add 2.8 to update_discons, regenerate DISCON Should match closely to original DISCON * Update AWC_Mode descriptions * Updated Coleman Transformation based AWC * Tidy print statements, file writing * Remove duplicate PF_Offsets input read * Rename methods in readme * Tidy input writing, remove `future` references * Force AWC_n into int * Force AWC_n into int better * Make AWC_n a list, too * Fix input file writing, force into int in write_array * Run ROSCO_testing from anywhere * Dylib -> so in Test_Cases * Updated AWC input parameters. * Added checks for AWC inputs. * Fixed bug in added AWC input checks. * Update error message * Tidy up IPC, allow AWC and IPC with warning * Remove AWC references from IPC * Remove lingering comment * Tidy file writing * Clean up comments * Allow more than 99 local variables in dbg2 * Update api_change.rst Added AWC inputs * Update 20_active_wake_control.py --------- Co-authored-by: Nathaniel deVelder Co-authored-by: kbrown1snl <66843135+kbrown1snl@users.noreply.github.com> Co-authored-by: jfrederik-nrel Co-authored-by: jfrederik-nrel <120053750+jfrederik-nrel@users.noreply.github.com> --- .gitignore | 1 + Examples/12_tune_ipc.py | 153 +-- Examples/20_active_wake_control.py | 244 ++++ Examples/test_examples.py | 1 + ROSCO/rosco_registry/rosco_types.yaml | 81 ++ ROSCO/rosco_registry/write_registry.py | 28 +- ROSCO/src/Controllers.f90 | 113 +- ROSCO/src/ROSCO_IO.f90 | 164 ++- ROSCO/src/ROSCO_Types.f90 | 14 + ROSCO/src/ReadSetParameters.f90 | 59 + ROSCO_testing/ROSCO_testing.py | 15 +- ROSCO_toolbox/controller.py | 5 +- ROSCO_toolbox/inputs/toolbox_schema.yaml | 51 + ROSCO_toolbox/ofTools/case_gen/CaseLibrary.py | 42 +- ROSCO_toolbox/ofTools/case_gen/HH_WindFile.py | 26 +- ROSCO_toolbox/ofTools/fast_io/FAST_reader.py | 4 +- .../ofTools/fast_io/output_processing.py | 115 +- ROSCO_toolbox/ofTools/fast_io/plot_FAST.ipynb | 455 ++----- .../ofTools/fast_io/read_fast_input.py | 1202 ----------------- ROSCO_toolbox/utilities.py | 25 +- Test_Cases/BAR_10/BAR_10_DISCON.IN | 21 +- .../DISCON-UMaineSemi.IN | 21 +- Test_Cases/NREL-5MW/DISCON.IN | 21 +- .../Airfoils/NREL-2p8-127_AF00_Coords.txt | 208 +++ .../Airfoils/NREL-2p8-127_AF01_Coords.txt | 208 +++ .../Airfoils/NREL-2p8-127_AF02_Coords.txt | 208 +++ .../Airfoils/NREL-2p8-127_AF03_Coords.txt | 208 +++ .../Airfoils/NREL-2p8-127_AF04_Coords.txt | 208 +++ .../Airfoils/NREL-2p8-127_AF05_Coords.txt | 208 +++ .../Airfoils/NREL-2p8-127_AF06_Coords.txt | 208 +++ .../Airfoils/NREL-2p8-127_AF07_Coords.txt | 208 +++ .../Airfoils/NREL-2p8-127_AF08_Coords.txt | 208 +++ .../Airfoils/NREL-2p8-127_AF09_Coords.txt | 208 +++ .../Airfoils/NREL-2p8-127_AF10_Coords.txt | 208 +++ .../Airfoils/NREL-2p8-127_AF11_Coords.txt | 208 +++ .../Airfoils/NREL-2p8-127_AF12_Coords.txt | 208 +++ .../Airfoils/NREL-2p8-127_AF13_Coords.txt | 208 +++ .../Airfoils/NREL-2p8-127_AF14_Coords.txt | 208 +++ .../Airfoils/NREL-2p8-127_AF15_Coords.txt | 208 +++ .../Airfoils/NREL-2p8-127_AF16_Coords.txt | 208 +++ .../Airfoils/NREL-2p8-127_AF17_Coords.txt | 208 +++ .../Airfoils/NREL-2p8-127_AF18_Coords.txt | 208 +++ .../Airfoils/NREL-2p8-127_AF19_Coords.txt | 208 +++ .../Airfoils/NREL-2p8-127_AF20_Coords.txt | 208 +++ .../Airfoils/NREL-2p8-127_AF21_Coords.txt | 208 +++ .../Airfoils/NREL-2p8-127_AF22_Coords.txt | 208 +++ .../Airfoils/NREL-2p8-127_AF23_Coords.txt | 208 +++ .../Airfoils/NREL-2p8-127_AF24_Coords.txt | 208 +++ .../Airfoils/NREL-2p8-127_AF25_Coords.txt | 208 +++ .../Airfoils/NREL-2p8-127_AF26_Coords.txt | 208 +++ .../Airfoils/NREL-2p8-127_AF27_Coords.txt | 208 +++ .../Airfoils/NREL-2p8-127_AF28_Coords.txt | 208 +++ .../Airfoils/NREL-2p8-127_AF29_Coords.txt | 208 +++ .../NREL-2p8-127_AeroDyn15_Polar_00.dat | 254 ++++ .../NREL-2p8-127_AeroDyn15_Polar_01.dat | 254 ++++ .../NREL-2p8-127_AeroDyn15_Polar_02.dat | 254 ++++ .../NREL-2p8-127_AeroDyn15_Polar_03.dat | 254 ++++ .../NREL-2p8-127_AeroDyn15_Polar_04.dat | 254 ++++ .../NREL-2p8-127_AeroDyn15_Polar_05.dat | 254 ++++ .../NREL-2p8-127_AeroDyn15_Polar_06.dat | 254 ++++ .../NREL-2p8-127_AeroDyn15_Polar_07.dat | 254 ++++ .../NREL-2p8-127_AeroDyn15_Polar_08.dat | 254 ++++ .../NREL-2p8-127_AeroDyn15_Polar_09.dat | 254 ++++ .../NREL-2p8-127_AeroDyn15_Polar_10.dat | 254 ++++ .../NREL-2p8-127_AeroDyn15_Polar_11.dat | 254 ++++ .../NREL-2p8-127_AeroDyn15_Polar_12.dat | 254 ++++ .../NREL-2p8-127_AeroDyn15_Polar_13.dat | 254 ++++ .../NREL-2p8-127_AeroDyn15_Polar_14.dat | 254 ++++ .../NREL-2p8-127_AeroDyn15_Polar_15.dat | 254 ++++ .../NREL-2p8-127_AeroDyn15_Polar_16.dat | 254 ++++ .../NREL-2p8-127_AeroDyn15_Polar_17.dat | 254 ++++ .../NREL-2p8-127_AeroDyn15_Polar_18.dat | 254 ++++ .../NREL-2p8-127_AeroDyn15_Polar_19.dat | 254 ++++ .../NREL-2p8-127_AeroDyn15_Polar_20.dat | 254 ++++ .../NREL-2p8-127_AeroDyn15_Polar_21.dat | 254 ++++ .../NREL-2p8-127_AeroDyn15_Polar_22.dat | 254 ++++ .../NREL-2p8-127_AeroDyn15_Polar_23.dat | 254 ++++ .../NREL-2p8-127_AeroDyn15_Polar_24.dat | 254 ++++ .../NREL-2p8-127_AeroDyn15_Polar_25.dat | 254 ++++ .../NREL-2p8-127_AeroDyn15_Polar_26.dat | 254 ++++ .../NREL-2p8-127_AeroDyn15_Polar_27.dat | 254 ++++ .../NREL-2p8-127_AeroDyn15_Polar_28.dat | 254 ++++ .../NREL-2p8-127_AeroDyn15_Polar_29.dat | 254 ++++ Test_Cases/NREL_2p8_127/NREL-2.8-127.xlsx | Bin 0 -> 14107 bytes .../NREL_2p8_127/NREL-2.8-127_pitch-speed.csv | 31 + Test_Cases/NREL_2p8_127/NREL-2p8-127.fst | 71 + .../NREL_2p8_127/NREL-2p8-127_AeroDyn15.dat | 134 ++ .../NREL-2p8-127_AeroDyn15_blade.dat | 36 + .../NREL_2p8_127/NREL-2p8-127_Cp_Ct_Cq.txt | 111 ++ .../NREL_2p8_127/NREL-2p8-127_DISCON.IN | 171 +++ .../NREL_2p8_127/NREL-2p8-127_ElastoDyn.dat | 210 +++ .../NREL-2p8-127_ElastoDyn_blade.dat | 62 + .../NREL-2p8-127_ElastoDyn_tower.dat | 50 + .../NREL_2p8_127/NREL-2p8-127_InflowFile.dat | 57 + .../NREL_2p8_127/NREL-2p8-127_ServoDyn.dat | 110 ++ Test_Cases/update_rosco_discons.py | 3 +- Tune_Cases/NREL2p8.yaml | 65 + docs/source/api_change.rst | 31 +- setup.py | 5 +- 99 files changed, 16075 insertions(+), 1793 deletions(-) create mode 100644 Examples/20_active_wake_control.py delete mode 100644 ROSCO_toolbox/ofTools/fast_io/read_fast_input.py create mode 100644 Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF00_Coords.txt create mode 100644 Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF01_Coords.txt create mode 100644 Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF02_Coords.txt create mode 100644 Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF03_Coords.txt create mode 100644 Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF04_Coords.txt create mode 100644 Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF05_Coords.txt create mode 100644 Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF06_Coords.txt create mode 100644 Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF07_Coords.txt create mode 100644 Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF08_Coords.txt create mode 100644 Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF09_Coords.txt create mode 100644 Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF10_Coords.txt create mode 100644 Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF11_Coords.txt create mode 100644 Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF12_Coords.txt create mode 100644 Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF13_Coords.txt create mode 100644 Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF14_Coords.txt create mode 100644 Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF15_Coords.txt create mode 100644 Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF16_Coords.txt create mode 100644 Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF17_Coords.txt create mode 100644 Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF18_Coords.txt create mode 100644 Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF19_Coords.txt create mode 100644 Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF20_Coords.txt create mode 100644 Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF21_Coords.txt create mode 100644 Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF22_Coords.txt create mode 100644 Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF23_Coords.txt create mode 100644 Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF24_Coords.txt create mode 100644 Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF25_Coords.txt create mode 100644 Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF26_Coords.txt create mode 100644 Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF27_Coords.txt create mode 100644 Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF28_Coords.txt create mode 100644 Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF29_Coords.txt create mode 100644 Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_00.dat create mode 100644 Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_01.dat create mode 100644 Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_02.dat create mode 100644 Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_03.dat create mode 100644 Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_04.dat create mode 100644 Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_05.dat create mode 100644 Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_06.dat create mode 100644 Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_07.dat create mode 100644 Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_08.dat create mode 100644 Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_09.dat create mode 100644 Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_10.dat create mode 100644 Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_11.dat create mode 100644 Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_12.dat create mode 100644 Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_13.dat create mode 100644 Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_14.dat create mode 100644 Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_15.dat create mode 100644 Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_16.dat create mode 100644 Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_17.dat create mode 100644 Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_18.dat create mode 100644 Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_19.dat create mode 100644 Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_20.dat create mode 100644 Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_21.dat create mode 100644 Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_22.dat create mode 100644 Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_23.dat create mode 100644 Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_24.dat create mode 100644 Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_25.dat create mode 100644 Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_26.dat create mode 100644 Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_27.dat create mode 100644 Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_28.dat create mode 100644 Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_29.dat create mode 100644 Test_Cases/NREL_2p8_127/NREL-2.8-127.xlsx create mode 100644 Test_Cases/NREL_2p8_127/NREL-2.8-127_pitch-speed.csv create mode 100644 Test_Cases/NREL_2p8_127/NREL-2p8-127.fst create mode 100644 Test_Cases/NREL_2p8_127/NREL-2p8-127_AeroDyn15.dat create mode 100644 Test_Cases/NREL_2p8_127/NREL-2p8-127_AeroDyn15_blade.dat create mode 100644 Test_Cases/NREL_2p8_127/NREL-2p8-127_Cp_Ct_Cq.txt create mode 100644 Test_Cases/NREL_2p8_127/NREL-2p8-127_DISCON.IN create mode 100644 Test_Cases/NREL_2p8_127/NREL-2p8-127_ElastoDyn.dat create mode 100644 Test_Cases/NREL_2p8_127/NREL-2p8-127_ElastoDyn_blade.dat create mode 100644 Test_Cases/NREL_2p8_127/NREL-2p8-127_ElastoDyn_tower.dat create mode 100644 Test_Cases/NREL_2p8_127/NREL-2p8-127_InflowFile.dat create mode 100644 Test_Cases/NREL_2p8_127/NREL-2p8-127_ServoDyn.dat create mode 100644 Tune_Cases/NREL2p8.yaml diff --git a/.gitignore b/.gitignore index e633e4cd..ba1e27c1 100644 --- a/.gitignore +++ b/.gitignore @@ -81,6 +81,7 @@ Examples/*.p # Exclude testing results ROSCO_testing/results/ +ROSCO_testing/testing # Simulink/Matlab temp files *.slxc diff --git a/Examples/12_tune_ipc.py b/Examples/12_tune_ipc.py index d4040a68..e435becf 100644 --- a/Examples/12_tune_ipc.py +++ b/Examples/12_tune_ipc.py @@ -14,105 +14,58 @@ import matplotlib.pyplot as plt # ROSCO toolbox modules -from ROSCO_toolbox import controller as ROSCO_controller -from ROSCO_toolbox import turbine as ROSCO_turbine -from ROSCO_toolbox.utilities import DISCON_dict from ROSCO_toolbox.ofTools.fast_io import output_processing -from ROSCO_toolbox.inputs.validation import load_rosco_yaml -from ROSCO_toolbox.ofTools.case_gen.CaseLibrary import set_channels -from ROSCO_toolbox.ofTools.case_gen.runFAST_pywrapper import runFAST_pywrapper_batch -from ROSCO_toolbox.ofTools.case_gen.CaseGen_General import CaseGen_General - - - -this_dir = os.path.dirname(os.path.abspath(__file__)) -rosco_dir = os.path.dirname(this_dir) -example_out_dir = os.path.join(this_dir,'examples_out') -example_name = '12_ipc_sim' -run_dir = os.path.join(example_out_dir, example_name) - -# Load yaml file (Open Loop Case) -parameter_filename = os.path.join(rosco_dir,'Tune_Cases/BAR.yaml') - -inps = load_rosco_yaml(parameter_filename) -path_params = inps['path_params'] -turbine_params = inps['turbine_params'] -controller_params = inps['controller_params'] - -# Turn flaps off and IPC on -controller_params['Flp_Mode'] = 0 -controller_params['IPC_ControlMode'] = 1 - -# Instantiate turbine, and controller -turbine = ROSCO_turbine.Turbine(turbine_params) -controller = ROSCO_controller.Controller(controller_params) - -# Load turbine data from OpenFAST and rotor performance text file -turbine.load_from_fast( - path_params['FAST_InputFile'], - os.path.join(this_dir, path_params['FAST_directory']) - ) -# Tune controller -controller.tune_controller(turbine) - -# Set rosco_dll -if platform.system() == 'Windows': - rosco_dll = os.path.join(rosco_dir, 'ROSCO/build/libdiscon.dll') -elif platform.system() == 'Darwin': - rosco_dll = os.path.join(rosco_dir, 'ROSCO/build/libdiscon.dylib') -else: - rosco_dll = os.path.join(rosco_dir, 'ROSCO/build/libdiscon.so') - -case_inputs = {} -case_inputs[('ServoDyn','DLL_FileName')] = {'vals': [rosco_dll], 'group': 0} -case_inputs[('ServoDyn','Ptch_Cntrl')] = {'vals': [1], 'group': 0} - -# Apply all discon variables as case inputs -discon_vt = DISCON_dict( - turbine, - controller, - txt_filename=os.path.join(this_dir,path_params['FAST_directory'],path_params['rotor_performance_filename']) - ) - -for discon_input in discon_vt: - case_inputs[('DISCON_in',discon_input)] = {'vals': [discon_vt[discon_input]], 'group': 0} - -# Generate cases -if not os.path.exists(run_dir): - os.makedirs(run_dir) - -case_list, case_name_list = CaseGen_General(case_inputs, dir_matrix=run_dir, namebase='ipc_example') -channels = set_channels() -channels['BldPitch2'] = True -channels['BldPitch3'] = True - -# Run FAST cases -fastBatch = runFAST_pywrapper_batch() - -fastBatch.FAST_directory = os.path.realpath(os.path.join(rosco_dir,'Tune_Cases',path_params['FAST_directory'])) -fastBatch.FAST_InputFile = path_params['FAST_InputFile'] -fastBatch.channels = channels -fastBatch.FAST_runDirectory = run_dir -fastBatch.case_list = case_list -fastBatch.case_name_list = case_name_list -fastBatch.debug_level = 2 -fastBatch.FAST_exe = 'openfast' - -fastBatch.run_serial() - - -# # Define Plot cases -cases = {} -cases['Baseline'] = ['Wind1VelX', ('BldPitch1', 'BldPitch2', 'BldPitch3'), 'RootMyc1', 'RotSpeed'] - -out_file = os.path.join(example_out_dir,example_name,'ipc_example_0.outb') -op = output_processing.output_processing() -fastout = op.load_fast_out(out_file, tmin=0) -fig, ax = op.plot_fast_out(cases=cases,showplot=False) -if False: - plt.show() -else: - fig[0].savefig(os.path.join(example_out_dir,'13_ipc_FAST_Out.png')) - - +from ROSCO_toolbox.ofTools.case_gen.run_FAST import run_FAST_ROSCO +from ROSCO_toolbox.ofTools.case_gen import CaseLibrary as cl + +def main(): + this_dir = os.path.dirname(os.path.abspath(__file__)) + rosco_dir = os.path.dirname(this_dir) + example_out_dir = os.path.join(this_dir,'examples_out') + example_name = '12_ipc_sim' + run_dir = os.path.join(example_out_dir, example_name) + + # Load yaml file (Open Loop Case) + parameter_filename = os.path.join(rosco_dir,'Tune_Cases/NREL2p8.yaml') + + case_inputs = {} + case_inputs[('ServoDyn','Ptch_Cntrl')] = {'vals': [1], 'group': 0} + case_inputs[('DISCON_in','IPC_SatMode')] = {'vals': [0,1,2,3], 'group': 1} + + + + # simulation set up + r = run_FAST_ROSCO() + r.tuning_yaml = parameter_filename + r.wind_case_fcn = cl.ramp # single step wind input + r.wind_case_opts = { + 'U_start': 11, # from 10 to 15 m/s + 'U_end': 9, + 't_start': 100, + 't_end': 400, + 'both_dir': True, + 'vert_shear': 0.2 + } + r.case_inputs = case_inputs + r.save_dir = run_dir + r.rosco_dir = rosco_dir + r.n_cores = 4 + r.run_FAST() + + + # # Define Plot cases + cases = {} + cases['Baseline'] = ['Wind1VelX', 'BldPitch1', 'RootMyc1', 'RotSpeed'] + + out_files = [os.path.join(example_out_dir,example_name,f'NREL2p8/ramp/base/NREL2p8_{i_case}.outb') for i_case in range(4)] + op = output_processing.output_processing() + fastout = op.load_fast_out(out_files, tmin=0) + fig, ax = op.plot_fast_out(cases=cases,showplot=False) + if False: + plt.show() + else: + fig[0].savefig(os.path.join(example_out_dir,'12_ipc_FAST_Out.png')) + +if __name__=="__main__": + main() diff --git a/Examples/20_active_wake_control.py b/Examples/20_active_wake_control.py new file mode 100644 index 00000000..c67555d8 --- /dev/null +++ b/Examples/20_active_wake_control.py @@ -0,0 +1,244 @@ +''' +----------- 20_active_wake_control ------------ +Run openfast with ROSCO and active wake control +----------------------------------------------- +Set up and run simulation with AWC, check outputs +Active wake control (AWC) with blade pitching is implemented in this example with two approaches as detailed below: + +----------------------------------------------- +AWC_Mode = 1: Normal mode method: +----------------------------------------------- +The normal mode method is an adaptation into the rotating frame of the mathematical framework from the classical theory for stability of axisymmetric jets [1], which offers flexibility in specifying the forcing strategy. + +The inputs to the controller are: + Name Unit Type Range Description + AWC_NumModes - Integer [0,inf] number of forcing modes + AWC_n - Integer [-inf,inf] azimuthal mode number(s) (i.e., the azimuthal mode number relates to the number and direction of the lobes of the wake structure according to the classical spatio-temporal Fourier decomposition of an arbitrary quantity q, sigma{sigma{q*exp(i*n*theta)*exp(i*omega*time)}}. For the case of a non-time-varying flow (i.e., where omega = 0), the azimuthal mode number specifies the number of cycles of blade pitch oscillation per one rotation around the rotor azimuth.) + AWC_clockangle deg Float [0,360] clocking angle(s) of forcing mode(s) + AWC_freq Hz Float [0,inf] frequency(s) of forcing mode(s) + AWC_amp deg Float [0,inf] pitch amplitude(s) of forcing mode(s) (note that AWC_amp specifies the amplitude of each individual mode so that the total amplitude of pitching will be the sum of AWC_amp) + +The latter two inputs may be specified based on the expected inflow while the former three inputs determine the type of active wake control to be used. + +Readers may be familiar with several forcing strategies from literature on active wake control that can be represented as follows: + -collective dynamic induction control: AWC_NumModes = 1, AWC_n = 0, AWC_clockangle = 0 + -helix clockwise [2]: AWC_NumModes = 1, AWC_n = 1, AWC_clockangle = 0 + -helix counter-clockwise [2]: AWC_NumModes = 1, AWC_n = -1, AWC_clockangle = 0 + -up-and-down: AWC_NumModes = 2, AWC_n = -1 1, AWC_clockangle = 0 0 + -side-to-side: AWC_NumModes = 2, AWC_n = -1 1, AWC_clockangle = 90 90 + -other: Higher-order modes or different combinations of the above can also be specified + + These strategies are implemented using the following calculation methodology: + For each blade, we compute the total phase angle of blade pitch excursion according to: + AWC_angle(t) = 2*Pi*AWC_freq * t - AWC_n * (psi(t) + phi + AWC_clockangle*PI/180) (eq 1) + where t is time + phi(t) is the angular offset of the given blade in the rotor plane relative to blade 1 + psi is the angle of blade 1 in the rotor plane from top-dead center + + Next, the phase angle is converted into the complex pitch amplitude: + AWC_complexangle(t) = AWC_amp*PI/180 * EXP(i * AWC_angle(t)) (eq 2) + where i is the square root of -1 + + Note that if AWC_NumModes>1, then eq 1 and 2 are computed for each additional mode, and AWC_complexangle becomes a summation over all modes for each blade. + + Finally, the real pitch amplitude, theta(t), to be passed to the next step of the controller is calculated: + theta(t) = theta_0(t) + REAL(AWC_complexangle(t)) (eq 3) + where theta_0(t) is the controller's nominal pitch command + + Rearranging for ease of viewing: + Inserting eq 1 into eq 2, and then putting that result into eq 3 gives: + theta(t) = theta_0(t) + REAL(AWC_amp*PI/180 * EXP(i * (2*Pi*AWC_freq * t - AWC_n * (psi(t) + phi + AWC_clockangle*PI/180)))) (eq 4) + + Applying Euler's formula and carrying out the REAL operator: + theta(t) = theta_0(t) + AWC_amp*PI/180 * cos(2*Pi*AWC_freq * t - AWC_n * (psi(t) + phi + AWC_clockangle*PI/180)) (eq 5) + + As an example, we can set parameters to produce the counter-clockwise helix pattern from [2] using AWC_NumModes = 1, AWC_n = -1, and AWC_clockangle = 0: + For blade 1, eq 5 becomes: + theta(t) = theta_0(t) + AWC_amp*PI/180 * cos(2*Pi*AWC_freq * t + psi(t)) (eq 6) + +Note that the inverse multi-blade coordinate (MBC) transformation can also be used to obtain the same result as eq 6. + Beginning with Eq. 3 from [2], we have + + / \ / \ + | theta_1(t) | | theta_0(t) | + | theta_2(t) | = T^-1(psi(t)) * | theta_tilt(t) | (eq 7) + | theta_3(t) | | theta_yaw(t) | + \ / \ / + + where + + / \ + | 1 cos(psi_1(t)) sin(psi_1(t)) | + T^-1(psi(t)) = | 1 cos(psi_2(t)) sin(psi_2(t)) | + | 1 cos(psi_3(t)) sin(psi_3(t)) | + \ / + + Multiplying the first row of the top matrix (and dropping the subscript of blade 1) yields: + theta(t) = theta_0(t) + theta_tilt(t)*cos(psi(t)) + theta_yaw(t)*sin(psi(t)) (eq 8) + + Setting theta_tilt(t) = AWC_amp*PI/180 * cos(2*Pi*AWC_freq * t) and theta_yaw(t) = -AWC_amp*PI/180 * sin(2*Pi*AWC_freq * t) gives: + theta(t) = theta_0(t) + (AWC_amp*PI/180 * cos(2*Pi*AWC_freq * t))*cos(psi(t)) - (AWC_amp*PI/180 * sin(2*Pi*AWC_freq * t))*sin(psi(t)) (eq 9) + + Applying a Ptolemy identity gives: + theta(t) = theta_0(t) + AWC_amp*PI/180 * cos(2*Pi*AWC_freq * t + psi(t)) (eq 10) + which is equivlanet to eq 6 above. + +----------------------------------------------- +AWC_Mode = 2: Coleman transform method: +----------------------------------------------- +A second method is the Coleman transform method. + +The inputs to the controller are: + Name Unit Type Range Description + AWC_NumModes - Integer [1,2] number of modes for tilt and yaw (1: identical settings for tilt and yaw pitch angles, 2: seperate settings for tilt and yaw moments) + AWC_harmonic - Integer [0,inf] harmonic(s) to apply in the inverse Coleman transform (size = AWC_NumModes. 0: collective pitch AWC, 1: 1P IPC-AWC, 2: 2P IPC-AWC, etc.) + AWC_clockangle deg Array of Floats [-360,360] clocking angle(s) of tilt and yaw pitch angles (size = AWC_NumModes. If size = 1, yaw clockangle = 2*clockangle) + AWC_freq Hz Array of Floats [0,inf] frequency(s) of the tilt and yaw ptich angles, respectively (size = AWC_NumModes. If size = 1, both frequencies are assumed identical) + AWC_amp deg Array of Floats [0,inf] pitch amplitude(s) of tilt and yaw pitch angles (size = AWC_NumModes. If size = 1, both amplitudes are assumed identical) + +Using the inputs mentioned above, the user is able to specify any desired combination of sinusoidal tilt and yaw modes to be tracked by the turbine. +When a single mode is defined in the inputs, the prescribed tilt and yaw angles are assumed to be identical, except for the phase. The phase difference +between the tilt and yaw angles is taken from the input AWC_clockangle. + +Readers may be familiar with several forcing strategies from literature on active wake control that can be represented as follows: + -collective dynamic induction control: AWC_NumModes = 1, AWC_harmonic = 0 + -helix clockwise [2]: AWC_NumModes = 1, AWC_harmonic = 1, AWC_clockangle = -90 OR AWC_NumModes = 2, AWC_n = [1 1], AWC_clockangle = [0 -90] + -helix counter-clockwise [2]: AWC_NumModes = 1, AWC_harmonic = 1, AWC_clockangle = 90 OR AWC_NumModes = 2, AWC_n = [1 1], AWC_clockangle = [0 90] + -up-and-down: AWC_NumModes = 2, AWC_harmonic = [1 1], AWC_amp = [# 0] (where "#" represents the desired amplitude) + -side-to-side: AWC_NumModes = 2, AWC_harmonic = [1 1], AWC_amp = [0 #] (where "#" represents the desired amplitude) + -other: different combinations of the above can also be specified + + These strategies are implemented using the following calculation methodology: + The inputs described above enable the user to specify a desired sinusoidal signal for either the collective pitch (AWC_n = 0) or tilt and yaw pitch + angles (AWC_n = 1). These AWC pitch angles are defined as: + AWC_angle(t) = AWC_amp * sin(2*pi*AWC_freq*t + AWC_clockangle) (eq 1) + + In case of collective pitch AWC, this signal is directly superimposed on the regular pitch control signal. + + In case of IPC-based AWC, the reference tilt and yaw pitch angles theta are transformed to the rotating frame (i.e., pitch angles theta_k(t) for all + individual blades) using the inverse MBC transformation: + + / \ / \ + | theta_1(t) | | theta_0(t) | + | theta_2(t) | = T^-1(psi(t)) * | theta_tilt(t) | (eq 2) + | theta_3(t) | | theta_yaw(t) | + \ / \ / + + where + + theta_tilt(t) = AWC_amp(1) * sin(2*pi*AWC_freq(1)*t + AWC_clockangle(1)) (eq 3) + theta_yaw(t) = AWC_amp(2) * sin(2*pi*AWC_freq(2)*t + AWC_clockangle(2)) (eq 4) + + and + / \ + | 1 cos(psi_1(t)) sin(psi_1(t)) | + T^-1(psi(t)) = | 1 cos(psi_2(t)) sin(psi_2(t)) | (eq 5) + | 1 cos(psi_3(t)) sin(psi_3(t)) | + \ / + + with psi_k(t) the azimuthal position of blade k at time instant t. Note that if AWC_NumModes = 1, it is assumed that: + AWC_amp(2) = AWC_amp(1) + AWC_freq(2) = AWC_freq(1) + AWC_clockangle(2) = 2*AWC_clockangle(1) + + For more information on this control strategy, the user is referred to [2]. + +----------------------------------------------- + +General Implementation note: AWC strategies will be compromised if the AWC pitch command attempts to lower the blade pitch below value PC_MinPit as specified +in the DISCON file, so PC_MinPit may need to be reduced by the user. + +References: +[1] - Batchelor, G. K., and A. E. Gill. "Analysis of the stability of axisymmetric jets." Journal of fluid mechanics 14.4 (1962): 529-551. +[2] - Frederik, Joeri A., et al. "The helix approach: Using dynamic individual pitch control to enhance wake mixing in wind farms." Wind Energy 23.8 (2020): 1739-1751. +''' + +import os, platform +from ROSCO_toolbox.ofTools.case_gen.run_FAST import run_FAST_ROSCO +from ROSCO_toolbox.ofTools.case_gen import CaseLibrary as cl +from ROSCO_toolbox.ofTools.fast_io import output_processing +from ROSCO_toolbox.utilities import read_DISCON, DISCON_dict +import numpy as np + +# Choose your implementation method +AWC_Mode = 1 # 1 for SNL implementation, 2 for Coleman Transformation implementation + +#directories +this_dir = os.path.dirname(os.path.abspath(__file__)) +rosco_dir = os.path.dirname(this_dir) +example_out_dir = os.path.join(this_dir,'examples_out') +os.makedirs(example_out_dir,exist_ok=True) + +if platform.system() == 'Windows': + lib_name = os.path.realpath(os.path.join(this_dir, '../ROSCO/build/libdiscon.dll')) +elif platform.system() == 'Darwin': + lib_name = os.path.realpath(os.path.join(this_dir, '../ROSCO/build/libdiscon.dylib')) +else: + lib_name = os.path.realpath(os.path.join(this_dir, '../ROSCO/build/libdiscon.so')) + + +def main(): + + # Input yaml and output directory + parameter_filename = os.path.join(rosco_dir,'Tune_Cases/NREL2p8.yaml') # will be dummy and overwritten with SNL DISCON params + run_dir = os.path.join(example_out_dir,'20_active_wake_control/all_cases') + os.makedirs(run_dir,exist_ok=True) + + # Read all DISCON inputs + rosco_vt = read_DISCON(os.path.join(rosco_dir,'Test_Cases','NREL_2p8_127/NREL-2p8-127_DISCON.IN')) + + # Apply all discon variables as case inputs + control_base_case = {} + for discon_input in rosco_vt: + control_base_case[('DISCON_in',discon_input)] = {'vals': [rosco_vt[discon_input]], 'group': 0} + + # Set up AWC cases defined above + if AWC_Mode == 1: + control_base_case[('DISCON_in','AWC_Mode')] = {'vals': [0,1,1,1,1,1], 'group': 2} + control_base_case[('DISCON_in','AWC_NumModes')] = {'vals': [1,1,1,1,2,2], 'group': 2} + control_base_case[('DISCON_in','AWC_n')] = {'vals': [[0],[0],[1],[-1],[-1,1], [-1,1]], 'group': 2} + control_base_case[('DISCON_in','AWC_freq')] = {'vals': [[0],[0.05],[0.05],[0.05],[0.05,0.05], [0.05,0.05]], 'group': 2} + control_base_case[('DISCON_in','AWC_amp')] = {'vals': [[0],[2.5],[2.5],[2.5],[1.25,1.25], [1.25,1.25]], 'group': 2} + control_base_case[('DISCON_in','AWC_clockangle')] = {'vals': [[0],[0],[0],[0],[0,0], [90,90]], 'group': 2} + elif AWC_Mode == 2: + control_base_case[('DISCON_in','AWC_Mode')] = {'vals': [0,2,2,2,2,2], 'group': 2} + control_base_case[('DISCON_in','AWC_NumModes')] = {'vals': [1,1,2,2,2,2], 'group': 2} + control_base_case[('DISCON_in','AWC_harmonic')] = {'vals': [[0],[0],[1,1],[1,1],[1,1], [1,1]], 'group': 2} + control_base_case[('DISCON_in','AWC_freq')] = {'vals': [[0],[0.05],[0.05,0.05],[0.05,0.05],[0.05,0.05], [0.05,0.05]], 'group': 2} + control_base_case[('DISCON_in','AWC_amp')] = {'vals': [[0],[2.5],[2.5,2.5],[2.5,2.5],[2.5,0.0], [0.0,2.5]], 'group': 2} + control_base_case[('DISCON_in','AWC_clockangle')] = {'vals': [[0],[0],[0,-90],[0,90],[0,0], [180,180]], 'group': 2} + + # simulation set up + r = run_FAST_ROSCO() + r.tuning_yaml = parameter_filename + r.wind_case_fcn = cl.power_curve # single step wind input + r.wind_case_opts = { + 'U': [14], # from 10 to 15 m/s + 'TMax': 100, + } + r.case_inputs = control_base_case + r.case_inputs[("ServoDyn","Ptch_Cntrl")] = {'vals':[1], 'group':0} # Individual pitch control must be enabled in ServoDyn + r.save_dir = run_dir + r.rosco_dir = rosco_dir + r.n_cores = 5 + r.run_FAST() + + # # Check AWC here + # filenames = [os.path.join(run_dir,'IEA15MW/simp_step/base/IEA15MW_0.outb')] + # fast_out = output_processing.output_processing() + + # # Load and plot + # fastout = fast_out.load_fast_out(filenames) + # offset_2 = fastout[0]['BldPitch2'] - fastout[0]['BldPitch1'] + # offset_3 = fastout[0]['BldPitch3'] - fastout[0]['BldPitch1'] + + # # check that offset (min,max) is very close to prescribed values + # np.testing.assert_almost_equal(offset_2.max(),pitch2_offset,decimal=3) + # np.testing.assert_almost_equal(offset_2.min(),pitch2_offset,decimal=3) + # np.testing.assert_almost_equal(offset_3.max(),pitch3_offset,decimal=3) + # np.testing.assert_almost_equal(offset_3.max(),pitch3_offset,decimal=3) + + + +if __name__=="__main__": + main() diff --git a/Examples/test_examples.py b/Examples/test_examples.py index 6f46db30..0bd6840e 100644 --- a/Examples/test_examples.py +++ b/Examples/test_examples.py @@ -22,6 +22,7 @@ '17_zeromq_interface', # NJA: only runs on unix in CI '18_pitch_offsets', '19_update_discon_version', + '20_active_wake_control', '21_optional_inputs', '22_cable_control', 'update_rosco_discons', diff --git a/ROSCO/rosco_registry/rosco_types.yaml b/ROSCO/rosco_registry/rosco_types.yaml index ff831169..d2d5fa60 100644 --- a/ROSCO/rosco_registry/rosco_types.yaml +++ b/ROSCO/rosco_registry/rosco_types.yaml @@ -12,6 +12,13 @@ default_types: size: 0 # Use this if the type IS an array (size:3 --> REAL(8), BldPitch(3)) allocatable: False equals: + complex: &complex + type: complex + description: + dimension: # Use this if a higher-dimensional allocatable array (dimension:(:,:) --> REAL(8), DIMESION(:,:), ALLOCATABLE) + size: 0 # Use this if the type IS an array (size:3 --> REAL(8), BldPitch(3)) + allocatable: False + equals: float: &float type: float description: @@ -442,6 +449,58 @@ ControlParameters: PA_Damping: <<: *real description: Pitch actuator damping ratio [-, unused if PA_Mode = 1] + + # Active wake control + AWC_Mode: + <<: *integer + description: Active wake control mode [0 - unused, 1 - complex number method, 2 - Coleman transform method] + AWC_NumModes: + <<: *integer + description: AWC- Number of modes to include [-] + AWC_n: + <<: *integer + allocatable: True + description: AWC azimuthal mode [-] + AWC_harmonic: + <<: *integer + allocatable: True + description: AWC AWC Coleman transform harmonic [-] + AWC_freq: + <<: *real + allocatable: True + description: AWC frequency [Hz] + AWC_amp: + <<: *real + allocatable: True + description: AWC amplitude [deg] + AWC_clockangle: + <<: *real + allocatable: True + description: AWC clocking angle [deg] + + # Active wake control + AWC_Mode: + <<: *integer + description: Active wake control mode [0 - unused, 1 - SNL method, 2 - NREL method] + AWC_NumModes: + <<: *integer + description: AWC- Number of modes to include [-] + AWC_n: + <<: *integer + allocatable: True + description: AWC azimuthal mode [-] + AWC_freq: + <<: *real + allocatable: True + description: AWC frequency [Hz] + AWC_amp: + <<: *real + allocatable: True + description: AWC amplitude [deg] + AWC_clockangle: + <<: *real + allocatable: True + description: AWC clocking angle [deg] # Pitch actuator error PF_Mode: @@ -896,6 +955,24 @@ LocalVariables: IPC_AxisYaw_2P: <<: *real description: Integral of quadrature, 2P + axisTilt_1P: + <<: *real + description: Tilt moment, 1P + axisYaw_1P: + <<: *real + description: Yaw moment, 1P + axisYawF_1P: + <<: *real + description: Filtered yaw moment, 1P + axisTilt_2P: + <<: *real + description: Tilt moment, 2P + axisYaw_2P: + <<: *real + description: Yaw moment, 2P + axisYawF_2P: + <<: *real + description: Filtered yaw moment, 2P IPC_KI: <<: *real description: Integral gain for IPC, after ramp [-] @@ -1061,6 +1138,10 @@ LocalVariables: restart: <<: *logical description: Restart flag + AWC_complexangle: + <<: *complex + description: Complex angle for each blade, sum of modes? + size: 3 WE: <<: *derived_type id: WE diff --git a/ROSCO/rosco_registry/write_registry.py b/ROSCO/rosco_registry/write_registry.py index 83c9211c..2f31b400 100644 --- a/ROSCO/rosco_registry/write_registry.py +++ b/ROSCO/rosco_registry/write_registry.py @@ -183,7 +183,7 @@ def write_roscoio(yfile): file.write(' INTEGER(IntKi), INTENT(IN) :: size_avcOUTNAME\n') file.write(' INTEGER(IntKi) :: I , nDebugOuts, nLocalVars ! Generic index.\n') file.write(' CHARACTER(1), PARAMETER :: Tab = CHAR(9) ! The tab character.\n') - file.write(' CHARACTER(29), PARAMETER :: FmtDat = "(F20.5,TR5,99(ES20.5E2,TR5:))" ! The format of the debugging data\n') + file.write(' CHARACTER(100) :: FmtDat ! The format of the debugging data\n') file.write(' INTEGER(IntKi), SAVE :: UnDb ! I/O unit for the debugging information\n') file.write(' INTEGER(IntKi), SAVE :: UnDb2 ! I/O unit for the debugging information, avrSWAP\n') file.write(' INTEGER(IntKi), SAVE :: UnDb3 ! I/O unit for the debugging information, avrSWAP\n') @@ -244,9 +244,11 @@ def write_roscoio(yfile): # -- Always prints blade(1) for multi-bladed inputss (e.g. BldPitch(1)) lv_strings = [] for lv_idx, localvar in enumerate(reg['LocalVariables']): - if reg['LocalVariables'][localvar]['type'] in ['integer', 'real']: + if reg['LocalVariables'][localvar]['type'] in ['integer', 'real', 'complex']: lv_strings.append(localvar) - file.write(' nLocalVars = {}\n'.format(len(lv_strings))) + + n_lv_outputs = len(lv_strings) + file.write(' nLocalVars = {}\n'.format(n_lv_outputs)) file.write(' Allocate(LocalVarOutData(nLocalVars))\n') file.write(' Allocate(LocalVarOutStrings(nLocalVars))\n') @@ -287,8 +289,8 @@ def write_roscoio(yfile): file.write(" CALL GetNewUnit(UnDb2, ErrVar)\n") file.write(" OPEN(unit=UnDb2, FILE=TRIM(RootName)//'.RO.dbg2')\n") file.write(" WRITE(UnDb2, *) 'Generated on '//CurDate()//' at '//CurTime()//' using ROSCO-'//TRIM(rosco_version)\n") - file.write(" WRITE(UnDb2, '(99(a20,TR5:))') 'Time', LocalVarOutStrings\n") - file.write(" WRITE(UnDb2, '(99(a20,TR5:))')\n") + file.write(f" WRITE(UnDb2, '({n_lv_outputs+1}(a20,TR5:))') 'Time', LocalVarOutStrings\n") + file.write(f" WRITE(UnDb2, '({n_lv_outputs+1}(a20,TR5:))')\n") file.write(" END IF\n") file.write("\n") # avrSWAP debug @@ -347,16 +349,17 @@ def write_roscoio(yfile): file.write(" END DO\n") file.write(" \n") file.write(" ! Write debug files\n") + file.write(f' FmtDat = "(F20.5,TR5,{n_lv_outputs}(ES20.5E2,TR5:))" ! The format of the debugging data\n') file.write(" IF(CntrPar%LoggingLevel > 0) THEN\n") - file.write(" WRITE (UnDb, FmtDat) LocalVar%Time, DebugOutData\n") + file.write(" WRITE (UnDb, TRIM(FmtDat)) LocalVar%Time, DebugOutData\n") file.write(" END IF\n") file.write("\n") file.write(" IF(CntrPar%LoggingLevel > 1) THEN\n") - file.write(" WRITE (UnDb2, FmtDat) LocalVar%Time, LocalVarOutData\n") + file.write(" WRITE (UnDb2, TRIM(FmtDat)) LocalVar%Time, LocalVarOutData\n") file.write(" END IF\n") file.write("\n") file.write(" IF(CntrPar%LoggingLevel > 2) THEN\n") - file.write(" WRITE (UnDb3, FmtDat) LocalVar%Time, avrSWAP(avrIndices)\n") + file.write(" WRITE (UnDb3, TRIM(FmtDat)) LocalVar%Time, avrSWAP(avrIndices)\n") file.write(" END IF\n") file.write("\n") file.write("END SUBROUTINE Debug\n") @@ -389,6 +392,15 @@ def read_type(param): f90type += ', DIMENSION(:), ALLOCATABLE' elif param['dimension']: f90type += ', DIMENSION{}'.format(param['dimension']) + elif param['type'] == 'complex': + f90type = 'COMPLEX(DbKi)' + if param['allocatable']: + if param['dimension']: + f90type += ', DIMENSION{}, ALLOCATABLE'.format(param['dimension']) + else: + f90type += ', DIMENSION(:), ALLOCATABLE' + elif param['dimension']: + f90type += ', DIMENSION{}'.format(param['dimension']) elif param['type'] == 'float': f90type = 'REAL(ReKi)' if param['allocatable']: diff --git a/ROSCO/src/Controllers.f90 b/ROSCO/src/Controllers.f90 index da8966fc..c966ac20 100644 --- a/ROSCO/src/Controllers.f90 +++ b/ROSCO/src/Controllers.f90 @@ -102,7 +102,7 @@ SUBROUTINE PitchControl(avrSWAP, CntrPar, LocalVar, objInst, DebugVar, ErrVar) ! Combine and saturate all individual pitch commands in software DO K = 1,LocalVar%NumBl ! Loop through all blades, add IPC contribution and limit pitch rate LocalVar%PitCom(K) = LocalVar%PC_PitComT + LocalVar%FA_PitCom(K) - LocalVar%PitCom(K) = saturate(LocalVar%PitCom(K), LocalVar%PC_MinPit, CntrPar%PC_MaxPit) ! Saturate the command using the pitch satauration limits + LocalVar%PitCom(K) = saturate(LocalVar%PitCom(K), LocalVar%PC_MinPit, CntrPar%PC_MaxPit) ! Saturate the command using the pitch saturation limits LocalVar%PitCom(K) = LocalVar%PitCom(K) + LocalVar%IPC_PitComF(K) ! Add IPC ! Hard IPC saturation by peak shaving limit @@ -124,6 +124,11 @@ SUBROUTINE PitchControl(avrSWAP, CntrPar, LocalVar, objInst, DebugVar, ErrVar) ENDIF ENDIF + ! Active wake control + IF (CntrPar%AWC_Mode > 0) THEN + CALL ActiveWakeControl(CntrPar, LocalVar, DebugVar) + ENDIF + ! Place pitch actuator here, so it can be used with or without open-loop DO K = 1,LocalVar%NumBl ! Loop through all blades, add IPC contribution and limit pitch rate IF (CntrPar%PA_Mode > 0) THEN @@ -155,10 +160,10 @@ SUBROUTINE PitchControl(avrSWAP, CntrPar, LocalVar, objInst, DebugVar, ErrVar) ! Command the pitch demanded from the last ! call to the controller (See Appendix A of Bladed User's Guide): - avrSWAP(42) = LocalVar%PitComAct(1) ! Use the command angles of all blades if using individual pitch - avrSWAP(43) = LocalVar%PitComAct(2) ! " - avrSWAP(44) = LocalVar%PitComAct(3) ! " - avrSWAP(45) = LocalVar%PitComAct(1) ! Use the command angle of blade 1 if using collective pitch + avrSWAP(42) = LocalVar%PitComAct(1) ! Use the command angles of all blades if using individual pitch + avrSWAP(43) = LocalVar%PitComAct(2) ! " + avrSWAP(44) = LocalVar%PitComAct(3) ! " + avrSWAP(45) = LocalVar%PitComAct(1) ! Use the command angle of blade 1 if using collective pitch ! Add RoutineName to error message IF (ErrVar%aviFAIL < 0) THEN @@ -391,8 +396,6 @@ SUBROUTINE IPC(CntrPar, LocalVar, objInst, DebugVar, ErrVar) ! Local variables REAL(DbKi) :: PitComIPC(3), PitComIPCF(3), PitComIPC_1P(3), PitComIPC_2P(3) INTEGER(IntKi) :: i, K ! Integer used to loop through gains and turbine blades - REAL(DbKi) :: axisTilt_1P, axisYaw_1P, axisYawF_1P ! Direct axis and quadrature axis outputted by Coleman transform, 1P - REAL(DbKi) :: axisTilt_2P, axisYaw_2P, axisYawF_2P ! Direct axis and quadrature axis outputted by Coleman transform, 1P REAL(DbKi) :: axisYawIPC_1P ! IPC contribution with yaw-by-IPC component REAL(DbKi) :: Y_MErr, Y_MErrF, Y_MErrF_IPC ! Unfiltered and filtered yaw alignment error [rad] @@ -400,8 +403,8 @@ SUBROUTINE IPC(CntrPar, LocalVar, objInst, DebugVar, ErrVar) ! Body ! Pass rootMOOPs through the Coleman transform to get the tilt and yaw moment axis - CALL ColemanTransform(LocalVar%rootMOOPF, LocalVar%Azimuth, NP_1, axisTilt_1P, axisYaw_1P) - CALL ColemanTransform(LocalVar%rootMOOPF, LocalVar%Azimuth, NP_2, axisTilt_2P, axisYaw_2P) + CALL ColemanTransform(LocalVar%rootMOOPF, LocalVar%Azimuth, NP_1, LocalVar%axisTilt_1P, LocalVar%axisYaw_1P) + CALL ColemanTransform(LocalVar%rootMOOPF, LocalVar%Azimuth, NP_2, LocalVar%axisTilt_2P, LocalVar%axisYaw_2P) ! High-pass filter the MBC yaw component and filter yaw alignment error, and compute the yaw-by-IPC contribution IF (CntrPar%Y_ControlMode == 2) THEN @@ -409,7 +412,7 @@ SUBROUTINE IPC(CntrPar, LocalVar, objInst, DebugVar, ErrVar) Y_MErrF = LPFilter(Y_MErr, LocalVar%DT, CntrPar%F_YawErr, LocalVar%FP, LocalVar%iStatus, LocalVar%restart, objInst%instSecLPF) Y_MErrF_IPC = PIController(Y_MErrF, CntrPar%Y_IPC_KP, CntrPar%Y_IPC_KI, -CntrPar%Y_IPC_IntSat, CntrPar%Y_IPC_IntSat, LocalVar%DT, 0.0_DbKi, LocalVar%piP, LocalVar%restart, objInst%instPI) ELSE - axisYawF_1P = axisYaw_1P + LocalVar%axisYawF_1P = LocalVar%axisYaw_1P Y_MErrF = 0.0 Y_MErrF_IPC = 0.0 END IF @@ -432,20 +435,20 @@ SUBROUTINE IPC(CntrPar, LocalVar, objInst, DebugVar, ErrVar) ENDIF ! Integrate the signal and multiply with the IPC gain - IF ((CntrPar%IPC_ControlMode >= 1) .AND. (CntrPar%Y_ControlMode /= 2)) THEN - LocalVar%IPC_axisTilt_1P = PIController(axisTilt_1P, LocalVar%IPC_KP(1), LocalVar%IPC_KI(1), -LocalVar%IPC_IntSat, LocalVar%IPC_IntSat, LocalVar%DT, 0.0_DbKi, LocalVar%piP, LocalVar%restart, objInst%instPI) - LocalVar%IPC_axisYaw_1P = PIController(axisYawF_1P, LocalVar%IPC_KP(1), LocalVar%IPC_KI(1), -LocalVar%IPC_IntSat, LocalVar%IPC_IntSat, LocalVar%DT, 0.0_DbKi, LocalVar%piP, LocalVar%restart, objInst%instPI) + IF (CntrPar%IPC_ControlMode >= 1 .AND. CntrPar%Y_ControlMode /= 2) THEN + LocalVar%IPC_axisTilt_1P = PIController(LocalVar%axisTilt_1P, LocalVar%IPC_KP(1), LocalVar%IPC_KI(1), -LocalVar%IPC_IntSat, LocalVar%IPC_IntSat, LocalVar%DT, 0.0_DbKi, LocalVar%piP, LocalVar%restart, objInst%instPI) + LocalVar%IPC_axisYaw_1P = PIController(LocalVar%axisYawF_1P, LocalVar%IPC_KP(1), LocalVar%IPC_KI(1), -LocalVar%IPC_IntSat, LocalVar%IPC_IntSat, LocalVar%DT, 0.0_DbKi, LocalVar%piP, LocalVar%restart, objInst%instPI) IF (CntrPar%IPC_ControlMode >= 2) THEN - LocalVar%IPC_axisTilt_2P = PIController(axisTilt_2P, LocalVar%IPC_KP(2), LocalVar%IPC_KI(2), -LocalVar%IPC_IntSat, LocalVar%IPC_IntSat, LocalVar%DT, 0.0_DbKi, LocalVar%piP, LocalVar%restart, objInst%instPI) - LocalVar%IPC_axisYaw_2P = PIController(axisYawF_2P, LocalVar%IPC_KP(2), LocalVar%IPC_KI(2), -LocalVar%IPC_IntSat, LocalVar%IPC_IntSat, LocalVar%DT, 0.0_DbKi, LocalVar%piP, LocalVar%restart, objInst%instPI) + LocalVar%IPC_axisTilt_2P = PIController(LocalVar%axisTilt_2P, LocalVar%IPC_KP(2), LocalVar%IPC_KI(2), -LocalVar%IPC_IntSat, LocalVar%IPC_IntSat, LocalVar%DT, 0.0_DbKi, LocalVar%piP, LocalVar%restart, objInst%instPI) + LocalVar%IPC_axisYaw_2P = PIController(LocalVar%axisYawF_2P, LocalVar%IPC_KP(2), LocalVar%IPC_KI(2), -LocalVar%IPC_IntSat, LocalVar%IPC_IntSat, LocalVar%DT, 0.0_DbKi, LocalVar%piP, LocalVar%restart, objInst%instPI) END IF ELSE LocalVar%IPC_axisTilt_1P = 0.0 LocalVar%IPC_axisYaw_1P = 0.0 LocalVar%IPC_axisTilt_2P = 0.0 LocalVar%IPC_axisYaw_2P = 0.0 - END IF + ENDIF ! Add the yaw-by-IPC contribution axisYawIPC_1P = LocalVar%IPC_axisYaw_1P + Y_MErrF_IPC @@ -468,13 +471,6 @@ SUBROUTINE IPC(CntrPar, LocalVar, objInst, DebugVar, ErrVar) LocalVar%IPC_PitComF(K) = PitComIPCF(K) END DO - ! debugging - DebugVar%axisTilt_1P = axisTilt_1P - DebugVar%axisYaw_1P = axisYaw_1P - DebugVar%axisTilt_2P = axisTilt_2P - DebugVar%axisYaw_2P = axisYaw_2P - - ! Add RoutineName to error message IF (ErrVar%aviFAIL < 0) THEN @@ -602,6 +598,77 @@ SUBROUTINE FlapControl(avrSWAP, CntrPar, LocalVar, objInst) ENDIF END SUBROUTINE FlapControl + +!------------------------------------------------------------------------------------------------------------------------------- + SUBROUTINE ActiveWakeControl(CntrPar, LocalVar, DebugVar) + ! Active wake controller + ! AWC_Mode = 0, No active wake control + ! AWC_Mode = 1, SNL active wake control + ! AWC_Mode = 2, Coleman Transform-based active wake control + USE ROSCO_Types, ONLY : ControlParameters, LocalVariables, DebugVariables, ObjectInstances + + TYPE(ControlParameters), INTENT(INOUT) :: CntrPar + TYPE(DebugVariables), INTENT(INOUT) :: DebugVar + TYPE(LocalVariables), INTENT(INOUT) :: LocalVar + + ! Local vars + REAL(DbKi), PARAMETER :: phi1 = 0.0 ! Phase difference from first to first blade + REAL(DbKi), PARAMETER :: phi2 = 2.0/3.0*PI ! Phase difference from first to second blade + REAL(DbKi), PARAMETER :: phi3 = 4.0/3.0*PI ! Phase difference from first to third blade + REAL(DbKi), DIMENSION(3) :: AWC_angle + COMPLEX(DbKi), DIMENSION(3) :: AWC_complexangle + COMPLEX(DbKi) :: complexI = (0.0, 1.0) + INTEGER(IntKi) :: Imode, K ! Index used for looping through AWC modes, blades + REAL(DbKi) :: clockang ! Clock angle for AWC pitching + REAL(DbKi) :: omega ! angular frequency for AWC pitching in Hz + REAL(DbKi) :: amp ! amplitude for AWC pitching in degrees + REAL(DbKi), DIMENSION(2) :: AWC_TiltYaw = [0.0, 0.0] ! AWC Tilt and yaw pitch signal + + + ! Compute the AWC pitch settings + IF (CntrPar%AWC_Mode == 1) THEN + + LocalVar%AWC_complexangle = 0.0D0 + + DO Imode = 1,CntrPar%AWC_NumModes + clockang = CntrPar%AWC_clockangle(Imode)*PI/180.0_DbKi + omega = CntrPar%AWC_freq(Imode)*PI*2.0_DbKi + AWC_angle(1) = omega * LocalVar%Time - CntrPar%AWC_n(Imode) * (LocalVar%Azimuth + phi1 + clockang) + AWC_angle(2) = omega * LocalVar%Time - CntrPar%AWC_n(Imode) * (LocalVar%Azimuth + phi2 + clockang) + AWC_angle(3) = omega * LocalVar%Time - CntrPar%AWC_n(Imode) * (LocalVar%Azimuth + phi3 + clockang) + ! Add the forcing contribution to LocalVar%AWC_complexangle + amp = CntrPar%AWC_amp(Imode)*PI/180.0_DbKi + DO K = 1,LocalVar%NumBl ! Loop through all blades + LocalVar%AWC_complexangle(K) = LocalVar%AWC_complexangle(K) + amp * EXP(complexI * (AWC_angle(K))) + END DO + END DO + + DO K = 1,LocalVar%NumBl ! Loop through all blades, apply AWC_angle + LocalVar%PitCom(K) = LocalVar%PitCom(K) + REAL(LocalVar%AWC_complexangle(K)) + END DO + + ELSEIF (CntrPar%AWC_Mode == 2) THEN + + DO Imode = 1,CntrPar%AWC_NumModes + DebugVar%axisTilt_1P = AWC_TiltYaw(1) + AWC_TiltYaw = [0.0, 0.0] + AWC_TiltYaw(Imode) = PI/180*CntrPar%AWC_amp(Imode)*cos(LocalVar%Time*2*PI*CntrPar%AWC_freq(Imode) + CntrPar%AWC_clockangle(Imode)*PI/180) + IF (CntrPar%AWC_NumModes == 1) THEN + AWC_TiltYaw(2) = PI/180*CntrPar%AWC_amp(1)*cos(LocalVar%Time*2*PI*CntrPar%AWC_freq(1) + 2*CntrPar%AWC_clockangle(1)*PI/180) + ENDIF + CALL ColemanTransformInverse(AWC_TiltYaw(1), AWC_TiltYaw(2), LocalVar%Azimuth, CntrPar%AWC_harmonic(Imode), 0.0, AWC_angle) + + DO K = 1,LocalVar%NumBl ! Loop through all blades, apply AWC_angle + LocalVar%PitCom(K) = LocalVar%PitCom(K) + AWC_angle(K) + END DO + END DO + DebugVar%axisYaw_1P = AWC_TiltYaw(2) + DebugVar%axisTilt_2P = AWC_angle(1) + + ENDIF + + END SUBROUTINE ActiveWakeControl + !------------------------------------------------------------------------------------------------------------------------------- SUBROUTINE CableControl(avrSWAP, CntrPar, LocalVar, objInst) ! Cable controller diff --git a/ROSCO/src/ROSCO_IO.f90 b/ROSCO/src/ROSCO_IO.f90 index d3b0ee66..5f53a1ce 100644 --- a/ROSCO/src/ROSCO_IO.f90 +++ b/ROSCO/src/ROSCO_IO.f90 @@ -90,6 +90,12 @@ SUBROUTINE WriteRestartFile(LocalVar, CntrPar, ErrVar, objInst, RootName, size_a WRITE( Un, IOSTAT=ErrStat) LocalVar%IPC_AxisYaw_1P WRITE( Un, IOSTAT=ErrStat) LocalVar%IPC_AxisTilt_2P WRITE( Un, IOSTAT=ErrStat) LocalVar%IPC_AxisYaw_2P + WRITE( Un, IOSTAT=ErrStat) LocalVar%axisTilt_1P + WRITE( Un, IOSTAT=ErrStat) LocalVar%axisYaw_1P + WRITE( Un, IOSTAT=ErrStat) LocalVar%axisYawF_1P + WRITE( Un, IOSTAT=ErrStat) LocalVar%axisTilt_2P + WRITE( Un, IOSTAT=ErrStat) LocalVar%axisYaw_2P + WRITE( Un, IOSTAT=ErrStat) LocalVar%axisYawF_2P WRITE( Un, IOSTAT=ErrStat) LocalVar%IPC_KI(1) WRITE( Un, IOSTAT=ErrStat) LocalVar%IPC_KI(2) WRITE( Un, IOSTAT=ErrStat) LocalVar%IPC_KP(1) @@ -197,6 +203,9 @@ SUBROUTINE WriteRestartFile(LocalVar, CntrPar, ErrVar, objInst, RootName, size_a WRITE( Un, IOSTAT=ErrStat) LocalVar%ACC_INFILE_SIZE WRITE( Un, IOSTAT=ErrStat) LocalVar%ACC_INFILE WRITE( Un, IOSTAT=ErrStat) LocalVar%restart + WRITE( Un, IOSTAT=ErrStat) LocalVar%AWC_complexangle(1) + WRITE( Un, IOSTAT=ErrStat) LocalVar%AWC_complexangle(2) + WRITE( Un, IOSTAT=ErrStat) LocalVar%AWC_complexangle(3) WRITE( Un, IOSTAT=ErrStat) LocalVar%WE%om_r WRITE( Un, IOSTAT=ErrStat) LocalVar%WE%v_t WRITE( Un, IOSTAT=ErrStat) LocalVar%WE%v_m @@ -350,6 +359,12 @@ SUBROUTINE ReadRestartFile(avrSWAP, LocalVar, CntrPar, objInst, PerfData, RootNa READ( Un, IOSTAT=ErrStat) LocalVar%IPC_AxisYaw_1P READ( Un, IOSTAT=ErrStat) LocalVar%IPC_AxisTilt_2P READ( Un, IOSTAT=ErrStat) LocalVar%IPC_AxisYaw_2P + READ( Un, IOSTAT=ErrStat) LocalVar%axisTilt_1P + READ( Un, IOSTAT=ErrStat) LocalVar%axisYaw_1P + READ( Un, IOSTAT=ErrStat) LocalVar%axisYawF_1P + READ( Un, IOSTAT=ErrStat) LocalVar%axisTilt_2P + READ( Un, IOSTAT=ErrStat) LocalVar%axisYaw_2P + READ( Un, IOSTAT=ErrStat) LocalVar%axisYawF_2P READ( Un, IOSTAT=ErrStat) LocalVar%IPC_KI(1) READ( Un, IOSTAT=ErrStat) LocalVar%IPC_KI(2) READ( Un, IOSTAT=ErrStat) LocalVar%IPC_KP(1) @@ -458,6 +473,9 @@ SUBROUTINE ReadRestartFile(avrSWAP, LocalVar, CntrPar, objInst, PerfData, RootNa ALLOCATE(LocalVar%ACC_INFILE(LocalVar%ACC_INFILE_SIZE)) READ( Un, IOSTAT=ErrStat) LocalVar%ACC_INFILE READ( Un, IOSTAT=ErrStat) LocalVar%restart + READ( Un, IOSTAT=ErrStat) LocalVar%AWC_complexangle(1) + READ( Un, IOSTAT=ErrStat) LocalVar%AWC_complexangle(2) + READ( Un, IOSTAT=ErrStat) LocalVar%AWC_complexangle(3) READ( Un, IOSTAT=ErrStat) LocalVar%WE%om_r READ( Un, IOSTAT=ErrStat) LocalVar%WE%v_t READ( Un, IOSTAT=ErrStat) LocalVar%WE%v_m @@ -545,7 +563,7 @@ SUBROUTINE Debug(LocalVar, CntrPar, DebugVar, ErrVar, avrSWAP, RootName, size_av INTEGER(IntKi), INTENT(IN) :: size_avcOUTNAME INTEGER(IntKi) :: I , nDebugOuts, nLocalVars ! Generic index. CHARACTER(1), PARAMETER :: Tab = CHAR(9) ! The tab character. - CHARACTER(29), PARAMETER :: FmtDat = "(F20.5,TR5,99(ES20.5E2,TR5:))" ! The format of the debugging data + CHARACTER(100) :: FmtDat ! The format of the debugging data INTEGER(IntKi), SAVE :: UnDb ! I/O unit for the debugging information INTEGER(IntKi), SAVE :: UnDb2 ! I/O unit for the debugging information, avrSWAP INTEGER(IntKi), SAVE :: UnDb3 ! I/O unit for the debugging information, avrSWAP @@ -603,7 +621,7 @@ SUBROUTINE Debug(LocalVar, CntrPar, DebugVar, ErrVar, avrSWAP, RootName, size_av '[rad/s]', '[rad/s]', '[m/s]', '[rad]', '[rad]', & '[N/A]', '[N/A]', '[N/A]', '[N/A]', '[rad/s]', & '[deg]', '[deg]', '[deg]', '[N/A]'] - nLocalVars = 93 + nLocalVars = 100 Allocate(LocalVarOutData(nLocalVars)) Allocate(LocalVarOutStrings(nLocalVars)) LocalVarOutData(1) = LocalVar%iStatus @@ -649,56 +667,63 @@ SUBROUTINE Debug(LocalVar, CntrPar, DebugVar, ErrVar, avrSWAP, RootName, size_av LocalVarOutData(41) = LocalVar%IPC_AxisYaw_1P LocalVarOutData(42) = LocalVar%IPC_AxisTilt_2P LocalVarOutData(43) = LocalVar%IPC_AxisYaw_2P - LocalVarOutData(44) = LocalVar%IPC_KI(1) - LocalVarOutData(45) = LocalVar%IPC_KP(1) - LocalVarOutData(46) = LocalVar%IPC_IntSat - LocalVarOutData(47) = LocalVar%PC_State - LocalVarOutData(48) = LocalVar%PitCom(1) - LocalVarOutData(49) = LocalVar%PitComAct(1) - LocalVarOutData(50) = LocalVar%SS_DelOmegaF - LocalVarOutData(51) = LocalVar%TestType - LocalVarOutData(52) = LocalVar%VS_MaxTq - LocalVarOutData(53) = LocalVar%VS_LastGenTrq - LocalVarOutData(54) = LocalVar%VS_LastGenPwr - LocalVarOutData(55) = LocalVar%VS_MechGenPwr - LocalVarOutData(56) = LocalVar%VS_SpdErrAr - LocalVarOutData(57) = LocalVar%VS_SpdErrBr - LocalVarOutData(58) = LocalVar%VS_SpdErr - LocalVarOutData(59) = LocalVar%VS_State - LocalVarOutData(60) = LocalVar%VS_Rgn3Pitch - LocalVarOutData(61) = LocalVar%WE_Vw - LocalVarOutData(62) = LocalVar%WE_Vw_F - LocalVarOutData(63) = LocalVar%WE_VwI - LocalVarOutData(64) = LocalVar%WE_VwIdot - LocalVarOutData(65) = LocalVar%VS_LastGenTrqF - LocalVarOutData(66) = LocalVar%Fl_PitCom - LocalVarOutData(67) = LocalVar%NACIMU_FA_AccF - LocalVarOutData(68) = LocalVar%FA_AccF - LocalVarOutData(69) = LocalVar%PtfmTDX - LocalVarOutData(70) = LocalVar%PtfmTDY - LocalVarOutData(71) = LocalVar%PtfmTDZ - LocalVarOutData(72) = LocalVar%PtfmRDX - LocalVarOutData(73) = LocalVar%PtfmRDY - LocalVarOutData(74) = LocalVar%PtfmRDZ - LocalVarOutData(75) = LocalVar%PtfmTVX - LocalVarOutData(76) = LocalVar%PtfmTVY - LocalVarOutData(77) = LocalVar%PtfmTVZ - LocalVarOutData(78) = LocalVar%PtfmRVX - LocalVarOutData(79) = LocalVar%PtfmRVY - LocalVarOutData(80) = LocalVar%PtfmRVZ - LocalVarOutData(81) = LocalVar%PtfmTAX - LocalVarOutData(82) = LocalVar%PtfmTAY - LocalVarOutData(83) = LocalVar%PtfmTAZ - LocalVarOutData(84) = LocalVar%PtfmRAX - LocalVarOutData(85) = LocalVar%PtfmRAY - LocalVarOutData(86) = LocalVar%PtfmRAZ - LocalVarOutData(87) = LocalVar%CC_DesiredL(1) - LocalVarOutData(88) = LocalVar%CC_ActuatedL(1) - LocalVarOutData(89) = LocalVar%CC_ActuatedDL(1) - LocalVarOutData(90) = LocalVar%StC_Input(1) - LocalVarOutData(91) = LocalVar%Flp_Angle(1) - LocalVarOutData(92) = LocalVar%RootMyb_Last(1) - LocalVarOutData(93) = LocalVar%ACC_INFILE_SIZE + LocalVarOutData(44) = LocalVar%axisTilt_1P + LocalVarOutData(45) = LocalVar%axisYaw_1P + LocalVarOutData(46) = LocalVar%axisYawF_1P + LocalVarOutData(47) = LocalVar%axisTilt_2P + LocalVarOutData(48) = LocalVar%axisYaw_2P + LocalVarOutData(49) = LocalVar%axisYawF_2P + LocalVarOutData(50) = LocalVar%IPC_KI(1) + LocalVarOutData(51) = LocalVar%IPC_KP(1) + LocalVarOutData(52) = LocalVar%IPC_IntSat + LocalVarOutData(53) = LocalVar%PC_State + LocalVarOutData(54) = LocalVar%PitCom(1) + LocalVarOutData(55) = LocalVar%PitComAct(1) + LocalVarOutData(56) = LocalVar%SS_DelOmegaF + LocalVarOutData(57) = LocalVar%TestType + LocalVarOutData(58) = LocalVar%VS_MaxTq + LocalVarOutData(59) = LocalVar%VS_LastGenTrq + LocalVarOutData(60) = LocalVar%VS_LastGenPwr + LocalVarOutData(61) = LocalVar%VS_MechGenPwr + LocalVarOutData(62) = LocalVar%VS_SpdErrAr + LocalVarOutData(63) = LocalVar%VS_SpdErrBr + LocalVarOutData(64) = LocalVar%VS_SpdErr + LocalVarOutData(65) = LocalVar%VS_State + LocalVarOutData(66) = LocalVar%VS_Rgn3Pitch + LocalVarOutData(67) = LocalVar%WE_Vw + LocalVarOutData(68) = LocalVar%WE_Vw_F + LocalVarOutData(69) = LocalVar%WE_VwI + LocalVarOutData(70) = LocalVar%WE_VwIdot + LocalVarOutData(71) = LocalVar%VS_LastGenTrqF + LocalVarOutData(72) = LocalVar%Fl_PitCom + LocalVarOutData(73) = LocalVar%NACIMU_FA_AccF + LocalVarOutData(74) = LocalVar%FA_AccF + LocalVarOutData(75) = LocalVar%PtfmTDX + LocalVarOutData(76) = LocalVar%PtfmTDY + LocalVarOutData(77) = LocalVar%PtfmTDZ + LocalVarOutData(78) = LocalVar%PtfmRDX + LocalVarOutData(79) = LocalVar%PtfmRDY + LocalVarOutData(80) = LocalVar%PtfmRDZ + LocalVarOutData(81) = LocalVar%PtfmTVX + LocalVarOutData(82) = LocalVar%PtfmTVY + LocalVarOutData(83) = LocalVar%PtfmTVZ + LocalVarOutData(84) = LocalVar%PtfmRVX + LocalVarOutData(85) = LocalVar%PtfmRVY + LocalVarOutData(86) = LocalVar%PtfmRVZ + LocalVarOutData(87) = LocalVar%PtfmTAX + LocalVarOutData(88) = LocalVar%PtfmTAY + LocalVarOutData(89) = LocalVar%PtfmTAZ + LocalVarOutData(90) = LocalVar%PtfmRAX + LocalVarOutData(91) = LocalVar%PtfmRAY + LocalVarOutData(92) = LocalVar%PtfmRAZ + LocalVarOutData(93) = LocalVar%CC_DesiredL(1) + LocalVarOutData(94) = LocalVar%CC_ActuatedL(1) + LocalVarOutData(95) = LocalVar%CC_ActuatedDL(1) + LocalVarOutData(96) = LocalVar%StC_Input(1) + LocalVarOutData(97) = LocalVar%Flp_Angle(1) + LocalVarOutData(98) = LocalVar%RootMyb_Last(1) + LocalVarOutData(99) = LocalVar%ACC_INFILE_SIZE + LocalVarOutData(100) = LocalVar%AWC_complexangle(1) LocalVarOutStrings = [CHARACTER(15) :: 'iStatus', 'Time', 'DT', 'VS_GenPwr', 'GenSpeed', & 'RotSpeed', 'NacHeading', 'NacVane', 'HorWindV', 'rootMOOP', & 'rootMOOPF', 'BlPitch', 'BlPitchCMeas', 'Azimuth', 'NumBl', & @@ -707,17 +732,19 @@ SUBROUTINE Debug(LocalVar, CntrPar, DebugVar, ErrVar, avrSWAP, RootName, size_av 'GenBrTq', 'IPC_PitComF', 'PC_KP', 'PC_KI', 'PC_KD', & 'PC_TF', 'PC_MaxPit', 'PC_MinPit', 'PC_PitComT', 'PC_PitComT_Last', & 'PC_PitComTF', 'PC_PitComT_IPC', 'PC_PwrErr', 'PC_SpdErr', 'IPC_AxisTilt_1P', & - 'IPC_AxisYaw_1P', 'IPC_AxisTilt_2P', 'IPC_AxisYaw_2P', 'IPC_KI', 'IPC_KP', & - 'IPC_IntSat', 'PC_State', 'PitCom', 'PitComAct', 'SS_DelOmegaF', & - 'TestType', 'VS_MaxTq', 'VS_LastGenTrq', 'VS_LastGenPwr', 'VS_MechGenPwr', & - 'VS_SpdErrAr', 'VS_SpdErrBr', 'VS_SpdErr', 'VS_State', 'VS_Rgn3Pitch', & - 'WE_Vw', 'WE_Vw_F', 'WE_VwI', 'WE_VwIdot', 'VS_LastGenTrqF', & - 'Fl_PitCom', 'NACIMU_FA_AccF', 'FA_AccF', 'PtfmTDX', 'PtfmTDY', & - 'PtfmTDZ', 'PtfmRDX', 'PtfmRDY', 'PtfmRDZ', 'PtfmTVX', & - 'PtfmTVY', 'PtfmTVZ', 'PtfmRVX', 'PtfmRVY', 'PtfmRVZ', & - 'PtfmTAX', 'PtfmTAY', 'PtfmTAZ', 'PtfmRAX', 'PtfmRAY', & - 'PtfmRAZ', 'CC_DesiredL', 'CC_ActuatedL', 'CC_ActuatedDL', 'StC_Input', & - 'Flp_Angle', 'RootMyb_Last', 'ACC_INFILE_SIZE'] + 'IPC_AxisYaw_1P', 'IPC_AxisTilt_2P', 'IPC_AxisYaw_2P', 'axisTilt_1P', 'axisYaw_1P', & + 'axisYawF_1P', 'axisTilt_2P', 'axisYaw_2P', 'axisYawF_2P', 'IPC_KI', & + 'IPC_KP', 'IPC_IntSat', 'PC_State', 'PitCom', 'PitComAct', & + 'SS_DelOmegaF', 'TestType', 'VS_MaxTq', 'VS_LastGenTrq', 'VS_LastGenPwr', & + 'VS_MechGenPwr', 'VS_SpdErrAr', 'VS_SpdErrBr', 'VS_SpdErr', 'VS_State', & + 'VS_Rgn3Pitch', 'WE_Vw', 'WE_Vw_F', 'WE_VwI', 'WE_VwIdot', & + 'VS_LastGenTrqF', 'Fl_PitCom', 'NACIMU_FA_AccF', 'FA_AccF', 'PtfmTDX', & + 'PtfmTDY', 'PtfmTDZ', 'PtfmRDX', 'PtfmRDY', 'PtfmRDZ', & + 'PtfmTVX', 'PtfmTVY', 'PtfmTVZ', 'PtfmRVX', 'PtfmRVY', & + 'PtfmRVZ', 'PtfmTAX', 'PtfmTAY', 'PtfmTAZ', 'PtfmRAX', & + 'PtfmRAY', 'PtfmRAZ', 'CC_DesiredL', 'CC_ActuatedL', 'CC_ActuatedDL', & + 'StC_Input', 'Flp_Angle', 'RootMyb_Last', 'ACC_INFILE_SIZE', 'AWC_complexangle' & + ] ! Initialize debug file IF ((LocalVar%iStatus == 0) .OR. (LocalVar%iStatus == -9)) THEN ! .TRUE. if we're on the first call to the DLL IF (CntrPar%LoggingLevel > 0) THEN @@ -732,8 +759,8 @@ SUBROUTINE Debug(LocalVar, CntrPar, DebugVar, ErrVar, avrSWAP, RootName, size_av CALL GetNewUnit(UnDb2, ErrVar) OPEN(unit=UnDb2, FILE=TRIM(RootName)//'.RO.dbg2') WRITE(UnDb2, *) 'Generated on '//CurDate()//' at '//CurTime()//' using ROSCO-'//TRIM(rosco_version) - WRITE(UnDb2, '(99(a20,TR5:))') 'Time', LocalVarOutStrings - WRITE(UnDb2, '(99(a20,TR5:))') + WRITE(UnDb2, '(101(a20,TR5:))') 'Time', LocalVarOutStrings + WRITE(UnDb2, '(101(a20,TR5:))') END IF IF (CntrPar%LoggingLevel > 2) THEN @@ -790,16 +817,17 @@ SUBROUTINE Debug(LocalVar, CntrPar, DebugVar, ErrVar, avrSWAP, RootName, size_av END DO ! Write debug files + FmtDat = "(F20.5,TR5,100(ES20.5E2,TR5:))" ! The format of the debugging data IF(CntrPar%LoggingLevel > 0) THEN - WRITE (UnDb, FmtDat) LocalVar%Time, DebugOutData + WRITE (UnDb, TRIM(FmtDat)) LocalVar%Time, DebugOutData END IF IF(CntrPar%LoggingLevel > 1) THEN - WRITE (UnDb2, FmtDat) LocalVar%Time, LocalVarOutData + WRITE (UnDb2, TRIM(FmtDat)) LocalVar%Time, LocalVarOutData END IF IF(CntrPar%LoggingLevel > 2) THEN - WRITE (UnDb3, FmtDat) LocalVar%Time, avrSWAP(avrIndices) + WRITE (UnDb3, TRIM(FmtDat)) LocalVar%Time, avrSWAP(avrIndices) END IF END SUBROUTINE Debug diff --git a/ROSCO/src/ROSCO_Types.f90 b/ROSCO/src/ROSCO_Types.f90 index 3988f93a..987f1a6c 100644 --- a/ROSCO/src/ROSCO_Types.f90 +++ b/ROSCO/src/ROSCO_Types.f90 @@ -115,6 +115,13 @@ MODULE ROSCO_Types INTEGER(IntKi) :: PA_Mode ! Pitch actuator mode {0 - not used, 1 - first order filter, 2 - second order filter} REAL(DbKi) :: PA_CornerFreq ! Pitch actuator bandwidth/cut-off frequency [rad/s] REAL(DbKi) :: PA_Damping ! Pitch actuator damping ratio [-, unused if PA_Mode = 1] + INTEGER(IntKi) :: AWC_Mode ! Active wake control mode [0 - unused, 1 - SNL method, 2 - NREL method] + INTEGER(IntKi) :: AWC_NumModes ! AWC- Number of modes to include [-] + INTEGER(IntKi), DIMENSION(:), ALLOCATABLE :: AWC_n ! AWC azimuthal mode [-] + INTEGER(IntKi), DIMENSION(:), ALLOCATABLE :: AWC_harmonic ! AWC AWC Coleman transform harmonic [-] + REAL(DbKi), DIMENSION(:), ALLOCATABLE :: AWC_freq ! AWC frequency [Hz] + REAL(DbKi), DIMENSION(:), ALLOCATABLE :: AWC_amp ! AWC amplitude [deg] + REAL(DbKi), DIMENSION(:), ALLOCATABLE :: AWC_clockangle ! AWC clocking angle [deg] INTEGER(IntKi) :: PF_Mode ! Pitch actuator fault mode {0 - not used, 1 - offsets on one or more blades} REAL(DbKi), DIMENSION(:), ALLOCATABLE :: PF_Offsets ! Pitch actuator fault offsets for blade 1-3 [rad/s] INTEGER(IntKi) :: Ext_Mode ! External control mode (0 - not used, 1 - call external control library) @@ -250,6 +257,12 @@ MODULE ROSCO_Types REAL(DbKi) :: IPC_AxisYaw_1P ! Integral of quadrature, 1P REAL(DbKi) :: IPC_AxisTilt_2P ! Integral of the direct axis, 2P REAL(DbKi) :: IPC_AxisYaw_2P ! Integral of quadrature, 2P + REAL(DbKi) :: axisTilt_1P ! Tilt moment, 1P + REAL(DbKi) :: axisYaw_1P ! Yaw moment, 1P + REAL(DbKi) :: axisYawF_1P ! Filtered yaw moment, 1P + REAL(DbKi) :: axisTilt_2P ! Tilt moment, 2P + REAL(DbKi) :: axisYaw_2P ! Yaw moment, 2P + REAL(DbKi) :: axisYawF_2P ! Filtered yaw moment, 2P REAL(DbKi) :: IPC_KI(2) ! Integral gain for IPC, after ramp [-] REAL(DbKi) :: IPC_KP(2) ! Proportional gain for IPC, after ramp [-] REAL(DbKi) :: IPC_IntSat ! Integrator saturation (maximum signal amplitude contrbution to pitch from IPC) @@ -303,6 +316,7 @@ MODULE ROSCO_Types INTEGER(IntKi) :: ACC_INFILE_SIZE ! Length of parameter input filename CHARACTER, DIMENSION(:), ALLOCATABLE :: ACC_INFILE ! Parameter input filename LOGICAL :: restart ! Restart flag + COMPLEX(DbKi) :: AWC_complexangle(3) ! Complex angle for each blade, sum of modes? TYPE(WE) :: WE ! Wind speed estimator parameters derived type TYPE(FilterParameters) :: FP ! Filter parameters derived type TYPE(piParams) :: piP ! PI parameters derived type diff --git a/ROSCO/src/ReadSetParameters.f90 b/ROSCO/src/ReadSetParameters.f90 index a7f912af..dcaecbc1 100644 --- a/ROSCO/src/ReadSetParameters.f90 +++ b/ROSCO/src/ReadSetParameters.f90 @@ -364,6 +364,7 @@ SUBROUTINE ReadControlParameterFileSub(CntrPar, zmqVar, accINFILE, accINFILE_siz CALL ParseInput(FileLines,'OL_Mode', CntrPar%OL_Mode, accINFILE(1), ErrVar, UnEc=UnEc) CALL ParseInput(FileLines,'PA_Mode', CntrPar%PA_Mode, accINFILE(1), ErrVar, UnEc=UnEc) CALL ParseInput(FileLines,'PF_Mode', CntrPar%PF_Mode, accINFILE(1), ErrVar, UnEc=UnEc) + CALL ParseInput(FileLines,'AWC_Mode', CntrPar%AWC_Mode, accINFILE(1), ErrVar, UnEc=UnEc) CALL ParseInput(FileLines,'Ext_Mode', CntrPar%Ext_Mode, accINFILE(1), ErrVar, UnEc=UnEc) CALL ParseInput(FileLines,'ZMQ_Mode', CntrPar%ZMQ_Mode, accINFILE(1), ErrVar, UnEc=UnEc) CALL ParseInput(FileLines,'CC_Mode', CntrPar%CC_Mode, accINFILE(1), ErrVar, UnEc=UnEc) @@ -504,6 +505,15 @@ SUBROUTINE ReadControlParameterFileSub(CntrPar, zmqVar, accINFILE, accINFILE_siz CALL ParseAry(FileLines, 'PF_Offsets', CntrPar%PF_Offsets, 3, accINFILE(1), ErrVar, CntrPar%PF_Mode == 0, UnEc) IF (ErrVar%aviFAIL < 0) RETURN + !------------ AWC input ------------ + CALL ParseInput(FileLines, 'AWC_NumModes', CntrPar%AWC_NumModes, accINFILE(1), ErrVar, CntrPar%AWC_Mode == 0, UnEc) + CALL ParseAry( FileLines, 'AWC_n', CntrPar%AWC_n, CntrPar%AWC_NumModes, accINFILE(1), ErrVar, CntrPar%AWC_Mode /= 1, UnEc) + CALL ParseAry( FileLines, 'AWC_harmonic', CntrPar%AWC_harmonic, CntrPar%AWC_NumModes, accINFILE(1), ErrVar, CntrPar%AWC_Mode < 2, UnEc) + CALL ParseAry( FileLines, 'AWC_freq', CntrPar%AWC_freq, CntrPar%AWC_NumModes, accINFILE(1), ErrVar, CntrPar%AWC_Mode == 0, UnEc) + CALL ParseAry( FileLines, 'AWC_amp', CntrPar%AWC_amp, CntrPar%AWC_NumModes, accINFILE(1), ErrVar, CntrPar%AWC_Mode == 0, UnEc) + CALL ParseAry( FileLines, 'AWC_clockangle', CntrPar%AWC_clockangle, CntrPar%AWC_NumModes, accINFILE(1), ErrVar, CntrPar%AWC_Mode == 0, UnEc) + IF (ErrVar%aviFAIL < 0) RETURN + !------------ External control interface ------------ CALL ParseInput(FileLines, 'DLL_FileName', CntrPar%DLL_FileName, accINFILE(1), ErrVar, CntrPar%Ext_Mode == 0, UnEc) CALL ParseInput(FileLines, 'DLL_InFile', CntrPar%DLL_InFile, accINFILE(1), ErrVar, CntrPar%Ext_Mode == 0, UnEc) @@ -638,6 +648,7 @@ SUBROUTINE CheckInputs(LocalVar, CntrPar, avrSWAP, ErrVar, size_avcMSG) TYPE(LocalVariables), INTENT(IN ) :: LocalVar TYPE(ErrorVariables), INTENT(INOUT) :: ErrVar INTEGER(IntKi), INTENT(IN ) :: size_avcMSG + INTEGER(IntKi) :: Imode ! Index used for looping through AWC modes REAL(ReKi), INTENT(IN ) :: avrSWAP(*) ! The swap array, used to pass data to, and receive data from, the DLL controller. CHARACTER(*), PARAMETER :: RoutineName = 'CheckInputs' @@ -1078,6 +1089,11 @@ SUBROUTINE CheckInputs(LocalVar, CntrPar, avrSWAP, ErrVar, size_avcMSG) ENDIF ENDIF + ! ---- AWC vs. IPC + IF (CntrPar%AWC_Mode > 0 .AND. CntrPar%IPC_ControlMode > 0) THEN + PRINT *, "ROSCO WARNING: Individual pitch control and active wake control are both enabled. Performance may be compromised." + ENDIF + ! --- Pitch Actuator --- IF (CntrPar%PA_Mode > 0) THEN IF ((CntrPar%PA_Mode < 0) .OR. (CntrPar%PA_Mode > 2)) THEN @@ -1094,6 +1110,49 @@ SUBROUTINE CheckInputs(LocalVar, CntrPar, avrSWAP, ErrVar, size_avcMSG) END IF END IF + ! --- Active Wake Control --- + IF (CntrPar%AWC_Mode > 0) THEN + IF (CntrPar%AWC_NumModes < 0) THEN + ErrVar%aviFAIL = -1 + ErrVar%ErrMsg = 'AWC_NumModes must be a positive integer if AWC_Mode = 1' + END IF + DO Imode = 1,CntrPar%AWC_NumModes + IF (CntrPar%AWC_freq(Imode) < 0.0) THEN + ErrVar%aviFAIL = -1 + ErrVar%ErrMsg = 'AWC_freq cannot be less than 0' + END IF + IF (CntrPar%AWC_amp(Imode) < 0.0) THEN + ErrVar%aviFAIL = -1 + ErrVar%ErrMsg = 'AWC_amp cannot be less than 0' + END IF + END DO + IF (CntrPar%AWC_Mode == 1) THEN + DO Imode = 1,CntrPar%AWC_NumModes + IF ((CntrPar%AWC_clockangle(Imode) > 360.0) .OR. (CntrPar%AWC_clockangle(Imode) < 0.0)) THEN + ErrVar%aviFAIL = -1 + ErrVar%ErrMsg = 'AWC_clockangle must be between 0 and 360 in AWC_Mode = 1' + END IF + END DO + END IF + + IF (CntrPar%AWC_Mode == 2) THEN + IF ((CntrPar%AWC_NumModes > 2) .OR. (CntrPar%AWC_NumModes < 1)) THEN + ErrVar%aviFAIL = -1 + ErrVar%ErrMsg = 'AWC_NumModes must be either 1 or 2 if AWC_Mode = 2' + END IF + DO Imode = 1,CntrPar%AWC_NumModes + IF ((CntrPar%AWC_clockangle(Imode) > 360.0) .OR. (CntrPar%AWC_clockangle(Imode) < -360.0)) THEN + ErrVar%aviFAIL = -1 + ErrVar%ErrMsg = 'AWC_clockangle must be between -360 and 360 in AWC_Mode = 2' + END IF + IF (CntrPar%AWC_harmonic(Imode) < 0) THEN + ErrVar%aviFAIL = -1 + ErrVar%ErrMsg = 'AWC_harmonic must be a positive integer' + END IF + END DO + END IF + END IF + IF ((CntrPar%CC_Mode < 0) .OR. (CntrPar%CC_Mode > 1)) THEN ErrVar%aviFAIL = -1 ErrVar%ErrMsg = 'CC_Mode must be 0 or 1' diff --git a/ROSCO_testing/ROSCO_testing.py b/ROSCO_testing/ROSCO_testing.py index 00535118..7ddfea70 100644 --- a/ROSCO_testing/ROSCO_testing.py +++ b/ROSCO_testing/ROSCO_testing.py @@ -17,7 +17,6 @@ import glob import multiprocessing as mp -import ROSCO_toolbox.ofTools.fast_io.read_fast_input as fast_io from ROSCO_toolbox.ofTools.fast_io.FAST_reader import InputReader_OpenFAST from ROSCO_toolbox.ofTools.case_gen.CaseGen_IEC import CaseGen_IEC from ROSCO_toolbox.ofTools.case_gen.runFAST_pywrapper import runFAST_pywrapper_batch @@ -545,6 +544,8 @@ def print_results(self,outfiles): if __name__=='__main__': rt = ROSCO_testing() + this_dir = os.path.dirname(__file__) + ## =================== INITIALIZATION =================== # Setup simulation parameters @@ -553,14 +554,14 @@ def print_results(self,outfiles): rt.Turbsim_exe = 'turbsim' # Turbsim executable path # path to compiled ROSCO controller if platform.system() == 'Windows': - rt.rosco_path = os.path.join(os.getcwd(), '../ROSCO/build/libdiscon.dll') + rt.rosco_path = os.path.join(this_dir, '../ROSCO/build/libdiscon.dll') elif platform.system() == 'Darwin': - rt.rosco_path = os.path.join(os.getcwd(), '../ROSCO/build/libdiscon.dylib') + rt.rosco_path = os.path.join(this_dir, '../ROSCO/build/libdiscon.dylib') else: - rt.rosco_path = os.path.join(os.getcwd(), '../ROSCO/build/libdiscon.so') + rt.rosco_path = os.path.join(this_dir, '../ROSCO/build/libdiscon.so') rt.debug_level = 2 # debug level. 0 - no outputs, 1 - minimal outputs, 2 - all outputs rt.overwrite = True # overwite fast sims? - rt.cores = 4 # number of cores if multiprocessings + rt.cores = 1 # number of cores if multiprocessings rt.mpi_run = False # run using mpi rt.mpi_comm_map_down = [] # core mapping for MPI rt.outfile_fmt = 2 # 1 = .txt, 2 = binary, 3 = both @@ -568,7 +569,7 @@ def print_results(self,outfiles): # Setup turbine rt.Turbine_Class = 'I' rt.Turbulence_Class = 'B' - rt.FAST_directory = os.path.join(os.getcwd(), '../Test_Cases/IEA-15-240-RWT-UMaineSemi') + rt.FAST_directory = os.path.join(this_dir, '../Test_Cases/IEA-15-240-RWT-UMaineSemi') rt.FAST_InputFile = 'IEA-15-240-RWT-UMaineSemi.fst' # Additional inputs @@ -584,7 +585,7 @@ def print_results(self,outfiles): case_inputs[('DISCON_in', 'WE_Mode')] = {'vals': [2], 'group': 0} # Wind Speeds - U = [5, 9, 12, 15] + U = [5] # Run test rt.ROSCO_Test_lite(more_case_inputs=case_inputs, U=U) diff --git a/ROSCO_toolbox/controller.py b/ROSCO_toolbox/controller.py index c780daab..13672371 100644 --- a/ROSCO_toolbox/controller.py +++ b/ROSCO_toolbox/controller.py @@ -63,8 +63,9 @@ def __init__(self, controller_params): self.Fl_Mode = controller_params['Fl_Mode'] self.TD_Mode = controller_params['TD_Mode'] self.Flp_Mode = controller_params['Flp_Mode'] - self.PA_Mode = controller_params['PA_Mode'] - self.PF_Mode = controller_params['PF_Mode'] + self.PA_Mode = controller_params['PA_Mode'] + self.PF_Mode = controller_params['PF_Mode'] + self.AWC_Mode = controller_params['AWC_Mode'] self.Ext_Mode = controller_params['Ext_Mode'] self.ZMQ_Mode = controller_params['ZMQ_Mode'] self.CC_Mode = controller_params['CC_Mode'] diff --git a/ROSCO_toolbox/inputs/toolbox_schema.yaml b/ROSCO_toolbox/inputs/toolbox_schema.yaml index da3f21f8..c5d08c74 100644 --- a/ROSCO_toolbox/inputs/toolbox_schema.yaml +++ b/ROSCO_toolbox/inputs/toolbox_schema.yaml @@ -203,6 +203,12 @@ properties: maximum: 1 default: 0 description: Pitch fault mode {0 - not used, 1 - constant offset on one or more blades} + AWC_Mode: + type: number + minimum: 0 + maximum: 2 + default: 0 + description: Active wake control mode {0 - not used, 1 - SNL method, 2 - NREL method} Ext_Mode: type: number minimum: 0 @@ -880,6 +886,7 @@ properties: type: number description: Pitch angle offsets for each blade (array with length of 3) units: rad + default: [0,0,0] CC_Group_N: type: number description: Number of cable control groups @@ -904,6 +911,50 @@ properties: type: number description: First index for structural control group, options specified in ServoDyn summary output default: [0] + AWC_Mode: + type: number + minimum: 0 + maximum: 2 + default: 0 + description: Active wake control mode {0 - not used, 1 - complex number method, 2 - Coleman transformation method} + AWC_NumModes: + type: number + description: Number of AWC modes + units: rad + default: 1 + AWC_n: + type: array + items: + type: number + description: AWC azimuthal number (only used in complex number method) + default: [1] + AWC_harmonic: + type: array + items: + type: integer + description: AWC Coleman transform harmonic (only used in Coleman transform method) + default: [1] + AWC_freq: + type: array + items: + type: number + description: AWC frequency [Hz] + units: Hz + default: [0.05] + AWC_amp: + type: array + items: + type: number + description: AWC amplitude [deg] + units: deg + default: [1.0] + AWC_clockangle: + type: array + items: + type: number + description: AWC clock angle [deg] + units: deg + default: [0] linmodel_tuning: type: object diff --git a/ROSCO_toolbox/ofTools/case_gen/CaseLibrary.py b/ROSCO_toolbox/ofTools/case_gen/CaseLibrary.py index aa4d1ce4..e6aef0bf 100644 --- a/ROSCO_toolbox/ofTools/case_gen/CaseLibrary.py +++ b/ROSCO_toolbox/ofTools/case_gen/CaseLibrary.py @@ -127,7 +127,7 @@ def power_curve(**wind_case_opts): # Constant wind speed, multiple wind speeds, define below # Runtime - T_max = 400. + T_max = wind_case_opts.get('TMax',400.) if 'U' in wind_case_opts: U = wind_case_opts['U'] @@ -363,6 +363,42 @@ def user_hh(**wind_case_opts): case_inputs[("InflowWind","Filename_Uni")] = {'vals':wind_case_opts['wind_filenames'], 'group':1} return case_inputs + +def ramp(**wind_case_opts): + U_start = wind_case_opts.get('U_start',8.) + U_end = wind_case_opts.get('U_end',15.) + t_start = wind_case_opts.get('t_start',100.) + t_end = wind_case_opts.get('t_end',400.) + vert_shear = wind_case_opts.get('vert_shear',.2) + both_dir = wind_case_opts.get('both_dir',False) # ramp up and down + + # Make Default step wind object + hh_wind = HH_WindFile() + hh_wind.t_max = t_end + hh_wind.filename = os.path.join(wind_case_opts['run_dir'],'ramp.hh') + + # Step Wind Setup + if both_dir: + hh_wind.time = [0, t_start, (t_start + t_end) / 2, t_end] + hh_wind.wind_speed = [U_start, U_start, U_end, U_start] + else: + hh_wind.time = [0, t_start, t_end] + hh_wind.wind_speed = [U_start, U_start, U_end] + + hh_wind.vert_shear = [vert_shear] * len(hh_wind.time) + + hh_wind.resample() + hh_wind.write() + + case_inputs = base_op_case() + case_inputs[("Fst","TMax")] = {'vals':[t_end], 'group':0} + case_inputs[("InflowWind","WindType")] = {'vals':[2], 'group':0} + case_inputs[("InflowWind","Filename_Uni")] = {'vals':[hh_wind.filename], 'group':0} + + return case_inputs + + + ############################################################################################## # @@ -432,9 +468,9 @@ def sweep_pitch_act(start_group, **control_sweep_opts): def sweep_ipc_gains(start_group, **control_sweep_opts): case_inputs_control = {} - kis = np.linspace(0,1,6).tolist() + kis = np.linspace(0,1,8).tolist() # kis = [0.,0.6,1.2,1.8,2.4,3.] - KIs = [[ki * 6e-9,0.] for ki in kis] + KIs = [[ki * 12e-9,0.] for ki in kis] case_inputs_control[('DISCON_in','IPC_ControlMode')] = {'vals': [1], 'group': 0} # case_inputs_control[('DISCON_in','IPC_KI')] = {'vals': [[0.,0.],[1e-8,0.]], 'group': start_group} case_inputs_control[('DISCON_in','IPC_KI')] = {'vals': KIs, 'group': start_group} diff --git a/ROSCO_toolbox/ofTools/case_gen/HH_WindFile.py b/ROSCO_toolbox/ofTools/case_gen/HH_WindFile.py index a74205ce..54ed2ff5 100644 --- a/ROSCO_toolbox/ofTools/case_gen/HH_WindFile.py +++ b/ROSCO_toolbox/ofTools/case_gen/HH_WindFile.py @@ -44,16 +44,38 @@ def __init__(self,**kwargs): super(HH_WindFile, self).__init__() + def resample(self): + # Using time index, check if constant, otherwise throw a warning + if len(set(self.wind_dir)) != 1: # all same + print('ROSCO Warning: all wind_dir elements not equal in resample') + if len(set(self.vert_speed)) != 1: # all same + print('ROSCO Warning: all vert_speed elements not equal in resample') + if len(set(self.horiz_shear)) != 1: # all same + print('ROSCO Warning: all horiz_shear elements not equal in resample') + if len(set(self.vert_shear)) != 1: # all same + print('ROSCO Warning: all vert_shear elements not equal in resample') + if len(set(self.linv_shear)) != 1: # all same + print('ROSCO Warning: all linv_shear elements not equal in resample') + if len(set(self.gust_speed)) != 1: # all same + print('ROSCO Warning: all gust_speed elements not equal in resample') + + self.wind_dir = len(self.time) * [self.wind_dir[0]] + self.vert_speed = len(self.time) * [self.vert_speed[0]] + self.horiz_shear = len(self.time) * [self.horiz_shear[0]] + self.vert_shear = len(self.time) * [self.vert_shear[0]] + self.linv_shear = len(self.time) * [self.linv_shear[0]] + self.gust_speed = len(self.time) * [self.gust_speed[0]] + def write(self): if not os.path.isdir(os.path.dirname(self.filename)): os.makedirs(os.path.dirname(self.filename)) with open(self.filename,'w') as f: f.write('!\tTime\tWind Speed\tWind Dir\tVert. Spd.\tHoriz. Shr.\t Vert. Shr.\t LinV. Shr.\tGust Speed\n') - for t, ws, wd, vs, hs, vs, ls, gs in zip(self.time,self.wind_speed,self.wind_dir,self.vert_speed, \ + for t, ws, wd, vsp, hs, vsh, ls, gs in zip(self.time,self.wind_speed,self.wind_dir,self.vert_speed, \ self.horiz_shear, self.vert_shear, self.linv_shear, self.gust_speed): f.write('{:6.6f}\t{:6.6f}\t{:6.6f}\t{:6.6f}\t{:6.6f}\t{:6.6f}\t{:6.6f}\t{:6.6f}\n'.format( - t,ws,wd,vs,hs,vs,ls,gs)) + t,ws,wd,vsp,hs,vsh,ls,gs)) def plot(self): diff --git a/ROSCO_toolbox/ofTools/fast_io/FAST_reader.py b/ROSCO_toolbox/ofTools/fast_io/FAST_reader.py index c2c7e156..adf08ae2 100644 --- a/ROSCO_toolbox/ofTools/fast_io/FAST_reader.py +++ b/ROSCO_toolbox/ofTools/fast_io/FAST_reader.py @@ -797,8 +797,8 @@ def read_AeroDyn15(self): f.readline() self.fst_vt['AeroDyn15']['UAMod'] = int(f.readline().split()[0]) self.fst_vt['AeroDyn15']['FLookup'] = bool_read(f.readline().split()[0]) - # self.fst_vt['AeroDyn15']['UAStartRad'] = float_read(f.readline().split()[0]) - # self.fst_vt['AeroDyn15']['UAEndRad'] = float_read(f.readline().split()[0]) + #self.fst_vt['AeroDyn15']['UAStartRad'] = float_read(f.readline().split()[0]) + #self.fst_vt['AeroDyn15']['UAEndRad'] = float_read(f.readline().split()[0]) # Airfoil Information f.readline() diff --git a/ROSCO_toolbox/ofTools/fast_io/output_processing.py b/ROSCO_toolbox/ofTools/fast_io/output_processing.py index 266a9da2..ef3684b1 100644 --- a/ROSCO_toolbox/ofTools/fast_io/output_processing.py +++ b/ROSCO_toolbox/ofTools/fast_io/output_processing.py @@ -15,6 +15,7 @@ from matplotlib import transforms from itertools import takewhile import struct +import multiprocessing as mp from ROSCO_toolbox.ofTools.util import spectral @@ -39,7 +40,7 @@ def __init__(self, filenames=[], cases=None, tmin=None, tmax=None, verbose=False if len(filenames) > 0: self.load_fast_out(filenames, tmin=tmin, tmax=tmax, verbose=verbose) - def load_fast_out(self, filenames, tmin=None, tmax=None, verbose=False): + def load_fast_out(self, filenames, tmin=None, tmax=None, verbose=False, max_cores=4): """Load a FAST binary or ascii output file Parameters @@ -52,6 +53,8 @@ def load_fast_out(self, filenames, tmin=None, tmax=None, verbose=False): final data to trim output data to verbose : bool, optional Print updates + max_cores: int, optional + Maximum number of cores to use for loading outputs in parallel Returns ------- @@ -60,30 +63,30 @@ def load_fast_out(self, filenames, tmin=None, tmax=None, verbose=False): """ if type(filenames) is str: filenames = [filenames] + + cores = min(len(filenames), max_cores) - # data = [] - # info = [] try: self.fastout except AttributeError: self.fastout = [] - for i, filename in enumerate(filenames): - assert os.path.isfile(filename), "File, %s, does not exists" % filename - with open(filename, 'r') as f: - if verbose: - print('Loading data from {}'.format(filename)) - try: - f.readline() - except UnicodeDecodeError: - data, info = load_binary_output(filename) - else: - data, info = load_ascii_output(filename) - - # Build dictionary - fast_data = dict(zip(info['channels'],data.T)) - fast_data['meta'] = info - fast_data['meta']['filename'] = filename - self.fastout.append(fast_data) + + inputs = [] + for filename in filenames: + inp = {} + inp['filename'] = filename + inp['verbose'] = verbose + inputs.append(inp) + + if cores > 1: + pool = mp.Pool(cores) + self.fastout = pool.map(self._load_fast_data, inputs) + pool.close() + pool.join() + else: + for inp in inputs: + fast_data = self._load_fast_data(inp) + self.fastout.append(fast_data) # Trim outputs if (tmin) or (tmax): @@ -91,6 +94,28 @@ def load_fast_out(self, filenames, tmin=None, tmax=None, verbose=False): # return fastout return self.fastout + + def _load_fast_data(self,input): + # Unpack + filename = input['filename'] + verbose = input['verbose'] + + assert os.path.isfile(filename), "File, %s, does not exists" % filename + with open(filename, 'r') as f: + if verbose: + print('Loading data from {}'.format(filename)) + try: + f.readline() + except UnicodeDecodeError: + data, info = load_binary_output(filename) + else: + data, info = load_ascii_output(filename) + + # Build dictionary + fast_data = dict(zip(info['channels'],data.T)) + fast_data['meta'] = info + fast_data['meta']['filename'] = filename + return fast_data def plot_fast_out(self, fastout=None, cases=None, showplot=True, fignum=None, xlim=None): ''' @@ -581,3 +606,53 @@ def trim_output(fast_data, tmin=None, tmax=None, verbose=False): return fast_data + + +if __name__ == "__main__": + outfiles = [ + '/Users/dzalkind/Tools/ROSCO3/outputs/IPC_tune_1/NREL2p8/turb_bts/sweep_ipc_gains/NREL2p8_0.out', + '/Users/dzalkind/Tools/ROSCO3/outputs/IPC_tune_1/NREL2p8/turb_bts/sweep_ipc_gains/NREL2p8_1.out', + '/Users/dzalkind/Tools/ROSCO3/outputs/IPC_tune_1/NREL2p8/turb_bts/sweep_ipc_gains/NREL2p8_2.out', + '/Users/dzalkind/Tools/ROSCO3/outputs/IPC_tune_1/NREL2p8/turb_bts/sweep_ipc_gains/NREL2p8_3.out' + ] + + plt.rcParams["figure.figsize"] = [9,12] + + ROSCO = False + ROSCO2 = False + + # Define Plot cases + cases = {} + cases['Gen. Speed Sigs.'] = ['Wind1VelX','BldPitch1', 'GenTq', 'GenSpeed','TwrBsMyt','GenPwr','RootMyb1']#,'PtfmPitch','PtfmYaw','NacYaw'] + + op = output_processing() + op_RO = output_processing() + op_RO2 = output_processing() + + fast_out = [] + fast_out = op.load_fast_out(outfiles, tmin=0) + if ROSCO: + # Rosco outfiles + r_outfiles = [out.split('.out')[0] + '.RO.dbg' for out in outfiles] + rosco_out = op_RO.load_fast_out(r_outfiles, tmin=0) + + if ROSCO2: + r_outfiles = [out.split('.out')[0] + '.RO.dbg2' for out in outfiles] + rosco_out2 = op_RO2.load_fast_out(r_outfiles, tmin=0) + + # Combine outputs + if ROSCO: + comb_out = [None] * len(fast_out) + for i, (r_out, f_out) in enumerate(zip(rosco_out,fast_out)): + r_out.update(f_out) + comb_out[i] = r_out + if ROSCO2: + for i, (r_out2, f_out) in enumerate(zip(rosco_out2,comb_out)): + r_out2.update(f_out) + comb_out[i] = r_out2 + else: + comb_out = fast_out + + + # Plot + fig, ax = op.plot_fast_out(comb_out,cases, showplot=True) diff --git a/ROSCO_toolbox/ofTools/fast_io/plot_FAST.ipynb b/ROSCO_toolbox/ofTools/fast_io/plot_FAST.ipynb index 4e64a191..52fe840c 100644 --- a/ROSCO_toolbox/ofTools/fast_io/plot_FAST.ipynb +++ b/ROSCO_toolbox/ofTools/fast_io/plot_FAST.ipynb @@ -9,7 +9,7 @@ }, { "cell_type": "code", - "execution_count": 2, + "execution_count": 1, "metadata": {}, "outputs": [], "source": [ @@ -50,27 +50,15 @@ }, { "cell_type": "code", - "execution_count": 3, + "execution_count": 13, "metadata": {}, "outputs": [], "source": [ "outfiles = [\n", - "# '/Users/dzalkind/Tools/WEIS-1/outputs/iea15mw/iea15mw_00.outb',\n", - "# '/Users/dzalkind/Tools/WEIS-1/outputs/iea15mw/iea15mw_01.outb',\n", - "# '/Users/dzalkind/Tools/WEIS-1/outputs/iea15mw/iea15mw_02.outb',\n", - "# '/Users/dzalkind/Tools/WEIS-1/outputs/iea15mw/iea15mw_08.outb',\n", - "# '/Users/dzalkind/Tools/ROSCO_toolbox/Examples/examples_out/13_Simulink_Test/OL_Test_1.SFunc.outb',\n", - " '/Users/dzalkind/Projects/FOCAL/IEA15MW_FOCAL/power_curve/base/IEA15MW_FOCAL_07.outb',\n", - "# '/Users/dzalkind/Tools/WEIS-3/results/UMaine-Semi/DISCON/IB_NTM_Raft/iea15mw_1.outb',\n", - "# '/Users/dzalkind/Tools/WEIS-3/results/UMaine-Semi/DISCON/IB_NTM_Raft/iea15mw_2.outb',\n", - "# '/Users/dzalkind/Tools/WEIS-3/results/CT-semi/ntm_long/DISCON-CT-semi/iea15mw_13.outb',\n", - "# '/Users/dzalkind/Tools/WEIS-4/optimizations/both_debug_nowrapper/NREL5MW_OC3_spar_IEC_0.outb',\n", - "# '/Users/dzalkind/Tools/WEIS-4/optimizations/outputs_opt_both_debug/NREL5MW_OC3_spar_IEC_0.outb',\n", - "# '/Users/dzalkind/Tools/WEIS-4/optimizations/outputs_opt_both_debug2/NREL5MW_OC3_spar_IEC_0.outb',\n", - "# '/Users/dzalkind/Tools/WEIS-4/optimizations/outputs_opt_both_debug3/NREL5MW_OC3_spar_IEC_0.outb',\n", - "# '/Users/dzalkind/Tools/WEIS-4/optimizations/outputs_opt_both_debug4/NREL5MW_OC3_spar_IEC_0.outb',\n", - "# '/Users/dzalkind/Tools/WEIS-3/sowfa_debug/rotor_sweep/c_001_sp6_h150_D240_oR2_yaw_base/IEA-15-240-RWT-Monopile.2.T2.out',\n", - "# '/Users/dzalkind/Tools/WEIS-3/results/CT-barge/DISCON-CT-barge_hiBW/simp/step_1.outb',\n", + " # '/Users/dzalkind/Tools/ROSCO3/Examples/examples_out/12_ipc_sim/NREL2p8/ramp/base/NREL2p8_0.out',\n", + " # '/Users/dzalkind/Tools/ROSCO3/Examples/examples_out/12_ipc_sim/NREL2p8/ramp/base/NREL2p8_1.out',\n", + " # '/Users/dzalkind/Tools/ROSCO3/Examples/examples_out/12_ipc_sim/NREL2p8/ramp/base/NREL2p8_2.out',\n", + " '/Users/dzalkind/Tools/ROSCO3/Examples/examples_out/12_ipc_sim/NREL2p8/ramp/base/NREL2p8_3.out',\n", "]\n", "\n", "# outfiles" @@ -78,76 +66,14 @@ }, { "cell_type": "code", - "execution_count": 6, + "execution_count": 25, "metadata": {}, "outputs": [ - { - "name": "stdout", - "output_type": "stream", - "text": [ - "Wind1VelX is not available as an output channel.\n", - "BldPitch1 is not available as an output channel.\n", - "GenTq is not available as an output channel.\n", - "TwrBsMyt is not available as an output channel.\n", - "GenPwr is not available as an output channel.\n", - "RotThrust is not available as an output channel.\n", - "Fl_Pitcom is not available as an output channel.\n", - "PC_MinPit is not available as an output channel.\n", - "WE_Vw is not available as an output channel.\n", - "RtVAvgxh is not available as an output channel.\n", - "BldPitch1 is not available as an output channel.\n", - "PtfmSurge is not available as an output channel.\n", - "PtfmSway is not available as an output channel.\n", - "PtfmHeave is not available as an output channel.\n", - "PtfmPitch is not available as an output channel.\n", - "PtfmRoll is not available as an output channel.\n", - "PtfmYaw is not available as an output channel.\n", - "RtVAvgxh is not available as an output channel.\n", - "BldPitch1 is not available as an output channel.\n", - "RotThrust is not available as an output channel.\n" - ] - }, - { - "data": { - "image/png": "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\n", - "text/plain": [ - "
" - ] - }, - "metadata": { - "needs_background": "light" - }, - "output_type": "display_data" - }, - { - "data": { - "image/png": "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\n", - "text/plain": [ - "
" - ] - }, - "metadata": { - "needs_background": "light" - }, - "output_type": "display_data" - }, - { - "data": { - "image/png": "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\n", - "text/plain": [ - "
" - ] - }, - "metadata": { - "needs_background": "light" - }, - "output_type": "display_data" - }, { "data": { - "image/png": "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\n", + "image/png": "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\n", "text/plain": [ - "
" + "
" ] }, "metadata": { @@ -158,27 +84,45 @@ ], "source": [ "output_ext = '.out'\n", - "plt.rcParams[\"figure.figsize\"] = [9,7]\n", + "plt.rcParams[\"figure.figsize\"] = [9,12]\n", "\n", "ROSCO = True\n", + "ROSCO2 = True\n", "\n", "# Define Plot cases \n", "cases = {}\n", - "cases['Gen. Speed Sigs.'] = ['Wind1VelX', 'BldPitch1', 'GenTq', 'GenSpeed','TwrBsMyt','GenPwr','RotThrust']#,'PtfmPitch','PtfmYaw','NacYaw']\n", - "# cases['Debug'] = ['IPDefl1','OoPDefl1','Azimuth','RotTorq']#,'PtfmPitch','PtfmYaw','NacYaw']\n", - "cases['Plt. Control Sigs.'] = ['RtVAvgxh', 'BldPitch1', 'Fl_Pitcom', 'PC_MinPit','WE_Vw']\n", - "cases['Platform Motion'] = ['PtfmSurge', 'PtfmSway', 'PtfmHeave', 'PtfmPitch','PtfmRoll','PtfmYaw']\n", - "cases['Rot Thrust'] = ['RtVAvgxh','BldPitch1','RotThrust']\n", + "# cases['Gen. Speed Sigs.'] = ['Wind1VelX', 'BldPitch1', 'GenTq', 'GenSpeed','TwrBsMyt','GenPwr','RootMyb1']#,'PtfmPitch','PtfmYaw','NacYaw']\n", + "cases['Gen. Speed Sigs.'] = ['Wind1VelX','BldPitch1', 'GenTq', 'GenSpeed','TwrBsMyt','GenPwr','RootMyb1']#,'PtfmPitch','PtfmYaw','NacYaw']\n", + "# # cases['Debug'] = ['IPDefl1','OoPDefl1','Azimuth','RotTorq']#,'PtfmPitch','PtfmYaw','NacYaw']\n", + "# cases['Plt. Control Sigs.'] = ['Fl_PitCom', 'PC_MinPit']\n", + "# cases['Platform Motion'] = ['PtfmSurge', 'PtfmSway', 'PtfmHeave', 'PtfmPitch','PtfmRoll','PtfmYaw']\n", + "# # cases['Tower Loads'] = ['TwrBsFxt','TwrBsFyt', 'TwrBsFzt', 'TwrBsMxt', 'TwrBsMyt','TwrBsMzt']\n", + "# # cases['Rot Thrust'] = ['RtVAvgxh','BldPitch1','RotThrust']\n", + "# cases['IPC'] = ['PitCom','PitComAct']\n", + "# # cases['IPC'] = ['PtfmYaw','YawBrMzp','YawBrMyp']\n", + "\n", + "# cases['Gen. Speed Sigs.'] = ['Wind1VelX', 'GenPwr', 'RotSpeed', 'GenSpeed', 'GenTq', 'BldPitch1','B1RootMyr'] #, 'PtfmPitch','PtfmYaw'] #,'PtfmPitch','PtfmYaw','NacYaw']\n", + "# cases['Rot. Pos'] = ['RotSpeed',('BldPitch1','BldPitch2','BldPitch3'),'GenTq','Azimuth']\n", + "# cases['Rotor Position'] = ['AzError','GenTqAz','Azimuth','AzUnwrapped','OL_Azimuth']\n", + "# cases['Aero'] = [\"B1N3Alpha\",\"B1N3Cd\",\"B1N3Cl\"]\n", + "\n", "\n", "op = output_processing.output_processing()\n", + "op_RO = output_processing.output_processing()\n", + "op_RO2 = output_processing.output_processing()\n", + "\n", "\n", - "# Rosco outfiles\n", - "r_outfiles = [out.split('.out')[0] + '.RO.dbg' for out in outfiles]\n", "\n", "fast_out = []\n", "fast_out = op.load_fast_out(outfiles, tmin=0)\n", "if ROSCO:\n", - " rosco_out = op.load_fast_out(r_outfiles, tmin=0)\n", + " # Rosco outfiles\n", + " r_outfiles = [out.split('.out')[0] + '.RO.dbg' for out in outfiles]\n", + " rosco_out = op_RO.load_fast_out(r_outfiles, tmin=0)\n", + " \n", + " if ROSCO2:\n", + " r_outfiles = [out.split('.out')[0] + '.RO.dbg2' for out in outfiles]\n", + " rosco_out2 = op_RO2.load_fast_out(r_outfiles, tmin=0)\n", " \n", "# Combine outputs\n", "if ROSCO:\n", @@ -186,6 +130,10 @@ " for i, (r_out, f_out) in enumerate(zip(rosco_out,fast_out)):\n", " r_out.update(f_out)\n", " comb_out[i] = r_out\n", + " if ROSCO2:\n", + " for i, (r_out2, f_out) in enumerate(zip(rosco_out2,comb_out)):\n", + " r_out2.update(f_out)\n", + " comb_out[i] = r_out2\n", "else:\n", " comb_out = fast_out\n", "\n", @@ -202,7 +150,97 @@ " save_fig_dir = '/Users/dzalkind/Projects/CarbonTrust/Deliverables'\n", " for f in fig:\n", " f.savefig(os.path.join(save_fig_dir,'ts'+str(i_fig)))\n", - " i_fig += 1" + " i_fig += 1\n", + "\n", + "output_ext = '.out'\n", + "plt.rcParams[\"figure.figsize\"] = [9,7]\n", + "\n" + ] + }, + { + "cell_type": "code", + "execution_count": 70, + "metadata": {}, + "outputs": [ + { + "data": { + "text/plain": [ + "array([14.97, 15. , 15.02, ..., 90. , 90. , 90. ])" + ] + }, + "execution_count": 70, + "metadata": {}, + "output_type": "execute_result" + } + ], + "source": [ + "fast_out[1]['PtfmHeave'].mean()\n", + "\n", + "fast_out[0]['BldPitch1']" + ] + }, + { + "cell_type": "code", + "execution_count": 16, + "metadata": { + "tags": [] + }, + "outputs": [ + { + "data": { + "text/plain": [ + "[]" + ] + }, + "execution_count": 16, + "metadata": {}, + "output_type": "execute_result" + }, + { + "data": { + "image/png": "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\n", + "text/plain": [ + "
" + ] + }, + "metadata": { + "needs_background": "light" + }, + "output_type": "display_data" + } + ], + "source": [ + "\n", + "ind = comb_out[0]['Time'] > 120\n", + "a = np.array([co['RootMyb1'][ind].std() for co in comb_out])\n", + "b = np.array([co['BldPitch1'][ind].std() for co in comb_out])\n", + "\n", + "fig, axs = plt.subplots(2,1)\n", + "axs[0].plot(a)\n", + "axs[1].plot(b)\n", + "\n" + ] + }, + { + "cell_type": "code", + "execution_count": 33, + "metadata": { + "tags": [] + }, + "outputs": [ + { + "data": { + "text/plain": [ + "360" + ] + }, + "execution_count": 33, + "metadata": {}, + "output_type": "execute_result" + } + ], + "source": [ + "18*20\n" ] }, { @@ -433,93 +471,6 @@ "df" ] }, - { - "cell_type": "code", - "execution_count": 27, - "metadata": {}, - "outputs": [ - { - "data": { - "text/plain": [ - "{'Time': array([0.00000e+00, 1.30000e-02, 2.50000e-02, ..., 7.99975e+02,\n", - " 7.99987e+02, 8.00000e+02]),\n", - " 'FA_AccF': array([ 0.000e+00, 1.264e-23, -8.574e-23, ..., -9.656e-17, -9.670e-17,\n", - " -9.684e-17]),\n", - " 'FA_AccR': array([-0.000e+00, 7.226e-18, -7.774e-17, ..., -3.648e-17, 2.417e-17,\n", - " 2.873e-17]),\n", - " 'RotSpeed': array([0.6132, 0.6131, 0.613 , ..., 0.5879, 0.5878, 0.5878]),\n", - " 'RotSpeedF': array([0.6132, 0.6132, 0.6132, ..., 0.5932, 0.5932, 0.5931]),\n", - " 'GenSpeed': array([0.6132, 0.6131, 0.613 , ..., 0.5879, 0.5878, 0.5878]),\n", - " 'GenSpeedF': array([0.6132, 0.6132, 0.6132, ..., 0.5932, 0.5932, 0.5931]),\n", - " 'FA_Acc': array([0., 0., 0., ..., 0., 0., 0.]),\n", - " 'Fl_Pitcom': array([-0.000e+00, 1.481e-24, -8.567e-24, ..., 4.151e-13, 4.151e-13,\n", - " 4.151e-13]),\n", - " 'PC_MinPit': array([0., 0., 0., ..., 0., 0., 0.]),\n", - " 'SS_dOmF': array([-0.0007917, -0.0007917, -0.0007901, ..., -0.0004443, -0.0004443,\n", - " -0.0004444]),\n", - " 'WE_Vw': array([8.963, 8.963, 8.963, ..., 7.916, 7.916, 7.916]),\n", - " 'WE_b': array([0.000e+00, 0.000e+00, 2.101e-28, ..., 2.392e-11, 2.392e-11,\n", - " 2.392e-11]),\n", - " 'WE_t': array([13140000., 13140000., 13140000., ..., 11480000., 11470000.,\n", - " 11470000.]),\n", - " 'WE_w': array([0.6132, 0.6132, 0.6132, ..., 0.5932, 0.5932, 0.5931]),\n", - " 'WE_Vm': array([8.963, 8.963, 8.963, ..., 7.981, 7.98 , 7.98 ]),\n", - " 'WE_Vt': array([ 0.000e+00, -2.132e-13, -8.994e-09, ..., -6.438e-02, -6.455e-02,\n", - " -6.472e-02]),\n", - " 'WE_lambda': array([8.21 , 8.209, 8.208, ..., 8.911, 8.911, 8.91 ]),\n", - " 'WE_Cp': array([0.25 , 0.4574, 0.4574, ..., 0.4622, 0.4622, 0.4622]),\n", - " 'meta': {'name': 'iea15mw_0.RO',\n", - " 'description': [' Generated on 22-Jun-2021 at 17:43:27 using ROSCO-v2.1.1-43-g22b65089\\n'],\n", - " 'channels': ['Time',\n", - " 'FA_AccF',\n", - " 'FA_AccR',\n", - " 'RotSpeed',\n", - " 'RotSpeedF',\n", - " 'GenSpeed',\n", - " 'GenSpeedF',\n", - " 'FA_Acc',\n", - " 'Fl_Pitcom',\n", - " 'PC_MinPit',\n", - " 'SS_dOmF',\n", - " 'WE_Vw',\n", - " 'WE_b',\n", - " 'WE_t',\n", - " 'WE_w',\n", - " 'WE_Vm',\n", - " 'WE_Vt',\n", - " 'WE_lambda',\n", - " 'WE_Cp'],\n", - " 'attribute_units': ['sec',\n", - " 'm/s',\n", - " 'rad/s^2',\n", - " 'rad/s',\n", - " 'rad/s',\n", - " 'rad/s',\n", - " 'rad/s',\n", - " 'm/s^2',\n", - " 'rad',\n", - " 'rad',\n", - " 'rad/s',\n", - " 'rad',\n", - " 'deg',\n", - " 'Nm',\n", - " 'rad/s',\n", - " 'm/s',\n", - " 'm/s',\n", - " 'rad/s',\n", - " '-'],\n", - " 'filename': '/Users/dzalkind/Tools/WEIS-3/results/UMaine-Semi/DISCON/IB_NTM_Raft/iea15mw_0.RO.dbg'}}" - ] - }, - "execution_count": 27, - "metadata": {}, - "output_type": "execute_result" - } - ], - "source": [ - "fast_out[3]" - ] - }, { "cell_type": "code", "execution_count": 11, @@ -561,148 +512,6 @@ "\n", "# op" ] - }, - { - "cell_type": "code", - "execution_count": 48, - "metadata": {}, - "outputs": [], - "source": [ - "# ret" - ] - }, - { - "cell_type": "code", - "execution_count": 49, - "metadata": {}, - "outputs": [ - { - "data": { - "text/plain": [ - "94.73684210526316" - ] - }, - "execution_count": 49, - "metadata": {}, - "output_type": "execute_result" - } - ], - "source": [ - "1/2e-3\n", - "\n", - "3600/38\n" - ] - }, - { - "cell_type": "code", - "execution_count": 50, - "metadata": {}, - "outputs": [ - { - "data": { - "text/plain": [ - "1.9752718440907233" - ] - }, - "execution_count": 50, - "metadata": {}, - "output_type": "execute_result" - }, - { - "data": { - "image/png": "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\n", - "text/plain": [ - "
" - ] - }, - "metadata": { - "needs_background": "light" - }, - "output_type": "display_data" - } - ], - "source": [ - "yaw_fast = fast_out[0]['PtfmYaw']\n", - "amp = np.std(yaw_fast) * np.sqrt(2)\n", - "\n", - "\n", - "per = 3600/38\n", - "\n", - "tt = fast_out[0]['Time']\n", - "\n", - "yaw_sowfa = amp * np.sin(2 * np.pi / per * tt)\n", - "\n", - "\n", - "plt.plot(tt,yaw_fast,tt,yaw_sowfa)\n", - "\n", - "np.min(yaw_fast)\n", - "\n", - "amp" - ] - }, - { - "cell_type": "code", - "execution_count": null, - "metadata": {}, - "outputs": [], - "source": [] - }, - { - "cell_type": "code", - "execution_count": 51, - "metadata": {}, - "outputs": [ - { - "data": { - "text/plain": [ - "'/Users/dzalkind/Tools/WEIS-3/pCrunch/HPC_tools/eagle2local_sim_inp.sh /Users/dzalkind/Tools/WEIS-3/results/CT-semi/ntm_long/DISCON-CT-semi/ iea15mw_07'" - ] - }, - "execution_count": 51, - "metadata": {}, - "output_type": "execute_result" - } - ], - "source": [ - "# pull from eagle if necessary\n", - "pull_script = '/Users/dzalkind/Tools/WEIS-3/pCrunch/HPC_tools/eagle2local_sim_inp.sh'\n", - "\n", - "\n", - "basedir = outfiles[0].split('/')[1]\n", - "# if basedir == 'scratch':\n", - " \n", - "temp = outfiles[0].split('/')\n", - "filedir = '/'.join(temp[:-1]) + '/'\n", - "\n", - "namebase = temp[-1].split('.')[0]\n", - "search_str = namebase + '*'\n", - "\n", - "shell_cmd = pull_script + ' ' + filedir + ' ' + namebase\n", - "\n", - "shell_cmd\n", - "# ret = subprocess.call(pull_script,shell=True)\n" - ] - }, - { - "cell_type": "code", - "execution_count": null, - "metadata": {}, - "outputs": [], - "source": [] - }, - { - "cell_type": "code", - "execution_count": null, - "metadata": {}, - "outputs": [], - "source": [] - }, - { - "cell_type": "code", - "execution_count": null, - "metadata": {}, - "outputs": [], - "source": [] } ], "metadata": { @@ -721,7 +530,7 @@ "name": "python", "nbconvert_exporter": "python", "pygments_lexer": "ipython3", - "version": "3.8.6" + "version": "3.8.13" } }, "nbformat": 4, diff --git a/ROSCO_toolbox/ofTools/fast_io/read_fast_input.py b/ROSCO_toolbox/ofTools/fast_io/read_fast_input.py deleted file mode 100644 index c8b76313..00000000 --- a/ROSCO_toolbox/ofTools/fast_io/read_fast_input.py +++ /dev/null @@ -1,1202 +0,0 @@ -''' -Reads OpenFAST input files. - -Most of this script is copied from: -https://github.com/OpenFAST/python-toolbox/blob/dev/pyFAST/input_output/fast_input_file.py -on 11/05/2020 - -''' - -from __future__ import division -from __future__ import unicode_literals -from __future__ import print_function -from __future__ import absolute_import -from io import open -from builtins import range -from builtins import str -from future import standard_library -standard_library.install_aliases() -from .file import File, WrongFormatError, BrokenFormatError -import os -import numpy as np -import re -import pandas as pd - -from ROSCO_toolbox.utilities import read_DISCON - -__all__ = ['FASTInputFile'] - -TABTYPE_NOT_A_TAB = 0 -TABTYPE_NUM_WITH_HEADER = 1 -TABTYPE_NUM_WITH_HEADERCOM = 2 -TABTYPE_NUM_NO_HEADER = 4 -TABTYPE_NUM_BEAMDYN = 5 -TABTYPE_MIX_WITH_HEADER = 6 -TABTYPE_FIL = 3 -TABTYPE_FMT = 9999 # TODO - -# --------------------------------------------------------------------------------} -# --- INPUT FILE -# --------------------------------------------------------------------------------{ -class FASTInputDeck(): - ''' - Read/write an OpenFAST input file deck. Behaves like a dictionary - ''' - def __init__(self, fst_file): - self.Fst = FASTInputFile(fst_file) - self.path = os.path.dirname(os.path.abspath(fst_file)) - - def load(self): - fst_dict = {} - try: - fst_dict['ElastoDyn'] = self.load_ElastoDyn() - except: - "Error loading {}".format(self.Fst['EDFile'].strip('\'').strip('\"')) - - try: - fst_dict['BDBldFile(1)'] = self.load_BDBldFile1() - except: - "Error loading {}".format(self.Fst['BDBldFile(1)'].strip('\'').strip('\"')) - - try: - fst_dict['BDBldFile(2)'] = self.load_BDBldFile2() - except: - "Error loading {}".format(self.Fst['BDBldFile(2)'].strip('\'').strip('\"')) - - try: - fst_dict['BDBldFile(3)'] = self.load_BDBldFile3() - except: - "Error loading {}".format(self.Fst['BDBldFile(3)'].strip('\'').strip('\"')) - - try: - fst_dict['InflowWind'] = self.load_InflowWind() - except: - "Error loading {}".format(self.Fst['InflowFile'].strip('\'').strip('\"')) - - try: - fst_dict['AeroDyn'] = self.load_AeroDyn() - except: - "Error loading {}".format(self.Fst['AeroFile'].strip('\'').strip('\"')) - - try: - fst_dict['ServoDyn'] = self.load_ServoDyn() - try: - fst_dict['DISCON_in'] = self.load_DISCON() - except: - "Error loading {}".format(self.ServoDyn['DLL_InFile'].strip('\'').strip('\"')) - - except: - "Error loading {}".format(self.Fst['ServoFile'].strip('\'').strip('\"')) - - try: - fst_dict['HydroDyn'] = self.load_HydroDyn() - except: - "Error loading {}".format(self.Fst['HydroFile'].strip('\'').strip('\"')) - - try: - fst_dict['SubDyn'] = self.load_SubDyn() - except: - "Error loading {}".format(self.Fst['SubFile'].strip('\'').strip('\"')) - - try: - fst_dict['MoorDyn'] = self.load_MoorDyn() - except: - "Error loading {}".format(self.Fst['MooringFile'].strip('\'').strip('\"')) - - try: - fst_dict['IceDyn'] = self.load_IceDyn() - except: - "Error loading {}".format(self.Fst['IceFile'].strip('\'').strip('\"')) - - - return fst_dict - - def load_ElastoDyn(self): - ED_fullfile = os.path.join(self.path, self.Fst['EDFile'].strip('\'').strip('\"')) - self.ElastoDyn = FASTInputFile(ED_fullfile) - return self.ElastoDyn - - def load_BDBldFile1(self): - BD1_fullfile = os.path.join(self.path, self.Fst['BDBldFile(1)'].strip('\'').strip('\"')) - self.BD1_fullfile = FASTInputFile(BD1_fullfile) - return self.load_BDBldFile1 - - def load_BDBldFile2(self): - BD2_fullfile = os.path.join(self.path, self.Fst['BDBldFile(2)'].strip('\'').strip('\"')) - self.BD2_fullfile = FASTInputFile(BD2_fullfile) - return self.load_BDBldFile2 - - def load_BDBldFile3(self): - BD3_fullfile = os.path.join(self.path, self.Fst['BDBldFile(3)'].strip('\'').strip('\"')) - self.BD3_fullfile = FASTInputFile(BD3_fullfile) - return self.load_BDBldFile3 - - def load_InflowWind(self): - IF_fullfile = os.path.join(self.path, self.Fst['InflowFile'].strip('\'').strip('\"')) - self.InflowWind = FASTInputFile(IF_fullfile) - return self.InflowWind - - def load_AeroDyn(self): - AF_fullfile = os.path.join(self.path, self.Fst['AeroFile'].strip('\'').strip('\"')) - self.AeroDyn = FASTInputFile(AF_fullfile) - return self.AeroDyn - - def load_ServoDyn(self): - SF_fullfile = os.path.join(self.path, self.Fst['ServoFile'].strip('\'').strip('\"')) - self.ServoDyn = FASTInputFile(SF_fullfile) - return self.ServoDyn - - def load_HydroDyn(self): - HF_fullfile = os.path.join(self.path, self.Fst['HydroFile'].strip('\'').strip('\"')) - self.HydroDyn = FASTInputFile(HF_fullfile) - return self.HydroDyn - - def load_SubDyn(self): - SUBF_fullfile = os.path.join(self.path, self.Fst['SubFile'].strip('\'').strip('\"')) - self.SubDyn = FASTInputFile(SUBF_fullfile) - return self.SubDyn - - def load_MoorDyn(self): - MF_fullfile = os.path.join(self.path, self.Fst['MooringFile'].strip('\'').strip('\"')) - self.MoorDyn = FASTInputFile(MF_fullfile) - return self.MoorDyn - - def load_IceDyn(self): - IceF_fullfile = os.path.join(self.path, self.Fst['IceFile'].strip('\'').strip('\"')) - self.IceDyn = FASTInputFile(IceF_fullfile) - return self.IceDyn - - def load_DISCON(self): # (TODO - Move this out of the ROSCO toolbox and into ofTools) - DISCON_fullfile = os.path.join(self.path, self.ServoDyn['DLL_InFile'].strip('\'').strip('\"')) - self.DISCON_in = read_DISCON(DISCON_fullfile) - return self.DISCON_in - -# --------------------------------------------------------------------------------} -# --- INPUT FILE -# --------------------------------------------------------------------------------{ -class FASTInputFile(File): - """ - Read/write an OpenFAST input file. The object behaves like a dictionary. - - Main methods - ------------ - - read, write, toDataFrame, keys - - Main keys - --------- - The keys correspond to the keys used in the file. For instance for a .fst file: 'DT','TMax' - - Examples - -------- - - filename = 'AeroDyn.dat' - f = FASTInputFile(filename) - f['TwrAero'] = True - f['AirDens'] = 1.225 - f.write('AeroDyn_Changed.dat') - - """ - - @staticmethod - def defaultExtensions(): - return ['.dat','.fst','.txt','.fstf'] - - @staticmethod - def formatName(): - return 'FAST input file' - - def __init__(self, filename=None, **kwargs): - super(FASTInputFile, self).__init__(filename=filename,**kwargs) - - def keys(self): - self.labels = [ d['label'] for d in self.data if not d['isComment'] ] - return self.labels - - def getID(self,label): - i=self.getIDSafe(label) - if i<0: - raise KeyError('Variable `'+ label+'` not found in FAST file:'+self.filename) - else: - return i - def getIDs(self,label): - I=[] - # brute force search - for i in range(len(self.data)): - d = self.data[i] - if d['label'].lower()==label.lower(): - I.append(i) - if len(I)<0: - raise KeyError('Variable `'+ label+'` not found in FAST file:'+self.filename) - else: - return I - - def getIDSafe(self,label): - # brute force search - for i in range(len(self.data)): - d = self.data[i] - if d['label'].lower()==label.lower(): - return i - return -1 - - # Making object an iterator - def __iter__(self): - self.iCurrent=-1 - self.iMax=len(self.data)-1 - return self - - def __next__(self): # Python 2: def next(self) - if self.iCurrent > self.iMax: - raise StopIteration - else: - self.iCurrent += 1 - return self.data[self.iCurrent] - - # Making it behave like a dictionary - def __setitem__(self,key,item): - I = self.getIDs(key) - for i in I: - self.data[i]['value'] = item - - def __getitem__(self,key): - i = self.getID(key) - return self.data[i]['value'] - - def __repr__(self): - s ='Fast input file: {}\n'.format(self.filename) - return s+'\n'.join(['{:15s}: {}'.format(d['label'],d['value']) for i,d in enumerate(self.data)]) - - def addKeyVal(self,key,val,descr=None): - d=getDict() - d['label']=key - d['value']=val - if descr is not None: - d['descr']=descr - self.data.append(d) - - def _read(self): - - # TODO members for BeamDyn with mutliple key point ####### TODO PropSetID is Duplicate SubDyn and used in HydroDyn - NUMTAB_FROM_VAL_DETECT = ['HtFract' , 'TwrElev' , 'BlFract' , 'Genspd_TLU' , 'BlSpn' , 'WndSpeed' , 'HvCoefID' , 'AxCoefID' , 'JointID' , 'Dpth' , 'FillNumM' , 'MGDpth' , 'SimplCd' , 'RNodes' , 'kp_xr' , 'mu1' , 'TwrHtFr' , 'TwrRe' , 'RJointID' , 'IJointID' , 'COSMID' , 'CMJointID' , 'WT_X'] - NUMTAB_FROM_VAL_DIM_VAR = ['NTwInpSt' , 'NumTwrNds' , 'NBlInpSt' , 'DLL_NumTrq' , 'NumBlNds' , 'NumCases' , 'NHvCoef' , 'NAxCoef' , 'NJoints' , 'NCoefDpth' , 'NFillGroups' , 'NMGDepths' , 1 , 'BldNodes' , 'kp_total' , 1 , 'NTwrHt' , 'NTwrRe' , 'NReact' , 'NInterf' , 'NCOSMs' , 'NCmass' , 'NumTurbines'] - NUMTAB_FROM_VAL_VARNAME = ['TowProp' , 'TowProp' , 'BldProp' , 'DLLProp' , 'BldAeroNodes' , 'Cases' , 'HvCoefs' , 'AxCoefs' , 'Joints' , 'DpthProp' , 'FillGroups' , 'MGProp' , 'SmplProp' , 'BldAeroNodes' , 'MemberGeom' , 'DampingCoeffs' , 'TowerProp' , 'TowerRe' , 'BaseReactJoints' , 'InterfaceJoints' , 'MemberCosineMatrix' , 'ConcentratedMasses','WindTurbines'] - NUMTAB_FROM_VAL_NHEADER = [2 , 2 , 2 , 2 , 2 , 2 , 2 , 2 , 2 , 2 , 2 , 2 , 2 , 1 , 2 , 2 , 1 , 1 , 2 , 2 , 2 , 2 ,2] - NUMTAB_FROM_VAL_TYPE = ['num' , 'num' , 'num' , 'num' , 'num' , 'num' , 'num' , 'num' , 'num' , 'num' , 'num' , 'num' , 'num' , 'mix' , 'num' , 'num' , 'num' , 'num' , 'mix' , 'num' , 'num' , 'num' ,'mix'] - NUMTAB_FROM_VAL_DETECT_L = [s.lower() for s in NUMTAB_FROM_VAL_DETECT] - - # NOTE: MJointID1, used by SubDyn and HydroDyn - NUMTAB_FROM_LAB_DETECT = ['NumAlf' , 'F_X' , 'MemberCd1' , 'MJointID1' , 'NOutLoc' , 'NOutCnt' , 'PropD' , 'YoungE' , 'YoungE' ] - NUMTAB_FROM_LAB_DIM_VAR = ['NumAlf' , 'NKInpSt' , 'NCoefMembers' , 'NMembers' , 'NMOutputs' , 'NMOutputs' , 'NPropSets' , 'NPropSets' , 'NXPropSets' ] - NUMTAB_FROM_LAB_VARNAME = ['AFCoeff' , 'TMDspProp' , 'MemberProp' , 'Members' , 'MemberOuts' , 'MemberOuts' , 'MemberSectionProp' , 'MemberSectionProp' , 'MemberSectionProp2' ] - NUMTAB_FROM_LAB_TYPE = ['num' , 'num' , 'num' , 'mix' , 'num' , 'num' , 'num' , 'num' , 'num' ] - NUMTAB_FROM_LAB_DETECT_L = [s.lower() for s in NUMTAB_FROM_LAB_DETECT] - - FILTAB_FROM_LAB_DETECT = ['FoilNm' ,'AFNames'] - FILTAB_FROM_LAB_DIM_VAR = ['NumFoil','NumAFfiles'] - FILTAB_FROM_LAB_VARNAME = ['FoilNm' ,'AFNames'] - FILTAB_FROM_LAB_DETECT_L = [s.lower() for s in FILTAB_FROM_LAB_DETECT] - - self.data = [] - self.module = None - #with open(self.filename, 'r', errors="surrogateescape") as f: - with open(self.filename, 'r', errors="surrogateescape") as f: - lines=f.read().splitlines() - # IF NEEDED> DO THE FOLLOWING FORMATTING: - #lines = [str(l).encode('utf-8').decode('ascii','ignore') for l in f.read().splitlines()] - - # Fast files start with ! or - - #if lines[0][0]!='!' and lines[0][0]!='-': - # raise Exception('Fast file do not start with ! or -, is it the right format?') - - # Special filetypes - if self.detectAndReadExtPtfmSE(lines): - return - if self.detectAndReadAirfoil(lines): - return - - # Parsing line by line, storing each line into a dictionary - i=0 - nComments = 0 - nWrongLabels = 0 - allowSpaceSeparatedList=False - while i0 \ - or line.upper().find('MESH-BASED OUTPUTS')>0 \ - or line.upper().find('OUTPUT CHANNELS' )>0: - # TODO, lazy implementation so far, MAKE SUB FUNCTION - parts = re.match(r'^\W*\w+', line) - if parts: - firstword = parts.group(0).strip() - else: - raise NotImplementedError - remainer = re.sub(r'^\W*\w+\W*', '', line) - # Parsing outlist, and then we continue at a new "i" (to read END etc.) - OutList,i = parseFASTOutList(lines,i+1) - d = getDict() - d['label'] = firstword - d['descr'] = remainer - d['tabType'] = TABTYPE_FIL # TODO - d['value'] = ['']+OutList - self.data.append(d) - if i>=len(lines): - break - - # --- Here we cheat and force an exit of the input file - # The reason for this is that some files have a lot of things after the END, which will result in the file being intepreted as a wrong format due to too many comments - if i+20: - print('>>>Bld Nodal outputs present') - else: - self.data.append(parseFASTInputLine('END of input file (the word "END" must appear in the first 3 columns of this last OutList line)',i+1)) - self.data.append(parseFASTInputLine('---------------------------------------------------------------------------------------',i+2)) - break - elif line.upper().find('SSOUTLIST' )>0: - # SUBDYN Outlist doesn not follow regular format - self.data.append(parseFASTInputLine(line,i)) - # OUTLIST Exception for BeamDyn - OutList,i = parseFASTOutList(lines,i+1) - # TODO - for o in OutList: - d = getDict() - d['isComment'] = True - d['value']=o - self.data.append(d) - # --- Here we cheat and force an exit of the input file - self.data.append(parseFASTInputLine('END of input file (the word "END" must appear in the first 3 columns of this last OutList line)',i+1)) - self.data.append(parseFASTInputLine('---------------------------------------------------------------------------------------',i+2)) - break - - elif line.upper().find('ADDITIONAL STIFFNESS')>0: - # TODO, lazy implementation so far, MAKE SUB FUNCTION - self.data.append(parseFASTInputLine(line,i)) - i +=1 - KDAdd = [] - for _ in range(19): - KDAdd.append(lines[i]) - i +=1 - d = getDict() - d['label'] = 'KDAdd' # TODO - d['tabType'] = TABTYPE_FIL # TODO - d['value'] = KDAdd - self.data.append(d) - if i>=len(lines): - break - elif line.upper().find('DISTRIBUTED PROPERTIES')>0: - self.data.append(parseFASTInputLine(line,i)); - i+=1; - self.readBeamDynProps(lines,i) - return - - # --- Parsing of standard lines: value(s) key comment - line = lines[i] - d = parseFASTInputLine(line,i,allowSpaceSeparatedList) - - # --- Handling of special files - if d['label'].lower()=='kp_total': - # BeamDyn has weird space speparated list around keypoint definition - allowSpaceSeparatedList=True - elif d['label'].lower()=='numcoords': - # TODO, lazy implementation so far, MAKE SUB FUNCTION - if isStr(d['value']): - if d['value'][0]=='@': - # it's a ref to the airfoil coord file - pass - else: - if not strIsInt(d['value']): - raise WrongFormatError('Wrong value of NumCoords') - if int(d['value'])<=0: - pass - else: - self.data.append(d); i+=1; - # 3 comment lines - self.data.append(parseFASTInputLine(lines[i],i)); i+=1; - self.data.append(parseFASTInputLine(lines[i],i)); i+=1; - self.data.append(parseFASTInputLine(lines[i],i)); i+=1; - splits=cleanAfterChar(cleanLine(lines[i]),'!').split() - # Airfoil ref point - try: - pos=[float(splits[0]), float(splits[1])] - except: - raise WrongFormatError('Wrong format while reading coordinates of airfoil reference') - i+=1 - d = getDict() - d['label'] = 'AirfoilRefPoint' - d['value'] = pos - self.data.append(d) - # 2 comment lines - self.data.append(parseFASTInputLine(lines[i],i)); i+=1; - self.data.append(parseFASTInputLine(lines[i],i)); i+=1; - # Table of coordinats itself - d = getDict() - d['label'] = 'AirfoilCoord' - d['tabDimVar'] = 'NumCoords' - d['tabType'] = TABTYPE_NUM_WITH_HEADERCOM - nTabLines = self[d['tabDimVar']]-1 # SOMEHOW ONE DATA POINT LESS - d['value'], d['tabColumnNames'],_ = parseFASTNumTable(self.filename,lines[i:i+nTabLines+1],nTabLines,i,1) - d['tabUnits'] = ['(-)','(-)'] - self.data.append(d) - break - - - - #print('label>',d['label'],'<',type(d['label'])); - #print('value>',d['value'],'<',type(d['value'])); - #print(isStr(d['value'])) - #if isStr(d['value']): - # print(d['value'].lower() in NUMTAB_FROM_VAL_DETECT_L) - - - # --- Handling of tables - if isStr(d['value']) and d['value'].lower() in NUMTAB_FROM_VAL_DETECT_L: - # Table with numerical values, - ii = NUMTAB_FROM_VAL_DETECT_L.index(d['value'].lower()) - tab_type = NUMTAB_FROM_VAL_TYPE[ii] - if tab_type=='num': - d['tabType'] = TABTYPE_NUM_WITH_HEADER - else: - d['tabType'] = TABTYPE_MIX_WITH_HEADER - d['label'] = NUMTAB_FROM_VAL_VARNAME[ii] - d['tabDimVar'] = NUMTAB_FROM_VAL_DIM_VAR[ii] - nHeaders = NUMTAB_FROM_VAL_NHEADER[ii] - nTabLines=0 - if isinstance(d['tabDimVar'],int): - nTabLines = d['tabDimVar'] - else: - nTabLines = self[d['tabDimVar']] - #print('Reading table {} Dimension {} (based on {})'.format(d['label'],nTabLines,d['tabDimVar'])); - d['value'], d['tabColumnNames'], d['tabUnits'] = parseFASTNumTable(self.filename,lines[i:i+nTabLines+nHeaders],nTabLines,i,nHeaders,tableType=tab_type) - i += nTabLines+nHeaders-1 - - # --- Temporary hack for e.g. SubDyn, that has duplicate table, impossible to detect in the current way... - # So we remove the element form the list one read - del NUMTAB_FROM_VAL_DETECT[ii] - del NUMTAB_FROM_VAL_DIM_VAR[ii] - del NUMTAB_FROM_VAL_VARNAME[ii] - del NUMTAB_FROM_VAL_NHEADER[ii] - del NUMTAB_FROM_VAL_TYPE [ii] - del NUMTAB_FROM_VAL_DETECT_L[ii] - - elif isStr(d['label']) and d['label'].lower() in NUMTAB_FROM_LAB_DETECT_L: - ii = NUMTAB_FROM_LAB_DETECT_L.index(d['label'].lower()) - tab_type = NUMTAB_FROM_LAB_TYPE[ii] - # Special case for airfoil data, the table follows NumAlf, so we add d first - if d['label'].lower()=='numalf': - d['tabType']=TABTYPE_NOT_A_TAB - self.data.append(d) - # Creating a new dictionary for the table - d = {'value':None, 'label':'NumAlf', 'isComment':False, 'descr':'', 'tabType':None} - i += 1 - d['label'] = NUMTAB_FROM_LAB_VARNAME[ii] - d['tabDimVar'] = NUMTAB_FROM_LAB_DIM_VAR[ii] - if d['label'].lower()=='afcoeff' : - d['tabType'] = TABTYPE_NUM_WITH_HEADERCOM - else: - if tab_type=='num': - d['tabType'] = TABTYPE_NUM_WITH_HEADER - else: - d['tabType'] = TABTYPE_MIX_WITH_HEADER - nTabLines = self[d['tabDimVar']] - #print('Reading table {} Dimension {} (based on {})'.format(d['label'],nTabLines,d['tabDimVar'])); - d['value'], d['tabColumnNames'], d['tabUnits'] = parseFASTNumTable(self.filename,lines[i:i+nTabLines+2],nTabLines,i,2,tableType=tab_type) - i += nTabLines+1 - - # --- Temporary hack for e.g. SubDyn, that has duplicate table, impossible to detect in the current way... - # So we remove the element form the list one read - del NUMTAB_FROM_LAB_DETECT[ii] - del NUMTAB_FROM_LAB_DIM_VAR[ii] - del NUMTAB_FROM_LAB_VARNAME[ii] - del NUMTAB_FROM_LAB_TYPE [ii] - del NUMTAB_FROM_LAB_DETECT_L[ii] - - elif isStr(d['label']) and d['label'].lower() in FILTAB_FROM_LAB_DETECT_L: - ii = FILTAB_FROM_LAB_DETECT_L.index(d['label'].lower()) - d['label'] = FILTAB_FROM_LAB_VARNAME[ii] - d['tabDimVar'] = FILTAB_FROM_LAB_DIM_VAR[ii] - d['tabType'] = TABTYPE_FIL - nTabLines = self[d['tabDimVar']] - #print('Reading table {} Dimension {} (based on {})'.format(d['label'],nTabLines,d['tabDimVar'])); - d['value'] = parseFASTFilTable(lines[i:i+nTabLines],nTabLines,i) - i += nTabLines-1 - - - - self.data.append(d) - i += 1 - # --- Safety checks - if d['isComment']: - #print(line) - nComments +=1 - else: - if hasSpecialChars(d['label']): - nWrongLabels +=1 - #print('label>',d['label'],'<',type(d['label']),line); - if i>3: # first few lines may be comments, we allow it - #print('Line',i,'Label:',d['label']) - raise WrongFormatError('Special Character found in Label: `{}`'.format(d['label'])) - if len(d['label'])==0: - nWrongLabels +=1 - if nComments>len(lines)*0.35: - #print('Comment fail',nComments,len(lines),self.filename) - raise WrongFormatError('Most lines were read as comments, probably not a FAST Input File') - if nWrongLabels>len(lines)*0.10: - #print('Label fail',nWrongLabels,len(lines),self.filename) - raise WrongFormatError('Too many lines with wrong labels, probably not a FAST Input File') - - # --- PostReading checks - labels = self.keys() - duplicates = set([x for x in labels if labels.count(x) > 1]) - if len(duplicates)>0: - print('[WARN] Duplicate labels found in file: '+self.filename) - print(' Duplicates: '+', '.join(duplicates)) - print(' It\'s strongly recommended to make them unique! ') -# except WrongFormatError as e: -# raise WrongFormatError('Fast File {}: '.format(self.filename)+'\n'+e.args[0]) -# except Exception as e: -# raise e -# # print(e) -# raise Exception('Fast File {}: '.format(self.filename)+'\n'+e.args[0]) - - - def toString(self): - s='' - # Special file formats, TODO subclass - if self.module=='ExtPtfm': - s+='!Comment\n' - s+='!Comment Flex 5 Format\n' - s+='!Dimension: {}\n'.format(self['nDOF']) - s+='!Time increment in simulation: {}\n'.format(self['dt']) - s+='!Total simulation time in file: {}\n'.format(self['T']) - - s+='\n!Mass Matrix\n' - s+='!Dimension: {}\n'.format(self['nDOF']) - s+='\n'.join(''.join('{:16.8e}'.format(x) for x in y) for y in self['MassMatrix']) - - s+='\n\n!Stiffness Matrix\n' - s+='!Dimension: {}\n'.format(self['nDOF']) - s+='\n'.join(''.join('{:16.8e}'.format(x) for x in y) for y in self['StiffnessMatrix']) - - s+='\n\n!Damping Matrix\n' - s+='!Dimension: {}\n'.format(self['nDOF']) - s+='\n'.join(''.join('{:16.8e}'.format(x) for x in y) for y in self['DampingMatrix']) - - s+='\n\n!Loading and Wave Elevation\n' - s+='!Dimension: 1 time column - {} force columns\n'.format(self['nDOF']) - s+='\n'.join(''.join('{:16.8e}'.format(x) for x in y) for y in self['Loading']) - return s - - def toStringVLD(val,lab,descr): - val='{}'.format(val) - lab='{}'.format(lab) - if len(val)<13: - val='{:13s}'.format(val) - if len(lab)<13: - lab='{:13s}'.format(lab) - return val+' '+lab+' - '+descr.strip().strip('-').strip()+'\n' - - for i in range(len(self.data)): - d=self.data[i] - if d['isComment']: - s+='{}'.format(d['value']) - elif d['tabType']==TABTYPE_NOT_A_TAB: - if isinstance(d['value'], list): - sList=', '.join([str(x) for x in d['value']]) - s+='{} {} {}'.format(sList,d['label'],d['descr']) - else: - s+=toStringVLD(d['value'],d['label'],d['descr']).strip() - elif d['tabType']==TABTYPE_NUM_WITH_HEADER: - s+='{}'.format(' '.join(['{:15s}'.format(s) for s in d['tabColumnNames']])) - #s+=d['descr'] # Not ready for that - if d['tabUnits'] is not None: - s+='\n' - s+='{}'.format(' '.join(['{:15s}'.format(s) for s in d['tabUnits']])) - if np.size(d['value'],0) > 0 : - s+='\n' - s+='\n'.join('\t'.join( ('{:15.0f}'.format(x) if int(x)==x else '{:15.8e}'.format(x) ) for x in y) for y in d['value']) - elif d['tabType']==TABTYPE_MIX_WITH_HEADER: - s+='{}'.format(' '.join(['{:15s}'.format(s) for s in d['tabColumnNames']])) - if d['tabUnits'] is not None: - s+='\n' - s+='{}'.format(' '.join(['{:15s}'.format(s) for s in d['tabUnits']])) - if np.size(d['value'],0) > 0 : - s+='\n' - s+='\n'.join('\t'.join('{}'.format(x) for x in y) for y in d['value']) - elif d['tabType']==TABTYPE_NUM_WITH_HEADERCOM: - s+='! {}\n'.format(' '.join(['{:15s}'.format(s) for s in d['tabColumnNames']])) - s+='! {}\n'.format(' '.join(['{:15s}'.format(s) for s in d['tabUnits']])) - s+='\n'.join('\t'.join('{:15.8e}'.format(x) for x in y) for y in d['value']) - elif d['tabType']==TABTYPE_FIL: - #f.write('{} {} {}\n'.format(d['value'][0],d['tabDetect'],d['descr'])) - s+='{} {} {}\n'.format(d['value'][0],d['label'],d['descr']) # TODO? - s+='\n'.join(fil for fil in d['value'][1:]) - else: - raise Exception('Unknown table type for variable {}',d) - if i0: - # Hack for blade files, we add the modes - x=Val[:,0] - Modes=np.zeros((x.shape[0],3)) - Modes[:,0] = x**2 * self['BldFl1Sh(2)'] \ - + x**3 * self['BldFl1Sh(3)'] \ - + x**4 * self['BldFl1Sh(4)'] \ - + x**5 * self['BldFl1Sh(5)'] \ - + x**6 * self['BldFl1Sh(6)'] - Modes[:,1] = x**2 * self['BldFl2Sh(2)'] \ - + x**3 * self['BldFl2Sh(3)'] \ - + x**4 * self['BldFl2Sh(4)'] \ - + x**5 * self['BldFl2Sh(5)'] \ - + x**6 * self['BldFl2Sh(6)'] - Modes[:,2] = x**2 * self['BldEdgSh(2)'] \ - + x**3 * self['BldEdgSh(3)'] \ - + x**4 * self['BldEdgSh(4)'] \ - + x**5 * self['BldEdgSh(5)'] \ - + x**6 * self['BldEdgSh(6)'] - Val = np.hstack((Val,Modes)) - Cols = Cols + ['ShapeFlap1_[-]','ShapeFlap2_[-]','ShapeEdge1_[-]'] - - elif self.getIDSafe('TwFAM1Sh(2)')>0: - # Hack for tower files, we add the modes - x=Val[:,0] - Modes=np.zeros((x.shape[0],4)) - Modes[:,0] = x**2 * self['TwFAM1Sh(2)'] \ - + x**3 * self['TwFAM1Sh(3)'] \ - + x**4 * self['TwFAM1Sh(4)'] \ - + x**5 * self['TwFAM1Sh(5)'] \ - + x**6 * self['TwFAM1Sh(6)'] - Modes[:,1] = x**2 * self['TwFAM2Sh(2)'] \ - + x**3 * self['TwFAM2Sh(3)'] \ - + x**4 * self['TwFAM2Sh(4)'] \ - + x**5 * self['TwFAM2Sh(5)'] \ - + x**6 * self['TwFAM2Sh(6)'] - Modes[:,2] = x**2 * self['TwSSM1Sh(2)'] \ - + x**3 * self['TwSSM1Sh(3)'] \ - + x**4 * self['TwSSM1Sh(4)'] \ - + x**5 * self['TwSSM1Sh(5)'] \ - + x**6 * self['TwSSM1Sh(6)'] - Modes[:,3] = x**2 * self['TwSSM2Sh(2)'] \ - + x**3 * self['TwSSM2Sh(3)'] \ - + x**4 * self['TwSSM2Sh(4)'] \ - + x**5 * self['TwSSM2Sh(5)'] \ - + x**6 * self['TwSSM2Sh(6)'] - Val = np.hstack((Val,Modes)) - Cols = Cols + ['ShapeForeAft1_[-]','ShapeForeAft2_[-]','ShapeSideSide1_[-]','ShapeSideSide2_[-]'] - - name=d['label'] - dfs[name]=pd.DataFrame(data=Val,columns=Cols) - elif d['tabType'] in [TABTYPE_NUM_BEAMDYN]: - data = d['value'] - Cols =['Span'] - Cols+=['K{}{}'.format(i+1,j+1) for i in range(6) for j in range(6)] - Cols+=['M{}{}'.format(i+1,j+1) for i in range(6) for j in range(6)] - # Putting the main terms first - IAll = range(1+36+36) - IMain= [0] + [i*6+i+1 for i in range(6)] + [i*6+i+37 for i in range(6)] - IOrg = IMain + [i for i in range(1+36+36) if i not in IMain] - Cols = [Cols[i] for i in IOrg] - data = data[:,IOrg] - name=d['label'] - dfs[name]=pd.DataFrame(data=data,columns=Cols) - if len(dfs)==1: - dfs=dfs[list(dfs.keys())[0]] - return dfs - -# --------------------------------------------------------------------------------} -# --- SubReaders /detectors -# --------------------------------------------------------------------------------{ - def detectAndReadExtPtfmSE(self,lines): - def readmat(n,m,lines,iStart): - M=np.zeros((n,m)) - for j in np.arange(n): - i=iStart+j - M[j,:]=np.array(lines[i].split()).astype(float) - return M - if len(lines)<10: - return False - if not (lines[0][0]=='!' and lines[1][0]=='!'): - return False - if lines[1].lower().find('flex')<0: - return - if lines[2].lower().find('!dimension')<0: - return - # --- At this stage we assume it's in the proper format - self.module='ExtPtfm' - nDOFCommon = -1 - i=2; - try: - while i0: - if l[0]=='!': - if l.find('!dimension')==0: - self.addKeyVal('nDOF',int(l.split(':')[1])) - nDOFCommon=self['nDOF'] - elif l.find('!time increment')==0: - self.addKeyVal('dt',np.float_(l.split(':')[1])) - elif l.find('!total simulation time')==0: - self.addKeyVal('T',np.float_(l.split(':')[1])) - else: - raise BrokenFormatError('Unexcepted content found on line {}'.format(i)) - i+=1 - except BrokenFormatError as e: - raise e - except: - raise - - - return True - - - - def detectAndReadAirfoil(self,lines): - if len(lines)<14: - return False - # Reading number of tables - L3 = lines[2].strip().split() - if len(L3)<=0: - return False - if not strIsInt(L3[0]): - return False - nTables=int(L3[0]) - # Reading table ID - L4 = lines[3].strip().split() - if len(L4)<=nTables: - return False - TableID=L4[:nTables] - if nTables==1: - TableID=[''] - # Keywords for file format - KW1=lines[12].strip().split() - KW2=lines[13].strip().split() - if len(KW1)>nTables and len(KW2)>nTables: - if KW1[nTables].lower()=='angle' and KW2[nTables].lower()=='minimum': - d = getDict(); d['isComment'] = True; d['value'] = lines[0]; self.data.append(d); - d = getDict(); d['isComment'] = True; d['value'] = lines[1]; self.data.append(d); - for i in range(2,14): - splits = lines[i].split() - #print(splits) - d = getDict() - d['label'] = ' '.join(splits[1:]) # TODO - d['descr'] = ' '.join(splits[1:]) # TODO - d['value'] = float(splits[0]) - self.data.append(d) - #pass - #for i in range(2,14): - nTabLines=0 - while 14+nTabLines0 : - nTabLines +=1 - #data = np.array([lines[i].strip().split() for i in range(14,len(lines)) if len(lines[i])>0]).astype(np.float_) - #data = np.array([lines[i].strip().split() for i in takewhile(lambda x: len(lines[i].strip())>0, range(14,len(lines)-1))]).astype(np.float_) - data = np.array([lines[i].strip().split() for i in range(14,nTabLines+14)]).astype(np.float_) - #print(data) - d = getDict() - d['label'] = 'Polar' - d['tabDimVar'] = nTabLines - d['tabType'] = TABTYPE_NUM_NO_HEADER - d['value'] = data - if np.size(data,1)==1+nTables*3: - d['tabColumnNames'] = ['Alpha']+[n+l for l in TableID for n in ['Cl','Cd','Cm']] - d['tabUnits'] = ['(deg)']+['(-)' , '(-)' , '(-)']*nTables - elif np.size(data,1)==1+nTables*2: - d['tabColumnNames'] = ['Alpha']+[n+l for l in TableID for n in ['Cl','Cd']] - d['tabUnits'] = ['(deg)']+['(-)' , '(-)']*nTables - else: - d['tabColumnNames'] = ['col{}'.format(j) for j in range(np.size(data,1))] - self.data.append(d) - return True - - def readBeamDynProps(self,lines,iStart): - nStations=self['station_total'] - M=np.zeros((nStations,1+36+36)) - i=iStart; - try: - for j in range(nStations): - M[j,0]=float(lines[i]); i+=1; - LL = lines[i:i+6] - M[j,1:37]=np.array((' '.join(lines[i:i+6])).split()).astype(np.float_) - i+=7 - M[j,37:]=np.array((' '.join(lines[i:i+6])).split()).astype(np.float_) - i+=7 - except: - raise WrongFormatError('An error occured while reading section {}/{}'.format(j+1,nStations)) - d = getDict() - d['label'] = 'BeamProperties' - d['descr'] = '' - d['tabType'] = TABTYPE_NUM_BEAMDYN - d['value'] = M - self.data.append(d) - - -# --------------------------------------------------------------------------------} -# --- Helper functions -# --------------------------------------------------------------------------------{ -def isStr(s): - # Python 2 and 3 compatible - # Two options below - # NOTE: all this avoided since we import str from builtins - # --- Version 2 - # isString = False; - # if(isinstance(s, str)): - # isString = True; - # try: - # if(isinstance(s, basestring)): # todo unicode as well - # isString = True; - # except NameError: - # pass; - # return isString - # --- Version 1 - # try: - # basestring # python 2 - # return isinstance(s, basestring) or isinstance(s,unicode) - # except NameError: - # basestring=str #python 3 - # return isinstance(s, str) - return isinstance(s, str) - -def strIsFloat(s): - #return s.replace('.',',1').isdigit() - try: - float(s) - return True - except: - return False - -def strIsBool(s): - return (s.lower() == 'true') or (s.lower() == 'false') - -def strIsInt(s): - s = str(s) - if s[0] in ('-', '+'): - return s[1:].isdigit() - return s.isdigit() - -def hasSpecialChars(s): - # fast allows for parenthesis - # For now we allow for - but that's because of BeamDyn geometry members - return not re.match("^[\"\'a-zA-Z0-9_()-]*$", s) - -def cleanLine(l): - # makes a string single space separated - l = l.replace('\t',' ') - l = ' '.join(l.split()) - l = l.strip() - return l - -def cleanAfterChar(l,c): - # remove whats after a character - n = l.find(c); - if n>0: - return l[:n] - else: - return l - -def getDict(): - return {'value':None, 'label':'', 'isComment':False, 'descr':'', 'tabType':TABTYPE_NOT_A_TAB} - - -def parseFASTInputLine(line_raw,i,allowSpaceSeparatedList=False): - d = getDict() - #print(line_raw) - try: - # preliminary cleaning (Note: loss of formatting) - line = cleanLine(line_raw) - # Comment - if any(line.startswith(c) for c in ['#','!','--','==']) or len(line)==0: - d['isComment']=True - d['value']=line_raw - return d - - # Detecting lists - List=[]; - iComma=line.find(',') - if iComma>0 and iComma<30: - fakeline=line.replace(' ',',') - fakeline=re.sub(',+',',',fakeline) - csplits=fakeline.split(',') - # Splitting based on comma and looping while it's numbers of booleans - ii=0 - s=csplits[ii] - #print(csplits) - while strIsFloat(s) or strIsBool(s) and ii=len(csplits): - raise WrongFormatError('Wrong number of list values') - s = csplits[ii] - #print('[INFO] Line {}: Found list: '.format(i),List) - # Defining value and remaining splits - if len(List)>=2: - d['value']=List - line_remaining=line - # eating line, removing each values - for iii in range(ii): - sValue=csplits[iii] - ipos=line_remaining.find(sValue) - line_remaining = line_remaining[ipos+len(sValue):] - splits=line_remaining.split() - iNext=0 - else: - # It's not a list, we just use space as separators - splits=line.split(' ') - s=splits[0] - - if strIsInt(s): - d['value']=int(s) - if allowSpaceSeparatedList and len(splits)>1: - if strIsInt(splits[1]): - d['value']=splits[0]+ ' '+splits[1] - elif strIsFloat(s): - d['value']=float(s) - elif strIsBool(s): - d['value']=bool(s) - else: - d['value']=s - iNext=1 - #import pdb ; pdb.set_trace(); - - # Extracting label (TODO, for now only second split) - bOK=False - while (not bOK) and iNext comment assumed'.format(i+1)) - d['isComment']=True - d['value']=line_raw - iNext = len(splits)+1 - - # Recombining description - if len(splits)>=iNext+1: - d['descr']=' '.join(splits[iNext:]) - except WrongFormatError as e: - raise WrongFormatError('Line {}: '.format(i+1)+e.args[0]) - except Exception as e: - raise Exception('Line {}: '.format(i+1)+e.args[0]) - - return d - -def parseFASTOutList(lines,iStart): - OutList=[] - i = iStart - MAX=200 - while iMAX : - raise Exception('More that 200 lines found in outlist') - if i>=len(lines): - print('[WARN] End of file reached while reading Outlist') - #i=min(i+1,len(lines)) - return OutList,iStart+len(OutList) - - -def extractWithinParenthesis(s): - mo = re.search(r'\((.*)\)', s) - if mo: - return mo.group(1) - return '' - -def extractWithinBrackets(s): - mo = re.search(r'\((.*)\)', s) - if mo: - return mo.group(1) - return '' - -def detectUnits(s,nRef): - nPOpen=s.count('(') - nPClos=s.count(')') - nBOpen=s.count('[') - nBClos=s.count(']') - - sep='!#@#!' - if (nPOpen == nPClos) and (nPOpen>=nRef): - #that's pretty good - Units=s.replace('(','').replace(')',sep).split(sep)[:-1] - elif (nBOpen == nBClos) and (nBOpen>=nRef): - Units=s.replace('[','').replace(']',sep).split(sep)[:-1] - else: - Units=s.split() - return Units - - -def parseFASTNumTable(filename,lines,n,iStart,nHeaders=2,tableType='num'): - Tab = None - ColNames = None - Units = None - - if len(lines)!=n+nHeaders: - raise BrokenFormatError('Not enough lines in table: {} lines instead of {}\nFile:{}'.format(len(lines)-nHeaders,n,filename)) - - if nHeaders<1: - raise NotImplementedError('Reading FAST tables with no headers not implemented yet') - - try: - if nHeaders>=1: - # Extract column names - i = 0 - sTmp = cleanLine(lines[i]) - sTmp = cleanAfterChar(sTmp,'[') - if sTmp.startswith('!'): - sTmp=sTmp[1:].strip() - ColNames=sTmp.split() - if nHeaders>=2: - # Extract units - i = 1 - sTmp = cleanLine(lines[i]) - if sTmp.startswith('!'): - sTmp=sTmp[1:].strip() - - Units = detectUnits(sTmp,len(ColNames)) - Units = ['({})'.format(u.strip()) for u in Units] - # Forcing user to match number of units and column names - if len(ColNames) != len(Units): - print(ColNames) - print(Units) - raise Exception('Number of column names different from number of units in table') - - nCols=len(ColNames) - - if tableType=='num': - Tab = np.zeros((n, nCols)) - for i in range(nHeaders,n+nHeaders): - l = lines[i].lower() - v = l.split() - if len(v) > nCols: - print('[WARN] {}: Line {}: number of data different from number of column names'.format(filename, iStart+i+1)) - if len(v) < nCols: - raise Exception('Number of data is lower than number of column names') - # Accounting for TRUE FALSE and converting to float - v = [s.replace('true','1').replace('false','0').replace('noprint','0').replace('print','1') for s in v] - v = [float(s) for s in v[0:nCols]] - if len(v) < nCols: - raise Exception('Number of data is lower than number of column names') - Tab[i-nHeaders,:] = v - elif tableType=='mix': - # a mix table contains a mixed of strings and floats - # For now, we are being a bit more relaxed about the number of columns - Tab = np.zeros((n, nCols)).astype(object) - for i in range(nHeaders,n+nHeaders): - l = lines[i] - v = l.split() - if len(v) != nCols: - print('[WARN] {}: Line {}: Number of data is different than number of column names'.format(filename,iStart+1+i)) - v=v[0:min(len(v),nCols)] - Tab[i-nHeaders,0:len(v)] = v - else: - raise Exception('Unknown table type') - - except Exception as e: - raise BrokenFormatError('Line {}: {}'.format(iStart+i+1,e.args[0])) - return Tab, ColNames, Units - - -def parseFASTFilTable(lines,n,iStart): - Tab = [] - try: - i=0 - if len(lines)!=n: - raise WrongFormatError('Not enough lines in table: {} lines instead of {}'.format(len(lines),n)) - for i in range(n): - l = lines[i].split() - #print(l[0].strip()) - Tab.append(l[0].strip()) - - except Exception as e: - raise Exception('Line {}: '.format(iStart+i+1)+e.args[0]) - return Tab - - -if __name__ == "__main__": - B=FASTInFile('BeamDyn_Blade.dat') - - - diff --git a/ROSCO_toolbox/utilities.py b/ROSCO_toolbox/utilities.py index b50a6595..b15b46e2 100644 --- a/ROSCO_toolbox/utilities.py +++ b/ROSCO_toolbox/utilities.py @@ -107,6 +107,7 @@ def write_DISCON(turbine, controller, param_file='DISCON.IN', txt_filename='Cp_C file.write('{0:<12d} ! OL_Mode - Open loop control mode {{0: no open loop control, 1: open loop control vs. time}}\n'.format(int(rosco_vt['OL_Mode']))) file.write('{0:<12d} ! PA_Mode - Pitch actuator mode {{0 - not used, 1 - first order filter, 2 - second order filter}}\n'.format(int(rosco_vt['PA_Mode']))) file.write('{0:<12d} ! PF_Mode - Pitch fault mode {{0 - not used, 1 - constant offset on one or more blades}}\n'.format(int(rosco_vt['PF_Mode']))) + file.write('{0:<12d} ! AWC_Mode - Active wake control {{0 - not used, 1 - complex number method, 2 - Coleman transform method}}\n'.format(int(rosco_vt['AWC_Mode']))) file.write('{0:<12d} ! Ext_Mode - External control mode {{0 - not used, 1 - call external dynamic library}}\n'.format(int(rosco_vt['Ext_Mode']))) file.write('{0:<12d} ! ZMQ_Mode - Fuse ZeroMQ interface {{0: unused, 1: Yaw Control}}\n'.format(int(rosco_vt['ZMQ_Mode']))) file.write('{:<12d} ! CC_Mode - {}\n'.format(int(rosco_vt['CC_Mode']),mode_descriptions['CC_Mode'])) @@ -234,6 +235,14 @@ def write_DISCON(turbine, controller, param_file='DISCON.IN', txt_filename='Cp_C file.write('!------- Pitch Actuator Faults -----------------------------------------------------\n') file.write('{} ! PF_Offsets - Constant blade pitch offsets for blades 1-3 [rad]\n'.format(''.join('{:<10.8f} '.format(rosco_vt['PF_Offsets'][i]) for i in range(3)))) file.write('\n') + file.write('!------- Active Wake Control -----------------------------------------------------\n') + file.write('{0:<12d} ! AWC_NumModes - Number of user-defined AWC forcing modes \n'.format(int(rosco_vt['AWC_NumModes']))) + file.write('{} ! AWC_n - Azimuthal mode number(s) (i.e., the number and direction of the lobes of the wake structure)\n'.format(write_array(rosco_vt['AWC_n'],'<4d'))) + file.write('{} ! AWC_harmonic - Harmonic(s) to apply in the AWC Inverse Coleman Transformation (only used when AWC_Mode = 2)\n'.format(write_array(rosco_vt['AWC_harmonic'],'<4d'))) + file.write('{} ! AWC_freq - Frequency(s) of forcing mode(s) [Hz]\n'.format(write_array(rosco_vt['AWC_freq'],'<6.4f'))) + file.write('{} ! AWC_amp - Pitch amplitude(s) of individual forcing mode(s) [deg]\n'.format(write_array(rosco_vt['AWC_amp'],'<6.4f'))) + file.write('{} ! AWC_clockangle - Initial angle(s) of forcing mode(s) [deg]\n'.format(write_array(rosco_vt['AWC_clockangle'],'<6.4f'))) + file.write('\n') file.write('!------- External Controller Interface -----------------------------------------------------\n') file.write('"{}" ! DLL_FileName - Name/location of the dynamic library in the Bladed-DLL format\n'.format(rosco_vt['DLL_FileName'])) file.write('"{}" ! DLL_InFile - Name of input file sent to the DLL (-)\n'.format(rosco_vt['DLL_InFile'])) @@ -245,12 +254,12 @@ def write_DISCON(turbine, controller, param_file='DISCON.IN', txt_filename='Cp_C file.write('\n') file.write('!------- Cable Control ---------------------------------------------------------\n') file.write('{:<11d} ! CC_Group_N - {}\n'.format(len(rosco_vt['CC_GroupIndex']), input_descriptions['CC_Group_N'])) - file.write('{:^11s} ! CC_GroupIndex - {}\n'.format(' '.join([f'{int(ind):d}' for ind in rosco_vt['CC_GroupIndex']]), input_descriptions['CC_GroupIndex'])) + file.write('{:^11s} ! CC_GroupIndex - {}\n'.format(write_array(rosco_vt['CC_GroupIndex'],'<6d'), input_descriptions['CC_GroupIndex'])) file.write('{:<11f} ! CC_ActTau - {}\n'.format(rosco_vt['CC_ActTau'], input_descriptions['CC_ActTau'] )) file.write('\n') file.write('!------- Structural Controllers ---------------------------------------------------------\n') file.write('{:<11d} ! StC_Group_N - {}\n'.format(len(rosco_vt['StC_GroupIndex']), input_descriptions['StC_Group_N'])) - file.write('{:^11s} ! StC_GroupIndex - {}\n'.format(' '.join([f'{int(ind):d}' for ind in rosco_vt['StC_GroupIndex']]), input_descriptions['StC_GroupIndex'])) + file.write('{:^11s} ! StC_GroupIndex - {}\n'.format(write_array(rosco_vt['StC_GroupIndex'],'<6d'), input_descriptions['StC_GroupIndex'])) file.close() @@ -445,6 +454,7 @@ def DISCON_dict(turbine, controller, txt_filename=None): DISCON_dict['OL_Mode'] = int(controller.OL_Mode) DISCON_dict['PF_Mode'] = int(controller.PF_Mode) DISCON_dict['PA_Mode'] = int(controller.PA_Mode) + DISCON_dict['AWC_Mode'] = int(controller.AWC_Mode) DISCON_dict['Ext_Mode'] = int(controller.Ext_Mode) DISCON_dict['ZMQ_Mode'] = int(controller.ZMQ_Mode) DISCON_dict['CC_Mode'] = int(controller.CC_Mode) @@ -648,3 +658,14 @@ def list_check(x, return_bool=True): return is_list else: return y + +def write_array(array,format='<.4f'): + + if not hasattr(array,'__len__'): #not an array + array = [array] + + # force int if not + if 'd' in format and type(array[0]) != int: + array = [int(a) for a in array] + + return ''.join(['{:{}} '.format(item,format) for item in array]) diff --git a/Test_Cases/BAR_10/BAR_10_DISCON.IN b/Test_Cases/BAR_10/BAR_10_DISCON.IN index d915a5c0..6bdb4e12 100644 --- a/Test_Cases/BAR_10/BAR_10_DISCON.IN +++ b/Test_Cases/BAR_10/BAR_10_DISCON.IN @@ -1,5 +1,5 @@ ! Controller parameter input file for the BAR_10 wind turbine -! - File written using ROSCO version 2.7.0 controller tuning logic on 02/28/23 +! - File written using ROSCO version 2.7.0 controller tuning logic on 03/20/23 !------- DEBUG ------------------------------------------------------------ 1 ! LoggingLevel - (0: write no debug files, 1: write standard output .dbg-file, 2: LoggingLevel 1 + ROSCO LocalVars (.dbg2) 3: LoggingLevel 2 + complete avrSWAP-array (.dbg3)) @@ -22,6 +22,7 @@ 0 ! OL_Mode - Open loop control mode {0: no open loop control, 1: open loop control vs. time} 0 ! PA_Mode - Pitch actuator mode {0 - not used, 1 - first order filter, 2 - second order filter} 0 ! PF_Mode - Pitch fault mode {0 - not used, 1 - constant offset on one or more blades} +0 ! AWC_Mode - Active wake control {0 - not used, 1 - complex number method, 2 - Coleman transform method} 0 ! Ext_Mode - External control mode {0 - not used, 1 - call external dynamic library} 0 ! ZMQ_Mode - Fuse ZeroMQ interface {0: unused, 1: Yaw Control} 0 ! CC_Mode - Cable control mode [0- unused, 1- User defined, 2- Position control (not yet implemented)] @@ -143,6 +144,14 @@ !------- Pitch Actuator Faults ----------------------------------------------------- 0.00000000 0.00000000 0.00000000 ! PF_Offsets - Constant blade pitch offsets for blades 1-3 [rad] +!------- Active Wake Control ----------------------------------------------------- +1 ! AWC_NumModes - Number of user-defined AWC forcing modes +1 ! AWC_n - Azimuthal mode number(s) (i.e., the number and direction of the lobes of the wake structure) +1 ! AWC_harmonic - Harmonic(s) to apply in the AWC Inverse Coleman Transformation (only used when AWC_Mode = 2) +0.0500 ! AWC_freq - Frequency(s) of forcing mode(s) [Hz] +1.0000 ! AWC_amp - Pitch amplitude(s) of individual forcing mode(s) [deg] +0.0000 ! AWC_clockangle - Initial angle(s) of forcing mode(s) [deg] + !------- External Controller Interface ----------------------------------------------------- "unused" ! DLL_FileName - Name/location of the dynamic library in the Bladed-DLL format "unused" ! DLL_InFile - Name of input file sent to the DLL (-) @@ -153,10 +162,10 @@ 2 ! ZMQ_UpdatePeriod - Call ZeroMQ every [x] seconds, [s] !------- Cable Control --------------------------------------------------------- -1 ! CC_Group_N - Number of cable control groups - 0 ! CC_GroupIndex - First index for cable control group, should correspond to deltaL -20.000000 ! CC_ActTau - Time constant for line actuator [s] +1 ! CC_Group_N - Number of cable control groups + 0 ! CC_GroupIndex - First index for cable control group, should correspond to deltaL +20.000000 ! CC_ActTau - Time constant for line actuator [s] !------- Structural Controllers --------------------------------------------------------- -1 ! StC_Group_N - Number of cable control groups - 0 ! StC_GroupIndex - First index for structural control group, options specified in ServoDyn summary output +1 ! StC_Group_N - Number of cable control groups + 0 ! StC_GroupIndex - First index for structural control group, options specified in ServoDyn summary output diff --git a/Test_Cases/IEA-15-240-RWT-UMaineSemi/DISCON-UMaineSemi.IN b/Test_Cases/IEA-15-240-RWT-UMaineSemi/DISCON-UMaineSemi.IN index 30f764c6..078319ac 100644 --- a/Test_Cases/IEA-15-240-RWT-UMaineSemi/DISCON-UMaineSemi.IN +++ b/Test_Cases/IEA-15-240-RWT-UMaineSemi/DISCON-UMaineSemi.IN @@ -1,5 +1,5 @@ ! Controller parameter input file for the IEA-15-240-RWT-UMaineSemi wind turbine -! - File written using ROSCO version 2.7.0 controller tuning logic on 02/28/23 +! - File written using ROSCO version 2.7.0 controller tuning logic on 03/20/23 !------- DEBUG ------------------------------------------------------------ 2 ! LoggingLevel - (0: write no debug files, 1: write standard output .dbg-file, 2: LoggingLevel 1 + ROSCO LocalVars (.dbg2) 3: LoggingLevel 2 + complete avrSWAP-array (.dbg3)) @@ -22,6 +22,7 @@ 0 ! OL_Mode - Open loop control mode {0: no open loop control, 1: open loop control vs. time} 2 ! PA_Mode - Pitch actuator mode {0 - not used, 1 - first order filter, 2 - second order filter} 0 ! PF_Mode - Pitch fault mode {0 - not used, 1 - constant offset on one or more blades} +0 ! AWC_Mode - Active wake control {0 - not used, 1 - complex number method, 2 - Coleman transform method} 0 ! Ext_Mode - External control mode {0 - not used, 1 - call external dynamic library} 0 ! ZMQ_Mode - Fuse ZeroMQ interface {0: unused, 1: Yaw Control} 0 ! CC_Mode - Cable control mode [0- unused, 1- User defined, 2- Position control (not yet implemented)] @@ -143,6 +144,14 @@ !------- Pitch Actuator Faults ----------------------------------------------------- 0.00000000 0.00000000 0.00000000 ! PF_Offsets - Constant blade pitch offsets for blades 1-3 [rad] +!------- Active Wake Control ----------------------------------------------------- +1 ! AWC_NumModes - Number of user-defined AWC forcing modes +1 ! AWC_n - Azimuthal mode number(s) (i.e., the number and direction of the lobes of the wake structure) +1 ! AWC_harmonic - Harmonic(s) to apply in the AWC Inverse Coleman Transformation (only used when AWC_Mode = 2) +0.0500 ! AWC_freq - Frequency(s) of forcing mode(s) [Hz] +1.0000 ! AWC_amp - Pitch amplitude(s) of individual forcing mode(s) [deg] +0.0000 ! AWC_clockangle - Initial angle(s) of forcing mode(s) [deg] + !------- External Controller Interface ----------------------------------------------------- "unused" ! DLL_FileName - Name/location of the dynamic library in the Bladed-DLL format "unused" ! DLL_InFile - Name of input file sent to the DLL (-) @@ -153,10 +162,10 @@ 2 ! ZMQ_UpdatePeriod - Call ZeroMQ every [x] seconds, [s] !------- Cable Control --------------------------------------------------------- -1 ! CC_Group_N - Number of cable control groups - 0 ! CC_GroupIndex - First index for cable control group, should correspond to deltaL -20.000000 ! CC_ActTau - Time constant for line actuator [s] +1 ! CC_Group_N - Number of cable control groups + 0 ! CC_GroupIndex - First index for cable control group, should correspond to deltaL +20.000000 ! CC_ActTau - Time constant for line actuator [s] !------- Structural Controllers --------------------------------------------------------- -1 ! StC_Group_N - Number of cable control groups - 0 ! StC_GroupIndex - First index for structural control group, options specified in ServoDyn summary output +1 ! StC_Group_N - Number of cable control groups + 0 ! StC_GroupIndex - First index for structural control group, options specified in ServoDyn summary output diff --git a/Test_Cases/NREL-5MW/DISCON.IN b/Test_Cases/NREL-5MW/DISCON.IN index 3da89959..60775ec0 100644 --- a/Test_Cases/NREL-5MW/DISCON.IN +++ b/Test_Cases/NREL-5MW/DISCON.IN @@ -1,5 +1,5 @@ ! Controller parameter input file for the NREL-5MW wind turbine -! - File written using ROSCO version 2.7.0 controller tuning logic on 02/28/23 +! - File written using ROSCO version 2.7.0 controller tuning logic on 03/20/23 !------- DEBUG ------------------------------------------------------------ 1 ! LoggingLevel - (0: write no debug files, 1: write standard output .dbg-file, 2: LoggingLevel 1 + ROSCO LocalVars (.dbg2) 3: LoggingLevel 2 + complete avrSWAP-array (.dbg3)) @@ -22,6 +22,7 @@ 0 ! OL_Mode - Open loop control mode {0: no open loop control, 1: open loop control vs. time} 0 ! PA_Mode - Pitch actuator mode {0 - not used, 1 - first order filter, 2 - second order filter} 0 ! PF_Mode - Pitch fault mode {0 - not used, 1 - constant offset on one or more blades} +0 ! AWC_Mode - Active wake control {0 - not used, 1 - complex number method, 2 - Coleman transform method} 0 ! Ext_Mode - External control mode {0 - not used, 1 - call external dynamic library} 0 ! ZMQ_Mode - Fuse ZeroMQ interface {0: unused, 1: Yaw Control} 0 ! CC_Mode - Cable control mode [0- unused, 1- User defined, 2- Position control (not yet implemented)] @@ -143,6 +144,14 @@ !------- Pitch Actuator Faults ----------------------------------------------------- 0.00000000 0.00000000 0.00000000 ! PF_Offsets - Constant blade pitch offsets for blades 1-3 [rad] +!------- Active Wake Control ----------------------------------------------------- +1 ! AWC_NumModes - Number of user-defined AWC forcing modes +1 ! AWC_n - Azimuthal mode number(s) (i.e., the number and direction of the lobes of the wake structure) +1 ! AWC_harmonic - Harmonic(s) to apply in the AWC Inverse Coleman Transformation (only used when AWC_Mode = 2) +0.0500 ! AWC_freq - Frequency(s) of forcing mode(s) [Hz] +1.0000 ! AWC_amp - Pitch amplitude(s) of individual forcing mode(s) [deg] +0.0000 ! AWC_clockangle - Initial angle(s) of forcing mode(s) [deg] + !------- External Controller Interface ----------------------------------------------------- "unused" ! DLL_FileName - Name/location of the dynamic library in the Bladed-DLL format "unused" ! DLL_InFile - Name of input file sent to the DLL (-) @@ -153,10 +162,10 @@ 2 ! ZMQ_UpdatePeriod - Call ZeroMQ every [x] seconds, [s] !------- Cable Control --------------------------------------------------------- -1 ! CC_Group_N - Number of cable control groups - 0 ! CC_GroupIndex - First index for cable control group, should correspond to deltaL -20.000000 ! CC_ActTau - Time constant for line actuator [s] +1 ! CC_Group_N - Number of cable control groups + 0 ! CC_GroupIndex - First index for cable control group, should correspond to deltaL +20.000000 ! CC_ActTau - Time constant for line actuator [s] !------- Structural Controllers --------------------------------------------------------- -1 ! StC_Group_N - Number of cable control groups - 0 ! StC_GroupIndex - First index for structural control group, options specified in ServoDyn summary output +1 ! StC_Group_N - Number of cable control groups + 0 ! StC_GroupIndex - First index for structural control group, options specified in ServoDyn summary output diff --git a/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF00_Coords.txt b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF00_Coords.txt new file mode 100644 index 00000000..e9309e03 --- /dev/null +++ b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF00_Coords.txt @@ -0,0 +1,208 @@ + 201 NumCoords ! The number of coordinates in the airfoil shape file (including an extra coordinate for airfoil reference). Set to zero if coordinates not included. +! ......... x-y coordinates are next if NumCoords > 0 ............. +! x-y coordinate of airfoil reference +! x/c y/c + 0.500000 0 +! coordinates of airfoil shape +! interpolation to 200 points +! x/c y/c + 1.00000000000000e+00 1.39471767468535e-15 + 9.99492456366675e-01 -2.24148318097192e-02 + 9.97998442938042e-01 -4.47793322876220e-02 + 9.95467925285309e-01 -6.70365581798988e-02 + 9.91981297584349e-01 -8.91473650534134e-02 + 9.87535715129057e-01 -1.11060278052329e-01 + 9.82077318711035e-01 -1.32710580192188e-01 + 9.75645752125599e-01 -1.54053421230182e-01 + 9.68327814997901e-01 -1.75062933826036e-01 + 9.60169311985103e-01 -1.95709072524484e-01 + 9.51019761347344e-01 -2.15876183412258e-01 + 9.41032965384679e-01 -2.35574562290692e-01 + 9.30228135178293e-01 -2.54760790502087e-01 + 9.18600973249388e-01 -2.73373623585437e-01 + 9.06286773024904e-01 -2.91445285668231e-01 + 8.93185468322794e-01 -3.08852284793353e-01 + 8.79429131687551e-01 -3.25629671028512e-01 + 8.65020010482894e-01 -3.41723774803256e-01 + 8.50001183978561e-01 -3.57112177867390e-01 + 8.34409947013148e-01 -3.71770913166281e-01 + 8.18263641617925e-01 -3.85648552858056e-01 + 8.01628456968450e-01 -3.98748400170390e-01 + 7.84595497003635e-01 -4.11125308634395e-01 + 7.67122879759481e-01 -4.22652791316593e-01 + 7.49310431319132e-01 -4.33396610986265e-01 + 7.31192318835036e-01 -4.43343955969101e-01 + 7.12809122212147e-01 -4.52489087671710e-01 + 6.94192882766294e-01 -4.60805480273623e-01 + 6.75356426213553e-01 -4.68221413716844e-01 + 6.56401839622218e-01 -4.74887730613940e-01 + 6.37339053739694e-01 -4.80732155257960e-01 + 6.18216799132259e-01 -4.85797045327747e-01 + 5.99072127289441e-01 -4.90092245328121e-01 + 5.79920098443495e-01 -4.93529601024917e-01 + 5.60830239179689e-01 -4.96308798320980e-01 + 5.41809841204068e-01 -4.98254021026852e-01 + 5.22902255947823e-01 -4.99468302412137e-01 + 5.04138617740840e-01 -4.99969461095629e-01 + 4.85547896236042e-01 -4.99782528766859e-01 + 4.67157180742230e-01 -4.98932207272937e-01 + 4.48992436485026e-01 -4.97429938215178e-01 + 4.31090922803529e-01 -4.95199601187320e-01 + 4.13451809735344e-01 -4.92443613818918e-01 + 3.96103805194879e-01 -4.89121761104649e-01 + 3.79096627499341e-01 -4.85124024486578e-01 + 3.62407327470865e-01 -4.80659331665282e-01 + 3.46066636516655e-01 -4.75685087833417e-01 + 3.30096115507155e-01 -4.70203747355840e-01 + 3.14480352866339e-01 -4.64314583285520e-01 + 2.99254081643518e-01 -4.57980939909463e-01 + 2.84450426976392e-01 -4.51177575409728e-01 + 2.70052866033160e-01 -4.43988939168408e-01 + 2.56066550501318e-01 -4.36445000343028e-01 + 2.42483923277781e-01 -4.28590357469827e-01 + 2.29353790045290e-01 -4.20376016737305e-01 + 2.16603264062538e-01 -4.11943400950387e-01 + 2.04317853658681e-01 -4.03192627249739e-01 + 1.92459446608375e-01 -3.94201135001427e-01 + 1.81000889336564e-01 -3.85028191464174e-01 + 1.69975424985927e-01 -3.75644842886581e-01 + 1.59391096347033e-01 -3.66066250246720e-01 + 1.49207465402409e-01 -3.56350787229031e-01 + 1.39487797355366e-01 -3.46454046169616e-01 + 1.30120240319336e-01 -3.36494792306467e-01 + 1.21215059211584e-01 -3.26386152642893e-01 + 1.12658598266997e-01 -3.16237746353461e-01 + 1.04576031217800e-01 -3.05961432628231e-01 + 9.68117255237024e-02 -2.95688054408038e-01 + 8.94183192669232e-02 -2.85386126810182e-01 + 8.24692613312736e-02 -2.75012912186705e-01 + 7.58031535914957e-02 -2.64686382950272e-01 + 6.95265332165359e-02 -2.54344021225804e-01 + 6.36014773641337e-02 -2.44016481364265e-01 + 5.79875426758039e-02 -2.33733614688635e-01 + 5.27214572831349e-02 -2.23480055785704e-01 + 4.77407756799443e-02 -2.13293199734344e-01 + 4.30911198450984e-02 -2.03156079856565e-01 + 3.87383767680824e-02 -1.93089031734237e-01 + 3.47120078049050e-02 -1.83082592300236e-01 + 3.09831915833964e-02 -1.73156756176345e-01 + 2.73972939643108e-02 -1.63368018994347e-01 + 2.42148186237083e-02 -1.53628642008223e-01 + 2.11591799216729e-02 -1.44034525093811e-01 + 1.84468268040835e-02 -1.34516182856983e-01 + 1.59138335980001e-02 -1.25130288878497e-01 + 1.36131610235361e-02 -1.15857640369663e-01 + 1.14838295959446e-02 -1.06718459753818e-01 + 9.63946848246122e-03 -9.76879552179587e-02 + 7.95426403181202e-03 -8.87933378901162e-02 + 6.48712578142165e-03 -8.00260463587484e-02 + 5.16242415846458e-03 -7.13984274261874e-02 + 3.96141128417998e-03 -6.29131069298763e-02 + 2.94206395570219e-03 -5.45622661453796e-02 + 2.13806552335743e-03 -4.63439971542207e-02 + 1.44971764281537e-03 -3.82678090225701e-02 + 9.19962693446690e-04 -3.03318166757594e-02 + 5.13539051739693e-04 -2.25365794204782e-02 + 2.28620066730956e-04 -1.48836875697269e-02 + 7.90911911777832e-05 -7.37097402213213e-03 + 0.00000000000000e+00 0.00000000000000e+00 + 7.90677652262213e-05 7.36950623430851e-03 + 2.28464565111448e-04 1.48777524287952e-02 + 5.12873373489222e-04 2.25230881526787e-02 + 9.18597455380868e-04 3.03075781606325e-02 + 1.44666023734530e-03 3.82295855300727e-02 + 2.13316604432083e-03 4.62883932406539e-02 + 2.93360033162344e-03 5.44859437589187e-02 + 3.94803817877652e-03 6.28126278437423e-02 + 5.14351598889891e-03 7.12701576675508e-02 + 6.46190285472730e-03 7.98662577301812e-02 + 7.91902151822289e-03 8.85987369572577e-02 + 9.59444803793060e-03 9.74544221488751e-02 + 1.14235102541198e-02 1.06442996258128e-01 + 1.35337735871235e-02 1.15536956454720e-01 + 1.58224157496375e-02 1.24758221029162e-01 + 1.83235379987219e-02 1.34093489066500e-01 + 2.10204849111940e-02 1.43552196795823e-01 + 2.40367775427033e-02 1.53088940216613e-01 + 2.71877316554608e-02 1.62764372071491e-01 + 3.07399015207509e-02 1.72484170230167e-01 + 3.44190712967375e-02 1.82342411230462e-01 + 3.84042462872392e-02 1.92272935169736e-01 + 4.26949602499204e-02 2.02267606430067e-01 + 4.72829519098945e-02 2.12327253752788e-01 + 5.21982679528133e-02 2.22432953038477e-01 + 5.73926065743804e-02 2.32603305860823e-01 + 6.29241217245761e-02 2.42803072101294e-01 + 6.87643637125652e-02 2.53043124634065e-01 + 7.49396649714102e-02 2.63302631639567e-01 + 8.15067225995126e-02 2.73538864194590e-01 + 8.83465340790937e-02 2.83822725719936e-01 + 9.56069618941523e-02 2.94046380437990e-01 + 1.03242517429104e-01 3.04232736766140e-01 + 1.11181349110592e-01 3.14429033366110e-01 + 1.19600191231908e-01 3.24484491634080e-01 + 1.28332959831487e-01 3.34525491878455e-01 + 1.37529624980321e-01 3.44409800526354e-01 + 1.47054393871766e-01 3.54250702832129e-01 + 1.57068458906247e-01 3.63878030450328e-01 + 1.67434000189824e-01 3.73414748310375e-01 + 1.78267900010996e-01 3.82720355055487e-01 + 1.89470766243389e-01 3.91888095042532e-01 + 2.01116356758227e-01 4.00815766784955e-01 + 2.13142982412971e-01 4.09560128320329e-01 + 2.25647591527817e-01 4.17962490202192e-01 + 2.38508303803600e-01 4.26178518900819e-01 + 2.51815542326035e-01 4.34041451446706e-01 + 2.65513873471791e-01 4.41613730534841e-01 + 2.79625890849574e-01 4.48822548308045e-01 + 2.94122344676086e-01 4.55688297738170e-01 + 3.09025395595222e-01 4.62123018507889e-01 + 3.24322980248437e-01 4.68104987140686e-01 + 3.39961508551486e-01 4.73721797521014e-01 + 3.55970212497486e-01 4.78842188217134e-01 + 3.72330405840910e-01 4.83451204703119e-01 + 3.89018592148974e-01 4.87553971207526e-01 + 4.06028086432003e-01 4.91073750593815e-01 + 4.23330061515063e-01 4.94038626508448e-01 + 4.40892507832343e-01 4.96523552581426e-01 + 4.58722088973087e-01 4.98299627767656e-01 + 4.76781800214759e-01 4.99452452619975e-01 + 4.95047752165150e-01 4.99958293491181e-01 + 5.13494417346180e-01 4.99806115294212e-01 + 5.32095125341593e-01 4.98977641113232e-01 + 5.50821128028667e-01 4.97448239777686e-01 + 5.69628317431665e-01 4.95095914136444e-01 + 5.88509798330163e-01 4.92097041935332e-01 + 6.07423091269127e-01 4.88360764967307e-01 + 6.26315879676062e-01 4.83792644100844e-01 + 6.45179027618201e-01 4.78506342917923e-01 + 6.63949992276556e-01 4.72397468589394e-01 + 6.82596771397553e-01 4.65480454296126e-01 + 7.01105667898352e-01 4.57821533331759e-01 + 7.19390458980571e-01 4.49306560335264e-01 + 7.37449386734799e-01 4.40021763716986e-01 + 7.55233287450602e-01 4.29949280199755e-01 + 7.72675183085231e-01 4.19055842892285e-01 + 7.89810876588208e-01 4.07465502995371e-01 + 8.06484809364324e-01 3.95019026978122e-01 + 8.22749466427636e-01 3.81863671783111e-01 + 8.38549437843995e-01 3.67985948498897e-01 + 8.53822843141276e-01 3.53376712171519e-01 + 8.68482698282576e-01 3.38013117891467e-01 + 8.82527277768971e-01 3.21961416297325e-01 + 8.95954036277289e-01 3.05275366473099e-01 + 9.08757285533517e-01 2.87998251390473e-01 + 9.20757624348661e-01 2.70058949061020e-01 + 9.32077214908394e-01 2.51596702608668e-01 + 9.42611287438903e-01 2.32595879244925e-01 + 9.52349414910574e-01 2.13103474747613e-01 + 9.61237529561560e-01 1.93147648123409e-01 + 9.69168871294468e-01 1.72736199342553e-01 + 9.76326703713309e-01 1.51992962994221e-01 + 9.82585730197106e-01 1.30917869381533e-01 + 9.87884002029843e-01 1.09544033639734e-01 + 9.92202667894419e-01 8.79209963846691e-02 + 9.95599172262122e-01 6.61100082160239e-02 + 9.98052102758341e-01 4.41573284776160e-02 + 9.99507690675012e-01 2.21028728366928e-02 + 1.00000000000000e+00 1.39471767468535e-15 diff --git a/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF01_Coords.txt b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF01_Coords.txt new file mode 100644 index 00000000..c0c8ddad --- /dev/null +++ b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF01_Coords.txt @@ -0,0 +1,208 @@ + 201 NumCoords ! The number of coordinates in the airfoil shape file (including an extra coordinate for airfoil reference). Set to zero if coordinates not included. +! ......... x-y coordinates are next if NumCoords > 0 ............. +! x-y coordinate of airfoil reference +! x/c y/c + 0.489474 0 +! coordinates of airfoil shape +! interpolation to 200 points +! x/c y/c + 1.00000000000000e+00 -3.16421772612390e-03 + 9.99110945270443e-01 -2.47105920697162e-02 + 9.97576994375339e-01 -4.67993845022092e-02 + 9.95459944687624e-01 -6.84337167356077e-02 + 9.91976392334682e-01 -9.00657715770117e-02 + 9.87532357694084e-01 -1.11371691742356e-01 + 9.82073007117098e-01 -1.32004290598503e-01 + 9.75632495177376e-01 -1.51997295578341e-01 + 9.68304625227921e-01 -1.71396793768580e-01 + 9.60134319308372e-01 -1.90350472287492e-01 + 9.50973174570070e-01 -2.10503605813256e-01 + 9.40976075096518e-01 -2.30186416006723e-01 + 9.30161994799789e-01 -2.49354345164969e-01 + 9.18526548050635e-01 -2.67946053746076e-01 + 9.06204685559811e-01 -2.85993589913206e-01 + 8.93096814131007e-01 -3.03374276912405e-01 + 8.79335004439212e-01 -3.20123403157046e-01 + 8.64921830314282e-01 -3.36188237142695e-01 + 8.49900429191050e-01 -3.51546887620593e-01 + 8.34308004668356e-01 -3.66174875302933e-01 + 8.18161715887287e-01 -3.80020141794273e-01 + 8.01527591100297e-01 -3.93086268689914e-01 + 7.84496904773810e-01 -4.04786375894643e-01 + 7.67028251214628e-01 -4.15444728414506e-01 + 7.49221098481114e-01 -4.25443666639427e-01 + 7.31109312546861e-01 -4.34681496122239e-01 + 7.12733221739921e-01 -4.43095560497414e-01 + 6.94124804992610e-01 -4.50716083967267e-01 + 6.75296861217813e-01 -4.57507733373021e-01 + 6.56351220288612e-01 -4.63629797162085e-01 + 6.37297642282493e-01 -4.69021650406962e-01 + 6.18184579076336e-01 -4.73661711191075e-01 + 5.99048824748551e-01 -4.77500682555689e-01 + 5.79905140141725e-01 -4.80476298777868e-01 + 5.60822552266790e-01 -4.82821100897016e-01 + 5.41807779672030e-01 -4.84393609336454e-01 + 5.23137860195204e-01 -4.85340334737817e-01 + 5.04895615780131e-01 -4.85677059437076e-01 + 4.86822413494681e-01 -4.85372268979213e-01 + 4.68943246111643e-01 -4.84434587337354e-01 + 4.51281215228627e-01 -4.82849729526095e-01 + 4.33869791962394e-01 -4.80550261086293e-01 + 4.16708291601139e-01 -4.77756903947675e-01 + 3.99821942290793e-01 -4.74438844863898e-01 + 3.83021226581361e-01 -4.70501187606855e-01 + 3.66510028690683e-01 -4.66117838259083e-01 + 3.50339822528374e-01 -4.61229488062895e-01 + 3.34529434920323e-01 -4.55868065561778e-01 + 3.19060580350289e-01 -4.50137865005078e-01 + 3.03961951611492e-01 -4.44019094016567e-01 + 2.89263477671933e-01 -4.37498086693495e-01 + 2.74954691526094e-01 -4.30627011410182e-01 + 2.61045693322669e-01 -4.23408038064864e-01 + 2.47531081353258e-01 -4.15862808513859e-01 + 2.34454873671549e-01 -4.07946420300901e-01 + 2.21749536060482e-01 -3.99796724707317e-01 + 2.09495761009538e-01 -3.91329723402531e-01 + 1.97654805990354e-01 -3.82623286493885e-01 + 1.86194798835722e-01 -3.73767309376824e-01 + 1.75143832165431e-01 -3.64767492631537e-01 + 1.64510931825440e-01 -3.55619768853155e-01 + 1.54264662143747e-01 -3.46336240294808e-01 + 1.44469444171873e-01 -3.36855727877300e-01 + 1.35016546824907e-01 -3.27295058357275e-01 + 1.26007074796798e-01 -3.17588898325485e-01 + 1.17335095261661e-01 -3.07850346569760e-01 + 1.09122191907664e-01 -2.97988397774553e-01 + 1.01228904610188e-01 -2.88095133738336e-01 + 9.37005857644255e-02 -2.78149751233394e-01 + 8.65952060326960e-02 -2.68149983931702e-01 + 7.97470493709899e-02 -2.58245516255184e-01 + 7.32564041991407e-02 -2.48375945846845e-01 + 6.71103398619902e-02 -2.38520800068324e-01 + 6.12956358739206e-02 -2.28273089593854e-01 + 5.58512861647731e-02 -2.18035625337734e-01 + 5.06986492562267e-02 -2.07863675578317e-01 + 4.58459063482147e-02 -1.97741417265822e-01 + 4.12374651654770e-02 -1.87689118226564e-01 + 3.69363886388660e-02 -1.77695953267912e-01 + 3.29623755477581e-02 -1.67780856055308e-01 + 2.91933599630294e-02 -1.58000033452927e-01 + 2.58326584607911e-02 -1.48266339522027e-01 + 2.25688351721396e-02 -1.39011630549253e-01 + 1.95732992520596e-02 -1.30105462233865e-01 + 1.67610738246130e-02 -1.21314096800611e-01 + 1.42583321073789e-02 -1.12582415338248e-01 + 1.19908166431120e-02 -1.03925933593292e-01 + 9.99928542511028e-03 -9.53469054771868e-02 + 8.12764378342123e-03 -8.68845733614765e-02 + 6.50553857600199e-03 -7.85191937270735e-02 + 5.17572423597908e-03 -7.02483867655549e-02 + 3.97140784027181e-03 -6.20650797672678e-02 + 2.94862431147953e-03 -5.39399963412825e-02 + 2.14055966565164e-03 -4.58470093224122e-02 + 1.45003537340197e-03 -3.78838208911683e-02 + 9.20097460438803e-04 -3.00188642323400e-02 + 5.13569518013506e-04 -2.22872670431334e-02 + 2.24854144698289e-04 -1.47090799938054e-02 + 7.16420419797124e-05 -7.28122005805669e-03 + 0.00000000000000e+00 0.00000000000000e+00 + 8.30667337145912e-05 7.28493907761252e-03 + 2.40621206193159e-04 1.47085612205429e-02 + 5.29850643501296e-04 2.22690666161207e-02 + 9.37552646642290e-04 2.99680567436069e-02 + 1.46364423687516e-03 3.78031462162717e-02 + 2.13415396408500e-03 4.57718293152885e-02 + 2.98505302314019e-03 5.38762991811228e-02 + 4.08049090961046e-03 6.21031222356185e-02 + 5.32348409326103e-03 7.04621026477038e-02 + 6.68540525770168e-03 7.89717384981979e-02 + 8.16349050305524e-03 8.76289039370964e-02 + 9.84115364385886e-03 9.63974146736541e-02 + 1.17664515759166e-02 1.05263924316241e-01 + 1.40318228128144e-02 1.14211150659918e-01 + 1.64404096111178e-02 1.23297936682812e-01 + 1.90063994463009e-02 1.32535275404535e-01 + 2.17243347773833e-02 1.41923218754833e-01 + 2.47531082013638e-02 1.51382020977074e-01 + 2.79876147869340e-02 1.60929925146753e-01 + 3.16880968401645e-02 1.70478068315566e-01 + 3.55350251674146e-02 1.80153130476464e-01 + 3.96263775536540e-02 1.89947425730580e-01 + 4.39456143792258e-02 1.99882812309296e-01 + 4.85239794021445e-02 2.09908181416265e-01 + 5.34534137951630e-02 2.19944265641675e-01 + 5.87462885442388e-02 2.29964197658055e-01 + 6.44270496014028e-02 2.39969754830107e-01 + 7.04097222861749e-02 2.50025763168648e-01 + 7.66631835969947e-02 2.60165429986364e-01 + 8.32549959691082e-02 2.70336561512274e-01 + 9.01101313435420e-02 2.80563309640775e-01 + 9.74049202740261e-02 2.90697579494236e-01 + 1.05114698051431e-01 3.00743368754403e-01 + 1.13145220439572e-01 3.10785648613665e-01 + 1.21630315794086e-01 3.20725544551961e-01 + 1.30390853479517e-01 3.30702112547975e-01 + 1.39590645856004e-01 3.40558753101048e-01 + 1.49124870362037e-01 3.50362123732590e-01 + 1.59154982855993e-01 3.59921913101712e-01 + 1.69544432069570e-01 3.69399060590938e-01 + 1.80386709779081e-01 3.78695988921857e-01 + 1.91579763428791e-01 3.87884300501059e-01 + 2.03215759235826e-01 3.96833543919666e-01 + 2.15253430564785e-01 4.05547214951462e-01 + 2.27772014189445e-01 4.13882927583771e-01 + 2.40642603224139e-01 4.22086896802528e-01 + 2.53939036577503e-01 4.30033802762336e-01 + 2.67609972467099e-01 4.37691285847929e-01 + 2.81557875539761e-01 4.44965913565754e-01 + 2.95881178190567e-01 4.51813642422346e-01 + 3.10595953223466e-01 4.58226822092898e-01 + 3.25692615194284e-01 4.64358752082265e-01 + 3.41122510103875e-01 4.70166093755745e-01 + 3.56906920161226e-01 4.75457819601108e-01 + 3.73028060365530e-01 4.80296533840550e-01 + 3.89466547847528e-01 4.84640854961732e-01 + 4.06216915276230e-01 4.88245022885247e-01 + 4.23329613709593e-01 4.91316221321931e-01 + 4.40890014276592e-01 4.94066031076244e-01 + 4.58716932230117e-01 4.96120177384477e-01 + 4.76773550105776e-01 4.97493108926328e-01 + 4.95036075072470e-01 4.98220076856676e-01 + 5.13479009238266e-01 4.98328313435672e-01 + 5.32075794301084e-01 4.97686119534454e-01 + 5.50797707737235e-01 4.96272617324986e-01 + 5.69600641150388e-01 4.94015215318247e-01 + 5.88477721457098e-01 4.91029243067188e-01 + 6.07386635657425e-01 4.87295372664773e-01 + 6.26275242831597e-01 4.82792184672487e-01 + 6.45134391494005e-01 4.77579799714536e-01 + 6.63901695169446e-01 4.71560607238906e-01 + 6.82545269979229e-01 4.64770350611842e-01 + 7.01051428389662e-01 4.57262911241947e-01 + 7.19334097084216e-01 4.48930414817246e-01 + 7.37391465413848e-01 4.39841141799307e-01 + 7.55174481191430e-01 4.29986432588973e-01 + 7.72616437803403e-01 4.19381365239015e-01 + 7.89753200934423e-01 4.08201692944460e-01 + 8.06429273866882e-01 3.96269530921693e-01 + 8.22696674409171e-01 3.83630606068877e-01 + 8.38499958578817e-01 3.70228814924312e-01 + 8.53777444028247e-01 3.56113546193772e-01 + 8.68442280245945e-01 3.41287951489090e-01 + 8.82492540270293e-01 3.25786277344664e-01 + 8.95925498965556e-01 3.09679894523524e-01 + 9.08735247378820e-01 2.93027554712345e-01 + 9.20742332422719e-01 2.75162884784513e-01 + 9.32068464518384e-01 2.56731572981429e-01 + 9.42608539274729e-01 2.37762434632290e-01 + 9.52774207875208e-01 2.18302108340019e-01 + 9.62859775973639e-01 1.98379401591706e-01 + 9.70800878118612e-01 1.77985574843893e-01 + 9.77526560026023e-01 1.57228723263127e-01 + 9.83348702581913e-01 1.35262496314977e-01 + 9.88287866680976e-01 1.12048580600310e-01 + 9.92312239757846e-01 8.89420954512888e-02 + 9.95598399807970e-01 6.64089965678724e-02 + 9.97884993829918e-01 4.40785443080142e-02 + 9.99371468236542e-01 2.18636293439463e-02 + 1.00000000000000e+00 -1.46513661216579e-04 diff --git a/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF02_Coords.txt b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF02_Coords.txt new file mode 100644 index 00000000..3d277f48 --- /dev/null +++ b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF02_Coords.txt @@ -0,0 +1,208 @@ + 201 NumCoords ! The number of coordinates in the airfoil shape file (including an extra coordinate for airfoil reference). Set to zero if coordinates not included. +! ......... x-y coordinates are next if NumCoords > 0 ............. +! x-y coordinate of airfoil reference +! x/c y/c + 0.405419 0 +! coordinates of airfoil shape +! interpolation to 200 points +! x/c y/c + 1.00000000000000e+00 -1.94964271094086e-02 + 9.96919760277077e-01 -3.64826077995756e-02 + 9.94667087130123e-01 -5.60719522447348e-02 + 9.94761079761680e-01 -7.41287339133444e-02 + 9.91487644632361e-01 -9.30111065602699e-02 + 9.87177265536021e-01 -1.10830801551200e-01 + 9.81618438289038e-01 -1.25618285586318e-01 + 9.74359531938626e-01 -1.37858592038257e-01 + 9.66196197839873e-01 -1.48011073720888e-01 + 9.57084778530041e-01 -1.57244213613537e-01 + 9.47030628319075e-01 -1.76163809587731e-01 + 9.36255994779871e-01 -1.94451554089259e-01 + 9.24755229326704e-01 -2.12084822033116e-01 + 9.12514414231155e-01 -2.28979937705261e-01 + 8.99641900735580e-01 -2.45152777431143e-01 + 8.86071424135137e-01 -2.60541847813049e-01 + 8.71933069994702e-01 -2.75199084385032e-01 + 8.57249287582935e-01 -2.89132205047948e-01 + 8.42064402212172e-01 -3.02348165923965e-01 + 8.26409062460493e-01 -3.14787448920772e-01 + 8.10288808146397e-01 -3.26359904138149e-01 + 7.93758629967803e-01 -3.37091676397995e-01 + 7.76918356342850e-01 -3.44291222218988e-01 + 7.59756850873003e-01 -3.49997131324565e-01 + 7.42348874985586e-01 -3.55640730349542e-01 + 7.24708863089766e-01 -3.60706166782752e-01 + 7.06860528348044e-01 -3.64855413158321e-01 + 6.88831517526942e-01 -3.68409151382566e-01 + 6.70633473983476e-01 -3.71524443372096e-01 + 6.52350564072767e-01 -3.74401784953206e-01 + 6.33982188894777e-01 -3.77065482741049e-01 + 6.15559054509071e-01 -3.79168407766431e-01 + 5.97101918875316e-01 -3.80350473776001e-01 + 5.78607712056559e-01 -3.80687774167715e-01 + 5.60114269360246e-01 -3.80570858605504e-01 + 5.41594988940669e-01 -3.80067548433720e-01 + 5.24491038376215e-01 -3.79537588218947e-01 + 5.09243386421893e-01 -3.78981564014641e-01 + 4.94142523233296e-01 -3.78083193106923e-01 + 4.79201400260462e-01 -3.76755219694438e-01 + 4.64426672033553e-01 -3.74840429494636e-01 + 4.49830052252528e-01 -3.72341501685922e-01 + 4.35411690443212e-01 -3.69564589340833e-01 + 4.21176828920086e-01 -3.66527761938651e-01 + 4.06104752722998e-01 -3.63217644680091e-01 + 3.91187261313758e-01 -3.59606140139742e-01 + 3.76543272121399e-01 -3.55540172858436e-01 + 3.62174951181275e-01 -3.51199859300841e-01 + 3.48051575371203e-01 -3.46733492501332e-01 + 3.34166838440425e-01 -3.42236418543471e-01 + 3.20531094536529e-01 -3.37752409778483e-01 + 3.07166374335585e-01 -3.33138685551140e-01 + 2.94106366929472e-01 -3.28233453302116e-01 + 2.81356553687748e-01 -3.22927037164433e-01 + 2.68929414080849e-01 -3.17210399237509e-01 + 2.56792257622504e-01 -3.11199667576809e-01 + 2.44988366773819e-01 -3.04908147192347e-01 + 2.33487068586780e-01 -2.98398015474454e-01 + 2.22244174627754e-01 -2.91908544458142e-01 + 2.11259238518723e-01 -2.85624154835144e-01 + 2.00540109534862e-01 -2.79445232131323e-01 + 1.90099108400639e-01 -2.73144271821139e-01 + 1.79974500726159e-01 -2.66577875347765e-01 + 1.69915683501289e-01 -2.59834415460592e-01 + 1.60172080930679e-01 -2.52962962830656e-01 + 1.50692746390245e-01 -2.46077778027207e-01 + 1.41572171628772e-01 -2.39083657564268e-01 + 1.32782528972732e-01 -2.31868964518358e-01 + 1.24316300642292e-01 -2.24479019688654e-01 + 1.16125227242430e-01 -2.17115852851904e-01 + 1.08022185325659e-01 -2.10062937367560e-01 + 1.00068510946488e-01 -2.03253136991591e-01 + 9.24181923986685e-02 -1.96403291468797e-01 + 8.52292314707568e-02 -1.87525621188063e-01 + 7.85442356694309e-02 -1.78452955788562e-01 + 7.21826484759061e-02 -1.69371289606163e-01 + 6.59224769279808e-02 -1.60339488949538e-01 + 5.95888908522178e-02 -1.51375335195636e-01 + 5.34570839330547e-02 -1.42381729136260e-01 + 4.78323253460157e-02 -1.33307333331388e-01 + 4.27773110897719e-02 -1.24183705410093e-01 + 3.81406060607182e-02 -1.14969947782298e-01 + 3.34394858942616e-02 -1.07833476412008e-01 + 2.85905771976062e-02 -1.02443290523446e-01 + 2.39758840800528e-02 -9.70665624082339e-02 + 2.00924464828600e-02 -9.14418911635026e-02 + 1.67774266077405e-02 -8.55577600333846e-02 + 1.37085226488790e-02 -7.95717583471716e-02 + 1.06047400652709e-02 -7.35922291670351e-02 + 7.90398428387208e-03 -6.75352052422909e-02 + 6.19892209075347e-03 -6.13137254015921e-02 + 4.74163822479280e-03 -5.48650139398457e-02 + 3.46348797721600e-03 -4.81553931473352e-02 + 2.35439809271567e-03 -4.11318098186878e-02 + 1.48284350464362e-03 -3.41609786643930e-02 + 9.33668904559450e-04 -2.70825630260840e-02 + 5.16784288069033e-04 -2.00607976197347e-02 + 2.03224808289276e-04 -1.32008980839843e-02 + 2.88583219323030e-05 -6.51695336105137e-03 + 0.00000000000000e+00 0.00000000000000e+00 + 1.06034557788935e-04 6.54242344402049e-03 + 3.10442109886626e-04 1.32200621240131e-02 + 6.27358526355077e-04 2.00270586046359e-02 + 1.04642059582819e-03 2.69584070704927e-02 + 1.56119077029123e-03 3.40044020355773e-02 + 2.20965204677518e-03 4.11549554928511e-02 + 3.41098060660727e-03 4.84144618046186e-02 + 5.03360788709283e-03 5.57589214681263e-02 + 6.61245394229265e-03 6.32348735880216e-02 + 8.28994979066480e-03 7.08911179309667e-02 + 9.96034393771960e-03 7.87021820009504e-02 + 1.17636547160994e-02 8.65345063094756e-02 + 1.43612220190213e-02 9.42922806414463e-02 + 1.76430317064128e-02 1.02026805686471e-01 + 2.08737235707927e-02 1.09949354414078e-01 + 2.39097774660482e-02 1.18163715137690e-01 + 2.68277855724522e-02 1.26610148817642e-01 + 3.00184157320084e-02 1.35071752122783e-01 + 3.38529447168762e-02 1.43382634408088e-01 + 3.85374178015213e-02 1.51512804458775e-01 + 4.35193302635381e-02 1.59709865654183e-01 + 4.83524785822808e-02 1.68285035077358e-01 + 5.28925514814938e-02 1.77785241588636e-01 + 5.74509623742945e-02 1.87519752029641e-01 + 6.25207280441538e-02 1.96995257755178e-01 + 6.84864459272233e-02 2.05895125589205e-01 + 7.51749747555155e-02 2.14483369522917e-01 + 8.21424789239981e-02 2.23186204375288e-01 + 8.89480736036874e-02 2.32391482476344e-01 + 9.57168879662020e-02 2.41977056322773e-01 + 1.02682866347355e-01 2.51651269226778e-01 + 1.10220820704945e-01 2.61011250036727e-01 + 1.18407958380338e-01 2.69947451121491e-01 + 1.26881602570982e-01 2.78784626441245e-01 + 1.35660947758076e-01 2.87754998986677e-01 + 1.44539262453658e-01 2.97066755412224e-01 + 1.53710627262191e-01 3.06476813639894e-01 + 1.63224044690801e-01 3.15759213512801e-01 + 1.73217608842146e-01 3.24616725514123e-01 + 1.83592362834056e-01 3.33425258716891e-01 + 1.94325962262670e-01 3.42337881360872e-01 + 2.05324011045863e-01 3.51288753587316e-01 + 2.16730097076787e-01 3.60001663577674e-01 + 2.28586578632938e-01 3.68187843125944e-01 + 2.40883113525511e-01 3.75812546015869e-01 + 2.53496856322201e-01 3.83600826529355e-01 + 2.66426205569999e-01 3.91650072271809e-01 + 2.79648785252606e-01 3.99396772979447e-01 + 2.92654108132638e-01 4.06655149783746e-01 + 3.05982927892807e-01 4.13055764549372e-01 + 3.19616352211114e-01 4.19007565475870e-01 + 3.33559027388770e-01 4.25557700509835e-01 + 3.47790649521039e-01 4.31983019768178e-01 + 3.62286841731615e-01 4.37810261240227e-01 + 3.77034995262049e-01 4.43528144955168e-01 + 3.92039353236568e-01 4.48820541528545e-01 + 4.07301441870269e-01 4.52540541894158e-01 + 4.23279474819674e-01 4.55820048720622e-01 + 4.40634468309514e-01 4.59564402113604e-01 + 4.58216729640812e-01 4.62715547857050e-01 + 4.76002112543622e-01 4.64915551067932e-01 + 4.93972301744354e-01 4.66495076484244e-01 + 5.12102601808104e-01 4.67675381916421e-01 + 5.30374260454303e-01 4.67718175971608e-01 + 5.48760443148615e-01 4.66664714353419e-01 + 5.67217438731546e-01 4.64745135086648e-01 + 5.85739737161608e-01 4.61729462619936e-01 + 6.04297036727046e-01 4.57963754355715e-01 + 6.22849821404431e-01 4.53804771006538e-01 + 6.41387754588488e-01 4.49034662925732e-01 + 6.59860243895401e-01 4.43612634661173e-01 + 6.78243902722125e-01 4.37681519215445e-01 + 6.96525620003880e-01 4.31223433182484e-01 + 7.14630615751572e-01 4.24172943475969e-01 + 7.32553281453510e-01 4.16497772874745e-01 + 7.50252988657587e-01 4.08237425290133e-01 + 7.67683365695193e-01 3.99660004830094e-01 + 7.84884705771043e-01 3.91177827246511e-01 + 8.01707686882478e-01 3.82511987837697e-01 + 8.18171045140217e-01 3.73184018737277e-01 + 8.34218184325793e-01 3.62939454140551e-01 + 8.49803537682218e-01 3.52119100925938e-01 + 8.64853102337230e-01 3.40870213182952e-01 + 8.79352542615986e-01 3.29069212973395e-01 + 8.93288312520579e-01 3.16847374518213e-01 + 9.06641281797077e-01 3.04310322344821e-01 + 9.19235341950085e-01 2.88747970901776e-01 + 9.31163314413939e-01 2.72527797669352e-01 + 9.42304292794809e-01 2.55835364954767e-01 + 9.55213979558356e-01 2.38692901385650e-01 + 9.72177046241266e-01 2.21180379624901e-01 + 9.80174206699236e-01 2.02148008484942e-01 + 9.84417859316093e-01 1.80623200933622e-01 + 9.87730786501502e-01 1.53965422157644e-01 + 9.90607437911417e-01 1.22548669883815e-01 + 9.92941558866010e-01 9.10997252988497e-02 + 9.95524996439665e-01 6.60081316645982e-02 + 9.96925214206640e-01 4.30168042831882e-02 + 9.98589083226293e-01 2.09101531114029e-02 + 1.00000000000000e+00 -1.10918874127508e-04 diff --git a/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF03_Coords.txt b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF03_Coords.txt new file mode 100644 index 00000000..3574f261 --- /dev/null +++ b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF03_Coords.txt @@ -0,0 +1,208 @@ + 201 NumCoords ! The number of coordinates in the airfoil shape file (including an extra coordinate for airfoil reference). Set to zero if coordinates not included. +! ......... x-y coordinates are next if NumCoords > 0 ............. +! x-y coordinate of airfoil reference +! x/c y/c + 0.300072 0 +! coordinates of airfoil shape +! interpolation to 200 points +! x/c y/c + 1.00000000000000e+00 -2.35717905236513e-02 + 9.95894264742224e-01 -3.92526822859504e-02 + 9.92356907783760e-01 -5.58972397758731e-02 + 9.91832649399724e-01 -7.22796935620756e-02 + 9.89065767280758e-01 -8.98751886421859e-02 + 9.85303518885023e-01 -1.06063296906901e-01 + 9.79227294864432e-01 -1.18115211299191e-01 + 9.68317731645526e-01 -1.26727180688080e-01 + 9.56870605029902e-01 -1.32551970200501e-01 + 9.44399782765251e-01 -1.37235805042327e-01 + 9.31376191661979e-01 -1.49921669278151e-01 + 9.18131472990873e-01 -1.62163429513691e-01 + 9.04532462534647e-01 -1.73794296481196e-01 + 8.90513850343901e-01 -1.84548505419301e-01 + 8.76094083221940e-01 -1.94369351614981e-01 + 8.61295443643247e-01 -2.03387259424766e-01 + 8.46228194041534e-01 -2.11697233177751e-01 + 8.30943028446170e-01 -2.19423235960492e-01 + 8.15464579238373e-01 -2.26583810092412e-01 + 7.99805091304501e-01 -2.33034629864386e-01 + 7.83949186991882e-01 -2.38634111936675e-01 + 7.67924901075415e-01 -2.43491491542901e-01 + 7.51827610435101e-01 -2.46922502098554e-01 + 7.35700766231654e-01 -2.49967384402370e-01 + 7.19557581083962e-01 -2.53049973028183e-01 + 7.03374920806515e-01 -2.55675693783315e-01 + 6.87141084317211e-01 -2.57511647636345e-01 + 6.70872708173025e-01 -2.58916159150435e-01 + 6.54584120557027e-01 -2.60070409267096e-01 + 6.38316166451763e-01 -2.61147805145693e-01 + 6.22053812145135e-01 -2.62242468065543e-01 + 6.05795467035195e-01 -2.62984971699304e-01 + 5.89535785963171e-01 -2.62980782780771e-01 + 5.73249959911008e-01 -2.62338277960480e-01 + 5.56924435273058e-01 -2.61412073870956e-01 + 5.40499557828918e-01 -2.60380178738677e-01 + 5.25124338707629e-01 -2.59541047800324e-01 + 5.11278184667223e-01 -2.58859241415762e-01 + 4.97568404605392e-01 -2.58048556490882e-01 + 4.84002314517955e-01 -2.56975419244797e-01 + 4.70578871550198e-01 -2.55452441773426e-01 + 4.57299606722912e-01 -2.53575365177959e-01 + 4.44165059993117e-01 -2.51608626178359e-01 + 4.31171120115011e-01 -2.49565341878899e-01 + 4.17960046660827e-01 -2.47435089625259e-01 + 4.04894573177154e-01 -2.45125131039407e-01 + 3.92025010140446e-01 -2.42462612691433e-01 + 3.79343869682045e-01 -2.39595692647852e-01 + 3.66822492601097e-01 -2.36738334901165e-01 + 3.54437597401984e-01 -2.34084096374542e-01 + 3.42188016976202e-01 -2.31663337492797e-01 + 3.30106565812339e-01 -2.29245864019644e-01 + 3.18228608318416e-01 -2.26607512965020e-01 + 3.06561819529862e-01 -2.23599397180190e-01 + 2.95096087112862e-01 -2.20264450363764e-01 + 2.83822976873035e-01 -2.16705858133672e-01 + 2.72749367112427e-01 -2.12987917599575e-01 + 2.61871015332779e-01 -2.09105223071590e-01 + 2.51166620646972e-01 -2.05257087666955e-01 + 2.40624400846784e-01 -2.01625484971293e-01 + 2.30238432660905e-01 -1.98140713780569e-01 + 2.20026112530791e-01 -1.94584499409339e-01 + 2.09976055390476e-01 -1.90827834894363e-01 + 1.99702136630218e-01 -1.86888650453711e-01 + 1.89635587559752e-01 -1.82831573590219e-01 + 1.79772976644460e-01 -1.78716242047549e-01 + 1.70166626869497e-01 -1.74489311956110e-01 + 1.60857736786573e-01 -1.70006317401921e-01 + 1.51803109355095e-01 -1.65351581130296e-01 + 1.42904673719036e-01 -1.60741881001108e-01 + 1.34016689385335e-01 -1.56400925252111e-01 + 1.25172927433342e-01 -1.52235477594800e-01 + 1.16585145327233e-01 -1.47936269496174e-01 + 1.08455437817872e-01 -1.42606858442656e-01 + 1.00797932241528e-01 -1.36869866343013e-01 + 9.34220406155034e-02 -1.30998286551843e-01 + 8.60634069002927e-02 -1.25203141666258e-01 + 7.85543380199848e-02 -1.19513567026171e-01 + 7.12090438710948e-02 -1.13679449812632e-01 + 6.43781714721257e-02 -1.07497988597386e-01 + 5.81748969271094e-02 -1.00901485941624e-01 + 5.23111625072034e-02 -9.40070595698379e-02 + 4.63848694510659e-02 -8.87274392056592e-02 + 4.02274234777820e-02 -8.49827667220595e-02 + 3.43402499368400e-02 -8.12041215315654e-02 + 2.92122911092120e-02 -7.70335607862094e-02 + 2.46619896023326e-02 -7.24469162604508e-02 + 2.03998728457045e-02 -6.76744757448659e-02 + 1.62083083553108e-02 -6.28569220857654e-02 + 1.24122747710821e-02 -5.78802307117992e-02 + 9.59261999542548e-03 -5.26178555647791e-02 + 7.30477546051285e-03 -4.69809514049654e-02 + 5.24424677887566e-03 -4.11640833368231e-02 + 3.22154066429621e-03 -3.53189852766165e-02 + 1.65180206365193e-03 -2.94779767104117e-02 + 1.00171614777338e-03 -2.35012775997985e-02 + 5.33709082287082e-04 -1.74789869612144e-02 + 1.93102071972421e-04 -1.15157513977575e-02 + 8.83513173800652e-06 -5.67716919165800e-03 + 0.00000000000000e+00 0.00000000000000e+00 + 1.16783719135356e-04 5.69723987547027e-03 + 3.43118960628982e-04 1.15219848562656e-02 + 6.72993148161244e-04 1.74602777849096e-02 + 1.09737183733306e-03 2.34963725200926e-02 + 1.60684348093023e-03 2.96112825450017e-02 + 2.45643493250886e-03 3.57965862211899e-02 + 3.99538452491140e-03 4.20591838228941e-02 + 5.93173609093872e-03 4.83922212075131e-02 + 7.78831860532396e-03 5.48405525131736e-02 + 9.77944638510934e-03 6.14059674486418e-02 + 1.18236157695499e-02 6.80196332226401e-02 + 1.41090606785859e-02 7.45698337168348e-02 + 1.73056541184598e-02 8.10186811443194e-02 + 2.11847229777394e-02 8.74687230723911e-02 + 2.49676864074981e-02 9.40869839667322e-02 + 2.84682042956027e-02 1.00930111245539e-01 + 3.18331846418495e-02 1.07898963211733e-01 + 3.54793253397875e-02 1.14828880543840e-01 + 3.98821847361107e-02 1.21582993745491e-01 + 4.51314595122883e-02 1.28212190706429e-01 + 5.07378731779770e-02 1.34892120261391e-01 + 5.60731260647946e-02 1.41960877640708e-01 + 6.09722950181842e-02 1.50342170540091e-01 + 6.58438293017437e-02 1.58942245558348e-01 + 7.12537393230430e-02 1.67161944148746e-01 + 7.76600623439659e-02 1.74624850622013e-01 + 8.48496220471092e-02 1.81687450473830e-01 + 9.23057704681641e-02 1.88867715176475e-01 + 9.94459240673263e-02 1.96648864845365e-01 + 1.06388932256554e-01 2.04900423667625e-01 + 1.13500915840888e-01 2.13208533649742e-01 + 1.21190173762834e-01 2.21120456132424e-01 + 1.29552662653441e-01 2.28502274929156e-01 + 1.38071878683882e-01 2.35719905821540e-01 + 1.46821747467612e-01 2.43114116431733e-01 + 1.55674346023180e-01 2.50880294859766e-01 + 1.64742508530083e-01 2.58798876919177e-01 + 1.74100620712751e-01 2.66555316753591e-01 + 1.83827637281412e-01 2.73887896215538e-01 + 1.93900930930976e-01 2.81137679364482e-01 + 2.04279807701489e-01 2.88489630315669e-01 + 2.14917904141514e-01 2.95836142276111e-01 + 2.25877633648094e-01 3.02970528418131e-01 + 2.37175240693611e-01 3.09614749723245e-01 + 2.48781997761441e-01 3.15783316315385e-01 + 2.60667851543173e-01 3.22097199193517e-01 + 2.72834283839390e-01 3.28652682218705e-01 + 2.85283064783479e-01 3.34865419367518e-01 + 2.97847251117894e-01 3.40624356479022e-01 + 3.10710643373344e-01 3.45634518095723e-01 + 3.23837985214461e-01 3.50222642863971e-01 + 3.37240583535417e-01 3.55267130987121e-01 + 3.50911402546816e-01 3.60167827153803e-01 + 3.64804696483725e-01 3.64587389850643e-01 + 3.78910279118625e-01 3.69073483105304e-01 + 3.93243450766671e-01 3.73200860402215e-01 + 4.07809010689417e-01 3.75729715812861e-01 + 4.23000375070936e-01 3.77751754255469e-01 + 4.39328786730662e-01 3.80141190316103e-01 + 4.55813610039226e-01 3.82101412277872e-01 + 4.72460251929427e-01 3.83235896264865e-01 + 4.89254536599454e-01 3.83843952964464e-01 + 5.06163834453059e-01 3.84146352307061e-01 + 5.23189394372787e-01 3.83285841342889e-01 + 5.40310058634680e-01 3.81443701603978e-01 + 5.57486522435475e-01 3.79033596004446e-01 + 5.74715352025665e-01 3.75685474236072e-01 + 5.92000372484674e-01 3.71765261705014e-01 + 6.09337554036771e-01 3.67670925407177e-01 + 6.26712711199081e-01 3.63152537787024e-01 + 6.44112689354547e-01 3.58249400169114e-01 + 6.61537902878510e-01 3.53105856660785e-01 + 6.78976015503225e-01 3.47670000178051e-01 + 6.96388219208155e-01 3.41916005228908e-01 + 7.13758174635815e-01 3.35774011869113e-01 + 7.31072071555730e-01 3.29291743909179e-01 + 7.48347054469357e-01 3.22782481179152e-01 + 7.65635234168385e-01 3.16597107059741e-01 + 7.82817938077837e-01 3.10445909406222e-01 + 7.99822649562144e-01 3.03782942002751e-01 + 8.16599499725996e-01 2.96387728717845e-01 + 8.33162654038272e-01 2.88615543528075e-01 + 8.49499238755804e-01 2.80681153424459e-01 + 8.65575980032653e-01 2.72460131547320e-01 + 8.81365101325771e-01 2.64006588773166e-01 + 8.96830625839868e-01 2.55349206752237e-01 + 9.11860293545010e-01 2.45521741551255e-01 + 9.26493285460369e-01 2.35422284498711e-01 + 9.40627758148684e-01 2.25124409413752e-01 + 9.56355816041677e-01 2.14591442921710e-01 + 9.76537617843118e-01 2.04082237971755e-01 + 9.84561014127750e-01 1.89606914519805e-01 + 9.87643053296840e-01 1.67544521992612e-01 + 9.89781643689051e-01 1.41487907300533e-01 + 9.91693019433194e-01 1.13998602352113e-01 + 9.93236086227859e-01 8.40282639292492e-02 + 9.95181038506289e-01 6.17158184066358e-02 + 9.96476028162972e-01 4.13392188133469e-02 + 9.98222919558243e-01 2.12790182529935e-02 + 1.00000000000000e+00 1.60547379486788e-03 diff --git a/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF04_Coords.txt b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF04_Coords.txt new file mode 100644 index 00000000..7c0a13b7 --- /dev/null +++ b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF04_Coords.txt @@ -0,0 +1,208 @@ + 201 NumCoords ! The number of coordinates in the airfoil shape file (including an extra coordinate for airfoil reference). Set to zero if coordinates not included. +! ......... x-y coordinates are next if NumCoords > 0 ............. +! x-y coordinate of airfoil reference +! x/c y/c + 0.250000 0 +! coordinates of airfoil shape +! interpolation to 200 points +! x/c y/c + 1.00000000000000e+00 -2.27521504445117e-02 + 9.95825558916260e-01 -3.85996552852628e-02 + 9.91908351102147e-01 -5.44969196641126e-02 + 9.88416628115054e-01 -7.07599158572808e-02 + 9.85866922904108e-01 -8.82610141031158e-02 + 9.82725730996461e-01 -1.04331474026742e-01 + 9.75943584414250e-01 -1.16192160119479e-01 + 9.60562898886437e-01 -1.24553806205324e-01 + 9.45502094163868e-01 -1.30081821439202e-01 + 9.29689968161834e-01 -1.34454116305964e-01 + 9.13964300425632e-01 -1.38792987259912e-01 + 8.98614488822684e-01 -1.43791084896220e-01 + 8.83335037065323e-01 -1.48845719057247e-01 + 8.67989583131007e-01 -1.53392395893884e-01 + 8.52512977524852e-01 -1.57285196860484e-01 + 8.36980556973450e-01 -1.60814946557067e-01 + 8.21468173261859e-01 -1.64100703909415e-01 + 8.06005351604761e-01 -1.67267075710542e-01 + 7.90569523846495e-01 -1.70238657955313e-01 + 7.75160420278176e-01 -1.72833393586880e-01 + 7.59765591487754e-01 -1.74956177670212e-01 + 7.44400605416898e-01 -1.76801895913143e-01 + 7.29116033776629e-01 -1.78610693133524e-01 + 7.13947989837457e-01 -1.80610582068115e-01 + 6.98879169529179e-01 -1.82683486229382e-01 + 6.83885725014230e-01 -1.84453890742002e-01 + 6.68948266000129e-01 -1.85692240974458e-01 + 6.54077597403275e-01 -1.86675765092582e-01 + 6.39298560836104e-01 -1.87505908577295e-01 + 6.24631617962163e-01 -1.88281679546669e-01 + 6.10073346044509e-01 -1.89102453976540e-01 + 5.95625793495472e-01 -1.89726467074718e-01 + 5.81293508075112e-01 -1.89890541527727e-01 + 5.67078321487802e-01 -1.89672724652735e-01 + 5.52984605219614e-01 -1.89300253242408e-01 + 5.39018740189456e-01 -1.88942147239663e-01 + 5.25163688284825e-01 -1.88679571252767e-01 + 5.11413609207518e-01 -1.88425702489593e-01 + 4.97799177395975e-01 -1.88101973722528e-01 + 4.84327325660904e-01 -1.87580974813977e-01 + 4.70996488304439e-01 -1.86734079403737e-01 + 4.57807499457728e-01 -1.85719999075378e-01 + 4.44760927152842e-01 -1.84696486770858e-01 + 4.31852022455883e-01 -1.83635353168758e-01 + 4.19090901616490e-01 -1.82470445502636e-01 + 4.06491363898788e-01 -1.81170983464115e-01 + 3.94068316367388e-01 -1.79605967544454e-01 + 3.81813043724431e-01 -1.77780857103527e-01 + 3.69699449630328e-01 -1.75956382315867e-01 + 3.57702913407548e-01 -1.74362578401297e-01 + 3.45820758127239e-01 -1.72975266565004e-01 + 3.34085173594801e-01 -1.71599837205798e-01 + 3.22528762317999e-01 -1.70053358838540e-01 + 3.11158458585437e-01 -1.68229483638464e-01 + 2.99960205902575e-01 -1.66205813724721e-01 + 2.88929664556996e-01 -1.64083038925404e-01 + 2.78065429500551e-01 -1.61919157747390e-01 + 2.67372016639914e-01 -1.59640340608867e-01 + 2.56838483482072e-01 -1.57303663087410e-01 + 2.46452895340118e-01 -1.54979944998565e-01 + 2.36204329661831e-01 -1.52707294515853e-01 + 2.26105799104062e-01 -1.50433273332383e-01 + 2.16178334826531e-01 -1.48092285325409e-01 + 2.06440462240654e-01 -1.45637282290730e-01 + 1.96869285515018e-01 -1.43086175320475e-01 + 1.87473435872977e-01 -1.40444127091679e-01 + 1.78262653731453e-01 -1.37710428849814e-01 + 1.69252630220208e-01 -1.34804420084564e-01 + 1.60413244437104e-01 -1.31813387053438e-01 + 1.51703588066681e-01 -1.28882641840022e-01 + 1.43077619868567e-01 -1.26142317505189e-01 + 1.34558223959049e-01 -1.23515015039303e-01 + 1.26236077097364e-01 -1.20786093116937e-01 + 1.18187874855922e-01 -1.17753964310198e-01 + 1.10394900564033e-01 -1.14389083257162e-01 + 1.02776771116232e-01 -1.10926463752281e-01 + 9.52576323187684e-02 -1.07596450900910e-01 + 8.77890248291223e-02 -1.04462641719461e-01 + 8.04931796353551e-02 -1.01301294317992e-01 + 7.35128190911369e-02 -9.78736275580912e-02 + 6.68963895240495e-02 -9.40003856565595e-02 + 6.05009896751561e-02 -8.99475473560910e-02 + 5.41691079982236e-02 -8.60337352895419e-02 + 4.77847233189376e-02 -8.24016920600191e-02 + 4.16000737650022e-02 -7.87323954691971e-02 + 3.58929498807395e-02 -7.46615383996122e-02 + 3.05718156448606e-02 -7.01640817880520e-02 + 2.55841457444921e-02 -6.54750339821926e-02 + 2.08026533112682e-02 -6.07371500023589e-02 + 1.63439586202605e-02 -5.58344930848473e-02 + 1.26739780200523e-02 -5.06379447657982e-02 + 9.64255085974439e-03 -4.50568616338899e-02 + 6.95205676239145e-03 -3.93718854579150e-02 + 4.20584482318000e-03 -3.38153278580581e-02 + 1.88154483510298e-03 -2.82556740113477e-02 + 1.09259224757715e-03 -2.25793808835637e-02 + 5.57027370894427e-04 -1.68301482885243e-02 + 1.92532044605606e-04 -1.11001611628179e-02 + 7.52083255272135e-06 -5.47188430262417e-03 + 0.00000000000000e+00 0.00000000000000e+00 + 1.17486562914811e-04 5.48679985210707e-03 + 3.45293358213107e-04 1.10987098718478e-02 + 6.76028572561267e-04 1.68193159983466e-02 + 1.10074682910982e-03 2.26297904761801e-02 + 1.60992601121548e-03 2.85087154571350e-02 + 2.67599544106549e-03 3.44493853796572e-02 + 4.39289337028668e-03 4.04593247588465e-02 + 6.27509694854768e-03 4.65396355123101e-02 + 8.18501856800657e-03 5.27292560994769e-02 + 1.03189035753580e-02 5.90079710526583e-02 + 1.27370291299606e-02 6.52938850681379e-02 + 1.55557604269686e-02 7.14974882867604e-02 + 1.89758697009180e-02 7.76144942393735e-02 + 2.27125265955629e-02 8.37568225375172e-02 + 2.64205973892604e-02 9.00529677985623e-02 + 3.01282733583995e-02 9.65285394067050e-02 + 3.39926189539913e-02 1.03078210289796e-01 + 3.81573198488582e-02 1.09576659446866e-01 + 4.27861195062449e-02 1.15924379625249e-01 + 4.78311663375292e-02 1.22194138387785e-01 + 5.30764574325103e-02 1.28517196960692e-01 + 5.83111363244493e-02 1.35033938551462e-01 + 6.35760553124462e-02 1.41734309721268e-01 + 6.90274085645503e-02 1.48474163992816e-01 + 7.48336167040122e-02 1.55069663963807e-01 + 8.11611766171277e-02 1.61401120064374e-01 + 8.79191588167710e-02 1.67593332097610e-01 + 9.48826093561019e-02 1.73826214118695e-01 + 1.01844855099363e-01 1.80284855885651e-01 + 1.08870960569728e-01 1.86945163887416e-01 + 1.16112032555569e-01 1.93604681567356e-01 + 1.23730351466839e-01 2.00035948444507e-01 + 1.31824094660795e-01 2.06181698317671e-01 + 1.40296730825128e-01 2.12179485190627e-01 + 1.48993250461499e-01 2.18163657713048e-01 + 1.57819272344995e-01 2.24246096031123e-01 + 1.66852794875010e-01 2.30358166418523e-01 + 1.76155620082319e-01 2.36368608053698e-01 + 1.85787867463952e-01 2.42168413364266e-01 + 1.95750148009566e-01 2.47820613232954e-01 + 2.06011532032752e-01 2.53317180198825e-01 + 2.16542581694721e-01 2.58641479671493e-01 + 2.27367855996913e-01 2.63825228256786e-01 + 2.38481776223131e-01 2.68855474330982e-01 + 2.49861589948929e-01 2.73698630151439e-01 + 2.61511196031386e-01 2.78418546610769e-01 + 2.73444081521194e-01 2.82942196705218e-01 + 2.85666898746156e-01 2.87119018069479e-01 + 2.98200734062047e-01 2.91001132958173e-01 + 3.11032065305424e-01 2.94621877568295e-01 + 3.24124539258925e-01 2.97872294592512e-01 + 3.37489921714358e-01 3.00767227942365e-01 + 3.51122091139916e-01 3.03395484009736e-01 + 3.64973840498426e-01 3.05782280483364e-01 + 3.79035138325125e-01 3.08249753379266e-01 + 3.93322041497236e-01 3.10433221242496e-01 + 4.07839547608925e-01 3.11538517913751e-01 + 4.22602719706730e-01 3.12017813468019e-01 + 4.37571388858179e-01 3.12308843703191e-01 + 4.52705694129202e-01 3.12333639153740e-01 + 4.68022386434649e-01 3.11853160827979e-01 + 4.83493649847560e-01 3.10957551960417e-01 + 4.99066517917555e-01 3.09764580509872e-01 + 5.14753065556197e-01 3.07600736594501e-01 + 5.30536608928272e-01 3.04749547523736e-01 + 5.46385724990049e-01 3.01659366948820e-01 + 5.62295818718890e-01 2.97977515095747e-01 + 5.78294553201899e-01 2.93910589456047e-01 + 5.94402144736603e-01 2.89716319978192e-01 + 6.10601043028817e-01 2.85246570693586e-01 + 6.26909980423233e-01 2.80596756484263e-01 + 6.43345516347184e-01 2.75862073462143e-01 + 6.59894609560225e-01 2.70990265506853e-01 + 6.76549242992279e-01 2.65977472599385e-01 + 6.93285667658481e-01 2.60762532727095e-01 + 7.10113002149428e-01 2.55379870427853e-01 + 7.27101101620968e-01 2.50077155704390e-01 + 7.44309174064674e-01 2.45048240418275e-01 + 7.61658961677203e-01 2.40058424294836e-01 + 7.79018980351826e-01 2.34727092866611e-01 + 7.96358584077290e-01 2.28942034208237e-01 + 8.13753854561790e-01 2.22958342564097e-01 + 8.31270319341910e-01 2.17014377218330e-01 + 8.48885104644356e-01 2.11048726086036e-01 + 8.66584330124259e-01 2.05031932644156e-01 + 8.84350172928721e-01 1.98925268297828e-01 + 9.02193707353903e-01 1.92773917580206e-01 + 9.20157773678337e-01 1.86723259912781e-01 + 9.38246381637406e-01 1.80792430732304e-01 + 9.56399217082597e-01 1.74918496768106e-01 + 9.76798363881330e-01 1.69533670492790e-01 + 9.84828566855567e-01 1.59247090588959e-01 + 9.87839059292136e-01 1.39199540261784e-01 + 9.89905373069722e-01 1.17616603808733e-01 + 9.91757893422502e-01 9.85412138534034e-02 + 9.93252480473954e-01 7.94410871228046e-02 + 9.94743975611726e-01 6.01627278016894e-02 + 9.96445705560557e-01 4.08626126297221e-02 + 9.98198658774545e-01 2.15548416438615e-02 + 1.00000000000000e+00 2.24462872737125e-03 diff --git a/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF05_Coords.txt b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF05_Coords.txt new file mode 100644 index 00000000..e390be98 --- /dev/null +++ b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF05_Coords.txt @@ -0,0 +1,208 @@ + 201 NumCoords ! The number of coordinates in the airfoil shape file (including an extra coordinate for airfoil reference). Set to zero if coordinates not included. +! ......... x-y coordinates are next if NumCoords > 0 ............. +! x-y coordinate of airfoil reference +! x/c y/c + 0.250000 0 +! coordinates of airfoil shape +! interpolation to 200 points +! x/c y/c + 1.00000000000000e+00 -1.79613835013314e-02 + 9.96961558343373e-01 -3.53902489488287e-02 + 9.92023630619313e-01 -4.91929101534255e-02 + 9.84379446083511e-01 -6.00348210114478e-02 + 9.75468141678190e-01 -7.09859658723328e-02 + 9.66631278884337e-01 -8.10763642717688e-02 + 9.55798039282918e-01 -8.89193213483636e-02 + 9.40573198850503e-01 -9.51466796435252e-02 + 9.25558881802059e-01 -9.98612000663832e-02 + 9.10156047961303e-01 -1.03818167988873e-01 + 8.94845249828711e-01 -1.07053770498790e-01 + 8.79788764043181e-01 -1.10793970812780e-01 + 8.64816289515449e-01 -1.14657288651007e-01 + 8.49854909867423e-01 -1.18332319693786e-01 + 8.34868122131193e-01 -1.21755694040649e-01 + 8.19932031659274e-01 -1.25185347068945e-01 + 8.05100969303777e-01 -1.28769954116135e-01 + 7.90321333537330e-01 -1.32315399189505e-01 + 7.75523132904363e-01 -1.35552178535652e-01 + 7.60741767498039e-01 -1.38522987025004e-01 + 7.46023130239504e-01 -1.41378450540013e-01 + 7.31401419294347e-01 -1.44351973608261e-01 + 7.16841539978852e-01 -1.47259170049408e-01 + 7.02302981796658e-01 -1.49894404232336e-01 + 6.87793305289350e-01 -1.52332219473336e-01 + 6.73332858807799e-01 -1.54446440090132e-01 + 6.58925185976507e-01 -1.56177321792256e-01 + 6.44572195057741e-01 -1.57666344545681e-01 + 6.30298458454963e-01 -1.58910640661020e-01 + 6.16114416580374e-01 -1.59951057500702e-01 + 6.02026953030919e-01 -1.60900948878695e-01 + 5.88050398086629e-01 -1.61711857451049e-01 + 5.74189109055960e-01 -1.62294350346538e-01 + 5.60448390812326e-01 -1.62664500132555e-01 + 5.46836999554392e-01 -1.62937231340188e-01 + 5.33367864981090e-01 -1.63248884154172e-01 + 5.19932409233419e-01 -1.63449902911388e-01 + 5.06477442605548e-01 -1.63417485627504e-01 + 4.93144035884787e-01 -1.63328228686621e-01 + 4.79941368474168e-01 -1.63060331436217e-01 + 4.66871737010151e-01 -1.62569827406711e-01 + 4.53934990999079e-01 -1.62070487200764e-01 + 4.41133168558923e-01 -1.61632173585030e-01 + 4.28463654391992e-01 -1.61187532275481e-01 + 4.15933178526276e-01 -1.60548880877149e-01 + 4.03555052687744e-01 -1.59798188531010e-01 + 3.91342756149186e-01 -1.58846604242981e-01 + 3.79289683322135e-01 -1.57540790079054e-01 + 3.67375264219574e-01 -1.56189884356924e-01 + 3.55580233434555e-01 -1.55081224503574e-01 + 3.43903993529589e-01 -1.54105712386970e-01 + 3.32371689603571e-01 -1.53109720354745e-01 + 3.21008399939002e-01 -1.51964778739524e-01 + 3.09818365007830e-01 -1.50611104402699e-01 + 2.98789403182843e-01 -1.49154888767305e-01 + 2.87915260467706e-01 -1.47707797499490e-01 + 2.77192797094198e-01 -1.46295028972452e-01 + 2.66634642137323e-01 -1.44782680901920e-01 + 2.56243230473741e-01 -1.43092118304113e-01 + 2.46011513861498e-01 -1.41179312266907e-01 + 2.35923227561334e-01 -1.39187527359477e-01 + 2.25978716650481e-01 -1.37235092846332e-01 + 2.16205677937271e-01 -1.35310903535781e-01 + 2.06778722942050e-01 -1.33322871209808e-01 + 1.97516042359716e-01 -1.31227497717662e-01 + 1.88427440008692e-01 -1.28991125900883e-01 + 1.79502980110518e-01 -1.26649399614310e-01 + 1.70733325816940e-01 -1.24213566866553e-01 + 1.62098170428490e-01 -1.21762260683871e-01 + 1.53596861253099e-01 -1.19338023194216e-01 + 1.45242024458811e-01 -1.16964714586022e-01 + 1.37059827832412e-01 -1.14553161865558e-01 + 1.29058111671005e-01 -1.12011104818429e-01 + 1.21217330976586e-01 -1.09333580954571e-01 + 1.13490793020045e-01 -1.06582482287198e-01 + 1.05872478787586e-01 -1.03835726838741e-01 + 9.84312049808396e-02 -1.01090373016527e-01 + 9.12178971287871e-02 -9.82756005290104e-02 + 8.42187577306301e-02 -9.53136441369315e-02 + 7.73955759457572e-02 -9.22209615041234e-02 + 7.07054294736601e-02 -8.89789985808886e-02 + 6.41548755011769e-02 -8.56689842703127e-02 + 5.77914057011829e-02 -8.22370633159429e-02 + 5.16081911372133e-02 -7.87250303745277e-02 + 4.56080027670407e-02 -7.51373524837015e-02 + 3.97932691904809e-02 -7.13640514386860e-02 + 3.41289275285710e-02 -6.73803370811387e-02 + 2.88546712589916e-02 -6.31532691299288e-02 + 2.39831240698773e-02 -5.86665495096452e-02 + 1.94527821619992e-02 -5.39591200958821e-02 + 1.53491720497801e-02 -4.90523270599134e-02 + 1.16943357256612e-02 -4.38406284119954e-02 + 8.65365253109135e-03 -3.84459455205228e-02 + 5.92370160379059e-03 -3.30114750896427e-02 + 3.46212829965803e-03 -2.75812253497000e-02 + 1.58454458640205e-03 -2.21027074392882e-02 + 7.35715040582169e-04 -1.65321192119310e-02 + 2.97907005116705e-04 -1.09279875504530e-02 + 5.30676565098627e-05 -5.39101103138609e-03 + 0.00000000000000e+00 0.00000000000000e+00 + 9.16249484271071e-05 5.39472463076042e-03 + 2.97114014867658e-04 1.09125341734703e-02 + 6.07765485359921e-04 1.65347368419011e-02 + 1.01319685944283e-03 2.22398721797630e-02 + 1.57860720361388e-03 2.80048570638302e-02 + 2.85770205402702e-03 3.38268128923488e-02 + 4.60485640943450e-03 3.97136792782237e-02 + 6.36963363495096e-03 4.56791798263678e-02 + 8.27460103313730e-03 5.17469828248211e-02 + 1.04559502964479e-02 5.78621045555090e-02 + 1.30787206403767e-02 6.39307928915866e-02 + 1.62476019915294e-02 6.99136016610049e-02 + 1.97064472281925e-02 7.58656576746356e-02 + 2.32055551437451e-02 8.18956044570781e-02 + 2.67780264071069e-02 8.80520763606948e-02 + 3.05536180174887e-02 9.43034458705317e-02 + 3.46895645314508e-02 1.00552628487572e-01 + 3.91594998227274e-02 1.06753941085293e-01 + 4.38513894815309e-02 1.12886816803394e-01 + 4.86469345513260e-02 1.19031991526595e-01 + 5.35662818491533e-02 1.25246183971636e-01 + 5.86765310389434e-02 1.31515765400035e-01 + 6.41158119407387e-02 1.37430772030919e-01 + 6.98941360883445e-02 1.43254800103538e-01 + 7.59170877123488e-02 1.49053754727573e-01 + 8.21227682881698e-02 1.54888203928039e-01 + 8.85359454387846e-02 1.60747975413262e-01 + 9.51513059583106e-02 1.66598125672197e-01 + 1.01977161405040e-01 1.72421724747484e-01 + 1.09029076244286e-01 1.78602175887026e-01 + 1.16324626112349e-01 1.84952513492490e-01 + 1.23886862179539e-01 1.91028384041450e-01 + 1.31793661272858e-01 1.96904454248269e-01 + 1.40137015144785e-01 2.02603209487098e-01 + 1.48722392856665e-01 2.08131821762515e-01 + 1.57498055037009e-01 2.13566417662387e-01 + 1.66499738307440e-01 2.18924804988545e-01 + 1.75746807567001e-01 2.24209223798866e-01 + 1.85282812844636e-01 2.29419693016131e-01 + 1.95126003842738e-01 2.34424150993428e-01 + 2.05278382458868e-01 2.39064246909332e-01 + 2.15728458898676e-01 2.43395275762812e-01 + 2.26448399402852e-01 2.47609942869563e-01 + 2.37390616140716e-01 2.51915193162418e-01 + 2.48555223136142e-01 2.56240468008173e-01 + 2.59983581489374e-01 2.60218095713622e-01 + 2.71719323509248e-01 2.63616598352372e-01 + 2.83748575426622e-01 2.66632889055311e-01 + 2.96041798832288e-01 2.69453390481384e-01 + 3.08575060192042e-01 2.72409404922417e-01 + 3.21340186072523e-01 2.75012415222477e-01 + 3.34353685398402e-01 2.76492953153595e-01 + 3.47617985877095e-01 2.77530644029356e-01 + 3.61086047806733e-01 2.78478291157024e-01 + 3.74735967198890e-01 2.79421812258223e-01 + 3.88584839416611e-01 2.80075134954841e-01 + 4.02610569745306e-01 2.80158921396025e-01 + 4.16769966222890e-01 2.79426952940989e-01 + 4.31000767416746e-01 2.77780180205803e-01 + 4.45367430099069e-01 2.75892299873811e-01 + 4.59886426162136e-01 2.73764712702610e-01 + 4.74522704612306e-01 2.71235104254327e-01 + 4.89216780464507e-01 2.68272718312492e-01 + 5.03966776199603e-01 2.64447118696879e-01 + 5.18806020666685e-01 2.60200052632834e-01 + 5.33757172542646e-01 2.56033656152525e-01 + 5.48800417061940e-01 2.51670207782890e-01 + 5.63928433117745e-01 2.47052734150705e-01 + 5.79139293361131e-01 2.42196437539003e-01 + 5.94438582209324e-01 2.37156310638374e-01 + 6.09857099330908e-01 2.32081069158076e-01 + 6.25400870520805e-01 2.26991368536271e-01 + 6.41058606965589e-01 2.21852557624183e-01 + 6.56827119257239e-01 2.16670545580237e-01 + 6.72692401163725e-01 2.11435826592181e-01 + 6.88658261530256e-01 2.06153724323127e-01 + 7.04768588597026e-01 2.00939949019601e-01 + 7.21023238876672e-01 1.95698405223399e-01 + 7.37357768356274e-01 1.90224737500501e-01 + 7.53717588941763e-01 1.84447648187462e-01 + 7.70112763502082e-01 1.78479680783297e-01 + 7.86578143910845e-01 1.72394810225689e-01 + 8.03184229023836e-01 1.66738239461448e-01 + 8.19942143394421e-01 1.61342896059017e-01 + 8.36804795974800e-01 1.55942560425342e-01 + 8.53725343344330e-01 1.50402193026770e-01 + 8.70748946763591e-01 1.44842377351049e-01 + 8.87946529574867e-01 1.39474077514211e-01 + 9.05306293149628e-01 1.34235143291426e-01 + 9.22545067587843e-01 1.28920314434417e-01 + 9.40600734347715e-01 1.23754776734464e-01 + 9.53048939484955e-01 1.16864623799960e-01 + 9.63077773676104e-01 1.06395431570647e-01 + 9.72474093255454e-01 9.57868792253965e-02 + 9.81179655916868e-01 8.60931773916215e-02 + 9.88539472463695e-01 7.50338503152747e-02 + 9.93965264664499e-01 5.85418242094117e-02 + 9.96759513501900e-01 4.07113376276323e-02 + 9.98822819206952e-01 2.22334005961241e-02 + 1.00000000000000e+00 3.03882619127306e-03 diff --git a/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF06_Coords.txt b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF06_Coords.txt new file mode 100644 index 00000000..9931444e --- /dev/null +++ b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF06_Coords.txt @@ -0,0 +1,208 @@ + 201 NumCoords ! The number of coordinates in the airfoil shape file (including an extra coordinate for airfoil reference). Set to zero if coordinates not included. +! ......... x-y coordinates are next if NumCoords > 0 ............. +! x-y coordinate of airfoil reference +! x/c y/c + 0.250000 0 +! coordinates of airfoil shape +! interpolation to 200 points +! x/c y/c + 1.00000000000000e+00 -1.13904183263968e-02 + 9.97616112402170e-01 -3.02925242439361e-02 + 9.92090053782966e-01 -4.09226344496437e-02 + 9.78779505574386e-01 -4.46317953566502e-02 + 9.62630848882990e-01 -4.78657079982365e-02 + 9.48002016685502e-01 -5.14602797602320e-02 + 9.33316247673508e-01 -5.51593031128816e-02 + 9.18496232612161e-01 -5.92254605712216e-02 + 9.03703201804367e-01 -6.31663589833213e-02 + 8.88853928485311e-01 -6.68255900117923e-02 + 8.74049386501296e-01 -7.05161511584427e-02 + 8.59334016743915e-01 -7.43874436875609e-02 + 8.44688974778042e-01 -7.83626507822871e-02 + 8.30107202160351e-01 -8.23961121367229e-02 + 8.15594575089335e-01 -8.65047449737667e-02 + 8.01218061118175e-01 -9.08578559827087e-02 + 7.87017154459310e-01 -9.56014747506557e-02 + 7.72867465331189e-01 -1.00310586221221e-01 + 7.58658127516040e-01 -1.04602689055293e-01 + 7.44454533959962e-01 -1.08689082390743e-01 + 7.30359770774575e-01 -1.12881924651599e-01 + 7.16430384005105e-01 -1.17399987158617e-01 + 7.02548411333571e-01 -1.21769749655608e-01 + 6.88587907939929e-01 -1.25508162707915e-01 + 6.74579309967017e-01 -1.28831256546796e-01 + 6.60588643228054e-01 -1.31814109374650e-01 + 6.46644883677572e-01 -1.34518684272535e-01 + 6.32738136446085e-01 -1.36970560657454e-01 + 6.18888539380060e-01 -1.39099781158483e-01 + 6.05094599842353e-01 -1.40925423892468e-01 + 5.91370497948358e-01 -1.42548078837611e-01 + 5.77742681423787e-01 -1.44039268742623e-01 + 5.64210789942644e-01 -1.45418710112677e-01 + 5.50776369602557e-01 -1.46660362777981e-01 + 5.37444968071300e-01 -1.47785036756530e-01 + 5.24218800582908e-01 -1.48883649416298e-01 + 5.11096793180140e-01 -1.49725747746255e-01 + 4.98077600261809e-01 -1.50190862529385e-01 + 4.85165286248710e-01 -1.50548451423256e-01 + 4.72371838173648e-01 -1.50709025323563e-01 + 4.59704855658886e-01 -1.50660182339889e-01 + 4.47162353937939e-01 -1.50610036032676e-01 + 4.34748236821129e-01 -1.50574316591260e-01 + 4.22462962227877e-01 -1.50466331413989e-01 + 4.10307413565604e-01 -1.50120854962051e-01 + 3.98293549815832e-01 -1.49646376138536e-01 + 3.86431947049557e-01 -1.48985011501092e-01 + 3.74719035040848e-01 -1.47937284203969e-01 + 3.63143253860895e-01 -1.46805960127425e-01 + 3.51694487399415e-01 -1.45836094033469e-01 + 3.40375820106151e-01 -1.44917425523182e-01 + 3.29200242436979e-01 -1.43946965381053e-01 + 3.18179373560524e-01 -1.42835461865229e-01 + 3.07312147043483e-01 -1.41563685586535e-01 + 2.96589198655950e-01 -1.40239218363699e-01 + 2.86000302805324e-01 -1.38971039533067e-01 + 2.75538569884689e-01 -1.37776349074027e-01 + 2.65231088919120e-01 -1.36509074431539e-01 + 2.55105124935306e-01 -1.35017464348563e-01 + 2.45163330716385e-01 -1.33182240433968e-01 + 2.35380065561362e-01 -1.31184297306223e-01 + 2.25731797335499e-01 -1.29236565554543e-01 + 2.16212918345480e-01 -1.27375368900912e-01 + 2.06869737828596e-01 -1.25493378403087e-01 + 1.97692792848475e-01 -1.23508013308052e-01 + 1.88692178275185e-01 -1.21356126184016e-01 + 1.79852140135191e-01 -1.19094041300472e-01 + 1.71155287788632e-01 -1.16810198318667e-01 + 1.62583572203815e-01 -1.14572084308225e-01 + 1.54148627233356e-01 -1.12333771605582e-01 + 1.45882282736195e-01 -1.10017484528559e-01 + 1.37813705509852e-01 -1.07521934723333e-01 + 1.29924389454779e-01 -1.04868618458173e-01 + 1.22160459722846e-01 -1.02232244909791e-01 + 1.14462997638161e-01 -9.97769981877239e-02 + 1.06850950889400e-01 -9.74418050455991e-02 + 9.94456540823707e-02 -9.49708378396853e-02 + 9.23374027952569e-02 -9.21230511653797e-02 + 8.54657300321368e-02 -8.89658600035733e-02 + 7.87212757634630e-02 -8.58036899472230e-02 + 7.20187471524862e-02 -8.28315669774048e-02 + 6.54246409525636e-02 -7.99018939763046e-02 + 5.90704249471530e-02 -7.68099610722217e-02 + 5.30035679474469e-02 -7.34323254403719e-02 + 4.71239339609886e-02 -6.99340905790686e-02 + 4.13031360007540e-02 -6.65329912958667e-02 + 3.55234699482794e-02 -6.32184019501613e-02 + 3.01619829327107e-02 -5.96139288290971e-02 + 2.53031775785438e-02 -5.54778043544704e-02 + 2.08048174587776e-02 -5.10511978893060e-02 + 1.65388584263945e-02 -4.65627010925328e-02 + 1.26090766129194e-02 -4.18918267420981e-02 + 9.43378362085923e-03 -3.69337921085883e-02 + 6.78961770854852e-03 -3.16963231219606e-02 + 4.34237637716249e-03 -2.64747404683854e-02 + 1.85598728281019e-03 -2.13060647449452e-02 + 8.70334950751159e-04 -1.60204557614650e-02 + 3.78614157542381e-04 -1.06258278582999e-02 + 8.34360366869797e-05 -5.24793360453415e-03 + 0.00000000000000e+00 0.00000000000000e+00 + 7.67236867486678e-05 5.23517737179421e-03 + 2.69353450923468e-04 1.05899507024689e-02 + 5.68432823980679e-04 1.60424452959359e-02 + 9.62751245980932e-04 2.15677746016270e-02 + 1.56056154959061e-03 2.71408610938964e-02 + 2.93760353810514e-03 3.27643997804523e-02 + 4.68388731306286e-03 3.84466954603457e-02 + 6.39829873698727e-03 4.42192833035362e-02 + 8.30088094239591e-03 5.00830587126182e-02 + 1.04968991067837e-02 5.59331418219662e-02 + 1.31905356506929e-02 6.16590402853706e-02 + 1.64944927228985e-02 6.72926557763616e-02 + 1.99584847680105e-02 7.29780548965268e-02 + 2.33603947254173e-02 7.88193742129969e-02 + 2.68842534255446e-02 8.47441200649158e-02 + 3.06808954672960e-02 9.06322348821772e-02 + 3.49084527320684e-02 9.63920127695594e-02 + 3.94874921561364e-02 1.02093915910307e-01 + 4.41979239135200e-02 1.07851341351126e-01 + 4.88991643814045e-02 1.13771751479133e-01 + 5.37085410028852e-02 1.19785527662613e-01 + 5.87799300044820e-02 1.25738707322743e-01 + 6.42723709032797e-02 1.31439519919589e-01 + 7.01563729259333e-02 1.37001677458821e-01 + 7.62522111785621e-02 1.42563767678454e-01 + 8.24142000324228e-02 1.48247461470601e-01 + 8.87141756594531e-02 1.54005995560218e-01 + 9.52252089668619e-02 1.59738341000206e-01 + 1.02012827165119e-01 1.65362107222581e-01 + 1.09071839770933e-01 1.71005609066199e-01 + 1.16382532480666e-01 1.76625410480436e-01 + 1.23929157304783e-01 1.82119310647882e-01 + 1.31734456855347e-01 1.87537907766897e-01 + 1.39830632988419e-01 1.92818237288258e-01 + 1.48208290383940e-01 1.97881178099860e-01 + 1.56890640982985e-01 2.02754105050709e-01 + 1.65833248340983e-01 2.07492675263682e-01 + 1.74977872658223e-01 2.12167028768671e-01 + 1.84339215056554e-01 2.16828518735710e-01 + 1.93969002461360e-01 2.21262214470146e-01 + 2.03927738995053e-01 2.25232399682506e-01 + 2.14233998923319e-01 2.28819156679255e-01 + 2.24768775871601e-01 2.32298339432912e-01 + 2.35414724132119e-01 2.35983917716678e-01 + 2.46214765126001e-01 2.39788864290029e-01 + 2.57273968847626e-01 2.43131931500378e-01 + 2.68683262153020e-01 2.45701077047944e-01 + 2.80394161446840e-01 2.47884449864113e-01 + 2.92298014116652e-01 2.49928845873406e-01 + 3.04358015522582e-01 2.52310200009780e-01 + 3.16612004841116e-01 2.54366837382113e-01 + 3.29084707645504e-01 2.54944026733475e-01 + 3.41791574758934e-01 2.55013657780952e-01 + 3.54686633087091e-01 2.55077224740846e-01 + 3.67732287456134e-01 2.55080989890258e-01 + 3.80947927549799e-01 2.54809270763009e-01 + 3.94277125966556e-01 2.54299155434133e-01 + 4.07679990408069e-01 2.52964484309584e-01 + 4.21176069905831e-01 2.50460618119005e-01 + 4.34780235148961e-01 2.47779904156950e-01 + 4.48508915785030e-01 2.45032787159418e-01 + 4.62324554197701e-01 2.41951247240081e-01 + 4.76168679634616e-01 2.38443526187009e-01 + 4.90026518395832e-01 2.34310030235241e-01 + 5.03986607097025e-01 2.29965169629546e-01 + 5.18124607276385e-01 2.25794521855877e-01 + 5.32402710892978e-01 2.21622952392128e-01 + 5.46773333755108e-01 2.17288635068298e-01 + 5.61209497775237e-01 2.12697198172799e-01 + 5.75739948251087e-01 2.07963361115272e-01 + 5.90401181915651e-01 2.03229629742975e-01 + 6.05186266686445e-01 1.98479319175866e-01 + 6.20086166342671e-01 1.93692356863453e-01 + 6.35097907187523e-01 1.88871403344983e-01 + 6.50216806205491e-01 1.84017547463539e-01 + 6.65438113197408e-01 1.79123980133843e-01 + 6.80773250934036e-01 1.74228906733020e-01 + 6.96172960729631e-01 1.69180559493466e-01 + 7.11585661998256e-01 1.63830547989403e-01 + 7.27034942498605e-01 1.58268579741071e-01 + 7.42558721683669e-01 1.52649157462292e-01 + 7.58144383438193e-01 1.46939483520203e-01 + 7.73847783484881e-01 1.41394650866481e-01 + 7.89701647082685e-01 1.36067884587493e-01 + 8.05635711733308e-01 1.30738018396962e-01 + 8.21581445293506e-01 1.25220232868624e-01 + 8.37586124515025e-01 1.19666988037264e-01 + 8.53726898147738e-01 1.14318888381174e-01 + 8.69963585585765e-01 1.09065119635605e-01 + 8.86190226070913e-01 1.03619764994052e-01 + 9.02483979686875e-01 9.80682052774082e-02 + 9.18558853276680e-01 9.26538040770285e-02 + 9.34548045768020e-01 8.73262649268327e-02 + 9.50649300724702e-01 8.23994229326946e-02 + 9.66427399966504e-01 7.70749674918775e-02 + 9.80999886673880e-01 6.90076199367232e-02 + 9.92612066213372e-01 5.56165891750792e-02 + 9.96940327203726e-01 4.00048120288691e-02 + 9.99182455606956e-01 2.29517217456512e-02 + 1.00000000000000e+00 4.20817591936930e-03 diff --git a/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF07_Coords.txt b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF07_Coords.txt new file mode 100644 index 00000000..ce777e0d --- /dev/null +++ b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF07_Coords.txt @@ -0,0 +1,208 @@ + 201 NumCoords ! The number of coordinates in the airfoil shape file (including an extra coordinate for airfoil reference). Set to zero if coordinates not included. +! ......... x-y coordinates are next if NumCoords > 0 ............. +! x-y coordinate of airfoil reference +! x/c y/c + 0.250000 0 +! coordinates of airfoil shape +! interpolation to 200 points +! x/c y/c + 1.00000000000000e+00 -7.22169847721207e-03 + 9.93657635607014e-01 -9.80951552444892e-03 + 9.85015925953616e-01 -1.30850106016452e-02 + 9.68838039545111e-01 -1.84611077131393e-02 + 9.50612974422184e-01 -2.33823451641766e-02 + 9.34054843802496e-01 -2.68598144161353e-02 + 9.17904876813281e-01 -2.92032016919475e-02 + 9.02410145568755e-01 -3.25195649501926e-02 + 8.86984531818462e-01 -3.63341125283542e-02 + 8.71653146034245e-01 -4.02779399999799e-02 + 8.56421678685942e-01 -4.44297430955853e-02 + 8.41297341579872e-01 -4.88277542480629e-02 + 8.26299922405764e-01 -5.34725994663518e-02 + 8.11418218122957e-01 -5.83063399795375e-02 + 7.96668059771363e-01 -6.33518858746505e-02 + 7.82093073102221e-01 -6.86691608646314e-02 + 7.67715947269790e-01 -7.43397495082482e-02 + 7.53432129505621e-01 -8.00400824090274e-02 + 7.39140921507287e-01 -8.54783114096485e-02 + 7.24887781938029e-01 -9.07927090242104e-02 + 7.10763647733484e-01 -9.62089130617438e-02 + 6.96813846978418e-01 -1.01849003923843e-01 + 6.82926720247006e-01 -1.07345616986875e-01 + 6.68987494011958e-01 -1.12341932591132e-01 + 6.55015055372256e-01 -1.16974857778111e-01 + 6.41069653036586e-01 -1.21324695308618e-01 + 6.27178381576740e-01 -1.25441039708115e-01 + 6.13325927341839e-01 -1.29300851927610e-01 + 5.99526121249635e-01 -1.32836295356277e-01 + 5.85782516774879e-01 -1.36082768510397e-01 + 5.72099418530029e-01 -1.39062285229702e-01 + 5.58500671454668e-01 -1.41826434136283e-01 + 5.44989585070756e-01 -1.44410477552523e-01 + 5.31572041625452e-01 -1.46801987807261e-01 + 5.18249443006677e-01 -1.48965339749430e-01 + 5.05024114284701e-01 -1.51306014609625e-01 + 4.91903544204855e-01 -1.53396356865900e-01 + 4.78886537168064e-01 -1.55029927452596e-01 + 4.65973152938946e-01 -1.56361009079535e-01 + 4.53179119201583e-01 -1.57373248363793e-01 + 4.40511641089995e-01 -1.58032071375895e-01 + 4.27973254627328e-01 -1.58511320266496e-01 + 4.15569568070292e-01 -1.58830392050982e-01 + 4.03305571015855e-01 -1.58908632350926e-01 + 3.91181433267754e-01 -1.58751137788738e-01 + 3.79208355061609e-01 -1.58402513518675e-01 + 3.67395164279636e-01 -1.57823599361342e-01 + 3.55740722338427e-01 -1.56880132251604e-01 + 3.44238533276691e-01 -1.55825370105009e-01 + 3.32890410142460e-01 -1.54776742866931e-01 + 3.21695626476537e-01 -1.53702620246411e-01 + 3.10660511859208e-01 -1.52547932345675e-01 + 2.99792418198384e-01 -1.51236406478805e-01 + 2.89088689354766e-01 -1.49773471325457e-01 + 2.78543651775726e-01 -1.48236644042898e-01 + 2.68149273917489e-01 -1.46704827592144e-01 + 2.57896406226205e-01 -1.45208435280521e-01 + 2.47810593764685e-01 -1.43640086484094e-01 + 2.37924398764870e-01 -1.41871396589496e-01 + 2.28243375505465e-01 -1.39800943847393e-01 + 2.18746002754731e-01 -1.37561331679565e-01 + 2.09407739643021e-01 -1.35323082679671e-01 + 2.00204632082914e-01 -1.33142628436607e-01 + 1.91097767708039e-01 -1.30937919464830e-01 + 1.82170786872752e-01 -1.28640807136328e-01 + 1.73438864168049e-01 -1.26185420973317e-01 + 1.64887367765774e-01 -1.23622391399294e-01 + 1.56497023195920e-01 -1.21049752796620e-01 + 1.48258982483410e-01 -1.18508626502639e-01 + 1.40184001337527e-01 -1.15939910025142e-01 + 1.32310114080237e-01 -1.13239907331215e-01 + 1.24637510518848e-01 -1.10361154607051e-01 + 1.17138359086711e-01 -1.07372231954189e-01 + 1.09808401127193e-01 -1.04399442414758e-01 + 1.02594618944679e-01 -1.01600341650075e-01 + 9.54864171319728e-02 -9.89295946584694e-02 + 8.85996519559139e-02 -9.61035248577797e-02 + 8.20051916775647e-02 -9.28926032526868e-02 + 7.56369542864789e-02 -8.94141742247751e-02 + 6.94224285943848e-02 -8.59586167133803e-02 + 6.33063696107793e-02 -8.27169512241728e-02 + 5.73252083536456e-02 -7.95397742824449e-02 + 5.15865051316583e-02 -7.61848830062020e-02 + 4.61300367417238e-02 -7.25118010504582e-02 + 4.08738115912319e-02 -6.87276051345213e-02 + 3.57389328883182e-02 -6.50758836466640e-02 + 3.07040311089050e-02 -6.15616444241208e-02 + 2.60327010981162e-02 -5.78249541857669e-02 + 2.18044848917305e-02 -5.36151169153552e-02 + 1.79125721708463e-02 -4.91694235722464e-02 + 1.42640650272980e-02 -4.47148049333326e-02 + 1.09301665102860e-02 -4.01661895085117e-02 + 8.21488787888461e-03 -3.53822053138899e-02 + 5.97345205176603e-03 -3.03209729737249e-02 + 3.91406699176672e-03 -2.52857837799812e-02 + 1.81775566819190e-03 -2.03309654023002e-02 + 9.12160954949108e-04 -1.52977122324043e-02 + 4.02582765125064e-04 -1.01721928519313e-02 + 8.81962189848521e-05 -5.04398886153351e-03 + 0.00000000000000e+00 0.00000000000000e+00 + 7.88481242318804e-05 4.71135299425895e-03 + 2.80754052876520e-04 9.46261288508707e-03 + 6.13006828585368e-04 1.43031715472917e-02 + 1.05300322116593e-03 1.92164339057439e-02 + 1.65902417833529e-03 2.41858280981452e-02 + 2.88604628288041e-03 2.92144066457047e-02 + 4.45666746110958e-03 3.43052576770996e-02 + 6.03753907265340e-03 3.94795983867471e-02 + 7.82960449484624e-03 4.47233966620429e-02 + 9.91655407404961e-03 4.99442035624549e-02 + 1.24284772687387e-02 5.50687705625851e-02 + 1.54763292167825e-02 6.01250554953811e-02 + 1.86843960997679e-02 6.52596352562490e-02 + 2.18962093706069e-02 7.05324271196803e-02 + 2.52784929759404e-02 7.58378592538172e-02 + 2.89300636094216e-02 8.10694276026404e-02 + 3.29484021469950e-02 8.61824529289475e-02 + 3.72852782429899e-02 9.12501336825606e-02 + 4.17870700061248e-02 9.63840447729288e-02 + 4.63496453037568e-02 1.01661284055219e-01 + 5.10435239639925e-02 1.07009882208275e-01 + 5.59875070986280e-02 1.12277397844824e-01 + 6.13148588789216e-02 1.17455631946297e-01 + 6.70010356595760e-02 1.22519800002061e-01 + 7.29051769183183e-02 1.27568059236526e-01 + 7.89112995425554e-02 1.32686684152645e-01 + 8.50741136975359e-02 1.37843119031058e-01 + 9.14578688138890e-02 1.42951013415473e-01 + 9.81151304128743e-02 1.47950651124437e-01 + 1.05022936124011e-01 1.52865251715801e-01 + 1.12182877397443e-01 1.57757291795771e-01 + 1.19585877721620e-01 1.62614046073641e-01 + 1.27214720177563e-01 1.67446356419965e-01 + 1.35051758382265e-01 1.72165225608851e-01 + 1.43176044526092e-01 1.76678814786360e-01 + 1.51634312233503e-01 1.80984672889066e-01 + 1.60356678124586e-01 1.85147263518180e-01 + 1.69269127559869e-01 1.89234816532284e-01 + 1.78381320346887e-01 1.93269420198442e-01 + 1.87736592934877e-01 1.97097647600736e-01 + 1.97403400646351e-01 2.00521431354757e-01 + 2.07414560220724e-01 2.03579949812533e-01 + 2.17637947930063e-01 2.06524316560926e-01 + 2.27957250958957e-01 2.09606621172829e-01 + 2.38424311306026e-01 2.12738917135585e-01 + 2.49140241428875e-01 2.15458447992728e-01 + 2.60193207505178e-01 2.17511148705191e-01 + 2.71533533873424e-01 2.19224005878087e-01 + 2.83047744346193e-01 2.20787015818953e-01 + 2.94701890510800e-01 2.22583472274857e-01 + 3.06540852849821e-01 2.24096763539104e-01 + 3.18587112400968e-01 2.24415002618965e-01 + 3.30855654708830e-01 2.24301491408268e-01 + 3.43310579183658e-01 2.24139847149895e-01 + 3.55916656194316e-01 2.23898337931694e-01 + 3.68688998774519e-01 2.23408427293927e-01 + 3.81572695782548e-01 2.22730323737716e-01 + 3.94527023625166e-01 2.21420378888789e-01 + 4.07577420363382e-01 2.19229578580146e-01 + 4.20747484227582e-01 2.16905927479625e-01 + 4.34048855640024e-01 2.14517519518509e-01 + 4.47450165980170e-01 2.11864556981160e-01 + 4.60905424804169e-01 2.08876051783214e-01 + 4.74402418451617e-01 2.05501088301643e-01 + 4.88022240093813e-01 2.01966908762110e-01 + 5.01834194639075e-01 1.98470477662966e-01 + 5.15805558738129e-01 1.94947715634616e-01 + 5.29888183465374e-01 1.91277769157688e-01 + 5.44052932281682e-01 1.87389757043223e-01 + 5.58325058597065e-01 1.83339503703845e-01 + 5.72736421684721e-01 1.79233707897876e-01 + 5.87278008452787e-01 1.75063217405684e-01 + 6.01942226550589e-01 1.70800025984236e-01 + 6.16726346705862e-01 1.66455074142313e-01 + 6.31625058034417e-01 1.61970282233741e-01 + 6.46632291278635e-01 1.57504594571016e-01 + 6.61751041325077e-01 1.53059152834824e-01 + 6.76936236795835e-01 1.48499192638019e-01 + 6.92147476339639e-01 1.43724258513413e-01 + 7.07422281167433e-01 1.38823871106520e-01 + 7.22793007484622e-01 1.33869944353296e-01 + 7.38235455101973e-01 1.28814615957645e-01 + 7.53788409699974e-01 1.23522467900944e-01 + 7.69480657356214e-01 1.18283395144514e-01 + 7.85257633409310e-01 1.13044577909845e-01 + 8.01060519005720e-01 1.07644700685774e-01 + 8.16924009082326e-01 1.02213067786408e-01 + 8.32899942925333e-01 9.69408719881597e-02 + 8.48952317457811e-01 9.17358463767536e-02 + 8.65002071649512e-01 8.63711864178634e-02 + 8.80969831955332e-01 8.09281767032574e-02 + 8.97584200496906e-01 7.56224024173498e-02 + 9.14568727916341e-01 7.04186437860226e-02 + 9.31904847981603e-01 6.55248665698794e-02 + 9.49305251019172e-01 6.03216786607366e-02 + 9.66164153664091e-01 4.90247665870267e-02 + 9.80884725394935e-01 3.29696041722759e-02 + 9.88910360671404e-01 2.19933114134784e-02 + 9.94960172555627e-01 1.27529106155588e-02 + 1.00000000000000e+00 4.45165609285943e-03 diff --git a/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF08_Coords.txt b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF08_Coords.txt new file mode 100644 index 00000000..478fc66c --- /dev/null +++ b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF08_Coords.txt @@ -0,0 +1,208 @@ + 201 NumCoords ! The number of coordinates in the airfoil shape file (including an extra coordinate for airfoil reference). Set to zero if coordinates not included. +! ......... x-y coordinates are next if NumCoords > 0 ............. +! x-y coordinate of airfoil reference +! x/c y/c + 0.250000 0 +! coordinates of airfoil shape +! interpolation to 200 points +! x/c y/c + 1.00000000000000e+00 -5.11794789304784e-03 + 9.87005763971439e-01 -5.16840068225131e-03 + 9.73038425383534e-01 -5.32849535777342e-03 + 9.56081318146453e-01 -5.65516774424684e-03 + 9.38258725113225e-01 -6.13509187042994e-03 + 9.21098802615238e-01 -7.37719929228484e-03 + 9.04171761208617e-01 -9.67764145296581e-03 + 8.87610187611954e-01 -1.28830910336964e-02 + 8.71194318647985e-01 -1.68426370240972e-02 + 8.54930444958429e-01 -2.12840484397517e-02 + 8.38825194115695e-01 -2.61486444777100e-02 + 8.22890453894495e-01 -3.14203814417820e-02 + 8.07149028562320e-01 -3.70963167232995e-02 + 7.91559160728296e-01 -4.30129343317612e-02 + 7.76134809703913e-01 -4.91784530431020e-02 + 7.60882930217529e-01 -5.55441031998046e-02 + 7.45808391148759e-01 -6.21129397508765e-02 + 7.30872703797860e-01 -6.87753213244312e-02 + 7.16019391262118e-01 -7.53975930760553e-02 + 7.01249601839577e-01 -8.19653842497797e-02 + 6.86602027371248e-01 -8.85381279067066e-02 + 6.72088450727254e-01 -9.51198902776138e-02 + 6.57658826413606e-01 -1.01580704997215e-01 + 6.43273510875851e-01 -1.07825082904111e-01 + 6.28922441703606e-01 -1.13838136909654e-01 + 6.14629543830024e-01 -1.19633865914327e-01 + 6.00402302207097e-01 -1.25204051915514e-01 + 5.86224990574980e-01 -1.30504150242841e-01 + 5.72102688198421e-01 -1.35489694904769e-01 + 5.58056462396552e-01 -1.40219795793820e-01 + 5.44068657963509e-01 -1.44621519921740e-01 + 5.30149292300862e-01 -1.48688195730507e-01 + 5.16309904342871e-01 -1.52448246865224e-01 + 5.02564054060932e-01 -1.55921626814940e-01 + 4.88906214250242e-01 -1.59037421835638e-01 + 4.75341042823127e-01 -1.62423955617231e-01 + 4.61888620093194e-01 -1.65573917902269e-01 + 4.48549276031540e-01 -1.68227765214179e-01 + 4.35323450667154e-01 -1.70397650719714e-01 + 4.22231621477117e-01 -1.72138327387660e-01 + 4.09276701428819e-01 -1.73387571753102e-01 + 3.96470584896236e-01 -1.74281084442316e-01 + 3.83820866691607e-01 -1.74849339228191e-01 + 3.71337084681443e-01 -1.75019751577656e-01 + 3.59023523674681e-01 -1.74968047652900e-01 + 3.46890000105156e-01 -1.74665880146742e-01 + 3.34945069696063e-01 -1.74085229376070e-01 + 3.23189763794252e-01 -1.73173272026349e-01 + 3.11618801432831e-01 -1.72128336356160e-01 + 3.00245771337945e-01 -1.70930259894987e-01 + 2.89061607633421e-01 -1.69632705367369e-01 + 2.78070348777523e-01 -1.68223429598176e-01 + 2.67282084006707e-01 -1.66631651581257e-01 + 2.56695506216341e-01 -1.64880753133419e-01 + 2.46309210866574e-01 -1.63007736992023e-01 + 2.36121268527904e-01 -1.61049692711949e-01 + 2.26122324781829e-01 -1.59049566833247e-01 + 2.16324437766268e-01 -1.56951849123834e-01 + 2.06745907176088e-01 -1.54690861611926e-01 + 1.97389066205685e-01 -1.52226909705892e-01 + 1.88247721921604e-01 -1.49614702715995e-01 + 1.79314005605731e-01 -1.46926220464477e-01 + 1.70566694081349e-01 -1.44223107768427e-01 + 1.61987928073239e-01 -1.41464913845606e-01 + 1.53613637192824e-01 -1.38621916691031e-01 + 1.45465791115612e-01 -1.35641236981406e-01 + 1.37531633873771e-01 -1.32555619747964e-01 + 1.29789500501668e-01 -1.29438714378930e-01 + 1.22244457727610e-01 -1.26295657217261e-01 + 1.14904434138070e-01 -1.23092443693640e-01 + 1.07815146473205e-01 -1.19743795226088e-01 + 1.00932689591638e-01 -1.16291158229989e-01 + 9.42157410411242e-02 -1.12813381113546e-01 + 8.77349155613034e-02 -1.09269854169755e-01 + 8.14482559337302e-02 -1.05747275959770e-01 + 7.53019277572595e-02 -1.02291481938668e-01 + 6.93966080685775e-02 -9.87222833516028e-02 + 6.37676017649456e-02 -9.49332169892506e-02 + 5.83449527155066e-02 -9.10314379469155e-02 + 5.31177088421891e-02 -8.71178387550273e-02 + 4.80761779909361e-02 -8.32564851010753e-02 + 4.32072188935750e-02 -7.94169605594471e-02 + 3.85782245145711e-02 -7.54792072837812e-02 + 3.42154217216861e-02 -7.13768818016279e-02 + 3.00688981057734e-02 -6.72145109220034e-02 + 2.61374641397527e-02 -6.30734442017404e-02 + 2.23928752768931e-02 -5.89691912908124e-02 + 1.89178199388277e-02 -5.47792526393842e-02 + 1.57782895775260e-02 -5.03896663818205e-02 + 1.29264432287037e-02 -4.59030547514804e-02 + 1.03316751650313e-02 -4.14081472593511e-02 + 8.01095482796203e-03 -3.68823744341440e-02 + 6.08150946456878e-03 -3.22776443558319e-02 + 4.52036674400099e-03 -2.75690188527804e-02 + 3.11828349938427e-03 -2.29033385892524e-02 + 1.72653564695298e-03 -1.83027858589327e-02 + 9.36354454312048e-04 -1.37093359958523e-02 + 4.16310542075031e-04 -9.11214382596928e-03 + 9.05200308349797e-05 -4.53311172713394e-03 + 0.00000000000000e+00 0.00000000000000e+00 + 8.23110428241997e-05 3.97993478406906e-03 + 2.98468273940176e-04 7.93603235163689e-03 + 6.81113520909810e-04 1.19732402957132e-02 + 1.19041733235376e-03 1.60895922280325e-02 + 1.80832364157979e-03 2.02825181518579e-02 + 2.76834570722558e-03 2.45519466760042e-02 + 3.99985774071954e-03 2.88929320741292e-02 + 5.33098003226254e-03 3.32996052893721e-02 + 6.90917800997795e-03 3.77505431103084e-02 + 8.77992723995089e-03 4.22046062180702e-02 + 1.09457919494102e-02 4.66556914052094e-02 + 1.35126204924888e-02 5.10795304396620e-02 + 1.62412425116766e-02 5.55670056227592e-02 + 1.90868246244520e-02 6.01139718284135e-02 + 2.21802651667868e-02 6.46464708799812e-02 + 2.55327767469641e-02 6.91387827146383e-02 + 2.91390326059276e-02 7.36166345104199e-02 + 3.30039777104017e-02 7.80809269502797e-02 + 3.70896196513728e-02 8.25444208474574e-02 + 4.13563599588328e-02 8.70143468541920e-02 + 4.57942488220187e-02 9.15057079185578e-02 + 5.04601677621719e-02 9.59562675686702e-02 + 5.54400970779884e-02 1.00346688860753e-01 + 6.07171145906721e-02 1.04660979867235e-01 + 6.62216553378991e-02 1.08935080787161e-01 + 7.18940181674464e-02 1.13200789970514e-01 + 7.77574457722054e-02 1.17447559516479e-01 + 8.38582528706480e-02 1.21612209930337e-01 + 9.02250315657730e-02 1.25670302033989e-01 + 9.68042562433391e-02 1.29880982393018e-01 + 1.03635628099521e-01 1.34244912721725e-01 + 1.10722912321640e-01 1.38498319800975e-01 + 1.18029172437582e-01 1.42690766816319e-01 + 1.25557277062529e-01 1.46757468146931e-01 + 1.33346382566007e-01 1.50646937087769e-01 + 1.41422111706339e-01 1.54348524617411e-01 + 1.49738752822182e-01 1.57926503716025e-01 + 1.58261307252747e-01 1.61412895932014e-01 + 1.67014562834699e-01 1.64759052986503e-01 + 1.75997148265051e-01 1.67949166953076e-01 + 1.85241674734378e-01 1.70882184716457e-01 + 1.94781635865444e-01 1.73518364853247e-01 + 2.04539228304846e-01 1.76027713882885e-01 + 2.14458567307343e-01 1.78522958537949e-01 + 2.24570098428163e-01 1.80925955576210e-01 + 2.34913847146583e-01 1.83050172483361e-01 + 2.45534451193117e-01 1.84760209750302e-01 + 2.56409639618004e-01 1.86197622355102e-01 + 2.67481214281869e-01 1.87445374261523e-01 + 2.78729550445907e-01 1.88701260713293e-01 + 2.90174585689315e-01 1.89727304194648e-01 + 3.01827744802688e-01 1.90098148646786e-01 + 3.13693266853199e-01 1.90148247690122e-01 + 3.25752387770815e-01 1.90049748389473e-01 + 3.37985999295062e-01 1.89850482601187e-01 + 3.50399511022203e-01 1.89420380078704e-01 + 3.62964646417233e-01 1.88761112183883e-01 + 3.75659599317119e-01 1.87699877039682e-01 + 3.88493946311551e-01 1.86138748269845e-01 + 4.01479623369996e-01 1.84435211491590e-01 + 4.14618975626936e-01 1.82594846533824e-01 + 4.27893504473755e-01 1.80517499301112e-01 + 4.41277817165844e-01 1.78160355503343e-01 + 4.54769684184117e-01 1.75569963848603e-01 + 4.68402276532037e-01 1.72797452588699e-01 + 4.82204018250152e-01 1.69896570381480e-01 + 4.96163589481294e-01 1.66904476133250e-01 + 5.10254815759577e-01 1.63749683743645e-01 + 5.24457636672397e-01 1.60385631582868e-01 + 5.38778999812109e-01 1.56819010856189e-01 + 5.53239404956048e-01 1.53135112253065e-01 + 5.67833029385625e-01 1.49336436080728e-01 + 5.82554003323792e-01 1.45391901778675e-01 + 5.97398824215910e-01 1.41321960812472e-01 + 6.12357976569945e-01 1.37030889241381e-01 + 6.27427066223596e-01 1.32799780757966e-01 + 6.42609031829815e-01 1.28608187585689e-01 + 6.57884967455200e-01 1.24319134244053e-01 + 6.73222159445380e-01 1.19854473146893e-01 + 6.88646887911997e-01 1.15297096039949e-01 + 7.04172277874646e-01 1.10673352001207e-01 + 7.19774747820223e-01 1.05929035833374e-01 + 7.35472858003156e-01 1.00901982607120e-01 + 7.51283076871008e-01 9.58585566601091e-02 + 7.67180686513965e-01 9.08137757626553e-02 + 7.83126081044713e-01 8.56561702301634e-02 + 7.99132991302778e-01 8.04660870681737e-02 + 8.15219075008360e-01 7.53413348195255e-02 + 8.31361072829366e-01 7.02307546393778e-02 + 8.47517852331182e-01 6.50201985415269e-02 + 8.63656467507866e-01 5.97821549429307e-02 + 8.80097857298869e-01 5.46370739285706e-02 + 8.96698968133781e-01 4.95450131245877e-02 + 9.13428903265378e-01 4.45899999689061e-02 + 9.30165973653682e-01 3.95022753998810e-02 + 9.46677106385649e-01 3.35856041834030e-02 + 9.62366570300102e-01 2.64891184968628e-02 + 9.75524413777782e-01 1.96392571440591e-02 + 9.87942439431026e-01 1.23546891949117e-02 + 1.00000000000000e+00 4.46208092342662e-03 diff --git a/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF09_Coords.txt b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF09_Coords.txt new file mode 100644 index 00000000..ad8befd3 --- /dev/null +++ b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF09_Coords.txt @@ -0,0 +1,208 @@ + 201 NumCoords ! The number of coordinates in the airfoil shape file (including an extra coordinate for airfoil reference). Set to zero if coordinates not included. +! ......... x-y coordinates are next if NumCoords > 0 ............. +! x-y coordinate of airfoil reference +! x/c y/c + 0.250000 0 +! coordinates of airfoil shape +! interpolation to 200 points +! x/c y/c + 1.00000000000000e+00 -4.48290689425684e-03 + 9.82685147820042e-01 -8.53514315789639e-04 + 9.65074173125769e-01 1.52396515243919e-03 + 9.47131369847641e-01 2.38186310542476e-03 + 9.29079738392991e-01 1.98605407767317e-03 + 9.11136932686656e-01 5.84573053769325e-04 + 8.93331110552002e-01 -1.81559310542060e-03 + 8.75696926836349e-01 -5.03012545181162e-03 + 8.58278441614373e-01 -9.07756072898963e-03 + 8.41065780811555e-01 -1.37558503877734e-02 + 8.24066502389336e-01 -1.89558446797954e-02 + 8.07294332368906e-01 -2.46418157238813e-02 + 7.90771378093859e-01 -3.08020117323259e-02 + 7.74436098064809e-01 -3.72183726376832e-02 + 7.58302300968262e-01 -4.38908526083423e-02 + 7.42347203951615e-01 -5.07231917195430e-02 + 7.26567046543587e-01 -5.76828350641104e-02 + 7.10965565373373e-01 -6.47638335469136e-02 + 6.95519902088750e-01 -7.19078088118299e-02 + 6.80200852515995e-01 -7.90264679400814e-02 + 6.65009538158461e-01 -8.60993846853897e-02 + 6.49932728810378e-01 -9.30770840488921e-02 + 6.34965245124027e-01 -9.99452370375686e-02 + 6.20121473822035e-01 -1.06734816345267e-01 + 6.05369724148523e-01 -1.13358005108072e-01 + 5.90709203181047e-01 -1.19793368271858e-01 + 5.76132232588897e-01 -1.26003318443933e-01 + 5.61623485073142e-01 -1.31936337860336e-01 + 5.47180334826478e-01 -1.37560084850570e-01 + 5.32836011294100e-01 -1.42944693135479e-01 + 5.18557682393933e-01 -1.47974227654401e-01 + 5.04345019178191e-01 -1.52613115006628e-01 + 4.90215407430556e-01 -1.56884809310840e-01 + 4.76188015830545e-01 -1.60825115471635e-01 + 4.62253033665051e-01 -1.64349593909143e-01 + 4.48417515713528e-01 -1.67663331883973e-01 + 4.34710843069829e-01 -1.70667352837079e-01 + 4.21135345763282e-01 -1.73250013095204e-01 + 4.07692539196562e-01 -1.75369441774164e-01 + 3.94406397743186e-01 -1.77099957202116e-01 + 3.81276986557577e-01 -1.78362483813652e-01 + 3.68322783092766e-01 -1.79242115776658e-01 + 3.55553206107463e-01 -1.79749612515479e-01 + 3.42979242027837e-01 -1.79808674233742e-01 + 3.30609148150643e-01 -1.79674534400684e-01 + 3.18449580230503e-01 -1.79275909211052e-01 + 3.06509322655533e-01 -1.78584001099644e-01 + 2.94791175146716e-01 -1.77599602041753e-01 + 2.83289821555050e-01 -1.76476773548797e-01 + 2.72024535692418e-01 -1.75094998486103e-01 + 2.60982410030143e-01 -1.73562091072792e-01 + 2.50165091041909e-01 -1.71897518205597e-01 + 2.39583243413264e-01 -1.70036954342752e-01 + 2.29235853918176e-01 -1.68016721779713e-01 + 2.19124464871966e-01 -1.65842406240233e-01 + 2.09249588884711e-01 -1.63520913043737e-01 + 1.99602392919692e-01 -1.61103792507202e-01 + 1.90186989829693e-01 -1.58574244986568e-01 + 1.81007010664238e-01 -1.55917942725202e-01 + 1.72062553557725e-01 -1.53140009241234e-01 + 1.63359202368110e-01 -1.50235559165085e-01 + 1.54898392347029e-01 -1.47206088517032e-01 + 1.46661235477579e-01 -1.44116632162527e-01 + 1.38647675436818e-01 -1.40957746936569e-01 + 1.30857477642150e-01 -1.37727894684008e-01 + 1.23314150088703e-01 -1.34386012966235e-01 + 1.16005990278055e-01 -1.30951821112718e-01 + 1.08910846474458e-01 -1.27479847786535e-01 + 1.02040340343061e-01 -1.23952846372826e-01 + 9.53986311193279e-02 -1.20357474728516e-01 + 8.90323993394245e-02 -1.16626303852397e-01 + 8.28767305111376e-02 -1.12854160647330e-01 + 7.68844182301344e-02 -1.09120085561990e-01 + 7.11597965516513e-02 -1.05283382260545e-01 + 6.56696750940585e-02 -1.01384532327587e-01 + 6.03433734169027e-02 -9.75228716647275e-02 + 5.52631810751249e-02 -9.35945518645845e-02 + 5.04374628719753e-02 -8.95752445382964e-02 + 4.58017138657216e-02 -8.55532445604049e-02 + 4.13825063739979e-02 -8.15090777857146e-02 + 3.71903771573731e-02 -7.74330944997390e-02 + 3.31831498539127e-02 -7.33695626942466e-02 + 2.94044512619656e-02 -6.92770916723935e-02 + 2.58722600796746e-02 -6.51347604857932e-02 + 2.25572604740764e-02 -6.09795630283635e-02 + 1.94959660050299e-02 -5.67979807916763e-02 + 1.66549185470222e-02 -5.26131319251651e-02 + 1.40190892255552e-02 -4.84378076871468e-02 + 1.16391072588897e-02 -4.42393355742390e-02 + 9.50228788811488e-03 -4.00394598279192e-02 + 7.61750558427819e-03 -3.58461293746517e-02 + 5.96961734277674e-03 -3.16700112648946e-02 + 4.57051426408954e-03 -2.75182493553630e-02 + 3.46220550430262e-03 -2.33803588641517e-02 + 2.49916702260785e-03 -1.93106678103887e-02 + 1.63033961162431e-03 -1.53141667384712e-02 + 9.45407884520976e-04 -1.13883102313619e-02 + 4.21430261701436e-04 -7.52929844595465e-03 + 9.13381590902419e-05 -3.73175381667205e-03 + 0.00000000000000e+00 0.00000000000000e+00 + 8.39329452090013e-05 3.54374461053228e-03 + 3.06764956816802e-04 7.13454764013681e-03 + 7.13012164714768e-04 1.08029006119544e-02 + 1.25477699565490e-03 1.45538137640591e-02 + 1.87824996211846e-03 1.83913428617193e-02 + 2.64208856620242e-03 2.23137326727634e-02 + 3.57895258939452e-03 2.63122664551712e-02 + 4.70335330309463e-03 3.03676984106315e-02 + 6.09496820298392e-03 3.44560592490469e-02 + 7.77012954132717e-03 3.85621978759486e-02 + 9.64425945479125e-03 4.27121086824562e-02 + 1.18165673299811e-02 4.68542778685051e-02 + 1.41500458554206e-02 5.10499179457540e-02 + 1.66757939188311e-02 5.52650509642601e-02 + 1.94944358078314e-02 5.94454470327604e-02 + 2.25601750791306e-02 6.36068555875123e-02 + 2.57991449009508e-02 6.78079383217997e-02 + 2.92507958725958e-02 7.20111307917660e-02 + 3.29560547332662e-02 7.61771155635355e-02 + 3.69223016317185e-02 8.02789497263063e-02 + 4.10868701381863e-02 8.43778345265497e-02 + 4.54636094053712e-02 8.84590735779314e-02 + 5.01015073543740e-02 9.24805126256261e-02 + 5.49864471213822e-02 9.64435890880417e-02 + 6.01030437388835e-02 1.00355103021560e-01 + 6.54365794824045e-02 1.04221338170475e-01 + 7.09866408760679e-02 1.08042054278353e-01 + 7.67848489938729e-02 1.11764924267835e-01 + 8.28419567185367e-02 1.15382031398279e-01 + 8.90827233315631e-02 1.19090347853174e-01 + 9.55745973139600e-02 1.22782565847220e-01 + 1.02331435541202e-01 1.26329878276425e-01 + 1.09301721897512e-01 1.29816008658284e-01 + 1.16503807036038e-01 1.33194917983426e-01 + 1.23946109720764e-01 1.36448961986286e-01 + 1.31637302974835e-01 1.39553652375047e-01 + 1.39550632997968e-01 1.42570826391307e-01 + 1.47682542702398e-01 1.45498302111650e-01 + 1.56069518605229e-01 1.48227377016446e-01 + 1.64675258837698e-01 1.50862919805664e-01 + 1.73503763301154e-01 1.53381044924379e-01 + 1.82588549258338e-01 1.55672292390839e-01 + 1.91896032540898e-01 1.57837375775528e-01 + 2.01419018649528e-01 1.59879697369963e-01 + 2.11170879173786e-01 1.61737676480272e-01 + 2.21142920533604e-01 1.63440457557596e-01 + 2.31344785241530e-01 1.64936734040921e-01 + 2.41776812876277e-01 1.66222595255920e-01 + 2.52425332490408e-01 1.67302947561355e-01 + 2.63282507223669e-01 1.68244340945048e-01 + 2.74348610121382e-01 1.69012303782361e-01 + 2.85626365865730e-01 1.69515492111364e-01 + 2.97112155171042e-01 1.69781263535723e-01 + 3.08800622317762e-01 1.69842332018192e-01 + 3.20686150985499e-01 1.69794894735041e-01 + 3.32766911432096e-01 1.69536965688287e-01 + 3.45035577717233e-01 1.69036525986778e-01 + 3.57485836149525e-01 1.68290434604480e-01 + 3.70115165868763e-01 1.67285953978053e-01 + 3.82926121840238e-01 1.66129716711123e-01 + 3.95913836963527e-01 1.64788643586246e-01 + 4.09070495847257e-01 1.63222025400885e-01 + 4.22386727818900e-01 1.61413466981118e-01 + 4.35868199635534e-01 1.59446587441237e-01 + 4.49510425897221e-01 1.57282538740608e-01 + 4.63310011853810e-01 1.54890791219506e-01 + 4.77272395344154e-01 1.52355017486446e-01 + 4.91388930511577e-01 1.49650569804520e-01 + 5.05646917362174e-01 1.46740875171855e-01 + 5.20039269071302e-01 1.43601845074114e-01 + 5.34577578408399e-01 1.40310816694090e-01 + 5.49258664193118e-01 1.36874027194232e-01 + 5.64078723855862e-01 1.33285076105752e-01 + 5.79033365779676e-01 1.29550827646836e-01 + 5.94111062600388e-01 1.25620789009221e-01 + 6.09309105749297e-01 1.21600186027117e-01 + 6.24630556848364e-01 1.17501437763810e-01 + 6.40076803181406e-01 1.13310521064511e-01 + 6.55621511472488e-01 1.08956689246299e-01 + 6.71282434069662e-01 1.04519499702055e-01 + 6.87058502926135e-01 1.00008908785847e-01 + 7.02927846961763e-01 9.53686490689770e-02 + 7.18895804076489e-01 9.05798419248120e-02 + 7.34971135576913e-01 8.57455415670096e-02 + 7.51152054267092e-01 8.08966931334801e-02 + 7.67413928372726e-01 7.59701046314968e-02 + 7.83757964100345e-01 7.09983525490587e-02 + 8.00181412903085e-01 6.60019195388936e-02 + 8.16674324716874e-01 6.09715410793434e-02 + 8.33223797983461e-01 5.58863227273931e-02 + 8.49836681673719e-01 5.08054192889429e-02 + 8.66528789392319e-01 4.57720870242744e-02 + 8.83272682730090e-01 4.07491338740728e-02 + 9.00052750797641e-01 3.57316517957309e-02 + 9.16852440088815e-01 3.07020031399376e-02 + 9.33648056912371e-01 2.56007231641426e-02 + 9.50397160534152e-01 2.04803293247181e-02 + 9.66974356849030e-01 1.53946239244196e-02 + 9.83503121344171e-01 1.03013893225374e-02 + 1.00000000000000e+00 5.19104209295961e-03 diff --git a/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF10_Coords.txt b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF10_Coords.txt new file mode 100644 index 00000000..2306aabb --- /dev/null +++ b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF10_Coords.txt @@ -0,0 +1,208 @@ + 201 NumCoords ! The number of coordinates in the airfoil shape file (including an extra coordinate for airfoil reference). Set to zero if coordinates not included. +! ......... x-y coordinates are next if NumCoords > 0 ............. +! x-y coordinate of airfoil reference +! x/c y/c + 0.250000 0 +! coordinates of airfoil shape +! interpolation to 200 points +! x/c y/c + 1.00000000000000e+00 -4.86297327722780e-03 + 9.80511984509124e-01 -9.31133134220648e-04 + 9.60815932067473e-01 1.58783899675626e-03 + 9.41263727013327e-01 2.45977643583330e-03 + 9.21908373952958e-01 2.02318714366812e-03 + 9.02633195879556e-01 5.53907693277352e-04 + 8.83548952910911e-01 -1.92622687280061e-03 + 8.64676068654257e-01 -5.23592974327322e-03 + 8.46074367845829e-01 -9.38251493217475e-03 + 8.27741297597062e-01 -1.41772631793085e-02 + 8.09672007216587e-01 -1.94973257087956e-02 + 7.91873336657596e-01 -2.52977908683563e-02 + 7.74367735549103e-01 -3.15620058422089e-02 + 7.57090038050940e-01 -3.80736794610610e-02 + 7.40059721602248e-01 -4.48406933947372e-02 + 7.23230579889469e-01 -5.17449963666943e-02 + 7.06605015919964e-01 -5.87716939723825e-02 + 6.90194826941935e-01 -6.59021942385170e-02 + 6.73996889494706e-01 -7.30893135249750e-02 + 6.57970960213318e-01 -8.02435270068158e-02 + 6.42102769339429e-01 -8.73411845286708e-02 + 6.26367045194948e-01 -9.43282695074803e-02 + 6.10778899846100e-01 -1.01198731702759e-01 + 5.95374122609830e-01 -1.07986550525514e-01 + 5.80108917172105e-01 -1.14593528787722e-01 + 5.64977322759140e-01 -1.21007184170168e-01 + 5.49963599827458e-01 -1.27184493648524e-01 + 5.35054509500322e-01 -1.33078736790999e-01 + 5.20240239002187e-01 -1.38649489081145e-01 + 5.05557788087488e-01 -1.43964284458764e-01 + 4.90970256041941e-01 -1.48911007050803e-01 + 4.76472728677462e-01 -1.53449856278318e-01 + 4.62084942212174e-01 -1.57602665694934e-01 + 4.47828765294808e-01 -1.61403714230558e-01 + 4.33694515609551e-01 -1.64768180098576e-01 + 4.19692014900672e-01 -1.67312421586961e-01 + 4.05855041232298e-01 -1.69438167354179e-01 + 3.92188826102844e-01 -1.71236764964869e-01 + 3.78696783687713e-01 -1.72680366966462e-01 + 3.65404165992181e-01 -1.73828350111621e-01 + 3.52309960259442e-01 -1.74603832845386e-01 + 3.39434352269169e-01 -1.75046402850823e-01 + 3.26788044378576e-01 -1.75133825786606e-01 + 3.14377288520538e-01 -1.74796806544884e-01 + 3.02214001378326e-01 -1.74281937784550e-01 + 2.90296958909308e-01 -1.73520780939566e-01 + 2.78635485836657e-01 -1.72477429763394e-01 + 2.67233529810193e-01 -1.71175577799686e-01 + 2.56083711507059e-01 -1.69740287783202e-01 + 2.45202102031515e-01 -1.68009517278914e-01 + 2.34579105150908e-01 -1.66103858628628e-01 + 2.24212170859206e-01 -1.64059794305773e-01 + 2.14107895836219e-01 -1.61831060401740e-01 + 2.04263429104938e-01 -1.59459845656682e-01 + 1.94681903392709e-01 -1.56932790054656e-01 + 1.85360827376149e-01 -1.54246702766653e-01 + 1.76292980865286e-01 -1.51449979369351e-01 + 1.67482564557179e-01 -1.48544746675442e-01 + 1.58917391100164e-01 -1.45558949901677e-01 + 1.50597215806486e-01 -1.42512007742927e-01 + 1.42535487762553e-01 -1.39364415484843e-01 + 1.34732399664726e-01 -1.36087431797309e-01 + 1.27168245136680e-01 -1.32747266345250e-01 + 1.19842841419690e-01 -1.29351677052803e-01 + 1.12750494865106e-01 -1.25924352574772e-01 + 1.05909796567034e-01 -1.22436413682471e-01 + 9.93094805058807e-02 -1.18882766273095e-01 + 9.29294502220848e-02 -1.15306400616325e-01 + 8.67798712020860e-02 -1.11683261666515e-01 + 8.08601043456327e-02 -1.08010634641524e-01 + 7.52105971387069e-02 -1.04233041725997e-01 + 6.97707736814900e-02 -1.00453870449379e-01 + 6.44954666632857e-02 -9.67461879884846e-02 + 5.94792621751988e-02 -9.29557913115884e-02 + 5.46968806556035e-02 -8.91053349016699e-02 + 5.00889983595891e-02 -8.52955052036599e-02 + 4.57150288715163e-02 -8.14584893545538e-02 + 4.15643801762247e-02 -7.76015601232226e-02 + 3.75882055097653e-02 -7.37928505464360e-02 + 3.38275455149990e-02 -6.99786331700560e-02 + 3.02887595308436e-02 -6.61394551074094e-02 + 2.69209980985916e-02 -6.23365636550792e-02 + 2.37600762514079e-02 -5.85464923862813e-02 + 2.08209273086278e-02 -5.47566143699477e-02 + 1.80843181668748e-02 -5.09866904767273e-02 + 1.55871667540216e-02 -4.72112704231235e-02 + 1.32930091997276e-02 -4.34579786243884e-02 + 1.11671609158122e-02 -3.97587139427468e-02 + 9.24302286361386e-03 -3.60973970879580e-02 + 7.52099695998262e-03 -3.24775010120743e-02 + 6.02824547033773e-03 -2.88913977885378e-02 + 4.73760869802884e-03 -2.53555749353871e-02 + 3.63179948486746e-03 -2.18830234339889e-02 + 2.76343151147194e-03 -1.84654987945057e-02 + 2.02988502957333e-03 -1.51380631574757e-02 + 1.46813569910251e-03 -1.19064518890580e-02 + 8.92625474122533e-04 -8.77454309044243e-03 + 3.99065689084287e-04 -5.74363785175138e-03 + 8.70943828190601e-05 -2.81422588679827e-03 + 0.00000000000000e+00 0.00000000000000e+00 + 8.02187075687612e-05 3.23896444371914e-03 + 2.92360984112174e-04 6.64836967518462e-03 + 6.77158021962086e-04 1.01332887079749e-02 + 1.19066014968889e-03 1.36987991407504e-02 + 1.78076395507241e-03 1.73491673472808e-02 + 2.40903747756074e-03 2.10824160991588e-02 + 3.12276106703853e-03 2.48895553910672e-02 + 4.07783832276212e-03 2.87525459149076e-02 + 5.29086782469029e-03 3.26492458807703e-02 + 6.76340526224963e-03 3.65661596791223e-02 + 8.38018584402884e-03 4.05288053998209e-02 + 1.02253241413783e-02 4.44891365322827e-02 + 1.22248587000671e-02 4.85018949098202e-02 + 1.44438730234543e-02 5.25327300962284e-02 + 1.69548467514969e-02 5.65334970723320e-02 + 1.96931133190989e-02 6.05207316239289e-02 + 2.25638609500651e-02 6.45491498636593e-02 + 2.56161511220727e-02 6.85831866314810e-02 + 2.89202819428702e-02 7.25851847243638e-02 + 3.25062523751746e-02 7.65285938527960e-02 + 3.62951761898641e-02 8.04726459274233e-02 + 4.02846009364239e-02 8.44024704703390e-02 + 4.45007879918332e-02 8.82780700165274e-02 + 4.89247556185767e-02 9.21060334637697e-02 + 5.35723096647886e-02 9.58897521485476e-02 + 5.84592407255586e-02 9.96298721593641e-02 + 6.35713075613679e-02 1.03329002883886e-01 + 6.89278104673831e-02 1.06940810225108e-01 + 7.45312963741614e-02 1.10457519647787e-01 + 8.03023396546418e-02 1.13808960354886e-01 + 8.63179073064753e-02 1.16806322489047e-01 + 9.25972420849028e-02 1.19687016346367e-01 + 9.90811043339423e-02 1.22544358196588e-01 + 1.05787895955984e-01 1.25340806259942e-01 + 1.12724232239356e-01 1.28073095299648e-01 + 1.19892971306548e-01 1.30703114138229e-01 + 1.27273440293726e-01 1.33288917717216e-01 + 1.34877152315313e-01 1.35805891937509e-01 + 1.42744011141429e-01 1.38116832152479e-01 + 1.50823603558752e-01 1.40392690357772e-01 + 1.59107761029883e-01 1.42661149234078e-01 + 1.67629352696633e-01 1.44772172686264e-01 + 1.76377704606620e-01 1.46774529039623e-01 + 1.85370180781539e-01 1.48614215130669e-01 + 1.94612923349638e-01 1.50247989477911e-01 + 2.04074586490007e-01 1.51818931098813e-01 + 2.13747530977158e-01 1.53313183639193e-01 + 2.23645236800479e-01 1.54647357802947e-01 + 2.33775728681758e-01 1.55792644992903e-01 + 2.44138440260482e-01 1.56752241560042e-01 + 2.54726045330669e-01 1.57590263699543e-01 + 2.65537343044850e-01 1.58361624334313e-01 + 2.76567564773377e-01 1.58942652997736e-01 + 2.87817345414617e-01 1.59319971716534e-01 + 2.99290232425583e-01 1.59589784224439e-01 + 3.10982335287392e-01 1.59671340810000e-01 + 3.22895608718648e-01 1.59537343958620e-01 + 3.35033089062765e-01 1.59236217541811e-01 + 3.47389002674619e-01 1.58767154984173e-01 + 3.59961889407242e-01 1.58139657212231e-01 + 3.72743440456310e-01 1.57309327495217e-01 + 3.85733458057802e-01 1.56248726075227e-01 + 3.98930703138098e-01 1.54975303437308e-01 + 4.12345184105345e-01 1.53551512089131e-01 + 4.25954142961272e-01 1.51935725721345e-01 + 4.39739441903326e-01 1.50056917065730e-01 + 4.53714268006763e-01 1.47990332900825e-01 + 4.67878910856137e-01 1.45763613299970e-01 + 4.82224623597588e-01 1.43333415389031e-01 + 4.96738039338005e-01 1.40653686928458e-01 + 5.11425301120766e-01 1.37802798976480e-01 + 5.26284017534203e-01 1.34778098917954e-01 + 5.41313223595069e-01 1.31616771414899e-01 + 5.56506191866471e-01 1.28282935128933e-01 + 5.71853456832878e-01 1.24814251336103e-01 + 5.87352855179168e-01 1.21054902047869e-01 + 6.03005431727672e-01 1.17060565551195e-01 + 6.18822144334829e-01 1.12966378040271e-01 + 6.34781882100071e-01 1.08702844246632e-01 + 6.50899402129147e-01 1.04349818477932e-01 + 6.67165890781568e-01 9.99118836260051e-02 + 6.83560340804585e-01 9.53341953789793e-02 + 7.00082231463252e-01 9.07664656077491e-02 + 7.16736439213004e-01 8.61324826330526e-02 + 7.33532609513889e-01 8.14583044049984e-02 + 7.50453705328182e-01 7.67128793620926e-02 + 7.67496896127474e-01 7.18988453285231e-02 + 7.84651539969057e-01 6.69901347588158e-02 + 8.01917466461742e-01 6.20117979514114e-02 + 8.19294924371077e-01 5.69943186539853e-02 + 8.36792306469474e-01 5.19801638256853e-02 + 8.54409507470158e-01 4.69691610485990e-02 + 8.72138737961771e-01 4.19401147746978e-02 + 8.89967727577875e-01 3.68416407164412e-02 + 9.07923286973654e-01 3.17741055104095e-02 + 9.26040022335196e-01 2.69066169756247e-02 + 9.44348788456134e-01 2.21078957421789e-02 + 9.62867272385349e-01 1.70474154188180e-02 + 9.81428540150012e-01 1.18282222218164e-02 + 1.00000000000000e+00 6.42193222596370e-03 diff --git a/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF11_Coords.txt b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF11_Coords.txt new file mode 100644 index 00000000..cea9e099 --- /dev/null +++ b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF11_Coords.txt @@ -0,0 +1,208 @@ + 201 NumCoords ! The number of coordinates in the airfoil shape file (including an extra coordinate for airfoil reference). Set to zero if coordinates not included. +! ......... x-y coordinates are next if NumCoords > 0 ............. +! x-y coordinate of airfoil reference +! x/c y/c + 0.250000 0 +! coordinates of airfoil shape +! interpolation to 200 points +! x/c y/c + 1.00000000000000e+00 -5.69525046509396e-03 + 9.78806538918783e-01 -1.52333707624982e-03 + 9.57388982524555e-01 1.12180524962487e-03 + 9.36194732688498e-01 2.02641546982668e-03 + 9.15272729634671e-01 1.50711995585143e-03 + 8.94450817639587e-01 -1.31121257641393e-04 + 8.73855886372089e-01 -2.82614463352886e-03 + 8.53513143501759e-01 -6.40839878682634e-03 + 8.33476839211981e-01 -1.08310870429086e-02 + 8.13756218644144e-01 -1.59345264947230e-02 + 7.94338172931301e-01 -2.15617459883902e-02 + 7.75223162367073e-01 -2.76433664245668e-02 + 7.56430809853826e-01 -3.41498879519738e-02 + 7.37902039055167e-01 -4.08770619092354e-02 + 7.19666804126832e-01 -4.78568465131379e-02 + 7.01658130282083e-01 -5.49136484928595e-02 + 6.83899927259984e-01 -6.20881481267653e-02 + 6.66390228117896e-01 -6.93121843337415e-02 + 6.49139979076653e-01 -7.65617633025002e-02 + 6.32111246018286e-01 -8.37529658171195e-02 + 6.15288445442940e-01 -9.08626791271311e-02 + 5.98643467384132e-01 -9.78302135918077e-02 + 5.82199702299186e-01 -1.04659155113551e-01 + 5.65994720552908e-01 -1.11376506607751e-01 + 5.49978071618322e-01 -1.17862982731167e-01 + 5.34153023591067e-01 -1.24136613279468e-01 + 5.18499703066478e-01 -1.30142303625889e-01 + 5.03010433237196e-01 -1.35847983922864e-01 + 4.87668238679784e-01 -1.41188236613217e-01 + 4.72507803295827e-01 -1.46221700598355e-01 + 4.57497896342093e-01 -1.50852564976543e-01 + 4.42633017601021e-01 -1.55032379104410e-01 + 4.27932599332219e-01 -1.58778956843575e-01 + 4.13418848394650e-01 -1.62120173617977e-01 + 3.99086452753069e-01 -1.64971636857931e-01 + 3.84948831136274e-01 -1.67048827443987e-01 + 3.71039880058497e-01 -1.68671738056494e-01 + 3.57369018629051e-01 -1.69925952664825e-01 + 3.43942688850799e-01 -1.70795813632049e-01 + 3.30784793117660e-01 -1.71334788788157e-01 + 3.17893696334626e-01 -1.71490756553470e-01 + 3.05286580000178e-01 -1.71294197311131e-01 + 2.92974406928141e-01 -1.70717197421300e-01 + 2.80951411412875e-01 -1.69737797343376e-01 + 2.69233585663057e-01 -1.68548716430126e-01 + 2.57805947668032e-01 -1.67130702113460e-01 + 2.46678614080578e-01 -1.65444540916611e-01 + 2.35855708755702e-01 -1.63515711588020e-01 + 2.25324636807488e-01 -1.61458171344871e-01 + 2.15089578214410e-01 -1.59139131505499e-01 + 2.05150257762253e-01 -1.56651810005603e-01 + 1.95498465637821e-01 -1.54032321793723e-01 + 1.86133303884814e-01 -1.51267800061800e-01 + 1.77048514682184e-01 -1.48396307898530e-01 + 1.68247904545403e-01 -1.45397772039655e-01 + 1.59721997054468e-01 -1.42280347630919e-01 + 1.51466704551609e-01 -1.39072008137626e-01 + 1.43490819529254e-01 -1.35772826875173e-01 + 1.35761290420028e-01 -1.32454355349041e-01 + 1.28278100435328e-01 -1.29124976897121e-01 + 1.21061925252952e-01 -1.25731442239843e-01 + 1.14106782713019e-01 -1.22244231683582e-01 + 1.07392996712928e-01 -1.18723433818558e-01 + 1.00921587269965e-01 -1.15182636140660e-01 + 9.46841600395731e-02 -1.11678741751433e-01 + 8.86904020175527e-02 -1.08199712602269e-01 + 8.29295937403109e-02 -1.04690677290643e-01 + 7.73855253774526e-02 -1.01182355772936e-01 + 7.20632038828038e-02 -9.76537898724569e-02 + 6.69567872583836e-02 -9.41087513314784e-02 + 6.20974140669556e-02 -9.05039743293917e-02 + 5.74408846245436e-02 -8.69216814878245e-02 + 5.29472035657151e-02 -8.34211011266652e-02 + 4.86830821705248e-02 -7.98783109729412e-02 + 4.46330074510540e-02 -7.63028087621810e-02 + 4.07611793756051e-02 -7.27687863405534e-02 + 3.71009763948847e-02 -6.92364489374634e-02 + 3.36248359360092e-02 -6.57310546071755e-02 + 3.03041413909075e-02 -6.22959704284829e-02 + 2.71879524688719e-02 -5.88684263115360e-02 + 2.42717576545455e-02 -5.54343443189173e-02 + 2.15027525196933e-02 -5.20540051592585e-02 + 1.89137313912481e-02 -4.87090785971533e-02 + 1.65182266978350e-02 -4.53887621601851e-02 + 1.43049162404917e-02 -4.21042791351809e-02 + 1.23028427731255e-02 -3.88313724591694e-02 + 1.04741934250062e-02 -3.55976591947433e-02 + 8.78311115027676e-03 -3.24338519377945e-02 + 7.24533815833448e-03 -2.93330391673238e-02 + 5.86947854914707e-03 -2.62910386079313e-02 + 4.69611128198702e-03 -2.32928044536227e-02 + 3.68981688144507e-03 -2.03556383168934e-02 + 2.82187228866077e-03 -1.74932823095649e-02 + 2.14089095819824e-03 -1.46985911948591e-02 + 1.57630652997499e-03 -1.19942243149679e-02 + 1.18984777333983e-03 -9.38552769920999e-03 + 7.38439523884420e-04 -6.87678063790083e-03 + 3.33591616922490e-04 -4.47097508153630e-03 + 7.46901189097683e-05 -2.17087537934301e-03 + 0.00000000000000e+00 0.00000000000000e+00 + 6.92412634353660e-05 2.74621576665460e-03 + 2.49543457687775e-04 5.67381024680127e-03 + 5.69195748818264e-04 8.67143602234610e-03 + 9.96695834445714e-04 1.17435040095864e-02 + 1.48928310396865e-03 1.48940750374214e-02 + 1.98849119023728e-03 1.81207435789369e-02 + 2.54959257779418e-03 2.14141902325502e-02 + 3.34181357652084e-03 2.47615483193398e-02 + 4.35138049766192e-03 2.81462543893500e-02 + 5.57852652609682e-03 3.15563440839828e-02 + 6.92222649894473e-03 3.50119837686661e-02 + 8.43795113911303e-03 3.84786497098604e-02 + 1.00930905567546e-02 4.19960985164764e-02 + 1.19621589285143e-02 4.55325565150444e-02 + 1.40852578757622e-02 4.90549107074214e-02 + 1.64039291216290e-02 5.25767354668559e-02 + 1.88398593495795e-02 5.61372533386474e-02 + 2.14333380897448e-02 5.97116148591461e-02 + 2.42465708836148e-02 6.32736158904520e-02 + 2.73128417251185e-02 6.68021029337550e-02 + 3.05634247430033e-02 7.03446938508445e-02 + 3.40012367549624e-02 7.38799559097142e-02 + 3.76412740591324e-02 7.73776756177052e-02 + 4.14526743416006e-02 8.08567034039700e-02 + 4.54648935651470e-02 8.43141185886057e-02 + 4.97138325875744e-02 8.77373418115587e-02 + 5.41781481654145e-02 9.11359855290002e-02 + 5.88644478021621e-02 9.44797733214635e-02 + 6.37759842093246e-02 9.77593136724116e-02 + 6.88488483685858e-02 1.00823224034846e-01 + 7.41507917548021e-02 1.03488541051867e-01 + 7.97016770601785e-02 1.06075588555681e-01 + 8.54487989072580e-02 1.08666353687266e-01 + 9.14085009112059e-02 1.11233062570593e-01 + 9.75916624744935e-02 1.13770253357497e-01 + 1.03999187359272e-01 1.16244616416147e-01 + 1.10612131361174e-01 1.18708964579629e-01 + 1.17449024487558e-01 1.21131135964468e-01 + 1.24546888925588e-01 1.23387153002500e-01 + 1.31860808435011e-01 1.25637788779435e-01 + 1.39382107499695e-01 1.27944947022874e-01 + 1.47138451129947e-01 1.30161879268156e-01 + 1.55130130177100e-01 1.32297385813300e-01 + 1.63380895148427e-01 1.34288717996456e-01 + 1.71895347851209e-01 1.36104388754837e-01 + 1.80641095940374e-01 1.37908869745374e-01 + 1.89607443624250e-01 1.39694681869496e-01 + 1.98815192027444e-01 1.41352012545062e-01 + 2.08277829742442e-01 1.42856034753896e-01 + 2.17998788821085e-01 1.44187980224416e-01 + 2.27971555762112e-01 1.45430091516579e-01 + 2.38195302318094e-01 1.46673887296536e-01 + 2.48670661039287e-01 1.47744688351893e-01 + 2.59395614367826e-01 1.48645867466862e-01 + 2.70380513809449e-01 1.49438453642673e-01 + 2.81625107704732e-01 1.50057622177488e-01 + 2.93131175607184e-01 1.50496964150777e-01 + 3.04908162749787e-01 1.50795041350106e-01 + 3.16953693264067e-01 1.50926867573051e-01 + 3.29263945095546e-01 1.50884243661390e-01 + 3.41831054632093e-01 1.50627191696395e-01 + 3.54660098331472e-01 1.50114926580935e-01 + 3.67749572260908e-01 1.49411069482863e-01 + 3.81111124669245e-01 1.48516691724055e-01 + 3.94719101684341e-01 1.47440799158347e-01 + 4.08554267680281e-01 1.46095627806137e-01 + 4.22629583420339e-01 1.44515583307731e-01 + 4.36948565719152e-01 1.42787868414573e-01 + 4.51504717292113e-01 1.40851047954471e-01 + 4.66284547735849e-01 1.38636208645556e-01 + 4.81291098416158e-01 1.36225156460815e-01 + 4.96521243549536e-01 1.33595494775405e-01 + 5.11977506070676e-01 1.30819756217691e-01 + 5.27648084830866e-01 1.27801959456686e-01 + 5.43529232837187e-01 1.24624712255092e-01 + 5.59617766329048e-01 1.21167360031619e-01 + 5.75910930604750e-01 1.17465675967471e-01 + 5.92420943986219e-01 1.13641307775934e-01 + 6.09129433020705e-01 1.09627607546218e-01 + 6.26048292506993e-01 1.05505710212843e-01 + 6.43163878485665e-01 1.01266416248930e-01 + 6.60456216477355e-01 9.68592270720327e-02 + 6.77923642030845e-01 9.24805992427934e-02 + 6.95566193064319e-01 8.80054199530201e-02 + 7.13393826614235e-01 8.34592506694026e-02 + 7.31389719769680e-01 7.88141754388108e-02 + 7.49549904053857e-01 7.40757159847257e-02 + 7.67859592973647e-01 6.92056573065396e-02 + 7.86320983784494e-01 6.42470162878310e-02 + 8.04932658647533e-01 5.92311705291700e-02 + 8.23696980505892e-01 5.41849164919753e-02 + 8.42611206733270e-01 4.91017607941500e-02 + 8.61674584002276e-01 4.39898310628447e-02 + 8.80870637502453e-01 3.87781149653440e-02 + 9.00229080614011e-01 3.35800045674166e-02 + 9.19795776538293e-01 2.86236343997086e-02 + 9.39609936409794e-01 2.37339679553963e-02 + 9.59701477871013e-01 1.84898366266777e-02 + 9.79845921697258e-01 1.30253668628043e-02 + 1.00000000000000e+00 7.30191104279453e-03 diff --git a/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF12_Coords.txt b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF12_Coords.txt new file mode 100644 index 00000000..0559474f --- /dev/null +++ b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF12_Coords.txt @@ -0,0 +1,208 @@ + 201 NumCoords ! The number of coordinates in the airfoil shape file (including an extra coordinate for airfoil reference). Set to zero if coordinates not included. +! ......... x-y coordinates are next if NumCoords > 0 ............. +! x-y coordinate of airfoil reference +! x/c y/c + 0.250000 0 +! coordinates of airfoil shape +! interpolation to 200 points +! x/c y/c + 1.00000000000000e+00 -6.59289903496683e-03 + 9.77462574493223e-01 -2.16354893719578e-03 + 9.54655435704073e-01 6.29155968453326e-04 + 9.32021629665813e-01 1.58147595579106e-03 + 9.09641132745904e-01 9.68321497165801e-04 + 8.87387976484538e-01 -8.61665541778709e-04 + 8.65383162362486e-01 -3.80055493480974e-03 + 8.43662068878266e-01 -7.69211321552455e-03 + 8.22270394573964e-01 -1.24281363324318e-02 + 8.01229047333685e-01 -1.78818932097066e-02 + 7.80519648544988e-01 -2.38576889999194e-02 + 7.60137450727518e-01 -3.02583777838988e-02 + 7.40098281598073e-01 -3.70398802849335e-02 + 7.20352027908950e-01 -4.40116142510090e-02 + 7.00939656244907e-01 -5.12328611067571e-02 + 6.81776953494553e-01 -5.84627261960696e-02 + 6.62912611308619e-01 -6.58049585843197e-02 + 6.44324407874433e-01 -7.31351438149378e-02 + 6.26033587000552e-01 -8.04556049946791e-02 + 6.08009280948661e-01 -8.76887844187042e-02 + 5.90240034355429e-01 -9.48121792091236e-02 + 5.72698730868021e-01 -1.01757526822754e-01 + 5.55411618765222e-01 -1.08539348714150e-01 + 5.38410505295645e-01 -1.15176730540461e-01 + 5.21641137664166e-01 -1.21526455119343e-01 + 5.05120327854410e-01 -1.27641178842136e-01 + 4.88826034147189e-01 -1.33452107654868e-01 + 4.72756829324759e-01 -1.38943797888081e-01 + 4.56889462779481e-01 -1.44022468696136e-01 + 4.41254283784751e-01 -1.48736664468832e-01 + 4.25828763295902e-01 -1.53009077959500e-01 + 4.10608396875106e-01 -1.56781442021245e-01 + 3.95611341439966e-01 -1.60067008778474e-01 + 3.80859198346160e-01 -1.62886386652726e-01 + 3.66352119576184e-01 -1.65155670170054e-01 + 3.52107005040102e-01 -1.66902005730228e-01 + 3.38156214714513e-01 -1.68180087712901e-01 + 3.24513341344794e-01 -1.69002675432013e-01 + 3.11187922762876e-01 -1.69365388971009e-01 + 2.98201656691272e-01 -1.69321104984817e-01 + 2.85552513851790e-01 -1.68850434152112e-01 + 2.73253227372360e-01 -1.67989608645765e-01 + 2.61314584364762e-01 -1.66716467434525e-01 + 2.49717456201525e-01 -1.65067768351444e-01 + 2.38481581724083e-01 -1.63168950410788e-01 + 2.27577633315906e-01 -1.61061577397165e-01 + 2.17016518468669e-01 -1.58704919182658e-01 + 2.06802133386028e-01 -1.56117655460340e-01 + 1.96916073521044e-01 -1.53408634182298e-01 + 1.87348745914297e-01 -1.50498802686717e-01 + 1.78110341897585e-01 -1.47440177216010e-01 + 1.69187136270505e-01 -1.44263475400156e-01 + 1.60570365998313e-01 -1.40988056631572e-01 + 1.52250193619772e-01 -1.37644886570335e-01 + 1.44230669463642e-01 -1.34212542197887e-01 + 1.36494686486109e-01 -1.30715956516135e-01 + 1.29041497441893e-01 -1.27160062404650e-01 + 1.21885590388894e-01 -1.23534314732798e-01 + 1.14973606123809e-01 -1.19946512938672e-01 + 1.08305921585264e-01 -1.16388074461917e-01 + 1.01909359633608e-01 -1.12800979544153e-01 + 9.57707298096185e-02 -1.09166779555742e-01 + 8.98707927414503e-02 -1.05536283052279e-01 + 8.42125339933439e-02 -1.01922663598644e-01 + 7.87856905027138e-02 -9.84078143770367e-02 + 7.35906514404928e-02 -9.49953343228512e-02 + 6.86172317695538e-02 -9.15875578296713e-02 + 6.38533217988130e-02 -8.82040084294520e-02 + 5.92980557795527e-02 -8.48301665574652e-02 + 5.49408872977093e-02 -8.14740098816748e-02 + 5.08036836099950e-02 -7.81032042579184e-02 + 4.68610047073478e-02 -7.47702209343977e-02 + 4.30785112607683e-02 -7.15190729392446e-02 + 3.94919427630735e-02 -6.82684814540532e-02 + 3.60951095929823e-02 -6.50177741480466e-02 + 3.28772361824951e-02 -6.18076334563007e-02 + 2.98476901787584e-02 -5.86203472715078e-02 + 2.69646970034140e-02 -5.54923720162200e-02 + 2.42190323125321e-02 -5.24435068585061e-02 + 2.16645901488774e-02 -4.94116456937637e-02 + 1.92850652097574e-02 -4.63923677020781e-02 + 1.70282894977093e-02 -4.34389302947373e-02 + 1.49260602838669e-02 -4.05334871230597e-02 + 1.29912536138279e-02 -3.76649194227854e-02 + 1.12187903727820e-02 -3.48395240965275e-02 + 9.62813430202066e-03 -3.20378388982212e-02 + 8.18092003399821e-03 -2.92857015336182e-02 + 6.84633398695211e-03 -2.66067373303015e-02 + 5.62450310894219e-03 -2.40002771296278e-02 + 4.52964061799434e-03 -2.14585557295876e-02 + 3.61249392215131e-03 -1.89621107862018e-02 + 2.83156382020768e-03 -1.65274274071386e-02 + 2.15391143043915e-03 -1.41677824378179e-02 + 1.61971733933399e-03 -1.18767840274053e-02 + 1.18249367536328e-03 -9.66762809531005e-03 + 9.00276584579961e-04 -7.54452003683207e-03 + 5.63461991934761e-04 -5.51056387158645e-03 + 2.59288533302532e-04 -3.56890304558222e-03 + 6.06131716837195e-05 -1.72224692907942e-03 + 0.00000000000000e+00 0.00000000000000e+00 + 5.67835389889402e-05 2.23388026035764e-03 + 2.00952097149670e-04 4.61469303956217e-03 + 4.46675038797624e-04 7.05931530631234e-03 + 7.76575926534887e-04 9.57140139412797e-03 + 1.15849680432229e-03 1.21547788698366e-02 + 1.54614500966935e-03 1.48065561530573e-02 + 2.00070260770825e-03 1.75170400276963e-02 + 2.65215356260171e-03 2.02792339598468e-02 + 3.47323279235998e-03 2.30829050644064e-02 + 4.46819146620787e-03 2.59178267189914e-02 + 5.56561856863645e-03 2.87980918982248e-02 + 6.79056284994487e-03 3.17045231575689e-02 + 8.13858873349298e-03 3.46598711622827e-02 + 9.68330745830288e-03 3.76352864715079e-02 + 1.14346994907591e-02 4.06147151377888e-02 + 1.33491940226201e-02 4.36083707829037e-02 + 1.53772074549925e-02 4.66378931168147e-02 + 1.75443628317557e-02 4.96905933565631e-02 + 1.98915287956748e-02 5.27532648459689e-02 + 2.24474950353453e-02 5.58108786203703e-02 + 2.51624414470984e-02 5.88978723678661e-02 + 2.80522645924001e-02 6.19853661991399e-02 + 3.11264629746060e-02 6.50542499375811e-02 + 3.43410667421415e-02 6.81372889799119e-02 + 3.77308203466917e-02 7.12243994705516e-02 + 4.13453068432654e-02 7.42879931829202e-02 + 4.51595000908772e-02 7.73456299876008e-02 + 4.91686920501722e-02 8.03852564794801e-02 + 5.33801809367164e-02 8.33956461149312e-02 + 5.77512987175583e-02 8.62331801696985e-02 + 6.23344808339581e-02 8.87547541886008e-02 + 6.71482925323690e-02 9.12346139217212e-02 + 7.21514064313091e-02 9.37368421170488e-02 + 7.73578208727705e-02 9.62429430485729e-02 + 8.27840233215640e-02 9.87392024812666e-02 + 8.84305455042329e-02 1.01203971113129e-01 + 9.42784521040168e-02 1.03684898058958e-01 + 1.00349482885677e-01 1.06148999300961e-01 + 1.06675746455941e-01 1.08500173174811e-01 + 1.13224681689826e-01 1.10860453971563e-01 + 1.19991569273127e-01 1.13309399912637e-01 + 1.26997678082753e-01 1.15723096597717e-01 + 1.34248487747998e-01 1.18083169460431e-01 + 1.41766455235735e-01 1.20337838546890e-01 + 1.49556942766775e-01 1.22463305444449e-01 + 1.57594884531095e-01 1.24605078711964e-01 + 1.65872323102866e-01 1.26751754125367e-01 + 1.74414303121935e-01 1.28791936379402e-01 + 1.83232973200224e-01 1.30716996095475e-01 + 1.92334031181005e-01 1.32504394318715e-01 + 2.01714845882273e-01 1.34221597554837e-01 + 2.11376563986695e-01 1.35950985429642e-01 + 2.21327073690106e-01 1.37513571507823e-01 + 2.31558674587867e-01 1.38949208546669e-01 + 2.42086808461520e-01 1.40274988342984e-01 + 2.52916621133675e-01 1.41437460216382e-01 + 2.64046135586957e-01 1.42454319791249e-01 + 2.75489341566209e-01 1.43333195335266e-01 + 2.87249360771650e-01 1.44017218149413e-01 + 2.99320864102740e-01 1.44510983023378e-01 + 3.11697880289428e-01 1.44782627217238e-01 + 3.24389216406290e-01 1.44771773129655e-01 + 3.37389885735918e-01 1.44584432506276e-01 + 3.50711947471814e-01 1.44154382165419e-01 + 3.64333063360102e-01 1.43552910023117e-01 + 3.78238232522780e-01 1.42687210105816e-01 + 3.92437161035743e-01 1.41543861735063e-01 + 4.06934048908587e-01 1.40264190680221e-01 + 4.21723746945062e-01 1.38767747462759e-01 + 4.36795000699457e-01 1.36967177057565e-01 + 4.52149019127696e-01 1.34947664351219e-01 + 4.67781452534759e-01 1.32666334029277e-01 + 4.83698128848859e-01 1.30225012111576e-01 + 4.99881720532700e-01 1.27468428284761e-01 + 5.16334894694303e-01 1.24505686672269e-01 + 5.33052962546645e-01 1.21341841759092e-01 + 5.50029162636473e-01 1.17972273560778e-01 + 5.67273658847011e-01 1.14454109134925e-01 + 5.84769489731911e-01 1.10723931887335e-01 + 6.02525985564944e-01 1.06864330068656e-01 + 6.20526328831323e-01 1.02850463209321e-01 + 6.38751539751037e-01 9.86367644668299e-02 + 6.57200727073522e-01 9.44111760430084e-02 + 6.75869233343243e-01 9.00585516397063e-02 + 6.94763003002744e-01 8.56060946859686e-02 + 7.13862552225269e-01 8.10172115726413e-02 + 7.33163934294235e-01 7.63128882283146e-02 + 7.52650023865557e-01 7.14576086673483e-02 + 7.72322163431510e-01 6.65036673628003e-02 + 7.92171758296376e-01 6.14635847757860e-02 + 8.12193610513406e-01 5.63508957281089e-02 + 8.32382188739325e-01 5.11679507532475e-02 + 8.52739781790815e-01 4.59537194411629e-02 + 8.73243502309430e-01 4.06300736331539e-02 + 8.93910339588305e-01 3.52818185648098e-02 + 9.14779694269379e-01 3.01276312748428e-02 + 9.35880709193391e-01 2.50231519126587e-02 + 9.57228053275711e-01 1.95608523563538e-02 + 9.78615505631340e-01 1.38731920021658e-02 + 1.00000000000000e+00 7.91978608447872e-03 diff --git a/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF13_Coords.txt b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF13_Coords.txt new file mode 100644 index 00000000..1e2d3601 --- /dev/null +++ b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF13_Coords.txt @@ -0,0 +1,208 @@ + 201 NumCoords ! The number of coordinates in the airfoil shape file (including an extra coordinate for airfoil reference). Set to zero if coordinates not included. +! ......... x-y coordinates are next if NumCoords > 0 ............. +! x-y coordinate of airfoil reference +! x/c y/c + 0.250000 0 +! coordinates of airfoil shape +! interpolation to 200 points +! x/c y/c + 1.00000000000000e+00 -7.43253554058350e-03 + 9.76403943349399e-01 -2.76411676761089e-03 + 9.52484559548605e-01 1.70901095140179e-04 + 9.28638752659537e-01 1.17264141488701e-03 + 9.04989311213425e-01 4.70169949588895e-04 + 8.81494872571301e-01 -1.54228412257468e-03 + 8.58261823976117e-01 -4.71323858688598e-03 + 8.35336988680772e-01 -8.89913342673737e-03 + 8.12757098532986e-01 -1.39333287845482e-02 + 7.90553516827622e-01 -1.97204508402206e-02 + 7.68704378080380e-01 -2.60279549350672e-02 + 7.47200735959936e-01 -3.27322719971618e-02 + 7.26054587908095e-01 -3.97754488388574e-02 + 7.05225114492986e-01 -4.69799082848601e-02 + 6.84763435154875e-01 -5.44309327674479e-02 + 6.64571290619340e-01 -6.18254862513697e-02 + 6.44721094918900e-01 -6.93273346207594e-02 + 6.25169625290117e-01 -7.67585322065482e-02 + 6.05945813175358e-01 -8.41464455288096e-02 + 5.87027171152179e-01 -9.14195705532406e-02 + 5.68408265127836e-01 -9.85559847621229e-02 + 5.50064494090816e-01 -1.05480219170930e-01 + 5.32022391078534e-01 -1.12217201602923e-01 + 5.14305379706589e-01 -1.18778483581882e-01 + 4.96856985375564e-01 -1.24998074174480e-01 + 4.79708052221339e-01 -1.30961580748527e-01 + 4.62835414864543e-01 -1.36587172753257e-01 + 4.46243569969428e-01 -1.41875228138195e-01 + 4.29903985709251e-01 -1.46704975300093e-01 + 4.13842250877566e-01 -1.51115352601705e-01 + 3.98044961478621e-01 -1.55046661039126e-01 + 3.82509179271707e-01 -1.58431291993384e-01 + 3.67251501006871e-01 -1.61278156599173e-01 + 3.52292583349217e-01 -1.63600947933904e-01 + 3.37637965766980e-01 -1.65316224048267e-01 + 3.23307637097987e-01 -1.66752310164544e-01 + 3.09331872759859e-01 -1.67700911633119e-01 + 2.95728021634658e-01 -1.68102591062499e-01 + 2.82508440825120e-01 -1.67965908456118e-01 + 2.69692479373679e-01 -1.67345872254253e-01 + 2.57277849131547e-01 -1.66258775918654e-01 + 2.45272663136680e-01 -1.64751212632708e-01 + 2.33687365765199e-01 -1.62810360546622e-01 + 2.22490214641063e-01 -1.60532132121801e-01 + 2.11704186735648e-01 -1.57971495180763e-01 + 2.01286775160185e-01 -1.55229506262782e-01 + 1.91249599793888e-01 -1.52264499706685e-01 + 1.81596180932401e-01 -1.49084933070302e-01 + 1.72302626179722e-01 -1.45794670174339e-01 + 1.63346132459904e-01 -1.42374113100026e-01 + 1.54746809674797e-01 -1.38830155258698e-01 + 1.46486022194054e-01 -1.35188632600945e-01 + 1.38547760953462e-01 -1.31493700970626e-01 + 1.30918888826124e-01 -1.27769213465648e-01 + 1.23603494162898e-01 -1.23994562827742e-01 + 1.16577318947649e-01 -1.20210273993055e-01 + 1.09842714794822e-01 -1.16401422895844e-01 + 1.03419770202037e-01 -1.12543409822447e-01 + 9.72370562742986e-02 -1.08770274872843e-01 + 9.12953749434174e-02 -1.05058596046523e-01 + 8.56266337766400e-02 -1.01348959545830e-01 + 8.02107080494107e-02 -9.76386287937753e-02 + 7.50289238576886e-02 -9.39674688861899e-02 + 7.00863608932403e-02 -9.03441792141839e-02 + 6.53714233337561e-02 -8.68604994148313e-02 + 6.08759530256630e-02 -8.35323692737949e-02 + 5.65902415275960e-02 -8.02398098638649e-02 + 5.25059651925724e-02 -7.69927063770997e-02 + 4.86166628447913e-02 -7.37837554314917e-02 + 4.49077582947745e-02 -7.06237618527845e-02 + 4.13927777039596e-02 -6.74897039413312e-02 + 3.80641981810206e-02 -6.44036061372499e-02 + 3.48929832724408e-02 -6.13951848582158e-02 + 3.18856459672562e-02 -5.84268249770528e-02 + 2.90442132262908e-02 -5.54899494869964e-02 + 2.63811004580753e-02 -5.25920709101139e-02 + 2.38848880530692e-02 -4.97328732122965e-02 + 2.15021569942004e-02 -4.69560380557319e-02 + 1.92408086204874e-02 -4.42606273044788e-02 + 1.71577483979552e-02 -4.15892362716984e-02 + 1.52256501903280e-02 -3.89479589361177e-02 + 1.33940150325620e-02 -3.63811619058724e-02 + 1.16945968480858e-02 -3.38694685065991e-02 + 1.01399947277134e-02 -3.14005699954941e-02 + 8.73005199067174e-03 -2.89778491430780e-02 + 7.47487782179956e-03 -2.65876880354154e-02 + 6.33594551826867e-03 -2.42535714842850e-02 + 5.28961501167165e-03 -2.19902421680995e-02 + 4.32280168968960e-03 -1.98014211395919e-02 + 3.45367866450521e-03 -1.76778349381210e-02 + 2.74078600109631e-03 -1.55973088719527e-02 + 2.13806582939436e-03 -1.35749028237675e-02 + 1.61183106799287e-03 -1.16229600944032e-02 + 1.19278741801813e-03 -9.73562172682337e-03 + 8.52780015436871e-04 -7.91879592506294e-03 + 6.34492750095705e-04 -6.17534236909210e-03 + 3.96951815978446e-04 -4.50663935247869e-03 + 1.88581057949551e-04 -2.91531619917444e-03 + 4.72174234786785e-05 -1.40304801253723e-03 + 0.00000000000000e+00 0.00000000000000e+00 + 4.49286575851582e-05 1.76091109368109e-03 + 1.54712126205946e-04 3.62140154224627e-03 + 3.30083241230729e-04 5.53978075065709e-03 + 5.67107864039499e-04 7.51898308153193e-03 + 8.43717618992945e-04 9.56261412743599e-03 + 1.13820712865826e-03 1.16673197751854e-02 + 1.51620497309045e-03 1.38230510834726e-02 + 2.05010390234215e-03 1.60283976006057e-02 + 2.70761333894050e-03 1.82791506633120e-02 + 3.49886357702170e-03 2.05667372944473e-02 + 4.38563597305350e-03 2.28994709759180e-02 + 5.36480583545219e-03 2.52727779283164e-02 + 6.45176350756975e-03 2.76932258096428e-02 + 7.71493839934877e-03 3.01347479048045e-02 + 9.13811424494260e-03 3.25975238107331e-02 + 1.06948081659682e-02 3.50885690282112e-02 + 1.23665030939463e-02 3.76127912846818e-02 + 1.41631103789096e-02 4.01690740091098e-02 + 1.61006676743100e-02 4.27565790645424e-02 + 1.82006253144294e-02 4.53661056474953e-02 + 2.04339011456132e-02 4.80195490755358e-02 + 2.28313083356356e-02 5.06809426782037e-02 + 2.53998275561691e-02 5.33417422932120e-02 + 2.80831554197667e-02 5.60479549242059e-02 + 3.09172689371117e-02 5.87826801739081e-02 + 3.39613669672685e-02 6.15040472448373e-02 + 3.71885488983873e-02 6.42371788378289e-02 + 4.05844892078012e-02 6.69873627303355e-02 + 4.41615443337093e-02 6.97416261506273e-02 + 4.78986121512040e-02 7.24009578305107e-02 + 5.18317438541022e-02 7.48725582194455e-02 + 5.59775247308777e-02 7.73346153272878e-02 + 6.03069307314000e-02 7.98322938773953e-02 + 6.48317249020550e-02 8.23552542934740e-02 + 6.95740177949655e-02 8.48797840519584e-02 + 7.45346746264872e-02 8.73976434260533e-02 + 7.96940411568568e-02 8.99518601786404e-02 + 8.50751411244750e-02 9.25115521139639e-02 + 9.07047952097347e-02 9.50119363718962e-02 + 9.65644778591387e-02 9.75280567202470e-02 + 1.02654922362443e-01 1.00141176068606e-01 + 1.08991128382069e-01 1.02759655535384e-01 + 1.15580811141506e-01 1.05350177915118e-01 + 1.22442015345549e-01 1.07879078703890e-01 + 1.29581761141198e-01 1.10327867455967e-01 + 1.36985125957807e-01 1.12805201120027e-01 + 1.44649070157922e-01 1.15294515341388e-01 + 1.52601162527081e-01 1.17695162751273e-01 + 1.60849467906986e-01 1.20016136499640e-01 + 1.69400994120977e-01 1.22239166511633e-01 + 1.78257906944928e-01 1.24404435861666e-01 + 1.87423810521919e-01 1.26566367432406e-01 + 1.96913917030033e-01 1.28565322487382e-01 + 2.06714122721902e-01 1.30480002121111e-01 + 2.16843733267671e-01 1.32284460248505e-01 + 2.27313503043412e-01 1.33932897606815e-01 + 2.38116555091135e-01 1.35466082264203e-01 + 2.49270187442578e-01 1.36855347383195e-01 + 2.60783364777495e-01 1.38015044037685e-01 + 2.72649760913212e-01 1.38972898742601e-01 + 2.84865722003232e-01 1.39703902024797e-01 + 2.97442765366165e-01 1.40129901393810e-01 + 3.10371404770489e-01 1.40389901175565e-01 + 3.23663550383385e-01 1.40356686531760e-01 + 3.37302478141465e-01 1.40159944002643e-01 + 3.51279258331868e-01 1.39708203283014e-01 + 3.65599383240653e-01 1.38942103586727e-01 + 3.80266593353821e-01 1.38048333465819e-01 + 3.95276573569828e-01 1.36930305581693e-01 + 4.10621082225397e-01 1.35488514837408e-01 + 4.26300213083275e-01 1.33810605435263e-01 + 4.42308306311055e-01 1.31836152808260e-01 + 4.58654091580520e-01 1.29693294983505e-01 + 4.75315068619854e-01 1.27173492402662e-01 + 4.92299980112839e-01 1.24408547660075e-01 + 5.09602575838928e-01 1.21522453981813e-01 + 5.27212395134502e-01 1.18468930195838e-01 + 5.45136348862968e-01 1.15242151997318e-01 + 5.63358188082521e-01 1.11781777741663e-01 + 5.81885057318307e-01 1.08171778668078e-01 + 6.00697978768359e-01 1.04372430246799e-01 + 6.19778853163952e-01 1.00342858722927e-01 + 6.39128296470107e-01 9.62399740334075e-02 + 6.58737479416311e-01 9.19824964120890e-02 + 6.78606901768962e-01 8.76000132289643e-02 + 6.98713465939465e-01 8.30431156104294e-02 + 7.19053735025290e-01 7.83520462505258e-02 + 7.39609238737388e-01 7.34999974962512e-02 + 7.60379187011757e-01 6.85439537095766e-02 + 7.81346186916718e-01 6.34710892603186e-02 + 8.02497578082114e-01 5.82840033620211e-02 + 8.23825251477110e-01 5.29994283777580e-02 + 8.45332549847506e-01 4.76847762917876e-02 + 8.66989872326120e-01 4.22607936796464e-02 + 8.88796133601469e-01 3.67689289229451e-02 + 9.10777419149797e-01 3.13903865017990e-02 + 9.32946008475891e-01 2.60399205588807e-02 + 9.55291210260545e-01 2.03661935434009e-02 + 9.77655302958250e-01 1.44867409656004e-02 + 1.00000000000000e+00 8.36305924051618e-03 diff --git a/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF14_Coords.txt b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF14_Coords.txt new file mode 100644 index 00000000..21ac9bc9 --- /dev/null +++ b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF14_Coords.txt @@ -0,0 +1,208 @@ + 201 NumCoords ! The number of coordinates in the airfoil shape file (including an extra coordinate for airfoil reference). Set to zero if coordinates not included. +! ......... x-y coordinates are next if NumCoords > 0 ............. +! x-y coordinate of airfoil reference +! x/c y/c + 0.250000 0 +! coordinates of airfoil shape +! interpolation to 200 points +! x/c y/c + 1.00000000000000e+00 -8.14836236062521e-03 + 9.75605454220754e-01 -3.27870018079412e-03 + 9.50836784314451e-01 -2.20900988818551e-04 + 9.26031070036306e-01 8.25225422744434e-04 + 9.01354150415546e-01 4.63723364948677e-05 + 8.76856729032888e-01 -2.12212287818620e-03 + 8.52628325860033e-01 -5.49153345932107e-03 + 8.28726407818510e-01 -9.92913740060339e-03 + 8.05179636734850e-01 -1.52183220368432e-02 + 7.82028005324449e-01 -2.12905294714742e-02 + 7.59247407101620e-01 -2.78817020291902e-02 + 7.36825672022388e-01 -3.48456742332678e-02 + 7.14771415904034e-01 -4.21126282820779e-02 + 6.93052137845832e-01 -4.95161086094975e-02 + 6.71727481343893e-01 -5.71636330448956e-02 + 6.50688318620596e-01 -6.46990238340603e-02 + 6.30027418222565e-01 -7.23373717103563e-02 + 6.09682760834827e-01 -7.98549524801710e-02 + 5.89688828203817e-01 -8.73005491504785e-02 + 5.70031102500545e-01 -9.46078346312720e-02 + 5.50710313744022e-01 -1.01755382714016e-01 + 5.31704773200269e-01 -1.08661561649762e-01 + 5.13040076772302e-01 -1.15360198522277e-01 + 4.94731072648672e-01 -1.21856401857074e-01 + 4.76720063365871e-01 -1.27964705191137e-01 + 4.59050447577727e-01 -1.33798894725046e-01 + 4.41698554665827e-01 -1.39265991429221e-01 + 4.24673935956588e-01 -1.44379903497306e-01 + 4.07943877996459e-01 -1.48996777520091e-01 + 3.91529590322889e-01 -1.53147337031555e-01 + 3.75425881926708e-01 -1.56786941146897e-01 + 3.59631453908511e-01 -1.59839992659012e-01 + 3.44161400760639e-01 -1.62311690399160e-01 + 3.29035392588028e-01 -1.64209813619226e-01 + 3.14263667203509e-01 -1.65451316764320e-01 + 2.99868746495612e-01 -1.66506903639003e-01 + 2.85878821421829e-01 -1.67028933600720e-01 + 2.72314348501668e-01 -1.66931590818852e-01 + 2.59190034344532e-01 -1.66240903049082e-01 + 2.46523097896223e-01 -1.65015711658322e-01 + 2.34311085993631e-01 -1.63309762544107e-01 + 2.22557973039563e-01 -1.61179016172101e-01 + 2.11273825191574e-01 -1.58619367104621e-01 + 2.00416162834866e-01 -1.55781295522583e-01 + 1.90010573443506e-01 -1.52649361562255e-01 + 1.80003508496110e-01 -1.49375875213019e-01 + 1.70407177602816e-01 -1.45918068123790e-01 + 1.61224702358730e-01 -1.42273052042672e-01 + 1.52427517023986e-01 -1.38535454147255e-01 + 1.43981471299467e-01 -1.34741684356880e-01 + 1.35915137076383e-01 -1.30853570083458e-01 + 1.28205843380849e-01 -1.26896454867671e-01 + 1.20831500156688e-01 -1.22926515095291e-01 + 1.13776200252657e-01 -1.18962260383654e-01 + 1.07043970465416e-01 -1.14984403533098e-01 + 1.00604490983182e-01 -1.11043538945192e-01 + 9.44627247382671e-02 -1.07112169597954e-01 + 8.86436371027153e-02 -1.03150305327463e-01 + 8.30609551236505e-02 -9.93048193507565e-02 + 7.77158685764800e-02 -9.55452265219299e-02 + 7.26442623777319e-02 -9.18109492601984e-02 + 6.78200455328382e-02 -8.81164194990571e-02 + 6.32251003858072e-02 -8.44890217245990e-02 + 5.88664059457334e-02 -8.09291839835693e-02 + 5.47314426912757e-02 -7.75147830298754e-02 + 5.08048887650857e-02 -7.42689802432870e-02 + 4.70774277960059e-02 -7.10840961776320e-02 + 4.35439177679982e-02 -6.79622663696009e-02 + 4.01931090877671e-02 -6.49028866719955e-02 + 3.70071961558051e-02 -6.19186097345931e-02 + 3.39928055580254e-02 -5.89938489520709e-02 + 3.11577683019826e-02 -5.61235560760588e-02 + 2.84775442869274e-02 -5.33253098749644e-02 + 2.59337722860059e-02 -5.06003306707210e-02 + 2.35351879537169e-02 -4.79341414523893e-02 + 2.13137371577664e-02 -4.53052669924546e-02 + 1.92412232739687e-02 -4.27265135238339e-02 + 1.72551808149047e-02 -4.02460777005286e-02 + 1.53775125192213e-02 -3.78461069409167e-02 + 1.36669286314092e-02 -3.54751904767474e-02 + 1.20867763486272e-02 -3.31490567840202e-02 + 1.05884996763417e-02 -3.09033988993154e-02 + 9.20425453765281e-03 -2.87165660887120e-02 + 7.94657176624660e-03 -2.65748008857490e-02 + 6.81901031712526e-03 -2.44798541378323e-02 + 5.82356366307817e-03 -2.24237272913497e-02 + 4.92174384636360e-03 -2.04275731539013e-02 + 4.09719664088157e-03 -1.84975012786712e-02 + 3.32633841273745e-03 -1.66402354620686e-02 + 2.63006056419046e-03 -1.48461343785805e-02 + 2.07265379541992e-03 -1.30914265545919e-02 + 1.60475669651842e-03 -1.13896387204853e-02 + 1.19362491575511e-03 -9.75207784151342e-03 + 8.61158304775857e-04 -8.17325143675256e-03 + 5.92658871339785e-04 -6.65366840829812e-03 + 4.11941085518658e-04 -5.19491140252507e-03 + 2.54556569896829e-04 -3.79658841465355e-03 + 1.28113832478964e-04 -2.46056989256330e-03 + 3.57617220409199e-05 -1.18717030094207e-03 + 0.00000000000000e+00 0.00000000000000e+00 + 3.47906660476153e-05 1.35864880901149e-03 + 1.15168885058535e-04 2.77417290109050e-03 + 2.30376916315236e-04 4.24252249803400e-03 + 3.87976131495443e-04 5.76601626174964e-03 + 5.74526506204122e-04 7.34806995808761e-03 + 7.95654255520616e-04 8.98493392763457e-03 + 1.12021971636174e-03 1.06662550219730e-02 + 1.56154664930487e-03 1.23953998641279e-02 + 2.08683544746350e-03 1.41733115513416e-02 + 2.71224085851922e-03 1.59928312616081e-02 + 3.43035954718513e-03 1.78573300023999e-02 + 4.21435009067654e-03 1.97747226754239e-02 + 5.09317032805970e-03 2.17377376445490e-02 + 6.12872222137403e-03 2.37226879106243e-02 + 7.28358292664935e-03 2.57436355827732e-02 + 8.54729910157088e-03 2.78048612104546e-02 + 9.92972828959359e-03 2.98969637573703e-02 + 1.14264946100910e-02 3.20287229123090e-02 + 1.30302058764849e-02 3.42098777797921e-02 + 1.47545509310666e-02 3.64362116507928e-02 + 1.65895142682137e-02 3.87188939282128e-02 + 1.85799091430884e-02 4.10158975075125e-02 + 2.07318790579148e-02 4.33277140117620e-02 + 2.29786410496385e-02 4.57116743283601e-02 + 2.53553835037421e-02 4.81450487278177e-02 + 2.79278776797602e-02 5.05737523231150e-02 + 3.06684104757498e-02 5.30293753541954e-02 + 3.35549896302923e-02 5.55320353345598e-02 + 3.66048832549710e-02 5.80672661628428e-02 + 3.98160878278975e-02 6.05922518843348e-02 + 4.32097657635900e-02 6.30632131339738e-02 + 4.68004477364611e-02 6.55508747412392e-02 + 5.05703468888338e-02 6.80833115592091e-02 + 5.45293129960311e-02 7.06568325856674e-02 + 5.87044042125043e-02 7.32381347585862e-02 + 6.30971043353738e-02 7.58315677252795e-02 + 6.76867916036615e-02 7.84763490181517e-02 + 7.24967292572105e-02 8.11447924400529e-02 + 7.75489190519818e-02 8.38012218025252e-02 + 8.28379430912991e-02 8.64755853792752e-02 + 8.83700160522555e-02 8.92311260118967e-02 + 9.41546877815251e-02 9.20147089552618e-02 + 1.00200275044183e-01 9.47925250920637e-02 + 1.06519506627458e-01 9.75499482587641e-02 + 1.13121273553931e-01 1.00272215404985e-01 + 1.20000865270765e-01 1.03022793377647e-01 + 1.27160568795956e-01 1.05784624380971e-01 + 1.34629377330607e-01 1.08475019956957e-01 + 1.42410501436542e-01 1.11115501827654e-01 + 1.50511658880668e-01 1.13695222223560e-01 + 1.58939652295794e-01 1.16224524312285e-01 + 1.67700467710513e-01 1.18723937489766e-01 + 1.76815783980035e-01 1.21067625942295e-01 + 1.86265538652919e-01 1.23365512977448e-01 + 1.96071866452217e-01 1.25554708540608e-01 + 2.06250547051562e-01 1.27593275787970e-01 + 2.16789870603760e-01 1.29541754711146e-01 + 2.27709471480002e-01 1.31337948456032e-01 + 2.39023607624358e-01 1.32877774715532e-01 + 2.50725312099806e-01 1.34211878219550e-01 + 2.62813163393733e-01 1.35317273908679e-01 + 2.75300589304416e-01 1.36105292149500e-01 + 2.88173680979742e-01 1.36733482190757e-01 + 3.01443959248928e-01 1.37027602201975e-01 + 3.15100693572125e-01 1.37162360722735e-01 + 3.29141136015704e-01 1.37051985111160e-01 + 3.43566633885766e-01 1.36597826483452e-01 + 3.58379996607331e-01 1.36020493099717e-01 + 3.73577404766437e-01 1.35212892447741e-01 + 3.89153622315017e-01 1.34072142153192e-01 + 4.05108094120761e-01 1.32686673560345e-01 + 4.21433969423481e-01 1.30984053441620e-01 + 4.38142341403862e-01 1.29118324458878e-01 + 4.55206328011914e-01 1.26836633577195e-01 + 4.72639853963158e-01 1.24300133080523e-01 + 4.90435271070256e-01 1.21679117794261e-01 + 5.08579010309887e-01 1.18895867110872e-01 + 5.27074571229468e-01 1.15918274965440e-01 + 5.45906008138401e-01 1.12688629331682e-01 + 5.65078719861412e-01 1.09292084145262e-01 + 5.84572298052518e-01 1.05676186408607e-01 + 6.04369364403524e-01 1.01804075775369e-01 + 6.24472197888980e-01 9.77950051523939e-02 + 6.44868545310258e-01 9.36084798785348e-02 + 6.65553461692358e-01 8.92765243340495e-02 + 6.86500234562328e-01 8.47365603510263e-02 + 7.07706100172094e-01 8.00475004561028e-02 + 7.29151865146187e-01 7.51929614727690e-02 + 7.50834276036418e-01 7.02319315014268e-02 + 7.72727461247450e-01 6.51263205099363e-02 + 7.94812249063048e-01 5.98701925922095e-02 + 8.17078362972243e-01 5.44954720205527e-02 + 8.39529154287222e-01 4.90934541266714e-02 + 8.62128984506176e-01 4.35866611147249e-02 + 8.84858418262504e-01 3.79716307048406e-02 + 9.07728679674592e-01 3.23837149939797e-02 + 9.30734095888120e-01 2.68027303925987e-02 + 9.53837027134021e-01 2.09467195741978e-02 + 9.76936319972422e-01 1.49132298932001e-02 + 1.00000000000000e+00 8.66710884250080e-03 diff --git a/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF15_Coords.txt b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF15_Coords.txt new file mode 100644 index 00000000..670d0c5a --- /dev/null +++ b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF15_Coords.txt @@ -0,0 +1,208 @@ + 201 NumCoords ! The number of coordinates in the airfoil shape file (including an extra coordinate for airfoil reference). Set to zero if coordinates not included. +! ......... x-y coordinates are next if NumCoords > 0 ............. +! x-y coordinate of airfoil reference +! x/c y/c + 0.250000 0 +! coordinates of airfoil shape +! interpolation to 200 points +! x/c y/c + 1.00000000000000e+00 -8.57879977773810e-03 + 9.75180222150308e-01 -3.03879904135747e-03 + 9.49954708363444e-01 -1.26002872729501e-04 + 9.24617663626292e-01 6.10122226095701e-04 + 8.99362589909934e-01 -2.13375521927681e-04 + 8.74301657857705e-01 -2.47307597608542e-03 + 8.49512831893362e-01 -5.95848312946069e-03 + 8.25060132654372e-01 -1.05432097366251e-02 + 8.00967349009157e-01 -1.59814342852104e-02 + 7.77279396459348e-01 -2.22202726470426e-02 + 7.53971146353458e-01 -2.89772479518455e-02 + 7.31028686926424e-01 -3.60929872413459e-02 + 7.08458616265561e-01 -4.34907379085029e-02 + 6.86233439551971e-01 -5.10105449101421e-02 + 6.64417721038235e-01 -5.87729225500483e-02 + 6.42896424356607e-01 -6.63906320145616e-02 + 6.21774241465352e-01 -7.41087631455492e-02 + 6.00977841522425e-01 -8.16768344389446e-02 + 5.80544552788493e-01 -8.91561467273735e-02 + 5.60464827414216e-01 -9.64833988179528e-02 + 5.40743392390515e-01 -1.03637454592294e-01 + 5.21360556780428e-01 -1.10533080197566e-01 + 5.02340910284044e-01 -1.17209304289204e-01 + 4.83693742857298e-01 -1.23667469493609e-01 + 4.65360905225594e-01 -1.29710726001548e-01 + 4.47393349439378e-01 -1.35469330395386e-01 + 4.29767286515700e-01 -1.40843787417424e-01 + 4.12495217820767e-01 -1.45855913618906e-01 + 3.95542115741603e-01 -1.50348364394606e-01 + 3.78926510481714e-01 -1.54347061753637e-01 + 3.62648170482185e-01 -1.57816166203811e-01 + 3.46706871509637e-01 -1.60675411249642e-01 + 3.31116764742986e-01 -1.62927825900264e-01 + 3.15896874263702e-01 -1.64577732807176e-01 + 3.01060219418983e-01 -1.65542318105973e-01 + 2.86630760513041e-01 -1.66019067198897e-01 + 2.72635352957487e-01 -1.65852810272617e-01 + 2.59096229086319e-01 -1.65053656791642e-01 + 2.46029444917578e-01 -1.63674484017382e-01 + 2.33450927162206e-01 -1.61779021413358e-01 + 2.21358148093932e-01 -1.59458179997197e-01 + 2.09752590238530e-01 -1.56768645463127e-01 + 1.98644065634366e-01 -1.53708652225252e-01 + 1.87983838111383e-01 -1.50468466633829e-01 + 1.77798959359292e-01 -1.46968929468240e-01 + 1.68029515979667e-01 -1.43391369897358e-01 + 1.58688054711323e-01 -1.39690800395147e-01 + 1.49777434120809e-01 -1.35854606762879e-01 + 1.41266364582040e-01 -1.31957036662395e-01 + 1.33114043882986e-01 -1.28072240442312e-01 + 1.25353982091811e-01 -1.24123605323377e-01 + 1.17961213252232e-01 -1.20147065379440e-01 + 1.10910137898332e-01 -1.16185429245801e-01 + 1.04183249914720e-01 -1.12256793878014e-01 + 9.77845035922472e-02 -1.08341834070059e-01 + 9.16800568181114e-02 -1.04487577173595e-01 + 8.58763837804680e-02 -1.00669929174109e-01 + 8.04013343441990e-02 -9.68347298049542e-02 + 7.51601956348723e-02 -9.31177415424908e-02 + 7.01543935952098e-02 -8.94997948476300e-02 + 6.54219938355571e-02 -8.59156686036492e-02 + 6.09334040261291e-02 -8.23945222782936e-02 + 5.66708598548473e-02 -7.89496641080547e-02 + 5.26424925924951e-02 -7.55684130212430e-02 + 4.88353267109018e-02 -7.22706692662718e-02 + 4.52299098002129e-02 -6.90769445598798e-02 + 4.18171486326621e-02 -6.59585470797291e-02 + 3.85937390562270e-02 -6.29132740880722e-02 + 3.55456313710721e-02 -5.99446421848028e-02 + 3.26532165695984e-02 -5.70661627728155e-02 + 2.99191791468483e-02 -5.42663897359114e-02 + 2.73603366698335e-02 -5.15240489459803e-02 + 2.49547621710270e-02 -4.88496591224952e-02 + 2.26696019923393e-02 -4.62677203676052e-02 + 2.05173895362584e-02 -4.37606410408951e-02 + 1.85413689047946e-02 -4.12897613211990e-02 + 1.67039255897644e-02 -3.88748760932536e-02 + 1.49376604499564e-02 -3.65661749206043e-02 + 1.32724098833742e-02 -3.43362370571288e-02 + 1.17676398242478e-02 -3.21379214236623e-02 + 1.03812841619170e-02 -2.99928372995567e-02 + 9.06612278982865e-03 -2.79311924288680e-02 + 7.85471709046639e-03 -2.59296320464281e-02 + 6.75962346486767e-03 -2.39733845222929e-02 + 5.78638085277238e-03 -2.20635808604033e-02 + 4.93219411743517e-03 -2.01957483008656e-02 + 4.15866656660073e-03 -1.83895524002002e-02 + 3.45414954175195e-03 -1.66456540575484e-02 + 2.78923310544400e-03 -1.49722402872741e-02 + 2.18613805623396e-03 -1.33598127496920e-02 + 1.71216161569515e-03 -1.17839473069557e-02 + 1.31624248102220e-03 -1.02571525116732e-02 + 9.66801840458578e-04 -8.79003718291119e-03 + 6.80319528299336e-04 -7.37728839044000e-03 + 4.49100581451274e-04 -6.01658261674601e-03 + 2.83701305712447e-04 -4.70870707990412e-03 + 1.71327286198412e-04 -3.45212068865394e-03 + 9.27710524239121e-05 -2.24812638028363e-03 + 2.90659238934096e-05 -1.09605843814913e-03 + 0.00000000000000e+00 0.00000000000000e+00 + 2.88650625107761e-05 1.11148823849564e-03 + 9.20560654498922e-05 2.26693180022457e-03 + 1.72099085901139e-04 3.47224142051019e-03 + 2.83274561762190e-04 4.72937588738418e-03 + 4.17185695243679e-04 6.04164001396517e-03 + 5.97882203243190e-04 7.40505294611765e-03 + 8.95891727887411e-04 8.80908372794426e-03 + 1.28619996129368e-03 1.02598911578957e-02 + 1.73718091964475e-03 1.17614295105485e-02 + 2.26889766516844e-03 1.33073665302488e-02 + 2.89290184609361e-03 1.48981843737658e-02 + 3.56863592046535e-03 1.65490975122241e-02 + 4.33167262281806e-03 1.82447453137629e-02 + 5.23928473841845e-03 1.99628317108720e-02 + 6.24211877712485e-03 2.17255330691366e-02 + 7.33964056226407e-03 2.35355313731346e-02 + 8.55899423724526e-03 2.53750621882832e-02 + 9.88712266524690e-03 2.72586895159738e-02 + 1.13020867063170e-02 2.92023348035768e-02 + 1.28124619939745e-02 3.12046945194575e-02 + 1.44198946335000e-02 3.32706688249579e-02 + 1.61778638266544e-02 3.53546883232132e-02 + 1.80925347692918e-02 3.74625260070275e-02 + 2.00910255479398e-02 3.96581315151937e-02 + 2.22073480805733e-02 4.19153679037419e-02 + 2.45104741518688e-02 4.41730112135886e-02 + 2.69725227219957e-02 4.64664319277826e-02 + 2.95672369905170e-02 4.88244154637241e-02 + 3.23149834672359e-02 5.12316228766112e-02 + 3.52251763885414e-02 5.36850922615401e-02 + 3.83099350602331e-02 5.61720264031417e-02 + 4.15824489104227e-02 5.86905077324653e-02 + 4.50317770709382e-02 6.12582681605947e-02 + 4.86666503586395e-02 6.38753760166677e-02 + 5.25170727043328e-02 6.65025186818970e-02 + 5.65850189187534e-02 6.91518398462091e-02 + 6.08491647683366e-02 7.18603850558563e-02 + 6.53325801131270e-02 7.46028792309043e-02 + 7.00543348142427e-02 7.73615611579748e-02 + 7.50171013293054e-02 8.01381142978750e-02 + 8.02306159895163e-02 8.29454075566739e-02 + 8.57012088705319e-02 8.57724141117260e-02 + 9.14370395472359e-02 8.86083733592826e-02 + 9.74471306573141e-02 9.14506955541571e-02 + 1.03741642665461e-01 9.42869115799166e-02 + 1.10322431016719e-01 9.71366683959768e-02 + 1.17195331455295e-01 9.99963817208149e-02 + 1.24389884664589e-01 1.02804765589993e-01 + 1.31905935056049e-01 1.05580086008781e-01 + 1.39751456026638e-01 1.08317196263952e-01 + 1.47936168023821e-01 1.11006216128796e-01 + 1.56467558128623e-01 1.13642271424664e-01 + 1.65371163914618e-01 1.16141616432774e-01 + 1.74623252652850e-01 1.18621015919461e-01 + 1.84247428093051e-01 1.20997142483866e-01 + 1.94262496093302e-01 1.23226242267470e-01 + 2.04653672488981e-01 1.25380363541681e-01 + 2.15441765864240e-01 1.27378959185081e-01 + 2.26644243180055e-01 1.29123968217828e-01 + 2.38253845273158e-01 1.30674870254090e-01 + 2.50270552701415e-01 1.31999307783067e-01 + 2.62708751790901e-01 1.33015597369151e-01 + 2.75551725512235e-01 1.33872159509066e-01 + 2.88810665433822e-01 1.34378959676908e-01 + 3.02478807217932e-01 1.34723171413855e-01 + 3.16557400521368e-01 1.34828318979527e-01 + 3.31045159681679e-01 1.34573337077908e-01 + 3.45944140981529e-01 1.34191735267806e-01 + 3.61250730235273e-01 1.33577791174796e-01 + 3.76961614806380e-01 1.32641039909018e-01 + 3.93075978637921e-01 1.31467341415961e-01 + 4.09586247490783e-01 1.29983874522969e-01 + 4.26504850189084e-01 1.28372193187690e-01 + 4.43802359792042e-01 1.26353263881723e-01 + 4.61495724587332e-01 1.24138877363526e-01 + 4.79576454948711e-01 1.21758646632159e-01 + 4.98029186432348e-01 1.19133369177162e-01 + 5.16855180283856e-01 1.16301424988927e-01 + 5.36038549215196e-01 1.13206639039446e-01 + 5.55583719652262e-01 1.09934856544340e-01 + 5.75469608979237e-01 1.06426184782536e-01 + 5.95679247848144e-01 1.02646109224194e-01 + 6.16216032509872e-01 9.86875548679134e-02 + 6.37065764297449e-01 9.45384567802663e-02 + 6.58220009598337e-01 9.02324184327279e-02 + 6.79649739397516e-01 8.56983061171984e-02 + 7.01352675498130e-01 8.10067998035236e-02 + 7.23309367720016e-01 7.61487654794268e-02 + 7.45514874390413e-01 7.11835831183337e-02 + 7.67937997489119e-01 6.60570021231055e-02 + 7.90555709099499e-01 6.07584149955232e-02 + 8.13356480155146e-01 5.53297489402000e-02 + 8.36343320325429e-01 4.98760881816722e-02 + 8.59476947043660e-01 4.43220559191783e-02 + 8.82726076021484e-01 3.86348982394945e-02 + 9.06091895800112e-01 3.29178055135213e-02 + 9.29556869258233e-01 2.71942568107446e-02 + 9.53065562517705e-01 2.12312867691710e-02 + 9.76555746470235e-01 1.51116304681152e-02 + 1.00000000000000e+00 8.80279316603190e-03 diff --git a/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF16_Coords.txt b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF16_Coords.txt new file mode 100644 index 00000000..c1f50c91 --- /dev/null +++ b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF16_Coords.txt @@ -0,0 +1,208 @@ + 201 NumCoords ! The number of coordinates in the airfoil shape file (including an extra coordinate for airfoil reference). Set to zero if coordinates not included. +! ......... x-y coordinates are next if NumCoords > 0 ............. +! x-y coordinate of airfoil reference +! x/c y/c + 0.250000 0 +! coordinates of airfoil shape +! interpolation to 200 points +! x/c y/c + 1.00000000000000e+00 -7.93823528916634e-03 + 9.75306611523266e-01 -3.07804362808370e-03 + 9.50254896398834e-01 2.12362996603380e-05 + 9.25086956564820e-01 1.10034879293892e-03 + 8.99988535976524e-01 4.37422920277549e-04 + 8.75072599857149e-01 -1.69228312874642e-03 + 8.50417485943084e-01 -5.02575124436309e-03 + 8.26088106219083e-01 -9.48963995265479e-03 + 8.02111382252523e-01 -1.48157088586162e-02 + 7.78533224241522e-01 -2.09559594834436e-02 + 7.55333131164625e-01 -2.76360667094703e-02 + 7.32498770899621e-01 -3.46931927585546e-02 + 7.10037524800713e-01 -4.20512954807589e-02 + 6.87921684496055e-01 -4.95447286109428e-02 + 6.66209179710118e-01 -5.72757010622818e-02 + 6.44793205529505e-01 -6.48779142100834e-02 + 6.23770247083330e-01 -7.25767710634749e-02 + 6.03070773283972e-01 -8.01314038494710e-02 + 5.82725782097447e-01 -8.75866260531345e-02 + 5.62727405516286e-01 -9.48842528629214e-02 + 5.43080423918886e-01 -1.02003644748097e-01 + 5.23763733755852e-01 -1.08853301029009e-01 + 5.04803219809205e-01 -1.15477844917736e-01 + 4.86206982188546e-01 -1.21874673443526e-01 + 4.67921007083763e-01 -1.27856568331733e-01 + 4.49992820623389e-01 -1.33542654805615e-01 + 4.32401794865636e-01 -1.38840810792771e-01 + 4.15160522435188e-01 -1.43774009354166e-01 + 3.98236888852800e-01 -1.48190991673080e-01 + 3.81648251477225e-01 -1.52112731931741e-01 + 3.65396878028470e-01 -1.55516473547203e-01 + 3.49482408564341e-01 -1.58321238170515e-01 + 3.33919160469124e-01 -1.60534240376794e-01 + 3.18725408829206e-01 -1.62165537784395e-01 + 3.03913049141917e-01 -1.63131873998207e-01 + 2.89504737395872e-01 -1.62983765163967e-01 + 2.75525761184225e-01 -1.62070670020849e-01 + 2.61996790164123e-01 -1.60600815773790e-01 + 2.48932908441187e-01 -1.58650156209932e-01 + 2.36348800371720e-01 -1.56288718478177e-01 + 2.24242074483076e-01 -1.53625685704211e-01 + 2.12614132311826e-01 -1.50704613076576e-01 + 2.01474116266847e-01 -1.47515164268461e-01 + 1.90775946871820e-01 -1.44259340711770e-01 + 1.80545164370369e-01 -1.40816254075015e-01 + 1.70726148932411e-01 -1.37356122795043e-01 + 1.61329495142793e-01 -1.33838435774938e-01 + 1.52357448812365e-01 -1.30248116217731e-01 + 1.43781676609354e-01 -1.26622879278557e-01 + 1.35562251699688e-01 -1.23048941083730e-01 + 1.27731865989209e-01 -1.19425293871551e-01 + 1.20263781459649e-01 -1.15816680044401e-01 + 1.13136940952170e-01 -1.12220007869416e-01 + 1.06332983042845e-01 -1.08662489701008e-01 + 9.98554576560956e-02 -1.05123339035014e-01 + 9.36729639947835e-02 -1.01629914852298e-01 + 8.77889829403561e-02 -9.81820383630434e-02 + 8.22313494306295e-02 -9.47155808667247e-02 + 7.69114078116147e-02 -9.13308647018588e-02 + 7.18269333109061e-02 -8.80418761209455e-02 + 6.70154064102991e-02 -8.47739827365595e-02 + 6.24469306153174e-02 -8.15646647777206e-02 + 5.81057659587854e-02 -7.84140549690817e-02 + 5.40009405345228e-02 -7.52947049856435e-02 + 5.01151207789006e-02 -7.21659059076321e-02 + 4.64322700792648e-02 -6.90335942126407e-02 + 4.29462331812666e-02 -6.59671142994205e-02 + 3.96515804572136e-02 -6.29681996718810e-02 + 3.65329345743545e-02 -6.00437178811974e-02 + 3.35738970738148e-02 -5.72025031652544e-02 + 3.07754335365257e-02 -5.44358564951100e-02 + 2.81537659173496e-02 -5.17226337871633e-02 + 2.56886770890630e-02 -4.90717427799052e-02 + 2.33482991143229e-02 -4.65080355566962e-02 + 2.11432730232991e-02 -4.40159414301263e-02 + 1.91121471256101e-02 -4.15606205415437e-02 + 1.72228999311958e-02 -3.91575871889248e-02 + 1.54064395993220e-02 -3.68520424585129e-02 + 1.36928020357784e-02 -3.46229069295389e-02 + 1.21373998162167e-02 -3.24269429373621e-02 + 1.07044618156111e-02 -3.02820978142858e-02 + 9.34868730826734e-03 -2.82170700487391e-02 + 8.09806623056062e-03 -2.62111289422148e-02 + 6.96372181943001e-03 -2.42506526569285e-02 + 5.96056834155680e-03 -2.23318948971137e-02 + 5.06965708895582e-03 -2.04584451649110e-02 + 4.26820207826318e-03 -1.86422076010040e-02 + 3.54215279838966e-03 -1.68853270402674e-02 + 2.85815863780286e-03 -1.51976459649791e-02 + 2.24323664486902e-03 -1.35681174800671e-02 + 1.75728174742475e-03 -1.19752101824980e-02 + 1.34793914004162e-03 -1.04318177524506e-02 + 9.90510266959983e-04 -8.94698512072236e-03 + 6.97578703019438e-04 -7.51579339168028e-03 + 4.64357280248315e-04 -6.13612031461294e-03 + 2.88591972559368e-04 -4.81032939412014e-03 + 1.72652071928442e-04 -3.53504260318557e-03 + 9.21726822772373e-05 -2.31236956248856e-03 + 2.89749158143047e-05 -1.14152595228739e-03 + 0.00000000000000e+00 0.00000000000000e+00 + 2.89846382908482e-05 1.09904377509191e-03 + 9.25460105131971e-05 2.26825426701565e-03 + 1.77372928637046e-04 3.48749114259613e-03 + 2.94928045666597e-04 4.75871421546040e-03 + 4.43018528169673e-04 6.08403094200768e-03 + 6.38312963887756e-04 7.46056696755252e-03 + 9.47163065524872e-04 8.87928204628239e-03 + 1.36292248354851e-03 1.03385546497900e-02 + 1.83694236418441e-03 1.18499779537360e-02 + 2.40074018468558e-03 1.34014033663973e-02 + 3.05594814662641e-03 1.49976678162017e-02 + 3.77032037989221e-03 1.66497807270228e-02 + 4.57488786576987e-03 1.83443029444178e-02 + 5.51906408703589e-03 2.00632619669774e-02 + 6.56072342496301e-03 2.18246212199481e-02 + 7.69623508636216e-03 2.36337857570079e-02 + 8.95571256166709e-03 2.54702712422116e-02 + 1.03262325097732e-02 2.73482935706184e-02 + 1.17850925399475e-02 2.92850723449938e-02 + 1.33375184491728e-02 3.12822963331383e-02 + 1.49920040237809e-02 3.33377667408644e-02 + 1.67963509381930e-02 3.54114606810732e-02 + 1.87564987080519e-02 3.75086023081501e-02 + 2.08048274019325e-02 3.96894126704762e-02 + 2.29716484700822e-02 4.19312226540401e-02 + 2.53216431358212e-02 4.41765315953156e-02 + 2.78298220840403e-02 4.64577629177545e-02 + 3.04725601623169e-02 4.88011066487437e-02 + 3.32695085116736e-02 5.11918075676120e-02 + 3.62304186897929e-02 5.36280031772383e-02 + 3.93644755511771e-02 5.61022315336534e-02 + 4.26868496705988e-02 5.86057232062309e-02 + 4.61876578605174e-02 6.11553846039597e-02 + 4.98741851089849e-02 6.37532547016415e-02 + 5.37745202719990e-02 6.63631960936247e-02 + 5.78890274684652e-02 6.90003260469755e-02 + 6.22045848623571e-02 7.16867591984326e-02 + 6.67395204425100e-02 7.44058004604966e-02 + 7.15094552811985e-02 7.71467339233253e-02 + 7.65211067667525e-02 7.99024876975873e-02 + 8.17838450454122e-02 8.26301768788084e-02 + 8.73028349577319e-02 8.53481713528125e-02 + 9.30858323711997e-02 8.80783750999101e-02 + 9.91416946670507e-02 9.08176986892974e-02 + 1.05480595351981e-01 9.35548293971554e-02 + 1.12106860649107e-01 9.62797051576990e-02 + 1.19024136382428e-01 9.90174394136982e-02 + 1.26260042330622e-01 1.01725417281737e-01 + 1.33816269566989e-01 1.04399273374098e-01 + 1.41700663462267e-01 1.07033756577881e-01 + 1.49922921245669e-01 1.09617507912382e-01 + 1.58490745848084e-01 1.12140288851728e-01 + 1.67427226610566e-01 1.14558206235614e-01 + 1.76710282027346e-01 1.16962741891360e-01 + 1.86363310666109e-01 1.19272582161213e-01 + 1.96405140293252e-01 1.21436031107907e-01 + 2.06821300548881e-01 1.23525479904894e-01 + 2.17631928576255e-01 1.25464812094116e-01 + 2.28852962522468e-01 1.27193749895941e-01 + 2.40477755282815e-01 1.28758039445176e-01 + 2.52507693678930e-01 1.30101102154715e-01 + 2.64955599100463e-01 1.31171639589549e-01 + 2.77806279246518e-01 1.32075007668201e-01 + 2.91070185192249e-01 1.32646573696457e-01 + 3.04740840328737e-01 1.33041903853136e-01 + 3.18819477395129e-01 1.33195283275007e-01 + 3.33304350362167e-01 1.32986169941820e-01 + 3.48197166977535e-01 1.32632958624357e-01 + 3.63493940108890e-01 1.32044025079949e-01 + 3.79191584895447e-01 1.31162317872549e-01 + 3.95288926848852e-01 1.30062172860921e-01 + 4.11778548872039e-01 1.28686018034213e-01 + 4.28672318266481e-01 1.27234783277367e-01 + 4.45941423639317e-01 1.25432754513171e-01 + 4.63601280756515e-01 1.23542253443373e-01 + 4.81644473880432e-01 1.21300435261224e-01 + 5.00056154441041e-01 1.18664422872359e-01 + 5.18836063389421e-01 1.15815814392759e-01 + 5.37969499408613e-01 1.12707530577688e-01 + 5.57460349222905e-01 1.09422776572642e-01 + 5.77288515939648e-01 1.05906885195990e-01 + 5.97436626517306e-01 1.02120358117792e-01 + 6.17906665003925e-01 9.81468229100023e-02 + 6.38686205928774e-01 9.39865902403502e-02 + 6.59766571546815e-01 8.96723879840407e-02 + 6.81119084918578e-01 8.51320545501444e-02 + 7.02741779443877e-01 8.04384800208977e-02 + 7.24615479257981e-01 7.55830551158126e-02 + 7.46734371501449e-01 7.06203776437117e-02 + 7.69068303705288e-01 6.55004145708381e-02 + 7.91594648342087e-01 6.02131883818753e-02 + 8.14301397875068e-01 5.47976161070736e-02 + 8.37189869304468e-01 4.93502115779818e-02 + 8.60223965891098e-01 4.38110631161306e-02 + 8.83371421758982e-01 3.81398145030035e-02 + 9.06633371381850e-01 3.24408481950457e-02 + 9.29989733000046e-01 2.67257978266275e-02 + 9.53387742290786e-01 2.07144753192261e-02 + 9.76768638918538e-01 1.45035303709754e-02 + 1.00000000000000e+00 8.08144847432573e-03 diff --git a/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF17_Coords.txt b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF17_Coords.txt new file mode 100644 index 00000000..e8398cd3 --- /dev/null +++ b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF17_Coords.txt @@ -0,0 +1,208 @@ + 201 NumCoords ! The number of coordinates in the airfoil shape file (including an extra coordinate for airfoil reference). Set to zero if coordinates not included. +! ......... x-y coordinates are next if NumCoords > 0 ............. +! x-y coordinate of airfoil reference +! x/c y/c + 0.250000 0 +! coordinates of airfoil shape +! interpolation to 200 points +! x/c y/c + 1.00000000000000e+00 -5.45301418050398e-03 + 9.75817754636844e-01 -1.07014594571340e-03 + 9.51454474857096e-01 1.91024365189180e-03 + 9.26967643090702e-01 3.00968706555777e-03 + 9.02511079251701e-01 2.94654327425755e-03 + 8.78192574605997e-01 1.33458056758987e-03 + 8.54093368263713e-01 -1.40182384869508e-03 + 8.30280803054358e-01 -5.36722915654211e-03 + 8.06793858998891e-01 -1.02284409757101e-02 + 7.83681486977920e-01 -1.59512159380425e-02 + 7.60940204843493e-01 -2.22950822168370e-02 + 7.38563657479683e-01 -2.90867632401626e-02 + 7.16562339357988e-01 -3.62524846703740e-02 + 6.94907137649732e-01 -4.36064241543176e-02 + 6.73631134029173e-01 -5.11811692579687e-02 + 6.52658302378040e-01 -5.86920124341470e-02 + 6.32053668313489e-01 -6.62866061150648e-02 + 6.11762998595842e-01 -7.37633434906679e-02 + 5.91793833227140e-01 -8.11048412074493e-02 + 5.72143812615339e-01 -8.82708930236720e-02 + 5.52817394328116e-01 -9.52421061177968e-02 + 5.33788045856372e-01 -1.01905267173908e-01 + 5.15086541349180e-01 -1.08323876177549e-01 + 4.96717352144744e-01 -1.14481204108679e-01 + 4.78641616276281e-01 -1.20227783933246e-01 + 4.60893396881899e-01 -1.25639100003988e-01 + 4.43463621570381e-01 -1.30651726403441e-01 + 4.26364855167011e-01 -1.35291421458868e-01 + 4.09575905165181e-01 -1.39432097972120e-01 + 3.93110179140291e-01 -1.43077401925812e-01 + 3.76978460385483e-01 -1.46251273376598e-01 + 3.61179752938969e-01 -1.48871519397112e-01 + 3.45729101934949e-01 -1.50960869674387e-01 + 3.30642129005544e-01 -1.52550649026425e-01 + 3.15926278476078e-01 -1.53556648571138e-01 + 3.01599265716078e-01 -1.53406493492377e-01 + 2.87680819991451e-01 -1.52565505829207e-01 + 2.74185684558165e-01 -1.51262467818296e-01 + 2.61125227450442e-01 -1.49553952675144e-01 + 2.48509753994654e-01 -1.47518928364719e-01 + 2.36337378313774e-01 -1.45239165168132e-01 + 2.24609516585392e-01 -1.42744892161473e-01 + 2.13332897224055e-01 -1.40016001929494e-01 + 2.02471916601662e-01 -1.37246042052315e-01 + 1.92046415499529e-01 -1.34302336350696e-01 + 1.82017241046991e-01 -1.31316990852076e-01 + 1.72387811926573e-01 -1.28277098407418e-01 + 1.63158168703259e-01 -1.25175025059640e-01 + 1.54311116670428e-01 -1.22008726981644e-01 + 1.45810745366912e-01 -1.18882519862654e-01 + 1.37686151480707e-01 -1.15678943069290e-01 + 1.29904396960524e-01 -1.12501052056401e-01 + 1.22461453799045e-01 -1.09296875694661e-01 + 1.15336029025638e-01 -1.06110381969955e-01 + 1.08530206086421e-01 -1.02923068284723e-01 + 1.02021937517086e-01 -9.97477261452737e-02 + 9.58035794795516e-02 -9.66087731597880e-02 + 8.99025563208008e-02 -9.34345462961179e-02 + 8.42533694191495e-02 -9.03001520357529e-02 + 7.88404210406804e-02 -8.72478321301334e-02 + 7.36987958956943e-02 -8.41967679007426e-02 + 6.87979160132652e-02 -8.11907184984598e-02 + 6.41293950735861e-02 -7.82219427896279e-02 + 5.97053948052580e-02 -7.52557475365361e-02 + 5.54927030145125e-02 -7.23200756561499e-02 + 5.14882701745751e-02 -6.94055630007988e-02 + 4.76966523729130e-02 -6.65204388093482e-02 + 4.41044276154980e-02 -6.36813418052842e-02 + 4.06917094514561e-02 -6.09068675236080e-02 + 3.74540490762733e-02 -5.81886656057259e-02 + 3.43866063044132e-02 -5.55275845558965e-02 + 3.15023235573427e-02 -5.29049733067924e-02 + 2.87869138658892e-02 -5.03247145633268e-02 + 2.62138854996644e-02 -4.78100517604238e-02 + 2.37865060486491e-02 -4.53531589485433e-02 + 2.15247839409282e-02 -4.29352820557746e-02 + 1.94182671926051e-02 -4.05554813845574e-02 + 1.73965234398919e-02 -3.82405266496950e-02 + 1.54853588645235e-02 -3.59936663761455e-02 + 1.37247140912916e-02 -3.37853520929274e-02 + 1.21016771194090e-02 -3.16194081025936e-02 + 1.05781206388565e-02 -2.95197185049363e-02 + 9.16563324054632e-03 -2.74753790222862e-02 + 7.87017740303867e-03 -2.54771064952531e-02 + 6.73874368242485e-03 -2.35033804471445e-02 + 5.69708622898664e-03 -2.15868085403806e-02 + 4.77713369380707e-03 -1.97111181309851e-02 + 3.95637742176391e-03 -1.78845743446675e-02 + 3.18867965744800e-03 -1.61229116929551e-02 + 2.51755355177319e-03 -1.44093804163539e-02 + 1.97561081401136e-03 -1.27330821562174e-02 + 1.50680513040740e-03 -1.11084517063373e-02 + 1.11087123697807e-03 -9.53891013699422e-03 + 7.87187928013208e-04 -8.02095919047579e-03 + 5.40440313749341e-04 -6.55353655736207e-03 + 3.24451588791395e-04 -5.14486804718090e-03 + 1.88916042874488e-04 -3.78501062412031e-03 + 9.46340362822307e-05 -2.47910069070381e-03 + 2.95523038007147e-05 -1.22605370486567e-03 + 0.00000000000000e+00 0.00000000000000e+00 + 3.01481344622130e-05 1.17505317893727e-03 + 9.71702652511514e-05 2.42646619372459e-03 + 2.03793338171215e-04 3.72885439165868e-03 + 3.50357301196391e-04 5.08422545353897e-03 + 5.56726492329121e-04 6.49032410794411e-03 + 8.10159355539692e-04 7.94834859081885e-03 + 1.16155592002565e-03 9.45472898904353e-03 + 1.67637488199947e-03 1.09790644306452e-02 + 2.24350076193863e-03 1.25604990644086e-02 + 2.93581026563085e-03 1.41655243002384e-02 + 3.71628942355257e-03 1.58152478828471e-02 + 4.58474262640831e-03 1.75044149307111e-02 + 5.55488305863393e-03 1.92276009432552e-02 + 6.64802371618967e-03 2.09824655006495e-02 + 7.84988650655681e-03 2.27705789972541e-02 + 9.14426750365521e-03 2.46074952599354e-02 + 1.05699641486623e-02 2.64638140414759e-02 + 1.21156298219846e-02 2.83517697847890e-02 + 1.37576162529760e-02 3.02925689186482e-02 + 1.54895733386299e-02 3.22984799032679e-02 + 1.73435567726879e-02 3.43421258897796e-02 + 1.93455202749544e-02 3.64041907098984e-02 + 2.15005396192731e-02 3.84872450496868e-02 + 2.37609732142698e-02 4.06370705630654e-02 + 2.61438022753388e-02 4.28440907355414e-02 + 2.86976791253163e-02 4.50652887339507e-02 + 3.14081825116334e-02 4.73218530627499e-02 + 3.42618133903517e-02 4.96294249787890e-02 + 3.72752122579656e-02 5.19754897747939e-02 + 4.04579457665667e-02 5.43568206182997e-02 + 4.38096061596044e-02 5.67814925288692e-02 + 4.73527794655686e-02 5.92252949852968e-02 + 5.10805893305958e-02 6.17034102753216e-02 + 5.49951734742978e-02 6.42246281779437e-02 + 5.91172562090566e-02 6.67651820406855e-02 + 6.34412452148952e-02 6.93500711466022e-02 + 6.79840941864798e-02 7.19471001376835e-02 + 7.27468469458395e-02 7.45705996505986e-02 + 7.77328868720285e-02 7.72333440704537e-02 + 8.29626933019556e-02 7.98998610400721e-02 + 8.84438437146468e-02 8.25516267432993e-02 + 9.41776411888755e-02 8.52039636550780e-02 + 1.00170421380160e-01 8.78676504969935e-02 + 1.06430934474038e-01 9.05393436776120e-02 + 1.12969233548496e-01 9.32086710673799e-02 + 1.19797828219200e-01 9.58462247530667e-02 + 1.26911894255357e-01 9.84958150865328e-02 + 1.34331983632213e-01 1.01128226770770e-01 + 1.42066987117710e-01 1.03723117625941e-01 + 1.50124262102595e-01 1.06274763475707e-01 + 1.58513048529723e-01 1.08770852235264e-01 + 1.67241646522678e-01 1.11196896421823e-01 + 1.76323718493828e-01 1.13540445285679e-01 + 1.85743681389525e-01 1.15873278276396e-01 + 1.95524016824630e-01 1.18115770052045e-01 + 2.05683255342811e-01 1.20208699038275e-01 + 2.16208468120044e-01 1.22224461173209e-01 + 2.27117207800504e-01 1.24090288616604e-01 + 2.38419423158324e-01 1.25782649954125e-01 + 2.50110734150605e-01 1.27336011108803e-01 + 2.62197488700551e-01 1.28669969942400e-01 + 2.74686682065653e-01 1.29764427838693e-01 + 2.87569054903857e-01 1.30681368424973e-01 + 3.00852399367078e-01 1.31283757276969e-01 + 3.14530771437150e-01 1.31692707165930e-01 + 3.28604824690067e-01 1.31851460992892e-01 + 3.43071468150563e-01 1.31640913718290e-01 + 3.57931242815408e-01 1.31256435294713e-01 + 3.73178779264493e-01 1.30614578750586e-01 + 3.88811577543217e-01 1.29697152615801e-01 + 4.04827176697756e-01 1.28553939360805e-01 + 4.21218824620110e-01 1.27145088813715e-01 + 4.37996175755373e-01 1.25658971878768e-01 + 4.55132979373076e-01 1.23843182272296e-01 + 4.72638679585242e-01 1.21926903878881e-01 + 4.90509890590074e-01 1.19631762561332e-01 + 5.08733867924661e-01 1.16939647488128e-01 + 5.27305087603049e-01 1.14015126381095e-01 + 5.46213184288326e-01 1.10843992328087e-01 + 5.65460187911138e-01 1.07498826395060e-01 + 5.85029675577305e-01 1.03944942811554e-01 + 6.04902749493555e-01 1.00126044902967e-01 + 6.25076084848418e-01 9.60954974978452e-02 + 6.45543971739222e-01 9.18933165314899e-02 + 6.66297289512585e-01 8.75484886184110e-02 + 6.87308946494649e-01 8.29877474141992e-02 + 7.08578048914644e-01 7.82894566836472e-02 + 7.30086443256557e-01 7.34459663833689e-02 + 7.51825357054199e-01 6.84945162374382e-02 + 7.73769138587997e-01 6.34023849460844e-02 + 7.95897100069124e-01 5.81625974308282e-02 + 8.18195637696294e-01 5.28018830946166e-02 + 8.40659948231990e-01 4.73841857178122e-02 + 8.63266034014869e-01 4.19041191703725e-02 + 8.85979573720097e-01 3.62991883120328e-02 + 9.08802830149653e-01 3.06806974342369e-02 + 9.31707972602122e-01 2.50135348041367e-02 + 9.54654320230810e-01 1.88471626322655e-02 + 9.77590603702380e-01 1.23214474808323e-02 + 1.00000000000000e+00 5.52162384629112e-03 diff --git a/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF18_Coords.txt b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF18_Coords.txt new file mode 100644 index 00000000..87813ee7 --- /dev/null +++ b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF18_Coords.txt @@ -0,0 +1,208 @@ + 201 NumCoords ! The number of coordinates in the airfoil shape file (including an extra coordinate for airfoil reference). Set to zero if coordinates not included. +! ......... x-y coordinates are next if NumCoords > 0 ............. +! x-y coordinate of airfoil reference +! x/c y/c + 0.250000 0 +! coordinates of airfoil shape +! interpolation to 200 points +! x/c y/c + 1.00000000000000e+00 -2.37767599414968e-03 + 9.76446819562239e-01 1.18667276573974e-03 + 9.52930798636692e-01 3.80478847156908e-03 + 9.29282208028914e-01 5.37628501132393e-03 + 9.05615578666939e-01 6.07272680933467e-03 + 8.82032334216335e-01 5.18874855240369e-03 + 8.58617284514100e-01 3.26660678111755e-03 + 8.35440764035589e-01 2.67187094232616e-05 + 8.12556593166433e-01 -4.15650599841566e-03 + 7.90017464961696e-01 -9.25945431510779e-03 + 7.67840842437519e-01 -1.50885188225015e-02 + 7.46027726392422e-01 -2.14593261524176e-02 + 7.24592442618031e-01 -2.82974871754426e-02 + 7.03504149817637e-01 -3.53964569024539e-02 + 6.82765349116846e-01 -4.26998988823194e-02 + 6.62337893926518e-01 -5.00271216489902e-02 + 6.42248092575011e-01 -5.74239730292741e-02 + 6.22460538916900e-01 -6.47395984745764e-02 + 6.02953903187687e-01 -7.18789103015881e-02 + 5.83732605013996e-01 -7.88228152136706e-02 + 5.64800704679662e-01 -8.55519158464723e-02 + 5.46124988243235e-01 -9.19284463008494e-02 + 5.27742247208307e-01 -9.80364414989111e-02 + 5.09652486976343e-01 -1.03841306232240e-01 + 4.91835492986616e-01 -1.09243363075515e-01 + 4.74308759446067e-01 -1.14261681915081e-01 + 4.57077435404333e-01 -1.18870892627075e-01 + 4.40154051473917e-01 -1.23098817274973e-01 + 4.23530856843343e-01 -1.26854027870635e-01 + 4.07216398081170e-01 -1.30119328171116e-01 + 3.91231938614656e-01 -1.32976005720577e-01 + 3.75575699731328e-01 -1.35342726415398e-01 + 3.60263622208770e-01 -1.37261172568907e-01 + 3.45308062067250e-01 -1.38788502251440e-01 + 3.30710985565161e-01 -1.39841337156737e-01 + 3.16484027641533e-01 -1.40100625734666e-01 + 3.02640076917013e-01 -1.39862266369132e-01 + 2.89186583012941e-01 -1.39252768782004e-01 + 2.76130340586499e-01 -1.38286107582322e-01 + 2.63476265682543e-01 -1.37049216008764e-01 + 2.51223094661652e-01 -1.35572490644241e-01 + 2.39372261720154e-01 -1.33875529784685e-01 + 2.27927524364597e-01 -1.31931209492906e-01 + 2.16866171615739e-01 -1.29910205264487e-01 + 2.06201029914413e-01 -1.27692002391941e-01 + 1.95913212312204e-01 -1.25358568326782e-01 + 1.85997306093273e-01 -1.22934748923442e-01 + 1.76450637821784e-01 -1.20426052562665e-01 + 1.67269721120968e-01 -1.17795029832047e-01 + 1.58423588488400e-01 -1.15164333199127e-01 + 1.49936911969762e-01 -1.12408754691065e-01 + 1.41769123119841e-01 -1.09669875291307e-01 + 1.33937151744594e-01 -1.06851502319845e-01 + 1.26416097012572e-01 -1.04016679034228e-01 + 1.19206237571905e-01 -1.01151657303313e-01 + 1.12297037125044e-01 -9.82587192113124e-02 + 1.05667160617742e-01 -9.53856625792421e-02 + 9.93435270819619e-02 -9.24557770413018e-02 + 9.32891373053101e-02 -8.95249953967126e-02 + 8.74719354214747e-02 -8.66600851213458e-02 + 8.19240576596432e-02 -8.37764095161515e-02 + 7.66140873543626e-02 -8.09233249988340e-02 + 7.15426883354032e-02 -7.80879536266522e-02 + 6.67258789024077e-02 -7.52313564677441e-02 + 6.21109049974624e-02 -7.24930414546405e-02 + 5.77107003282204e-02 -6.98465745441758e-02 + 5.35430034534783e-02 -6.71846452282005e-02 + 4.95845561568290e-02 -6.45422361158792e-02 + 4.58099226060605e-02 -6.19523763970443e-02 + 4.22293604618921e-02 -5.93855665933846e-02 + 3.88308843695516e-02 -5.68544053787320e-02 + 3.56234006217278e-02 -5.43433098462299e-02 + 3.25999205074709e-02 -5.18499783811972e-02 + 2.97405688058144e-02 -4.93956746514801e-02 + 2.70395385980955e-02 -4.69821041730334e-02 + 2.44940212404595e-02 -4.46103096861655e-02 + 2.21201103864747e-02 -4.22591015257432e-02 + 1.98580479062668e-02 -3.99325658782353e-02 + 1.77168686887470e-02 -3.76638917235478e-02 + 1.57157807032474e-02 -3.54403779106754e-02 + 1.38676651671849e-02 -3.32484674991874e-02 + 1.21441938253155e-02 -3.11061195104619e-02 + 1.05378361076491e-02 -2.90145230640159e-02 + 9.04844929893957e-03 -2.69697346212576e-02 + 7.75683497330708e-03 -2.49283589829342e-02 + 6.52980280782892e-03 -2.29587165235158e-02 + 5.45989916249106e-03 -2.10098573697542e-02 + 4.51688987743758e-03 -1.90975789024075e-02 + 3.64156821001467e-03 -1.72448669660278e-02 + 2.89517955356030e-03 -1.54279532736546e-02 + 2.27709187814676e-03 -1.36490255771574e-02 + 1.72915425508911e-03 -1.19244153221547e-02 + 1.27964769399565e-03 -1.02506222817353e-02 + 9.12717177077437e-04 -8.62589658032073e-03 + 6.43670432858475e-04 -7.05048038051019e-03 + 3.75496964177492e-04 -5.53981424307094e-03 + 2.12451593354277e-04 -4.07587556179559e-03 + 9.85747212878459e-05 -2.66752580611053e-03 + 3.05204163981267e-05 -1.31331094969237e-03 + 0.00000000000000e+00 0.00000000000000e+00 + 3.15800516939920e-05 1.28536935659477e-03 + 1.02861345468154e-04 2.63794919245206e-03 + 2.36308992810849e-04 4.04267190102204e-03 + 4.18574204776478e-04 5.50160407333578e-03 + 6.96667127526426e-04 7.00712121949262e-03 + 1.02165107805804e-03 8.56543372145463e-03 + 1.42540966556040e-03 1.01797040162715e-02 + 2.06214142058454e-03 1.17841124321626e-02 + 2.74385305341704e-03 1.34517101595850e-02 + 3.59432216104703e-03 1.51227008126668e-02 + 4.52897284835177e-03 1.68382166645950e-02 + 5.58705383071816e-03 1.85729863183344e-02 + 6.76096524288088e-03 2.03314489250025e-02 + 8.03743675144860e-03 2.21305025010730e-02 + 9.43646227409209e-03 2.39515425026592e-02 + 1.09263641031346e-02 2.58226128735423e-02 + 1.25566270365459e-02 2.77033405353925e-02 + 1.43178449292754e-02 2.96035213537207e-02 + 1.61852054142408e-02 3.15492683526132e-02 + 1.81381119035080e-02 3.35658704424136e-02 + 2.02376177807679e-02 3.55949640883938e-02 + 2.24827884412515e-02 3.76427169254937e-02 + 2.48776366499191e-02 3.97084340106233e-02 + 2.73991082013164e-02 4.18201264039935e-02 + 3.00477787622335e-02 4.39843306813997e-02 + 3.28525738533268e-02 4.61758552907474e-02 + 3.58120783592458e-02 4.84020618976064e-02 + 3.89252554594669e-02 5.06656093643179e-02 + 4.22050404438107e-02 5.29567403882480e-02 + 4.56607724006619e-02 5.52705490464994e-02 + 4.92802379264876e-02 5.76342317329541e-02 + 5.30951492645608e-02 6.00045745431363e-02 + 5.71023305776689e-02 6.23946378850674e-02 + 6.12975848311221e-02 6.48215197669438e-02 + 6.56925727776909e-02 6.72766782487322e-02 + 7.02743714952992e-02 6.97972744317459e-02 + 7.50969486986961e-02 7.22842735310359e-02 + 8.01400765487782e-02 7.47901896085021e-02 + 8.53920774693246e-02 7.73567066055900e-02 + 9.08903676568554e-02 7.99133996484751e-02 + 9.66403183510142e-02 8.24936560307861e-02 + 1.02638479952074e-01 8.50997650283062e-02 + 1.08889440257636e-01 8.77162219327400e-02 + 1.15401817527268e-01 9.03394906080130e-02 + 1.22185516627081e-01 9.29598512750285e-02 + 1.29263118491494e-01 9.55337809970597e-02 + 1.36619374775123e-01 9.81184385458023e-02 + 1.44266139092389e-01 1.00694502173312e-01 + 1.52221162890854e-01 1.03229848289691e-01 + 1.60491203003249e-01 1.05718276956696e-01 + 1.69084936589124e-01 1.08146601356303e-01 + 1.78011398738398e-01 1.10496847084347e-01 + 1.87272650122097e-01 1.12780737463291e-01 + 1.96861105345526e-01 1.15054643125002e-01 + 2.06798117527740e-01 1.17240543617190e-01 + 2.17101851419760e-01 1.19273158884218e-01 + 2.27761275369060e-01 1.21224134069861e-01 + 2.38790761271252e-01 1.23023413411139e-01 + 2.50192886766329e-01 1.24678047176873e-01 + 2.61966061889217e-01 1.26213824812832e-01 + 2.74122740201456e-01 1.27530811823120e-01 + 2.86662746727198e-01 1.28636005140460e-01 + 2.99584123829558e-01 1.29553120390120e-01 + 3.12891391317914e-01 1.30171094917509e-01 + 3.26579260634688e-01 1.30578353143042e-01 + 3.40647672578538e-01 1.30725411590738e-01 + 3.55091880946261e-01 1.30496104164832e-01 + 3.69910990811779e-01 1.30058415062081e-01 + 3.85097931570468e-01 1.29333718130797e-01 + 4.00650923113019e-01 1.28339370562823e-01 + 4.16565921229797e-01 1.27096432683427e-01 + 4.32836992216272e-01 1.25581769969023e-01 + 4.49471067150447e-01 1.23948898925125e-01 + 4.66445046714551e-01 1.21982635824263e-01 + 4.83761025693294e-01 1.19827800217627e-01 + 5.01420577935565e-01 1.17377223728947e-01 + 5.19413548507589e-01 1.14623284584942e-01 + 5.37727933854121e-01 1.11613572571558e-01 + 5.56358704938187e-01 1.08373804583437e-01 + 5.75305606530518e-01 1.04960916116859e-01 + 5.94556737334723e-01 1.01364726003763e-01 + 6.14091323042302e-01 9.75131887392979e-02 + 6.33899505217000e-01 9.34229607669790e-02 + 6.53983838820148e-01 8.91779646388802e-02 + 6.74334658110115e-01 8.48016108581404e-02 + 6.94926822402831e-01 8.02237288972718e-02 + 7.15760758260989e-01 7.55262386365138e-02 + 7.36819570375329e-01 7.07027052448581e-02 + 7.58090843885297e-01 6.57693336437398e-02 + 7.79554466153280e-01 6.07141783168916e-02 + 8.01192136630880e-01 5.55343914786427e-02 + 8.22988286990664e-01 5.02420511779286e-02 + 8.44930581805388e-01 4.48622679286764e-02 + 8.67009913774751e-01 3.94519467741740e-02 + 8.89189431928600e-01 3.39266635119004e-02 + 9.11472787704912e-01 2.84011627846064e-02 + 9.33822613763039e-01 2.27894520303026e-02 + 9.56213100416208e-01 1.64551756972167e-02 + 9.78602197523542e-01 9.57262213328838e-03 + 1.00000000000000e+00 2.38801343162379e-03 diff --git a/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF19_Coords.txt b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF19_Coords.txt new file mode 100644 index 00000000..ffdbb0d3 --- /dev/null +++ b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF19_Coords.txt @@ -0,0 +1,208 @@ + 201 NumCoords ! The number of coordinates in the airfoil shape file (including an extra coordinate for airfoil reference). Set to zero if coordinates not included. +! ......... x-y coordinates are next if NumCoords > 0 ............. +! x-y coordinate of airfoil reference +! x/c y/c + 0.250000 0 +! coordinates of airfoil shape +! interpolation to 200 points +! x/c y/c + 1.00000000000000e+00 -3.68399389995869e-04 + 9.76857008771838e-01 2.66731162732446e-03 + 9.53893452982560e-01 5.08228579069216e-03 + 9.30791447416205e-01 6.92341917618193e-03 + 9.07639904153749e-01 8.15655615709104e-03 + 8.84536094791801e-01 7.92264904224889e-03 + 8.61567157501965e-01 6.68493011849853e-03 + 8.38805377497580e-01 4.13452337383163e-03 + 8.16314251999226e-01 5.97915678772836e-04 + 7.94148914190988e-01 -3.89604633156816e-03 + 7.72340484630481e-01 -9.19436001700492e-03 + 7.50894760627057e-01 -1.51087969475548e-02 + 7.29828566229855e-01 -2.15579885729289e-02 + 7.09109933074187e-01 -2.83298125964794e-02 + 6.88721421877958e-01 -3.53036886233563e-02 + 6.68649585846097e-01 -4.23737071775973e-02 + 6.48895487241817e-01 -4.95075181376893e-02 + 6.29435996348719e-01 -5.65920614554448e-02 + 6.10230958530276e-01 -6.34793436033746e-02 + 5.91289213882662e-01 -7.01620809295741e-02 + 5.72614563636092e-01 -7.66179006666135e-02 + 5.54169437142293e-01 -8.26972170912674e-02 + 5.35994549591891e-01 -8.84922462055237e-02 + 5.18086994319589e-01 -9.39558134124888e-02 + 5.00438716025881e-01 -9.90271375426639e-02 + 4.83056404950572e-01 -1.03683276789266e-01 + 4.65954483401666e-01 -1.07928967059445e-01 + 4.49145459682817e-01 -1.11790741247148e-01 + 4.32630347798518e-01 -1.15206880360019e-01 + 4.16414524640443e-01 -1.18147531896552e-01 + 4.00526087330994e-01 -1.20731141532653e-01 + 3.84962746755882e-01 -1.22881481336833e-01 + 3.69741027707524e-01 -1.24652317902417e-01 + 3.54871156825438e-01 -1.26116996793257e-01 + 3.40351528329817e-01 -1.27196549851457e-01 + 3.26189812343215e-01 -1.27831505011485e-01 + 3.12394436962796e-01 -1.28135125466097e-01 + 2.98968095909353e-01 -1.28135971204913e-01 + 2.85914601715587e-01 -1.27815225606007e-01 + 2.73235356281731e-01 -1.27263263044964e-01 + 2.60929501705741e-01 -1.26470643765030e-01 + 2.48998483933274e-01 -1.25450275622875e-01 + 2.37444123255251e-01 -1.24173437692176e-01 + 2.26252115496294e-01 -1.22785796310441e-01 + 2.15430713313732e-01 -1.21185221143952e-01 + 2.04974244392958e-01 -1.19412349992892e-01 + 1.94871537400587e-01 -1.17520737121037e-01 + 1.85118149204518e-01 -1.15527561249974e-01 + 1.75719532106264e-01 -1.13369650618129e-01 + 1.66647941717989e-01 -1.11180617405335e-01 + 1.57925164945130e-01 -1.08833224985739e-01 + 1.49505657854053e-01 -1.06498338398972e-01 + 1.41420016040231e-01 -1.04044619127328e-01 + 1.33640986123984e-01 -1.01549904565748e-01 + 1.26167669913614e-01 -9.90049839819346e-02 + 1.18997037103723e-01 -9.64015758401574e-02 + 1.12098825120963e-01 -9.38093390294696e-02 + 1.05499623500676e-01 -9.11479135507931e-02 + 9.91810164066800e-02 -8.84508376192239e-02 + 9.31002162531755e-02 -8.58102997394773e-02 + 8.72874366774390e-02 -8.31377449587737e-02 + 8.17107141333520e-02 -8.04892138256785e-02 + 7.63766137075373e-02 -7.78449994839546e-02 + 7.13036684223055e-02 -7.51579825759147e-02 + 6.64263817165701e-02 -7.26018598042667e-02 + 6.17681093546461e-02 -7.01301752855594e-02 + 5.73551856813564e-02 -6.76137828225569e-02 + 5.31579386553926e-02 -6.50996263715978e-02 + 4.91473139049403e-02 -6.26301467575107e-02 + 4.53431586149581e-02 -6.01620539688450e-02 + 4.17288283387378e-02 -5.77156085161925e-02 + 3.83105975635588e-02 -5.52772281229456e-02 + 3.50862364938885e-02 -5.28405786158374e-02 + 3.20401842818251e-02 -5.04256327322228e-02 + 2.91607168682362e-02 -4.80403110926350e-02 + 2.64301474681941e-02 -4.56985651824556e-02 + 2.38818791314998e-02 -4.33660011061808e-02 + 2.14869187314351e-02 -4.10319139878904e-02 + 1.92210251217201e-02 -3.87490158345328e-02 + 1.70866204440822e-02 -3.65155909889459e-02 + 1.51088856667703e-02 -3.43067488660566e-02 + 1.32677571342121e-02 -3.21365849699287e-02 + 1.15452964783661e-02 -3.00141740624550e-02 + 9.93785550135011e-03 -2.79390543678102e-02 + 8.53733963199581e-03 -2.58535670157040e-02 + 7.18971942545551e-03 -2.38493192760235e-02 + 6.01408812501931e-03 -2.18527495788709e-02 + 4.98035831239796e-03 -1.98845668008135e-02 + 4.02595523871816e-03 -1.79724851036912e-02 + 3.21872354864114e-03 -1.60881596868680e-02 + 2.53699895316356e-03 -1.42423112550335e-02 + 1.92596838800982e-03 -1.24525079880165e-02 + 1.42958340648342e-03 -1.07107365453782e-02 + 1.02402066973875e-03 -9.01638710474725e-03 + 7.29515457680132e-04 -7.37055242509973e-03 + 4.22134415351005e-04 -5.79337753090592e-03 + 2.34596295265449e-04 -4.26157143671717e-03 + 1.02904903665998e-04 -2.78642458580164e-03 + 3.16491042877115e-05 -1.36624202526467e-03 + 0.00000000000000e+00 0.00000000000000e+00 + 3.25137502262144e-05 1.36126836315680e-03 + 1.06572281496749e-04 2.77981521878749e-03 + 2.57511209208200e-04 4.25126635289481e-03 + 4.63055841935316e-04 5.77772676962173e-03 + 7.87917070457592e-04 7.34807091678409e-03 + 1.15955675201046e-03 8.97177740531396e-03 + 1.59745861466139e-03 1.06563985806526e-02 + 2.31368504535807e-03 1.23130195245482e-02 + 3.07011367084607e-03 1.40368009141934e-02 + 4.02371261501702e-03 1.57508050961990e-02 + 5.05889266777718e-03 1.75092215738978e-02 + 6.24062268199277e-03 1.92737269450562e-02 + 7.54740536677814e-03 2.10551920713005e-02 + 8.94341992064346e-03 2.28830596185717e-02 + 1.04710077300238e-02 2.47255697363701e-02 + 1.20884012253117e-02 2.66189106966348e-02 + 1.38520540216189e-02 2.85155544569944e-02 + 1.57538252832241e-02 3.04237067797815e-02 + 1.77681435802238e-02 3.23726800924697e-02 + 1.98651227360326e-02 3.43962534435927e-02 + 2.21247244203388e-02 3.64158580641648e-02 + 2.45284811789666e-02 3.84542786038096e-02 + 2.70797126293869e-02 4.05086907274035e-02 + 2.97713970613449e-02 4.25955179697784e-02 + 3.25934127100249e-02 4.47318036374387e-02 + 3.55618220018821e-02 4.69039793632072e-02 + 3.86836906268538e-02 4.91103908591560e-02 + 4.19661079042882e-02 5.13452316640530e-02 + 4.54195931002610e-02 5.36005424735060e-02 + 4.90533369175556e-02 5.58703224938828e-02 + 5.28474279411799e-02 5.81942364368840e-02 + 5.68395292704747e-02 6.05166790176710e-02 + 6.10288780337881e-02 6.28493270475509e-02 + 6.54071465451169e-02 6.52146960136306e-02 + 6.99800855562079e-02 6.76141714293276e-02 + 7.47299921393616e-02 7.00928446530985e-02 + 7.97349694380070e-02 7.25080974627385e-02 + 8.49609191753247e-02 7.49373418732565e-02 + 9.03863431014392e-02 7.74411126435351e-02 + 9.60597012920897e-02 7.99261936987175e-02 + 1.01984926382490e-01 8.24310363129346e-02 + 1.08155469732798e-01 8.49653756451838e-02 + 1.14574779429234e-01 8.75131666717048e-02 + 1.21251387707475e-01 9.00699473431387e-02 + 1.28195102790333e-01 9.26263962880819e-02 + 1.35435072734491e-01 9.51218497619305e-02 + 1.42949252027610e-01 9.76304862957753e-02 + 1.50743822415266e-01 1.00143225443294e-01 + 1.58842313055751e-01 1.02614343572487e-01 + 1.67251089180853e-01 1.05037311736569e-01 + 1.75978460980627e-01 1.07398386544002e-01 + 1.85033942788463e-01 1.09676903953931e-01 + 1.94412030223010e-01 1.11906753065792e-01 + 2.04110352857490e-01 1.14127897662318e-01 + 2.14149527961947e-01 1.16265117747636e-01 + 2.24547481767990e-01 1.18248683868967e-01 + 2.35294419696161e-01 1.20148148534840e-01 + 2.46402639597428e-01 1.21897385397864e-01 + 2.57869912676765e-01 1.23526834665610e-01 + 2.69696468272276e-01 1.25053947368743e-01 + 2.81898741199044e-01 1.26364975026619e-01 + 2.94471881045941e-01 1.27487690783284e-01 + 3.07418691339119e-01 1.28414307575311e-01 + 3.20741558118385e-01 1.29056641751163e-01 + 3.34435620226968e-01 1.29474248027250e-01 + 3.48500353688656e-01 1.29624393334326e-01 + 3.62929932989329e-01 1.29396296126059e-01 + 3.77722526892471e-01 1.28930828553253e-01 + 3.92869955516012e-01 1.28156113952553e-01 + 4.08370908134265e-01 1.27114694902152e-01 + 4.24220308156953e-01 1.25806236875891e-01 + 4.40412755529192e-01 1.24220713149001e-01 + 4.56953405525328e-01 1.22475796836960e-01 + 4.73821213743432e-01 1.20395388434913e-01 + 4.91013482752600e-01 1.18050411789495e-01 + 5.08535020400488e-01 1.15490643648704e-01 + 5.26377360286358e-01 1.12710340482628e-01 + 5.44524273775329e-01 1.09660985096774e-01 + 5.62974211427790e-01 1.06393299108221e-01 + 5.81725427948974e-01 1.02949051041186e-01 + 6.00768970403698e-01 9.93338710397741e-02 + 6.20082840879561e-01 9.54749572480719e-02 + 6.39652920613148e-01 9.13660653707297e-02 + 6.59487153767914e-01 8.71101696164325e-02 + 6.79575519171002e-01 8.27251675441617e-02 + 6.99894148304263e-01 7.81515132973927e-02 + 7.20444328669405e-01 7.34673024705215e-02 + 7.41209985385736e-01 6.86669596077010e-02 + 7.62176328526465e-01 6.37536068656100e-02 + 7.83326857277745e-01 5.87278224664763e-02 + 8.04644827719480e-01 5.35902846761059e-02 + 8.26113390531774e-01 4.83441901136536e-02 + 8.47715298834171e-01 4.29917435480749e-02 + 8.69451154762037e-01 3.76211700207279e-02 + 8.91282457860132e-01 3.21440170875230e-02 + 9.13213765042928e-01 2.66674634778728e-02 + 9.35201490491600e-01 2.10851818173222e-02 + 9.57229521434730e-01 1.46843783125432e-02 + 9.79261819214701e-01 7.64883901865307e-03 + 1.00000000000000e+00 3.48671814865888e-04 diff --git a/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF20_Coords.txt b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF20_Coords.txt new file mode 100644 index 00000000..8e86a6c9 --- /dev/null +++ b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF20_Coords.txt @@ -0,0 +1,208 @@ + 201 NumCoords ! The number of coordinates in the airfoil shape file (including an extra coordinate for airfoil reference). Set to zero if coordinates not included. +! ......... x-y coordinates are next if NumCoords > 0 ............. +! x-y coordinate of airfoil reference +! x/c y/c + 0.250000 0 +! coordinates of airfoil shape +! interpolation to 200 points +! x/c y/c + 1.00000000000000e+00 -1.16970450232154e-05 + 9.76925950475657e-01 2.89849629928081e-03 + 9.54056302293072e-01 5.27987438372875e-03 + 9.31048128850624e-01 7.19864995910977e-03 + 9.07985124166376e-01 8.59432633354728e-03 + 8.84963341017396e-01 8.76245996738773e-03 + 8.62070108500804e-01 7.89821744156301e-03 + 8.39377957233181e-01 5.82757272129634e-03 + 8.16952105741759e-01 2.74131006023888e-03 + 7.94848134812973e-01 -1.31047187114084e-03 + 7.73099762468629e-01 -6.19594038201392e-03 + 7.51713796559463e-01 -1.17316935887704e-02 + 7.30707465507159e-01 -1.78243181962159e-02 + 7.10048880246723e-01 -2.42736757420121e-02 + 6.89717065485909e-01 -3.09377224920066e-02 + 6.69703185975444e-01 -3.77351051006435e-02 + 6.50003630817286e-01 -4.46004260244532e-02 + 6.30597616366455e-01 -5.14349380887498e-02 + 6.11441818070351e-01 -5.80781149510869e-02 + 5.92545822192135e-01 -6.45215136200802e-02 + 5.73913326684091e-01 -7.07373461559128e-02 + 5.55506287086248e-01 -7.65813023757692e-02 + 5.37365867311171e-01 -8.21381752489661e-02 + 5.19488675136997e-01 -8.73572229383648e-02 + 5.01868935197649e-01 -9.21948826265366e-02 + 4.84511382435821e-01 -9.66125856407465e-02 + 4.67432104979211e-01 -1.00628904032081e-01 + 4.50643532673488e-01 -1.04265668268842e-01 + 4.34148314472208e-01 -1.07478023174613e-01 + 4.17951273380630e-01 -1.10235646319524e-01 + 4.02081583043242e-01 -1.12662589853757e-01 + 3.86536904904201e-01 -1.14691181363898e-01 + 3.71333778363175e-01 -1.16376698317397e-01 + 3.56481987324237e-01 -1.17794019293702e-01 + 3.41979279301955e-01 -1.18871441512321e-01 + 3.27832555060862e-01 -1.19600488549061e-01 + 3.14049364730407e-01 -1.20059113518256e-01 + 3.00631508155208e-01 -1.20254220188729e-01 + 2.87582216544618e-01 -1.20159958866052e-01 + 2.74902221193761e-01 -1.19865036371322e-01 + 2.62590720444375e-01 -1.19348842067133e-01 + 2.50649124402496e-01 -1.18621135823199e-01 + 2.39078845345792e-01 -1.17656533028436e-01 + 2.27867184439070e-01 -1.16582394562078e-01 + 2.17021456811297e-01 -1.15308380050123e-01 + 2.06538387308884e-01 -1.13853615562753e-01 + 1.96405791960340e-01 -1.12282176086080e-01 + 1.86618882329224e-01 -1.10617167094150e-01 + 1.77184649555781e-01 -1.08781185951076e-01 + 1.68076082704334e-01 -1.06908773866295e-01 + 1.59314215217802e-01 -1.04873638045081e-01 + 1.50852862448295e-01 -1.02861593237538e-01 + 1.42724842088730e-01 -1.00718365786054e-01 + 1.34902608040035e-01 -9.85287421796948e-02 + 1.27384992592018e-01 -9.62861825827909e-02 + 1.20170299874457e-01 -9.39710611432170e-02 + 1.13226789857415e-01 -9.16709983326127e-02 + 1.06580720474888e-01 -8.93032875865484e-02 + 1.00217178769272e-01 -8.68749312381822e-02 + 9.40916537592124e-02 -8.45028367434999e-02 + 8.82337163668553e-02 -8.20944117938331e-02 + 8.26115051483221e-02 -7.97126340550203e-02 + 7.72312330966435e-02 -7.73288341051596e-02 + 7.21130677350178e-02 -7.48833638768388e-02 + 6.71894736753951e-02 -7.24763209375136e-02 + 6.24856412277135e-02 -7.00416636170101e-02 + 5.80294161668677e-02 -6.75572914548322e-02 + 5.37899973283964e-02 -6.50720675769313e-02 + 4.97376985419173e-02 -6.26297954371682e-02 + 4.58940560730263e-02 -6.01849905424522e-02 + 4.22416037500420e-02 -5.77591819336826e-02 + 3.87861465552347e-02 -5.53392550403537e-02 + 3.55262959996525e-02 -5.29181938435960e-02 + 3.24472582872532e-02 -5.05155931301242e-02 + 2.95362641509762e-02 -4.81404755119313e-02 + 2.67729953169852e-02 -4.58090684459152e-02 + 2.41939083904648e-02 -4.34848129849921e-02 + 2.18141572031663e-02 -4.11543813853988e-02 + 1.95673854713824e-02 -3.88737506338495e-02 + 1.74477564779088e-02 -3.66431614312941e-02 + 1.54752345352323e-02 -3.44358303125963e-02 + 1.36342551938651e-02 -3.22650844102067e-02 + 1.19084234941661e-02 -3.01413804853732e-02 + 1.02942941011661e-02 -2.80648529097022e-02 + 8.86743811777817e-03 -2.59756933328882e-02 + 7.49856900534070e-03 -2.39690434637317e-02 + 6.29098663294263e-03 -2.19677989083217e-02 + 5.22308841935517e-03 -1.99933475331875e-02 + 4.24008866088351e-03 -1.80740827427679e-02 + 3.40280642281631e-03 -1.61810689964114e-02 + 2.68688998868729e-03 -1.43265021403969e-02 + 2.04591034039661e-03 -1.25280222785356e-02 + 1.52162287314027e-03 -1.07769333035290e-02 + 1.09208473544427e-03 -9.07280332309622e-03 + 7.75103994536751e-04 -7.41691607941299e-03 + 4.52353374589913e-04 -5.83014500820004e-03 + 2.49723979775574e-04 -4.28843531366952e-03 + 1.06661955669598e-04 -2.80345353766615e-03 + 3.27195725030880e-05 -1.37348955310638e-03 + 0.00000000000000e+00 0.00000000000000e+00 + 3.26413884329373e-05 1.37318323731147e-03 + 1.07225011317394e-04 2.80153107572479e-03 + 2.61262892040196e-04 4.28285015690166e-03 + 4.70931448264386e-04 5.81923659176159e-03 + 8.04058189317705e-04 7.39899934408296e-03 + 1.18395464357889e-03 9.03211811477640e-03 + 1.62790475131778e-03 1.07268695231018e-02 + 2.35805156291858e-03 1.23907220018351e-02 + 3.12729867551767e-03 1.41221855611746e-02 + 4.09811443518625e-03 1.58417552692127e-02 + 5.15013525889198e-03 1.76056029553215e-02 + 6.35251451470470e-03 1.93733209765600e-02 + 7.68136628992783e-03 2.11568889489349e-02 + 9.09705641338774e-03 2.29878091550079e-02 + 1.06457219627370e-02 2.48321471768241e-02 + 1.22840569946196e-02 2.67273324555485e-02 + 1.40693975554630e-02 2.86248786440320e-02 + 1.59938671904845e-02 3.05326851588142e-02 + 1.80320179344073e-02 3.24804018390111e-02 + 2.01525184247463e-02 3.45030950602257e-02 + 2.24382250539517e-02 3.65190950131922e-02 + 2.48676010790424e-02 3.85540869978262e-02 + 2.74438995195706e-02 4.06048186992883e-02 + 3.01630613080321e-02 4.26855478409807e-02 + 3.30131439394830e-02 4.48150556811931e-02 + 3.60078117153417e-02 4.69819958893802e-02 + 3.91555926213345e-02 4.91831364532758e-02 + 4.24650818770967e-02 5.14111490804253e-02 + 4.59463399533206e-02 5.36584113782445e-02 + 4.96085019195341e-02 5.59187875417100e-02 + 5.34304029583731e-02 5.82339756158755e-02 + 5.74506053673470e-02 6.05464382961678e-02 + 6.16688433559805e-02 6.28675145510649e-02 + 6.60761101690652e-02 6.52205906481849e-02 + 7.06771229650270e-02 6.76087786085493e-02 + 7.54534564656442e-02 7.00783385211843e-02 + 8.04871181124642e-02 7.24796963744080e-02 + 8.57417937708899e-02 7.48942120614805e-02 + 9.11943707542743e-02 7.73854695174959e-02 + 9.68950720892806e-02 7.98566713262581e-02 + 1.02847573387230e-01 8.22876079010535e-02 + 1.09044858215908e-01 8.47210179791181e-02 + 1.15490222891971e-01 8.71750070246340e-02 + 1.22192184613505e-01 8.96434844224979e-02 + 1.29160511286559e-01 9.21174420433711e-02 + 1.36425397154230e-01 9.45156825723323e-02 + 1.43963785764342e-01 9.69333711278718e-02 + 1.51780847657248e-01 9.93726343552587e-02 + 1.59901053759045e-01 1.01772022005663e-01 + 1.68330718517798e-01 1.04124856132688e-01 + 1.77078093160315e-01 1.06417242140794e-01 + 1.86152768336554e-01 1.08626721316434e-01 + 1.95547957086479e-01 1.10808018380726e-01 + 2.05262344651788e-01 1.12982949744755e-01 + 2.15316288411784e-01 1.15080703683943e-01 + 2.25727640430810e-01 1.17028842247463e-01 + 2.36486953294469e-01 1.18893468221244e-01 + 2.47606103597236e-01 1.20613966312300e-01 + 2.59082067962401e-01 1.22236590592394e-01 + 2.70915428466803e-01 1.23770388922269e-01 + 2.83123302721779e-01 1.25093790952213e-01 + 2.95700040272605e-01 1.26248167564620e-01 + 3.08649339579229e-01 1.27202204411106e-01 + 3.21973207911371e-01 1.27886002490200e-01 + 3.35666915940575e-01 1.28336009455904e-01 + 3.49729856148137e-01 1.28515938919406e-01 + 3.64156044605897e-01 1.28322082434802e-01 + 3.78943465936109e-01 1.27872557734258e-01 + 3.94083763263825e-01 1.27105654197604e-01 + 4.09575696342703e-01 1.26076864381629e-01 + 4.25414011369775e-01 1.24776753517338e-01 + 4.41593423933488e-01 1.23203803654028e-01 + 4.58118698550793e-01 1.21453065442532e-01 + 4.74969289264106e-01 1.19379481227578e-01 + 4.92141581296370e-01 1.17024136753557e-01 + 5.09640928459442e-01 1.14468473774205e-01 + 5.27459181191729e-01 1.11706370002499e-01 + 5.45579400762510e-01 1.08675938318902e-01 + 5.64000646601103e-01 1.05430671339811e-01 + 5.82720846933108e-01 1.02001576810010e-01 + 6.01731586141294e-01 9.83969151548686e-02 + 6.21010755973352e-01 9.45591973944104e-02 + 6.40543478738464e-01 9.04796724759952e-02 + 6.60338537645302e-01 8.62499884007561e-02 + 6.80385825453853e-01 8.18833516289867e-02 + 7.00661796733097e-01 7.73360839181257e-02 + 7.21167806331622e-01 7.26753969763489e-02 + 7.41887916488567e-01 6.78960039061239e-02 + 7.62806892564257e-01 6.29998067215964e-02 + 7.83908861634844e-01 5.79878832722068e-02 + 8.05177351436274e-01 5.28629172742288e-02 + 8.26595261100184e-01 4.76276642630319e-02 + 8.48144449629654e-01 4.22843337759070e-02 + 8.69827140629476e-01 3.69111819966000e-02 + 8.91604637206406e-01 3.14360883953754e-02 + 9.13481489167149e-01 2.59485561418769e-02 + 9.35413129302637e-01 2.03601258502341e-02 + 9.57385180896840e-01 1.40200210251241e-02 + 9.79362661611973e-01 7.10265085432084e-03 + 1.00000000000000e+00 -1.07577592503420e-05 diff --git a/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF21_Coords.txt b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF21_Coords.txt new file mode 100644 index 00000000..388e7950 --- /dev/null +++ b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF21_Coords.txt @@ -0,0 +1,208 @@ + 201 NumCoords ! The number of coordinates in the airfoil shape file (including an extra coordinate for airfoil reference). Set to zero if coordinates not included. +! ......... x-y coordinates are next if NumCoords > 0 ............. +! x-y coordinate of airfoil reference +! x/c y/c + 0.250000 0 +! coordinates of airfoil shape +! interpolation to 200 points +! x/c y/c + 1.00000000000000e+00 -2.84740725711342e-05 + 9.76865338872185e-01 2.85428304137865e-03 + 9.53929219800446e-01 5.24327408174464e-03 + 9.30868587354945e-01 7.20751732930949e-03 + 9.07757786371386e-01 8.68022664963385e-03 + 8.84685981963589e-01 9.16779767337892e-03 + 8.61737273650503e-01 8.59878745573448e-03 + 8.38982716451081e-01 6.97032631101525e-03 + 8.16487465310072e-01 4.27790070293695e-03 + 7.94307280144394e-01 5.98958387499667e-04 + 7.72478209244049e-01 -3.92421216988763e-03 + 7.51009294443888e-01 -9.11447969158894e-03 + 7.29917171589636e-01 -1.48652160246661e-02 + 7.09173987466613e-01 -2.09915209310793e-02 + 6.88759055777041e-01 -2.73426738600162e-02 + 6.68666517410726e-01 -3.38483930358717e-02 + 6.48890300856279e-01 -4.04237940323079e-02 + 6.29411879426884e-01 -4.69774888101651e-02 + 6.10190624345359e-01 -5.33527496658855e-02 + 5.91235514841636e-01 -5.95364517406264e-02 + 5.72549427006805e-01 -6.54947690043992e-02 + 5.54098681203993e-01 -7.10990749251103e-02 + 5.35920827161821e-01 -7.64189417500869e-02 + 5.18012958869965e-01 -8.14046707993908e-02 + 5.00370906490186e-01 -8.60216565775983e-02 + 4.82998993642838e-01 -9.02272377996711e-02 + 4.65913482233682e-01 -9.40474533539546e-02 + 4.49125729712078e-01 -9.74967264248575e-02 + 4.32639419880572e-01 -1.00542965307158e-01 + 4.16459539589475e-01 -1.03161374243716e-01 + 4.00613215473433e-01 -1.05466420900906e-01 + 3.85098707684728e-01 -1.07402177176065e-01 + 3.69931266330609e-01 -1.09020571824359e-01 + 3.55119768331056e-01 -1.10391209715929e-01 + 3.40661821755905e-01 -1.11451999694907e-01 + 3.26563430473896e-01 -1.12194090288857e-01 + 3.12830956759217e-01 -1.12692769163857e-01 + 2.99465542002860e-01 -1.12952761784846e-01 + 2.86469704616211e-01 -1.12949992221423e-01 + 2.73843543674708e-01 -1.12766407873851e-01 + 2.61586025508254e-01 -1.12380265536283e-01 + 2.49698014015215e-01 -1.11799275824114e-01 + 2.38180021002129e-01 -1.11005012677545e-01 + 2.27020875450809e-01 -1.10103654156307e-01 + 2.16226137874301e-01 -1.09019236030612e-01 + 2.05793116599237e-01 -1.07760935076377e-01 + 1.95709833948425e-01 -1.06391330139806e-01 + 1.85971073779880e-01 -1.04935019609158e-01 + 1.76583031796272e-01 -1.03315378553033e-01 + 1.67520981485238e-01 -1.01654758321660e-01 + 1.58802515906259e-01 -9.98409591053214e-02 + 1.50385000970262e-01 -9.80499859448751e-02 + 1.42298158727063e-01 -9.61306196719593e-02 + 1.34516269147850e-01 -9.41634136087469e-02 + 1.27037305703638e-01 -9.21442045117529e-02 + 1.19859512781939e-01 -9.00492381147093e-02 + 1.12952800949352e-01 -8.79682875564088e-02 + 1.06339499636755e-01 -8.58264580885655e-02 + 1.00007414389900e-01 -8.36143627290609e-02 + 9.39147764330701e-02 -8.14516604635932e-02 + 8.80868393032252e-02 -7.92537536059723e-02 + 8.24946159428780e-02 -7.70801723815972e-02 + 7.71274250919293e-02 -7.49012538073132e-02 + 7.20190535116052e-02 -7.26564811445412e-02 + 6.71057079852937e-02 -7.03934414720974e-02 + 6.24118140095744e-02 -6.80431207723954e-02 + 5.79644757418812e-02 -6.56460890316721e-02 + 5.37333540900433e-02 -6.32481286299431e-02 + 4.96893756299879e-02 -6.08884959776765e-02 + 4.58534457561426e-02 -5.85255201649711e-02 + 4.22083319889390e-02 -5.61793213837462e-02 + 3.87596121937182e-02 -5.38383821901660e-02 + 3.55057922281837e-02 -5.14962236665323e-02 + 3.24322743559543e-02 -4.91703134749231e-02 + 2.95264783129621e-02 -4.68695823371802e-02 + 2.67683318695932e-02 -4.46098816905116e-02 + 2.41934701367245e-02 -4.23573844305122e-02 + 2.18548607049960e-02 -4.00989773901928e-02 + 1.96524338700715e-02 -3.78875178579182e-02 + 1.75755260431319e-02 -3.57232070150690e-02 + 1.56358377059865e-02 -3.35811088781324e-02 + 1.38207984844720e-02 -3.14734077737011e-02 + 1.21180061661380e-02 -2.94102107211683e-02 + 1.05254874189780e-02 -2.73912953793136e-02 + 9.09360929036987e-03 -2.53625298476404e-02 + 7.72181822309867e-03 -2.34101512080760e-02 + 6.49763138245874e-03 -2.14641052056444e-02 + 5.40871842169344e-03 -1.95429445805207e-02 + 4.40961919998241e-03 -1.76727016085954e-02 + 3.55040219006997e-03 -1.58276863888619e-02 + 2.80808183134115e-03 -1.40194239937278e-02 + 2.14649703528823e-03 -1.22634144788593e-02 + 1.59920737776881e-03 -1.05527195276620e-02 + 1.14930375044154e-03 -8.88654178716626e-03 + 8.10231534512569e-04 -7.26673074294147e-03 + 4.78895883677518e-04 -5.71256790934727e-03 + 2.63639401109400e-04 -4.20252872193405e-03 + 1.11557989496940e-04 -2.74745794723513e-03 + 3.44756369415605e-05 -1.34604561592499e-03 + 0.00000000000000e+00 0.00000000000000e+00 + 3.20816693922806e-05 1.34573179197360e-03 + 1.07094538044363e-04 2.74581135191723e-03 + 2.61023002477552e-04 4.19787122797409e-03 + 4.70744609715971e-04 5.70378084563639e-03 + 8.02668778110153e-04 7.25269694625556e-03 + 1.18211679499553e-03 8.85342213515878e-03 + 1.62613136894154e-03 1.05133892427942e-02 + 2.35095850098151e-03 1.21472955138763e-02 + 3.11291707163376e-03 1.38451043913963e-02 + 4.06681615370234e-03 1.55343607101053e-02 + 5.10318321837548e-03 1.72662509388141e-02 + 6.28537915014080e-03 1.90038719565046e-02 + 7.59081076018542e-03 2.07586526711072e-02 + 8.98284133346192e-03 2.25595390649685e-02 + 1.05048772029216e-02 2.43750659231944e-02 + 1.21173705320911e-02 2.62396209517460e-02 + 1.38724687721741e-02 2.81092919141236e-02 + 1.57628531446385e-02 2.99916503138032e-02 + 1.77668024925910e-02 3.19129888938685e-02 + 1.98560304119069e-02 3.39051089397272e-02 + 2.21065209505667e-02 3.58935725801445e-02 + 2.44975644102754e-02 3.79031615747998e-02 + 2.70332347408878e-02 3.99299291146165e-02 + 2.97109628466766e-02 4.19867024992787e-02 + 3.25200587654925e-02 4.40903080891470e-02 + 3.54726867654753e-02 4.62315479726106e-02 + 3.85766530005811e-02 4.84076241040826e-02 + 4.18413693987001e-02 5.06110330462258e-02 + 4.52764942398936e-02 5.28343865988492e-02 + 4.88907425761762e-02 5.50724163659514e-02 + 5.26646691476036e-02 5.73640816538310e-02 + 5.66345029639527e-02 5.96558451069643e-02 + 6.08009395375298e-02 6.19577340085226e-02 + 6.51558010698599e-02 6.42917617552471e-02 + 6.97040980071108e-02 6.66604081412036e-02 + 7.44292782322818e-02 6.91063981945018e-02 + 7.94075911539318e-02 7.14919169255233e-02 + 8.46064336120551e-02 7.38912356977943e-02 + 9.00046646171667e-02 7.63634375717562e-02 + 9.56495329755105e-02 7.88186816028507e-02 + 1.01544707534728e-01 8.12061081549737e-02 + 1.07684393957011e-01 8.35823621854077e-02 + 1.14072629815357e-01 8.59820974163730e-02 + 1.20717936678019e-01 8.83984296232361e-02 + 1.27629750106332e-01 9.08236951338500e-02 + 1.34836465041941e-01 9.31733181108972e-02 + 1.42317922535003e-01 9.55435716133629e-02 + 1.50079297300981e-01 9.79421782603361e-02 + 1.58143784516036e-01 1.00304899967289e-01 + 1.66517972957835e-01 1.02624809036553e-01 + 1.75210207161683e-01 1.04888579553756e-01 + 1.84229946037827e-01 1.07074677598208e-01 + 1.93571360679093e-01 1.09243451986783e-01 + 2.03234945574175e-01 1.11402415125159e-01 + 2.13239205546370e-01 1.13491436907172e-01 + 2.23601537222704e-01 1.15440504439587e-01 + 2.34314315339563e-01 1.17306503096526e-01 + 2.45388676682413e-01 1.19037311828905e-01 + 2.56822498877269e-01 1.20681072953816e-01 + 2.68616771371790e-01 1.22241825144540e-01 + 2.80788220103666e-01 1.23601558631169e-01 + 2.93331680600211e-01 1.24805212165338e-01 + 3.06251511490344e-01 1.25807926970102e-01 + 3.19549745336724e-01 1.26554338608240e-01 + 3.33222453479109e-01 1.27061326118213e-01 + 3.47269018943833e-01 1.27298091243991e-01 + 3.61683948293755e-01 1.27170458380383e-01 + 3.76464979016090e-01 1.26770572192297e-01 + 3.91604054165987e-01 1.26048320133488e-01 + 4.07099743027696e-01 1.25063728629558e-01 + 4.22946891110087e-01 1.23804897872974e-01 + 4.39140508807244e-01 1.22276792353123e-01 + 4.55684294155409e-01 1.20554509111602e-01 + 4.72559601516541e-01 1.18524015966612e-01 + 4.89761912975334e-01 1.16207419090395e-01 + 5.07296139266516e-01 1.13684964275664e-01 + 5.25154357085284e-01 1.10950890395180e-01 + 5.43320252389640e-01 1.07950681161174e-01 + 5.61792716627316e-01 1.04735757711390e-01 + 5.80568803339265e-01 1.01328525940682e-01 + 5.99640262789189e-01 9.77381351876646e-02 + 6.18986539924185e-01 9.39237635066851e-02 + 6.38592769146560e-01 8.98769749368346e-02 + 6.58465976460566e-01 8.56827556065770e-02 + 6.78595728050462e-01 8.13433005574353e-02 + 6.98959863838616e-01 7.68298671125305e-02 + 7.19558497677296e-01 7.21964039086358e-02 + 7.40375559459272e-01 6.74380995266311e-02 + 7.61395509952232e-01 6.25588162368450e-02 + 7.82602242599360e-01 5.75571816126900e-02 + 8.03979199523738e-01 5.24376017015890e-02 + 8.25508947220265e-01 4.72044836666912e-02 + 8.47173082201993e-01 4.18658829372147e-02 + 8.68972243269945e-01 3.64790803343795e-02 + 8.90869140608345e-01 3.09938752249591e-02 + 9.12865896627548e-01 2.54780934053288e-02 + 9.34919781152421e-01 1.98727453143736e-02 + 9.57016514682770e-01 1.36303405789984e-02 + 9.79120888238619e-01 6.90832082291697e-03 + 1.00000000000000e+00 3.57170593908316e-05 diff --git a/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF22_Coords.txt b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF22_Coords.txt new file mode 100644 index 00000000..ee67f764 --- /dev/null +++ b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF22_Coords.txt @@ -0,0 +1,208 @@ + 201 NumCoords ! The number of coordinates in the airfoil shape file (including an extra coordinate for airfoil reference). Set to zero if coordinates not included. +! ......... x-y coordinates are next if NumCoords > 0 ............. +! x-y coordinate of airfoil reference +! x/c y/c + 0.250000 0 +! coordinates of airfoil shape +! interpolation to 200 points +! x/c y/c + 1.00000000000000e+00 -1.37905772906987e-04 + 9.76725991935908e-01 2.75905550847849e-03 + 9.53631351611733e-01 5.18607754339260e-03 + 9.30439467907717e-01 7.21116637405844e-03 + 9.07208132179710e-01 8.76441631458846e-03 + 8.84013496158046e-01 9.51161259804528e-03 + 8.60933319861523e-01 9.19547841137385e-03 + 8.38035712490432e-01 7.96595476402018e-03 + 8.15385168895348e-01 5.62847327150540e-03 + 7.93037657818789e-01 2.28558101061580e-03 + 7.71032949299981e-01 -1.90093741181228e-03 + 7.49384114270963e-01 -6.76049461633643e-03 + 7.28106510273087e-01 -1.21725858076415e-02 + 7.07180107191085e-01 -1.79684774976327e-02 + 6.86585882704839e-01 -2.39949416112886e-02 + 6.66322327664117e-01 -3.01870419451860e-02 + 6.46380042253330e-01 -3.64467876017566e-02 + 6.26744157329858e-01 -4.26868759536930e-02 + 6.07380274045402e-01 -4.87646156436792e-02 + 5.88295958690534e-01 -5.46605390281692e-02 + 5.69492521413567e-01 -6.03344111379996e-02 + 5.50944917753757e-01 -6.56813210738157e-02 + 5.32683529719922e-01 -7.07499443242120e-02 + 5.14706548079326e-01 -7.54948621351449e-02 + 4.97012214427392e-01 -7.98856360729547e-02 + 4.79604661938784e-01 -8.38829246167327e-02 + 4.62499971271577e-01 -8.75164861473946e-02 + 4.45707439025159e-01 -9.07910364185073e-02 + 4.29232251749769e-01 -9.36853302638665e-02 + 4.13079887518895e-01 -9.61843197334282e-02 + 3.97273156999330e-01 -9.83823772625506e-02 + 3.81811499955324e-01 -1.00238171273862e-01 + 3.66707654879754e-01 -1.01796983957391e-01 + 3.51968873020320e-01 -1.03118493586559e-01 + 3.37592692843044e-01 -1.04152291381984e-01 + 3.23583613955391e-01 -1.04892228070397e-01 + 3.09945962441104e-01 -1.05403595252986e-01 + 2.96679877893668e-01 -1.05689666745533e-01 + 2.83786673843868e-01 -1.05732022868329e-01 + 2.71265428998315e-01 -1.05601326789481e-01 + 2.59114641005256e-01 -1.05279433841182e-01 + 2.47334122817983e-01 -1.04772898258849e-01 + 2.35922762413987e-01 -1.04073450080798e-01 + 2.24871859339431e-01 -1.03261410015675e-01 + 2.14183854398850e-01 -1.02280347491613e-01 + 2.03856443420195e-01 -1.01137855951245e-01 + 1.93878365466042e-01 -9.98859412460872e-02 + 1.84243680326433e-01 -9.85473584321357e-02 + 1.74956557366324e-01 -9.70603160684741e-02 + 1.65996483607503e-01 -9.55230954068784e-02 + 1.57374597017771e-01 -9.38510527263059e-02 + 1.49055367342827e-01 -9.21872601100961e-02 + 1.41061804544547e-01 -9.04086149008263e-02 + 1.33371830662132e-01 -8.85813343893779e-02 + 1.25981833168783e-01 -8.67037376102544e-02 + 1.18889524396252e-01 -8.47556746420726e-02 + 1.12068484997073e-01 -8.28134777714908e-02 + 1.05533508673527e-01 -8.08202882655789e-02 + 9.92765954754487e-02 -7.87616970055698e-02 + 9.32618460232315e-02 -7.67377034670206e-02 + 8.75063188947793e-02 -7.46839878289475e-02 + 8.19865845292902e-02 -7.26460887111042e-02 + 7.66696758964058e-02 -7.06018837113606e-02 + 7.16044906719353e-02 -6.85025449105124e-02 + 6.67363367619081e-02 -6.63816283727544e-02 + 6.20862671655154e-02 -6.41837626120213e-02 + 5.76781158267178e-02 -6.19465872092337e-02 + 5.34835811930607e-02 -5.97092958338184e-02 + 4.94762917876905e-02 -5.75018783824138e-02 + 4.56743711349976e-02 -5.52907634791866e-02 + 4.20616172369434e-02 -5.30929364276299e-02 + 3.86426064710656e-02 -5.08998396737268e-02 + 3.54153788093397e-02 -4.87062512082961e-02 + 3.23662010540160e-02 -4.65256202361847e-02 + 2.94833263627923e-02 -4.43663553536911e-02 + 2.67477674550665e-02 -4.22428674968400e-02 + 2.41915370057616e-02 -4.01273164512632e-02 + 2.18857573818062e-02 -3.80078237337925e-02 + 1.97179884024849e-02 -3.59301627477569e-02 + 1.76757845498892e-02 -3.38938481159999e-02 + 1.57641027306169e-02 -3.18781262584388e-02 + 1.39724593422236e-02 -2.98931987545935e-02 + 1.22918968479213e-02 -2.79480618328304e-02 + 1.07221372201749e-02 -2.60416137215328e-02 + 9.28872160500910e-03 -2.41314304207875e-02 + 7.91630048953282e-03 -2.22853322080103e-02 + 6.67953167608040e-03 -2.04480781470025e-02 + 5.57389618300349e-03 -1.86324963909326e-02 + 4.56332093730877e-03 -1.68598162507488e-02 + 3.68524480226045e-03 -1.51108431623255e-02 + 2.91938579202685e-03 -1.33953381237321e-02 + 2.24116079129066e-03 -1.17246173969605e-02 + 1.67248583161617e-03 -1.00953735229212e-02 + 1.20324454848532e-03 -8.50604304796152e-03 + 8.41606529174913e-04 -6.95951603892573e-03 + 5.04718335749302e-04 -5.47175146445821e-03 + 2.77648316387901e-04 -4.02638290581776e-03 + 1.17748797893260e-04 -2.63253995295761e-03 + 3.69468292642352e-05 -1.28969548263411e-03 + 0.00000000000000e+00 0.00000000000000e+00 + 3.09535021918612e-05 1.28936436929246e-03 + 1.06637401949987e-04 2.63142100210815e-03 + 2.59964572072159e-04 4.02351019908418e-03 + 4.69920111426106e-04 5.46706336175963e-03 + 7.96541452526313e-04 6.95306199333623e-03 + 1.17401205379525e-03 8.48786363886347e-03 + 1.61831089593917e-03 1.00770346353190e-02 + 2.32333874774940e-03 1.16504559884271e-02 + 3.06712959817167e-03 1.32804282822632e-02 + 3.98276803748560e-03 1.49090049113570e-02 + 4.98344743343845e-03 1.65770603791945e-02 + 6.11996090735756e-03 1.82551557640217e-02 + 7.37297343445192e-03 1.99533035573824e-02 + 8.71286539087883e-03 2.16948370578646e-02 + 1.01765501551493e-02 2.34537701968742e-02 + 1.17322670694759e-02 2.52581891303742e-02 + 1.34217992141067e-02 2.70733747583812e-02 + 1.52388298301360e-02 2.89063564237294e-02 + 1.71688461558914e-02 3.07767937542747e-02 + 1.91899331878790e-02 3.27097377805680e-02 + 2.13638093661363e-02 3.46457797783486e-02 + 2.36723297656305e-02 3.66070405437775e-02 + 2.61211854117630e-02 3.85883561887161e-02 + 2.87097811699761e-02 4.06004475067315e-02 + 3.14304301249726e-02 4.26557978654197e-02 + 3.42931270832587e-02 4.47486944963130e-02 + 3.73038188445460e-02 4.68776749211300e-02 + 4.04730361230994e-02 4.90353694174481e-02 + 4.38097981156242e-02 5.12147401773910e-02 + 4.73220204778543e-02 5.34122475810596e-02 + 5.09939923040230e-02 5.56608916859612e-02 + 5.48571252255563e-02 5.79155152658394e-02 + 5.89138291139096e-02 6.01837002893103e-02 + 6.31577497344129e-02 6.24845191863370e-02 + 6.75947899647940e-02 6.48186842922515e-02 + 7.22122652229698e-02 6.72216823767386e-02 + 7.70740114758716e-02 6.95807319849553e-02 + 8.21553322345438e-02 7.19550902719777e-02 + 8.74394236745447e-02 7.43941379373109e-02 + 9.29672017196781e-02 7.68226772209049e-02 + 9.87424021686052e-02 7.91978116359561e-02 + 1.04761752867740e-01 8.15667320414124e-02 + 1.11030780081871e-01 8.39572315421679e-02 + 1.17558018563720e-01 8.63625746301939e-02 + 1.24352270186846e-01 8.87774608495421e-02 + 1.31438105054613e-01 9.11321173164249e-02 + 1.38801313550205e-01 9.35029309525731e-02 + 1.46447393656373e-01 9.58971156573319e-02 + 1.54396766312990e-01 9.82613258248415e-02 + 1.62656569565700e-01 1.00588261686332e-01 + 1.71235347766832e-01 1.02865843879122e-01 + 1.80142279870852e-01 1.05076149462146e-01 + 1.89373799652761e-01 1.07269345993908e-01 + 1.98933590722142e-01 1.09443191127768e-01 + 2.08836636556623e-01 1.11554276573076e-01 + 2.19099471288483e-01 1.13540075332887e-01 + 2.29717904676441e-01 1.15442617819263e-01 + 2.40701766215834e-01 1.17220973164961e-01 + 2.52050933191971e-01 1.18911560197852e-01 + 2.63767077262110e-01 1.20517086973916e-01 + 2.75865949946677e-01 1.21934154882854e-01 + 2.88343581116220e-01 1.23201688742876e-01 + 3.01205334203085e-01 1.24270880831573e-01 + 3.14453408998862e-01 1.25097439258154e-01 + 3.28085392677879e-01 1.25681829879209e-01 + 3.42100675917614e-01 1.25997636647737e-01 + 3.56494768423971e-01 1.25962526629538e-01 + 3.71264984512598e-01 1.25638758942093e-01 + 3.86403905621335e-01 1.24988484201363e-01 + 4.01909708696471e-01 1.24068994185517e-01 + 4.17777487590764e-01 1.22870793211783e-01 + 4.34002789914367e-01 1.21403723025625e-01 + 4.50587361686721e-01 1.19722425477543e-01 + 4.67516097146081e-01 1.17745691253289e-01 + 4.84783008098729e-01 1.15478338348871e-01 + 5.02391973551338e-01 1.12996226374276e-01 + 5.20335411416213e-01 1.10293881931109e-01 + 5.38598443680468e-01 1.07327040011182e-01 + 5.57179445389403e-01 1.04143490655964e-01 + 5.76073870986909e-01 1.00758354775127e-01 + 5.95273625837750e-01 9.71818954906031e-02 + 6.14761209512960e-01 9.33892639430016e-02 + 6.34522016454894e-01 8.93721485884786e-02 + 6.54559394245177e-01 8.52121018071187e-02 + 6.74862300856641e-01 8.08992604208061e-02 + 6.95411169374383e-01 7.64180821116692e-02 + 7.16203679512635e-01 7.18100281693020e-02 + 7.37223461079002e-01 6.70709646616096e-02 + 7.58454521150695e-01 6.22070114365566e-02 + 7.79880103179641e-01 5.72143218232588e-02 + 8.01483398149160e-01 5.20988678810583e-02 + 8.23246404130259e-01 4.68667510151217e-02 + 8.45150485874660e-01 4.15319681044740e-02 + 8.67192695150624e-01 3.61314252690582e-02 + 8.89338539461505e-01 3.06353825258196e-02 + 9.11585423298854e-01 2.50909095333333e-02 + 9.33894494503434e-01 1.94679731415527e-02 + 9.56251121560769e-01 1.33384432495636e-02 + 9.78619325570430e-01 6.83697775457594e-03 + 1.00000000000000e+00 2.05198748460235e-04 diff --git a/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF23_Coords.txt b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF23_Coords.txt new file mode 100644 index 00000000..b7ccee65 --- /dev/null +++ b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF23_Coords.txt @@ -0,0 +1,208 @@ + 201 NumCoords ! The number of coordinates in the airfoil shape file (including an extra coordinate for airfoil reference). Set to zero if coordinates not included. +! ......... x-y coordinates are next if NumCoords > 0 ............. +! x-y coordinate of airfoil reference +! x/c y/c + 0.250000 0 +! coordinates of airfoil shape +! interpolation to 200 points +! x/c y/c + 1.00000000000000e+00 -3.89631805446465e-04 + 9.76523223440909e-01 2.57752479218257e-03 + 9.53190468875220e-01 5.08428616099728e-03 + 9.29793700110228e-01 7.19463079459903e-03 + 9.06373069230989e-01 8.83683936265999e-03 + 8.82989474321167e-01 9.75643931673717e-03 + 8.59712867174704e-01 9.61496203663975e-03 + 8.36607653336429e-01 8.67096288412905e-03 + 8.13736696364153e-01 6.61459865723342e-03 + 7.91156003915796e-01 3.56436965978782e-03 + 7.68908626920759e-01 -3.19229213119966e-04 + 7.47012054504006e-01 -4.87284377280892e-03 + 7.25479893786865e-01 -9.96177887707548e-03 + 7.04301598747634e-01 -1.54349458980302e-02 + 6.83461873027533e-01 -2.11434442792537e-02 + 6.62962284386421e-01 -2.70203050251467e-02 + 6.42791629284883e-01 -3.29619235742479e-02 + 6.22938362223096e-01 -3.88812963489969e-02 + 6.03377191897424e-01 -4.46577924076831e-02 + 5.84113605921901e-01 -5.02638611712951e-02 + 5.65147058057943e-01 -5.56526737727627e-02 + 5.46463242401931e-01 -6.07476183166026e-02 + 5.28083600651341e-01 -6.55730561886808e-02 + 5.10007892084025e-01 -7.00900567751652e-02 + 4.92236196987507e-01 -7.42679957358169e-02 + 4.74773357090323e-01 -7.80766311425804e-02 + 4.57634431292357e-01 -8.15460818492506e-02 + 4.40826245471248e-01 -8.46702707193481e-02 + 4.24355029015101e-01 -8.74363864527718e-02 + 4.08227124292632e-01 -8.98419112116650e-02 + 3.92459570866590e-01 -9.19539503766752e-02 + 3.77053268096062e-01 -9.37469616449339e-02 + 3.62017890326388e-01 -9.52572816145339e-02 + 3.47358922971653e-01 -9.65314596619472e-02 + 3.33074130797390e-01 -9.75316311345544e-02 + 3.19166552441191e-01 -9.82568017865109e-02 + 3.05638457789601e-01 -9.87570424765259e-02 + 2.92489196946871e-01 -9.90352109981780e-02 + 2.79718896446607e-01 -9.90816142636686e-02 + 2.67325715523272e-01 -9.89532661236331e-02 + 2.55307554299133e-01 -9.86395210813088e-02 + 2.43662963759620e-01 -9.81468679323721e-02 + 2.32389051593200e-01 -9.74790188542946e-02 + 2.21479352444559e-01 -9.66892453470001e-02 + 2.10932960713701e-01 -9.57430626738486e-02 + 2.00746891023561e-01 -9.46523604003965e-02 + 1.90911241857401e-01 -9.34530543544128e-02 + 1.81419357741535e-01 -9.21641429584474e-02 + 1.72272201518936e-01 -9.07467422355202e-02 + 1.63454036160759e-01 -8.92690930011261e-02 + 1.54968504898213e-01 -8.76805069244906e-02 + 1.46789032362938e-01 -8.60792825829244e-02 + 1.38929389926432e-01 -8.43836334579841e-02 + 1.31372073509835e-01 -8.26402323580097e-02 + 1.24111669738838e-01 -8.08497501671892e-02 + 1.17144601558583e-01 -7.89996633722882e-02 + 1.10449627383806e-01 -7.71449373419936e-02 + 1.04032527949034e-01 -7.52514037061188e-02 + 9.78887241867816e-02 -7.33057936883226e-02 + 9.19902897469441e-02 -7.13774864507213e-02 + 8.63446174524882e-02 -6.94278850804577e-02 + 8.09349931912135e-02 -6.74837749535468e-02 + 7.57176279736417e-02 -6.55345654926341e-02 + 7.07422636872318e-02 -6.35487599075303e-02 + 6.59681013466920e-02 -6.15577280140700e-02 + 6.14091796784638e-02 -5.95276219887417e-02 + 5.70825310884753e-02 -5.74696232341217e-02 + 5.29640917916176e-02 -5.54139826908802e-02 + 4.90331099431885e-02 -5.33787557780121e-02 + 4.53019232083321e-02 -5.13412852201466e-02 + 4.17564728311483e-02 -4.93141304770355e-02 + 3.83992522495016e-02 -4.72921118209637e-02 + 3.52273324651378e-02 -4.52718650652909e-02 + 3.22287783868937e-02 -4.32621299402485e-02 + 2.93935765607861e-02 -4.12701495319455e-02 + 2.67049962322860e-02 -3.93074868211488e-02 + 2.41875159700224e-02 -3.73546300420540e-02 + 2.19051355335849e-02 -3.54024649802942e-02 + 1.97596598780863e-02 -3.34865723449696e-02 + 1.77404917592603e-02 -3.16046902103228e-02 + 1.58480959117786e-02 -2.97420661384396e-02 + 1.40731937772208e-02 -2.79068578544306e-02 + 1.24092192372854e-02 -2.61060448917434e-02 + 1.08572800374988e-02 -2.43371683353192e-02 + 9.42416939885715e-03 -2.25730887258294e-02 + 8.05945666798942e-03 -2.08575096912792e-02 + 6.81900211726789e-03 -1.91549248355902e-02 + 5.70427188596224e-03 -1.74708678303986e-02 + 4.68929550551071e-03 -1.58203951766527e-02 + 3.79718481534846e-03 -1.41925025018919e-02 + 3.01254414274189e-03 -1.25940941416061e-02 + 2.32306506044275e-03 -1.10313592778986e-02 + 1.73616370284593e-03 -9.50573827422768e-03 + 1.25001115654578e-03 -8.01464961151014e-03 + 8.66582941084615e-04 -6.56215809631841e-03 + 5.27892943221305e-04 -5.15982819826281e-03 + 2.90620181051750e-04 -3.79793930383067e-03 + 1.24304967749036e-04 -2.48335242246912e-03 + 3.96737576866571e-05 -1.21650060438702e-03 + 0.00000000000000e+00 0.00000000000000e+00 + 2.95189184277812e-05 1.21614429607452e-03 + 1.05767060451514e-04 2.48286216056600e-03 + 2.57762778152470e-04 3.79720959162143e-03 + 4.68204860110995e-04 5.16008910759149e-03 + 7.83797140932723e-04 6.56497526010459e-03 + 1.15715502367995e-03 8.01500849124157e-03 + 1.60204509969143e-03 9.51313492711731e-03 + 2.26838290451738e-03 1.10094565184360e-02 + 2.98389530162135e-03 1.25531639212653e-02 + 3.84468300573088e-03 1.41052049491652e-02 + 4.79382432709198e-03 1.56929490788932e-02 + 5.86480251491728e-03 1.72970451450205e-02 + 7.04339712537743e-03 1.89252483507722e-02 + 8.31036366558127e-03 2.05930697348407e-02 + 9.69288686144440e-03 2.22822382309425e-02 + 1.11694244157683e-02 2.40125728679872e-02 + 1.27687195678609e-02 2.57610052570714e-02 + 1.44855480622724e-02 2.75340521574697e-02 + 1.63141117762223e-02 2.93431371358707e-02 + 1.82409459730255e-02 3.12044757360750e-02 + 2.03090129151232e-02 3.30784440112194e-02 + 2.25047656211822e-02 3.49825288350549e-02 + 2.48358954405978e-02 3.69102907266350e-02 + 2.73027851057594e-02 3.88709280586456e-02 + 2.99022786432083e-02 4.08708020979388e-02 + 3.26428835363264e-02 4.29073735254742e-02 + 3.55275801260422e-02 4.49815642845116e-02 + 3.85675366725734e-02 4.70868993056664e-02 + 4.17712151330545e-02 4.92166052451779e-02 + 4.51455848984656e-02 5.13693116705787e-02 + 4.86800832975236e-02 5.35697871829730e-02 + 5.23998258242555e-02 5.57840039693155e-02 + 5.63090699963194e-02 5.80167300546564e-02 + 6.04040077958621e-02 6.02830393557848e-02 + 6.46921254503434e-02 6.25806625362446e-02 + 6.91657933196187e-02 6.49357139206047e-02 + 7.38718601029010e-02 6.72692279831682e-02 + 7.87963189404003e-02 6.96202880139496e-02 + 8.39284216127343e-02 7.20249986111878e-02 + 8.93005278379212e-02 7.44277079926884e-02 + 9.49165785178080e-02 7.68080305069524e-02 + 1.00776596462740e-01 7.91941589367465e-02 + 1.06887992955234e-01 8.15979852235107e-02 + 1.13259326028114e-01 8.40133348371362e-02 + 1.19898645623439e-01 8.64376453292622e-02 + 1.26825363129969e-01 8.88246082279034e-02 + 1.34032996617006e-01 9.12209273262398e-02 + 1.41527923866446e-01 9.36300218950618e-02 + 1.49326736108375e-01 9.60160327660242e-02 + 1.57437264377705e-01 9.83712642438628e-02 + 1.65868324600152e-01 1.00685218752554e-01 + 1.74628718266615e-01 1.02944937223580e-01 + 1.83718250107745e-01 1.05182085806860e-01 + 1.93143977808745e-01 1.07387673596204e-01 + 2.02916723675256e-01 1.09537420256945e-01 + 2.13052007685298e-01 1.11578803647391e-01 + 2.23549653724373e-01 1.13536674601117e-01 + 2.34418102657221e-01 1.15382216081547e-01 + 2.45660047881914e-01 1.17132423550172e-01 + 2.57277821794247e-01 1.18790833197830e-01 + 2.69285661481619e-01 1.20274563173763e-01 + 2.81681435328113e-01 1.21610792504416e-01 + 2.94471299405458e-01 1.22753207590004e-01 + 3.07657839217654e-01 1.23665554126748e-01 + 3.21240423603742e-01 1.24335192568048e-01 + 3.35218492732312e-01 1.24739126354752e-01 + 3.49588853515411e-01 1.24807697648437e-01 + 3.64348393745959e-01 1.24573091480070e-01 + 3.79490557018895e-01 1.24009550543367e-01 + 3.95013008833302e-01 1.23166425873097e-01 + 4.10911230551784e-01 1.22040125894596e-01 + 4.27181368064296e-01 1.20643690185419e-01 + 4.43822979334143e-01 1.19012214211741e-01 + 4.60825027599087e-01 1.17096430824897e-01 + 4.78180176231373e-01 1.14887296599190e-01 + 4.95890785853081e-01 1.12452966207322e-01 + 5.13949537326196e-01 1.09787047252637e-01 + 5.32343642071341e-01 1.06859196176221e-01 + 5.51070553747742e-01 1.03710967331665e-01 + 5.70123937401839e-01 1.00351455565678e-01 + 5.89495628773574e-01 9.67909361070087e-02 + 6.09171898570426e-01 9.30211098562286e-02 + 6.29138822745811e-01 8.90355090111987e-02 + 6.49394868003684e-01 8.49035724050775e-02 + 6.69928293397831e-01 8.06107601158379e-02 + 6.90722533013325e-01 7.61534793554206e-02 + 7.11772271356487e-01 7.15640092699005e-02 + 7.33060707027799e-01 6.68388174833136e-02 + 7.54571508751324e-01 6.19858692115997e-02 + 7.76286826841553e-01 5.69994231785712e-02 + 7.98189415948090e-01 5.18865779509044e-02 + 8.20260703237170e-01 4.66547433653687e-02 + 8.42482201370411e-01 4.13224819490564e-02 + 8.64845816185461e-01 3.59114363001708e-02 + 8.87320554539452e-01 3.04068317544367e-02 + 9.09898081718863e-01 2.48403197190891e-02 + 9.32544737844051e-01 1.92037035893727e-02 + 9.55244628007707e-01 1.31962135682704e-02 + 9.77960328149588e-01 6.92447736867692e-03 + 1.00000000000000e+00 5.33569410323788e-04 diff --git a/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF24_Coords.txt b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF24_Coords.txt new file mode 100644 index 00000000..dee2a673 --- /dev/null +++ b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF24_Coords.txt @@ -0,0 +1,208 @@ + 201 NumCoords ! The number of coordinates in the airfoil shape file (including an extra coordinate for airfoil reference). Set to zero if coordinates not included. +! ......... x-y coordinates are next if NumCoords > 0 ............. +! x-y coordinate of airfoil reference +! x/c y/c + 0.250000 0 +! coordinates of airfoil shape +! interpolation to 200 points +! x/c y/c + 1.00000000000000e+00 -7.50291333776672e-04 + 9.76298896194702e-01 2.32889115261073e-03 + 9.52696096636841e-01 4.94521028450639e-03 + 9.29060312605788e-01 7.15692894407718e-03 + 9.05417910316586e-01 8.89067899641578e-03 + 8.81816184123139e-01 9.89569835581813e-03 + 8.58317705959904e-01 9.84322267766306e-03 + 8.34983301808537e-01 9.04823588658875e-03 + 8.11873434560873e-01 7.18374392840931e-03 + 7.89043919534343e-01 4.37297375841967e-03 + 7.66539540795448e-01 7.44223479357781e-04 + 7.44381391909662e-01 -3.54660860602751e-03 + 7.22581240917263e-01 -8.35156649411918e-03 + 7.01137346622867e-01 -1.35373495193734e-02 + 6.80039693873756e-01 -1.89641771354476e-02 + 6.59290364533785e-01 -2.45571754348028e-02 + 6.38878859868852e-01 -3.02132879449722e-02 + 6.18795535800661e-01 -3.58428941592947e-02 + 5.99025214360609e-01 -4.13502377144402e-02 + 5.79571063345178e-01 -4.66989833430834e-02 + 5.60430857912260e-01 -5.18361266758138e-02 + 5.41600549487872e-01 -5.67126894278324e-02 + 5.23093012388221e-01 -6.13292557711388e-02 + 5.04909716783247e-01 -6.56538953621398e-02 + 4.87051293227111e-01 -6.96530548678958e-02 + 4.69524243044734e-01 -7.33080529423055e-02 + 4.52341821294675e-01 -7.66472468360973e-02 + 4.35508589614116e-01 -7.96544207222355e-02 + 4.19030914862448e-01 -8.23226920725703e-02 + 4.02916228417393e-01 -8.46623466695113e-02 + 3.87175637539370e-01 -8.67119738820041e-02 + 3.71811428132166e-01 -8.84606569575440e-02 + 3.56830409304917e-01 -8.99353602919689e-02 + 3.42236645717252e-01 -9.11689881156119e-02 + 3.28028443529475e-01 -9.21352973252990e-02 + 3.14207871794200e-01 -9.28394446226089e-02 + 3.00775731152437e-01 -9.33148765751533e-02 + 2.87731091983130e-01 -9.35649492324365e-02 + 2.75073270707374e-01 -9.35897732815692e-02 + 2.62799911559184e-01 -9.34332051784304e-02 + 2.50908328649408e-01 -9.30938200207195e-02 + 2.39395914296969e-01 -9.25789080830780e-02 + 2.28258324217990e-01 -9.19038525166016e-02 + 2.17490357613613e-01 -9.10978135960199e-02 + 2.07088466750961e-01 -9.01469095785202e-02 + 1.97047806459751e-01 -8.90697005309464e-02 + 1.87360260340612e-01 -8.78852780089872e-02 + 1.78018682210870e-01 -8.66086122363040e-02 + 1.69020258315682e-01 -8.52244126115397e-02 + 1.60353331264926e-01 -8.37720812851559e-02 + 1.52014939197557e-01 -8.22330718969560e-02 + 1.43987185788990e-01 -8.06620558758565e-02 + 1.36274091000982e-01 -7.90182608959080e-02 + 1.28862566102960e-01 -7.73292710854366e-02 + 1.21745655831401e-01 -7.55977296970018e-02 + 1.14917898957625e-01 -7.38189265766767e-02 + 1.08363637615901e-01 -7.20267149673762e-02 + 1.02080415985040e-01 -7.02081908521227e-02 + 9.60650562136330e-02 -6.83524876726988e-02 + 9.02979483004230e-02 -6.64992618936153e-02 + 8.47777986078614e-02 -6.46338463331624e-02 + 7.94941040279597e-02 -6.27654801484029e-02 + 7.44102991938022e-02 -6.08945434432346e-02 + 6.95582747844778e-02 -5.90057327945389e-02 + 6.49131793283190e-02 -5.71216563862163e-02 + 6.04794197269670e-02 -5.52290978859873e-02 + 5.62646886835696e-02 -5.33218521504249e-02 + 5.22507416096869e-02 -5.14208493808622e-02 + 4.84245433996503e-02 -4.95323182851412e-02 + 4.47904867206598e-02 -4.76449015546858e-02 + 4.13374558635882e-02 -4.57663829252569e-02 + 3.80650840253715e-02 -4.38944940923365e-02 + 3.49691116419480e-02 -4.20279518522186e-02 + 3.20400727373755e-02 -4.01712967041496e-02 + 2.92703341033774e-02 -3.83301218257238e-02 + 2.66462635908786e-02 -3.65121714900467e-02 + 2.41819941212201e-02 -3.47068073590117e-02 + 2.19143199986438e-02 -3.29088330701643e-02 + 1.97796258019261e-02 -3.11426553752093e-02 + 1.77718675728929e-02 -2.94033561455842e-02 + 1.58892791802320e-02 -2.76827467855728e-02 + 1.41231129715086e-02 -2.59874713046408e-02 + 1.24680257561555e-02 -2.43219224431366e-02 + 1.09259070704779e-02 -2.26820710355976e-02 + 9.49343298356482e-03 -2.10561306903018e-02 + 8.14503768413817e-03 -1.94635072722990e-02 + 6.90999917273266e-03 -1.78889094607232e-02 + 5.79390475471148e-03 -1.63307209071248e-02 + 4.78106804114271e-03 -1.47978940894094e-02 + 3.88016584757143e-03 -1.32873649605637e-02 + 3.08233798054177e-03 -1.18026200908121e-02 + 2.38686534170238e-03 -1.03450301564476e-02 + 1.78599805341179e-03 -8.92081233071476e-03 + 1.28652156378685e-03 -7.52634471004791e-03 + 8.83996769448488e-04 -6.16669016705767e-03 + 5.46612029292912e-04 -4.84894257335285e-03 + 3.01376049559927e-04 -3.56996967423148e-03 + 1.30154076571712e-04 -2.33432457843823e-03 + 4.21374163304318e-05 -1.14334359217422e-03 + 0.00000000000000e+00 0.00000000000000e+00 + 2.81157574964881e-05 1.14295937760577e-03 + 1.04621923266427e-04 2.33440626401102e-03 + 2.54739066947636e-04 3.57120735782472e-03 + 4.65849257103884e-04 4.85377645755166e-03 + 7.66296706792806e-04 6.17820210329396e-03 + 1.13400710680486e-03 7.54436835218198e-03 + 1.57970905045129e-03 8.95240763421855e-03 + 2.19446599887451e-03 1.03731283301651e-02 + 2.87705684559474e-03 1.18324568030195e-02 + 3.67789371859726e-03 1.33102740954264e-02 + 4.57036584246313e-03 1.48203416608747e-02 + 5.56967498060080e-03 1.63537813005310e-02 + 6.66759090523285e-03 1.79156766085822e-02 + 7.85649334745409e-03 1.95131911485843e-02 + 9.15255477687989e-03 2.11363600124788e-02 + 1.05445488424763e-02 2.27966579112874e-02 + 1.20486064407746e-02 2.44823719840950e-02 + 1.36603871932619e-02 2.61996974106957e-02 + 1.53821576127598e-02 2.79522040521000e-02 + 1.72090722971723e-02 2.97472094765997e-02 + 1.91651219523706e-02 3.15651260035317e-02 + 2.12426156558742e-02 3.34176370326924e-02 + 2.34511443758688e-02 3.52973320141773e-02 + 2.57904895361023e-02 3.72130957307203e-02 + 2.82626509750913e-02 3.91646919322919e-02 + 3.08759739857624e-02 4.11514060005145e-02 + 3.36299253040576e-02 4.31771896078588e-02 + 3.65354985842998e-02 4.52371794325495e-02 + 3.96008704268746e-02 4.73246766888027e-02 + 4.28321561070921e-02 4.94404029988426e-02 + 4.62242346874908e-02 5.16004112773017e-02 + 4.97958902647260e-02 5.37820404238713e-02 + 5.35528496536011e-02 5.59876066111493e-02 + 5.74940264314054e-02 5.82280097517281e-02 + 6.16289114941267e-02 6.04973177565880e-02 + 6.59549586653717e-02 6.28123067599801e-02 + 7.05011791699481e-02 6.51291026479873e-02 + 7.52646676807933e-02 6.74659569979716e-02 + 8.02411483868892e-02 6.98450349458632e-02 + 8.54541005536459e-02 7.22307435968477e-02 + 9.09077876598320e-02 7.46202759272474e-02 + 9.66055445093218e-02 7.70252439848328e-02 + 1.02556617968726e-01 7.94445037398437e-02 + 1.08769595464231e-01 8.18723919264446e-02 + 1.15251846243329e-01 8.43087989893419e-02 + 1.22017436032429e-01 8.67299569776199e-02 + 1.29067606508560e-01 8.91543819424277e-02 + 1.36410072520413e-01 9.15812636222036e-02 + 1.44057372467977e-01 9.39916412991629e-02 + 1.52018009642350e-01 9.63774884768607e-02 + 1.60301083370340e-01 9.87298228910894e-02 + 1.68915004119298e-01 1.01040503878498e-01 + 1.77863375679202e-01 1.03322385460583e-01 + 1.87155863329685e-01 1.05561389941643e-01 + 1.96799541214523e-01 1.07750710152026e-01 + 2.06809021346131e-01 1.09847473640509e-01 + 2.17187694050625e-01 1.11860752579225e-01 + 2.27942920264959e-01 1.13772677888835e-01 + 2.39080425704280e-01 1.15580120940451e-01 + 2.50602978823008e-01 1.17288028936626e-01 + 2.62523055501980e-01 1.18833856236034e-01 + 2.74840647475125e-01 1.20232024719622e-01 + 2.87562192937226e-01 1.21441226349321e-01 + 3.00690830602118e-01 1.22430852727519e-01 + 3.14227523639263e-01 1.23178402093805e-01 + 3.28171801048535e-01 1.23663484726724e-01 + 3.42521760498053e-01 1.23828016318311e-01 + 3.57273986043832e-01 1.23678074838371e-01 + 3.72422815778781e-01 1.23198599341217e-01 + 3.87965402200350e-01 1.22429097089126e-01 + 4.03897678601998e-01 1.21373131778580e-01 + 4.20216289788358e-01 1.20045527577897e-01 + 4.36918952632428e-01 1.18464558254558e-01 + 4.53998170716250e-01 1.16608654175239e-01 + 4.71445818375774e-01 1.14459171027755e-01 + 4.89262561234794e-01 1.12074715982259e-01 + 5.07441163553935e-01 1.09446574254448e-01 + 5.25971148178741e-01 1.06560361311888e-01 + 5.44848798428680e-01 1.03449434794008e-01 + 5.64066277235567e-01 1.00118102629513e-01 + 5.83615080942241e-01 9.65751507526858e-02 + 6.03485053765207e-01 9.28288280428212e-02 + 6.23663294928140e-01 8.88766391764726e-02 + 6.44143290404599e-01 8.47640847275778e-02 + 6.64912691365091e-01 8.04820587812154e-02 + 6.85957565742361e-01 7.60375257877561e-02 + 7.07269770163650e-01 7.14578896712954e-02 + 7.28832031023755e-01 6.67399716333503e-02 + 7.50627928640914e-01 6.18927779581912e-02 + 7.72638273090132e-01 5.69095365551616e-02 + 7.94845273313031e-01 5.17979358377091e-02 + 8.17229952512696e-01 4.65661010560639e-02 + 8.39774418012758e-01 4.12350839199444e-02 + 8.62464948057395e-01 3.58183297895103e-02 + 8.85273913513708e-01 3.03089834179839e-02 + 9.08187630633643e-01 2.47304583972593e-02 + 9.31177783406441e-01 1.90863321564750e-02 + 9.54226411846771e-01 1.31957781659379e-02 + 9.77294204499900e-01 7.13558621173920e-03 + 1.00000000000000e+00 9.69484227912823e-04 diff --git a/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF25_Coords.txt b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF25_Coords.txt new file mode 100644 index 00000000..f5baf458 --- /dev/null +++ b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF25_Coords.txt @@ -0,0 +1,208 @@ + 201 NumCoords ! The number of coordinates in the airfoil shape file (including an extra coordinate for airfoil reference). Set to zero if coordinates not included. +! ......... x-y coordinates are next if NumCoords > 0 ............. +! x-y coordinate of airfoil reference +! x/c y/c + 0.250000 0 +! coordinates of airfoil shape +! interpolation to 200 points +! x/c y/c + 1.00000000000000e+00 -1.09250671868000e-03 + 9.76115586099618e-01 2.09600510332978e-03 + 9.52288294552172e-01 4.81417885933177e-03 + 9.28450060797343e-01 7.11490117592222e-03 + 9.04619297601449e-01 8.92329765774539e-03 + 8.80834074284664e-01 9.95340950185301e-03 + 8.57151659839586e-01 9.92756319875484e-03 + 8.33630254563209e-01 9.17783270101517e-03 + 8.10328015134571e-01 7.42012067290446e-03 + 7.87300463622396e-01 4.77516783787571e-03 + 7.64592703953390e-01 1.32624859090481e-03 + 7.42228033108644e-01 -2.77682728463799e-03 + 7.20216772646893e-01 -7.37607048945225e-03 + 6.98563400687629e-01 -1.23524458090196e-02 + 6.77262887692173e-01 -1.75755523866722e-02 + 6.56316064999009e-01 -2.29614286738159e-02 + 6.35714570806867e-01 -2.84102836191219e-02 + 6.15449288352083e-01 -3.38290876998397e-02 + 5.95513325480546e-01 -3.91424755035297e-02 + 5.75907942700664e-01 -4.43068439562326e-02 + 5.56629760363534e-01 -4.92645154005323e-02 + 5.37682173510500e-01 -5.39873548651573e-02 + 5.19071820661838e-01 -5.84578413099440e-02 + 5.00801555954315e-01 -6.26495762564164e-02 + 4.82871601768206e-01 -6.65256315806630e-02 + 4.65290321806567e-01 -7.00771541943242e-02 + 4.48069107802193e-01 -7.33303008744292e-02 + 4.31210942377935e-01 -7.62613694929760e-02 + 4.14721717256527e-01 -7.88670112627226e-02 + 3.98609830485640e-01 -8.11674486204708e-02 + 3.82881803238740e-01 -8.31789010896421e-02 + 3.67540922501510e-01 -8.49011792837672e-02 + 3.52591959359744e-01 -8.63538669976877e-02 + 3.38038125513927e-01 -8.75591661511401e-02 + 3.23878337769632e-01 -8.84993826488772e-02 + 3.10114246734585e-01 -8.91848244796117e-02 + 2.96745918134662e-01 -8.96356484654719e-02 + 2.83772536979569e-01 -8.98560569285609e-02 + 2.71193048529533e-01 -8.98541970412896e-02 + 2.59004966514683e-01 -8.96641882545778e-02 + 2.47205169565799e-01 -8.92924468430343e-02 + 2.35790240472659e-01 -8.87473051941079e-02 + 2.24754947680772e-01 -8.80529555951448e-02 + 2.14094425301211e-01 -8.72214656839783e-02 + 2.03803579375793e-01 -8.62541002544239e-02 + 1.93875405543264e-01 -8.51751516327919e-02 + 1.84303408655320e-01 -8.39908637540001e-02 + 1.75080215317279e-01 -8.27132159406177e-02 + 1.66199793240435e-01 -8.13445725448274e-02 + 1.57653122663062e-01 -7.99033042566852e-02 + 1.49432819276280e-01 -7.83940014030634e-02 + 1.41527369025976e-01 -7.68397516570057e-02 + 1.33933094840571e-01 -7.52295246442809e-02 + 1.26640143243466e-01 -7.35770567956669e-02 + 1.19640559393263e-01 -7.18863418890472e-02 + 1.12927077813054e-01 -7.01581195662533e-02 + 1.06488519837237e-01 -6.84113181275732e-02 + 1.00316701895756e-01 -6.66480482070258e-02 + 9.44082133574360e-02 -6.48587314973944e-02 + 8.87499483874507e-02 -6.30623827083626e-02 + 8.33346753623294e-02 -6.12610269188888e-02 + 7.81562621654159e-02 -5.94517874653428e-02 + 7.31951432238743e-02 -5.76424972836634e-02 + 6.84577626403403e-02 -5.58286777757905e-02 + 6.39326342358596e-02 -5.40173864513933e-02 + 5.96152121769926e-02 -5.22094494493164e-02 + 5.55045079578264e-02 -5.03979483760663e-02 + 5.15876859053906e-02 -4.85965280700871e-02 + 4.78588835860377e-02 -4.68025488097465e-02 + 4.43151088293809e-02 -4.50134393598166e-02 + 4.09479814741917e-02 -4.32331507155101e-02 + 3.77544761371438e-02 -4.14613164257821e-02 + 3.47290964996220e-02 -3.96983685901773e-02 + 3.18646716164714e-02 -3.79460007064151e-02 + 2.91557807064150e-02 -3.62082493349325e-02 + 2.65916717593254e-02 -3.44893521422311e-02 + 2.41768614668749e-02 -3.27857249071581e-02 + 2.19169363744281e-02 -3.10958697248329e-02 + 1.97853574099944e-02 -2.94351217148795e-02 + 1.77809502328637e-02 -2.77959928991413e-02 + 1.59012923654057e-02 -2.61756147968822e-02 + 1.41377791124355e-02 -2.45798265623274e-02 + 1.24854340081653e-02 -2.30107015135764e-02 + 1.09463949529226e-02 -2.14628875680232e-02 + 9.51420326071247e-03 -1.99362443503988e-02 + 8.18367131774184e-03 -1.84317002704562e-02 + 6.95781355369571e-03 -1.69495477016988e-02 + 5.84461757031922e-03 -1.54828594722959e-02 + 4.83675987451319e-03 -1.40360192911298e-02 + 3.93148210889690e-03 -1.26118037509212e-02 + 3.12597705524147e-03 -1.12107577936507e-02 + 2.42827959498203e-03 -9.83080813631348e-03 + 1.81848159181735e-03 -8.48180028772974e-03 + 1.31026857339993e-03 -7.15931186006862e-03 + 8.94028566689473e-04 -5.86904696569661e-03 + 5.59139659541858e-04 -4.61467241237522e-03 + 3.08713803920484e-04 -3.39799797587375e-03 + 1.34284352600275e-04 -2.22180755581035e-03 + 4.38766782931077e-05 -1.08808364043886e-03 + 0.00000000000000e+00 0.00000000000000e+00 + 2.70754963215136e-05 1.08767660334744e-03 + 1.03580808069746e-04 2.22228516879441e-03 + 2.51928419550096e-04 3.40061010146026e-03 + 4.63659613080425e-04 4.62272156443479e-03 + 7.50030014672317e-04 5.88676081458818e-03 + 1.11249110649511e-03 7.19012596240712e-03 + 1.55894767722491e-03 8.53069940774572e-03 + 2.12648113335517e-03 9.89524770439861e-03 + 2.78122395867452e-03 1.12920178518460e-02 + 3.53349472781731e-03 1.27152234032320e-02 + 4.37986080892483e-03 1.41682764668305e-02 + 5.32108740225112e-03 1.56504595401408e-02 + 6.35403104634295e-03 1.71645723270603e-02 + 7.48065465647005e-03 1.87111343722309e-02 + 8.70798790603196e-03 2.02868357356723e-02 + 1.00326625323290e-02 2.18967960271385e-02 + 1.14615517896570e-02 2.35376948845036e-02 + 1.29908498121995e-02 2.52156066282122e-02 + 1.46285017870635e-02 2.69284106702504e-02 + 1.63762840007771e-02 2.86766604856462e-02 + 1.82437127611806e-02 3.04560704781735e-02 + 2.02283271437812e-02 3.22731904280343e-02 + 2.23410892379826e-02 3.41200707129672e-02 + 2.45803161096591e-02 3.60061322399834e-02 + 2.69523034357121e-02 3.79258490183542e-02 + 2.94661214249216e-02 3.98790227559557e-02 + 3.21182316854737e-02 4.18723073706309e-02 + 3.49189765158157e-02 4.39025161395751e-02 + 3.78764907558025e-02 4.59628851663624e-02 + 4.09963031658456e-02 4.80556676923546e-02 + 4.42775927892050e-02 5.01900205707697e-02 + 4.77343365858657e-02 5.23520241988731e-02 + 5.13731297355052e-02 5.45423734775189e-02 + 5.51950546654045e-02 5.67687018233320e-02 + 5.92113866358186e-02 5.90218736527301e-02 + 6.34234392442166e-02 6.13116302117422e-02 + 6.78462003333466e-02 6.36214314140050e-02 + 7.24854173464343e-02 6.59533657552206e-02 + 7.73419721841157e-02 6.83186401819959e-02 + 8.24324258544088e-02 7.06971481688955e-02 + 8.77613607346135e-02 7.30926428047549e-02 + 9.33346253668055e-02 7.55076582271502e-02 + 9.91628221387800e-02 7.79350885797270e-02 + 1.05254564598752e-01 8.03695380742510e-02 + 1.11616753158002e-01 8.28125781644698e-02 + 1.18259294307182e-01 8.52558088653510e-02 + 1.25189263783572e-01 8.76985152086404e-02 + 1.32415679289748e-01 9.01369747472587e-02 + 1.39947873838956e-01 9.25638030881446e-02 + 1.47794845481183e-01 9.49707607832480e-02 + 1.55965915271520e-01 9.73499622034032e-02 + 1.64469189511735e-01 9.96967278841057e-02 + 1.73311416702080e-01 1.02010530578746e-01 + 1.82503742461270e-01 1.04273623478212e-01 + 1.92050672615684e-01 1.06491541481398e-01 + 2.01966200947807e-01 1.08628345168654e-01 + 2.12256126598972e-01 1.10681929211142e-01 + 2.22927191842667e-01 1.12642214263348e-01 + 2.33987552164155e-01 1.14491142152048e-01 + 2.45440161850974e-01 1.16234688095526e-01 + 2.57296008031495e-01 1.17825202458106e-01 + 2.69556869203747e-01 1.19267427279133e-01 + 2.82229070262522e-01 1.20524379694892e-01 + 2.95316275100028e-01 1.21569011458766e-01 + 3.08820531899773e-01 1.22372406982529e-01 + 3.22741461950530e-01 1.22915930928339e-01 + 3.37078134209340e-01 1.23149875849477e-01 + 3.51826981727722e-01 1.23062131822088e-01 + 3.66983039246985e-01 1.22645337613189e-01 + 3.82543070599223e-01 1.21930860322884e-01 + 3.98503391798556e-01 1.20928153680211e-01 + 4.14860961126985e-01 1.19652845240075e-01 + 4.31612326060530e-01 1.18111343121154e-01 + 4.48752327492312e-01 1.16301638158787e-01 + 4.66272601249854e-01 1.14199654104434e-01 + 4.84172419107913e-01 1.11855636518184e-01 + 5.02444493519843e-01 1.09258193501888e-01 + 5.21080236029992e-01 1.06406605973784e-01 + 5.40074886324364e-01 1.03326688418026e-01 + 5.59419655929053e-01 1.00019465978113e-01 + 5.79105612175721e-01 9.64916235087976e-02 + 5.99125173361441e-01 9.27647911198193e-02 + 6.19466430557399e-01 8.88409323564860e-02 + 6.40119041978738e-01 8.47390121899819e-02 + 6.61070257644903e-01 8.04603243420791e-02 + 6.82307901055849e-01 7.60197144231869e-02 + 7.03821798847536e-01 7.14430901975401e-02 + 7.25594294352276e-01 6.67273876453086e-02 + 7.47609060933277e-01 6.18819437827459e-02 + 7.69845737824426e-01 5.68996656088332e-02 + 7.92286051630428e-01 5.17884210392101e-02 + 8.14910827049322e-01 4.65565586752961e-02 + 8.37702906504111e-01 4.12259060670082e-02 + 8.60644007466582e-01 3.58073758391948e-02 + 8.83708956400804e-01 3.02965383060978e-02 + 9.06880276867715e-01 2.47142694962048e-02 + 9.30133788123677e-01 1.90677931913939e-02 + 9.53449456906722e-01 1.32665027689235e-02 + 9.76786262644257e-01 7.36258542738043e-03 + 1.00000000000000e+00 1.36768088735877e-03 diff --git a/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF26_Coords.txt b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF26_Coords.txt new file mode 100644 index 00000000..cf7fc7ad --- /dev/null +++ b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF26_Coords.txt @@ -0,0 +1,208 @@ + 201 NumCoords ! The number of coordinates in the airfoil shape file (including an extra coordinate for airfoil reference). Set to zero if coordinates not included. +! ......... x-y coordinates are next if NumCoords > 0 ............. +! x-y coordinate of airfoil reference +! x/c y/c + 0.250000 0 +! coordinates of airfoil shape +! interpolation to 200 points +! x/c y/c + 1.00000000000000e+00 -1.24163918250367e-03 + 9.76041165887563e-01 1.99488268803741e-03 + 9.52121914098850e-01 4.75706252222044e-03 + 9.28199957236603e-01 7.09542956274019e-03 + 9.04291190262318e-01 8.93443745793852e-03 + 8.80430343444036e-01 9.96657729426452e-03 + 8.56672689113696e-01 9.94290435584814e-03 + 8.33075425877888e-01 9.19689625764953e-03 + 8.09695700165266e-01 7.47347691185626e-03 + 7.86588885771507e-01 4.89111440127801e-03 + 7.63799981052509e-01 1.51070336812985e-03 + 7.41353018207342e-01 -2.52044512396319e-03 + 7.19257743648676e-01 -7.04038680187796e-03 + 6.97520950922480e-01 -1.19358851549070e-02 + 6.76139778430185e-01 -1.70807096849569e-02 + 6.55114191085606e-01 -2.23867022793893e-02 + 6.34437029834687e-01 -2.77559055040500e-02 + 6.14099171583599e-01 -3.30936716419077e-02 + 5.94097092702040e-01 -3.83329090713677e-02 + 5.74431276878783e-01 -4.34270288627529e-02 + 5.55097922205893e-01 -4.83165117769746e-02 + 5.36103244219295e-01 -5.29813461185869e-02 + 5.17451514118577e-01 -5.73969020907143e-02 + 4.99146144876149e-01 -6.15389789381977e-02 + 4.81187008959400e-01 -6.53691205567300e-02 + 4.63583334863196e-01 -6.88825029007271e-02 + 4.46345674250821e-01 -7.21042694778078e-02 + 4.29476426936704e-01 -7.50078286995993e-02 + 4.12981165598887e-01 -7.75910433182066e-02 + 3.96868697220895e-01 -7.98780646047934e-02 + 3.81143737274277e-01 -8.18762285984978e-02 + 3.65809950832190e-01 -8.35894755418217e-02 + 3.50871346715946e-01 -8.50344502846749e-02 + 3.36330856482784e-01 -8.62291005970239e-02 + 3.22187680974826e-01 -8.71590314211491e-02 + 3.08443381198299e-01 -8.78366569779970e-02 + 2.95097824515779e-01 -8.82768172546241e-02 + 2.82150316172696e-01 -8.84841421890272e-02 + 2.69599713195053e-01 -8.84700415928376e-02 + 2.57443538674293e-01 -8.82648900755557e-02 + 2.45678503760535e-01 -8.78783328013873e-02 + 2.34300892069519e-01 -8.73191978590562e-02 + 2.23305176083759e-01 -8.66151143715721e-02 + 2.12686475906400e-01 -8.57717042278548e-02 + 2.02439201431732e-01 -8.47960575058360e-02 + 1.92555334399891e-01 -8.37147804336106e-02 + 1.83029072759030e-01 -8.25291243560209e-02 + 1.73852988185549e-01 -8.12499391500962e-02 + 1.65019713285519e-01 -7.98863532611348e-02 + 1.56521149653515e-01 -7.84487425858802e-02 + 1.48348326905127e-01 -7.69504193661685e-02 + 1.40492169632055e-01 -7.54025801721342e-02 + 1.32945934195466e-01 -7.38053647018080e-02 + 1.25701000521494e-01 -7.21672889164535e-02 + 1.18749063872964e-01 -7.04928479452887e-02 + 1.12082069469409e-01 -6.87847420009533e-02 + 1.05690639166719e-01 -6.70564170338887e-02 + 9.95644793751720e-02 -6.53155594973088e-02 + 9.36997891046597e-02 -6.35528503057422e-02 + 8.80860404700645e-02 -6.17798179936638e-02 + 8.27138402760154e-02 -6.00046280095742e-02 + 7.75786796919451e-02 -5.82199952095701e-02 + 7.26702775903076e-02 -5.64364109081874e-02 + 6.79824154250675e-02 -5.46532131450536e-02 + 6.35091047142614e-02 -5.28689233118743e-02 + 5.92419326453291e-02 -5.10893765254210e-02 + 5.51761610142073e-02 -4.93108527891892e-02 + 5.13012904354392e-02 -4.75441103336549e-02 + 4.76145565870374e-02 -4.57830799218584e-02 + 4.41097775457074e-02 -4.40286611417737e-02 + 4.07797547228364e-02 -4.22832639538696e-02 + 3.76203144073222e-02 -4.05471915450099e-02 + 3.46254260858043e-02 -3.88215755752492e-02 + 3.17889101119942e-02 -3.71070792104368e-02 + 2.91063013242030e-02 -3.54070623086104e-02 + 2.65680917385227e-02 -3.37242560099722e-02 + 2.41746444824902e-02 -3.20578976536326e-02 + 2.19171444247013e-02 -3.04080975483655e-02 + 1.97858149698125e-02 -2.87865206302891e-02 + 1.77816785975911e-02 -2.71845498672619e-02 + 1.59022597396959e-02 -2.56014672844354e-02 + 1.41389646872167e-02 -2.40428780632352e-02 + 1.24868469400250e-02 -2.25098697316461e-02 + 1.09480652882895e-02 -2.09965445874096e-02 + 9.51590058520777e-03 -1.95072970846173e-02 + 8.19359579424781e-03 -1.80358499675050e-02 + 6.97242094431141e-03 -1.65886214694131e-02 + 5.86117299541770e-03 -1.51566425360256e-02 + 4.85595721623195e-03 -1.37425320553921e-02 + 3.94940941742267e-03 -1.23512986917568e-02 + 3.14133805635955e-03 -1.09822611963997e-02 + 2.44321685058300e-03 -9.63205407941857e-03 + 1.83022786901874e-03 -8.31193681735096e-03 + 1.31884419349740e-03 -7.01717270777278e-03 + 8.97352130663886e-04 -5.75368875832799e-03 + 5.63740815773768e-04 -4.52380901007206e-03 + 3.11436976892490e-04 -3.33125476138120e-03 + 1.35836193808489e-04 -2.17811670838639e-03 + 4.45280502729537e-05 -1.06661993857544e-03 + 0.00000000000000e+00 0.00000000000000e+00 + 2.66760054509128e-05 1.06620363196370e-03 + 1.03135511949883e-04 2.17873971903504e-03 + 2.50714385917578e-04 3.33437480200911e-03 + 4.62713811117844e-04 4.53305150068868e-03 + 7.43003875184307e-04 5.77372654297466e-03 + 1.10319761909825e-03 7.05282637820245e-03 + 1.54998013794877e-03 8.36733050300788e-03 + 2.09725226970234e-03 9.71027755670584e-03 + 2.74048621866142e-03 1.10830229161061e-02 + 3.47313095950444e-03 1.24853542942127e-02 + 4.30082217565610e-03 1.39166476275545e-02 + 5.21857196014794e-03 1.53794131710022e-02 + 6.22534316879645e-03 1.68755017759930e-02 + 7.32700741881788e-03 1.84027736911195e-02 + 8.52685165419718e-03 1.99605923185556e-02 + 9.82457508956703e-03 2.15515967524936e-02 + 1.12235177290181e-02 2.31756834085188e-02 + 1.27200503919435e-02 2.48389080154999e-02 + 1.43242279905998e-02 2.65369959399126e-02 + 1.60404245440130e-02 2.82678634249202e-02 + 1.78725008542331e-02 3.00332073110525e-02 + 1.98202147599872e-02 3.18374092114472e-02 + 2.18950460972363e-02 3.36723552878899e-02 + 2.40945084991586e-02 3.55478542511501e-02 + 2.64266594338935e-02 3.74562543671355e-02 + 2.89010475331631e-02 3.93973576550753e-02 + 3.15128856164724e-02 4.13789637240956e-02 + 3.42721423161374e-02 4.33986437239279e-02 + 3.71869766220148e-02 4.54495802606190e-02 + 4.02627031087678e-02 4.75346101784617e-02 + 4.35002150116920e-02 4.96601391986086e-02 + 4.69116164095437e-02 5.18156791609964e-02 + 5.05037836700218e-02 5.40013488484752e-02 + 5.42786678950318e-02 5.62234865342880e-02 + 5.82483001631071e-02 5.84716108883904e-02 + 6.24154978875846e-02 6.07527350834376e-02 + 6.67896743600186e-02 6.30611281243319e-02 + 7.13799999231155e-02 6.53925012153297e-02 + 7.61894222215938e-02 6.77537053720447e-02 + 8.12317662654453e-02 7.01307269242542e-02 + 8.65117557737097e-02 7.25279882775677e-02 + 9.20362184425747e-02 7.49454680746529e-02 + 9.78162759593724e-02 7.73748306064237e-02 + 1.03860552928939e-01 7.98107486389235e-02 + 1.10175778191298e-01 8.22554075072582e-02 + 1.16770214549517e-01 8.47058953467228e-02 + 1.23653203755665e-01 8.71546056154831e-02 + 1.30834337594950e-01 8.95968004923253e-02 + 1.38321670606146e-01 9.20292431191944e-02 + 1.46124389981669e-01 9.44436195002828e-02 + 1.54251904677806e-01 9.68324582790219e-02 + 1.62712200809751e-01 9.91923751629681e-02 + 1.71513312218537e-01 1.01517930059788e-01 + 1.80666845834493e-01 1.03789912148757e-01 + 1.90176370985942e-01 1.06018468666417e-01 + 2.00055657032727e-01 1.08170258618851e-01 + 2.10311372495842e-01 1.10238994003200e-01 + 2.20950065131051e-01 1.12217532980930e-01 + 2.31980866532305e-01 1.14082146312415e-01 + 2.43406769821147e-01 1.15839163095632e-01 + 2.55238147077280e-01 1.17446579677784e-01 + 2.67477513281741e-01 1.18905422327083e-01 + 2.80131073498889e-01 1.20180419750751e-01 + 2.93202720534022e-01 1.21245816208447e-01 + 3.06694896295832e-01 1.22070353231193e-01 + 3.20607263770737e-01 1.22636054133308e-01 + 3.34939268318345e-01 1.22896410171916e-01 + 3.49687302556342e-01 1.22832514196396e-01 + 3.64846676687070e-01 1.22439952772840e-01 + 3.80414003309436e-01 1.21746813551104e-01 + 3.96385756696833e-01 1.20764922463268e-01 + 4.12759002166226e-01 1.19510124555119e-01 + 4.29529884389691e-01 1.17984334619021e-01 + 4.46694073835668e-01 1.16192944649426e-01 + 4.64243196738119e-01 1.14110111055027e-01 + 4.82175957113290e-01 1.11782567369759e-01 + 5.00485020623298e-01 1.09197665297171e-01 + 5.19162565566196e-01 1.06360394677582e-01 + 5.38203389191021e-01 1.03293317692501e-01 + 5.57598376049888e-01 9.99962209759983e-02 + 5.77338386735964e-01 9.64747451695822e-02 + 5.97416810267783e-01 9.27560007851153e-02 + 6.17822173815498e-01 8.88440305009192e-02 + 6.38542633624223e-01 8.47454500445900e-02 + 6.59565297378976e-01 8.04670393872135e-02 + 6.80878616121945e-01 7.60267543210821e-02 + 7.02471652655181e-01 7.14503788937509e-02 + 7.24326595397154e-01 6.67348588383987e-02 + 7.46427190977622e-01 6.18895589890343e-02 + 7.68752587046382e-01 5.69073596180092e-02 + 7.91284306570890e-01 5.17961434205325e-02 + 8.14003121917812e-01 4.65642776255388e-02 + 8.36892227450033e-01 4.12336544355374e-02 + 8.59931497183523e-01 3.58149763309393e-02 + 8.83096691520270e-01 3.03040139923268e-02 + 9.06368918443855e-01 2.47214332231998e-02 + 9.29725626335315e-01 1.90747607002302e-02 + 9.53145857383183e-01 1.33087425250220e-02 + 9.76587861324942e-01 7.46542536535991e-03 + 1.00000000000000e+00 1.53835660395088e-03 diff --git a/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF27_Coords.txt b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF27_Coords.txt new file mode 100644 index 00000000..a8559b09 --- /dev/null +++ b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF27_Coords.txt @@ -0,0 +1,208 @@ + 201 NumCoords ! The number of coordinates in the airfoil shape file (including an extra coordinate for airfoil reference). Set to zero if coordinates not included. +! ......... x-y coordinates are next if NumCoords > 0 ............. +! x-y coordinate of airfoil reference +! x/c y/c + 0.250000 0 +! coordinates of airfoil shape +! interpolation to 200 points +! x/c y/c + 1.00000000000000e+00 -1.24164223325347e-03 + 9.76041164392396e-01 1.99488062082566e-03 + 9.52121910751731e-01 4.75706135335948e-03 + 9.28199952199219e-01 7.09542915865422e-03 + 9.04291183649571e-01 8.93443767118390e-03 + 8.80430335305919e-01 9.96657750751068e-03 + 8.56672679460919e-01 9.94290456909515e-03 + 8.33075414701384e-01 9.19689647089799e-03 + 8.09695687435274e-01 7.47347776900502e-03 + 7.86588871455130e-01 4.89111649401108e-03 + 7.63799965113471e-01 1.51070681640460e-03 + 7.41353000623285e-01 -2.52044025059049e-03 + 7.19257724385752e-01 -7.04038035491660e-03 + 6.97520929992240e-01 -1.19358771025367e-02 + 6.76139755888505e-01 -1.70807000809784e-02 + 6.55114166969036e-01 -2.23866910906930e-02 + 6.34437004205735e-01 -2.77558927368869e-02 + 6.14099144503465e-01 -3.30936572688430e-02 + 5.94097064299627e-01 -3.83328932311329e-02 + 5.74431247267374e-01 -4.34270116338703e-02 + 5.55097891490535e-01 -4.83164932012163e-02 + 5.36103212560625e-01 -5.29813263991864e-02 + 5.17451481630547e-01 -5.73968812892901e-02 + 4.99146111683925e-01 -6.15389571602501e-02 + 4.81186975180132e-01 -6.53690978763222e-02 + 4.63583300631990e-01 -6.88824794729917e-02 + 4.46345639685456e-01 -7.21042454369658e-02 + 4.29476392143564e-01 -7.50078041225779e-02 + 4.12981130677270e-01 -7.75910183051978e-02 + 3.96868662278405e-01 -7.98780393343755e-02 + 3.81143702382537e-01 -8.18762030718283e-02 + 3.65809916070270e-01 -8.35894498418953e-02 + 3.50871312147949e-01 -8.50344244357429e-02 + 3.36330822167539e-01 -8.62290745383426e-02 + 3.22187646977060e-01 -8.71590051574009e-02 + 3.08443347581371e-01 -8.78366305562361e-02 + 2.95097791339595e-01 -8.82767906155356e-02 + 2.82150283499973e-01 -8.84841152823162e-02 + 2.69599681087069e-01 -8.84700144337475e-02 + 2.57443507192848e-01 -8.82648626051867e-02 + 2.45678472964112e-01 -8.78783050259134e-02 + 2.34300862010750e-01 -8.73191697949781e-02 + 2.23305146809674e-01 -8.66150861037270e-02 + 2.12686447462944e-01 -8.57716757140843e-02 + 2.02439173855586e-01 -8.47960288193625e-02 + 1.92555307706631e-01 -8.37147516939257e-02 + 1.83029046978344e-01 -8.25290955835651e-02 + 1.73852963346223e-01 -8.12499103431124e-02 + 1.65019689389359e-01 -7.98863245514951e-02 + 1.56521126720043e-01 -7.84487139477401e-02 + 1.48348304923117e-01 -7.69503909453266e-02 + 1.40492148638460e-01 -7.54025518805833e-02 + 1.32945914165942e-01 -7.38053366709304e-02 + 1.25700981456047e-01 -7.21672611749456e-02 + 1.18749045764871e-01 -7.04928205316870e-02 + 1.12082052295785e-01 -6.87847149917338e-02 + 1.05690622940757e-01 -6.70563903986223e-02 + 9.95644640688240e-02 -6.53155333147837e-02 + 9.36997746804533e-02 -6.35528246583057e-02 + 8.80860269419856e-02 -6.17797928182627e-02 + 8.27138276159543e-02 -6.00046033630738e-02 + 7.75786679035966e-02 -5.82199710630611e-02 + 7.26702668766427e-02 -5.64363872841197e-02 + 6.79824057221827e-02 -5.46531901393429e-02 + 6.35090960690899e-02 -5.28689008362057e-02 + 5.92419250258708e-02 -5.10893545882387e-02 + 5.51761543119222e-02 -4.93108314830338e-02 + 5.13012845894761e-02 -4.75440896934531e-02 + 4.76145515997845e-02 -4.57830599145488e-02 + 4.41097733544431e-02 -4.40286418035125e-02 + 4.07797512889574e-02 -4.22832452899324e-02 + 3.76203116687853e-02 -4.05471735735779e-02 + 3.46254239696624e-02 -3.88215583285753e-02 + 3.17889085655347e-02 -3.71070627007449e-02 + 2.91063003142196e-02 -3.54070465342894e-02 + 2.65680912572024e-02 -3.37242409387003e-02 + 2.41746444372365e-02 -3.20578833095496e-02 + 2.19171444247057e-02 -3.04080839884921e-02 + 1.97858149698170e-02 -2.87865078379770e-02 + 1.77816785975956e-02 -2.71845378027204e-02 + 1.59022597397006e-02 -2.56014559510294e-02 + 1.41389646872214e-02 -2.40428674601252e-02 + 1.24868469400299e-02 -2.25098598379508e-02 + 1.09480652882944e-02 -2.09965353712404e-02 + 9.51590058521273e-03 -1.95072886041607e-02 + 8.19359596476239e-03 -1.80358421377615e-02 + 6.97242121388991e-03 -1.65886143273830e-02 + 5.86117330807756e-03 -1.51566360782969e-02 + 4.85595758514205e-03 -1.37425262435773e-02 + 3.94940976333073e-03 -1.23512935315688e-02 + 3.14133835342164e-03 -1.09822566687452e-02 + 2.44321714150649e-03 -9.63205013980954e-03 + 1.83022809796061e-03 -8.31193344939125e-03 + 1.31884436057794e-03 -7.01716988880847e-03 + 8.97352193736273e-04 -5.75368646998309e-03 + 5.63740905842356e-04 -4.52380720725293e-03 + 3.11437030347409e-04 -3.33125343689109e-03 + 1.35836224347021e-04 -2.17811584123553e-03 + 4.45280630750671e-05 -1.06661951254253e-03 + 0.00000000000000e+00 0.00000000000000e+00 + 2.66759975469128e-05 1.06620320574453e-03 + 1.03135502882502e-04 2.17873885472331e-03 + 2.50714361136359e-04 3.33437348745562e-03 + 4.62713791811825e-04 4.53304972124580e-03 + 7.43003731765193e-04 5.77372430028259e-03 + 1.10319742939756e-03 7.05282365458086e-03 + 1.54997995490141e-03 8.36732726269284e-03 + 2.09725167376054e-03 9.71027388884010e-03 + 2.74048539040992e-03 1.10830187729024e-02 + 3.47312973743479e-03 1.24853497385656e-02 + 4.30082057862358e-03 1.39166426421534e-02 + 5.21856989199968e-03 1.53794078029284e-02 + 6.22534057591764e-03 1.68754960531490e-02 + 7.32700432621982e-03 1.84027675881834e-02 + 8.52684801153103e-03 1.99605858637636e-02 + 9.82457090745577e-03 2.15515899247781e-02 + 1.12235129483028e-02 2.31756762504219e-02 + 1.27200449567995e-02 2.48389005693531e-02 + 1.43242218865420e-02 2.65369882056060e-02 + 1.60404178082626e-02 2.82678553499417e-02 + 1.78724934115684e-02 3.00331989618528e-02 + 1.98202065802740e-02 3.18374006104675e-02 + 2.18950371605342e-02 3.36723464545640e-02 + 2.40944987682683e-02 3.55478452136134e-02 + 2.64266489071067e-02 3.74562451109318e-02 + 2.89010362193680e-02 3.93973481646352e-02 + 3.15128734993139e-02 4.13789540071277e-02 + 3.42721293711695e-02 4.33986338037802e-02 + 3.71869628254960e-02 4.54495701594197e-02 + 4.02626884327817e-02 4.75345999298599e-02 + 4.35001994625931e-02 4.96601287812404e-02 + 4.69115999564798e-02 5.18156686218105e-02 + 5.05037662874084e-02 5.40013382232845e-02 + 5.42786495746735e-02 5.62234758330505e-02 + 5.82482809121614e-02 5.84716000937855e-02 + 6.24154777430842e-02 6.07527241240193e-02 + 6.67896532476333e-02 6.30611171442784e-02 + 7.13799778368031e-02 6.53924902316809e-02 + 7.61893991966636e-02 6.77536943148228e-02 + 8.12317422826271e-02 7.01307158448530e-02 + 8.65117308166364e-02 7.25279772295263e-02 + 9.20361925143298e-02 7.49454570665521e-02 + 9.78162490733068e-02 7.73748196288702e-02 + 1.03860525098628e-01 7.98107376836716e-02 + 1.10175749426971e-01 8.22553965780306e-02 + 1.16770184828620e-01 8.47058845532950e-02 + 1.23653173100621e-01 8.71545949342700e-02 + 1.30834306039958e-01 8.95967898803351e-02 + 1.38321638159842e-01 9.20292326136635e-02 + 1.46124356656426e-01 9.44436091370127e-02 + 1.54251870487751e-01 9.68324481019705e-02 + 1.62712165766615e-01 9.91923652415109e-02 + 1.71513276359922e-01 1.01517920367561e-01 + 1.80666809206519e-01 1.03789902629961e-01 + 1.90176333616483e-01 1.06018459355824e-01 + 2.00055618945293e-01 1.08170249602257e-01 + 2.10311333730825e-01 1.10238985284240e-01 + 2.20950025725240e-01 1.12217524621099e-01 + 2.31980826542045e-01 1.14082138261491e-01 + 2.43406729303366e-01 1.15839155310084e-01 + 2.55238106076494e-01 1.17446572225308e-01 + 2.67477471857320e-01 1.18905415201973e-01 + 2.80131031707401e-01 1.20180412981259e-01 + 2.93202678436719e-01 1.21245809848125e-01 + 3.06694853961626e-01 1.22070347287731e-01 + 3.20607221269401e-01 1.22636048627399e-01 + 3.34939225727116e-01 1.22896405187495e-01 + 3.49687259951759e-01 1.22832509683795e-01 + 3.64846634151165e-01 1.22439948740756e-01 + 3.80413960921238e-01 1.21746809942571e-01 + 3.96385714538567e-01 1.20764919268824e-01 + 4.12758960322157e-01 1.19510121769152e-01 + 4.29529842936380e-01 1.17984332147218e-01 + 4.46694032865700e-01 1.16192942543521e-01 + 4.64243156344356e-01 1.14110109333428e-01 + 4.82175917377177e-01 1.11782565979692e-01 + 5.00484981625201e-01 1.09197664159710e-01 + 5.19162527401886e-01 1.06360393829411e-01 + 5.38203351947280e-01 1.03293317103930e-01 + 5.57598339807246e-01 9.99962205928791e-02 + 5.77338351570623e-01 9.64747449157602e-02 + 5.97416776275050e-01 9.27560006949552e-02 + 6.17822141099620e-01 8.88440306520127e-02 + 6.38542602259551e-01 8.47454502578335e-02 + 6.59565267437110e-01 8.04670396004571e-02 + 6.80878587686638e-01 7.60267545343259e-02 + 7.02471625795160e-01 7.14503791069948e-02 + 7.24326570178040e-01 6.67348590516426e-02 + 7.46427167466697e-01 6.18895592022783e-02 + 7.68752565300964e-01 5.69073598312532e-02 + 7.91284286644164e-01 5.17961436337766e-02 + 8.14003103862062e-01 4.65642778387828e-02 + 8.36892211324902e-01 4.12336546487814e-02 + 8.59931483011660e-01 3.58149765441833e-02 + 8.83096679342750e-01 3.03040142055707e-02 + 9.06368908273977e-01 2.47214334364437e-02 + 9.29725618218844e-01 1.90747609134739e-02 + 9.53145851346865e-01 1.33087434425404e-02 + 9.76587857380671e-01 7.46542748662253e-03 + 1.00000000000000e+00 1.53836008119114e-03 diff --git a/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF28_Coords.txt b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF28_Coords.txt new file mode 100644 index 00000000..a8559b09 --- /dev/null +++ b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF28_Coords.txt @@ -0,0 +1,208 @@ + 201 NumCoords ! The number of coordinates in the airfoil shape file (including an extra coordinate for airfoil reference). Set to zero if coordinates not included. +! ......... x-y coordinates are next if NumCoords > 0 ............. +! x-y coordinate of airfoil reference +! x/c y/c + 0.250000 0 +! coordinates of airfoil shape +! interpolation to 200 points +! x/c y/c + 1.00000000000000e+00 -1.24164223325347e-03 + 9.76041164392396e-01 1.99488062082566e-03 + 9.52121910751731e-01 4.75706135335948e-03 + 9.28199952199219e-01 7.09542915865422e-03 + 9.04291183649571e-01 8.93443767118390e-03 + 8.80430335305919e-01 9.96657750751068e-03 + 8.56672679460919e-01 9.94290456909515e-03 + 8.33075414701384e-01 9.19689647089799e-03 + 8.09695687435274e-01 7.47347776900502e-03 + 7.86588871455130e-01 4.89111649401108e-03 + 7.63799965113471e-01 1.51070681640460e-03 + 7.41353000623285e-01 -2.52044025059049e-03 + 7.19257724385752e-01 -7.04038035491660e-03 + 6.97520929992240e-01 -1.19358771025367e-02 + 6.76139755888505e-01 -1.70807000809784e-02 + 6.55114166969036e-01 -2.23866910906930e-02 + 6.34437004205735e-01 -2.77558927368869e-02 + 6.14099144503465e-01 -3.30936572688430e-02 + 5.94097064299627e-01 -3.83328932311329e-02 + 5.74431247267374e-01 -4.34270116338703e-02 + 5.55097891490535e-01 -4.83164932012163e-02 + 5.36103212560625e-01 -5.29813263991864e-02 + 5.17451481630547e-01 -5.73968812892901e-02 + 4.99146111683925e-01 -6.15389571602501e-02 + 4.81186975180132e-01 -6.53690978763222e-02 + 4.63583300631990e-01 -6.88824794729917e-02 + 4.46345639685456e-01 -7.21042454369658e-02 + 4.29476392143564e-01 -7.50078041225779e-02 + 4.12981130677270e-01 -7.75910183051978e-02 + 3.96868662278405e-01 -7.98780393343755e-02 + 3.81143702382537e-01 -8.18762030718283e-02 + 3.65809916070270e-01 -8.35894498418953e-02 + 3.50871312147949e-01 -8.50344244357429e-02 + 3.36330822167539e-01 -8.62290745383426e-02 + 3.22187646977060e-01 -8.71590051574009e-02 + 3.08443347581371e-01 -8.78366305562361e-02 + 2.95097791339595e-01 -8.82767906155356e-02 + 2.82150283499973e-01 -8.84841152823162e-02 + 2.69599681087069e-01 -8.84700144337475e-02 + 2.57443507192848e-01 -8.82648626051867e-02 + 2.45678472964112e-01 -8.78783050259134e-02 + 2.34300862010750e-01 -8.73191697949781e-02 + 2.23305146809674e-01 -8.66150861037270e-02 + 2.12686447462944e-01 -8.57716757140843e-02 + 2.02439173855586e-01 -8.47960288193625e-02 + 1.92555307706631e-01 -8.37147516939257e-02 + 1.83029046978344e-01 -8.25290955835651e-02 + 1.73852963346223e-01 -8.12499103431124e-02 + 1.65019689389359e-01 -7.98863245514951e-02 + 1.56521126720043e-01 -7.84487139477401e-02 + 1.48348304923117e-01 -7.69503909453266e-02 + 1.40492148638460e-01 -7.54025518805833e-02 + 1.32945914165942e-01 -7.38053366709304e-02 + 1.25700981456047e-01 -7.21672611749456e-02 + 1.18749045764871e-01 -7.04928205316870e-02 + 1.12082052295785e-01 -6.87847149917338e-02 + 1.05690622940757e-01 -6.70563903986223e-02 + 9.95644640688240e-02 -6.53155333147837e-02 + 9.36997746804533e-02 -6.35528246583057e-02 + 8.80860269419856e-02 -6.17797928182627e-02 + 8.27138276159543e-02 -6.00046033630738e-02 + 7.75786679035966e-02 -5.82199710630611e-02 + 7.26702668766427e-02 -5.64363872841197e-02 + 6.79824057221827e-02 -5.46531901393429e-02 + 6.35090960690899e-02 -5.28689008362057e-02 + 5.92419250258708e-02 -5.10893545882387e-02 + 5.51761543119222e-02 -4.93108314830338e-02 + 5.13012845894761e-02 -4.75440896934531e-02 + 4.76145515997845e-02 -4.57830599145488e-02 + 4.41097733544431e-02 -4.40286418035125e-02 + 4.07797512889574e-02 -4.22832452899324e-02 + 3.76203116687853e-02 -4.05471735735779e-02 + 3.46254239696624e-02 -3.88215583285753e-02 + 3.17889085655347e-02 -3.71070627007449e-02 + 2.91063003142196e-02 -3.54070465342894e-02 + 2.65680912572024e-02 -3.37242409387003e-02 + 2.41746444372365e-02 -3.20578833095496e-02 + 2.19171444247057e-02 -3.04080839884921e-02 + 1.97858149698170e-02 -2.87865078379770e-02 + 1.77816785975956e-02 -2.71845378027204e-02 + 1.59022597397006e-02 -2.56014559510294e-02 + 1.41389646872214e-02 -2.40428674601252e-02 + 1.24868469400299e-02 -2.25098598379508e-02 + 1.09480652882944e-02 -2.09965353712404e-02 + 9.51590058521273e-03 -1.95072886041607e-02 + 8.19359596476239e-03 -1.80358421377615e-02 + 6.97242121388991e-03 -1.65886143273830e-02 + 5.86117330807756e-03 -1.51566360782969e-02 + 4.85595758514205e-03 -1.37425262435773e-02 + 3.94940976333073e-03 -1.23512935315688e-02 + 3.14133835342164e-03 -1.09822566687452e-02 + 2.44321714150649e-03 -9.63205013980954e-03 + 1.83022809796061e-03 -8.31193344939125e-03 + 1.31884436057794e-03 -7.01716988880847e-03 + 8.97352193736273e-04 -5.75368646998309e-03 + 5.63740905842356e-04 -4.52380720725293e-03 + 3.11437030347409e-04 -3.33125343689109e-03 + 1.35836224347021e-04 -2.17811584123553e-03 + 4.45280630750671e-05 -1.06661951254253e-03 + 0.00000000000000e+00 0.00000000000000e+00 + 2.66759975469128e-05 1.06620320574453e-03 + 1.03135502882502e-04 2.17873885472331e-03 + 2.50714361136359e-04 3.33437348745562e-03 + 4.62713791811825e-04 4.53304972124580e-03 + 7.43003731765193e-04 5.77372430028259e-03 + 1.10319742939756e-03 7.05282365458086e-03 + 1.54997995490141e-03 8.36732726269284e-03 + 2.09725167376054e-03 9.71027388884010e-03 + 2.74048539040992e-03 1.10830187729024e-02 + 3.47312973743479e-03 1.24853497385656e-02 + 4.30082057862358e-03 1.39166426421534e-02 + 5.21856989199968e-03 1.53794078029284e-02 + 6.22534057591764e-03 1.68754960531490e-02 + 7.32700432621982e-03 1.84027675881834e-02 + 8.52684801153103e-03 1.99605858637636e-02 + 9.82457090745577e-03 2.15515899247781e-02 + 1.12235129483028e-02 2.31756762504219e-02 + 1.27200449567995e-02 2.48389005693531e-02 + 1.43242218865420e-02 2.65369882056060e-02 + 1.60404178082626e-02 2.82678553499417e-02 + 1.78724934115684e-02 3.00331989618528e-02 + 1.98202065802740e-02 3.18374006104675e-02 + 2.18950371605342e-02 3.36723464545640e-02 + 2.40944987682683e-02 3.55478452136134e-02 + 2.64266489071067e-02 3.74562451109318e-02 + 2.89010362193680e-02 3.93973481646352e-02 + 3.15128734993139e-02 4.13789540071277e-02 + 3.42721293711695e-02 4.33986338037802e-02 + 3.71869628254960e-02 4.54495701594197e-02 + 4.02626884327817e-02 4.75345999298599e-02 + 4.35001994625931e-02 4.96601287812404e-02 + 4.69115999564798e-02 5.18156686218105e-02 + 5.05037662874084e-02 5.40013382232845e-02 + 5.42786495746735e-02 5.62234758330505e-02 + 5.82482809121614e-02 5.84716000937855e-02 + 6.24154777430842e-02 6.07527241240193e-02 + 6.67896532476333e-02 6.30611171442784e-02 + 7.13799778368031e-02 6.53924902316809e-02 + 7.61893991966636e-02 6.77536943148228e-02 + 8.12317422826271e-02 7.01307158448530e-02 + 8.65117308166364e-02 7.25279772295263e-02 + 9.20361925143298e-02 7.49454570665521e-02 + 9.78162490733068e-02 7.73748196288702e-02 + 1.03860525098628e-01 7.98107376836716e-02 + 1.10175749426971e-01 8.22553965780306e-02 + 1.16770184828620e-01 8.47058845532950e-02 + 1.23653173100621e-01 8.71545949342700e-02 + 1.30834306039958e-01 8.95967898803351e-02 + 1.38321638159842e-01 9.20292326136635e-02 + 1.46124356656426e-01 9.44436091370127e-02 + 1.54251870487751e-01 9.68324481019705e-02 + 1.62712165766615e-01 9.91923652415109e-02 + 1.71513276359922e-01 1.01517920367561e-01 + 1.80666809206519e-01 1.03789902629961e-01 + 1.90176333616483e-01 1.06018459355824e-01 + 2.00055618945293e-01 1.08170249602257e-01 + 2.10311333730825e-01 1.10238985284240e-01 + 2.20950025725240e-01 1.12217524621099e-01 + 2.31980826542045e-01 1.14082138261491e-01 + 2.43406729303366e-01 1.15839155310084e-01 + 2.55238106076494e-01 1.17446572225308e-01 + 2.67477471857320e-01 1.18905415201973e-01 + 2.80131031707401e-01 1.20180412981259e-01 + 2.93202678436719e-01 1.21245809848125e-01 + 3.06694853961626e-01 1.22070347287731e-01 + 3.20607221269401e-01 1.22636048627399e-01 + 3.34939225727116e-01 1.22896405187495e-01 + 3.49687259951759e-01 1.22832509683795e-01 + 3.64846634151165e-01 1.22439948740756e-01 + 3.80413960921238e-01 1.21746809942571e-01 + 3.96385714538567e-01 1.20764919268824e-01 + 4.12758960322157e-01 1.19510121769152e-01 + 4.29529842936380e-01 1.17984332147218e-01 + 4.46694032865700e-01 1.16192942543521e-01 + 4.64243156344356e-01 1.14110109333428e-01 + 4.82175917377177e-01 1.11782565979692e-01 + 5.00484981625201e-01 1.09197664159710e-01 + 5.19162527401886e-01 1.06360393829411e-01 + 5.38203351947280e-01 1.03293317103930e-01 + 5.57598339807246e-01 9.99962205928791e-02 + 5.77338351570623e-01 9.64747449157602e-02 + 5.97416776275050e-01 9.27560006949552e-02 + 6.17822141099620e-01 8.88440306520127e-02 + 6.38542602259551e-01 8.47454502578335e-02 + 6.59565267437110e-01 8.04670396004571e-02 + 6.80878587686638e-01 7.60267545343259e-02 + 7.02471625795160e-01 7.14503791069948e-02 + 7.24326570178040e-01 6.67348590516426e-02 + 7.46427167466697e-01 6.18895592022783e-02 + 7.68752565300964e-01 5.69073598312532e-02 + 7.91284286644164e-01 5.17961436337766e-02 + 8.14003103862062e-01 4.65642778387828e-02 + 8.36892211324902e-01 4.12336546487814e-02 + 8.59931483011660e-01 3.58149765441833e-02 + 8.83096679342750e-01 3.03040142055707e-02 + 9.06368908273977e-01 2.47214334364437e-02 + 9.29725618218844e-01 1.90747609134739e-02 + 9.53145851346865e-01 1.33087434425404e-02 + 9.76587857380671e-01 7.46542748662253e-03 + 1.00000000000000e+00 1.53836008119114e-03 diff --git a/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF29_Coords.txt b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF29_Coords.txt new file mode 100644 index 00000000..a8559b09 --- /dev/null +++ b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AF29_Coords.txt @@ -0,0 +1,208 @@ + 201 NumCoords ! The number of coordinates in the airfoil shape file (including an extra coordinate for airfoil reference). Set to zero if coordinates not included. +! ......... x-y coordinates are next if NumCoords > 0 ............. +! x-y coordinate of airfoil reference +! x/c y/c + 0.250000 0 +! coordinates of airfoil shape +! interpolation to 200 points +! x/c y/c + 1.00000000000000e+00 -1.24164223325347e-03 + 9.76041164392396e-01 1.99488062082566e-03 + 9.52121910751731e-01 4.75706135335948e-03 + 9.28199952199219e-01 7.09542915865422e-03 + 9.04291183649571e-01 8.93443767118390e-03 + 8.80430335305919e-01 9.96657750751068e-03 + 8.56672679460919e-01 9.94290456909515e-03 + 8.33075414701384e-01 9.19689647089799e-03 + 8.09695687435274e-01 7.47347776900502e-03 + 7.86588871455130e-01 4.89111649401108e-03 + 7.63799965113471e-01 1.51070681640460e-03 + 7.41353000623285e-01 -2.52044025059049e-03 + 7.19257724385752e-01 -7.04038035491660e-03 + 6.97520929992240e-01 -1.19358771025367e-02 + 6.76139755888505e-01 -1.70807000809784e-02 + 6.55114166969036e-01 -2.23866910906930e-02 + 6.34437004205735e-01 -2.77558927368869e-02 + 6.14099144503465e-01 -3.30936572688430e-02 + 5.94097064299627e-01 -3.83328932311329e-02 + 5.74431247267374e-01 -4.34270116338703e-02 + 5.55097891490535e-01 -4.83164932012163e-02 + 5.36103212560625e-01 -5.29813263991864e-02 + 5.17451481630547e-01 -5.73968812892901e-02 + 4.99146111683925e-01 -6.15389571602501e-02 + 4.81186975180132e-01 -6.53690978763222e-02 + 4.63583300631990e-01 -6.88824794729917e-02 + 4.46345639685456e-01 -7.21042454369658e-02 + 4.29476392143564e-01 -7.50078041225779e-02 + 4.12981130677270e-01 -7.75910183051978e-02 + 3.96868662278405e-01 -7.98780393343755e-02 + 3.81143702382537e-01 -8.18762030718283e-02 + 3.65809916070270e-01 -8.35894498418953e-02 + 3.50871312147949e-01 -8.50344244357429e-02 + 3.36330822167539e-01 -8.62290745383426e-02 + 3.22187646977060e-01 -8.71590051574009e-02 + 3.08443347581371e-01 -8.78366305562361e-02 + 2.95097791339595e-01 -8.82767906155356e-02 + 2.82150283499973e-01 -8.84841152823162e-02 + 2.69599681087069e-01 -8.84700144337475e-02 + 2.57443507192848e-01 -8.82648626051867e-02 + 2.45678472964112e-01 -8.78783050259134e-02 + 2.34300862010750e-01 -8.73191697949781e-02 + 2.23305146809674e-01 -8.66150861037270e-02 + 2.12686447462944e-01 -8.57716757140843e-02 + 2.02439173855586e-01 -8.47960288193625e-02 + 1.92555307706631e-01 -8.37147516939257e-02 + 1.83029046978344e-01 -8.25290955835651e-02 + 1.73852963346223e-01 -8.12499103431124e-02 + 1.65019689389359e-01 -7.98863245514951e-02 + 1.56521126720043e-01 -7.84487139477401e-02 + 1.48348304923117e-01 -7.69503909453266e-02 + 1.40492148638460e-01 -7.54025518805833e-02 + 1.32945914165942e-01 -7.38053366709304e-02 + 1.25700981456047e-01 -7.21672611749456e-02 + 1.18749045764871e-01 -7.04928205316870e-02 + 1.12082052295785e-01 -6.87847149917338e-02 + 1.05690622940757e-01 -6.70563903986223e-02 + 9.95644640688240e-02 -6.53155333147837e-02 + 9.36997746804533e-02 -6.35528246583057e-02 + 8.80860269419856e-02 -6.17797928182627e-02 + 8.27138276159543e-02 -6.00046033630738e-02 + 7.75786679035966e-02 -5.82199710630611e-02 + 7.26702668766427e-02 -5.64363872841197e-02 + 6.79824057221827e-02 -5.46531901393429e-02 + 6.35090960690899e-02 -5.28689008362057e-02 + 5.92419250258708e-02 -5.10893545882387e-02 + 5.51761543119222e-02 -4.93108314830338e-02 + 5.13012845894761e-02 -4.75440896934531e-02 + 4.76145515997845e-02 -4.57830599145488e-02 + 4.41097733544431e-02 -4.40286418035125e-02 + 4.07797512889574e-02 -4.22832452899324e-02 + 3.76203116687853e-02 -4.05471735735779e-02 + 3.46254239696624e-02 -3.88215583285753e-02 + 3.17889085655347e-02 -3.71070627007449e-02 + 2.91063003142196e-02 -3.54070465342894e-02 + 2.65680912572024e-02 -3.37242409387003e-02 + 2.41746444372365e-02 -3.20578833095496e-02 + 2.19171444247057e-02 -3.04080839884921e-02 + 1.97858149698170e-02 -2.87865078379770e-02 + 1.77816785975956e-02 -2.71845378027204e-02 + 1.59022597397006e-02 -2.56014559510294e-02 + 1.41389646872214e-02 -2.40428674601252e-02 + 1.24868469400299e-02 -2.25098598379508e-02 + 1.09480652882944e-02 -2.09965353712404e-02 + 9.51590058521273e-03 -1.95072886041607e-02 + 8.19359596476239e-03 -1.80358421377615e-02 + 6.97242121388991e-03 -1.65886143273830e-02 + 5.86117330807756e-03 -1.51566360782969e-02 + 4.85595758514205e-03 -1.37425262435773e-02 + 3.94940976333073e-03 -1.23512935315688e-02 + 3.14133835342164e-03 -1.09822566687452e-02 + 2.44321714150649e-03 -9.63205013980954e-03 + 1.83022809796061e-03 -8.31193344939125e-03 + 1.31884436057794e-03 -7.01716988880847e-03 + 8.97352193736273e-04 -5.75368646998309e-03 + 5.63740905842356e-04 -4.52380720725293e-03 + 3.11437030347409e-04 -3.33125343689109e-03 + 1.35836224347021e-04 -2.17811584123553e-03 + 4.45280630750671e-05 -1.06661951254253e-03 + 0.00000000000000e+00 0.00000000000000e+00 + 2.66759975469128e-05 1.06620320574453e-03 + 1.03135502882502e-04 2.17873885472331e-03 + 2.50714361136359e-04 3.33437348745562e-03 + 4.62713791811825e-04 4.53304972124580e-03 + 7.43003731765193e-04 5.77372430028259e-03 + 1.10319742939756e-03 7.05282365458086e-03 + 1.54997995490141e-03 8.36732726269284e-03 + 2.09725167376054e-03 9.71027388884010e-03 + 2.74048539040992e-03 1.10830187729024e-02 + 3.47312973743479e-03 1.24853497385656e-02 + 4.30082057862358e-03 1.39166426421534e-02 + 5.21856989199968e-03 1.53794078029284e-02 + 6.22534057591764e-03 1.68754960531490e-02 + 7.32700432621982e-03 1.84027675881834e-02 + 8.52684801153103e-03 1.99605858637636e-02 + 9.82457090745577e-03 2.15515899247781e-02 + 1.12235129483028e-02 2.31756762504219e-02 + 1.27200449567995e-02 2.48389005693531e-02 + 1.43242218865420e-02 2.65369882056060e-02 + 1.60404178082626e-02 2.82678553499417e-02 + 1.78724934115684e-02 3.00331989618528e-02 + 1.98202065802740e-02 3.18374006104675e-02 + 2.18950371605342e-02 3.36723464545640e-02 + 2.40944987682683e-02 3.55478452136134e-02 + 2.64266489071067e-02 3.74562451109318e-02 + 2.89010362193680e-02 3.93973481646352e-02 + 3.15128734993139e-02 4.13789540071277e-02 + 3.42721293711695e-02 4.33986338037802e-02 + 3.71869628254960e-02 4.54495701594197e-02 + 4.02626884327817e-02 4.75345999298599e-02 + 4.35001994625931e-02 4.96601287812404e-02 + 4.69115999564798e-02 5.18156686218105e-02 + 5.05037662874084e-02 5.40013382232845e-02 + 5.42786495746735e-02 5.62234758330505e-02 + 5.82482809121614e-02 5.84716000937855e-02 + 6.24154777430842e-02 6.07527241240193e-02 + 6.67896532476333e-02 6.30611171442784e-02 + 7.13799778368031e-02 6.53924902316809e-02 + 7.61893991966636e-02 6.77536943148228e-02 + 8.12317422826271e-02 7.01307158448530e-02 + 8.65117308166364e-02 7.25279772295263e-02 + 9.20361925143298e-02 7.49454570665521e-02 + 9.78162490733068e-02 7.73748196288702e-02 + 1.03860525098628e-01 7.98107376836716e-02 + 1.10175749426971e-01 8.22553965780306e-02 + 1.16770184828620e-01 8.47058845532950e-02 + 1.23653173100621e-01 8.71545949342700e-02 + 1.30834306039958e-01 8.95967898803351e-02 + 1.38321638159842e-01 9.20292326136635e-02 + 1.46124356656426e-01 9.44436091370127e-02 + 1.54251870487751e-01 9.68324481019705e-02 + 1.62712165766615e-01 9.91923652415109e-02 + 1.71513276359922e-01 1.01517920367561e-01 + 1.80666809206519e-01 1.03789902629961e-01 + 1.90176333616483e-01 1.06018459355824e-01 + 2.00055618945293e-01 1.08170249602257e-01 + 2.10311333730825e-01 1.10238985284240e-01 + 2.20950025725240e-01 1.12217524621099e-01 + 2.31980826542045e-01 1.14082138261491e-01 + 2.43406729303366e-01 1.15839155310084e-01 + 2.55238106076494e-01 1.17446572225308e-01 + 2.67477471857320e-01 1.18905415201973e-01 + 2.80131031707401e-01 1.20180412981259e-01 + 2.93202678436719e-01 1.21245809848125e-01 + 3.06694853961626e-01 1.22070347287731e-01 + 3.20607221269401e-01 1.22636048627399e-01 + 3.34939225727116e-01 1.22896405187495e-01 + 3.49687259951759e-01 1.22832509683795e-01 + 3.64846634151165e-01 1.22439948740756e-01 + 3.80413960921238e-01 1.21746809942571e-01 + 3.96385714538567e-01 1.20764919268824e-01 + 4.12758960322157e-01 1.19510121769152e-01 + 4.29529842936380e-01 1.17984332147218e-01 + 4.46694032865700e-01 1.16192942543521e-01 + 4.64243156344356e-01 1.14110109333428e-01 + 4.82175917377177e-01 1.11782565979692e-01 + 5.00484981625201e-01 1.09197664159710e-01 + 5.19162527401886e-01 1.06360393829411e-01 + 5.38203351947280e-01 1.03293317103930e-01 + 5.57598339807246e-01 9.99962205928791e-02 + 5.77338351570623e-01 9.64747449157602e-02 + 5.97416776275050e-01 9.27560006949552e-02 + 6.17822141099620e-01 8.88440306520127e-02 + 6.38542602259551e-01 8.47454502578335e-02 + 6.59565267437110e-01 8.04670396004571e-02 + 6.80878587686638e-01 7.60267545343259e-02 + 7.02471625795160e-01 7.14503791069948e-02 + 7.24326570178040e-01 6.67348590516426e-02 + 7.46427167466697e-01 6.18895592022783e-02 + 7.68752565300964e-01 5.69073598312532e-02 + 7.91284286644164e-01 5.17961436337766e-02 + 8.14003103862062e-01 4.65642778387828e-02 + 8.36892211324902e-01 4.12336546487814e-02 + 8.59931483011660e-01 3.58149765441833e-02 + 8.83096679342750e-01 3.03040142055707e-02 + 9.06368908273977e-01 2.47214334364437e-02 + 9.29725618218844e-01 1.90747609134739e-02 + 9.53145851346865e-01 1.33087434425404e-02 + 9.76587857380671e-01 7.46542748662253e-03 + 1.00000000000000e+00 1.53836008119114e-03 diff --git a/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_00.dat b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_00.dat new file mode 100644 index 00000000..b23ba71d --- /dev/null +++ b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_00.dat @@ -0,0 +1,254 @@ +! ------------ AirfoilInfo v1.01.x Input File ---------------------------------- +! AeroElasticSE FAST driver +! line +! line +! ------------------------------------------------------------------------------ +DEFAULT InterpOrd ! Interpolation order to use for quasi-steady table lookup {1=linear; 3=cubic spline; "default"} [default=3] +1 NonDimArea ! The non-dimensional area of the airfoil (area/chord^2) (set to 1.0 if unsure or unneeded) +@"NREL-2p8-127_AF00_Coords.txt" NumCoords ! The number of coordinates in the airfoil shape file. Set to zero if coordinates not included. +AF00_BL.txt BL_file ! The file name including the boundary layer characteristics of the profile. Ignored if the aeroacoustic module is not called. +1 NumTabs ! Number of airfoil tables in this file. Each table must have lines for Re and Ctrl. +! ------------------------------------------------------------------------------ +! data for table 1 +! ------------------------------------------------------------------------------ +6.000000 Re ! Reynolds number in millions +0 Ctrl ! Control setting (must be 0 for current AirfoilInfo) +True InclUAdata ! Is unsteady aerodynamics data included in this table? If TRUE, then include 30 UA coefficients below this line +!........................................ +0.000000 alpha0 ! 0-lift angle of attack, depends on airfoil. +0.000000 alpha1 ! Angle of attack at f=0.7, (approximately the stall angle) for AOA>alpha0. (deg) +0.000000 alpha2 ! Angle of attack at f=0.7, (approximately the stall angle) for AOA1] +0.000000 S2 ! Constant in the f curve best-fit for AOA> alpha1; by definition it depends on the airfoil. [ignored if UAMod<>1] +0.000000 S3 ! Constant in the f curve best-fit for alpha2<=AOA< alpha0; by definition it depends on the airfoil. [ignored if UAMod<>1] +0.000000 S4 ! Constant in the f curve best-fit for AOA< alpha2; by definition it depends on the airfoil. [ignored if UAMod<>1] +0.000000 Cn1 ! Critical value of C0n at leading edge separation. It should be extracted from airfoil data at a given Mach and Reynolds number. It can be calculated from the static value of Cn at either the break in the pitching moment or the loss of chord force at the onset of stall. It is close to the condition of maximum lift of the airfoil at low Mach numbers. +0.000000 Cn2 ! As Cn1 for negative AOAs. +Default St_sh ! Strouhal's shedding frequency constant. [default = 0.19] +0.000000 Cd0 ! 2D drag coefficient value at 0-lift. +0.000000 Cm0 ! 2D pitching moment coefficient about 1/4-chord location, at 0-lift, positive if nose up. [If the aerodynamics coefficients table does not include a column for Cm, this needs to be set to 0.0] +0.000000 k0 ! Constant in the \hat(x)_cp curve best-fit; = (\hat(x)_AC-0.25). [ignored if UAMod<>1] +0.000000 k1 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k2 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k3 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k1_hat ! Constant in the expression of Cc due to leading edge vortex effects. [ignored if UAMod<>1] +Default x_cp_bar ! Constant in the expression of \hat(x)_cp^v. [ignored if UAMod<>1, default = 0.2] +Default UACutout ! Angle of attack above which unsteady aerodynamics are disabled (deg). [Specifying the string "Default" sets UACutout to 45 degrees] +Default filtCutOff ! Cut-off frequency (-3 dB corner frequency) for low-pass filtering the AoA input to UA, as well as the 1st and 2nd derivatives (Hz) [default = 20] +!........................................ +! Table of aerodynamics coefficients +200 NumAlf ! Number of data lines in the following table +! Alpha Cl Cd Cm +! (deg) (-) (-) (-) +-1.80000000000000e+02 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-1.77000000000000e+02 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-1.74000000000000e+02 0.00000000000000e+00 5.00000000000000e-01 -2.77555756156289e-17 +-1.71000000000000e+02 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-1.68000000000000e+02 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-1.65000000000000e+02 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-1.62000000000000e+02 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-1.59000000000000e+02 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-1.56000000000000e+02 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-1.53000000000000e+02 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-1.50000000000000e+02 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-1.47000000000000e+02 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-1.44000000000000e+02 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-1.41000000000000e+02 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-1.38000000000000e+02 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-1.35000000000000e+02 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-1.32000000000000e+02 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-1.29000000000000e+02 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-1.26000000000000e+02 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-1.23000000000000e+02 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-1.20000000000000e+02 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-1.17000000000000e+02 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-1.14000000000000e+02 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-1.11000000000000e+02 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-1.08000000000000e+02 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-1.05000000000000e+02 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-1.02000000000000e+02 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-9.90000000000000e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-9.60000000000000e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-9.30000000000000e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-9.00000000000000e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-8.70000000000000e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-8.40000000000000e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-8.10000000000000e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-7.80000000000000e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-7.50000000000000e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-7.20000000000000e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-6.90000000000000e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-6.60000000000000e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-6.30000000000000e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-6.00000000000000e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-5.70000000000000e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-5.40000000000000e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-5.10000000000000e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-4.80000000000000e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-4.50000000000000e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-4.20000000000000e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-3.90000000000000e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-3.60000000000000e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-3.30000000000000e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-3.00000000000000e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-2.93939393939394e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-2.87878787878788e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-2.81818181818182e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-2.75757575757576e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-2.69696969696970e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-2.63636363636364e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-2.57575757575758e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-2.51515151515151e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-2.45454545454545e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-2.39393939393939e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-2.33333333333333e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-2.27272727272727e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-2.21212121212121e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-2.15151515151515e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-2.09090909090909e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-2.03030303030303e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-1.96969696969697e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-1.90909090909091e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-1.84848484848485e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-1.78787878787879e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-1.72727272727273e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-1.66666666666667e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-1.60606060606061e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-1.54545454545455e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-1.48484848484848e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-1.42424242424242e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-1.36363636363636e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-1.30303030303030e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-1.24242424242424e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-1.18181818181818e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-1.12121212121212e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-1.06060606060606e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-1.00000000000000e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-9.39393939393939e+00 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-8.78787878787879e+00 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-8.18181818181818e+00 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-7.57575757575758e+00 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-6.96969696969697e+00 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-6.36363636363636e+00 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-5.75757575757576e+00 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-5.15151515151515e+00 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-4.54545454545454e+00 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-3.93939393939394e+00 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-3.33333333333333e+00 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-2.72727272727273e+00 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-2.12121212121212e+00 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-1.51515151515152e+00 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-9.09090909090912e-01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 +-3.03030303030302e-01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 3.03030303030302e-01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 9.09090909090912e-01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 1.51515151515152e+00 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 2.12121212121212e+00 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 2.72727272727273e+00 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 3.33333333333333e+00 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 3.93939393939394e+00 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 4.54545454545455e+00 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 5.15151515151515e+00 1.11022302462516e-16 5.00000000000000e-01 0.00000000000000e+00 + 5.75757575757576e+00 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 6.36363636363637e+00 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 6.96969696969697e+00 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 7.57575757575757e+00 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 8.18181818181818e+00 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 8.78787878787879e+00 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 9.39393939393939e+00 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 1.00000000000000e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 1.06060606060606e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 1.12121212121212e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 1.18181818181818e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 1.24242424242424e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 1.30303030303030e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 1.36363636363636e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 1.42424242424242e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 1.48484848484848e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 1.54545454545455e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 1.60606060606061e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 1.66666666666667e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 1.72727272727273e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 1.78787878787879e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 1.84848484848485e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 1.90909090909091e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 1.96969696969697e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 2.03030303030303e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 2.09090909090909e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 2.15151515151515e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 2.21212121212121e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 2.27272727272727e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 2.33333333333333e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 2.39393939393939e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 2.45454545454545e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 2.51515151515151e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 2.57575757575758e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 2.63636363636364e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 2.69696969696970e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 2.75757575757576e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 2.81818181818182e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 2.87878787878788e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 2.93939393939394e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 3.00000000000000e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 3.30000000000000e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 3.60000000000000e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 3.90000000000000e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 4.20000000000000e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 4.50000000000000e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 4.80000000000000e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 5.10000000000000e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 5.40000000000000e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 5.70000000000000e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 6.00000000000000e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 6.30000000000000e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 6.60000000000000e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 6.90000000000000e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 7.20000000000000e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 7.50000000000000e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 7.80000000000000e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 8.10000000000000e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 8.40000000000000e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 8.70000000000000e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 9.00000000000000e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 9.30000000000000e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 9.60000000000000e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 9.90000000000000e+01 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 1.02000000000000e+02 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 1.05000000000000e+02 2.77555756156289e-17 5.00000000000000e-01 0.00000000000000e+00 + 1.08000000000000e+02 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 1.11000000000000e+02 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 1.14000000000000e+02 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 1.17000000000000e+02 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 1.20000000000000e+02 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 1.23000000000000e+02 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 1.26000000000000e+02 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 1.29000000000000e+02 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 1.32000000000000e+02 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 1.35000000000000e+02 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 1.38000000000000e+02 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 1.41000000000000e+02 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 1.44000000000000e+02 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 1.47000000000000e+02 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 1.50000000000000e+02 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 1.53000000000000e+02 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 1.56000000000000e+02 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 1.59000000000000e+02 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 1.62000000000000e+02 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 1.65000000000000e+02 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 1.68000000000000e+02 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 1.71000000000000e+02 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 1.74000000000000e+02 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 1.77000000000000e+02 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 + 1.80000000000000e+02 0.00000000000000e+00 5.00000000000000e-01 0.00000000000000e+00 diff --git a/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_01.dat b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_01.dat new file mode 100644 index 00000000..b197c637 --- /dev/null +++ b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_01.dat @@ -0,0 +1,254 @@ +! ------------ AirfoilInfo v1.01.x Input File ---------------------------------- +! AeroElasticSE FAST driver +! line +! line +! ------------------------------------------------------------------------------ +DEFAULT InterpOrd ! Interpolation order to use for quasi-steady table lookup {1=linear; 3=cubic spline; "default"} [default=3] +1 NonDimArea ! The non-dimensional area of the airfoil (area/chord^2) (set to 1.0 if unsure or unneeded) +@"NREL-2p8-127_AF01_Coords.txt" NumCoords ! The number of coordinates in the airfoil shape file. Set to zero if coordinates not included. +AF01_BL.txt BL_file ! The file name including the boundary layer characteristics of the profile. Ignored if the aeroacoustic module is not called. +1 NumTabs ! Number of airfoil tables in this file. Each table must have lines for Re and Ctrl. +! ------------------------------------------------------------------------------ +! data for table 1 +! ------------------------------------------------------------------------------ +6.000000 Re ! Reynolds number in millions +0 Ctrl ! Control setting (must be 0 for current AirfoilInfo) +True InclUAdata ! Is unsteady aerodynamics data included in this table? If TRUE, then include 30 UA coefficients below this line +!........................................ +0.000000 alpha0 ! 0-lift angle of attack, depends on airfoil. +0.000000 alpha1 ! Angle of attack at f=0.7, (approximately the stall angle) for AOA>alpha0. (deg) +0.000000 alpha2 ! Angle of attack at f=0.7, (approximately the stall angle) for AOA1] +0.000000 S2 ! Constant in the f curve best-fit for AOA> alpha1; by definition it depends on the airfoil. [ignored if UAMod<>1] +0.000000 S3 ! Constant in the f curve best-fit for alpha2<=AOA< alpha0; by definition it depends on the airfoil. [ignored if UAMod<>1] +0.000000 S4 ! Constant in the f curve best-fit for AOA< alpha2; by definition it depends on the airfoil. [ignored if UAMod<>1] +0.000000 Cn1 ! Critical value of C0n at leading edge separation. It should be extracted from airfoil data at a given Mach and Reynolds number. It can be calculated from the static value of Cn at either the break in the pitching moment or the loss of chord force at the onset of stall. It is close to the condition of maximum lift of the airfoil at low Mach numbers. +0.000000 Cn2 ! As Cn1 for negative AOAs. +Default St_sh ! Strouhal's shedding frequency constant. [default = 0.19] +0.000000 Cd0 ! 2D drag coefficient value at 0-lift. +0.000000 Cm0 ! 2D pitching moment coefficient about 1/4-chord location, at 0-lift, positive if nose up. [If the aerodynamics coefficients table does not include a column for Cm, this needs to be set to 0.0] +0.000000 k0 ! Constant in the \hat(x)_cp curve best-fit; = (\hat(x)_AC-0.25). [ignored if UAMod<>1] +0.000000 k1 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k2 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k3 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k1_hat ! Constant in the expression of Cc due to leading edge vortex effects. [ignored if UAMod<>1] +Default x_cp_bar ! Constant in the expression of \hat(x)_cp^v. [ignored if UAMod<>1, default = 0.2] +Default UACutout ! Angle of attack above which unsteady aerodynamics are disabled (deg). [Specifying the string "Default" sets UACutout to 45 degrees] +Default filtCutOff ! Cut-off frequency (-3 dB corner frequency) for low-pass filtering the AoA input to UA, as well as the 1st and 2nd derivatives (Hz) [default = 20] +!........................................ +! Table of aerodynamics coefficients +200 NumAlf ! Number of data lines in the following table +! Alpha Cl Cd Cm +! (deg) (-) (-) (-) +-1.80000000000000e+02 0.00000000000000e+00 4.98298540333591e-01 0.00000000000000e+00 +-1.77000000000000e+02 6.22917411225319e-03 4.99373778033698e-01 7.76775909182493e-03 +-1.74000000000000e+02 1.25154154596942e-02 4.99419482735902e-01 1.56066808333025e-02 +-1.71000000000000e+02 1.87731622461588e-02 4.99461965511715e-01 2.34100699534240e-02 +-1.68000000000000e+02 2.34094297732302e-02 4.99530448606310e-01 2.52436698228222e-02 +-1.65000000000000e+02 2.72360674222744e-02 4.99608171404762e-01 2.40924447430971e-02 +-1.62000000000000e+02 3.10637475603965e-02 4.99680051763820e-01 2.29412064713014e-02 +-1.59000000000000e+02 3.36494201711338e-02 4.99754234730512e-01 2.21517716457378e-02 +-1.56000000000000e+02 3.37510782194723e-02 4.99836914626034e-01 2.20859314734659e-02 +-1.53000000000000e+02 3.38548418745498e-02 4.99908331389323e-01 2.20200907982144e-02 +-1.50000000000000e+02 3.39610598736408e-02 4.99965130046894e-01 2.19542509808981e-02 +-1.47000000000000e+02 3.40022351252792e-02 5.01549605455131e-01 2.23645223424130e-02 +-1.44000000000000e+02 3.40443360294749e-02 5.07633704084372e-01 2.27747952710201e-02 +-1.41000000000000e+02 3.40874558144093e-02 5.13717849193324e-01 2.31850713339235e-02 +-1.38000000000000e+02 3.36790582106382e-02 5.20009950681803e-01 2.35945800253753e-02 +-1.35000000000000e+02 3.30448480367859e-02 5.26406029938182e-01 2.40037050326582e-02 +-1.32000000000000e+02 3.24110462717851e-02 5.32802182487933e-01 2.44128347281493e-02 +-1.29000000000000e+02 3.14966524820477e-02 5.39025691193689e-01 2.47587684454421e-02 +-1.26000000000000e+02 3.00203897774573e-02 5.44903911391262e-01 2.49783099065228e-02 +-1.23000000000000e+02 2.85442923527018e-02 5.47997043443126e-01 2.51978496904198e-02 +-1.20000000000000e+02 2.70683874187890e-02 5.50390438255170e-01 2.54173886357562e-02 +-1.17000000000000e+02 2.48208058238953e-02 5.51842311486022e-01 2.53547661804404e-02 +-1.14000000000000e+02 2.25732865469572e-02 5.53294177329843e-01 2.52921434125441e-02 +-1.11000000000000e+02 2.03258601363591e-02 5.54746032082366e-01 2.52295211230444e-02 +-1.08000000000000e+02 1.77044555792872e-02 5.55339410798165e-01 2.49510697467495e-02 +-1.05000000000000e+02 1.48960397658858e-02 5.55503544958830e-01 2.45647021836766e-02 +-1.02000000000000e+02 1.20876828091304e-02 5.55667677238678e-01 2.41783390479984e-02 +-9.90000000000000e+01 9.19392120485563e-03 5.55336597556942e-01 2.36900749881812e-02 +-9.60000000000000e+01 6.12926766887735e-03 5.54015072501802e-01 2.29980046662208e-02 +-9.30000000000000e+01 3.06463754512461e-03 5.52693557542367e-01 2.23059396312876e-02 +-9.00000000000000e+01 1.91272727247280e-08 5.51372047630695e-01 2.15841433608613e-02 +-8.70000000000000e+01 -3.06463440848635e-03 5.52693556189802e-01 2.16338466189352e-02 +-8.40000000000000e+01 -6.12927623833141e-03 5.54015076197080e-01 2.16677916947745e-02 +-8.10000000000000e+01 -9.19389465618328e-03 5.55336586108752e-01 2.16947509086332e-02 +-7.80000000000000e+01 -1.20876692076357e-02 5.55667678033613e-01 2.14919425433851e-02 +-7.50000000000000e+01 -1.48960583459338e-02 5.55503543872940e-01 2.11742464233755e-02 +-7.20000000000000e+01 -1.77044419776618e-02 5.55339411593092e-01 2.08565539438687e-02 +-6.90000000000000e+01 -2.03258406672883e-02 5.54746044659799e-01 2.04334687101240e-02 +-6.60000000000000e+01 -2.25732928313413e-02 5.53294173270158e-01 1.97995893374298e-02 +-6.30000000000000e+01 -2.48208206936227e-02 5.51842301880517e-01 1.91657099647355e-02 +-6.00000000000000e+01 -2.70683971825928e-02 5.50390422420595e-01 1.85318284698429e-02 +-5.70000000000000e+01 -2.85443021178706e-02 5.47997027608551e-01 1.76503617476530e-02 +-5.40000000000000e+01 -3.00203995438562e-02 5.44903872501265e-01 1.67688916585075e-02 +-5.10000000000000e+01 -3.14966622493741e-02 5.39025652303692e-01 1.58874148353996e-02 +-4.80000000000000e+01 -3.24110456233041e-02 5.32802189034552e-01 1.48845508415255e-02 +-4.50000000000000e+01 -3.30448401226552e-02 5.26406109778172e-01 1.38209952131320e-02 +-4.20000000000000e+01 -3.36790575613502e-02 5.20009957227964e-01 1.27574273972622e-02 +-3.90000000000000e+01 -3.40874557757088e-02 5.13717843800706e-01 1.16502587670957e-02 +-3.60000000000000e+01 -3.40443359103789e-02 5.07633687072646e-01 1.04558679399742e-02 +-3.30000000000000e+01 -3.40022354063646e-02 5.01549646541201e-01 9.26149992360155e-03 +-3.00000000000000e+01 -3.39610593176495e-02 4.99965129704843e-01 8.06710800308781e-03 +-2.93939393939394e+01 -3.39393842149473e-02 4.99955039870966e-01 7.77133972459921e-03 +-2.87878787878788e+01 -3.39178226626962e-02 4.99944209186026e-01 7.47170990628286e-03 +-2.81818181818182e+01 -3.38963709780943e-02 4.99932679692807e-01 7.17234251862615e-03 +-2.75757575757576e+01 -3.38750252088939e-02 4.99920490061147e-01 6.87323704771576e-03 +-2.69696969696970e+01 -3.38537822279900e-02 4.99907676487852e-01 6.57440256765985e-03 +-2.63636363636364e+01 -3.38326389844070e-02 4.99894272577114e-01 6.27584744506084e-03 +-2.57575757575758e+01 -3.38115926180026e-02 4.99880309637533e-01 5.97758105595668e-03 +-2.51515151515151e+01 -3.37906402717716e-02 4.99865816763762e-01 5.67961122622956e-03 +-2.45454545454545e+01 -3.37697787305793e-02 4.99850820740502e-01 5.38193913346827e-03 +-2.39393939393939e+01 -3.37490052565293e-02 4.99835346782305e-01 5.08457126751900e-03 +-2.33333333333333e+01 -3.37283172206986e-02 4.99819418446624e-01 4.78751430822279e-03 +-2.27272727272727e+01 -3.37077120977687e-02 4.99803057767734e-01 4.49077513241954e-03 +-2.21212121212121e+01 -3.36871874609726e-02 4.99786285377891e-01 4.19436082126422e-03 +-2.15151515151515e+01 -3.36667405096286e-02 4.99769120219361e-01 3.89827188626708e-03 +-2.09090909090909e+01 -3.36463693546679e-02 4.99751580718914e-01 3.60252094397359e-03 +-2.03030303030303e+01 -3.36260719547005e-02 4.99733684020483e-01 3.30711743419011e-03 +-1.96969696969697e+01 -3.29941770005342e-02 4.99715928910410e-01 2.97198266169500e-03 +-1.90909090909091e+01 -3.17509544740198e-02 4.99698118180787e-01 2.59700694849448e-03 +-1.84848484848485e+01 -3.05081921751880e-02 4.99679692312574e-01 2.22228885632221e-03 +-1.78787878787879e+01 -2.92658434632383e-02 4.99660638867322e-01 1.84786105360303e-03 +-1.72727272727273e+01 -2.80238734929002e-02 4.99640945159408e-01 1.47377573016103e-03 +-1.66666666666667e+01 -2.67823588448486e-02 4.99620599927312e-01 1.10014144572659e-03 +-1.60606060606061e+01 -2.55413203393379e-02 4.99599590742328e-01 7.27083418764568e-04 +-1.54545454545455e+01 -2.43008440419113e-02 4.99577905993521e-01 3.54797120669601e-04 +-1.48484848484848e+01 -2.30608787869031e-02 4.99555531346250e-01 4.21684305218460e-05 +-1.42424242424242e+01 -2.18214069842467e-02 4.99532452564366e-01 2.71911216522822e-05 +-1.36363636363636e+01 -2.05833091301585e-02 4.99508671393742e-01 1.42264537010822e-05 +-1.30303030303030e+01 -1.93442785240345e-02 4.99484131275150e-01 4.31295864732214e-06 +-1.24242424242424e+01 -1.81074797005703e-02 4.99458875874706e-01 -1.61041962405105e-04 +-1.18181818181818e+01 -1.68699463185017e-02 4.99432832875225e-01 -7.83817617224051e-04 +-1.12121212121212e+01 -1.56337784253251e-02 4.99406027440083e-01 -1.40654332027136e-03 +-1.06060606060606e+01 -1.43985688202720e-02 4.99052692242324e-01 -2.02931540870597e-03 +-1.00000000000000e+01 -1.31630022724158e-02 4.97993704507194e-01 -2.65204851654948e-03 +-9.39393939393939e+00 -1.11477228175490e-02 4.96487069320693e-01 -2.55646323442072e-03 +-8.78787878787879e+00 -9.13290842766007e-03 4.94977661180442e-01 -2.46147157009362e-03 +-8.18181818181818e+00 -7.12154268363285e-03 4.93467019568035e-01 -2.36566761577865e-03 +-7.57575757575758e+00 -5.11266117893152e-03 4.91954998300813e-01 -2.26283387170764e-03 +-6.96969696969697e+00 -3.10698824489412e-03 4.90440242965021e-01 -2.08181170391097e-03 +-6.36363636363636e+00 -1.10309834514044e-03 4.88921311313049e-01 -1.89874522974860e-03 +-5.75757575757576e+00 -3.00747474205360e-04 4.87401751405469e-01 -1.71567088819378e-03 +-5.15151515151515e+00 -2.21631176101127e-04 4.85879616962190e-01 -1.53403240787112e-03 +-4.54545454545454e+00 -1.49616631477367e-04 4.84353891592103e-01 -1.35030844364575e-03 +-3.93939393939394e+00 -8.68897616353509e-05 4.82825709613375e-01 -1.16711649919569e-03 +-3.33333333333333e+00 -3.06390387180330e-05 4.81485638756053e-01 -1.06097220254243e-03 +-2.72727272727273e+00 2.49883470329266e-03 4.81081167821070e-01 -1.11471300781816e-03 +-2.12121212121212e+00 9.70229526683138e-03 4.81205260595194e-01 -1.25146797918653e-03 +-1.51515151515152e+00 1.69064135086061e-02 4.81329323131111e-01 -1.47373619873665e-03 +-9.09090909090912e-01 2.15687752025109e-02 4.81450361624086e-01 -1.68081905636486e-03 +-3.03030303030302e-01 2.42404595537528e-02 4.81560887996981e-01 -1.90313415400156e-03 + 3.03030303030302e-01 2.69131749150450e-02 4.81684879937810e-01 -2.12376124690789e-03 + 9.09090909090912e-01 2.95856638229001e-02 4.81808857865227e-01 -2.33301661078614e-03 + 1.51515151515152e+00 3.22398936101882e-02 4.81929840079279e-01 -2.55120165338738e-03 + 2.12121212121212e+00 3.66675784640552e-02 4.81924986740543e-01 -2.77391835793390e-03 + 2.72727272727273e+00 4.19698427928253e-02 4.81879454613869e-01 -2.98510710550669e-03 + 3.33333333333333e+00 4.72717179522425e-02 4.81833922593971e-01 -3.18573614963958e-03 + 3.93939393939394e+00 5.25753326357400e-02 4.81775728360497e-01 -3.38638186200821e-03 + 4.54545454545455e+00 5.78765746006633e-02 4.81728632143155e-01 -3.59889201718914e-03 + 5.15151515151515e+00 6.31803800322498e-02 4.81680617938285e-01 -3.79953830438974e-03 + 5.75757575757576e+00 6.78668119866628e-02 4.81626107889307e-01 -4.03804041841606e-03 + 6.36363636363637e+00 7.15042486961224e-02 4.81584603835809e-01 -4.34980617905866e-03 + 6.96969696969697e+00 7.49998526302299e-02 4.81530576563388e-01 -4.66507085142508e-03 + 7.57575757575757e+00 7.85534281259633e-02 4.81489207644286e-01 -4.96022383060956e-03 + 8.18181818181818e+00 8.27222397693518e-02 4.81442706653469e-01 -5.12210053319802e-03 + 8.78787878787879e+00 8.59673537796770e-02 4.81485608223198e-01 -5.30026887591891e-03 + 9.39393939393939e+00 8.63938854494780e-02 4.81734888790963e-01 -5.58390579608546e-03 + 1.00000000000000e+01 8.61476310716953e-02 4.82033636040847e-01 -5.89351913489291e-03 + 1.06060606060606e+01 1.14640664678628e-02 4.86367761950627e-01 -4.32401101558585e-03 + 1.12121212121212e+01 1.77109990487445e-03 4.90977291638818e-01 -5.52690415533776e-05 + 1.18181818181818e+01 1.63608094150530e-03 4.94596563237555e-01 -4.71568484033090e-05 + 1.24242424242424e+01 5.38023265894621e-02 4.97637007791052e-01 -7.01427597271410e-05 + 1.30303030303030e+01 7.07102583465799e-02 4.99408388908304e-01 -2.78511851302713e-04 + 1.36363636363636e+01 6.81632004936948e-02 4.99466710089213e-01 -3.41458399817878e-04 + 1.42424242424242e+01 6.49592840496404e-02 4.99515392758744e-01 -3.60890382699212e-04 + 1.48484848484848e+01 6.00226087507924e-02 4.99558582755279e-01 -3.80502489146672e-04 + 1.54545454545455e+01 5.42932388358678e-02 4.99595173447000e-01 -3.60569709918067e-04 + 1.60606060606061e+01 4.89399852015463e-02 4.99626659734195e-01 -3.74707069218248e-04 + 1.66666666666667e+01 4.90264804982352e-02 4.99643029856566e-01 -8.14570485140793e-04 + 1.72727272727273e+01 4.89767434358854e-02 4.99658738397009e-01 -1.29542584308036e-03 + 1.78787878787879e+01 4.87601917929942e-02 4.99673710331708e-01 -1.82640692279492e-03 + 1.84848484848485e+01 4.85448822816922e-02 4.99688486075466e-01 -2.35860501303099e-03 + 1.90909090909091e+01 4.83300562227171e-02 4.99703072863703e-01 -2.89167774847090e-03 + 1.96969696969697e+01 4.81154623433704e-02 4.99717479015725e-01 -3.42523467641370e-03 + 2.03030303030303e+01 4.80233231913679e-02 4.99733684020482e-01 -3.86916331990858e-03 + 2.09090909090909e+01 4.80535318777004e-02 4.99751580718914e-01 -4.22318641357654e-03 + 2.15151515151515e+01 4.80838465710918e-02 4.99769120219361e-01 -4.57757988364418e-03 + 2.21212121212121e+01 4.81142702027946e-02 4.99786285377891e-01 -4.93233346765168e-03 + 2.27272727272727e+01 4.81448054735174e-02 4.99803057767734e-01 -5.28743306710894e-03 + 2.33333333333333e+01 4.81754564360106e-02 4.99819418446624e-01 -5.64287905507360e-03 + 2.39393939393939e+01 4.82062265821584e-02 4.99835346782305e-01 -5.99866390348971e-03 + 2.45454545454545e+01 4.82371195457987e-02 4.99850820740502e-01 -6.35478030087519e-03 + 2.51515151515151e+01 4.82681391100110e-02 4.99865816763762e-01 -6.71122114458926e-03 + 2.57575757575758e+01 4.82992892148572e-02 4.99880309637533e-01 -7.06797953342872e-03 + 2.63636363636364e+01 4.83305745045125e-02 4.99894272577114e-01 -7.42505490046007e-03 + 2.69696969696970e+01 4.83619990851020e-02 4.99907676487852e-01 -7.78243869417755e-03 + 2.75757575757576e+01 4.83935670617676e-02 4.99920490061147e-01 -8.14012048538783e-03 + 2.81818181818182e+01 4.84252828173819e-02 4.99932679692807e-01 -8.49809103217069e-03 + 2.87878787878788e+01 4.84571508417891e-02 4.99944209186026e-01 -8.85634022554155e-03 + 2.93939393939394e+01 4.84891768440017e-02 4.99955039870966e-01 -9.21486940940596e-03 + 3.00000000000000e+01 4.85213661255990e-02 4.99965129704843e-01 -9.57367290978077e-03 + 3.30000000000000e+01 4.85783850925221e-02 5.01549646541201e-01 -1.08893308683242e-02 + 3.60000000000000e+01 4.86367279082047e-02 5.07633687072646e-01 -1.21830696545693e-02 + 3.90000000000000e+01 4.86965308414856e-02 5.13717843800706e-01 -1.34715855024972e-02 + 4.20000000000000e+01 4.81074542024269e-02 5.20009957227964e-01 -1.45755410030633e-02 + 4.50000000000000e+01 4.71938349445183e-02 5.26406109778172e-01 -1.55872262614513e-02 + 4.80000000000000e+01 4.62807992978572e-02 5.32802189034552e-01 -1.65988999268877e-02 + 5.10000000000000e+01 4.49696537236258e-02 5.39025652303692e-01 -1.75196039279897e-02 + 5.40000000000000e+01 4.28613244897533e-02 5.44903872501265e-01 -1.82583627521897e-02 + 5.70000000000000e+01 4.07532301242102e-02 5.47997027608551e-01 -1.89971159327085e-02 + 6.00000000000000e+01 3.86454092273193e-02 5.50390422420595e-01 -1.97358662914081e-02 + 6.30000000000000e+01 3.54441639493027e-02 5.51842301880517e-01 -2.01991699310181e-02 + 6.60000000000000e+01 3.22429963032422e-02 5.53294173270158e-01 -2.06624712096125e-02 + 6.90000000000000e+01 2.90419479592744e-02 5.54746044659799e-01 -2.11257724882070e-02 + 7.20000000000000e+01 2.52997639160426e-02 5.55339411593092e-01 -2.14026262276280e-02 + 7.50000000000000e+01 2.12869899032544e-02 5.55503543872940e-01 -2.15862600142917e-02 + 7.80000000000000e+01 1.72742065965976e-02 5.55667678033613e-01 -2.17698959052524e-02 + 8.10000000000000e+01 1.31391516042592e-02 5.55336586108752e-01 -2.18644734045035e-02 + 8.40000000000000e+01 8.75945317316178e-03 5.54015076197080e-01 -2.17809402678169e-02 + 8.70000000000000e+01 4.37972128358576e-03 5.52693556189802e-01 -2.16904207186265e-02 + 9.00000000000000e+01 -1.91272727377706e-08 5.51372047630695e-01 -2.15841433608613e-02 + 9.30000000000000e+01 -3.06463754512461e-03 5.52693557542367e-01 -2.23059396312876e-02 + 9.60000000000000e+01 -6.12926766887736e-03 5.54015072501802e-01 -2.29980046662208e-02 + 9.90000000000000e+01 -9.19392120485563e-03 5.55336597556942e-01 -2.36900749881812e-02 + 1.02000000000000e+02 -1.20876828091304e-02 5.55667677238678e-01 -2.41783390479984e-02 + 1.05000000000000e+02 -1.48960397658858e-02 5.55503544958831e-01 -2.45647021836766e-02 + 1.08000000000000e+02 -1.77044555792872e-02 5.55339410798165e-01 -2.49510697467495e-02 + 1.11000000000000e+02 -2.03258601363591e-02 5.54746032082366e-01 -2.52295211230444e-02 + 1.14000000000000e+02 -2.25732865469573e-02 5.53294177329843e-01 -2.52921434125440e-02 + 1.17000000000000e+02 -2.48208058238953e-02 5.51842311486022e-01 -2.53547661804404e-02 + 1.20000000000000e+02 -2.70683874187890e-02 5.50390438255170e-01 -2.54173886357562e-02 + 1.23000000000000e+02 -2.85442923527018e-02 5.47997043443125e-01 -2.51978496904198e-02 + 1.26000000000000e+02 -3.00203897774573e-02 5.44903911391262e-01 -2.49783099065228e-02 + 1.29000000000000e+02 -3.14966524820477e-02 5.39025691193689e-01 -2.47587684454421e-02 + 1.32000000000000e+02 -3.24110462717851e-02 5.32802182487933e-01 -2.44128347281493e-02 + 1.35000000000000e+02 -3.30448480367859e-02 5.26406029938182e-01 -2.40037050326582e-02 + 1.38000000000000e+02 -3.36790582106382e-02 5.20009950681803e-01 -2.35945800253753e-02 + 1.41000000000000e+02 -3.40874558144093e-02 5.13717849193324e-01 -2.31850713339234e-02 + 1.44000000000000e+02 -3.40443360294749e-02 5.07633704084372e-01 -2.27747952710201e-02 + 1.47000000000000e+02 -3.40022351252792e-02 5.01549605455131e-01 -2.23645223424130e-02 + 1.50000000000000e+02 -3.39610598736408e-02 4.99965130046894e-01 -2.19542509808981e-02 + 1.53000000000000e+02 -3.38548418745498e-02 4.99908331389323e-01 -2.20200907982144e-02 + 1.56000000000000e+02 -3.37510782194723e-02 4.99836914626034e-01 -2.20859314734659e-02 + 1.59000000000000e+02 -3.36494201711338e-02 4.99754234730512e-01 -2.21517716457378e-02 + 1.62000000000000e+02 -3.10637475603964e-02 4.99680051763820e-01 -2.42417639918563e-02 + 1.65000000000000e+02 -2.72360674222744e-02 4.99608171404762e-01 -2.73438495435689e-02 + 1.68000000000000e+02 -2.34094297732302e-02 4.99530448606310e-01 -3.04458995483989e-02 + 1.71000000000000e+02 -1.87731622461588e-02 4.99461965511715e-01 -2.92625874417800e-02 + 1.74000000000000e+02 -1.25154154596942e-02 4.99419482735902e-01 -1.95083510416281e-02 + 1.77000000000000e+02 -6.22917411225319e-03 4.99373778033698e-01 -9.70969886478117e-03 + 1.80000000000000e+02 0.00000000000000e+00 4.98298540333591e-01 0.00000000000000e+00 diff --git a/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_02.dat b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_02.dat new file mode 100644 index 00000000..3b06888a --- /dev/null +++ b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_02.dat @@ -0,0 +1,254 @@ +! ------------ AirfoilInfo v1.01.x Input File ---------------------------------- +! AeroElasticSE FAST driver +! line +! line +! ------------------------------------------------------------------------------ +DEFAULT InterpOrd ! Interpolation order to use for quasi-steady table lookup {1=linear; 3=cubic spline; "default"} [default=3] +1 NonDimArea ! The non-dimensional area of the airfoil (area/chord^2) (set to 1.0 if unsure or unneeded) +@"NREL-2p8-127_AF02_Coords.txt" NumCoords ! The number of coordinates in the airfoil shape file. Set to zero if coordinates not included. +AF02_BL.txt BL_file ! The file name including the boundary layer characteristics of the profile. Ignored if the aeroacoustic module is not called. +1 NumTabs ! Number of airfoil tables in this file. Each table must have lines for Re and Ctrl. +! ------------------------------------------------------------------------------ +! data for table 1 +! ------------------------------------------------------------------------------ +6.000000 Re ! Reynolds number in millions +0 Ctrl ! Control setting (must be 0 for current AirfoilInfo) +True InclUAdata ! Is unsteady aerodynamics data included in this table? If TRUE, then include 30 UA coefficients below this line +!........................................ +0.000000 alpha0 ! 0-lift angle of attack, depends on airfoil. +0.000000 alpha1 ! Angle of attack at f=0.7, (approximately the stall angle) for AOA>alpha0. (deg) +0.000000 alpha2 ! Angle of attack at f=0.7, (approximately the stall angle) for AOA1] +0.000000 S2 ! Constant in the f curve best-fit for AOA> alpha1; by definition it depends on the airfoil. [ignored if UAMod<>1] +0.000000 S3 ! Constant in the f curve best-fit for alpha2<=AOA< alpha0; by definition it depends on the airfoil. [ignored if UAMod<>1] +0.000000 S4 ! Constant in the f curve best-fit for AOA< alpha2; by definition it depends on the airfoil. [ignored if UAMod<>1] +0.000000 Cn1 ! Critical value of C0n at leading edge separation. It should be extracted from airfoil data at a given Mach and Reynolds number. It can be calculated from the static value of Cn at either the break in the pitching moment or the loss of chord force at the onset of stall. It is close to the condition of maximum lift of the airfoil at low Mach numbers. +0.000000 Cn2 ! As Cn1 for negative AOAs. +Default St_sh ! Strouhal's shedding frequency constant. [default = 0.19] +0.000000 Cd0 ! 2D drag coefficient value at 0-lift. +0.000000 Cm0 ! 2D pitching moment coefficient about 1/4-chord location, at 0-lift, positive if nose up. [If the aerodynamics coefficients table does not include a column for Cm, this needs to be set to 0.0] +0.000000 k0 ! Constant in the \hat(x)_cp curve best-fit; = (\hat(x)_AC-0.25). [ignored if UAMod<>1] +0.000000 k1 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k2 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k3 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k1_hat ! Constant in the expression of Cc due to leading edge vortex effects. [ignored if UAMod<>1] +Default x_cp_bar ! Constant in the expression of \hat(x)_cp^v. [ignored if UAMod<>1, default = 0.2] +Default UACutout ! Angle of attack above which unsteady aerodynamics are disabled (deg). [Specifying the string "Default" sets UACutout to 45 degrees] +Default filtCutOff ! Cut-off frequency (-3 dB corner frequency) for low-pass filtering the AoA input to UA, as well as the 1st and 2nd derivatives (Hz) [default = 20] +!........................................ +! Table of aerodynamics coefficients +200 NumAlf ! Number of data lines in the following table +! Alpha Cl Cd Cm +! (deg) (-) (-) (-) +-1.80000000000000e+02 0.00000000000000e+00 4.43994184250602e-01 0.00000000000000e+00 +-1.77000000000000e+02 5.28218858836285e-02 4.51778947168691e-01 6.31301215186523e-02 +-1.74000000000000e+02 1.06127688082721e-01 4.54846200132976e-01 1.26838596030369e-01 +-1.71000000000000e+02 1.59191863314727e-01 4.57721687001980e-01 1.90258289868333e-01 +-1.68000000000000e+02 1.97447618139026e-01 4.62593607482116e-01 2.03998727898909e-01 +-1.65000000000000e+02 2.28363691552126e-01 4.68241882193770e-01 1.92900117855920e-01 +-1.62000000000000e+02 2.59339036364168e-01 4.73545480231159e-01 1.81801380632199e-01 +-1.59000000000000e+02 2.79820337838342e-01 4.79170658239085e-01 1.73519743179148e-01 +-1.56000000000000e+02 2.79311457907633e-01 4.85668590966138e-01 1.70872209970165e-01 +-1.53000000000000e+02 2.78926753637668e-01 4.91502040321387e-01 1.68224656535610e-01 +-1.50000000000000e+02 2.78686833504982e-01 4.96473066155593e-01 1.65577105058638e-01 +-1.47000000000000e+02 2.78482617289417e-01 5.10449666953889e-01 1.68109661007669e-01 +-1.44000000000000e+02 2.78333002128108e-01 5.51477403517201e-01 1.70642226630173e-01 +-1.41000000000000e+02 2.78243478183707e-01 5.92505453513528e-01 1.73174811600312e-01 +-1.38000000000000e+02 2.74638204421170e-01 6.34935844279750e-01 1.76256259812944e-01 +-1.35000000000000e+02 2.69271830313825e-01 6.78067402586119e-01 1.79612138533394e-01 +-1.32000000000000e+02 2.63929918544127e-01 7.21199455141732e-01 1.82968055709224e-01 +-1.29000000000000e+02 2.56353341244360e-01 7.63167294790495e-01 1.86036517826043e-01 +-1.26000000000000e+02 2.44267095501969e-01 8.02806703094638e-01 1.88530068460767e-01 +-1.23000000000000e+02 2.32190027809931e-01 8.30095142617392e-01 1.91023600046048e-01 +-1.20000000000000e+02 2.20124030074996e-01 8.54280447094884e-01 1.93517122106963e-01 +-1.17000000000000e+02 2.01822771772063e-01 8.71322712892104e-01 1.94226310566758e-01 +-1.14000000000000e+02 1.83524830303930e-01 8.88364899623064e-01 1.94935492828237e-01 +-1.11000000000000e+02 1.65231494534441e-01 9.05406956162956e-01 1.95644669672032e-01 +-1.08000000000000e+02 1.43911689592217e-01 9.15698197853296e-01 1.94815640807175e-01 +-1.05000000000000e+02 1.21077486266499e-01 9.22613980715162e-01 1.93217497375608e-01 +-1.02000000000000e+02 9.82451183513876e-02 9.29529684328913e-01 1.91619372257204e-01 +-9.90000000000000e+01 7.47225598413416e-02 9.32477260333714e-01 1.89218782642220e-01 +-9.60000000000000e+01 4.98149331461973e-02 9.27488409240135e-01 1.85213229275117e-01 +-9.30000000000000e+01 2.49074967312809e-02 9.22499596258566e-01 1.81207706508184e-01 +-9.00000000000000e+01 1.55454756347091e-07 9.17510802332658e-01 1.75447976882559e-01 +-8.70000000000000e+01 -2.49074712386065e-02 9.22499591152534e-01 1.75821854055456e-01 +-8.40000000000000e+01 -4.98150027934706e-02 9.27488423190074e-01 1.75265803096445e-01 +-8.10000000000000e+01 -7.47223440699950e-02 9.32477217115983e-01 1.74297623848041e-01 +-7.80000000000000e+01 -9.82450077740596e-02 9.29529717823434e-01 1.71657379233808e-01 +-7.50000000000000e+01 -1.21077637330475e-01 9.22613934961229e-01 1.68181073081051e-01 +-7.20000000000000e+01 -1.43911579000158e-01 9.15698231347477e-01 1.64704806763536e-01 +-6.90000000000000e+01 -1.65231336083193e-01 9.05407103798478e-01 1.60521039551036e-01 +-6.60000000000000e+01 -1.83524881462789e-01 8.88364851969969e-01 1.54922212612248e-01 +-6.30000000000000e+01 -2.01822892842596e-01 8.71322600141459e-01 1.49323385673460e-01 +-6.00000000000000e+01 -2.20124109861353e-01 8.54280287086177e-01 1.43724546113009e-01 +-5.70000000000000e+01 -2.32190107676827e-01 8.30094982608685e-01 1.36653206413885e-01 +-5.40000000000000e+01 -2.44267175435753e-01 8.02806440842389e-01 1.29581839704227e-01 +-5.10000000000000e+01 -2.56353421232862e-01 7.63167032538246e-01 1.22510418973089e-01 +-4.80000000000000e+01 -2.63929913090152e-01 7.21199499288443e-01 1.14843085027639e-01 +-4.50000000000000e+01 -2.69271763474185e-01 6.78067940982074e-01 1.06877804052201e-01 +-4.20000000000000e+01 -2.74638198917296e-01 6.34935888423376e-01 9.89124318011671e-02 +-3.90000000000000e+01 -2.78243478234639e-01 5.92505417148744e-01 9.07777362760891e-02 +-3.60000000000000e+01 -2.78333002465160e-01 5.51477288799700e-01 8.23042410827366e-02 +-3.30000000000000e+01 -2.78482616088909e-01 5.10449944015222e-01 7.38309077181307e-02 +-3.00000000000000e+01 -2.78686834724237e-01 4.96473034437446e-01 6.53574058853759e-02 +-2.93939393939394e+01 -2.78722484884278e-01 4.95550482915159e-01 6.31590888898999e-02 +-2.87878787878788e+01 -2.78764834228033e-01 4.94584223091226e-01 6.07329510056277e-02 +-2.81818181818182e+01 -2.78813665479675e-01 4.93576735381485e-01 5.83222958533192e-02 +-2.75757575757576e+01 -2.78868771825416e-01 4.92530294643563e-01 5.59273989519316e-02 +-2.69696969696970e+01 -2.78929953713021e-01 4.91447040145689e-01 5.35486208968168e-02 +-2.63636363636364e+01 -2.78997019845282e-01 4.90328957261459e-01 5.11863242110430e-02 +-2.57575757575758e+01 -2.79069786417323e-01 4.89177896868326e-01 4.88408872710036e-02 +-2.51515151515151e+01 -2.79148077344780e-01 4.87995577350176e-01 4.65126844314689e-02 +-2.45454545454545e+01 -2.79231725535284e-01 4.86783573310055e-01 4.42020473048908e-02 +-2.39393939393939e+01 -2.79320569460013e-01 4.85543372341575e-01 4.19093587754535e-02 +-2.33333333333333e+01 -2.79414454019281e-01 4.84276364273540e-01 3.96350129365467e-02 +-2.27272727272727e+01 -2.79513230225828e-01 4.82983849071519e-01 3.73794155039853e-02 +-2.21212121212121e+01 -2.79616754906648e-01 4.81667043985251e-01 3.51429842476471e-02 +-2.15151515151515e+01 -2.79724892952109e-01 4.80327059059195e-01 3.29260988660576e-02 +-2.09090909090909e+01 -2.79837510321443e-01 4.78964987050167e-01 3.07292415847816e-02 +-2.03030303030303e+01 -2.79954479045127e-01 4.77581841281423e-01 2.85528819253764e-02 +-1.96969696969697e+01 -2.75171456546404e-01 4.76241678491924e-01 2.59885541142665e-02 +-1.90909090909091e+01 -2.65502607041286e-01 4.74932861964715e-01 2.30296767768801e-02 +-1.84848484848485e+01 -2.55857808543395e-01 4.73587766414009e-01 2.00850651071971e-02 +-1.78787878787879e+01 -2.46237593082487e-01 4.72205644697461e-01 1.71576346825735e-02 +-1.72727272727273e+01 -2.36642641160737e-01 4.70785737308274e-01 1.42512880441333e-02 +-1.66666666666667e+01 -2.27074552079369e-01 4.69327391673071e-01 1.13715515436610e-02 +-1.60606060606061e+01 -2.17534554179683e-01 4.67829874530176e-01 8.52581274757511e-03 +-1.54545454545455e+01 -2.08024441493220e-01 4.66292514169838e-01 5.72461577042921e-03 +-1.48484848484848e+01 -1.98545026218225e-01 4.64714449362364e-01 3.24301314993957e-03 +-1.42424242424242e+01 -1.89097459745549e-01 4.63094831340957e-01 2.15754331667197e-03 +-1.36363636363636e+01 -1.79689119603896e-01 4.61433905636119e-01 1.19082104448867e-03 +-1.30303030303030e+01 -1.70305930436414e-01 4.59727952028918e-01 4.04096803450701e-04 +-1.24242424242424e+01 -1.60970739714131e-01 4.57980061533300e-01 -1.08597634782590e-03 +-1.18181818181818e+01 -1.51665423337775e-01 4.56185474694515e-01 -5.28562481853854e-03 +-1.12121212121212e+01 -1.42405828637851e-01 4.54346018736465e-01 -9.48493644261989e-03 +-1.06060606060606e+01 -1.33190990892009e-01 4.51015638941563e-01 -1.36845608636440e-02 +-1.00000000000000e+01 -1.24014684903561e-01 4.44510346744821e-01 -1.78839224215030e-02 +-9.39393939393939e+00 -1.08436489679061e-01 4.35608923797464e-01 -1.72393490814751e-02 +-8.78787878787879e+00 -9.29541316307449e-02 4.26594514374539e-01 -1.65987787657685e-02 +-8.18181818181818e+00 -7.76026887758120e-02 4.17469560995041e-01 -1.59527308236021e-02 +-7.57575757575758e+00 -6.23970752419446e-02 4.08227566266090e-01 -1.52754905468310e-02 +-6.96969696969697e+00 -4.73685296749869e-02 3.98853223979206e-01 -1.42539284761816e-02 +-6.36363636363636e+00 -3.25421758356058e-02 3.89329220025460e-01 -1.32208969139180e-02 +-5.75757575757576e+00 -2.32883547306756e-02 3.79669167553607e-01 -1.21878209564984e-02 +-5.15151515151515e+00 -1.75463818719779e-02 3.69851724588186e-01 -1.11628011971168e-02 +-4.54545454545454e+00 -1.22231690324848e-02 3.59859373530705e-01 -1.01275683268214e-02 +-3.93939393939394e+00 -7.44825163485882e-03 3.49689752142525e-01 -9.09398161623545e-03 +-3.33333333333333e+00 -2.91658839268368e-03 3.40624828035861e-01 -8.49251566568143e-03 +-2.72727272727273e+00 1.68507347052569e-02 3.37851584545355e-01 -9.05855564667579e-03 +-2.12121212121212e+00 6.54268180916555e-02 3.38696970690453e-01 -1.01724248228530e-02 +-1.51515151515152e+00 1.14007336489887e-01 3.39540888251967e-01 -1.18440226132878e-02 +-9.09090909090912e-01 1.51313727007511e-01 3.40364324377504e-01 -1.33594433207991e-02 +-3.03030303030302e-01 1.79793106660581e-01 3.41119901467205e-01 -1.49439775633901e-02 + 3.03030303030302e-01 2.08277227321411e-01 3.41959802485552e-01 -1.65190153005760e-02 + 9.09090909090912e-01 2.36761120877396e-01 3.42798375876233e-01 -1.80436696564668e-02 + 1.51515151515152e+00 2.62099120009543e-01 3.43615726098759e-01 -1.96089791867871e-02 + 2.12121212121212e+00 2.98214942887010e-01 3.43590036955630e-01 -2.12433569551258e-02 + 2.72727272727273e+00 3.41265305298494e-01 3.43282612273994e-01 -2.28522580646574e-02 + 3.33333333333333e+00 3.84321941282732e-01 3.42975023524515e-01 -2.44142825317703e-02 + 3.93939393939394e+00 4.27399321163861e-01 3.42588020332646e-01 -2.59764367716794e-02 + 4.54545454545455e+00 4.70462749288264e-01 3.42270335299019e-01 -2.75887619844635e-02 + 5.15151515151515e+00 5.13550609798191e-01 3.41947566135864e-01 -2.91509206998043e-02 + 5.75757575757576e+00 5.51690452105184e-01 3.41583432622427e-01 -3.09254291087337e-02 + 6.36363636363637e+00 5.81502121097488e-01 3.41302193452691e-01 -3.30991045572195e-02 + 6.96969696969697e+00 6.10301560112658e-01 3.40942615842003e-01 -3.52998315891569e-02 + 7.57575757575757e+00 6.39640830053245e-01 3.40662394282476e-01 -3.74120160931164e-02 + 8.18181818181818e+00 6.73716922359672e-01 3.40349350542629e-01 -3.89332211349433e-02 + 8.78787878787879e+00 7.00575005999923e-01 3.40649231227702e-01 -4.05874368999055e-02 + 9.39393939393939e+00 7.05980518760212e-01 3.42347265627704e-01 -4.28334247556514e-02 + 1.00000000000000e+01 7.06877424431301e-01 3.44374177297010e-01 -4.52251156741810e-02 + 1.06060606060606e+01 2.24043543681458e-01 3.72918111447314e-01 -3.53747047936440e-02 + 1.12121212121212e+01 1.40264660669456e-01 4.01951061572017e-01 -4.64618913321433e-03 + 1.18181818181818e+01 1.31385056875955e-01 4.23992085353333e-01 -4.07850695907500e-03 + 1.24242424242424e+01 4.46038012430764e-01 4.42283118524471e-01 -5.50420221929163e-03 + 1.30303030303030e+01 5.55998373281915e-01 4.54419475361305e-01 -7.26003568693194e-03 + 1.36363636363636e+01 5.44188127636130e-01 4.58360923643072e-01 -7.86408309600584e-03 + 1.42424242424242e+01 5.27942944540329e-01 4.61684804811602e-01 -8.24435657376023e-03 + 1.48484848484848e+01 4.89688648561149e-01 4.64663565131384e-01 -8.63252791099281e-03 + 1.54545454545455e+01 4.48737588342535e-01 4.67211594818839e-01 -8.81024773998454e-03 + 1.60606060606061e+01 4.12943834077636e-01 4.69433759746416e-01 -9.21685653350780e-03 + 1.66666666666667e+01 4.12507412476758e-01 4.70665756115078e-01 -1.23356902066896e-02 + 1.72727272727273e+01 4.11140315107920e-01 4.71853296753582e-01 -1.57410394707879e-02 + 1.78787878787879e+01 4.08617622571655e-01 4.72990750025282e-01 -1.94979904601476e-02 + 1.84848484848485e+01 4.06114881343676e-01 4.74116453453578e-01 -2.33119670538974e-02 + 1.90909090909091e+01 4.03627419358201e-01 4.75230998047512e-01 -2.71766217490092e-02 + 1.96969696969697e+01 4.01154151508036e-01 4.76335071600720e-01 -3.10855411393017e-02 + 2.03030303030303e+01 3.99841450263120e-01 4.77581841281423e-01 -3.43354943821136e-02 + 2.09090909090909e+01 3.99682666388390e-01 4.78964987050167e-01 -3.69103854071785e-02 + 2.15151515151515e+01 3.99530136656685e-01 4.80327059059195e-01 -3.95071276844189e-02 + 2.21212121212121e+01 3.99384045127721e-01 4.81667043985251e-01 -4.21252206930270e-02 + 2.27272727272727e+01 3.99244584495002e-01 4.82983849071519e-01 -4.47641473640253e-02 + 2.33333333333333e+01 3.99111949378307e-01 4.84276364273540e-01 -4.74235100634337e-02 + 2.39393939393939e+01 3.98986345789788e-01 4.85543372341575e-01 -5.01028646553693e-02 + 2.45454545454545e+01 3.98867988116513e-01 4.86783573310055e-01 -5.28017797812506e-02 + 2.51515151515151e+01 3.98757099550410e-01 4.87995577350176e-01 -5.55198364035922e-02 + 2.57575757575758e+01 3.98653912544980e-01 4.89177896868326e-01 -5.82566273692076e-02 + 2.63636363636364e+01 3.98558667733390e-01 4.90328957261459e-01 -6.10118045012879e-02 + 2.69696969696970e+01 3.98471618483357e-01 4.91447040145689e-01 -6.37849681601756e-02 + 2.75757575757576e+01 3.98393029231929e-01 4.92530294643563e-01 -6.65757129024393e-02 + 2.81818181818182e+01 3.98323175239888e-01 4.93576735381485e-01 -6.93836508624560e-02 + 2.87878787878788e+01 3.98262343636652e-01 4.94584223091226e-01 -7.22083954498178e-02 + 2.93939393939394e+01 3.98210832316413e-01 4.95550482915159e-01 -7.50496587540483e-02 + 3.00000000000000e+01 3.98168954058675e-01 4.96473034437446e-01 -7.79071060247789e-02 + 3.30000000000000e+01 3.97861629624178e-01 5.10449944015222e-01 -8.85000759993798e-02 + 3.60000000000000e+01 3.97632504408999e-01 5.51477288799700e-01 -9.78012526556367e-02 + 3.90000000000000e+01 3.97489452250910e-01 5.92505417148744e-01 -1.06793009320285e-01 + 4.20000000000000e+01 3.92296355524120e-01 6.34935888423376e-01 -1.14716558885029e-01 + 4.50000000000000e+01 3.84572561868948e-01 6.78067940982074e-01 -1.22106077030729e-01 + 4.80000000000000e+01 3.76882670622963e-01 7.21199499288443e-01 -1.29495510499575e-01 + 5.10000000000000e+01 3.66020533668567e-01 7.63167032538246e-01 -1.36361479578265e-01 + 5.40000000000000e+01 3.48758349336931e-01 8.02806440842389e-01 -1.42180486224307e-01 + 5.70000000000000e+01 3.31509203268269e-01 8.30094982608685e-01 -1.47999448416575e-01 + 6.00000000000000e+01 3.14275781966473e-01 8.54280287086177e-01 -1.53818388382123e-01 + 6.30000000000000e+01 2.88206454299320e-01 8.71322600141459e-01 -1.57969229855332e-01 + 6.60000000000000e+01 2.62142183925970e-01 8.88364851969969e-01 -1.62120057030290e-01 + 6.90000000000000e+01 2.36084952068339e-01 9.05407103798478e-01 -1.66270884205247e-01 + 7.20000000000000e+01 2.05649772307401e-01 9.15698231347478e-01 -1.69225081057529e-01 + 7.50000000000000e+01 1.73023749638975e-01 9.22613934961229e-01 -1.71580987245091e-01 + 7.80000000000000e+01 1.40399517677831e-01 9.29529717823434e-01 -1.73936920429460e-01 + 8.10000000000000e+01 1.06786972533886e-01 9.32477217115983e-01 -1.75676992294215e-01 + 8.40000000000000e+01 7.11914675762680e-02 9.27488423190074e-01 -1.76185384031098e-01 + 8.70000000000000e+01 3.55956906886392e-02 9.22499591152534e-01 -1.76281636984940e-01 + 9.00000000000000e+01 -1.55454756453089e-07 9.17510802332658e-01 -1.75447976882559e-01 + 9.30000000000000e+01 -2.49074967312808e-02 9.22499596258566e-01 -1.81207706508184e-01 + 9.60000000000000e+01 -4.98149331461974e-02 9.27488409240135e-01 -1.85213229275117e-01 + 9.90000000000000e+01 -7.47225598413417e-02 9.32477260333714e-01 -1.89218782642220e-01 + 1.02000000000000e+02 -9.82451183513876e-02 9.29529684328913e-01 -1.91619372257204e-01 + 1.05000000000000e+02 -1.21077486266499e-01 9.22613980715162e-01 -1.93217497375608e-01 + 1.08000000000000e+02 -1.43911689592217e-01 9.15698197853296e-01 -1.94815640807175e-01 + 1.11000000000000e+02 -1.65231494534441e-01 9.05406956162956e-01 -1.95644669672032e-01 + 1.14000000000000e+02 -1.83524830303930e-01 8.88364899623064e-01 -1.94935492828237e-01 + 1.17000000000000e+02 -2.01822771772063e-01 8.71322712892104e-01 -1.94226310566758e-01 + 1.20000000000000e+02 -2.20124030074997e-01 8.54280447094884e-01 -1.93517122106963e-01 + 1.23000000000000e+02 -2.32190027809931e-01 8.30095142617392e-01 -1.91023600046048e-01 + 1.26000000000000e+02 -2.44267095501969e-01 8.02806703094638e-01 -1.88530068460767e-01 + 1.29000000000000e+02 -2.56353341244360e-01 7.63167294790494e-01 -1.86036517826043e-01 + 1.32000000000000e+02 -2.63929918544127e-01 7.21199455141732e-01 -1.82968055709224e-01 + 1.35000000000000e+02 -2.69271830313825e-01 6.78067402586119e-01 -1.79612138533394e-01 + 1.38000000000000e+02 -2.74638204421170e-01 6.34935844279749e-01 -1.76256259812944e-01 + 1.41000000000000e+02 -2.78243478183707e-01 5.92505453513527e-01 -1.73174811600312e-01 + 1.44000000000000e+02 -2.78333002128108e-01 5.51477403517201e-01 -1.70642226630173e-01 + 1.47000000000000e+02 -2.78482617289417e-01 5.10449666953889e-01 -1.68109661007669e-01 + 1.50000000000000e+02 -2.78686833504982e-01 4.96473066155593e-01 -1.65577105058638e-01 + 1.53000000000000e+02 -2.78926753637668e-01 4.91502040321387e-01 -1.68224656535610e-01 + 1.56000000000000e+02 -2.79311457907633e-01 4.85668590966138e-01 -1.70872209970165e-01 + 1.59000000000000e+02 -2.79820337838342e-01 4.79170658239085e-01 -1.73519743179148e-01 + 1.62000000000000e+02 -2.59339036364167e-01 4.73545480231159e-01 -1.92371270010081e-01 + 1.65000000000000e+02 -2.28363691552126e-01 4.68241882193770e-01 -2.19324930692370e-01 + 1.68000000000000e+02 -1.97447618139026e-01 4.62593607482116e-01 -2.46278282511930e-01 + 1.71000000000000e+02 -1.59191863314727e-01 4.57721687001980e-01 -2.37822862335416e-01 + 1.74000000000000e+02 -1.06127688082721e-01 4.54846200132976e-01 -1.58548245037961e-01 + 1.77000000000000e+02 -5.28218858836285e-02 4.51778947168691e-01 -7.89126518983154e-02 + 1.80000000000000e+02 0.00000000000000e+00 4.43994184250602e-01 0.00000000000000e+00 diff --git a/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_03.dat b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_03.dat new file mode 100644 index 00000000..1c63fe2f --- /dev/null +++ b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_03.dat @@ -0,0 +1,254 @@ +! ------------ AirfoilInfo v1.01.x Input File ---------------------------------- +! AeroElasticSE FAST driver +! line +! line +! ------------------------------------------------------------------------------ +DEFAULT InterpOrd ! Interpolation order to use for quasi-steady table lookup {1=linear; 3=cubic spline; "default"} [default=3] +1 NonDimArea ! The non-dimensional area of the airfoil (area/chord^2) (set to 1.0 if unsure or unneeded) +@"NREL-2p8-127_AF03_Coords.txt" NumCoords ! The number of coordinates in the airfoil shape file. Set to zero if coordinates not included. +AF03_BL.txt BL_file ! The file name including the boundary layer characteristics of the profile. Ignored if the aeroacoustic module is not called. +1 NumTabs ! Number of airfoil tables in this file. Each table must have lines for Re and Ctrl. +! ------------------------------------------------------------------------------ +! data for table 1 +! ------------------------------------------------------------------------------ +6.000000 Re ! Reynolds number in millions +0 Ctrl ! Control setting (must be 0 for current AirfoilInfo) +True InclUAdata ! Is unsteady aerodynamics data included in this table? If TRUE, then include 30 UA coefficients below this line +!........................................ +0.000000 alpha0 ! 0-lift angle of attack, depends on airfoil. +0.000000 alpha1 ! Angle of attack at f=0.7, (approximately the stall angle) for AOA>alpha0. (deg) +0.000000 alpha2 ! Angle of attack at f=0.7, (approximately the stall angle) for AOA1] +0.000000 S2 ! Constant in the f curve best-fit for AOA> alpha1; by definition it depends on the airfoil. [ignored if UAMod<>1] +0.000000 S3 ! Constant in the f curve best-fit for alpha2<=AOA< alpha0; by definition it depends on the airfoil. [ignored if UAMod<>1] +0.000000 S4 ! Constant in the f curve best-fit for AOA< alpha2; by definition it depends on the airfoil. [ignored if UAMod<>1] +0.000000 Cn1 ! Critical value of C0n at leading edge separation. It should be extracted from airfoil data at a given Mach and Reynolds number. It can be calculated from the static value of Cn at either the break in the pitching moment or the loss of chord force at the onset of stall. It is close to the condition of maximum lift of the airfoil at low Mach numbers. +0.000000 Cn2 ! As Cn1 for negative AOAs. +Default St_sh ! Strouhal's shedding frequency constant. [default = 0.19] +0.000000 Cd0 ! 2D drag coefficient value at 0-lift. +0.000000 Cm0 ! 2D pitching moment coefficient about 1/4-chord location, at 0-lift, positive if nose up. [If the aerodynamics coefficients table does not include a column for Cm, this needs to be set to 0.0] +0.000000 k0 ! Constant in the \hat(x)_cp curve best-fit; = (\hat(x)_AC-0.25). [ignored if UAMod<>1] +0.000000 k1 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k2 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k3 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k1_hat ! Constant in the expression of Cc due to leading edge vortex effects. [ignored if UAMod<>1] +Default x_cp_bar ! Constant in the expression of \hat(x)_cp^v. [ignored if UAMod<>1, default = 0.2] +Default UACutout ! Angle of attack above which unsteady aerodynamics are disabled (deg). [Specifying the string "Default" sets UACutout to 45 degrees] +Default filtCutOff ! Cut-off frequency (-3 dB corner frequency) for low-pass filtering the AoA input to UA, as well as the 1st and 2nd derivatives (Hz) [default = 20] +!........................................ +! Table of aerodynamics coefficients +200 NumAlf ! Number of data lines in the following table +! Alpha Cl Cd Cm +! (deg) (-) (-) (-) +-1.80000000000000e+02 0.00000000000000e+00 2.86667939639823e-01 0.00000000000000e+00 +-1.77000000000000e+02 1.03993393584518e-01 2.98099548900633e-01 1.09870530503698e-01 +-1.74000000000000e+02 2.08939500216179e-01 3.07632373564454e-01 2.20747616176905e-01 +-1.71000000000000e+02 3.13409902357768e-01 3.16774623015665e-01 3.31122113148220e-01 +-1.68000000000000e+02 3.85054442612432e-01 3.34234373573580e-01 3.53101024359159e-01 +-1.65000000000000e+02 4.40412121695890e-01 3.55419527359135e-01 3.30883174396667e-01 +-1.62000000000000e+02 4.95885499788614e-01 3.75931646834106e-01 3.08665069836311e-01 +-1.59000000000000e+02 5.30626275353240e-01 3.98846265744607e-01 2.91144350600985e-01 +-1.56000000000000e+02 5.23897762918947e-01 4.27014220182996e-01 2.83018243112307e-01 +-1.53000000000000e+02 5.17411720704259e-01 4.53884562381070e-01 2.74892073545017e-01 +-1.50000000000000e+02 5.11208424965791e-01 4.79070665595520e-01 2.66765899031848e-01 +-1.47000000000000e+02 5.07722631231294e-01 5.14614980861448e-01 2.69838067335530e-01 +-1.44000000000000e+02 5.04343461108966e-01 5.71996674202226e-01 2.72910247373812e-01 +-1.41000000000000e+02 5.01081625048703e-01 6.29378805912717e-01 2.75982450882136e-01 +-1.38000000000000e+02 4.92453728624275e-01 6.88722261711689e-01 2.80934437546522e-01 +-1.35000000000000e+02 4.81136499725427e-01 7.49046375576140e-01 2.86826311975596e-01 +-1.32000000000000e+02 4.69867035979492e-01 8.09371180701211e-01 2.92718253920303e-01 +-1.29000000000000e+02 4.54938482726295e-01 8.68067709113985e-01 2.98486582390899e-01 +-1.26000000000000e+02 4.32612975232015e-01 9.23507676366582e-01 3.04007683325731e-01 +-1.23000000000000e+02 4.10305382623877e-01 9.74580839620112e-01 3.09528742082194e-01 +-1.20000000000000e+02 3.88019404664959e-01 1.02455678086533e+00 3.15049779750259e-01 +-1.17000000000000e+02 3.55328226413339e-01 1.06294869915767e+00 3.18312911803281e-01 +-1.14000000000000e+02 3.22643517723842e-01 1.10134044814828e+00 3.21576026976400e-01 +-1.11000000000000e+02 2.89967780617592e-01 1.13973190385125e+00 3.24839117221471e-01 +-1.08000000000000e+02 2.52261395940272e-01 1.16675109608688e+00 3.25784702971782e-01 +-1.05000000000000e+02 2.12037421291888e-01 1.18808406999478e+00 3.25571518828366e-01 +-1.02000000000000e+02 1.71816981097322e-01 1.20941679944765e+00 3.25358337127833e-01 +-9.90000000000000e+01 1.30505705696886e-01 1.22393767216320e+00 3.23791373077473e-01 +-9.60000000000000e+01 8.70036173585535e-02 1.22483453634678e+00 3.19516785688025e-01 +-9.30000000000000e+01 4.35018613516539e-02 1.22573139367882e+00 3.15242230954016e-01 +-9.00000000000000e+01 2.71507463396801e-07 1.22662824758516e+00 3.07541711312162e-01 +-8.70000000000000e+01 -4.35018168277582e-02 1.22573139459675e+00 3.06500259153458e-01 +-8.40000000000000e+01 -8.70037390000840e-02 1.22483453383895e+00 3.03642638678455e-01 +-8.10000000000000e+01 -1.30505328844274e-01 1.22393767993261e+00 2.99980148628166e-01 +-7.80000000000000e+01 -1.71816786310515e-01 1.20941690276751e+00 2.93732912001213e-01 +-7.50000000000000e+01 -2.12037687400372e-01 1.18808392885856e+00 2.86193257479784e-01 +-7.20000000000000e+01 -2.52261201124482e-01 1.16675119940570e+00 2.78653689355799e-01 +-6.90000000000000e+01 -2.89967497594430e-01 1.13973223643685e+00 2.70131045852760e-01 +-6.60000000000000e+01 -3.22643609105459e-01 1.10134034079787e+00 2.59642171088866e-01 +-6.30000000000000e+01 -3.55328442677626e-01 1.06294844515890e+00 2.49153296324973e-01 +-6.00000000000000e+01 -3.88019552026475e-01 1.02455645022712e+00 2.38664407299212e-01 +-5.70000000000000e+01 -4.10305530142687e-01 9.74580508981902e-01 2.26511664589643e-01 +-5.40000000000000e+01 -4.32613122881359e-01 9.23507309578663e-01 2.14358875460006e-01 +-5.10000000000000e+01 -4.54938630482502e-01 8.68067342326065e-01 2.02205993489526e-01 +-4.80000000000000e+01 -4.69867024471485e-01 8.09371242445124e-01 1.89666602848052e-01 +-4.50000000000000e+01 -4.81136358743375e-01 7.49047128580672e-01 1.76933964082825e-01 +-4.20000000000000e+01 -4.92453717018877e-01 6.88722323451287e-01 1.64201179411986e-01 +-3.90000000000000e+01 -5.01081627884301e-01 6.29378755052664e-01 1.51481884585662e-01 +-3.60000000000000e+01 -5.04343470398699e-01 5.71996513757487e-01 1.38789326350142e-01 +-3.30000000000000e+01 -5.07722608040306e-01 5.14615368361460e-01 1.26097010519998e-01 +-3.00000000000000e+01 -5.11208459117473e-01 4.79070493417508e-01 1.13404444471583e-01 +-2.93939393939394e+01 -5.12436596980431e-01 4.74141998928450e-01 1.10133084143430e-01 +-2.87878787878788e+01 -5.13677818293272e-01 4.69128142491057e-01 1.06416791520792e-01 +-2.81818181818182e+01 -5.14931698718120e-01 4.64033768336758e-01 1.02730736544464e-01 +-2.75757575757576e+01 -5.16197857581441e-01 4.58863256541541e-01 9.90754777938710e-02 +-2.69696969696970e+01 -5.17475891884770e-01 4.53620820905796e-01 9.54517077990795e-02 +-2.63636363636364e+01 -5.18765418068804e-01 4.48310365722169e-01 9.18601257810618e-02 +-2.57575757575758e+01 -5.20066063887109e-01 4.42935541572834e-01 8.83014589939624e-02 +-2.51515151515151e+01 -5.21377478812960e-01 4.37499722355814e-01 8.47764326963560e-02 +-2.45454545454545e+01 -5.22699356428834e-01 4.32005929515122e-01 8.12857120895547e-02 +-2.39393939393939e+01 -5.24031381270285e-01 4.26457068308669e-01 7.78300449431755e-02 +-2.33333333333333e+01 -5.25373250428924e-01 4.20855853060512e-01 7.44102009183187e-02 +-2.27272727272727e+01 -5.26724672933875e-01 4.15204822592555e-01 7.10269723745852e-02 +-2.21212121212121e+01 -5.28085369169450e-01 4.09506354183381e-01 6.76811752130597e-02 +-2.15151515151515e+01 -5.29455101817919e-01 4.03762544083001e-01 6.43735744019926e-02 +-2.09090909090909e+01 -5.30833589187798e-01 3.97975580174912e-01 6.11050941602448e-02 +-2.03030303030303e+01 -5.32220574716406e-01 3.92147459389974e-01 5.78766456029426e-02 +-1.96969696969697e+01 -5.25041853310013e-01 3.86734130344610e-01 5.36740381794206e-02 +-1.90909090909091e+01 -5.09325030771277e-01 3.81712847911617e-01 4.84844307653104e-02 +-1.84848484848485e+01 -4.93655025441404e-01 3.76620832907035e-01 4.33226553930925e-02 +-1.78787878787879e+01 -4.78033039651211e-01 3.71456499045297e-01 3.81944365371004e-02 +-1.72727272727273e+01 -4.62460538476065e-01 3.66218257085999e-01 3.31074211396244e-02 +-1.66666666666667e+01 -4.46940500203995e-01 3.60904945553023e-01 2.80723751195183e-02 +-1.60606060606061e+01 -4.31475323775307e-01 3.55515132392443e-01 2.31037263323430e-02 +-1.54545454545455e+01 -4.16068349642614e-01 3.50047632879528e-01 1.82220369706882e-02 +-1.48484848484848e+01 -4.00721354508913e-01 3.44500616736217e-01 1.35484980910323e-02 +-1.42424242424242e+01 -3.85436695885767e-01 3.38872341578923e-01 9.50016605244364e-03 +-1.36363636363636e+01 -3.70224538567261e-01 3.33164648622073e-01 5.68381330007907e-03 +-1.30303030303030e+01 -3.55069373476952e-01 3.27366609646139e-01 2.21886814225965e-03 +-1.24242424242424e+01 -3.39999733693878e-01 3.21489179943910e-01 -1.51885448689381e-03 +-1.18181818181818e+01 -3.24995626539620e-01 3.15518354985586e-01 -7.39251364704825e-03 +-1.12121212121212e+01 -3.10077560762327e-01 3.09460976947365e-01 -1.32657016910330e-02 +-1.06060606060606e+01 -2.95245474304323e-01 3.02802644980894e-01 -1.91393272151166e-02 +-1.00000000000000e+01 -2.80494800381428e-01 2.94941318686088e-01 -2.50125850968491e-02 +-9.39393939393939e+00 -2.53378368416910e-01 2.85498339501372e-01 -2.41110800948355e-02 +-8.78787878787879e+00 -2.26455617318188e-01 2.75839796452712e-01 -2.32151737520043e-02 +-8.18181818181818e+00 -1.99780347135765e-01 2.65960153502913e-01 -2.23116063606220e-02 +-7.57575757575758e+00 -1.73389839145603e-01 2.55848927836634e-01 -2.13969572586265e-02 +-6.96969696969697e+00 -1.47345183372831e-01 2.45482961997361e-01 -2.03679525995866e-02 +-6.36363636363636e+00 -1.21705108097721e-01 2.34834463036821e-01 -1.93275559307849e-02 +-5.75757575757576e+00 -9.84583488516512e-02 2.23910273504550e-01 -1.82871145503072e-02 +-5.15151515151515e+00 -7.69804748827422e-02 2.12678155631259e-01 -1.72546758160953e-02 +-4.54545454545454e+00 -5.63182850040337e-02 2.01106147724455e-01 -1.62156816231646e-02 +-3.93939393939394e+00 -3.67302227953779e-02 1.89186489694562e-01 -1.51750925589128e-02 +-3.33333333333333e+00 -1.62909510485965e-02 1.78416547415723e-01 -1.45633390580307e-02 +-2.72727272727273e+00 2.35675611773452e-02 1.75058203392890e-01 -1.57637846300459e-02 +-2.12121212121212e+00 9.15064277602737e-02 1.76056082872914e-01 -1.78244951342892e-02 +-1.51515151515152e+00 1.59451497183287e-01 1.77051126032286e-01 -2.03910649409379e-02 +-9.09090909090912e-01 2.23403602833365e-01 1.78026120925083e-01 -2.27493568922369e-02 +-3.03030303030302e-01 2.84237891949164e-01 1.78938378727225e-01 -2.51368568675113e-02 + 3.03030303030302e-01 3.45074372567327e-01 1.79925592577568e-01 -2.75148616917628e-02 + 9.09090909090912e-01 4.05913145027735e-01 1.80910163063640e-01 -2.98751951472708e-02 + 1.51515151515152e+00 4.60391564367498e-01 1.81869640777608e-01 -3.22531226669864e-02 + 2.12121212121212e+00 5.26159436695712e-01 1.81867217039864e-01 -3.48049504623527e-02 + 2.72727272727273e+00 6.00837730272748e-01 1.81506752812675e-01 -3.74260524663783e-02 + 3.33333333333333e+00 6.75529949068352e-01 1.81145950978939e-01 -4.00304350025881e-02 + 3.93939393939394e+00 7.50255901253955e-01 1.80716836967219e-01 -4.26350339105715e-02 + 4.54545454545455e+00 8.24966195051160e-01 1.80347288666951e-01 -4.52499112015484e-02 + 5.15151515151515e+00 8.99712588876260e-01 1.79976785308154e-01 -4.78545175714740e-02 + 5.75757575757576e+00 9.67968657716851e-01 1.79568694884216e-01 -5.06699455716737e-02 + 6.36363636363637e+00 1.02536319902264e+00 1.79238042626890e-01 -5.38531921907918e-02 + 6.96969696969697e+00 1.08152198541483e+00 1.78841802101979e-01 -5.70812124887872e-02 + 7.57575757575757e+00 1.13835718017464e+00 1.78513776681022e-01 -6.02799006382464e-02 + 8.18181818181818e+00 1.20034525413988e+00 1.78155584214918e-01 -6.32698190171098e-02 + 8.78787878787879e+00 1.25229031916550e+00 1.78543028590070e-01 -6.64922350787756e-02 + 9.39393939393939e+00 1.27694825197027e+00 1.80574010062172e-01 -7.03025346844773e-02 + 1.00000000000000e+01 1.29634873488058e+00 1.82986102023255e-01 -7.42574649964911e-02 + 1.06060606060606e+01 7.61428140940585e-01 2.15852259319746e-01 -6.42507106934242e-02 + 1.12121212121212e+01 6.15718379411708e-01 2.48106113414377e-01 -2.23104303837720e-02 + 1.18181818181818e+01 5.89645960609568e-01 2.71990713431963e-01 -2.03506593942910e-02 + 1.24242424242424e+01 8.40078452027123e-01 2.92157538787909e-01 -2.37998425692650e-02 + 1.30303030303030e+01 9.36540372696081e-01 3.08975183148329e-01 -2.65133219580019e-02 + 1.36363636363636e+01 9.30793183702627e-01 3.21455925212482e-01 -2.79339590650596e-02 + 1.42424242424242e+01 9.21535598013246e-01 3.32263191328175e-01 -2.92269843086423e-02 + 1.48484848484848e+01 8.79920211959341e-01 3.42195165358544e-01 -3.05512733483560e-02 + 1.54545454545455e+01 8.39112171194525e-01 3.50890504854493e-01 -3.17289039382959e-02 + 1.60606060606061e+01 8.05866011124999e-01 3.58713280531263e-01 -3.32426789378008e-02 + 1.66666666666667e+01 8.00847317731894e-01 3.63662607459754e-01 -3.82620408096336e-02 + 1.72727272727273e+01 7.94727809634000e-01 3.68473291646017e-01 -4.36253357634993e-02 + 1.78787878787879e+01 7.87227516277651e-01 3.73122818099744e-01 -4.94117560810391e-02 + 1.84848484848485e+01 7.79760973975816e-01 3.77747724480973e-01 -5.53090732287109e-02 + 1.90909090909091e+01 7.72322946522647e-01 3.82350733174758e-01 -6.13053346702226e-02 + 1.96969696969697e+01 7.64912514438728e-01 3.86935069316851e-01 -6.73885480064952e-02 + 2.03030303030303e+01 7.60227909567809e-01 3.92147459389974e-01 -7.23552962067858e-02 + 2.09090909090909e+01 7.58256171990743e-01 3.97975580174912e-01 -7.61741534254430e-02 + 2.15151515151515e+01 7.56296648702810e-01 4.03762544083001e-01 -8.00356859572341e-02 + 2.21212121212121e+01 7.54349708693408e-01 4.09506354183381e-01 -8.39389232226646e-02 + 2.27272727272727e+01 7.52415756848464e-01 4.15204822592555e-01 -8.78828761836009e-02 + 2.33333333333333e+01 7.50495135179352e-01 4.20855853060512e-01 -9.18667405374683e-02 + 2.39393939393939e+01 7.48588246026085e-01 4.26457068308669e-01 -9.58896488905942e-02 + 2.45454545454545e+01 7.46695508084816e-01 4.32005929515122e-01 -9.99507588032690e-02 + 2.51515151515151e+01 7.44817357247520e-01 4.37499722355814e-01 -1.04049251898781e-01 + 2.57575757575758e+01 7.42954247493942e-01 4.42935541572834e-01 -1.08184333010354e-01 + 2.63636363636364e+01 7.41106620219380e-01 4.48310365722169e-01 -1.12355301356762e-01 + 2.69696969696970e+01 7.39274979765670e-01 4.53620820905796e-01 -1.16561383374543e-01 + 2.75757575757576e+01 7.37459861618629e-01 4.58863256541540e-01 -1.20801801101431e-01 + 2.81818181818182e+01 7.35661817641651e-01 4.64033768336758e-01 -1.25075807437783e-01 + 2.87878787878788e+01 7.33881427635071e-01 4.69128142491057e-01 -1.29382661238589e-01 + 2.93939393939394e+01 7.32119240063399e-01 4.74141998928450e-01 -1.33721775955579e-01 + 3.00000000000000e+01 7.30375865782397e-01 4.79070493417508e-01 -1.38092497824076e-01 + 3.30000000000000e+01 7.25362478438806e-01 5.14615368361460e-01 -1.54403266201777e-01 + 3.60000000000000e+01 7.20501914137933e-01 5.71996513757487e-01 -1.68191263513666e-01 + 3.90000000000000e+01 7.15809365515503e-01 6.29378755052664e-01 -1.81374882567390e-01 + 4.20000000000000e+01 7.03433185279059e-01 6.88722323451288e-01 -1.93418520707176e-01 + 4.50000000000000e+01 6.87204092577322e-01 7.49047128580672e-01 -2.04892279627535e-01 + 4.80000000000000e+01 6.71041224113679e-01 8.09371242445124e-01 -2.16365907069522e-01 + 5.10000000000000e+01 6.49672046103066e-01 8.68067342326066e-01 -2.27288040920096e-01 + 5.40000000000000e+01 6.17781812255886e-01 9.23507309578663e-01 -2.37107152133572e-01 + 5.70000000000000e+01 5.85917028103372e-01 9.74580508981902e-01 -2.46926188334836e-01 + 6.00000000000000e+01 5.54082947327309e-01 1.02455645022712e+00 -2.56745187030279e-01 + 6.30000000000000e+01 5.07474214362050e-01 1.06294844515890e+00 -2.64611277891633e-01 + 6.60000000000000e+01 4.60875379522342e-01 1.10134034079787e+00 -2.72477352013468e-01 + 6.90000000000000e+01 4.14290290845089e-01 1.13973223643685e+00 -2.80343426135302e-01 + 7.20000000000000e+01 3.60455499151900e-01 1.16675119940570e+00 -2.86657663083315e-01 + 7.50000000000000e+01 3.02992179274825e-01 1.18808392885856e+00 -2.92196013212590e-01 + 7.80000000000000e+01 2.45532428311787e-01 1.20941690276751e+00 -2.97734426806946e-01 + 8.10000000000000e+01 1.86507133137001e-01 1.22393767993261e+00 -3.02380776716557e-01 + 8.40000000000000e+01 1.24338355198263e-01 1.22483453383895e+00 -3.05243060833536e-01 + 8.70000000000000e+01 6.21691023243765e-02 1.22573139459675e+00 -3.07300455628019e-01 + 9.00000000000000e+01 -2.71507463581614e-07 1.22662824758516e+00 -3.07541711312162e-01 + 9.30000000000000e+01 -4.35018613516539e-02 1.22573139367882e+00 -3.15242230954016e-01 + 9.60000000000000e+01 -8.70036173585537e-02 1.22483453634678e+00 -3.19516785688025e-01 + 9.90000000000000e+01 -1.30505705696887e-01 1.22393767216320e+00 -3.23791373077473e-01 + 1.02000000000000e+02 -1.71816981097322e-01 1.20941679944765e+00 -3.25358337127833e-01 + 1.05000000000000e+02 -2.12037421291888e-01 1.18808406999478e+00 -3.25571518828366e-01 + 1.08000000000000e+02 -2.52261395940272e-01 1.16675109608688e+00 -3.25784702971782e-01 + 1.11000000000000e+02 -2.89967780617593e-01 1.13973190385125e+00 -3.24839117221471e-01 + 1.14000000000000e+02 -3.22643517723843e-01 1.10134044814828e+00 -3.21576026976400e-01 + 1.17000000000000e+02 -3.55328226413339e-01 1.06294869915767e+00 -3.18312911803281e-01 + 1.20000000000000e+02 -3.88019404664959e-01 1.02455678086533e+00 -3.15049779750259e-01 + 1.23000000000000e+02 -4.10305382623878e-01 9.74580839620111e-01 -3.09528742082193e-01 + 1.26000000000000e+02 -4.32612975232015e-01 9.23507676366582e-01 -3.04007683325731e-01 + 1.29000000000000e+02 -4.54938482726295e-01 8.68067709113984e-01 -2.98486582390899e-01 + 1.32000000000000e+02 -4.69867035979492e-01 8.09371180701210e-01 -2.92718253920303e-01 + 1.35000000000000e+02 -4.81136499725427e-01 7.49046375576140e-01 -2.86826311975596e-01 + 1.38000000000000e+02 -4.92453728624275e-01 6.88722261711688e-01 -2.80934437546522e-01 + 1.41000000000000e+02 -5.01081625048703e-01 6.29378805912717e-01 -2.75982450882136e-01 + 1.44000000000000e+02 -5.04343461108966e-01 5.71996674202226e-01 -2.72910247373812e-01 + 1.47000000000000e+02 -5.07722631231294e-01 5.14614980861448e-01 -2.69838067335530e-01 + 1.50000000000000e+02 -5.11208424965791e-01 4.79070665595519e-01 -2.66765899031848e-01 + 1.53000000000000e+02 -5.17411720704259e-01 4.53884562381070e-01 -2.74892073545017e-01 + 1.56000000000000e+02 -5.23897762918947e-01 4.27014220182996e-01 -2.83018243112307e-01 + 1.59000000000000e+02 -5.30626275353240e-01 3.98846265744607e-01 -2.91144350600985e-01 + 1.62000000000000e+02 -4.95885499788614e-01 3.75931646834106e-01 -3.27060715613266e-01 + 1.65000000000000e+02 -4.40412121695890e-01 3.55419527359135e-01 -3.76872444414846e-01 + 1.68000000000000e+02 -3.85054442612432e-01 3.34234373573580e-01 -4.26683602422472e-01 + 1.71000000000000e+02 -3.13409902357768e-01 3.16774623015665e-01 -4.13902641435275e-01 + 1.74000000000000e+02 -2.08939500216179e-01 3.07632373564454e-01 -2.75934520221132e-01 + 1.77000000000000e+02 -1.03993393584518e-01 2.98099548900633e-01 -1.37338163129622e-01 + 1.80000000000000e+02 0.00000000000000e+00 2.86667939639823e-01 0.00000000000000e+00 diff --git a/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_04.dat b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_04.dat new file mode 100644 index 00000000..abbe8560 --- /dev/null +++ b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_04.dat @@ -0,0 +1,254 @@ +! ------------ AirfoilInfo v1.01.x Input File ---------------------------------- +! AeroElasticSE FAST driver +! line +! line +! ------------------------------------------------------------------------------ +DEFAULT InterpOrd ! Interpolation order to use for quasi-steady table lookup {1=linear; 3=cubic spline; "default"} [default=3] +1 NonDimArea ! The non-dimensional area of the airfoil (area/chord^2) (set to 1.0 if unsure or unneeded) +@"NREL-2p8-127_AF04_Coords.txt" NumCoords ! The number of coordinates in the airfoil shape file. Set to zero if coordinates not included. +AF04_BL.txt BL_file ! The file name including the boundary layer characteristics of the profile. Ignored if the aeroacoustic module is not called. +1 NumTabs ! Number of airfoil tables in this file. Each table must have lines for Re and Ctrl. +! ------------------------------------------------------------------------------ +! data for table 1 +! ------------------------------------------------------------------------------ +6.000000 Re ! Reynolds number in millions +0 Ctrl ! Control setting (must be 0 for current AirfoilInfo) +True InclUAdata ! Is unsteady aerodynamics data included in this table? If TRUE, then include 30 UA coefficients below this line +!........................................ +0.000000 alpha0 ! 0-lift angle of attack, depends on airfoil. +0.000000 alpha1 ! Angle of attack at f=0.7, (approximately the stall angle) for AOA>alpha0. (deg) +0.000000 alpha2 ! Angle of attack at f=0.7, (approximately the stall angle) for AOA1] +0.000000 S2 ! Constant in the f curve best-fit for AOA> alpha1; by definition it depends on the airfoil. [ignored if UAMod<>1] +0.000000 S3 ! Constant in the f curve best-fit for alpha2<=AOA< alpha0; by definition it depends on the airfoil. [ignored if UAMod<>1] +0.000000 S4 ! Constant in the f curve best-fit for AOA< alpha2; by definition it depends on the airfoil. [ignored if UAMod<>1] +0.000000 Cn1 ! Critical value of C0n at leading edge separation. It should be extracted from airfoil data at a given Mach and Reynolds number. It can be calculated from the static value of Cn at either the break in the pitching moment or the loss of chord force at the onset of stall. It is close to the condition of maximum lift of the airfoil at low Mach numbers. +0.000000 Cn2 ! As Cn1 for negative AOAs. +Default St_sh ! Strouhal's shedding frequency constant. [default = 0.19] +0.000000 Cd0 ! 2D drag coefficient value at 0-lift. +0.000000 Cm0 ! 2D pitching moment coefficient about 1/4-chord location, at 0-lift, positive if nose up. [If the aerodynamics coefficients table does not include a column for Cm, this needs to be set to 0.0] +0.000000 k0 ! Constant in the \hat(x)_cp curve best-fit; = (\hat(x)_AC-0.25). [ignored if UAMod<>1] +0.000000 k1 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k2 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k3 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k1_hat ! Constant in the expression of Cc due to leading edge vortex effects. [ignored if UAMod<>1] +Default x_cp_bar ! Constant in the expression of \hat(x)_cp^v. [ignored if UAMod<>1, default = 0.2] +Default UACutout ! Angle of attack above which unsteady aerodynamics are disabled (deg). [Specifying the string "Default" sets UACutout to 45 degrees] +Default filtCutOff ! Cut-off frequency (-3 dB corner frequency) for low-pass filtering the AoA input to UA, as well as the 1st and 2nd derivatives (Hz) [default = 20] +!........................................ +! Table of aerodynamics coefficients +200 NumAlf ! Number of data lines in the following table +! Alpha Cl Cd Cm +! (deg) (-) (-) (-) +-1.80000000000000e+02 0.00000000000000e+00 1.52890685398725e-01 0.00000000000000e+00 +-1.77000000000000e+02 1.31704479748411e-01 1.63763723652671e-01 1.19452717008645e-01 +-1.74000000000000e+02 2.64615541683425e-01 1.74744683765139e-01 2.39999774321882e-01 +-1.71000000000000e+02 3.96924138305795e-01 1.85683483417484e-01 3.60000410445527e-01 +-1.68000000000000e+02 4.83692709572010e-01 2.10410090026251e-01 3.83359490424043e-01 +-1.65000000000000e+02 5.47678400067375e-01 2.42039936419247e-01 3.58398920279377e-01 +-1.62000000000000e+02 6.11661936785840e-01 2.73684904094820e-01 3.33438064107582e-01 +-1.59000000000000e+02 6.49147890945894e-01 3.10889487497261e-01 3.13527249627107e-01 +-1.56000000000000e+02 6.33627994109589e-01 3.59203284556557e-01 3.03716295849012e-01 +-1.53000000000000e+02 6.18102771363694e-01 4.07545900233725e-01 2.93905168850931e-01 +-1.50000000000000e+02 6.02571440780362e-01 4.55925647601040e-01 2.84093898343018e-01 +-1.47000000000000e+02 5.93851743225456e-01 5.14758887292997e-01 2.87063352917468e-01 +-1.44000000000000e+02 5.85129730070885e-01 5.73263830376554e-01 2.90032783400607e-01 +-1.41000000000000e+02 5.76405140982154e-01 6.31769220410934e-01 2.93002194449487e-01 +-1.38000000000000e+02 5.62958434932229e-01 6.92274906461514e-01 2.98271914144742e-01 +-1.35000000000000e+02 5.47150816004827e-01 7.53780736462377e-01 3.04691792390807e-01 +-1.32000000000000e+02 5.31341994964165e-01 8.15287271265272e-01 3.11111734292256e-01 +-1.29000000000000e+02 5.11898674393990e-01 8.75134136992628e-01 3.17501821606841e-01 +-1.26000000000000e+02 4.85188015388141e-01 9.31661656684178e-01 3.23832218317126e-01 +-1.23000000000000e+02 4.58477182925037e-01 9.88188744534565e-01 3.30162566296010e-01 +-1.20000000000000e+02 4.31765994733252e-01 1.04471561647244e+00 3.36492889647229e-01 +-1.17000000000000e+02 3.94568156643264e-01 1.08888387091091e+00 3.40603620297433e-01 +-1.14000000000000e+02 3.57370304957649e-01 1.13305193246859e+00 3.44714328600463e-01 +-1.11000000000000e+02 3.20172552298473e-01 1.17721965661140e+00 3.48825002561235e-01 +-1.08000000000000e+02 2.77962126266291e-01 1.20912806034645e+00 3.50515840614408e-01 +-1.05000000000000e+02 2.33245372677999e-01 1.23490671052890e+00 3.50996730156169e-01 +-1.02000000000000e+02 1.88529066354869e-01 1.26068506531321e+00 3.51477592241862e-01 +-9.90000000000000e+01 1.42846269453300e-01 1.27908367222767e+00 3.50498451065250e-01 +-9.60000000000000e+01 9.52306422330625e-02 1.28272246374676e+00 3.46599247549748e-01 +-9.30000000000000e+01 4.76153787695439e-02 1.28636122746753e+00 3.42699970222382e-01 +-9.00000000000000e+01 2.97181093101284e-07 1.28999997728939e+00 3.38877476679819e-01 +-8.70000000000000e+01 -4.76153300354876e-02 1.28636123119179e+00 3.34288189245273e-01 +-8.40000000000000e+01 -9.52307753769642e-02 1.28272245357189e+00 3.29739597523247e-01 +-8.10000000000000e+01 -1.42845856965667e-01 1.27908370375002e+00 3.25207993177059e-01 +-7.80000000000000e+01 -1.88528849782130e-01 1.26068519016437e+00 3.17955441758359e-01 +-7.50000000000000e+01 -2.33245668518482e-01 1.23490653998066e+00 3.09344032062908e-01 +-7.20000000000000e+01 -2.77961909696404e-01 1.20912818519635e+00 3.00732721046221e-01 +-6.90000000000000e+01 -3.20172230052935e-01 1.17722003923687e+00 2.91121626468145e-01 +-6.60000000000000e+01 -3.57370408969930e-01 1.13305180896654e+00 2.79510882896335e-01 +-6.30000000000000e+01 -3.94568402742750e-01 1.08888357869621e+00 2.67900139324525e-01 +-6.00000000000000e+01 -4.31766171454802e-01 1.04471524249362e+00 2.56289382389432e-01 +-5.70000000000000e+01 -4.58477359643245e-01 9.88188370555741e-01 2.43119604599202e-01 +-5.40000000000000e+01 -4.85188192105633e-01 9.31661282701068e-01 2.29949776504115e-01 +-5.10000000000000e+01 -5.11898851109208e-01 8.75133763009519e-01 2.16779847798548e-01 +-4.80000000000000e+01 -5.31341959036239e-01 8.15287334218715e-01 2.03370614403917e-01 +-4.50000000000000e+01 -5.47150557766459e-01 7.53781504217852e-01 1.89841732510719e-01 +-4.20000000000000e+01 -5.62958388264277e-01 6.92274969410558e-01 1.76312695587616e-01 +-3.90000000000000e+01 -5.76405141219782e-01 6.31769168555292e-01 1.62884018923624e-01 +-3.60000000000000e+01 -5.85129736228324e-01 5.73263666791100e-01 1.49655804982024e-01 +-3.30000000000000e+01 -5.93851682613004e-01 5.14759282378343e-01 1.36427843675875e-01 +-3.00000000000000e+01 -6.02571527674987e-01 4.55925302880350e-01 1.23199622280574e-01 +-2.93939393939394e+01 -6.05709742968724e-01 4.46148292728679e-01 1.20183218217587e-01 +-2.87878787878788e+01 -6.08847690581429e-01 4.36373153786693e-01 1.17176335932680e-01 +-2.81818181818182e+01 -6.11985380005597e-01 4.26599779864539e-01 1.14168793413229e-01 +-2.75757575757576e+01 -6.15122858980615e-01 4.16827876718823e-01 1.11160516192624e-01 +-2.69696969696970e+01 -6.18260109619839e-01 4.07057465245291e-01 1.08151524224604e-01 +-2.63636363636364e+01 -6.21397122656834e-01 3.97288544820632e-01 1.05141828538283e-01 +-2.57575757575758e+01 -6.24533844014296e-01 3.87521148707597e-01 1.02131448274330e-01 +-2.51515151515151e+01 -6.27670245374249e-01 3.77755259564324e-01 9.91203848845818e-02 +-2.45454545454545e+01 -6.30806424352339e-01 3.67990641254345e-01 9.61085707127930e-02 +-2.39393939393939e+01 -6.33942376901069e-01 3.58227230091829e-01 9.30959891641372e-02 +-2.33333333333333e+01 -6.37078020453462e-01 3.48464966576383e-01 9.00826225283333e-02 +-2.27272727272727e+01 -6.40213455369502e-01 3.38703795054776e-01 8.70684539419758e-02 +-2.21212121212121e+01 -6.43348687727384e-01 3.28943663414953e-01 8.40534654418665e-02 +-2.15151515151515e+01 -6.46483666873065e-01 3.19184299164519e-01 8.10375681805418e-02 +-2.09090909090909e+01 -6.49618442068989e-01 3.09425824234104e-01 7.80207956612929e-02 +-2.03030303030303e+01 -6.52753032833882e-01 2.99668251498965e-01 7.50031458623772e-02 +-1.96969696969697e+01 -6.46281639088916e-01 2.90949411270925e-01 7.04968593518714e-02 +-1.90909090909091e+01 -6.30204218160431e-01 2.83269742867490e-01 6.45023032212650e-02 +-1.84848484848485e+01 -6.14126582290594e-01 2.75592004359402e-01 5.85074349929442e-02 +-1.78787878787879e+01 -5.98047856789765e-01 2.67915828822348e-01 5.25118142631482e-02 +-1.72727272727273e+01 -5.81967302635588e-01 2.60240916364328e-01 4.65150110129194e-02 +-1.66666666666667e+01 -5.65885606263078e-01 2.52567649498003e-01 4.05170693283586e-02 +-1.60606060606061e+01 -5.49802714208954e-01 2.44896059615267e-01 3.45176730639480e-02 +-1.54545454545455e+01 -5.33719399306242e-01 2.37226574370814e-01 2.85166866132808e-02 +-1.48484848484848e+01 -5.17634634029050e-01 2.29558765259197e-01 2.25131018007247e-02 +-1.42424242424242e+01 -5.01547801579493e-01 2.21892402675115e-01 1.65057329856289e-02 +-1.36363636363636e+01 -4.85463674091492e-01 2.14231747747893e-01 1.04934903363307e-02 +-1.30303030303030e+01 -4.69370079236432e-01 2.06565470271126e-01 4.47314506258597e-03 +-1.24242424242424e+01 -4.53283193318206e-01 1.98908867060531e-01 -1.54613211877309e-03 +-1.18181818181818e+01 -4.37187366788929e-01 1.91247369015575e-01 -7.53424241146752e-03 +-1.12121212121212e+01 -4.21093768204950e-01 1.83591167142366e-01 -1.35218680172613e-02 +-1.06060606060606e+01 -4.04998617109735e-01 1.75937905154481e-01 -1.95099338612331e-02 +-1.00000000000000e+01 -3.88896565106125e-01 1.68281357120578e-01 -2.54976171334784e-02 +-9.39393939393939e+00 -3.56980581536747e-01 1.60570608546530e-01 -2.45787021969936e-02 +-8.78787878787879e+00 -3.25052844156906e-01 1.52859809151608e-01 -2.36654666080170e-02 +-8.18181818181818e+00 -2.93123808227596e-01 1.45152920413788e-01 -2.27443554637733e-02 +-7.57575757575758e+00 -2.61189540733289e-01 1.37458302486576e-01 -2.18232254306519e-02 +-6.96969696969697e+00 -2.29253315550365e-01 1.29770338259547e-01 -2.09121948405043e-02 +-6.36363636363636e+00 -1.97299114478799e-01 1.22078681072535e-01 -1.99910067472643e-02 +-5.75757575757576e+00 -1.65337094409309e-01 1.14401642642313e-01 -1.90688307982063e-02 +-5.15151515151515e+00 -1.33363372258401e-01 1.06731125985166e-01 -1.81553134789971e-02 +-4.54545454545454e+00 -1.01365853608070e-01 9.90577635911853e-02 -1.72377886839538e-02 +-3.93939393939394e+00 -6.93567841681647e-02 9.14006376859695e-02 -1.63172897943185e-02 +-3.33333333333333e+00 -3.31807555093951e-02 8.46570826009648e-02 -1.57731499131537e-02 +-2.72727272727273e+00 2.39727377628819e-02 8.25273948895898e-02 -1.71381638240559e-02 +-2.12121212121212e+00 9.32486327068270e-02 8.31141750981614e-02 -1.96272564550678e-02 +-1.51515151515152e+00 1.62528583105757e-01 8.37008175454388e-02 -2.21076923365064e-02 +-9.09090909090912e-01 2.31797235397626e-01 8.42859193789413e-02 -2.45940451844470e-02 +-3.03030303030302e-01 3.01068246865505e-01 8.48656437169153e-02 -2.70868281606804e-02 + 3.03030303030302e-01 3.70338484450812e-01 8.54523328928443e-02 -2.95712433598367e-02 + 9.09090909090912e-01 4.39610300212106e-01 8.60391036829737e-02 -3.20559148731745e-02 + 1.51515151515152e+00 5.09192579530866e-01 8.66138848674114e-02 -3.45449324288621e-02 + 2.12121212121212e+00 5.86406064228343e-01 8.66581954835795e-02 -3.72379475609113e-02 + 2.72727272727273e+00 6.67209757832241e-01 8.64425327187755e-02 -4.00378706815080e-02 + 3.33333333333333e+00 7.48006310769884e-01 8.62268646743108e-02 -4.28376526659724e-02 + 3.93939393939394e+00 8.28814559558240e-01 8.60123335176102e-02 -4.56376672559721e-02 + 4.54545454545455e+00 9.09607713918266e-01 8.57976670724705e-02 -4.84274348252293e-02 + 5.15151515151515e+00 9.90415750809011e-01 8.55913123524140e-02 -5.12274574370195e-02 + 5.75757575757576e+00 1.06840447148798e+00 8.53816156813169e-02 -5.42125455584405e-02 + 6.36363636363637e+00 1.14160400255878e+00 8.51849910150180e-02 -5.75066351634233e-02 + 6.96969696969697e+00 1.21413721717018e+00 8.49944037839137e-02 -6.08487619763315e-02 + 7.57575757575757e+00 1.28664609286845e+00 8.48025295082906e-02 -6.41936917237977e-02 + 8.18181818181818e+00 1.35907367282053e+00 8.46074089108589e-02 -6.75395926025836e-02 + 8.78787878787879e+00 1.42498875451348e+00 8.48939582739108e-02 -7.11385484353892e-02 + 9.39393939393939e+00 1.47790044040096e+00 8.61562125019175e-02 -7.52537462367865e-02 + 1.00000000000000e+01 1.52761951021426e+00 8.76527806305783e-02 -7.94958935415669e-02 + 1.06060606060606e+01 1.21037111221097e+00 1.08368637158632e-01 -7.47780360782507e-02 + 1.12121212121212e+01 1.06745252059869e+00 1.30650270554887e-01 -4.13744293556483e-02 + 1.18181818181818e+01 1.04047682231151e+00 1.48602204458626e-01 -3.87322662567038e-02 + 1.24242424242424e+01 1.02050139325215e+00 1.65510670067403e-01 -4.07401587716326e-02 + 1.30303030303030e+01 1.00956882423978e+00 1.81609086020050e-01 -4.27814866733380e-02 + 1.36363636363636e+01 1.00743778578338e+00 1.96445539032532e-01 -4.48202992152467e-02 + 1.42424242424242e+01 1.00757475615447e+00 2.09842058498476e-01 -4.68758763258071e-02 + 1.48484848484848e+01 1.00899715128062e+00 2.22621760789065e-01 -4.89826947132140e-02 + 1.54545454545455e+01 1.01148957933609e+00 2.34179209308161e-01 -5.10542451445077e-02 + 1.60606060606061e+01 1.01288900592554e+00 2.45010338785109e-01 -5.35062027787723e-02 + 1.66666666666667e+01 1.00195252813289e+00 2.52941797110189e-01 -5.94879954798757e-02 + 1.72727272727273e+01 9.90372353173637e-01 2.60712604214289e-01 -6.56606862514200e-02 + 1.78787878787879e+01 9.78006308087524e-01 2.68286875927460e-01 -7.20666332697287e-02 + 1.84848484848485e+01 9.65644506690629e-01 2.75856403296140e-01 -7.84749075877025e-02 + 1.90909090909091e+01 9.53284332352213e-01 2.83426080329155e-01 -8.48813171286689e-02 + 1.96969696969697e+01 9.40924882807228e-01 2.91001781071828e-01 -9.12808153392477e-02 + 2.03030303030303e+01 9.32508485341658e-01 2.99668251498965e-01 -9.63197520692682e-02 + 2.09090909090909e+01 9.28035612370247e-01 3.09425824234104e-01 -9.99987465351088e-02 + 2.15151515151515e+01 9.23562474293211e-01 3.19184299164519e-01 -1.03676821203003e-01 + 2.21212121212121e+01 9.19089043051198e-01 3.28943663414953e-01 -1.07353977654978e-01 + 2.27272727272727e+01 9.14615247866511e-01 3.38703795054776e-01 -1.11030178126034e-01 + 2.33333333333333e+01 9.10141161527127e-01 3.48464966576383e-01 -1.14705513496165e-01 + 2.39393939393939e+01 9.05666775287466e-01 3.58227230091829e-01 -1.18380002566973e-01 + 2.45454545454545e+01 9.01191945397226e-01 3.67990641254345e-01 -1.22053668013310e-01 + 2.51515151515151e+01 8.96716790059191e-01 3.77755259564324e-01 -1.25726522238022e-01 + 2.57575757575758e+01 8.92241315022274e-01 3.87521148707597e-01 -1.29398582102913e-01 + 2.63636363636364e+01 8.87765380758913e-01 3.97288544820632e-01 -1.33069928789038e-01 + 2.69696969696970e+01 8.83289027675016e-01 4.07057465245291e-01 -1.36740556769150e-01 + 2.75757575757576e+01 8.78812332951360e-01 4.16827876718823e-01 -1.40410439162852e-01 + 2.81818181818182e+01 8.74335309658910e-01 4.26599779864539e-01 -1.44079560303650e-01 + 2.87878787878788e+01 8.69857983172985e-01 4.36373153786694e-01 -1.47747893479490e-01 + 2.93939393939394e+01 8.65380285398246e-01 4.46148292728679e-01 -1.51415526599333e-01 + 3.00000000000000e+01 8.60902202671727e-01 4.55925302880350e-01 -1.55082474171227e-01 + 3.30000000000000e+01 8.48397959434636e-01 5.14759282378343e-01 -1.68663399184894e-01 + 3.60000000000000e+01 8.35890707575628e-01 5.73263666791100e-01 -1.82298027595826e-01 + 3.90000000000000e+01 8.23379662232036e-01 6.31769168555292e-01 -1.95945868274559e-01 + 4.20000000000000e+01 8.04154954731604e-01 6.92274969410558e-01 -2.08554266597334e-01 + 4.50000000000000e+01 7.81573458480718e-01 7.53781504217852e-01 -2.20643060705334e-01 + 4.80000000000000e+01 7.58990915560083e-01 8.15287334218715e-01 -2.32731716287242e-01 + 5.10000000000000e+01 7.31215839592101e-01 8.75133763009519e-01 -2.44320755354886e-01 + 5.40000000000000e+01 6.93057699659601e-01 9.31661282701068e-01 -2.54910529274792e-01 + 5.70000000000000e+01 6.54899314951571e-01 9.88188370555741e-01 -2.65500222295077e-01 + 6.00000000000000e+01 6.16740425757725e-01 1.04471524249362e+00 -2.76089874865860e-01 + 6.30000000000000e+01 5.63629556606820e-01 1.08888357869621e+00 -2.84820525032635e-01 + 6.60000000000000e+01 5.10518346428343e-01 1.13305180896654e+00 -2.93551159264809e-01 + 6.90000000000000e+01 4.57406844501805e-01 1.17722003923687e+00 -3.02281793496983e-01 + 7.20000000000000e+01 3.97127599293486e-01 1.20912818519635e+00 -3.09472835540815e-01 + 7.50000000000000e+01 3.33264710335960e-01 1.23490653998066e+00 -3.15894113007981e-01 + 7.80000000000000e+01 2.69400999928860e-01 1.26068519016437e+00 -3.22315464057870e-01 + 8.10000000000000e+01 2.04142652815547e-01 1.27908370375002e+00 -3.27816939705399e-01 + 8.40000000000000e+01 1.36095393510895e-01 1.28272245357189e+00 -3.31478728044814e-01 + 8.70000000000000e+01 6.80476143629091e-02 1.28636123119179e+00 -3.35157787608892e-01 + 9.00000000000000e+01 -2.97181093302924e-07 1.28999997728939e+00 -3.38875766435868e-01 + 9.30000000000000e+01 -4.76153787695439e-02 1.28636122746753e+00 -3.42699882733940e-01 + 9.60000000000000e+01 -9.52306422330627e-02 1.28272246374676e+00 -3.46597404225314e-01 + 9.90000000000000e+01 -1.42846269453301e-01 1.27908367222767e+00 -3.50494955491782e-01 + 1.02000000000000e+02 -1.88529066354869e-01 1.26068506531321e+00 -3.51472552278717e-01 + 1.05000000000000e+02 -2.33245372677999e-01 1.23490671052890e+00 -3.50990203444848e-01 + 1.08000000000000e+02 -2.77962126266291e-01 1.20912806034645e+00 -3.50507849083669e-01 + 1.11000000000000e+02 -3.20172552298473e-01 1.17721965661140e+00 -3.48815656358806e-01 + 1.14000000000000e+02 -3.57370304957649e-01 1.13305193246859e+00 -3.44703823754748e-01 + 1.17000000000000e+02 -3.94568156643264e-01 1.08888387091091e+00 -3.40591959738759e-01 + 1.20000000000000e+02 -4.31765994733252e-01 1.04471561647244e+00 -3.36480075676600e-01 + 1.23000000000000e+02 -4.58477182925037e-01 9.88188744534564e-01 -3.30149032834181e-01 + 1.26000000000000e+02 -4.85188015388141e-01 9.31661656684178e-01 -3.23817965809434e-01 + 1.29000000000000e+02 -5.11898674393990e-01 8.75134136992627e-01 -3.17486850418223e-01 + 1.32000000000000e+02 -5.31341994964165e-01 8.15287271265271e-01 -3.11096424528303e-01 + 1.35000000000000e+02 -5.47150816004827e-01 7.53780736462377e-01 -3.04676343460043e-01 + 1.38000000000000e+02 -5.62958434932230e-01 6.92274906461514e-01 -2.98256335959350e-01 + 1.41000000000000e+02 -5.76405140982154e-01 6.31769220410933e-01 -2.92986730247466e-01 + 1.44000000000000e+02 -5.85129730070885e-01 5.73263830376554e-01 -2.90017937448097e-01 + 1.47000000000000e+02 -5.93851743225456e-01 5.14758887292997e-01 -2.87049167328765e-01 + 1.50000000000000e+02 -6.02571440780362e-01 4.55925647601039e-01 -2.84080408549046e-01 + 1.53000000000000e+02 -6.18102771363694e-01 4.07545900233725e-01 -2.93893652756478e-01 + 1.56000000000000e+02 -6.33627994109589e-01 3.59203284556557e-01 -3.03706889264038e-01 + 1.59000000000000e+02 -6.49147890945894e-01 3.10889487497261e-01 -3.13520050804901e-01 + 1.62000000000000e+02 -6.11662753189298e-01 2.73684904094820e-01 -3.53432900875577e-01 + 1.65000000000000e+02 -5.47687466921444e-01 2.42039936419247e-01 -4.08395849769896e-01 + 1.68000000000000e+02 -4.83692709572010e-01 2.10410090026251e-01 -4.63358168842291e-01 + 1.71000000000000e+02 -3.96924138305795e-01 1.85683483417484e-01 -4.50000513056908e-01 + 1.74000000000000e+02 -2.64615541683425e-01 1.74744683765139e-01 -2.99999717902353e-01 + 1.77000000000000e+02 -1.31704479748411e-01 1.63763723652671e-01 -1.49315896260807e-01 + 1.80000000000000e+02 0.00000000000000e+00 1.52890685398725e-01 0.00000000000000e+00 diff --git a/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_05.dat b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_05.dat new file mode 100644 index 00000000..28ca6bdb --- /dev/null +++ b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_05.dat @@ -0,0 +1,254 @@ +! ------------ AirfoilInfo v1.01.x Input File ---------------------------------- +! AeroElasticSE FAST driver +! line +! line +! ------------------------------------------------------------------------------ +DEFAULT InterpOrd ! Interpolation order to use for quasi-steady table lookup {1=linear; 3=cubic spline; "default"} [default=3] +1 NonDimArea ! The non-dimensional area of the airfoil (area/chord^2) (set to 1.0 if unsure or unneeded) +@"NREL-2p8-127_AF05_Coords.txt" NumCoords ! The number of coordinates in the airfoil shape file. Set to zero if coordinates not included. +AF05_BL.txt BL_file ! The file name including the boundary layer characteristics of the profile. Ignored if the aeroacoustic module is not called. +1 NumTabs ! Number of airfoil tables in this file. Each table must have lines for Re and Ctrl. +! ------------------------------------------------------------------------------ +! data for table 1 +! ------------------------------------------------------------------------------ +6.000000 Re ! Reynolds number in millions +0 Ctrl ! Control setting (must be 0 for current AirfoilInfo) +True InclUAdata ! Is unsteady aerodynamics data included in this table? If TRUE, then include 30 UA coefficients below this line +!........................................ +-2.550758 alpha0 ! 0-lift angle of attack, depends on airfoil. +11.972792 alpha1 ! Angle of attack at f=0.7, (approximately the stall angle) for AOA>alpha0. (deg) +-3.390653 alpha2 ! Angle of attack at f=0.7, (approximately the stall angle) for AOA1] +0.000000 S2 ! Constant in the f curve best-fit for AOA> alpha1; by definition it depends on the airfoil. [ignored if UAMod<>1] +0.000000 S3 ! Constant in the f curve best-fit for alpha2<=AOA< alpha0; by definition it depends on the airfoil. [ignored if UAMod<>1] +0.000000 S4 ! Constant in the f curve best-fit for AOA< alpha2; by definition it depends on the airfoil. [ignored if UAMod<>1] +1.577585 Cn1 ! Critical value of C0n at leading edge separation. It should be extracted from airfoil data at a given Mach and Reynolds number. It can be calculated from the static value of Cn at either the break in the pitching moment or the loss of chord force at the onset of stall. It is close to the condition of maximum lift of the airfoil at low Mach numbers. +-0.698181 Cn2 ! As Cn1 for negative AOAs. +Default St_sh ! Strouhal's shedding frequency constant. [default = 0.19] +0.047738 Cd0 ! 2D drag coefficient value at 0-lift. +-0.017884 Cm0 ! 2D pitching moment coefficient about 1/4-chord location, at 0-lift, positive if nose up. [If the aerodynamics coefficients table does not include a column for Cm, this needs to be set to 0.0] +0.000000 k0 ! Constant in the \hat(x)_cp curve best-fit; = (\hat(x)_AC-0.25). [ignored if UAMod<>1] +0.000000 k1 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k2 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k3 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k1_hat ! Constant in the expression of Cc due to leading edge vortex effects. [ignored if UAMod<>1] +Default x_cp_bar ! Constant in the expression of \hat(x)_cp^v. [ignored if UAMod<>1, default = 0.2] +Default UACutout ! Angle of attack above which unsteady aerodynamics are disabled (deg). [Specifying the string "Default" sets UACutout to 45 degrees] +Default filtCutOff ! Cut-off frequency (-3 dB corner frequency) for low-pass filtering the AoA input to UA, as well as the 1st and 2nd derivatives (Hz) [default = 20] +!........................................ +! Table of aerodynamics coefficients +200 NumAlf ! Number of data lines in the following table +! Alpha Cl Cd Cm +! (deg) (-) (-) (-) +-1.80000000000000e+02 0.00000000000000e+00 5.30927947138125e-02 0.00000000000000e+00 +-1.77000000000000e+02 1.43244990746609e-01 5.69851238094485e-02 1.19452717008645e-01 +-1.74000000000000e+02 2.87802289582396e-01 6.09656699428337e-02 2.39999774321882e-01 +-1.71000000000000e+02 4.31704332512692e-01 6.49763275693468e-02 3.60000410445527e-01 +-1.68000000000000e+02 5.23499707930916e-01 8.50931388592694e-02 3.82638556679456e-01 +-1.65000000000000e+02 5.83384432077198e-01 1.13322899941877e-01 3.56596594332269e-01 +-1.62000000000000e+02 6.43053795138515e-01 1.41646320077994e-01 3.30554333566108e-01 +-1.59000000000000e+02 6.78451069490567e-01 1.78095963395456e-01 3.09470086171798e-01 +-1.56000000000000e+02 6.58893043506451e-01 2.30735614552766e-01 2.98273249714432e-01 +-1.53000000000000e+02 6.39361023231318e-01 2.83555584049004e-01 2.87022407877401e-01 +-1.50000000000000e+02 6.19863301663139e-01 3.36609283159026e-01 2.75697034623494e-01 +-1.47000000000000e+02 6.09009472068249e-01 4.01283048649868e-01 2.78062585683198e-01 +-1.44000000000000e+02 5.98171151079133e-01 4.63879476339314e-01 2.80408703728939e-01 +-1.41000000000000e+02 5.87351226752077e-01 5.26476382236643e-01 2.82731729240854e-01 +-1.38000000000000e+02 5.72330730353409e-01 5.91679697265480e-01 2.87760801862453e-01 +-1.35000000000000e+02 5.55209533057542e-01 6.58186211572688e-01 2.94147772624518e-01 +-1.32000000000000e+02 5.38097371011921e-01 7.24693487985318e-01 3.00529378672850e-01 +-1.29000000000000e+02 5.17511317766740e-01 7.89812599804369e-01 3.07049734636571e-01 +-1.26000000000000e+02 4.89961725795433e-01 8.52155375838165e-01 3.13857858392341e-01 +-1.23000000000000e+02 4.62416171597766e-01 9.14497675605232e-01 3.20665726887359e-01 +-1.20000000000000e+02 4.34875524108853e-01 9.76839737247837e-01 3.27473323520141e-01 +-1.17000000000000e+02 3.97141252418688e-01 1.02744833950730e+00 3.32448774893895e-01 +-1.14000000000000e+02 3.59408610235184e-01 1.07805672550782e+00 3.37422939191108e-01 +-1.11000000000000e+02 3.21678367338784e-01 1.12866472489365e+00 3.42395452802871e-01 +-1.08000000000000e+02 2.79088060479540e-01 1.16729127063990e+00 3.45105968655180e-01 +-1.05000000000000e+02 2.34067147859934e-01 1.19992699833297e+00 3.46678811680518e-01 +-1.02000000000000e+02 1.89047548243342e-01 1.23256235205249e+00 3.48239595384036e-01 +-9.90000000000000e+01 1.43131704344168e-01 1.25788743783553e+00 3.48340383273987e-01 +-9.60000000000000e+01 9.54209316759962e-02 1.26859167109942e+00 3.45525190946857e-01 +-9.30000000000000e+01 4.77105235832516e-02 1.27929582258901e+00 3.42653176080977e-01 +-9.00000000000000e+01 2.97774918887840e-07 1.28999993319219e+00 3.41171513503408e-01 +-8.70000000000000e+01 -4.77104747518152e-02 1.27929583354468e+00 3.34817796856754e-01 +-8.40000000000000e+01 -9.54210650859458e-02 1.26859164116800e+00 3.29193185522394e-01 +-8.10000000000000e+01 -1.43131291032302e-01 1.25788753056483e+00 3.23300885206925e-01 +-7.80000000000000e+01 -1.89047330204813e-01 1.23256251011385e+00 3.14255422250019e-01 +-7.50000000000000e+01 -2.34067445710414e-01 1.19992678241918e+00 3.04545364776568e-01 +-7.20000000000000e+01 -2.79087842435176e-01 1.16729142869966e+00 2.94835418571366e-01 +-6.90000000000000e+01 -3.21678040492873e-01 1.12866516331131e+00 2.84308787573372e-01 +-6.60000000000000e+01 -3.59408715740005e-01 1.07805658399745e+00 2.72148720112555e-01 +-6.30000000000000e+01 -3.97141502062332e-01 1.02744800468359e+00 2.59988652651739e-01 +-6.00000000000000e+01 -4.34875706297759e-01 9.76839324796023e-01 2.47828577510345e-01 +-5.70000000000000e+01 -4.62416353822370e-01 9.14497263153418e-01 2.34772451636168e-01 +-5.40000000000000e+01 -4.89961908050355e-01 8.52154963381625e-01 2.21716275891253e-01 +-5.10000000000000e+01 -5.17511500044336e-01 7.89812187347829e-01 2.08660000404101e-01 +-4.80000000000000e+01 -5.38086518717761e-01 7.24693556057142e-01 1.95844288146640e-01 +-4.50000000000000e+01 -5.55175897952576e-01 6.58187041749934e-01 1.83148853637833e-01 +-4.20000000000000e+01 -5.72313983328070e-01 5.91679765332548e-01 1.70453273649745e-01 +-3.90000000000000e+01 -5.87347123075626e-01 5.26476326754529e-01 1.58085355571838e-01 +-3.60000000000000e+01 -5.98161176797901e-01 4.63879301313675e-01 1.46372520769741e-01 +-3.30000000000000e+01 -6.09008454841632e-01 4.01283471365111e-01 1.34659909662040e-01 +-3.00000000000000e+01 -6.19863411384585e-01 3.36608903265194e-01 1.22947070166372e-01 +-2.93939393939394e+01 -6.23846756639890e-01 3.25869060451884e-01 1.20313440786885e-01 +-2.87878787878788e+01 -6.27838778995726e-01 3.15141051259396e-01 1.17614452112613e-01 +-2.81818181818182e+01 -6.31839641876821e-01 3.04424204137947e-01 1.14912699050432e-01 +-2.75757575757576e+01 -6.35836270597920e-01 2.93717682812228e-01 1.12207880384010e-01 +-2.69696969696970e+01 -6.39833911454526e-01 2.83021034017517e-01 1.09499798315900e-01 +-2.63636363636364e+01 -6.43837810956875e-01 2.72333814688203e-01 1.06788280516258e-01 +-2.57575757575758e+01 -6.47833727204863e-01 2.61655649661799e-01 1.04073092351849e-01 +-2.51515151515151e+01 -6.51811878050700e-01 2.50986136645096e-01 1.01353965974111e-01 +-2.45454545454545e+01 -6.55792402610431e-01 2.40324660439802e-01 9.86307582663180e-02 +-2.39393939393939e+01 -6.59769329462643e-01 2.29670818293622e-01 9.59032541531653e-02 +-2.33333333333333e+01 -6.63693753618085e-01 2.19024233923185e-01 9.31708867916564e-02 +-2.27272727272727e+01 -6.67617282194909e-01 2.08384555374766e-01 9.04338238763716e-02 +-2.21212121212121e+01 -6.71539925846911e-01 1.97751453089189e-01 8.76919095450044e-02 +-2.15151515151515e+01 -6.75391364530441e-01 1.87124374677434e-01 8.49442500011879e-02 +-2.09090909090909e+01 -6.79225055311131e-01 1.76503213160456e-01 8.21911480032724e-02 +-2.03030303030303e+01 -6.83058586454578e-01 1.65887757170172e-01 7.94326338508051e-02 +-1.96969696969697e+01 -6.77179366626525e-01 1.57936143099498e-01 7.50259515023840e-02 +-1.90909090909091e+01 -6.61588812956316e-01 1.52651370129665e-01 6.89730817674315e-02 +-1.84848484848485e+01 -6.45998974297365e-01 1.47376694007528e-01 6.29169683694159e-02 +-1.78787878787879e+01 -6.30407947197086e-01 1.42112026219737e-01 5.68565081215708e-02 +-1.72727272727273e+01 -6.14814081267429e-01 1.36857330079429e-01 5.07903974899203e-02 +-1.66666666666667e+01 -5.99217230522637e-01 1.31613040740835e-01 4.47175106901892e-02 +-1.60606060606061e+01 -5.83616581541072e-01 1.26379356727811e-01 3.86359166779271e-02 +-1.54545454545455e+01 -5.68012174444683e-01 1.21156750685727e-01 3.25431989869031e-02 +-1.48484848484848e+01 -5.52402341156080e-01 1.15945116537827e-01 2.64350024320926e-02 +-1.42424242424242e+01 -5.36785838629193e-01 1.10744490215081e-01 2.03050549247369e-02 +-1.36363636363636e+01 -5.21164946554597e-01 1.05556831744732e-01 1.41441663106941e-02 +-1.30303030303030e+01 -5.05532268418259e-01 1.00377944456418e-01 7.93532744678689e-03 +-1.24242424242424e+01 -4.89896163495659e-01 9.52139797533199e-02 1.73252780437516e-03 +-1.18181818181818e+01 -4.74247226456870e-01 9.00595351969602e-02 -4.26939729837575e-03 +-1.12121212121212e+01 -4.58591426990099e-01 8.49188835204796e-02 -1.02684318086498e-02 +-1.06060606060606e+01 -4.42925008308680e-01 7.97910287467256e-02 -1.62647493676347e-02 +-1.00000000000000e+01 -4.27245419806289e-01 7.46743204034461e-02 -2.22564315863916e-02 +-9.39393939393939e+00 -3.94450071012984e-01 7.15761244145179e-02 -2.16020013916610e-02 +-8.78787878787879e+00 -3.61709763635419e-01 6.85053420395361e-02 -2.09365369698145e-02 +-8.18181818181818e+00 -3.29004774877055e-01 6.54609123314964e-02 -2.02303412864217e-02 +-7.57575757575758e+00 -2.96719457325792e-01 6.35194996651035e-02 -1.95537154607737e-02 +-6.96969696969697e+00 -2.64607645997063e-01 6.22646687778469e-02 -1.89056408818654e-02 +-6.36363636363636e+00 -2.32580527152297e-01 6.06079991204510e-02 -1.81689497551464e-02 +-5.75757575757576e+00 -2.00633174166183e-01 5.86072762325081e-02 -1.69119223172787e-02 +-5.15151515151515e+00 -1.68866114677660e-01 5.62255812194239e-02 -1.65526782796882e-02 +-4.54545454545454e+00 -1.37461932635248e-01 5.36929428917852e-02 -1.61977017355170e-02 +-3.93939393939394e+00 -1.06758451318221e-01 5.10791375965595e-02 -1.58364616756710e-02 +-3.33333333333333e+00 -7.62685548653199e-02 4.84672024181126e-02 -1.56131840112851e-02 +-2.72727272727273e+00 -2.30465602521035e-02 4.76318232912975e-02 -1.71370109715407e-02 +-2.12121212121212e+00 5.60835187551921e-02 4.79951799533595e-02 -1.97007210491168e-02 +-1.51515151515152e+00 1.33973262951602e-01 4.82654676882718e-02 -2.19439082938550e-02 +-9.09090909090912e-01 2.11028087723967e-01 4.85254853369285e-02 -2.42243917401695e-02 +-3.03030303030302e-01 2.87261368924859e-01 4.88198593001318e-02 -2.64441305820696e-02 + 3.03030303030302e-01 3.62683470094018e-01 4.90303436956597e-02 -2.86606885206110e-02 + 9.09090909090912e-01 4.37199562095510e-01 4.92283898912697e-02 -3.09291436006373e-02 + 1.51515151515152e+00 5.13610653178412e-01 4.93813249350217e-02 -3.31627344995039e-02 + 2.12121212121212e+00 5.93819523225117e-01 4.94346635643130e-02 -3.56399268252573e-02 + 2.72727272727273e+00 6.74386743494600e-01 4.93129308208056e-02 -3.83078247443938e-02 + 3.33333333333333e+00 7.54945044010580e-01 4.91755144944948e-02 -4.10234230183793e-02 + 3.93939393939394e+00 8.35509088091445e-01 4.91056624497743e-02 -4.37392469039279e-02 + 4.54545454545455e+00 9.16064316845785e-01 4.89398733238135e-02 -4.63880027667541e-02 + 5.15151515151515e+00 9.96625787614405e-01 4.87886086060796e-02 -4.91038344328945e-02 + 5.75757575757576e+00 1.07656301546343e+00 4.86681788543757e-02 -5.18876441202431e-02 + 6.36363636363637e+00 1.15542943443492e+00 4.84580270970572e-02 -5.47393555777829e-02 + 6.96969696969697e+00 1.23410923793262e+00 4.83167054847680e-02 -5.76374031069491e-02 + 7.57575757575757e+00 1.31245193672788e+00 4.80332030687119e-02 -6.06302767966048e-02 + 8.18181818181818e+00 1.38759943761324e+00 4.77434147182263e-02 -6.42287509236700e-02 + 8.78787878787879e+00 1.45873318731176e+00 4.76208649517908e-02 -6.80810236266958e-02 + 9.39393939393939e+00 1.52667302662998e+00 4.74125681417122e-02 -7.21235138863210e-02 + 1.00000000000000e+01 1.59364179899341e+00 4.69592426109806e-02 -7.62125968301386e-02 + 1.06060606060606e+01 1.53266180129203e+00 5.17795621500542e-02 -7.64122517246057e-02 + 1.12121212121212e+01 1.50662714460046e+00 5.81185911119093e-02 -6.22473445320763e-02 + 1.18181818181818e+01 1.52196088499542e+00 6.47040938908333e-02 -6.38501972207365e-02 + 1.24242424242424e+01 1.06125737520671e+00 7.27011070641862e-02 -5.06632430902114e-02 + 1.30303030303030e+01 9.86623647198398e-01 7.99581638241099e-02 -5.02161054006635e-02 + 1.36363636363636e+01 9.95413895615537e-01 8.64252489342137e-02 -5.25392814360008e-02 + 1.42424242424242e+01 1.00924723452713e+00 9.21833608579365e-02 -5.50345279620461e-02 + 1.48484848484848e+01 1.02661321711400e+00 9.75776888323979e-02 -5.76003393676277e-02 + 1.54545454545455e+01 1.05138532349845e+00 1.02292972150637e-01 -6.01726803278759e-02 + 1.60606060606061e+01 1.07964132412529e+00 1.07181768900225e-01 -6.30677892912717e-02 + 1.66666666666667e+01 1.06432412273203e+00 1.15493817389282e-01 -6.88775293421371e-02 + 1.72727272727273e+01 1.04867809191367e+00 1.23747525118351e-01 -7.47996579324639e-02 + 1.78787878787879e+01 1.03269240545081e+00 1.31928776633279e-01 -8.08557118437613e-02 + 1.84848484848485e+01 1.01640007994456e+00 1.40110699660449e-01 -8.69627224737571e-02 + 1.90909090909091e+01 1.00063944099394e+00 1.48295486938811e-01 -9.30638334648102e-02 + 1.96969696969697e+01 9.85938420719178e-01 1.56485775705632e-01 -9.91101057357213e-02 + 2.03030303030303e+01 9.75860062476632e-01 1.65887757170172e-01 -1.03774527782874e-01 + 2.09090909090909e+01 9.70385523569138e-01 1.76503213160456e-01 -1.07066137517572e-01 + 2.15151515151515e+01 9.64910741287637e-01 1.87124374677434e-01 -1.10360436221179e-01 + 2.21212121212121e+01 9.59410539374443e-01 1.97751453089189e-01 -1.13658562031653e-01 + 2.27272727272727e+01 9.53808409121640e-01 2.08384555374766e-01 -1.16963451063534e-01 + 2.33333333333333e+01 9.48205009566551e-01 2.19024233923185e-01 -1.20268180130586e-01 + 2.39393939393939e+01 9.42600325574261e-01 2.29670818293622e-01 -1.23572752917098e-01 + 2.45454545454545e+01 9.36920460742092e-01 2.40324660439802e-01 -1.26879595000076e-01 + 2.51515151515151e+01 9.31235454127077e-01 2.50986136645096e-01 -1.30185781900636e-01 + 2.57575757575758e+01 9.25553857527951e-01 2.61655649661799e-01 -1.33491111669471e-01 + 2.63636363636364e+01 9.19846852026574e-01 2.72333814688203e-01 -1.36796376983463e-01 + 2.69696969696970e+01 9.14128444983841e-01 2.83021034017517e-01 -1.40101150711351e-01 + 2.75757575757576e+01 9.08419019689508e-01 2.93717682812228e-01 -1.43405050790712e-01 + 2.81818181818182e+01 9.02711061316296e-01 3.04424204137947e-01 -1.46708310397499e-01 + 2.87878787878788e+01 8.96997060076054e-01 3.15141051259396e-01 -1.50011073235030e-01 + 2.93939393939394e+01 8.91295747727463e-01 3.25869060451884e-01 -1.53313276996418e-01 + 3.00000000000000e+01 8.85606890090034e-01 3.36608903265194e-01 -1.56615109400843e-01 + 3.30000000000000e+01 8.70046621612218e-01 4.01283471365112e-01 -1.68896662349608e-01 + 3.60000000000000e+01 8.54497762357662e-01 4.63879301313675e-01 -1.80807931817999e-01 + 3.90000000000000e+01 8.38996891272377e-01 5.26476326754529e-01 -1.92637317529328e-01 + 4.20000000000000e+01 8.17522301694096e-01 5.91679765332548e-01 -2.03957651916238e-01 + 4.50000000000000e+01 7.93066546402043e-01 6.58187041749934e-01 -2.15023567058536e-01 + 4.80000000000000e+01 7.68679932146205e-01 7.24693556057142e-01 -2.26089355395965e-01 + 5.10000000000000e+01 7.39303717872206e-01 7.89812187347829e-01 -2.36920708472379e-01 + 5.40000000000000e+01 6.99944452555873e-01 8.52154963381625e-01 -2.47283175955455e-01 + 5.70000000000000e+01 6.60590914392139e-01 9.14497263153418e-01 -2.57645564275396e-01 + 6.00000000000000e+01 6.21244336348351e-01 9.76839324796023e-01 -2.68007913014073e-01 + 6.30000000000000e+01 5.67342239658887e-01 1.02744800468359e+00 -2.77212112250156e-01 + 6.60000000000000e+01 5.13442407001332e-01 1.07805658399745e+00 -2.86416301559060e-01 + 6.90000000000000e+01 4.59545925192930e-01 1.12866516331131e+00 -2.95620490867964e-01 + 7.20000000000000e+01 3.98720080252567e-01 1.16729142869966e+00 -3.03676557424305e-01 + 7.50000000000000e+01 3.34428749413491e-01 1.19992678241918e+00 -3.11158586107968e-01 + 7.80000000000000e+01 2.70137761942138e-01 1.23256251011385e+00 -3.18640700529719e-01 + 8.10000000000000e+01 2.04550434150108e-01 1.25788753056483e+00 -3.25335532450249e-01 + 8.40000000000000e+01 1.36367248239496e-01 1.26859164116800e+00 -3.30455853712348e-01 + 8.70000000000000e+01 6.81835415395329e-02 1.27929583354468e+00 -3.35467708982822e-01 + 9.00000000000000e+01 -2.97774919089685e-07 1.28999993319219e+00 -3.40233119894460e-01 + 9.30000000000000e+01 -4.77105235832516e-02 1.27929582258901e+00 -3.42605172055241e-01 + 9.60000000000000e+01 -9.54209316759964e-02 1.26859167109942e+00 -3.44513777418663e-01 + 9.90000000000000e+01 -1.43131704344168e-01 1.25788743783553e+00 -3.46422397362864e-01 + 1.02000000000000e+02 -1.89047548243342e-01 1.23256235205249e+00 -3.45474218431042e-01 + 1.05000000000000e+02 -2.34067147859934e-01 1.19992699833297e+00 -3.43097670996285e-01 + 1.08000000000000e+02 -2.79088060479540e-01 1.16729127063990e+00 -3.40721096328304e-01 + 1.11000000000000e+02 -3.21678367338785e-01 1.12866472489365e+00 -3.37267285780153e-01 + 1.14000000000000e+02 -3.59408610235184e-01 1.07805672550782e+00 -3.31659036281393e-01 + 1.17000000000000e+02 -3.97141252418688e-01 1.02744833950730e+00 -3.26050743938977e-01 + 1.20000000000000e+02 -4.34875524108853e-01 9.76839737247837e-01 -3.20442427056780e-01 + 1.23000000000000e+02 -4.62416171597766e-01 9.14497675605232e-01 -3.13240052857952e-01 + 1.26000000000000e+02 -4.89961725795433e-01 8.52155375838165e-01 -3.06037651148621e-01 + 1.29000000000000e+02 -5.17511317766740e-01 7.89812599804369e-01 -2.98835194416227e-01 + 1.32000000000000e+02 -5.38097371011921e-01 7.24693487985317e-01 -2.92129065581036e-01 + 1.35000000000000e+02 -5.55209533057542e-01 6.58186211572688e-01 -2.85671100106641e-01 + 1.38000000000000e+02 -5.72330730353409e-01 5.91679697265480e-01 -2.79213208633931e-01 + 1.41000000000000e+02 -5.87351226752077e-01 5.26476382236642e-01 -2.74246677538335e-01 + 1.44000000000000e+02 -5.98171151079133e-01 4.63879476339314e-01 -2.72262879298565e-01 + 1.47000000000000e+02 -6.09009472068249e-01 4.01283048649868e-01 -2.70279096213984e-01 + 1.50000000000000e+02 -6.19863301663139e-01 3.36609283159026e-01 -2.68295320706727e-01 + 1.53000000000000e+02 -6.39361023231318e-01 2.83555584049004e-01 -2.80703642982803e-01 + 1.56000000000000e+02 -6.58893043506451e-01 2.30735614552766e-01 -2.93111951398230e-01 + 1.59000000000000e+02 -6.78451069490567e-01 1.78095963395456e-01 -3.05520165022309e-01 + 1.62000000000000e+02 -6.43501747482713e-01 1.41646320077994e-01 -3.47725013460614e-01 + 1.65000000000000e+02 -5.88359323471862e-01 1.13322899941877e-01 -4.04828431301629e-01 + 1.68000000000000e+02 -5.23499707930916e-01 8.50931388592694e-02 -4.61931194793028e-01 + 1.71000000000000e+02 -4.31704332512692e-01 6.49763275693468e-02 -4.50000513056908e-01 + 1.74000000000000e+02 -2.87802289582396e-01 6.09656699428337e-02 -2.99999717902353e-01 + 1.77000000000000e+02 -1.43244990746609e-01 5.69851238094485e-02 -1.49315896260807e-01 + 1.80000000000000e+02 0.00000000000000e+00 5.30927947138125e-02 0.00000000000000e+00 diff --git a/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_06.dat b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_06.dat new file mode 100644 index 00000000..28b7cb05 --- /dev/null +++ b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_06.dat @@ -0,0 +1,254 @@ +! ------------ AirfoilInfo v1.01.x Input File ---------------------------------- +! AeroElasticSE FAST driver +! line +! line +! ------------------------------------------------------------------------------ +DEFAULT InterpOrd ! Interpolation order to use for quasi-steady table lookup {1=linear; 3=cubic spline; "default"} [default=3] +1 NonDimArea ! The non-dimensional area of the airfoil (area/chord^2) (set to 1.0 if unsure or unneeded) +@"NREL-2p8-127_AF06_Coords.txt" NumCoords ! The number of coordinates in the airfoil shape file. Set to zero if coordinates not included. +AF06_BL.txt BL_file ! The file name including the boundary layer characteristics of the profile. Ignored if the aeroacoustic module is not called. +1 NumTabs ! Number of airfoil tables in this file. Each table must have lines for Re and Ctrl. +! ------------------------------------------------------------------------------ +! data for table 1 +! ------------------------------------------------------------------------------ +6.000000 Re ! Reynolds number in millions +0 Ctrl ! Control setting (must be 0 for current AirfoilInfo) +True InclUAdata ! Is unsteady aerodynamics data included in this table? If TRUE, then include 30 UA coefficients below this line +!........................................ +0.000000 alpha0 ! 0-lift angle of attack, depends on airfoil. +0.000000 alpha1 ! Angle of attack at f=0.7, (approximately the stall angle) for AOA>alpha0. (deg) +0.000000 alpha2 ! Angle of attack at f=0.7, (approximately the stall angle) for AOA1] +0.000000 S2 ! Constant in the f curve best-fit for AOA> alpha1; by definition it depends on the airfoil. [ignored if UAMod<>1] +0.000000 S3 ! Constant in the f curve best-fit for alpha2<=AOA< alpha0; by definition it depends on the airfoil. [ignored if UAMod<>1] +0.000000 S4 ! Constant in the f curve best-fit for AOA< alpha2; by definition it depends on the airfoil. [ignored if UAMod<>1] +0.000000 Cn1 ! Critical value of C0n at leading edge separation. It should be extracted from airfoil data at a given Mach and Reynolds number. It can be calculated from the static value of Cn at either the break in the pitching moment or the loss of chord force at the onset of stall. It is close to the condition of maximum lift of the airfoil at low Mach numbers. +0.000000 Cn2 ! As Cn1 for negative AOAs. +Default St_sh ! Strouhal's shedding frequency constant. [default = 0.19] +0.000000 Cd0 ! 2D drag coefficient value at 0-lift. +0.000000 Cm0 ! 2D pitching moment coefficient about 1/4-chord location, at 0-lift, positive if nose up. [If the aerodynamics coefficients table does not include a column for Cm, this needs to be set to 0.0] +0.000000 k0 ! Constant in the \hat(x)_cp curve best-fit; = (\hat(x)_AC-0.25). [ignored if UAMod<>1] +0.000000 k1 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k2 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k3 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k1_hat ! Constant in the expression of Cc due to leading edge vortex effects. [ignored if UAMod<>1] +Default x_cp_bar ! Constant in the expression of \hat(x)_cp^v. [ignored if UAMod<>1, default = 0.2] +Default UACutout ! Angle of attack above which unsteady aerodynamics are disabled (deg). [Specifying the string "Default" sets UACutout to 45 degrees] +Default filtCutOff ! Cut-off frequency (-3 dB corner frequency) for low-pass filtering the AoA input to UA, as well as the 1st and 2nd derivatives (Hz) [default = 20] +!........................................ +! Table of aerodynamics coefficients +200 NumAlf ! Number of data lines in the following table +! Alpha Cl Cd Cm +! (deg) (-) (-) (-) +-1.80000000000000e+02 0.00000000000000e+00 1.04451467064788e-02 0.00000000000000e+00 +-1.77000000000000e+02 1.47157007613739e-01 1.04872308588687e-02 1.19452717008645e-01 +-1.74000000000000e+02 2.95662162415483e-01 1.05303966409131e-02 2.39999774321882e-01 +-1.71000000000000e+02 4.43494166290477e-01 1.05740045222718e-02 3.60000410445527e-01 +-1.68000000000000e+02 5.36848745324298e-01 2.74506298830325e-02 3.81279166438973e-01 +-1.65000000000000e+02 6.01560063853722e-01 5.27443629674667e-02 3.53198134597150e-01 +-1.62000000000000e+02 6.66223778858103e-01 7.80396220376046e-02 3.25116780970332e-01 +-1.59000000000000e+02 7.02316612456853e-01 1.12504063201209e-01 3.01860860228524e-01 +-1.56000000000000e+02 6.79726083437648e-01 1.65305735070101e-01 2.88248798735499e-01 +-1.53000000000000e+02 6.57149315796707e-01 2.18110193131311e-01 2.74623662647778e-01 +-1.50000000000000e+02 6.34589659449874e-01 2.70917973756332e-01 2.60980583690885e-01 +-1.47000000000000e+02 6.22060969336252e-01 3.35899150571673e-01 2.62488656920504e-01 +-1.44000000000000e+02 6.09539332292595e-01 4.00853059956420e-01 2.63992059057429e-01 +-1.41000000000000e+02 5.97025743089158e-01 4.65807465559123e-01 2.65489913378387e-01 +-1.38000000000000e+02 5.80704075775906e-01 5.33717517969207e-01 2.70296859813583e-01 +-1.35000000000000e+02 5.62478076348152e-01 6.03105387787129e-01 2.76759519512185e-01 +-1.32000000000000e+02 5.44255597967036e-01 6.72494052728241e-01 2.83220945160593e-01 +-1.29000000000000e+02 5.22678505700544e-01 7.40650991852422e-01 2.90064291270315e-01 +-1.26000000000000e+02 4.94385901691070e-01 8.06344473485986e-01 2.97673949948684e-01 +-1.23000000000000e+02 4.66094993647798e-01 8.72037453255156e-01 3.05283501600632e-01 +-1.20000000000000e+02 4.37806027109449e-01 9.37730182101509e-01 3.12892965044744e-01 +-1.17000000000000e+02 3.99577421117098e-01 9.92049662822417e-01 3.19211276900007e-01 +-1.14000000000000e+02 3.61349504390741e-01 1.04636891381409e+00 3.25529257918674e-01 +-1.11000000000000e+02 3.23122662358267e-01 1.10068774984251e+00 3.31846802734848e-01 +-1.08000000000000e+02 2.80173308571465e-01 1.14318523690795e+00 3.36136841670906e-01 +-1.05000000000000e+02 2.34862463623927e-01 1.17977195947738e+00 3.39411510930403e-01 +-1.02000000000000e+02 1.89552426493172e-01 1.21635826279871e+00 3.42683246088910e-01 +-9.90000000000000e+01 1.43411370176115e-01 1.24567433198225e+00 3.44537199174708e-01 +-9.60000000000000e+01 9.56073752226676e-02 1.26044961797812e+00 3.43556506874831e-01 +-9.30000000000000e+01 4.78037454869307e-02 1.27522479109913e+00 3.42562148033031e-01 +-9.00000000000000e+01 2.98356743247137e-07 1.28999990778373e+00 3.41794286215052e-01 +-8.70000000000000e+01 -4.78036965600822e-02 1.27522480622146e+00 3.34958722226529e-01 +-8.40000000000000e+01 -9.56075088932874e-02 1.26044957666313e+00 3.28241304934322e-01 +-8.10000000000000e+01 -1.43410956056677e-01 1.24567445997852e+00 3.21434171665192e-01 +-7.80000000000000e+01 -1.89552207046124e-01 1.21635843999553e+00 3.12123499707622e-01 +-7.50000000000000e+01 -2.34862763393904e-01 1.17977171742431e+00 3.01780409905885e-01 +-7.20000000000000e+01 -2.80173089123731e-01 1.14318541410297e+00 2.91437438626359e-01 +-6.90000000000000e+01 -3.23122331202990e-01 1.10068822040718e+00 2.80383282644346e-01 +-6.60000000000000e+01 -3.61349611282076e-01 1.04636876192745e+00 2.67906699019381e-01 +-6.30000000000000e+01 -3.99577674034013e-01 9.92049303447725e-01 2.55430115394417e-01 +-6.00000000000000e+01 -4.37806214260738e-01 9.37729747481855e-01 2.42953527363207e-01 +-5.70000000000000e+01 -4.66095180812632e-01 8.72037018635503e-01 2.29962886841547e-01 +-5.40000000000000e+01 -4.94386088868899e-01 8.06344038861353e-01 2.16972196699283e-01 +-5.10000000000000e+01 -5.22678692887195e-01 7.40650557227788e-01 2.03981407315058e-01 +-4.80000000000000e+01 -5.44252972972638e-01 6.72494123749236e-01 1.91507677333331e-01 +-4.50000000000000e+01 -5.62469809216957e-01 6.03106253931314e-01 1.79292468742977e-01 +-4.20000000000000e+01 -5.80700032781224e-01 5.33717588985239e-01 1.67077120176337e-01 +-3.90000000000000e+01 -5.97024764718039e-01 4.65807407987464e-01 1.55320402968213e-01 +-3.60000000000000e+01 -6.09536960661095e-01 4.00852878339035e-01 1.44480717872626e-01 +-3.30000000000000e+01 -6.22060657674661e-01 3.35899589207050e-01 1.33641239795822e-01 +-3.00000000000000e+01 -6.34589785519217e-01 2.70917595996388e-01 1.22801551597028e-01 +-2.93939393939394e+01 -6.39157128083239e-01 2.60249253715867e-01 1.20443684761723e-01 +-2.87878787878788e+01 -6.43726970234920e-01 2.49581068160403e-01 1.18056074979326e-01 +-2.81818181818182e+01 -6.48299337915072e-01 2.38913030435958e-01 1.15668753051161e-01 +-2.75757575757576e+01 -6.52871145565939e-01 2.28244918383301e-01 1.13281631608806e-01 +-2.69696969696970e+01 -6.57443601591947e-01 2.17576846610789e-01 1.10894703470960e-01 +-2.63636363636364e+01 -6.62017925284925e-01 2.06908899722581e-01 1.08507963151374e-01 +-2.57575757575758e+01 -6.66590638057245e-01 1.96241193383532e-01 1.06121395705389e-01 +-2.51515151515151e+01 -6.71159355283587e-01 1.85573782554301e-01 1.03734968840955e-01 +-2.45454545454545e+01 -6.75728973211485e-01 1.74906478164995e-01 1.01348641226412e-01 +-2.39393939393939e+01 -6.80298045453838e-01 1.64239274881544e-01 9.89623846880801e-02 +-2.33333333333333e+01 -6.84854798199331e-01 1.53572167720432e-01 9.65760871231664e-02 +-2.27272727272727e+01 -6.89411636551734e-01 1.42905152020367e-01 9.41898138397285e-02 +-2.21212121212121e+01 -6.93968554262710e-01 1.32238223416651e-01 9.18035530549137e-02 +-2.15151515151515e+01 -6.98508709947078e-01 1.21571133361270e-01 8.94170767131999e-02 +-2.09090909090909e+01 -7.03044892648499e-01 1.10904061345980e-01 8.70305146317220e-02 +-2.03030303030303e+01 -7.07581304739425e-01 1.00237064894968e-01 8.46439121010197e-02 +-1.96969696969697e+01 -7.02434146497075e-01 9.30822479646328e-02 8.04176563008526e-02 +-1.90909090909091e+01 -6.87605029081401e-01 8.94394535867222e-02 7.43518989818734e-02 +-1.84848484848485e+01 -6.72778074386064e-01 8.57969669339951e-02 6.82864549586822e-02 +-1.78787878787879e+01 -6.57952316652420e-01 8.21546025938098e-02 6.22210099648385e-02 +-1.72727272727273e+01 -6.43126950262024e-01 7.85122065549102e-02 5.61553003431422e-02 +-1.66666666666667e+01 -6.28302519055304e-01 7.48699483442050e-02 5.00895983301152e-02 +-1.60606060606061e+01 -6.13478902955351e-01 7.12278305909537e-02 4.40238940514546e-02 +-1.54545454545455e+01 -5.98656762623450e-01 6.75860437894719e-02 3.79584834371826e-02 +-1.48484848484848e+01 -5.83835116087009e-01 6.39443715968832e-02 3.18929726477928e-02 +-1.42424242424242e+01 -5.69013374770912e-01 6.03026916613097e-02 2.58271029097552e-02 +-1.36363636363636e+01 -5.54192788419233e-01 5.66613031319075e-02 1.97612536677373e-02 +-1.30303030303030e+01 -5.39371304159858e-01 5.30198014190618e-02 1.36946491482892e-02 +-1.24242424242424e+01 -5.24551543111039e-01 4.93787366739739e-02 7.62887531626830e-03 +-1.18181818181818e+01 -5.09730889357631e-01 4.57375886003972e-02 1.56582884204670e-03 +-1.12121212121212e+01 -4.94911816881562e-01 4.20969074071858e-02 -4.49615178689840e-03 +-1.06060606060606e+01 -4.80091928606605e-01 3.84561282662129e-02 -1.05578228942103e-02 +-1.00000000000000e+01 -4.65272615271009e-01 3.48157175645994e-02 -1.66180951849822e-02 +-9.39393939393939e+00 -4.33015231009942e-01 3.42187656030196e-02 -1.65076215545108e-02 +-8.78787878787879e+00 -4.00776603293592e-01 3.36221501328585e-02 -1.63940097647302e-02 +-8.18181818181818e+00 -3.68550425214672e-01 3.30196417584014e-02 -1.62766322067477e-02 +-7.57575757575758e+00 -3.36434279469676e-01 3.26768333428082e-02 -1.61640703650675e-02 +-6.96969696969697e+00 -3.04375048369348e-01 3.24942948584592e-02 -1.60544597500587e-02 +-6.36363636363636e+00 -2.72349727408693e-01 3.22072522033381e-02 -1.59243774119394e-02 +-5.75757575757576e+00 -2.40358355463915e-01 3.18276476040425e-02 -1.56691283801087e-02 +-5.15151515151515e+00 -2.08432296047144e-01 3.13466648471733e-02 -1.56292523082999e-02 +-4.54545454545454e+00 -1.76609965524745e-01 3.08120593078346e-02 -1.55984117030112e-02 +-3.93939393939394e+00 -1.44997595632154e-01 3.02529210905892e-02 -1.55594122431336e-02 +-3.33333333333333e+00 -1.13863635347939e-01 2.96208324027153e-02 -1.55210128993654e-02 +-2.72727272727273e+00 -5.99893192871201e-02 2.93065185564550e-02 -1.71363467068633e-02 +-2.12121212121212e+00 2.27564888093693e-02 2.93538954238316e-02 -1.97749354532020e-02 +-1.51515151515152e+00 1.05200007924397e-01 2.93787983393214e-02 -2.18495371988307e-02 +-9.09090909090912e-01 1.87443112873824e-01 2.94162855389729e-02 -2.40114002927046e-02 +-3.03030303030302e-01 2.69492451080518e-01 2.95149670076408e-02 -2.60738132222027e-02 + 3.03030303030302e-01 3.51341217387514e-01 2.95252389442168e-02 -2.81360338847481e-02 + 9.09090909090912e-01 4.32977146923541e-01 2.95324300033464e-02 -3.02799067329311e-02 + 1.51515151515152e+00 5.14818629228781e-01 2.95320187044063e-02 -3.23663227732926e-02 + 2.12121212121212e+00 5.95875970346463e-01 2.96220237683965e-02 -3.47191596720360e-02 + 2.72727272727273e+00 6.76364098276864e-01 2.96076377124260e-02 -3.73109856941127e-02 + 3.33333333333333e+00 7.56846420931681e-01 2.95894663968510e-02 -3.99780779670709e-02 + 3.93939393939394e+00 8.37335412739111e-01 2.96601655289752e-02 -4.26453918217197e-02 + 4.54545454545455e+00 9.17819291031016e-01 2.96450963882609e-02 -4.52128978330237e-02 + 5.15151515151515e+00 9.98308476294268e-01 2.96479816058189e-02 -4.78802193292873e-02 + 5.75757575757576e+00 1.07878507397145e+00 2.96910810658735e-02 -5.05480539440911e-02 + 6.36363636363637e+00 1.15925721789623e+00 2.96540309894699e-02 -5.31448705442736e-02 + 6.96969696969697e+00 1.23972406223336e+00 2.97108111966689e-02 -5.57870430345416e-02 + 7.57575757575757e+00 1.31979653762893e+00 2.96607700932776e-02 -5.85770647543249e-02 + 8.18181818181818e+00 1.39574347837112e+00 2.96344899473148e-02 -6.23210696280249e-02 + 8.78787878787879e+00 1.46845278922940e+00 2.96855555923576e-02 -6.63193015468805e-02 + 9.39393939393939e+00 1.54113668312882e+00 2.96488360635837e-02 -7.03198982848751e-02 + 1.00000000000000e+01 1.61380661140144e+00 2.95365970912785e-02 -7.43207867311127e-02 + 1.06060606060606e+01 1.66835969927735e+00 2.93338363207452e-02 -7.80346111337379e-02 + 1.12121212121212e+01 1.70692741182872e+00 2.93798828283306e-02 -8.05927498314898e-02 + 1.18181818181818e+01 1.74587632218544e+00 3.01307604443737e-02 -8.45839669704818e-02 + 1.24242424242424e+01 1.09782720012007e+00 3.33105797425031e-02 -6.18259975113200e-02 + 1.30303030303030e+01 9.73402814155888e-01 3.56492113840093e-02 -5.87718757586572e-02 + 1.36363636363636e+01 9.88485823361229e-01 3.73441347002030e-02 -6.12633502425757e-02 + 1.42424242424242e+01 1.01090647828627e+00 3.86537299612605e-02 -6.40712596029900e-02 + 1.48484848484848e+01 1.04282842508625e+00 3.96717899749230e-02 -6.69529521512987e-02 + 1.54545454545455e+01 1.08269042899909e+00 4.02778502988878e-02 -7.00292393429914e-02 + 1.60606060606061e+01 1.12069441651250e+00 4.15211136336744e-02 -7.34124817337401e-02 + 1.66666666666667e+01 1.10428631804948e+00 4.97349677981258e-02 -7.89834353690655e-02 + 1.72727272727273e+01 1.08784286827117e+00 5.79481890360755e-02 -8.45666402360810e-02 + 1.78787878787879e+01 1.07137007227413e+00 6.61606214571691e-02 -9.01640784321922e-02 + 1.84848484848485e+01 1.05482456124854e+00 7.43726955221486e-02 -9.57806291561119e-02 + 1.90909090909091e+01 1.03840773749638e+00 8.25847845613570e-02 -1.01399088671180e-01 + 1.96969696969697e+01 1.02224607479530e+00 9.07973366722597e-02 -1.07003526290174e-01 + 2.03030303030303e+01 1.01092702064250e+00 1.00237064894968e-01 -1.11264195300182e-01 + 2.09090909090909e+01 1.00444584016781e+00 1.10904061345980e-01 -1.14182224296970e-01 + 2.15151515151515e+01 9.97964986040765e-01 1.21571133361270e-01 -1.17102244903151e-01 + 2.21212121212121e+01 9.91478442890709e-01 1.32238223416651e-01 -1.20024488822164e-01 + 2.27272727272727e+01 9.84967906725073e-01 1.42905152020367e-01 -1.22949596706990e-01 + 2.33333333333333e+01 9.78457485279851e-01 1.53572167720432e-01 -1.25875923784615e-01 + 2.39393939393939e+01 9.71947187592677e-01 1.64239274881544e-01 -1.28803443608322e-01 + 2.45454545454545e+01 9.65419250819274e-01 1.74906478164995e-01 -1.31732713112496e-01 + 2.51515151515151e+01 9.58890536835396e-01 1.85573782554301e-01 -1.34663003015135e-01 + 2.57575757575758e+01 9.52363117111773e-01 1.96241193383532e-01 -1.37594239679627e-01 + 2.63636363636364e+01 9.45829985373321e-01 2.06908899722581e-01 -1.40526626180439e-01 + 2.69696969696970e+01 9.39294556254110e-01 2.17576846610789e-01 -1.43460023904971e-01 + 2.75757575757576e+01 9.32761808370637e-01 2.28244918383301e-01 -1.46394293444329e-01 + 2.81818181818182e+01 9.26229995246710e-01 2.38913030435957e-01 -1.49329450107358e-01 + 2.87878787878788e+01 9.19697387107103e-01 2.49581068160403e-01 -1.52265482124334e-01 + 2.93939393939394e+01 9.13168404913080e-01 2.60249253715867e-01 -1.55202396247522e-01 + 3.00000000000000e+01 9.06643011580764e-01 2.70917595996388e-01 -1.58140217032240e-01 + 3.30000000000000e+01 8.88688675426252e-01 3.35899589207050e-01 -1.69129145388514e-01 + 3.60000000000000e+01 8.70742215903117e-01 4.00852878339035e-01 -1.79949350188385e-01 + 3.90000000000000e+01 8.52812326157355e-01 4.65807407987464e-01 -1.90730956251902e-01 + 4.20000000000000e+01 8.29505265359302e-01 5.33717588985240e-01 -2.01309118189523e-01 + 4.50000000000000e+01 8.03510457214686e-01 6.03106253931314e-01 -2.11785658405499e-01 + 4.80000000000000e+01 7.77534592624486e-01 6.72494123749237e-01 -2.22262078570281e-01 + 5.10000000000000e+01 7.46744805516537e-01 7.40650557227789e-01 -2.32656858855358e-01 + 5.40000000000000e+01 7.06322608215230e-01 8.06344038861353e-01 -2.42888354132579e-01 + 5.70000000000000e+01 6.65902819356557e-01 8.72037018635503e-01 -2.53119771247217e-01 + 6.00000000000000e+01 6.25485786688918e-01 9.37729747481856e-01 -2.63351149280861e-01 + 6.30000000000000e+01 5.70855611235508e-01 9.92049303447725e-01 -2.72828203817710e-01 + 6.60000000000000e+01 5.16226204482826e-01 1.04636876192745e+00 -2.82305251888810e-01 + 6.90000000000000e+01 4.61598036952559e-01 1.10068822040718e+00 -2.91782299959910e-01 + 7.20000000000000e+01 4.00255485500037e-01 1.14318541410298e+00 -3.00336786931006e-01 + 7.50000000000000e+01 3.35555531395701e-01 1.17977171742431e+00 -3.08430012238153e-01 + 7.80000000000000e+01 2.70855228914286e-01 1.21635843999553e+00 -3.16523330287215e-01 + 8.10000000000000e+01 2.04949941366059e-01 1.24567445997852e+00 -3.23905764836268e-01 + 8.40000000000000e+01 1.36633587012766e-01 1.26044957666313e+00 -3.29866481455659e-01 + 8.70000000000000e+01 6.83167107824974e-02 1.27522480622146e+00 -3.35775778267908e-01 + 9.00000000000000e+01 -2.98356743449189e-07 1.28999990778373e+00 -3.41568552350958e-01 + 9.30000000000000e+01 -4.78037454869307e-02 1.27522479109913e+00 -3.42550600496776e-01 + 9.60000000000000e+01 -9.56073752226678e-02 1.26044961797812e+00 -3.43313207813819e-01 + 9.90000000000000e+01 -1.43411370176115e-01 1.24567433198225e+00 -3.44075820956797e-01 + 1.02000000000000e+02 -1.89552426493172e-01 1.21635826279871e+00 -3.42018024992642e-01 + 1.05000000000000e+02 -2.34862463623927e-01 1.17977195947738e+00 -3.38550055015947e-01 + 1.08000000000000e+02 -2.80173308571465e-01 1.14318523690795e+00 -3.35082045299249e-01 + 1.11000000000000e+02 -3.23122662358267e-01 1.10068774984251e+00 -3.30613204224884e-01 + 1.14000000000000e+02 -3.61349504390742e-01 1.04636891381409e+00 -3.24142730917994e-01 + 1.17000000000000e+02 -3.99577421117098e-01 9.92049662822417e-01 -3.17672208180576e-01 + 1.20000000000000e+02 -4.37806027109449e-01 9.37730182101508e-01 -3.11201658314193e-01 + 1.23000000000000e+02 -4.66094993647798e-01 8.72037453255156e-01 -3.03497229746074e-01 + 1.26000000000000e+02 -4.94385901691070e-01 8.06344473485986e-01 -2.95792771749784e-01 + 1.29000000000000e+02 -5.22678505700545e-01 7.40650991852421e-01 -2.88088254894948e-01 + 1.32000000000000e+02 -5.44255597967036e-01 6.72494052728240e-01 -2.81200220471366e-01 + 1.35000000000000e+02 -5.62478076348152e-01 6.03105387787129e-01 -2.74720426295997e-01 + 1.38000000000000e+02 -5.80704075775906e-01 5.33717517969206e-01 -2.68240706372448e-01 + 1.41000000000000e+02 -5.97025743089158e-01 4.65807465559123e-01 -2.63448804520033e-01 + 1.44000000000000e+02 -6.09539332292595e-01 4.00853059956420e-01 -2.62032552505631e-01 + 1.47000000000000e+02 -6.22060969336252e-01 3.35899150571673e-01 -2.60616311310659e-01 + 1.50000000000000e+02 -6.34589659449874e-01 2.70917973756332e-01 -2.59200075525210e-01 + 1.53000000000000e+02 -6.57149315796707e-01 2.18110193131311e-01 -2.73103661656341e-01 + 1.56000000000000e+02 -6.79726083437648e-01 1.65305735070101e-01 -2.87007230377031e-01 + 1.59000000000000e+02 -7.02316612456853e-01 1.12504063201209e-01 -3.00910692883565e-01 + 1.62000000000000e+02 -6.66331535360941e-01 7.80396220376046e-02 -3.44436173003965e-01 + 1.65000000000000e+02 -6.02756791375368e-01 5.27443629674667e-02 -4.02772912450035e-01 + 1.68000000000000e+02 -5.36848745324298e-01 2.74506298830325e-02 -4.61108983413823e-01 + 1.71000000000000e+02 -4.43494166290477e-01 1.05740045222718e-02 -4.50000513056908e-01 + 1.74000000000000e+02 -2.95662162415483e-01 1.05303966409131e-02 -2.99999717902353e-01 + 1.77000000000000e+02 -1.47157007613739e-01 1.04872308588687e-02 -1.49315896260807e-01 + 1.80000000000000e+02 0.00000000000000e+00 1.04451467064788e-02 0.00000000000000e+00 diff --git a/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_07.dat b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_07.dat new file mode 100644 index 00000000..d854bfa0 --- /dev/null +++ b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_07.dat @@ -0,0 +1,254 @@ +! ------------ AirfoilInfo v1.01.x Input File ---------------------------------- +! AeroElasticSE FAST driver +! line +! line +! ------------------------------------------------------------------------------ +DEFAULT InterpOrd ! Interpolation order to use for quasi-steady table lookup {1=linear; 3=cubic spline; "default"} [default=3] +1 NonDimArea ! The non-dimensional area of the airfoil (area/chord^2) (set to 1.0 if unsure or unneeded) +@"NREL-2p8-127_AF07_Coords.txt" NumCoords ! The number of coordinates in the airfoil shape file. Set to zero if coordinates not included. +AF07_BL.txt BL_file ! The file name including the boundary layer characteristics of the profile. Ignored if the aeroacoustic module is not called. +1 NumTabs ! Number of airfoil tables in this file. Each table must have lines for Re and Ctrl. +! ------------------------------------------------------------------------------ +! data for table 1 +! ------------------------------------------------------------------------------ +6.000000 Re ! Reynolds number in millions +0 Ctrl ! Control setting (must be 0 for current AirfoilInfo) +True InclUAdata ! Is unsteady aerodynamics data included in this table? If TRUE, then include 30 UA coefficients below this line +!........................................ +-2.175483 alpha0 ! 0-lift angle of attack, depends on airfoil. +12.034907 alpha1 ! Angle of attack at f=0.7, (approximately the stall angle) for AOA>alpha0. (deg) +-4.017330 alpha2 ! Angle of attack at f=0.7, (approximately the stall angle) for AOA1] +0.000000 S2 ! Constant in the f curve best-fit for AOA> alpha1; by definition it depends on the airfoil. [ignored if UAMod<>1] +0.000000 S3 ! Constant in the f curve best-fit for alpha2<=AOA< alpha0; by definition it depends on the airfoil. [ignored if UAMod<>1] +0.000000 S4 ! Constant in the f curve best-fit for AOA< alpha2; by definition it depends on the airfoil. [ignored if UAMod<>1] +1.598379 Cn1 ! Critical value of C0n at leading edge separation. It should be extracted from airfoil data at a given Mach and Reynolds number. It can be calculated from the static value of Cn at either the break in the pitching moment or the loss of chord force at the onset of stall. It is close to the condition of maximum lift of the airfoil at low Mach numbers. +-0.740046 Cn2 ! As Cn1 for negative AOAs. +Default St_sh ! Strouhal's shedding frequency constant. [default = 0.19] +0.019639 Cd0 ! 2D drag coefficient value at 0-lift. +-0.026025 Cm0 ! 2D pitching moment coefficient about 1/4-chord location, at 0-lift, positive if nose up. [If the aerodynamics coefficients table does not include a column for Cm, this needs to be set to 0.0] +0.000000 k0 ! Constant in the \hat(x)_cp curve best-fit; = (\hat(x)_AC-0.25). [ignored if UAMod<>1] +0.000000 k1 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k2 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k3 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k1_hat ! Constant in the expression of Cc due to leading edge vortex effects. [ignored if UAMod<>1] +Default x_cp_bar ! Constant in the expression of \hat(x)_cp^v. [ignored if UAMod<>1, default = 0.2] +Default UACutout ! Angle of attack above which unsteady aerodynamics are disabled (deg). [Specifying the string "Default" sets UACutout to 45 degrees] +Default filtCutOff ! Cut-off frequency (-3 dB corner frequency) for low-pass filtering the AoA input to UA, as well as the 1st and 2nd derivatives (Hz) [default = 20] +!........................................ +! Table of aerodynamics coefficients +200 NumAlf ! Number of data lines in the following table +! Alpha Cl Cd Cm +! (deg) (-) (-) (-) +-1.80000000000000e+02 0.00000000000000e+00 2.33914127688100e-02 0.00000000000000e+00 +-1.77000000000000e+02 1.43031527763221e-01 2.33914127688100e-02 1.19163615697548e-01 +-1.74000000000000e+02 2.87990892106934e-01 2.66846196171584e-02 2.39999774321882e-01 +-1.71000000000000e+02 4.31987088278764e-01 3.65643482753360e-02 3.60000410445527e-01 +-1.68000000000000e+02 5.31545849874829e-01 5.84098652013656e-02 3.64532897060852e-01 +-1.65000000000000e+02 6.11268538666348e-01 8.62381366029380e-02 3.11332656605488e-01 +-1.62000000000000e+02 6.94600133989169e-01 1.14066726893083e-01 2.58131725599959e-01 +-1.59000000000000e+02 7.40824462046985e-01 1.50632267952715e-01 2.21242462675373e-01 +-1.56000000000000e+02 7.16139659509821e-01 2.04671414989218e-01 2.16831447428975e-01 +-1.53000000000000e+02 6.91423868529968e-01 2.58710851852227e-01 2.12177598920349e-01 +-1.50000000000000e+02 6.66670110194854e-01 3.12750462408367e-01 2.07242736249593e-01 +-1.47000000000000e+02 6.52900940317335e-01 3.79139090101126e-01 2.11698220689362e-01 +-1.44000000000000e+02 6.39116027015019e-01 4.45527909875772e-01 2.16157774411608e-01 +-1.41000000000000e+02 6.25312980734950e-01 5.11917113827909e-01 2.20622202461720e-01 +-1.38000000000000e+02 6.07728072005134e-01 5.81216719268110e-01 2.27857968655088e-01 +-1.35000000000000e+02 5.88252908821619e-01 6.51971519548278e-01 2.36476173369762e-01 +-1.32000000000000e+02 5.68769160282536e-01 7.22726946114877e-01 2.45092460374068e-01 +-1.29000000000000e+02 5.45846532434262e-01 7.92131150298341e-01 2.54083304617287e-01 +-1.26000000000000e+02 5.16059865398949e-01 8.58832903295187e-01 2.63823977750305e-01 +-1.23000000000000e+02 4.86270063393777e-01 9.25534146724964e-01 2.73560128804467e-01 +-1.20000000000000e+02 4.56476301826173e-01 9.92235135380730e-01 2.83291214803044e-01 +-1.17000000000000e+02 4.16489600596796e-01 1.04694876887339e+00 2.91917422175410e-01 +-1.14000000000000e+02 3.76501801901982e-01 1.10166216993032e+00 3.00538465312235e-01 +-1.11000000000000e+02 3.36512597958186e-01 1.15637515301294e+00 3.09153340377474e-01 +-1.08000000000000e+02 2.91693025082505e-01 1.19874087754264e+00 3.15840388222425e-01 +-1.05000000000000e+02 2.44458666678294e-01 1.23493287877690e+00 3.21561919471006e-01 +-1.02000000000000e+02 1.97224219276773e-01 1.27112446528618e+00 3.27278150969725e-01 +-9.90000000000000e+01 1.49160540417765e-01 1.29974121708087e+00 3.31577776566796e-01 +-9.60000000000000e+01 9.94402497296759e-02 1.31320797134044e+00 3.33053601420033e-01 +-9.30000000000000e+01 4.97202158283082e-02 1.32667462272159e+00 3.34536430978363e-01 +-9.00000000000000e+01 3.10317978578370e-07 1.34014122266447e+00 3.35516468539213e-01 +-8.70000000000000e+01 -4.97201649399637e-02 1.32667463650466e+00 3.30914309585675e-01 +-8.40000000000000e+01 -9.94403887586856e-02 1.31320793368439e+00 3.25875044063013e-01 +-8.10000000000000e+01 -1.49160109697721e-01 1.29974133374151e+00 3.20684674998472e-01 +-7.80000000000000e+01 -1.97223990505980e-01 1.27112464057129e+00 3.14068969100332e-01 +-7.50000000000000e+01 -2.44458979176423e-01 1.23493263933526e+00 3.06188477394521e-01 +-7.20000000000000e+01 -2.91692796320390e-01 1.19874105282597e+00 2.98307891491871e-01 +-6.90000000000000e+01 -3.36512251521935e-01 1.15637562699211e+00 2.89561021929827e-01 +-6.60000000000000e+01 -3.76501913717355e-01 1.10166201694156e+00 2.79081514110173e-01 +-6.30000000000000e+01 -4.16489865150498e-01 1.04694840689101e+00 2.68601883289040e-01 +-6.00000000000000e+01 -4.56476498955521e-01 9.92234694090483e-01 2.58122183245595e-01 +-5.70000000000000e+01 -4.86270260493495e-01 9.25533705434717e-01 2.46741658278199e-01 +-5.40000000000000e+01 -5.16060062475956e-01 8.58832461999884e-01 2.35361028339939e-01 +-5.10000000000000e+01 -5.45846729491953e-01 7.92130709003037e-01 2.23980188458352e-01 +-4.80000000000000e+01 -5.69289853059557e-01 7.22744238735752e-01 2.13008982600553e-01 +-4.50000000000000e+01 -5.89557703094231e-01 6.52015452980456e-01 2.02242587171249e-01 +-4.20000000000000e+01 -6.08251798068365e-01 5.81234011749336e-01 1.91868319013648e-01 +-3.90000000000000e+01 -6.25416926876934e-01 5.11597466281429e-01 1.81968105360702e-01 +-3.60000000000000e+01 -6.39316913259601e-01 4.44496914459934e-01 1.73264272171102e-01 +-3.30000000000000e+01 -6.52916432542900e-01 3.78198211323207e-01 1.65338571395536e-01 +-3.00000000000000e+01 -6.66670235178609e-01 3.12750067745499e-01 1.58271579799568e-01 +-2.93939393939394e+01 -6.71047367933391e-01 3.01438712775986e-01 1.57020885663939e-01 +-2.87878787878788e+01 -6.75419095195018e-01 2.90127357806473e-01 1.55835649782268e-01 +-2.81818181818182e+01 -6.79785363067838e-01 2.78816002836960e-01 1.54649678410992e-01 +-2.75757575757576e+01 -6.84281237628547e-01 2.67629852848922e-01 1.53624988893004e-01 +-2.69696969696970e+01 -6.88830733728478e-01 2.56497366741980e-01 1.52669124180276e-01 +-2.63636363636364e+01 -6.93376184149147e-01 2.45364880635039e-01 1.51712730581928e-01 +-2.57575757575758e+01 -6.98037897852729e-01 2.34311621831173e-01 1.50875935757439e-01 +-2.51515151515151e+01 -7.02877385944567e-01 2.23377185516994e-01 1.50218827286969e-01 +-2.45454545454545e+01 -7.07714903614937e-01 2.12442749202814e-01 1.49561371313348e-01 +-2.39393939393939e+01 -7.12595164217054e-01 2.01529837369162e-01 1.48943431555047e-01 +-2.33333333333333e+01 -7.17876308107891e-01 1.90810650027497e-01 1.48683703309005e-01 +-2.27272727272727e+01 -7.23157231061198e-01 1.80091462685832e-01 1.48423779056222e-01 +-2.21212121212121e+01 -7.28437947560357e-01 1.69372275344166e-01 1.48163680826540e-01 +-2.15151515151515e+01 -7.31713351978921e-01 1.58838231776999e-01 1.48337985994225e-01 +-2.09090909090909e+01 -7.34245840474427e-01 1.48350486062725e-01 1.48620871862006e-01 +-2.03030303030303e+01 -7.38065551990425e-01 1.37862740348452e-01 1.48903686939429e-01 +-1.96969696969697e+01 -7.32808819200495e-01 1.29918930302428e-01 1.44712603991306e-01 +-1.90909090909091e+01 -7.18361958000880e-01 1.24518912013222e-01 1.36047824693694e-01 +-1.84848484848485e+01 -7.04189587691779e-01 1.19119156714805e-01 1.27383320623159e-01 +-1.78787878787879e+01 -6.90170520790039e-01 1.13719385941933e-01 1.18718587275407e-01 +-1.72727272727273e+01 -6.76245095637824e-01 1.08319367652727e-01 1.10053115983160e-01 +-1.66666666666667e+01 -6.62381424994436e-01 1.02255720988610e-01 1.01387526517949e-01 +-1.60606060606061e+01 -6.48560316531438e-01 9.61448175238969e-02 9.27217646524863e-02 +-1.54545454545455e+01 -6.34969522120538e-01 9.03872009230254e-02 8.40561496211227e-02 +-1.48484848484848e+01 -6.21508539218862e-01 8.48230957038706e-02 7.53901059090511e-02 +-1.42424242424242e+01 -6.08408366025162e-01 7.96630711027307e-02 6.67232674713552e-02 +-1.36363636363636e+01 -5.95447218953895e-01 7.45632229779760e-02 5.80562179472338e-02 +-1.30303030303030e+01 -5.82646323386179e-01 6.95101444417735e-02 4.93879760859292e-02 +-1.24242424242424e+01 -5.70051253619176e-01 6.44104289730139e-02 4.07195611654372e-02 +-1.18181818181818e+01 -5.57661981483822e-01 5.92219660335435e-02 3.20496569255294e-02 +-1.12121212121212e+01 -5.45521148334811e-01 5.38126013913541e-02 2.33792067297271e-02 +-1.06060606060606e+01 -5.33770601268997e-01 4.82803386350898e-02 1.47062382307926e-02 +-1.00000000000000e+01 -5.22536282520595e-01 4.27091715581483e-02 6.03175191196416e-03 +-9.39393939393939e+00 -4.98663010113629e-01 3.97762979408636e-02 1.46216346791845e-03 +-8.78787878787879e+00 -4.74896579071385e-01 3.69498939396144e-02 -3.11443204072278e-03 +-8.18181818181818e+00 -4.50184735644143e-01 3.36609587046423e-02 -7.71668568938825e-03 +-7.57575757575758e+00 -4.16320862490726e-01 3.11984229016655e-02 -1.02342715344042e-02 +-6.96969696969697e+00 -3.78533908672691e-01 2.88846280067247e-02 -1.18586821223915e-02 +-6.36363636363636e+00 -3.41308425879108e-01 2.66987274834274e-02 -1.37039177713602e-02 +-5.75757575757576e+00 -3.03292128777548e-01 2.47793566352644e-02 -1.57278639083592e-02 +-5.15151515151515e+00 -2.63917787982752e-01 2.33543465327187e-02 -1.65422055989149e-02 +-4.54545454545454e+00 -2.22824817551322e-01 2.20950859887883e-02 -1.76054229676369e-02 +-3.93939393939394e+00 -1.80668798888092e-01 2.09756580073103e-02 -1.88443435684976e-02 +-3.33333333333333e+00 -1.34176568044395e-01 2.04804489661257e-02 -2.02207166542285e-02 +-2.72727272727273e+00 -7.19453798936780e-02 2.00079017312406e-02 -2.28911294526880e-02 +-2.12121212121212e+00 7.07606911784324e-03 1.96027557312253e-02 -2.63328024672574e-02 +-1.51515151515152e+00 8.73289871843104e-02 1.94248148430849e-02 -2.91753660865235e-02 +-9.09090909090912e-01 1.68214610603894e-01 1.93209749444206e-02 -3.21126237712362e-02 +-3.03030303030302e-01 2.49847575674565e-01 1.93085263731067e-02 -3.50069460021776e-02 + 3.03030303030302e-01 3.32076661864978e-01 1.92708245709109e-02 -3.78355127682451e-02 + 9.09090909090912e-01 4.14967913083368e-01 1.92564396323649e-02 -4.06506905185218e-02 + 1.51515151515152e+00 4.97503403994561e-01 1.93240509371219e-02 -4.34545183162005e-02 + 2.12121212121212e+00 5.78017026165593e-01 1.94699699516029e-02 -4.63887820732702e-02 + 2.72727272727273e+00 6.57982538458257e-01 1.95636992876711e-02 -4.91776418225647e-02 + 3.33333333333333e+00 7.37634840577441e-01 1.96859030314327e-02 -5.19181781483109e-02 + 3.93939393939394e+00 8.17042150325575e-01 1.99153209631174e-02 -5.45755311911616e-02 + 4.54545454545455e+00 8.95773550489732e-01 2.01574613792028e-02 -5.71758300930519e-02 + 5.15151515151515e+00 9.74202606524190e-01 2.04147221937826e-02 -5.98020954890244e-02 + 5.75757575757576e+00 1.05192610299832e+00 2.06935862917398e-02 -6.22831373010045e-02 + 6.36363636363637e+00 1.12864853703975e+00 2.09894711710230e-02 -6.45992855497388e-02 + 6.96969696969697e+00 1.20469677736454e+00 2.13767147820252e-02 -6.68719079346452e-02 + 7.57575757575757e+00 1.27852391355893e+00 2.18254003510820e-02 -6.92881289021872e-02 + 8.18181818181818e+00 1.34843619913274e+00 2.23379405478464e-02 -7.23998694538348e-02 + 8.78787878787879e+00 1.41389258501910e+00 2.29917029483263e-02 -7.57224146801624e-02 + 9.39393939393939e+00 1.47693105199554e+00 2.42669452043504e-02 -7.90940633281295e-02 + 1.00000000000000e+01 1.53866152751405e+00 2.58158538548453e-02 -8.24968128995006e-02 + 1.06060606060606e+01 1.58175634209111e+00 2.78715872133015e-02 -8.63366627353863e-02 + 1.12121212121212e+01 1.60853428444793e+00 2.99227788852005e-02 -9.25178530036142e-02 + 1.18181818181818e+01 1.62618116680780e+00 3.25599114107023e-02 -9.61254605123986e-02 + 1.24242424242424e+01 1.17081115183266e+00 3.76946916781032e-02 -7.96133950050748e-02 + 1.30303030303030e+01 1.07057266006274e+00 4.25731273306023e-02 -7.63714447703372e-02 + 1.36363636363636e+01 1.07323785139661e+00 4.76558461605604e-02 -7.83786809582152e-02 + 1.42424242424242e+01 1.08209790208772e+00 5.26403136632421e-02 -8.07401047567165e-02 + 1.48484848484848e+01 1.10354986974947e+00 5.77455347083801e-02 -8.32982121847380e-02 + 1.54545454545455e+01 1.13090095347719e+00 6.28922160620656e-02 -8.70718045668990e-02 + 1.60606060606061e+01 1.15290331847775e+00 6.85681445746570e-02 -9.13408073485258e-02 + 1.66666666666667e+01 1.13888783926795e+00 7.88844991137046e-02 -9.76066740175176e-02 + 1.72727272727273e+01 1.12569869109310e+00 8.91882738787458e-02 -1.03672038183508e-01 + 1.78787878787879e+01 1.11348996181680e+00 9.94766732049302e-02 -1.09493916588364e-01 + 1.84848484848485e+01 1.10412272552069e+00 1.09722110128521e-01 -1.14392819645911e-01 + 1.90909090909091e+01 1.09417618957362e+00 1.19712328172831e-01 -1.19171119055800e-01 + 1.96969696969697e+01 1.07815671838533e+00 1.28316705476137e-01 -1.24569996191147e-01 + 2.03030303030303e+01 1.06590918336347e+00 1.37862740348452e-01 -1.28927442015208e-01 + 2.09090909090909e+01 1.05744457824252e+00 1.48350486062725e-01 -1.32240940695518e-01 + 2.15151515151515e+01 1.04897922606013e+00 1.58838231776999e-01 -1.35550005581577e-01 + 2.21212121212121e+01 1.04069744082963e+00 1.69372275344167e-01 -1.38809930873424e-01 + 2.27272727272727e+01 1.03315254333471e+00 1.80091462685832e-01 -1.41886753748031e-01 + 2.33333333333333e+01 1.02560734768900e+00 1.90810650027497e-01 -1.44960808190677e-01 + 2.39393939393939e+01 1.01806183295191e+00 2.01529837369162e-01 -1.48032154260591e-01 + 2.45454545454545e+01 1.01108909354267e+00 2.12442749202814e-01 -1.50974394253646e-01 + 2.51515151515151e+01 1.00417741009351e+00 2.23377185516994e-01 -1.53900389859026e-01 + 2.57575757575758e+01 9.97262895226883e-01 2.34311621831173e-01 -1.56824213640932e-01 + 2.63636363636364e+01 9.90602272243490e-01 2.45364880635039e-01 -1.59691865247193e-01 + 2.69696969696970e+01 9.84107677556836e-01 2.56497366741980e-01 -1.62521495117230e-01 + 2.75757575757576e+01 9.77607274768511e-01 2.67629852848922e-01 -1.65349122555614e-01 + 2.81818181818182e+01 9.71183535418784e-01 2.78816002836960e-01 -1.68157082819057e-01 + 2.87878787878788e+01 9.64945123677017e-01 2.90127357806473e-01 -1.70921894375263e-01 + 2.93939393939394e+01 9.58698873686608e-01 3.01438712775986e-01 -1.73684689615452e-01 + 3.00000000000000e+01 9.52444862477794e-01 3.12750067745499e-01 -1.76445418513927e-01 + 3.30000000000000e+01 9.32757112804349e-01 3.78198211323207e-01 -1.87615870546037e-01 + 3.60000000000000e+01 9.13290569721045e-01 4.44496914459934e-01 -1.99008415557536e-01 + 3.90000000000000e+01 8.93393781094339e-01 5.11597466281430e-01 -2.09904410150492e-01 + 4.20000000000000e+01 8.68886648478033e-01 5.81234011749336e-01 -2.20659088173443e-01 + 4.50000000000000e+01 8.42222962046853e-01 6.52015452980456e-01 -2.31358509305899e-01 + 4.80000000000000e+01 8.13311107256429e-01 7.22744238735752e-01 -2.42008926938194e-01 + 5.10000000000000e+01 7.79848244960539e-01 7.92130709003037e-01 -2.52553412425687e-01 + 5.40000000000000e+01 7.37292615749320e-01 8.58832461999884e-01 -2.62871600790229e-01 + 5.70000000000000e+01 6.94732715144264e-01 9.25533705434717e-01 -2.73198801942233e-01 + 6.00000000000000e+01 6.52167283863280e-01 9.92234694090484e-01 -2.83534193702832e-01 + 6.30000000000000e+01 5.95021513422317e-01 1.04694840689101e+00 -2.92939646889504e-01 + 6.60000000000000e+01 5.37873671092777e-01 1.10166201694156e+00 -3.02353620386315e-01 + 6.90000000000000e+01 4.80723120327637e-01 1.15637562699211e+00 -3.11775458141060e-01 + 7.20000000000000e+01 4.16702853573743e-01 1.19874105282597e+00 -3.20152624301910e-01 + 7.50000000000000e+01 3.49248630212311e-01 1.23493263933526e+00 -3.28012827849872e-01 + 7.80000000000000e+01 2.81792775389929e-01 1.27112464057129e+00 -3.35882005640500e-01 + 8.10000000000000e+01 2.13139309353073e-01 1.29974133374152e+00 -3.42992209540911e-01 + 8.40000000000000e+01 1.42093279928522e-01 1.31320793368439e+00 -3.48577487448998e-01 + 8.70000000000000e+01 7.10465847027829e-02 1.32667463650466e+00 -3.54286237278487e-01 + 9.00000000000000e+01 -3.10317978790605e-07 1.34014122266447e+00 -3.60261329275921e-01 + 9.30000000000000e+01 -4.97202158283082e-02 1.32667462272159e+00 -3.60939509181810e-01 + 9.60000000000000e+01 -9.94402497296761e-02 1.31320797134044e+00 -3.62101276854683e-01 + 9.90000000000000e+01 -1.49160540417765e-01 1.29974121708087e+00 -3.63263116762426e-01 + 1.02000000000000e+02 -1.97224219276773e-01 1.27112446528618e+00 -3.61500175595017e-01 + 1.05000000000000e+02 -2.44458666678294e-01 1.23493287877690e+00 -3.58275028210518e-01 + 1.08000000000000e+02 -2.91693025082505e-01 1.19874087754264e+00 -3.55049870683841e-01 + 1.11000000000000e+02 -3.36512597958186e-01 1.15637515301294e+00 -3.50765979419127e-01 + 1.14000000000000e+02 -3.76501801901982e-01 1.10166216993032e+00 -3.44364638786946e-01 + 1.17000000000000e+02 -4.16489600596796e-01 1.04694876887339e+00 -3.37963575060275e-01 + 1.20000000000000e+02 -4.56476301826173e-01 9.92235135380730e-01 -3.31562852852576e-01 + 1.23000000000000e+02 -4.86270063393777e-01 9.25534146724963e-01 -3.23780752167797e-01 + 1.26000000000000e+02 -5.16059865398949e-01 8.58832903295187e-01 -3.15999386352538e-01 + 1.29000000000000e+02 -5.45846532434262e-01 7.92131150298340e-01 -3.08218654603481e-01 + 1.32000000000000e+02 -5.68769160282536e-01 7.22726946114877e-01 -3.01185530669448e-01 + 1.35000000000000e+02 -5.88252908821619e-01 6.51971519548278e-01 -2.94527284921154e-01 + 1.38000000000000e+02 -6.07728072005134e-01 5.81216719268109e-01 -2.87870702883092e-01 + 1.41000000000000e+02 -6.25312980734950e-01 5.11917113827908e-01 -2.82904694585223e-01 + 1.44000000000000e+02 -6.39116027015019e-01 4.45527909875772e-01 -2.81319615496767e-01 + 1.47000000000000e+02 -6.52900940317335e-01 3.79139090101126e-01 -2.79738043324018e-01 + 1.50000000000000e+02 -6.66670110194854e-01 3.12750462408366e-01 -2.78159839410523e-01 + 1.53000000000000e+02 -6.91423868529968e-01 2.58710851852227e-01 -2.92436611808699e-01 + 1.56000000000000e+02 -7.16139659509821e-01 2.04671414989218e-01 -3.06713727094434e-01 + 1.59000000000000e+02 -7.40824462046985e-01 1.50632267952715e-01 -3.20991093106481e-01 + 1.62000000000000e+02 -6.92523326346939e-01 1.14218878924218e-01 -3.60600316892406e-01 + 1.65000000000000e+02 -6.04090178045220e-01 8.66185179666223e-02 -4.12875574153840e-01 + 1.68000000000000e+02 -5.25703495579730e-01 5.90182887830723e-02 -4.65150066961505e-01 + 1.71000000000000e+02 -4.24060615670435e-01 3.72487259247374e-02 -4.50000513056908e-01 + 1.74000000000000e+02 -2.82706583196469e-01 2.71407679330614e-02 -2.99999717902353e-01 + 1.77000000000000e+02 -1.40374735896749e-01 2.36166297084173e-02 -1.48954519621935e-01 + 1.80000000000000e+02 0.00000000000000e+00 2.33914127688100e-02 0.00000000000000e+00 diff --git a/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_08.dat b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_08.dat new file mode 100644 index 00000000..d72fa625 --- /dev/null +++ b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_08.dat @@ -0,0 +1,254 @@ +! ------------ AirfoilInfo v1.01.x Input File ---------------------------------- +! AeroElasticSE FAST driver +! line +! line +! ------------------------------------------------------------------------------ +DEFAULT InterpOrd ! Interpolation order to use for quasi-steady table lookup {1=linear; 3=cubic spline; "default"} [default=3] +1 NonDimArea ! The non-dimensional area of the airfoil (area/chord^2) (set to 1.0 if unsure or unneeded) +@"NREL-2p8-127_AF08_Coords.txt" NumCoords ! The number of coordinates in the airfoil shape file. Set to zero if coordinates not included. +AF08_BL.txt BL_file ! The file name including the boundary layer characteristics of the profile. Ignored if the aeroacoustic module is not called. +1 NumTabs ! Number of airfoil tables in this file. Each table must have lines for Re and Ctrl. +! ------------------------------------------------------------------------------ +! data for table 1 +! ------------------------------------------------------------------------------ +6.000000 Re ! Reynolds number in millions +0 Ctrl ! Control setting (must be 0 for current AirfoilInfo) +True InclUAdata ! Is unsteady aerodynamics data included in this table? If TRUE, then include 30 UA coefficients below this line +!........................................ +-2.094045 alpha0 ! 0-lift angle of attack, depends on airfoil. +11.810318 alpha1 ! Angle of attack at f=0.7, (approximately the stall angle) for AOA>alpha0. (deg) +-5.789318 alpha2 ! Angle of attack at f=0.7, (approximately the stall angle) for AOA1] +0.000000 S2 ! Constant in the f curve best-fit for AOA> alpha1; by definition it depends on the airfoil. [ignored if UAMod<>1] +0.000000 S3 ! Constant in the f curve best-fit for alpha2<=AOA< alpha0; by definition it depends on the airfoil. [ignored if UAMod<>1] +0.000000 S4 ! Constant in the f curve best-fit for AOA< alpha2; by definition it depends on the airfoil. [ignored if UAMod<>1] +1.434702 Cn1 ! Critical value of C0n at leading edge separation. It should be extracted from airfoil data at a given Mach and Reynolds number. It can be calculated from the static value of Cn at either the break in the pitching moment or the loss of chord force at the onset of stall. It is close to the condition of maximum lift of the airfoil at low Mach numbers. +-0.791051 Cn2 ! As Cn1 for negative AOAs. +Default St_sh ! Strouhal's shedding frequency constant. [default = 0.19] +0.013400 Cd0 ! 2D drag coefficient value at 0-lift. +-0.038790 Cm0 ! 2D pitching moment coefficient about 1/4-chord location, at 0-lift, positive if nose up. [If the aerodynamics coefficients table does not include a column for Cm, this needs to be set to 0.0] +0.000000 k0 ! Constant in the \hat(x)_cp curve best-fit; = (\hat(x)_AC-0.25). [ignored if UAMod<>1] +0.000000 k1 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k2 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k3 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k1_hat ! Constant in the expression of Cc due to leading edge vortex effects. [ignored if UAMod<>1] +Default x_cp_bar ! Constant in the expression of \hat(x)_cp^v. [ignored if UAMod<>1, default = 0.2] +Default UACutout ! Angle of attack above which unsteady aerodynamics are disabled (deg). [Specifying the string "Default" sets UACutout to 45 degrees] +Default filtCutOff ! Cut-off frequency (-3 dB corner frequency) for low-pass filtering the AoA input to UA, as well as the 1st and 2nd derivatives (Hz) [default = 20] +!........................................ +! Table of aerodynamics coefficients +200 NumAlf ! Number of data lines in the following table +! Alpha Cl Cd Cm +! (deg) (-) (-) (-) +-1.80000000000000e+02 0.00000000000000e+00 4.36560269351644e-02 0.00000000000000e+00 +-1.77000000000000e+02 1.35439946882412e-01 4.36560269351644e-02 1.18726131869253e-01 +-1.74000000000000e+02 2.73681807554892e-01 5.19326935053434e-02 2.39999774321882e-01 +-1.71000000000000e+02 4.10523187830625e-01 7.67629649316860e-02 3.60000410445527e-01 +-1.68000000000000e+02 5.20540196449849e-01 1.06183060966195e-01 3.39345685302513e-01 +-1.65000000000000e+02 6.17416589309490e-01 1.37898015734769e-01 2.48364921181521e-01 +-1.62000000000000e+02 7.20366694799217e-01 1.69613333930037e-01 1.57382975358883e-01 +-1.59000000000000e+02 7.79902956443025e-01 2.09395231609251e-01 1.00198616429354e-01 +-1.56000000000000e+02 7.54094985201384e-01 2.65310015371530e-01 1.10341134086108e-01 +-1.53000000000000e+02 7.28273002358664e-01 3.21224917158275e-01 1.20030838658758e-01 +-1.50000000000000e+02 7.02433949228043e-01 3.77139907333099e-01 1.29188534097997e-01 +-1.47000000000000e+02 6.88056994571163e-01 4.45660752601736e-01 1.38937062638940e-01 +-1.44000000000000e+02 6.73672820323352e-01 5.14181705032495e-01 1.48679864311782e-01 +-1.41000000000000e+02 6.59280196399078e-01 5.82702871795152e-01 1.58415928945197e-01 +-1.38000000000000e+02 6.40870225785841e-01 6.54060157601795e-01 1.69647719764598e-01 +-1.35000000000000e+02 6.20451890084054e-01 7.26835497177056e-01 1.81625021280610e-01 +-1.32000000000000e+02 6.00029188829974e-01 7.99611206996042e-01 1.93595285306556e-01 +-1.29000000000000e+02 5.75956737945601e-01 8.70852261041323e-01 2.05770654480656e-01 +-1.26000000000000e+02 5.44590931294051e-01 9.39023996253647e-01 2.18364183904311e-01 +-1.23000000000000e+02 5.13223602126577e-01 1.00719521066899e+00 2.30949738818684e-01 +-1.20000000000000e+02 4.81854438801891e-01 1.07536616469559e+00 2.43526390646390e-01 +-1.17000000000000e+02 4.39681481271308e-01 1.13061446591332e+00 2.54956685887127e-01 +-1.14000000000000e+02 3.97508111898989e-01 1.18586253082399e+00 2.66377239042142e-01 +-1.11000000000000e+02 3.55334297402172e-01 1.24111017367587e+00 2.77786058750497e-01 +-1.08000000000000e+02 3.08037893527830e-01 1.28321205725494e+00 2.87281519675595e-01 +-1.05000000000000e+02 2.58180351390511e-01 1.31874096109859e+00 2.95813196403833e-01 +-1.02000000000000e+02 2.08323097887283e-01 1.35426945781572e+00 3.04327743613626e-01 +-9.90000000000000e+01 1.57576203402918e-01 1.38176151510008e+00 3.11395522027348e-01 +-9.60000000000000e+01 1.05050834785785e-01 1.39318034541842e+00 3.15588655906570e-01 +-9.30000000000000e+01 5.25255582791447e-02 1.40459908850334e+00 3.19756596609520e-01 +-9.00000000000000e+01 3.27826917023240e-07 1.41601778797233e+00 3.23659461316635e-01 +-8.70000000000000e+01 -5.25255045195490e-02 1.40459910019038e+00 3.22945034933183e-01 +-8.40000000000000e+01 -1.05050981658418e-01 1.39318031348883e+00 3.21791611743605e-01 +-8.10000000000000e+01 -1.57575748382869e-01 1.38176161401983e+00 3.20129918962609e-01 +-7.80000000000000e+01 -2.08322856414832e-01 1.35426962988931e+00 3.17048455458342e-01 +-7.50000000000000e+01 -2.58180681242367e-01 1.31874072604392e+00 3.12905041046394e-01 +-7.20000000000000e+01 -3.08037652060678e-01 1.28321222932679e+00 3.08761210418793e-01 +-6.90000000000000e+01 -3.55333932045767e-01 1.24111065228680e+00 3.03514635390291e-01 +-6.60000000000000e+01 -3.97508229824454e-01 1.18586237634021e+00 2.96062481257706e-01 +-6.30000000000000e+01 -4.39681760287162e-01 1.13061410039362e+00 2.88610017991116e-01 +-6.00000000000000e+01 -4.81854646345531e-01 1.07536571368012e+00 2.81157387364500e-01 +-5.70000000000000e+01 -5.13223809656928e-01 1.00719475965353e+00 2.72212286505312e-01 +-5.40000000000000e+01 -5.44591138813060e-01 9.39023545233018e-01 2.63266996912069e-01 +-5.10000000000000e+01 -5.75956945455947e-01 8.70851810020693e-01 2.54321329847841e-01 +-4.80000000000000e+01 -6.01326324662319e-01 7.99654560229442e-01 2.45618131252866e-01 +-4.50000000000000e+01 -6.23695970153485e-01 7.26944601773029e-01 2.37036162995707e-01 +-4.20000000000000e+01 -6.42168713793076e-01 6.54103510491734e-01 2.29439922053861e-01 +-3.90000000000000e+01 -6.59537045517161e-01 5.81899603350932e-01 2.22338894134465e-01 +-3.60000000000000e+01 -6.74166998306598e-01 5.11590826220192e-01 2.16852610379598e-01 +-3.30000000000000e+01 -6.88095062911521e-01 4.43295420850299e-01 2.13321658336198e-01 +-3.00000000000000e+01 -7.02434061164880e-01 3.77139487001304e-01 2.11949178572412e-01 +-2.93939393939394e+01 -7.06130482490463e-01 3.64852362744942e-01 2.12237605316701e-01 +-2.87878787878788e+01 -7.09824479328829e-01 3.52565238488579e-01 2.12555391583848e-01 +-2.81818181818182e+01 -7.13516027506550e-01 3.40278114232216e-01 2.12872847967098e-01 +-2.75757575757576e+01 -7.17530381434993e-01 3.28305985630029e-01 2.13597061869978e-01 +-2.69696969696970e+01 -7.21682227375692e-01 3.16468866746567e-01 2.14495479961637e-01 +-2.63636363636364e+01 -7.25832258736785e-01 3.04631747863105e-01 2.15393660836009e-01 +-2.57575757575758e+01 -7.30267770470675e-01 2.92993562362201e-01 2.16593296530334e-01 +-2.51515151515151e+01 -7.35132964149189e-01 2.81653730571187e-01 2.18245185960105e-01 +-2.45454545454545e+01 -7.39997274048644e-01 2.70313898780173e-01 2.19896919526772e-01 +-2.39393939393939e+01 -7.44966676859083e-01 2.59028163484346e-01 2.21648566366930e-01 +-2.33333333333333e+01 -7.50889197184390e-01 2.48229307118538e-01 2.24300599299510e-01 +-2.27272727272727e+01 -7.56811618414165e-01 2.37430450752730e-01 2.26952544318588e-01 +-2.21212121212121e+01 -7.62733947044537e-01 2.26631594386922e-01 2.29604411305050e-01 +-2.15151515151515e+01 -7.65543180919198e-01 2.16298421341179e-01 2.33347719604617e-01 +-2.09090909090909e+01 -7.67159390551658e-01 2.06081699080272e-01 2.37363936868452e-01 +-2.03030303030303e+01 -7.70989589899503e-01 1.95864976819365e-01 2.41380122381193e-01 +-1.96969696969697e+01 -7.66408855179284e-01 1.86713082311620e-01 2.37110565273848e-01 +-1.90909090909091e+01 -7.53224334899666e-01 1.78625955319317e-01 2.24555711213706e-01 +-1.84848484848485e+01 -7.40515247767467e-01 1.70539222184923e-01 2.12001402771163e-01 +-1.78787878787879e+01 -7.28073414237448e-01 1.62452465875814e-01 1.99446889701465e-01 +-1.72727272727273e+01 -7.15796412819352e-01 1.54365338883510e-01 1.86891340465851e-01 +-1.66666666666667e+01 -7.03628403601917e-01 1.45137051028637e-01 1.74335949867985e-01 +-1.60606060606061e+01 -6.91536071334431e-01 1.35827440633388e-01 1.61780655103707e-01 +-1.54545454545455e+01 -6.79841375439502e-01 1.27125362674088e-01 1.49225873196518e-01 +-1.48484848484848e+01 -6.68371976472640e-01 1.18756044019379e-01 1.36670824522160e-01 +-1.42424242424242e+01 -6.57525266337486e-01 1.11081575507249e-01 1.24115046890632e-01 +-1.36363636363636e+01 -6.46919349317121e-01 1.03510536591038e-01 1.11559472566631e-01 +-1.30303030303030e+01 -6.36590196575789e-01 9.60197655285123e-02 9.90027923089362e-02 +-1.24242424242424e+01 -6.26616545201912e-01 8.84489364835728e-02 8.64466304336154e-02 +-1.18181818181818e+01 -6.16997647064756e-01 8.07255969659771e-02 7.38892790664918e-02 +-1.12121212121212e+01 -6.07806438992942e-01 7.26223306995905e-02 6.13323781273887e-02 +-1.06060606060606e+01 -5.99288567453162e-01 6.43078358166966e-02 4.87732017593027e-02 +-1.00000000000000e+01 -5.91657873003445e-01 5.59263606591254e-02 3.62141784693746e-02 +-9.39393939393939e+00 -5.79058163807746e-01 4.91379422584400e-02 2.49867487590630e-02 +-8.78787878787879e+00 -5.66700483456983e-01 4.25327427253251e-02 1.37556766416755e-02 +-8.18181818181818e+00 -5.52767057263263e-01 3.51385027365045e-02 2.51431078401171e-03 +-7.57575757575758e+00 -5.16152487631087e-01 3.07167300167049e-02 -3.52520860243561e-03 +-6.96969696969697e+00 -4.69757056162087e-01 2.73460615848954e-02 -7.35433309173912e-03 +-6.36363636363636e+00 -4.23157901477119e-01 2.40466853818601e-02 -1.16480887450771e-02 +-5.75757575757576e+00 -3.74765829542321e-01 2.11022048511000e-02 -1.59084513723056e-02 +-5.15151515151515e+00 -3.23413692430681e-01 1.89550579096399e-02 -1.86750851344994e-02 +-4.54545454545454e+00 -2.68547626763533e-01 1.70622389773778e-02 -2.19719612773405e-02 +-3.93939393939394e+00 -2.11994257260558e-01 1.53692119559176e-02 -2.56157244462441e-02 +-3.33333333333333e+00 -1.48415934878880e-01 1.48139917958905e-02 -2.94968023177144e-02 +-2.72727272727273e+00 -7.89769276979072e-02 1.41624540467447e-02 -3.39437653144343e-02 +-2.12121212121212e+00 -3.46478095391404e-03 1.34145873263993e-02 -3.86035781138906e-02 +-1.51515151515152e+00 7.38291063274909e-02 1.30921930075161e-02 -4.27533487199522e-02 +-9.09090909090912e-01 1.51829760730163e-01 1.28923820998857e-02 -4.69054889010057e-02 +-3.03030303030302e-01 2.30822308320161e-01 1.28050693423605e-02 -5.10801102705995e-02 + 3.03030303030302e-01 3.10463730114934e-01 1.27477575306067e-02 -5.50677649278274e-02 + 9.09090909090912e-01 3.90790263359822e-01 1.27353987638778e-02 -5.88795212672597e-02 + 1.51515151515152e+00 4.71284233730724e-01 1.28776954822189e-02 -6.27273016180439e-02 + 2.12121212121212e+00 5.50963097343411e-01 1.30675735894997e-02 -6.64832475878559e-02 + 2.72727272727273e+00 6.30138935816981e-01 1.32424674678596e-02 -6.95217238202173e-02 + 3.33333333333333e+00 7.08536320290482e-01 1.34717732475649e-02 -7.23228820759458e-02 + 3.93939393939394e+00 7.86307858387585e-01 1.38172159080549e-02 -7.49142757271172e-02 + 4.54545454545455e+00 8.62388339964567e-01 1.42557288224049e-02 -7.75040470102574e-02 + 5.15151515151515e+00 9.37700928676955e-01 1.47059776016534e-02 -8.00049921252249e-02 + 5.75757575757576e+00 1.01125073389474e+00 1.51614417050010e-02 -8.21454604598515e-02 + 6.36363636363637e+00 1.08227624065879e+00 1.57108190803841e-02 -8.39835694506992e-02 + 6.96969696969697e+00 1.15161256120026e+00 1.63448211385627e-02 -8.56439571000181e-02 + 7.57575757575757e+00 1.21596411426272e+00 1.71676404929355e-02 -8.74082304182359e-02 + 8.18181818181818e+00 1.27673300509297e+00 1.80775111046661e-02 -8.94455339298536e-02 + 8.78787878787879e+00 1.33119115050654e+00 1.91750329509376e-02 -9.16003178554933e-02 + 9.39393939393939e+00 1.37956425338417e+00 2.13859354652657e-02 -9.38392678971121e-02 + 1.00000000000000e+01 1.42465603147829e+00 2.40167211153884e-02 -9.61318882807184e-02 + 1.06060606060606e+01 1.44856679840724e+00 2.73518951987084e-02 -9.83269145446295e-02 + 1.12121212121212e+01 1.45643493495683e+00 3.11907783963854e-02 -1.01693563008612e-01 + 1.18181818181818e+01 1.44145511321968e+00 3.67776864017581e-02 -1.04240570768266e-01 + 1.24242424242424e+01 1.25811612577190e+00 4.49502463857501e-02 -9.87981028722830e-02 + 1.30303030303030e+01 1.21783548130362e+00 5.37917825568218e-02 -9.72024540714103e-02 + 1.36363636363636e+01 1.20160458150153e+00 6.40421590933513e-02 -9.82023678961166e-02 + 1.42424242424242e+01 1.18813191525126e+00 7.46618265741957e-02 -9.95181720845514e-02 + 1.48484848484848e+01 1.18027423785320e+00 8.60251229889524e-02 -1.01193555150372e-01 + 1.54545454545455e+01 1.17877779387270e+00 9.81117465457450e-02 -1.05541629489454e-01 + 1.60606060606061e+01 1.17689322444726e+00 1.10556666678342e-01 -1.10785671275185e-01 + 1.66666666666667e+01 1.16581038309829e+00 1.24057053255380e-01 -1.18134261648867e-01 + 1.72727272727273e+01 1.15665660147017e+00 1.37525823660165e-01 -1.25046831531383e-01 + 1.78787878787879e+01 1.14984732933414e+00 1.50955951675739e-01 -1.31427188552528e-01 + 1.84848484848485e+01 1.14985357005765e+00 1.64278673861716e-01 -1.35546000357850e-01 + 1.90909090909091e+01 1.14897293619198e+00 1.76960001690690e-01 -1.39369242924789e-01 + 1.96969696969697e+01 1.13396288213762e+00 1.86157753963698e-01 -1.44719855669495e-01 + 2.03030303030303e+01 1.12113454332556e+00 1.95864976819365e-01 -1.49461918843513e-01 + 2.09090909090909e+01 1.11049287841322e+00 2.06081699080272e-01 -1.53594296036503e-01 + 2.15151515151515e+01 1.09985087842677e+00 2.16298421341179e-01 -1.57724684571442e-01 + 2.21212121212121e+01 1.08964494555376e+00 2.26631594386922e-01 -1.61741842424593e-01 + 2.27272727272727e+01 1.08118409226682e+00 2.37430450752730e-01 -1.65312206684248e-01 + 2.33333333333333e+01 1.07272310525245e+00 2.48229307118538e-01 -1.68881329238900e-01 + 2.39393939393939e+01 1.06426197511829e+00 2.59028163484346e-01 -1.72449237026485e-01 + 2.45454545454545e+01 1.05716247952044e+00 2.70313898780173e-01 -1.75700716715067e-01 + 2.51515151515151e+01 1.05021311424356e+00 2.81653730571187e-01 -1.78916186478768e-01 + 2.57575757575758e+01 1.04326247901123e+00 2.92993562362201e-01 -1.82130682130006e-01 + 2.63636363636364e+01 1.03692547814336e+00 3.04631747863105e-01 -1.85209085023971e-01 + 2.69696969696970e+01 1.03099616857058e+00 3.16468866746567e-01 -1.88196490642796e-01 + 2.75757575757576e+01 1.02506425393147e+00 3.28305985630029e-01 -1.91182998125262e-01 + 2.81818181818182e+01 1.01932894884137e+00 3.40278114232216e-01 -1.94124420358041e-01 + 2.87878787878788e+01 1.01405525818665e+00 3.52565238488579e-01 -1.96961880499345e-01 + 2.93939393939394e+01 1.00877805189828e+00 3.64852362744942e-01 -1.99798436276836e-01 + 3.00000000000000e+01 1.00349736452608e+00 3.77139487001304e-01 -2.02634065252844e-01 + 3.30000000000000e+01 9.82998715735978e-01 4.43295420850300e-01 -2.15352590816283e-01 + 3.60000000000000e+01 9.63089651383735e-01 5.11590826220192e-01 -2.27863925187279e-01 + 3.90000000000000e+01 9.42175986921238e-01 5.81899603350932e-01 -2.39321618575565e-01 + 4.20000000000000e+01 9.17369367761984e-01 6.54103510491734e-01 -2.50662792778012e-01 + 4.50000000000000e+01 8.90994844258789e-01 7.26944601773029e-01 -2.61985791102602e-01 + 4.80000000000000e+01 8.59052634531658e-01 7.99654560229442e-01 -2.73143035398585e-01 + 5.10000000000000e+01 8.22819956247608e-01 8.70851810020694e-01 -2.84140610804423e-01 + 5.40000000000000e+01 7.78010344233567e-01 9.39023545233018e-01 -2.94794033259472e-01 + 5.70000000000000e+01 7.33199012906027e-01 1.00719475965353e+00 -3.05462909314392e-01 + 6.00000000000000e+01 6.88385299195316e-01 1.07536571368012e+00 -3.16145847013128e-01 + 6.30000000000000e+01 6.28130235918108e-01 1.13061410039362e+00 -3.25620798502509e-01 + 6.60000000000000e+01 5.67874167049533e-01 1.18586237634021e+00 -3.35110403637996e-01 + 6.90000000000000e+01 5.07616883385694e-01 1.24111065228680e+00 -3.44613531015476e-01 + 7.20000000000000e+01 4.40053035872077e-01 1.28321222932679e+00 -3.52880607742317e-01 + 7.50000000000000e+01 3.68836397224492e-01 1.31874072604392e+00 -3.60538886626655e-01 + 7.80000000000000e+01 2.97618557438900e-01 1.35426962988931e+00 -3.68212529205940e-01 + 8.10000000000000e+01 2.25125798524460e-01 1.38176161401983e+00 -3.75046689565342e-01 + 8.40000000000000e+01 1.50084444920197e-01 1.39318031348883e+00 -3.80189854624853e-01 + 8.70000000000000e+01 7.50422088870966e-02 1.40459910019038e+00 -3.85401065327424e-01 + 9.00000000000000e+01 -3.27826917250672e-07 1.41601778797233e+00 -3.90743940003956e-01 + 9.30000000000000e+01 -5.25255582791447e-02 1.40459908850334e+00 -3.92409982314967e-01 + 9.60000000000000e+01 -1.05050834785786e-01 1.39318034541842e+00 -3.94293016797664e-01 + 9.90000000000000e+01 -1.57576203402918e-01 1.38176151510008e+00 -3.96176174609728e-01 + 1.02000000000000e+02 -2.08323097887283e-01 1.35426945781572e+00 -3.94964753048719e-01 + 1.05000000000000e+02 -2.58180351390512e-01 1.31874096109859e+00 -3.92206337784692e-01 + 1.08000000000000e+02 -3.08037893527830e-01 1.28321205725494e+00 -3.89447790562342e-01 + 1.11000000000000e+02 -3.55334297402172e-01 1.24111017367587e+00 -3.85534983800253e-01 + 1.14000000000000e+02 -3.97508111898989e-01 1.18586253082399e+00 -3.79313668806810e-01 + 1.17000000000000e+02 -4.39681481271308e-01 1.13061446591332e+00 -3.73092768861011e-01 + 1.20000000000000e+02 -4.81854438801891e-01 1.07536616469558e+00 -3.66872427068639e-01 + 1.23000000000000e+02 -5.13223602126577e-01 1.00719521066899e+00 -3.59027141872641e-01 + 1.26000000000000e+02 -5.44590931294051e-01 9.39023996253647e-01 -3.51183092578474e-01 + 1.29000000000000e+02 -5.75956737945602e-01 8.70852261041322e-01 -3.43340078183588e-01 + 1.32000000000000e+02 -6.00029188829974e-01 7.99611206996042e-01 -3.36135466500916e-01 + 1.35000000000000e+02 -6.20451890084054e-01 7.26835497177056e-01 -3.29251904114765e-01 + 1.38000000000000e+02 -6.40870225785841e-01 6.54060157601795e-01 -3.22371150094234e-01 + 1.41000000000000e+02 -6.59280196399078e-01 5.82702871795151e-01 -3.17195017404215e-01 + 1.44000000000000e+02 -6.73672820323352e-01 5.14181705032495e-01 -3.15427742312397e-01 + 1.47000000000000e+02 -6.88056994571163e-01 4.45660752601736e-01 -3.13666489886140e-01 + 1.50000000000000e+02 -7.02433949228043e-01 3.77139907333099e-01 -3.11911025372031e-01 + 1.53000000000000e+02 -7.28273002358664e-01 3.21224917158276e-01 -3.26779546578991e-01 + 1.56000000000000e+02 -7.54094985201384e-01 2.65310015371530e-01 -3.41648669551904e-01 + 1.59000000000000e+02 -7.79902956443025e-01 2.09395231609251e-01 -3.56518297584456e-01 + 1.62000000000000e+02 -7.15623711897387e-01 1.69995730690300e-01 -3.89180151768352e-01 + 1.65000000000000e+02 -6.04668180255573e-01 1.38854010867083e-01 -4.30738080965074e-01 + 1.68000000000000e+02 -5.04633128784701e-01 1.07712184204155e-01 -4.72295103043239e-01 + 1.71000000000000e+02 -3.90299886270968e-01 7.84829800637506e-02 -4.50000513056908e-01 + 1.74000000000000e+02 -2.60199626255756e-01 5.30791102629704e-02 -2.99999717902353e-01 + 1.77000000000000e+02 -1.28700931105444e-01 4.42220543974298e-02 -1.48407664836567e-01 + 1.80000000000000e+02 0.00000000000000e+00 4.36560269351644e-02 0.00000000000000e+00 diff --git a/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_09.dat b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_09.dat new file mode 100644 index 00000000..709a0e40 --- /dev/null +++ b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_09.dat @@ -0,0 +1,254 @@ +! ------------ AirfoilInfo v1.01.x Input File ---------------------------------- +! AeroElasticSE FAST driver +! line +! line +! ------------------------------------------------------------------------------ +DEFAULT InterpOrd ! Interpolation order to use for quasi-steady table lookup {1=linear; 3=cubic spline; "default"} [default=3] +1 NonDimArea ! The non-dimensional area of the airfoil (area/chord^2) (set to 1.0 if unsure or unneeded) +@"NREL-2p8-127_AF09_Coords.txt" NumCoords ! The number of coordinates in the airfoil shape file. Set to zero if coordinates not included. +AF09_BL.txt BL_file ! The file name including the boundary layer characteristics of the profile. Ignored if the aeroacoustic module is not called. +1 NumTabs ! Number of airfoil tables in this file. Each table must have lines for Re and Ctrl. +! ------------------------------------------------------------------------------ +! data for table 1 +! ------------------------------------------------------------------------------ +6.000000 Re ! Reynolds number in millions +0 Ctrl ! Control setting (must be 0 for current AirfoilInfo) +True InclUAdata ! Is unsteady aerodynamics data included in this table? If TRUE, then include 30 UA coefficients below this line +!........................................ +-2.060385 alpha0 ! 0-lift angle of attack, depends on airfoil. +11.208140 alpha1 ! Angle of attack at f=0.7, (approximately the stall angle) for AOA>alpha0. (deg) +-7.861323 alpha2 ! Angle of attack at f=0.7, (approximately the stall angle) for AOA1] +0.000000 S2 ! Constant in the f curve best-fit for AOA> alpha1; by definition it depends on the airfoil. [ignored if UAMod<>1] +0.000000 S3 ! Constant in the f curve best-fit for alpha2<=AOA< alpha0; by definition it depends on the airfoil. [ignored if UAMod<>1] +0.000000 S4 ! Constant in the f curve best-fit for AOA< alpha2; by definition it depends on the airfoil. [ignored if UAMod<>1] +1.367424 Cn1 ! Critical value of C0n at leading edge separation. It should be extracted from airfoil data at a given Mach and Reynolds number. It can be calculated from the static value of Cn at either the break in the pitching moment or the loss of chord force at the onset of stall. It is close to the condition of maximum lift of the airfoil at low Mach numbers. +-0.824883 Cn2 ! As Cn1 for negative AOAs. +Default St_sh ! Strouhal's shedding frequency constant. [default = 0.19] +0.010934 Cd0 ! 2D drag coefficient value at 0-lift. +-0.049324 Cm0 ! 2D pitching moment coefficient about 1/4-chord location, at 0-lift, positive if nose up. [If the aerodynamics coefficients table does not include a column for Cm, this needs to be set to 0.0] +0.000000 k0 ! Constant in the \hat(x)_cp curve best-fit; = (\hat(x)_AC-0.25). [ignored if UAMod<>1] +0.000000 k1 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k2 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k3 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k1_hat ! Constant in the expression of Cc due to leading edge vortex effects. [ignored if UAMod<>1] +Default x_cp_bar ! Constant in the expression of \hat(x)_cp^v. [ignored if UAMod<>1, default = 0.2] +Default UACutout ! Angle of attack above which unsteady aerodynamics are disabled (deg). [Specifying the string "Default" sets UACutout to 45 degrees] +Default filtCutOff ! Cut-off frequency (-3 dB corner frequency) for low-pass filtering the AoA input to UA, as well as the 1st and 2nd derivatives (Hz) [default = 20] +!........................................ +! Table of aerodynamics coefficients +200 NumAlf ! Number of data lines in the following table +! Alpha Cl Cd Cm +! (deg) (-) (-) (-) +-1.80000000000000e+02 0.00000000000000e+00 5.31472191671717e-02 0.00000000000000e+00 +-1.77000000000000e+02 1.29495037060763e-01 5.31472191671717e-02 1.18521230701205e-01 +-1.74000000000000e+02 2.62196549024508e-01 6.37579530831230e-02 2.39999774321882e-01 +-1.71000000000000e+02 3.93295149394492e-01 9.55905031721947e-02 3.60000410445527e-01 +-1.68000000000000e+02 5.10233340661308e-01 1.28558250585849e-01 3.26000611777352e-01 +-1.65000000000000e+02 6.19785379304123e-01 1.62093583412369e-01 2.15002393125294e-01 +-1.62000000000000e+02 7.31395834011373e-01 1.95629300525583e-01 1.04002855069395e-01 +-1.59000000000000e+02 7.97042839057236e-01 2.36917620123939e-01 3.50287462844128e-02 +-1.56000000000000e+02 7.70832295867696e-01 2.93710882428943e-01 5.00110113837699e-02 +-1.53000000000000e+02 7.44620920477827e-01 3.50504182292723e-01 6.48349471240901e-02 +-1.50000000000000e+02 7.18408694438638e-01 4.07297530590864e-01 7.94722317169135e-02 +-1.47000000000000e+02 7.03823896258865e-01 4.76817027337738e-01 9.22485232622368e-02 +-1.44000000000000e+02 6.89238523528509e-01 5.46336591473471e-01 1.05021570591302e-01 +-1.41000000000000e+02 6.74652275680612e-01 6.15856290391738e-01 1.17790814864596e-01 +-1.38000000000000e+02 6.55921766878216e-01 6.88177317217559e-01 1.31322598661476e-01 +-1.35000000000000e+02 6.35119149734577e-01 7.61899002314359e-01 1.45235182430339e-01 +-1.32000000000000e+02 6.14315531955484e-01 8.35620937733996e-01 1.59144670993128e-01 +-1.29000000000000e+02 5.89758365423619e-01 9.07722303996263e-01 1.73171416661612e-01 +-1.26000000000000e+02 5.57694365436177e-01 9.76582524253020e-01 1.87436089134836e-01 +-1.23000000000000e+02 5.25630147618883e-01 1.04544221845313e+00 2.01697660743594e-01 +-1.20000000000000e+02 4.93565771807661e-01 1.11430164963474e+00 2.15955995381730e-01 +-1.17000000000000e+02 4.50397682635010e-01 1.16980036934638e+00 2.29069583999682e-01 +-1.14000000000000e+02 4.07229711397332e-01 1.22529885093775e+00 2.42179581353683e-01 +-1.11000000000000e+02 3.64062034832866e-01 1.28079690855731e+00 2.55285105310821e-01 +-1.08000000000000e+02 3.15627063533621e-01 1.32277521883958e+00 2.66511224315401e-01 +-1.05000000000000e+02 2.64558413703211e-01 1.35799355250651e+00 2.76794753835721e-01 +-1.02000000000000e+02 2.13490336137694e-01 1.39321148260576e+00 2.87071098135651e-01 +-9.90000000000000e+01 1.61500486209697e-01 1.42017677477570e+00 2.95908817817940e-01 +-9.60000000000000e+01 1.07667090348450e-01 1.43063643362188e+00 3.01875969512173e-01 +-9.30000000000000e+01 5.38337094334587e-02 1.44109601256217e+00 3.07830613812683e-01 +-9.00000000000000e+01 3.35991459655313e-07 1.45155555155023e+00 3.13757307492905e-01 +-8.70000000000000e+01 -5.38336543349781e-02 1.44109602326751e+00 3.15792074690342e-01 +-8.40000000000000e+01 -1.07667240878618e-01 1.43063640437435e+00 3.17709664434913e-01 +-8.10000000000000e+01 -1.61500019858388e-01 1.42017686538628e+00 3.19427985605789e-01 +-7.80000000000000e+01 -2.13490088801890e-01 1.39321165317520e+00 3.18443936149184e-01 +-7.50000000000000e+01 -2.64558751566886e-01 1.35799331950653e+00 3.16050829869962e-01 +-7.20000000000000e+01 -3.15626816200455e-01 1.32277538940729e+00 3.13657156553441e-01 +-6.90000000000000e+01 -3.64061660870620e-01 1.28079738933759e+00 3.10049989411700e-01 +-6.60000000000000e+01 -4.07229832102981e-01 1.22529869575376e+00 3.04015735248115e-01 +-6.30000000000000e+01 -4.50397968233045e-01 1.16980000216993e+00 2.97981084772964e-01 +-6.00000000000000e+01 -4.93565983944208e-01 1.11430119406435e+00 2.91946220973731e-01 +-5.70000000000000e+01 -5.25630359754821e-01 1.04544176288274e+00 2.84141782265212e-01 +-5.40000000000000e+01 -5.57694577570126e-01 9.76582068677410e-01 2.76337115591071e-01 +-5.10000000000000e+01 -5.89758577557172e-01 9.07721848420653e-01 2.68531992982216e-01 +-4.80000000000000e+01 -6.15975377464480e-01 8.35676496789876e-01 2.60891044708829e-01 +-4.50000000000000e+01 -6.39268597360940e-01 7.62038630661659e-01 2.53332180964662e-01 +-4.20000000000000e+01 -6.57581661720133e-01 6.88232875834521e-01 2.47037064737753e-01 +-3.90000000000000e+01 -6.74980379108277e-01 6.14826511890619e-01 2.41247071396765e-01 +-3.60000000000000e+01 -6.89869193378202e-01 5.43015121244335e-01 2.37267768231330e-01 +-3.30000000000000e+01 -7.03872456392545e-01 4.73784534746912e-01 2.35795153182948e-01 +-3.00000000000000e+01 -7.18408799575845e-01 4.07297098236698e-01 2.37089771150360e-01 +-2.93939393939394e+01 -7.21762686347836e-01 3.94552959906465e-01 2.38090915530434e-01 +-2.87878787878788e+01 -7.25116462207148e-01 3.81808821576231e-01 2.39093403016499e-01 +-2.81818181818182e+01 -7.28470126047924e-01 3.69064683245998e-01 2.40095875411411e-01 +-2.75757575757576e+01 -7.32236853727248e-01 3.56724431468315e-01 2.41620187509530e-01 +-2.69696969696970e+01 -7.36180584373604e-01 3.44557288776848e-01 2.43368158185924e-01 +-2.63636363636364e+01 -7.40124232008641e-01 3.32390146085381e-01 2.45116118010372e-01 +-2.57575757575758e+01 -7.44432056142082e-01 3.20478002655761e-01 2.47250782325627e-01 +-2.51515151515151e+01 -7.49286130044737e-01 3.08948298688103e-01 2.49965419735941e-01 +-2.45454545454545e+01 -7.54140163517274e-01 2.97418594720445e-01 2.52680050016007e-01 +-2.39393939393939e+01 -7.59128300719057e-01 2.85958242769248e-01 2.55522930540395e-01 +-2.33333333333333e+01 -7.65323729613723e-01 2.75122072393073e-01 2.59520140578325e-01 +-2.27272727272727e+01 -7.71519153975079e-01 2.64285902016898e-01 2.63517346594489e-01 +-2.21212121212121e+01 -7.77714574100304e-01 2.53449731640723e-01 2.67514549040905e-01 +-2.15151515151515e+01 -7.83978195814861e-01 2.43210638882764e-01 2.72910891584855e-01 +-2.09090909090909e+01 -7.90117542155355e-01 2.33120853936042e-01 2.78657108165319e-01 +-2.03030303030303e+01 -7.97012109620063e-01 2.23031068989321e-01 2.84403323293269e-01 +-1.96969696969697e+01 -7.95415736248302e-01 2.13313352612748e-01 2.80089060137697e-01 +-1.90909090909091e+01 -7.85263277790639e-01 2.03967683758259e-01 2.65714886768838e-01 +-1.84848484848485e+01 -7.75273314466664e-01 1.94622470054976e-01 2.51341410437202e-01 +-1.78787878787879e+01 -7.65374889035412e-01 1.85277229570461e-01 2.36967769403479e-01 +-1.72727272727273e+01 -7.55533108229545e-01 1.75931560715972e-01 2.22592985180729e-01 +-1.66666666666667e+01 -7.45728795354525e-01 1.66196420256137e-01 2.08218526695132e-01 +-1.60606060606061e+01 -7.35950554364156e-01 1.56433343834581e-01 1.93844333165442e-01 +-1.54545454545455e+01 -7.26308463193755e-01 1.46878222014310e-01 1.79470874697127e-01 +-1.48484848484848e+01 -7.16743375686355e-01 1.37436585788465e-01 1.65097285434163e-01 +-1.42424242424242e+01 -7.07390619723189e-01 1.28231667233805e-01 1.50723069814813e-01 +-1.36363636363636e+01 -6.98120667001908e-01 1.19062253074563e-01 1.36349337872941e-01 +-1.30303030303030e+01 -6.88944298853437e-01 1.09919099684084e-01 1.21974646106258e-01 +-1.24242424242424e+01 -6.79890334514997e-01 1.00749731941577e-01 1.07600926861901e-01 +-1.18181818181818e+01 -6.70956348082078e-01 9.15279934171627e-02 9.32263230029353e-02 +-1.12121212121212e+01 -6.62168843237812e-01 8.21771971589323e-02 7.88528466356555e-02 +-1.06060606060606e+01 -6.53611277615254e-01 7.27538640183303e-02 6.44774855298434e-02 +-1.00000000000000e+01 -6.45356230550116e-01 6.33080422182624e-02 5.01034327127313e-02 +-9.39393939393939e+00 -6.36593332900123e-01 5.41963669816850e-02 3.57833738354860e-02 +-8.78787878787879e+00 -6.27918256833836e-01 4.51475416350120e-02 2.14623968040231e-02 +-8.18181818181818e+00 -6.18711373162793e-01 3.58305294547305e-02 7.14198465445491e-03 +-7.57575757575758e+00 -5.80216174573165e-01 3.01489440959233e-02 -5.19349418320715e-04 +-6.96969696969697e+00 -5.28953354241068e-01 2.59835542019697e-02 -5.35572587261972e-03 +-6.36363636363636e+00 -4.73862537653747e-01 2.22211779699908e-02 -1.07634960479835e-02 +-5.75757575757576e+00 -4.16582198644429e-01 1.90003840623066e-02 -1.61245333665883e-02 +-5.15151515151515e+00 -3.55933513528219e-01 1.66928246089848e-02 -2.10369141861243e-02 +-4.54545454545454e+00 -2.91472100196896e-01 1.47078923324148e-02 -2.64604110668977e-02 +-3.93939393939394e+00 -2.25304889231469e-01 1.29545096367512e-02 -3.21126856296872e-02 +-3.33333333333333e+00 -1.54104000261012e-01 1.23887165275606e-02 -3.78462438825610e-02 +-2.72727272727273e+00 -8.16248041858842e-02 1.17323458130580e-02 -4.34613224548195e-02 +-2.12121212121212e+00 -7.62116470645060e-03 1.09678271146517e-02 -4.88326464973399e-02 +-1.51515151515152e+00 6.83134982557210e-02 1.06280353358650e-02 -5.37247752016293e-02 +-9.09090909090912e-01 1.44916946777653e-01 1.04099760350921e-02 -5.85191375679298e-02 +-3.03030303030302e-01 2.22554588237817e-01 1.02931716210053e-02 -6.33281972284231e-02 + 3.03030303030302e-01 3.00795206874542e-01 1.02297528304907e-02 -6.78528768736416e-02 + 9.09090909090912e-01 3.79652000805070e-01 1.02202988420258e-02 -7.20918564811688e-02 + 1.51515151515152e+00 4.59004148697031e-01 1.03956813611896e-02 -7.63468764323537e-02 + 2.12121212121212e+00 5.38292042421047e-01 1.06036731488726e-02 -8.03761253262362e-02 + 2.72727272727273e+00 6.17098027022441e-01 1.08115944967115e-02 -8.34392709248819e-02 + 3.33333333333333e+00 6.94907654704091e-01 1.10839446374173e-02 -8.61737788284095e-02 + 3.93939393939394e+00 7.71913058145968e-01 1.14291538648689e-02 -8.86385535504365e-02 + 4.54545454545455e+00 8.46751947966220e-01 1.18860333393268e-02 -9.11095009974341e-02 + 5.15151515151515e+00 9.20604899194484e-01 1.23569858194089e-02 -9.34332370032627e-02 + 5.75757575757576e+00 9.92199902524323e-01 1.28374739059253e-02 -9.53033834851092e-02 + 6.36363636363637e+00 1.06055718025240e+00 1.34310891694729e-02 -9.68110066273987e-02 + 6.96969696969697e+00 1.12674988698576e+00 1.40997355822941e-02 -9.80785912470612e-02 + 7.57575757575757e+00 1.18666342902678e+00 1.49845781349695e-02 -9.93714676847982e-02 + 8.18181818181818e+00 1.24314989353240e+00 1.59667211082838e-02 -1.00692149985168e-01 + 8.78787878787879e+00 1.29245687180882e+00 1.71544710253729e-02 -1.02035478870500e-01 + 9.39393939393939e+00 1.33396126311506e+00 1.95659937586037e-02 -1.03407560601880e-01 + 1.00000000000000e+01 1.37126009363817e+00 2.25665763961257e-02 -1.04797915194330e-01 + 1.06060606060606e+01 1.38618576553784e+00 2.67311075620441e-02 -1.05641194801641e-01 + 1.12121212121212e+01 1.38519725174546e+00 3.17846622479086e-02 -1.06586637285388e-01 + 1.18181818181818e+01 1.35493629423442e+00 3.87531354728749e-02 -1.07628263634721e-01 + 1.24242424242424e+01 1.31246186473740e+00 4.83484785906573e-02 -1.07847108308056e-01 + 1.30303030303030e+01 1.28680791441048e+00 5.91170543627865e-02 -1.08015031049527e-01 + 1.36363636363636e+01 1.26172678770879e+00 7.17168991472314e-02 -1.08181203384768e-01 + 1.42424242424242e+01 1.23769104210515e+00 8.49758848909100e-02 -1.08605313713084e-01 + 1.48484848484848e+01 1.21528767185958e+00 9.92702312554880e-02 -1.09411818544650e-01 + 1.54545454545455e+01 1.19968194488222e+00 1.14607265848385e-01 -1.13749735842298e-01 + 1.60606060606061e+01 1.18663909270316e+00 1.30222530116573e-01 -1.19428362054540e-01 + 1.66666666666667e+01 1.17688627348101e+00 1.45214198979932e-01 -1.27285721302187e-01 + 1.72727272727273e+01 1.16956684907482e+00 1.60165335729503e-01 -1.34601993519905e-01 + 1.78787878787879e+01 1.16522099838670e+00 1.75066932714929e-01 -1.41256962609131e-01 + 1.84848484848485e+01 1.16952525051625e+00 1.89830940964302e-01 -1.45028799262795e-01 + 1.90909090909091e+01 1.17284535113364e+00 2.03772684613384e-01 -1.48423774647318e-01 + 1.96969696969697e+01 1.15835573662925e+00 2.13248351672080e-01 -1.53767566099225e-01 + 2.03030303030303e+01 1.14530509433480e+00 2.23031068989321e-01 -1.58704075145085e-01 + 2.09090909090909e+01 1.13369372685470e+00 2.33120853936042e-01 -1.63233228331231e-01 + 2.15151515151515e+01 1.12208234404602e+00 2.43210638882764e-01 -1.67762290542514e-01 + 2.21212121212121e+01 1.11102321657310e+00 2.53449731640723e-01 -1.72148946259134e-01 + 2.27272727272727e+01 1.10217259984565e+00 2.64285902016898e-01 -1.75966397581727e-01 + 2.33333333333333e+01 1.09332197700060e+00 2.75122072393073e-01 -1.79783792100215e-01 + 2.39393939393939e+01 1.08447134760827e+00 2.85958242769248e-01 -1.83601131046924e-01 + 2.45454545454545e+01 1.07734542237668e+00 2.97418594720445e-01 -1.87014968760816e-01 + 2.51515151515151e+01 1.07041107379095e+00 3.08948298688103e-01 -1.90383934992330e-01 + 2.57575757575758e+01 1.06347666710874e+00 3.20478002655761e-01 -1.93752856661258e-01 + 2.63636363636364e+01 1.05732236007864e+00 3.32390146085381e-01 -1.96948677634826e-01 + 2.69696969696970e+01 1.05168813342601e+00 3.44557288776848e-01 -2.00029068561270e-01 + 2.75757575757576e+01 1.04605378759977e+00 3.56724431468315e-01 -2.03109418400795e-01 + 2.81818181818182e+01 1.04067256013258e+00 3.69064683245998e-01 -2.06133132039065e-01 + 2.87878787878788e+01 1.03588202408929e+00 3.81808821576232e-01 -2.09024762045095e-01 + 2.93939393939394e+01 1.03109132721680e+00 3.94552959906465e-01 -2.11916350679321e-01 + 3.00000000000000e+01 1.02630047109565e+00 4.07297098236698e-01 -2.14807896915288e-01 + 3.30000000000000e+01 1.00553169528085e+00 4.73784534746913e-01 -2.28328930073073e-01 + 3.60000000000000e+01 9.85527854289020e-01 5.43015121244335e-01 -2.41378773612232e-01 + 3.90000000000000e+01 9.64256669240620e-01 6.14826511890619e-01 -2.53786845019076e-01 + 4.20000000000000e+01 9.39401732187148e-01 6.88232875834521e-01 -2.65971257965397e-01 + 4.50000000000000e+01 9.13241579977801e-01 7.62038630661659e-01 -2.78098314901201e-01 + 4.80000000000000e+01 8.79965823978363e-01 8.35676496789876e-01 -2.89925721686919e-01 + 5.10000000000000e+01 8.42513311869095e-01 9.07721848420653e-01 -3.01541565653910e-01 + 5.40000000000000e+01 7.96707214786344e-01 9.76582068677410e-01 -3.12725809880497e-01 + 5.70000000000000e+01 7.50901373321919e-01 1.04544176288274e+00 -3.23914976497956e-01 + 6.00000000000000e+01 7.05095590005431e-01 1.11430119406435e+00 -3.35108765012171e-01 + 6.30000000000000e+01 6.43426651348128e-01 1.16980000216993e+00 -3.44954018840384e-01 + 6.60000000000000e+01 5.81757536770671e-01 1.22529869575376e+00 -3.54804262733281e-01 + 6.90000000000000e+01 5.20088366620145e-01 1.28079738933759e+00 -3.64659118816904e-01 + 7.20000000000000e+01 4.50895765482209e-01 1.32277538940729e+00 -3.73183031740474e-01 + 7.50000000000000e+01 3.77941618474775e-01 1.35799331950653e+00 -3.81044639026107e-01 + 7.80000000000000e+01 3.04986617856015e-01 1.39321165317520e+00 -3.88911546743740e-01 + 8.10000000000000e+01 2.30715110532685e-01 1.42017686538628e+00 -3.95889296470916e-01 + 8.40000000000000e+01 1.53810733540745e-01 1.43063640437435e+00 -4.01084668321152e-01 + 8.70000000000000e+01 7.69053727306556e-02 1.44109602326751e+00 -4.06287962899012e-01 + 9.00000000000000e+01 -3.35991459889849e-07 1.45155555155023e+00 -4.11502017960891e-01 + 9.30000000000000e+01 -5.38337094334587e-02 1.44109601256217e+00 -4.13894658825039e-01 + 9.60000000000000e+01 -1.07667090348450e-01 1.43063643362188e+00 -4.16297269931508e-01 + 9.90000000000000e+01 -1.61500486209697e-01 1.42017677477570e+00 -4.18699936551505e-01 + 1.02000000000000e+02 -2.13490336137694e-01 1.39321148260576e+00 -4.17907661987286e-01 + 1.05000000000000e+02 -2.64558413703211e-01 1.35799355250651e+00 -4.15518040952612e-01 + 1.08000000000000e+02 -3.15627063533621e-01 1.32277521883958e+00 -4.13127922002446e-01 + 1.11000000000000e+02 -3.64062034832866e-01 1.28079690855731e+00 -4.09526520529020e-01 + 1.14000000000000e+02 -4.07229711397332e-01 1.22529885093775e+00 -4.03502582615359e-01 + 1.17000000000000e+02 -4.50397682635010e-01 1.16980036934638e+00 -3.97478465589571e-01 + 1.20000000000000e+02 -4.93565771807662e-01 1.11430164963474e+00 -3.91454376227199e-01 + 1.23000000000000e+02 -5.25630147618883e-01 1.04544221845313e+00 -3.83664668897240e-01 + 1.26000000000000e+02 -5.57694365436177e-01 9.76582524253020e-01 -3.75875218145706e-01 + 1.29000000000000e+02 -5.89758365423620e-01 9.07722303996263e-01 -3.68085790436742e-01 + 1.32000000000000e+02 -6.14315531955485e-01 8.35620937733996e-01 -3.60884266412265e-01 + 1.35000000000000e+02 -6.35119149734577e-01 7.61899002314359e-01 -3.53977324090480e-01 + 1.38000000000000e+02 -6.55921766878216e-01 6.88177317217558e-01 -3.47071391893562e-01 + 1.41000000000000e+02 -6.74652275680612e-01 6.15856290391737e-01 -3.41901008734909e-01 + 1.44000000000000e+02 -6.89238523528509e-01 5.46336591473471e-01 -3.40201601680046e-01 + 1.47000000000000e+02 -7.03823896258865e-01 4.76817027337738e-01 -3.38504257224453e-01 + 1.50000000000000e+02 -7.18408694438638e-01 4.07297530590864e-01 -3.36808891109050e-01 + 1.53000000000000e+02 -7.44620920477827e-01 3.50504182292723e-01 -3.52050708459141e-01 + 1.56000000000000e+02 -7.70832295867696e-01 2.93710882428943e-01 -3.67292718466256e-01 + 1.59000000000000e+02 -7.97042839057236e-01 2.36917620123939e-01 -3.82534823044658e-01 + 1.62000000000000e+02 -7.25443285329967e-01 1.96119535360957e-01 -4.10092686634208e-01 + 1.65000000000000e+02 -6.04863200846212e-01 1.63319174643805e-01 -4.43808469577462e-01 + 1.68000000000000e+02 -4.87346219362824e-01 1.30518595329125e-01 -4.77523282896420e-01 + 1.71000000000000e+02 -3.66753120134991e-01 9.77955724163158e-02 -4.50000513056908e-01 + 1.74000000000000e+02 -2.44501896830564e-01 6.52276659281221e-02 -2.99999717902353e-01 + 1.77000000000000e+02 -1.20729578177091e-01 5.38728696135554e-02 -1.48151538376506e-01 + 1.80000000000000e+02 0.00000000000000e+00 5.31472191671717e-02 0.00000000000000e+00 diff --git a/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_10.dat b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_10.dat new file mode 100644 index 00000000..3d0828bf --- /dev/null +++ b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_10.dat @@ -0,0 +1,254 @@ +! ------------ AirfoilInfo v1.01.x Input File ---------------------------------- +! AeroElasticSE FAST driver +! line +! line +! ------------------------------------------------------------------------------ +DEFAULT InterpOrd ! Interpolation order to use for quasi-steady table lookup {1=linear; 3=cubic spline; "default"} [default=3] +1 NonDimArea ! The non-dimensional area of the airfoil (area/chord^2) (set to 1.0 if unsure or unneeded) +@"NREL-2p8-127_AF10_Coords.txt" NumCoords ! The number of coordinates in the airfoil shape file. Set to zero if coordinates not included. +AF10_BL.txt BL_file ! The file name including the boundary layer characteristics of the profile. Ignored if the aeroacoustic module is not called. +1 NumTabs ! Number of airfoil tables in this file. Each table must have lines for Re and Ctrl. +! ------------------------------------------------------------------------------ +! data for table 1 +! ------------------------------------------------------------------------------ +6.000000 Re ! Reynolds number in millions +0 Ctrl ! Control setting (must be 0 for current AirfoilInfo) +True InclUAdata ! Is unsteady aerodynamics data included in this table? If TRUE, then include 30 UA coefficients below this line +!........................................ +-2.064146 alpha0 ! 0-lift angle of attack, depends on airfoil. +11.141003 alpha1 ! Angle of attack at f=0.7, (approximately the stall angle) for AOA>alpha0. (deg) +-8.373634 alpha2 ! Angle of attack at f=0.7, (approximately the stall angle) for AOA1] +0.000000 S2 ! Constant in the f curve best-fit for AOA> alpha1; by definition it depends on the airfoil. [ignored if UAMod<>1] +0.000000 S3 ! Constant in the f curve best-fit for alpha2<=AOA< alpha0; by definition it depends on the airfoil. [ignored if UAMod<>1] +0.000000 S4 ! Constant in the f curve best-fit for AOA< alpha2; by definition it depends on the airfoil. [ignored if UAMod<>1] +1.372191 Cn1 ! Critical value of C0n at leading edge separation. It should be extracted from airfoil data at a given Mach and Reynolds number. It can be calculated from the static value of Cn at either the break in the pitching moment or the loss of chord force at the onset of stall. It is close to the condition of maximum lift of the airfoil at low Mach numbers. +-0.848243 Cn2 ! As Cn1 for negative AOAs. +Default St_sh ! Strouhal's shedding frequency constant. [default = 0.19] +0.010759 Cd0 ! 2D drag coefficient value at 0-lift. +-0.057548 Cm0 ! 2D pitching moment coefficient about 1/4-chord location, at 0-lift, positive if nose up. [If the aerodynamics coefficients table does not include a column for Cm, this needs to be set to 0.0] +0.000000 k0 ! Constant in the \hat(x)_cp curve best-fit; = (\hat(x)_AC-0.25). [ignored if UAMod<>1] +0.000000 k1 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k2 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k3 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k1_hat ! Constant in the expression of Cc due to leading edge vortex effects. [ignored if UAMod<>1] +Default x_cp_bar ! Constant in the expression of \hat(x)_cp^v. [ignored if UAMod<>1, default = 0.2] +Default UACutout ! Angle of attack above which unsteady aerodynamics are disabled (deg). [Specifying the string "Default" sets UACutout to 45 degrees] +Default filtCutOff ! Cut-off frequency (-3 dB corner frequency) for low-pass filtering the AoA input to UA, as well as the 1st and 2nd derivatives (Hz) [default = 20] +!........................................ +! Table of aerodynamics coefficients +200 NumAlf ! Number of data lines in the following table +! Alpha Cl Cd Cm +! (deg) (-) (-) (-) +-1.80000000000000e+02 0.00000000000000e+00 5.30837886627506e-02 0.00000000000000e+00 +-1.77000000000000e+02 1.24966191469559e-01 5.30837886627506e-02 1.18576829157013e-01 +-1.74000000000000e+02 2.52998633091314e-01 6.37003001697374e-02 2.39999774321882e-01 +-1.71000000000000e+02 3.79498286143344e-01 9.55501832215890e-02 3.60000410445527e-01 +-1.68000000000000e+02 4.98757573511548e-01 1.28321372265423e-01 3.22914823147173e-01 +-1.65000000000000e+02 6.15220538714466e-01 1.61553203552249e-01 2.07287957565546e-01 +-1.62000000000000e+02 7.27077094368088e-01 1.94785456665805e-01 9.16599143637722e-02 +-1.59000000000000e+02 7.93230980672808e-01 2.35846387240917e-01 1.84100886242669e-02 +-1.56000000000000e+02 7.68234137241237e-01 2.92564407901613e-01 3.03932586734567e-02 +-1.53000000000000e+02 7.43356372402597e-01 3.49282461855920e-01 4.28162358403718e-02 +-1.50000000000000e+02 7.18478522993120e-01 4.06000562593489e-01 5.56156944862064e-02 +-1.47000000000000e+02 7.03955906925430e-01 4.75651465566945e-01 6.92790833714106e-02 +-1.44000000000000e+02 6.89433035390160e-01 5.45302448258410e-01 8.29503219976363e-02 +-1.41000000000000e+02 6.74909652901486e-01 6.14953590391589e-01 9.66309029164283e-02 +-1.38000000000000e+02 6.56219474668182e-01 6.87418368921680e-01 1.10881678895009e-01 +-1.35000000000000e+02 6.35445907015363e-01 7.61289959942459e-01 1.25418499888186e-01 +-1.32000000000000e+02 6.14671501318397e-01 8.35161838486049e-01 1.39961030153749e-01 +-1.29000000000000e+02 5.90134200485388e-01 9.07415349226177e-01 1.54621277427466e-01 +-1.26000000000000e+02 5.58071091549210e-01 9.76432116678355e-01 1.69509055919750e-01 +-1.23000000000000e+02 5.26007827556163e-01 1.04544835687794e+00 1.84402154814945e-01 +-1.20000000000000e+02 4.93944486037582e-01 1.11446433346109e+00 1.99301684126228e-01 +-1.17000000000000e+02 4.50754244383126e-01 1.17011434599327e+00 2.13130402729061e-01 +-1.14000000000000e+02 4.07564132273452e-01 1.22576411981700e+00 2.26966296053101e-01 +-1.11000000000000e+02 3.64374322762834e-01 1.28141346851316e+00 2.40810540320626e-01 +-1.08000000000000e+02 3.15905431030774e-01 1.32353352870914e+00 2.52837246360334e-01 +-1.05000000000000e+02 2.64796957994024e-01 1.35888884163568e+00 2.63961625640692e-01 +-1.02000000000000e+02 2.13689029593013e-01 1.39424374942488e+00 2.75099894116298e-01 +-9.90000000000000e+01 1.61655412340594e-01 1.42133844008909e+00 2.84836104947235e-01 +-9.60000000000000e+01 1.07770377288908e-01 1.43191233870989e+00 2.91753073560900e-01 +-9.30000000000000e+01 5.38853538885643e-02 1.44248615655205e+00 2.98698830338381e-01 +-9.00000000000000e+01 3.36313787357514e-07 1.45305993400564e+00 3.05684965975821e-01 +-8.70000000000000e+01 -5.38852987372259e-02 1.44248616737432e+00 3.09060154363404e-01 +-8.40000000000000e+01 -1.07770527963470e-01 1.43191230914291e+00 3.12686281197342e-01 +-8.10000000000000e+01 -1.61654945541942e-01 1.42133853168932e+00 3.16767616953733e-01 +-7.80000000000000e+01 -2.13688782064248e-01 1.39424392065773e+00 3.16540498625861e-01 +-7.50000000000000e+01 -2.64797296121353e-01 1.35888860772946e+00 3.14266811229411e-01 +-7.20000000000000e+01 -3.15905183504718e-01 1.32353369994026e+00 3.11992145479124e-01 +-6.90000000000000e+01 -3.64373948609042e-01 1.28141395060407e+00 3.08496020987835e-01 +-6.60000000000000e+01 -4.07564253041044e-01 1.22576396420997e+00 3.02557290547327e-01 +-6.30000000000000e+01 -4.50754530127646e-01 1.17011397781587e+00 2.96617404810894e-01 +-6.00000000000000e+01 -4.93944698166970e-01 1.11446387685501e+00 2.90676423054807e-01 +-5.70000000000000e+01 -5.26008039685552e-01 1.04544790027186e+00 2.82948402317780e-01 +-5.40000000000000e+01 -5.58071303677059e-01 9.76431660067037e-01 2.75218817710457e-01 +-5.10000000000000e+01 -5.90134412613238e-01 9.07414892614858e-01 2.67487195859118e-01 +-4.80000000000000e+01 -6.16349723026200e-01 8.35214742285566e-01 2.59915443758204e-01 +-4.50000000000000e+01 -6.39641228159956e-01 7.61422951679187e-01 2.52421684677788e-01 +-4.20000000000000e+01 -6.57897683242975e-01 6.87471272303016e-01 2.46204422934917e-01 +-3.90000000000000e+01 -6.75245094925222e-01 6.13911269891018e-01 2.40506244340753e-01 +-3.60000000000000e+01 -6.90083088589439e-01 5.41941245231535e-01 2.36695331229210e-01 +-3.30000000000000e+01 -7.04017120189319e-01 4.72583293422338e-01 2.35442916975004e-01 +-3.00000000000000e+01 -7.18478627259844e-01 4.06000129199683e-01 2.37016869904415e-01 +-2.93939393939394e+01 -7.21798350573784e-01 3.93221418404654e-01 2.38091117333048e-01 +-2.87878787878788e+01 -7.25118073887724e-01 3.80442707609625e-01 2.39165364761681e-01 +-2.81818181818182e+01 -7.28437797201663e-01 3.67663996814596e-01 2.40239612190314e-01 +-2.75757575757576e+01 -7.32172588884317e-01 3.55293602246098e-01 2.41847562956378e-01 +-2.69696969696970e+01 -7.36085282271228e-01 3.43098215358386e-01 2.43684263346490e-01 +-2.63636363636364e+01 -7.39997975658139e-01 3.30902828470674e-01 2.45520963736601e-01 +-2.57575757575758e+01 -7.44276884748962e-01 3.18965212168995e-01 2.47753414207092e-01 +-2.51515151515151e+01 -7.49105032044442e-01 3.07414191669665e-01 2.50579397563581e-01 +-2.45454545454545e+01 -7.53933179339923e-01 2.95863171170336e-01 2.53405380920070e-01 +-2.39393939393939e+01 -7.58896243502194e-01 2.84382247917907e-01 2.56362693669404e-01 +-2.33333333333333e+01 -7.65073585586137e-01 2.73532213458751e-01 2.60501996380347e-01 +-2.27272727272727e+01 -7.71250927670079e-01 2.62682178999596e-01 2.64779889466675e-01 +-2.21212121212121e+01 -7.77428269754022e-01 2.51832144540440e-01 2.68945623496597e-01 +-2.15151515151515e+01 -7.90262923140693e-01 2.41893541513143e-01 2.73249028596959e-01 +-2.09090909090909e+01 -8.05906043706644e-01 2.32182854971129e-01 2.77270518618669e-01 +-2.03030303030303e+01 -8.19489198628311e-01 2.22472168429115e-01 2.81192694187527e-01 +-1.96969696969697e+01 -8.24678039235549e-01 2.13080793622121e-01 2.75632215545996e-01 +-1.90909090909091e+01 -8.21619989791241e-01 2.04008712486556e-01 2.60613787847909e-01 +-1.84848484848485e+01 -8.18197356256183e-01 1.95010678250887e-01 2.45586809616841e-01 +-1.78787878787879e+01 -8.14569480885818e-01 1.86007505483073e-01 2.30648571774812e-01 +-1.72727272727273e+01 -8.10814834138077e-01 1.76823863436936e-01 2.15753896541975e-01 +-1.66666666666667e+01 -8.06976123403415e-01 1.68593035533169e-01 2.00859509073193e-01 +-1.60606060606061e+01 -8.03078897629092e-01 1.60454418431078e-01 1.85965357045289e-01 +-1.54545454545455e+01 -7.97000707157957e-01 1.51710915395437e-01 1.71396869835783e-01 +-1.48484848484848e+01 -7.89576615706775e-01 1.42625264033402e-01 1.57006741726859e-01 +-1.42424242424242e+01 -7.78781317063958e-01 1.32791872599405e-01 1.43201565946783e-01 +-1.36363636363636e+01 -7.67357420824222e-01 1.22849813294929e-01 1.29490112449071e-01 +-1.30303030303030e+01 -7.55422617396779e-01 1.12823830974163e-01 1.15644996580170e-01 +-1.24242424242424e+01 -7.42969206287619e-01 1.02890282642851e-01 1.01449124172212e-01 +-1.18181818181818e+01 -7.30244644590558e-01 9.31176217950954e-02 8.72464359531469e-02 +-1.12121212121212e+01 -7.17231543580288e-01 8.37383245063512e-02 7.30648930269649e-02 +-1.06060606060606e+01 -7.03577356362280e-01 7.45798495908964e-02 5.90622202437287e-02 +-1.00000000000000e+01 -6.89105145844174e-01 6.55059849764586e-02 4.51630398367081e-02 +-9.39393939393939e+00 -6.76227800071737e-01 5.54692165142735e-02 3.11059783824235e-02 +-8.78787878787879e+00 -6.64141630347962e-01 4.52369131161758e-02 1.71623095710831e-02 +-8.18181818181818e+00 -6.54216850502614e-01 3.55800439872753e-02 3.42154297533580e-03 +-7.57575757575758e+00 -6.14625042059806e-01 2.91666756670593e-02 -3.86341370860449e-03 +-6.96969696969697e+00 -5.61841937827523e-01 2.43864881766210e-02 -8.43665697005592e-03 +-6.36363636363636e+00 -4.99189572128014e-01 2.06688208542298e-02 -1.37959149818896e-02 +-5.75757575757576e+00 -4.34608760745885e-01 1.76932591752901e-02 -1.92729400057168e-02 +-5.15151515151515e+00 -3.67348413458166e-01 1.56052490200204e-02 -2.57288663338659e-02 +-4.54545454545454e+00 -2.97220789753124e-01 1.38965283846311e-02 -3.24773660126783e-02 +-3.93939393939394e+00 -2.25827092845188e-01 1.24332806711584e-02 -3.91885815676604e-02 +-3.33333333333333e+00 -1.54050456378233e-01 1.19149897769548e-02 -4.56999911417254e-02 +-2.72727272727273e+00 -8.12318984160244e-02 1.13706359706548e-02 -5.16384940099625e-02 +-2.12121212121212e+00 -7.14979346296234e-03 1.07859435280497e-02 -5.70801147069148e-02 +-1.51515151515152e+00 6.87826749054011e-02 1.05033451229781e-02 -6.20466375298444e-02 +-9.09090909090912e-01 1.45369872154627e-01 1.03139004235661e-02 -6.68516603553039e-02 +-3.03030303030302e-01 2.23028758160340e-01 1.02094317053058e-02 -7.16176330178895e-02 + 3.03030303030302e-01 3.01237277028695e-01 1.01564455703337e-02 -7.60536458286783e-02 + 9.09090909090912e-01 3.80006385780218e-01 1.01544863426098e-02 -8.01685273418174e-02 + 1.51515151515152e+00 4.59246642973497e-01 1.03195069670379e-02 -8.42292432054636e-02 + 2.12121212121212e+00 5.38436193741909e-01 1.05158173919170e-02 -8.80305585640893e-02 + 2.72727272727273e+00 6.17086435268518e-01 1.07234607719624e-02 -9.09221588982618e-02 + 3.33333333333333e+00 6.94766649922142e-01 1.09892374201398e-02 -9.34851438113357e-02 + 3.93939393939394e+00 7.71665263445708e-01 1.12674755215391e-02 -9.57801882660128e-02 + 4.54545454545455e+00 8.46424118402375e-01 1.16353662750350e-02 -9.80494154414620e-02 + 5.15151515151515e+00 9.20198652009909e-01 1.20213692284540e-02 -1.00166544091476e-01 + 5.75757575757576e+00 9.91711074228843e-01 1.24325530524450e-02 -1.01849307770008e-01 + 6.36363636363637e+00 1.06002251469050e+00 1.29373530659327e-02 -1.03182589271796e-01 + 6.96969696969697e+00 1.12620049862159e+00 1.35051858034989e-02 -1.04281097204592e-01 + 7.57575757575757e+00 1.18623076703795e+00 1.42446030038888e-02 -1.05323489221343e-01 + 8.18181818181818e+00 1.24304860221996e+00 1.50702587438949e-02 -1.06330821016929e-01 + 8.78787878787879e+00 1.29339454484370e+00 1.60680959350975e-02 -1.07320656167730e-01 + 9.39393939393939e+00 1.33640612125946e+00 1.81467491655883e-02 -1.08107944391156e-01 + 1.00000000000000e+01 1.37469506451432e+00 2.09438769808961e-02 -1.08769953707875e-01 + 1.06060606060606e+01 1.39128542708790e+00 2.53973640660572e-02 -1.08704427997839e-01 + 1.12121212121212e+01 1.39247645190556e+00 3.08345002992362e-02 -1.08511132324392e-01 + 1.18181818181818e+01 1.36506866603177e+00 3.75119498467862e-02 -1.07969033181396e-01 + 1.24242424242424e+01 1.33988550587683e+00 4.76821530474488e-02 -1.09070781012852e-01 + 1.30303030303030e+01 1.28517385394240e+00 5.94392540313143e-02 -1.10747213245403e-01 + 1.36363636363636e+01 1.25643020037597e+00 7.18386529645335e-02 -1.10309370469218e-01 + 1.42424242424242e+01 1.22941101634947e+00 8.49147013682724e-02 -1.10076808850556e-01 + 1.48484848484848e+01 1.20587360276360e+00 9.89301897374668e-02 -1.10132396182924e-01 + 1.54545454545455e+01 1.18936767768177e+00 1.13924838258266e-01 -1.13810701314704e-01 + 1.60606060606061e+01 1.17565898671524e+00 1.29176297116898e-01 -1.19071521356745e-01 + 1.66666666666667e+01 1.16603643374085e+00 1.43801932752626e-01 -1.26420182833845e-01 + 1.72727272727273e+01 1.15901294982273e+00 1.58412873301332e-01 -1.33298298163097e-01 + 1.78787878787879e+01 1.15516613881923e+00 1.73005853001785e-01 -1.39601295567204e-01 + 1.84848484848485e+01 1.16035329239803e+00 1.87605989072833e-01 -1.43318174504004e-01 + 1.90909090909091e+01 1.16482121671689e+00 2.01471765042406e-01 -1.46723090792030e-01 + 1.96969696969697e+01 1.15241186617039e+00 2.11164662608912e-01 -1.52023933649729e-01 + 2.03030303030303e+01 1.14108152143087e+00 2.21109741610071e-01 -1.56986307485845e-01 + 2.09090909090909e+01 1.13083024354155e+00 2.31307016312692e-01 -1.61635219687799e-01 + 2.15151515151515e+01 1.12057896565223e+00 2.41504291015314e-01 -1.66292754579922e-01 + 2.21212121212121e+01 1.11061305902249e+00 2.51832144540440e-01 -1.70802437318188e-01 + 2.27272727272727e+01 1.10178834380504e+00 2.62682178999596e-01 -1.74726995984381e-01 + 2.33333333333333e+01 1.09296362858759e+00 2.73532213458751e-01 -1.78657586333139e-01 + 2.39393939393939e+01 1.08413891337014e+00 2.84382247917907e-01 -1.82623234550793e-01 + 2.45454545454545e+01 1.07704877435898e+00 2.95863171170336e-01 -1.86155882534370e-01 + 2.51515151515151e+01 1.07015136189154e+00 3.07414191669665e-01 -1.89640420415756e-01 + 2.57575757575758e+01 1.06325394942410e+00 3.18965212168995e-01 -1.93124958297141e-01 + 2.63636363636364e+01 1.05714092098968e+00 3.30902828470674e-01 -1.96422469773296e-01 + 2.69696969696970e+01 1.05155089650575e+00 3.43098215358386e-01 -1.99595277603454e-01 + 2.75757575757576e+01 1.04596087202182e+00 3.55293602246098e-01 -2.02768085433612e-01 + 2.81818181818182e+01 1.04062530585900e+00 3.67663996814596e-01 -2.05879229073642e-01 + 2.87878787878788e+01 1.03588342484769e+00 3.80442707609625e-01 -2.08846501945758e-01 + 2.93939393939394e+01 1.03114154383638e+00 3.93221418404654e-01 -2.11813774817874e-01 + 3.00000000000000e+01 1.02639966282507e+00 4.06000129199683e-01 -2.14781047689990e-01 + 3.30000000000000e+01 1.00573804168069e+00 4.72583293422338e-01 -2.28629026765098e-01 + 3.60000000000000e+01 9.85833707743003e-01 5.41941245231535e-01 -2.41944387146083e-01 + 3.90000000000000e+01 9.64635684439964e-01 6.13911269891018e-01 -2.55359517097689e-01 + 4.20000000000000e+01 9.39853820984217e-01 6.87471272303016e-01 -2.68402760096020e-01 + 4.50000000000000e+01 9.13773877837909e-01 7.61422951679187e-01 -2.81321973111748e-01 + 4.80000000000000e+01 8.80499938641377e-01 8.35214742285566e-01 -2.93829895857158e-01 + 5.10000000000000e+01 8.43049140618493e-01 9.07414892614859e-01 -3.06092438249886e-01 + 5.40000000000000e+01 7.97244356422135e-01 9.76431660067036e-01 -3.17878305263492e-01 + 5.70000000000000e+01 7.51439922147286e-01 1.04544790027186e+00 -3.29653788801724e-01 + 6.00000000000000e+01 7.05635662831859e-01 1.11446387685501e+00 -3.41419875328892e-01 + 6.30000000000000e+01 6.43935405201049e-01 1.17011397781587e+00 -3.51824168446815e-01 + 6.60000000000000e+01 5.82235011316305e-01 1.22576396420997e+00 -3.62218653318893e-01 + 6.90000000000000e+01 5.20534617431561e-01 1.28141395060407e+00 -3.72603978485147e-01 + 7.20000000000000e+01 4.51293480954431e-01 1.32353369994026e+00 -3.81654848148536e-01 + 7.50000000000000e+01 3.78282127550152e-01 1.35888860772946e+00 -3.90032025372884e-01 + 7.80000000000000e+01 3.05269896475863e-01 1.39424392065773e+00 -3.98398550132911e-01 + 8.10000000000000e+01 2.30935739780878e-01 1.42133853168932e+00 -4.05862264958857e-01 + 8.40000000000000e+01 1.53957823095881e-01 1.43191230914291e+00 -4.11528875629133e-01 + 8.70000000000000e+01 7.69789183415259e-02 1.44248616737432e+00 -4.17182529414559e-01 + 9.00000000000000e+01 -3.36313787592115e-07 1.45305993400564e+00 -4.22823883213375e-01 + 9.30000000000000e+01 -5.38853538885643e-02 1.44248615655205e+00 -4.25531830444160e-01 + 9.60000000000000e+01 -1.07770377288908e-01 1.43191233870989e+00 -4.28239883474790e-01 + 9.90000000000000e+01 -1.61655412340595e-01 1.42133844008909e+00 -4.30948043344561e-01 + 1.02000000000000e+02 -2.13689029593013e-01 1.39424374942488e+00 -4.30426032722678e-01 + 1.05000000000000e+02 -2.64796957994024e-01 1.35888884163568e+00 -4.28288858720630e-01 + 1.08000000000000e+02 -3.15905431030774e-01 1.32353352870914e+00 -4.26150923676660e-01 + 1.11000000000000e+02 -3.64374322762835e-01 1.28141346851316e+00 -4.22781294573843e-01 + 1.14000000000000e+02 -4.07564132273452e-01 1.22576411981700e+00 -4.16948201170771e-01 + 1.17000000000000e+02 -4.50754244383126e-01 1.17011434599327e+00 -4.11114214652485e-01 + 1.20000000000000e+02 -4.93944486037582e-01 1.11446433346109e+00 -4.05279567496773e-01 + 1.23000000000000e+02 -5.26007827556164e-01 1.04544835687794e+00 -3.97635867656992e-01 + 1.26000000000000e+02 -5.58071091549210e-01 9.76432116678355e-01 -3.89990992242211e-01 + 1.29000000000000e+02 -5.90134200485389e-01 9.07415349226176e-01 -3.82344714919725e-01 + 1.32000000000000e+02 -6.14671501318397e-01 8.35161838486048e-01 -3.75290062239593e-01 + 1.35000000000000e+02 -6.35445907015363e-01 7.61289959942459e-01 -3.68529899569896e-01 + 1.38000000000000e+02 -6.56219474668182e-01 6.87418368921679e-01 -3.61767875968571e-01 + 1.41000000000000e+02 -6.74909652901486e-01 6.14953590391588e-01 -3.56786256817077e-01 + 1.44000000000000e+02 -6.89433035390160e-01 5.45302448258410e-01 -3.55365699643800e-01 + 1.47000000000000e+02 -7.03955906925430e-01 4.75651465566945e-01 -3.53940753692651e-01 + 1.50000000000000e+02 -7.18478522993120e-01 4.06000562593488e-01 -3.52511578047886e-01 + 1.53000000000000e+02 -7.42629245947763e-01 3.49402521602820e-01 -3.67942713897313e-01 + 1.56000000000000e+02 -7.66779899087500e-01 2.92804540889390e-01 -3.83374818114856e-01 + 1.59000000000000e+02 -7.91051572510474e-01 2.36206619897226e-01 -3.98807852435555e-01 + 1.62000000000000e+02 -7.19307409708115e-01 1.95606690636341e-01 -4.23162217489700e-01 + 1.65000000000000e+02 -5.99422550148399e-01 1.63005892539676e-01 -4.51976932817733e-01 + 1.68000000000000e+02 -4.72905933087606e-01 1.30404868023183e-01 -4.80790683446680e-01 + 1.71000000000000e+02 -3.52738917050312e-01 9.78037326537191e-02 -4.50000513056908e-01 + 1.74000000000000e+02 -2.35159145800089e-01 6.52023755731394e-02 -2.99999717902353e-01 + 1.77000000000000e+02 -1.16216409329782e-01 5.38259028959444e-02 -1.48221036446267e-01 + 1.80000000000000e+02 0.00000000000000e+00 5.30837886627506e-02 0.00000000000000e+00 diff --git a/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_11.dat b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_11.dat new file mode 100644 index 00000000..742ec4f5 --- /dev/null +++ b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_11.dat @@ -0,0 +1,254 @@ +! ------------ AirfoilInfo v1.01.x Input File ---------------------------------- +! AeroElasticSE FAST driver +! line +! line +! ------------------------------------------------------------------------------ +DEFAULT InterpOrd ! Interpolation order to use for quasi-steady table lookup {1=linear; 3=cubic spline; "default"} [default=3] +1 NonDimArea ! The non-dimensional area of the airfoil (area/chord^2) (set to 1.0 if unsure or unneeded) +@"NREL-2p8-127_AF11_Coords.txt" NumCoords ! The number of coordinates in the airfoil shape file. Set to zero if coordinates not included. +AF11_BL.txt BL_file ! The file name including the boundary layer characteristics of the profile. Ignored if the aeroacoustic module is not called. +1 NumTabs ! Number of airfoil tables in this file. Each table must have lines for Re and Ctrl. +! ------------------------------------------------------------------------------ +! data for table 1 +! ------------------------------------------------------------------------------ +6.000000 Re ! Reynolds number in millions +0 Ctrl ! Control setting (must be 0 for current AirfoilInfo) +True InclUAdata ! Is unsteady aerodynamics data included in this table? If TRUE, then include 30 UA coefficients below this line +!........................................ +-2.081115 alpha0 ! 0-lift angle of attack, depends on airfoil. +11.269045 alpha1 ! Angle of attack at f=0.7, (approximately the stall angle) for AOA>alpha0. (deg) +-8.662155 alpha2 ! Angle of attack at f=0.7, (approximately the stall angle) for AOA1] +0.000000 S2 ! Constant in the f curve best-fit for AOA> alpha1; by definition it depends on the airfoil. [ignored if UAMod<>1] +0.000000 S3 ! Constant in the f curve best-fit for alpha2<=AOA< alpha0; by definition it depends on the airfoil. [ignored if UAMod<>1] +0.000000 S4 ! Constant in the f curve best-fit for AOA< alpha2; by definition it depends on the airfoil. [ignored if UAMod<>1] +1.400649 Cn1 ! Critical value of C0n at leading edge separation. It should be extracted from airfoil data at a given Mach and Reynolds number. It can be calculated from the static value of Cn at either the break in the pitching moment or the loss of chord force at the onset of stall. It is close to the condition of maximum lift of the airfoil at low Mach numbers. +-0.915233 Cn2 ! As Cn1 for negative AOAs. +Default St_sh ! Strouhal's shedding frequency constant. [default = 0.19] +0.010727 Cd0 ! 2D drag coefficient value at 0-lift. +-0.065156 Cm0 ! 2D pitching moment coefficient about 1/4-chord location, at 0-lift, positive if nose up. [If the aerodynamics coefficients table does not include a column for Cm, this needs to be set to 0.0] +0.000000 k0 ! Constant in the \hat(x)_cp curve best-fit; = (\hat(x)_AC-0.25). [ignored if UAMod<>1] +0.000000 k1 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k2 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k3 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k1_hat ! Constant in the expression of Cc due to leading edge vortex effects. [ignored if UAMod<>1] +Default x_cp_bar ! Constant in the expression of \hat(x)_cp^v. [ignored if UAMod<>1, default = 0.2] +Default UACutout ! Angle of attack above which unsteady aerodynamics are disabled (deg). [Specifying the string "Default" sets UACutout to 45 degrees] +Default filtCutOff ! Cut-off frequency (-3 dB corner frequency) for low-pass filtering the AoA input to UA, as well as the 1st and 2nd derivatives (Hz) [default = 20] +!........................................ +! Table of aerodynamics coefficients +200 NumAlf ! Number of data lines in the following table +! Alpha Cl Cd Cm +! (deg) (-) (-) (-) +-1.80000000000000e+02 0.00000000000000e+00 5.17338093025581e-02 0.00000000000000e+00 +-1.77000000000000e+02 1.20610218452195e-01 5.17338093025581e-02 1.18763338610947e-01 +-1.74000000000000e+02 2.43846180796722e-01 6.20803661366883e-02 2.39999774321882e-01 +-1.71000000000000e+02 3.65769725958049e-01 9.31203763075915e-02 3.60000410445527e-01 +-1.68000000000000e+02 4.84069232089561e-01 1.24885380987671e-01 3.21035049116140e-01 +-1.65000000000000e+02 6.01637542467089e-01 1.57012874460584e-01 2.02588544427697e-01 +-1.62000000000000e+02 7.13153594297870e-01 1.89140896133777e-01 8.41409821795466e-02 +-1.59000000000000e+02 7.80068980000668e-01 2.29356923814875e-01 7.97341748695581e-03 +-1.56000000000000e+02 7.58681265140819e-01 2.85748689900454e-01 1.75916291927228e-02 +-1.53000000000000e+02 7.37716006162308e-01 3.42140486787254e-01 2.79764209288751e-02 +-1.50000000000000e+02 7.16750629236893e-01 3.98532330574024e-01 3.87597184159220e-02 +-1.47000000000000e+02 7.02430836152056e-01 4.68441880461646e-01 5.28948486721724e-02 +-1.44000000000000e+02 6.88110788374351e-01 5.38351550730586e-01 6.70401805724200e-02 +-1.41000000000000e+02 6.73790231192722e-01 6.08261461770758e-01 8.11976416970075e-02 +-1.38000000000000e+02 6.55253757939153e-01 6.81025000549314e-01 9.58313303466701e-02 +-1.35000000000000e+02 6.34609335202059e-01 7.55215347408169e-01 1.10704411230940e-01 +-1.32000000000000e+02 6.13964075900703e-01 8.29406104470313e-01 1.25585263221553e-01 +-1.29000000000000e+02 5.89541757042321e-01 9.01995435488593e-01 1.40592248603482e-01 +-1.26000000000000e+02 5.57565301171594e-01 9.71381906816171e-01 1.55841088781127e-01 +-1.23000000000000e+02 5.25588689582014e-01 1.04076784806681e+00 1.71097114222845e-01 +-1.20000000000000e+02 4.93612000135919e-01 1.11015352428889e+00 1.86361656418168e-01 +-1.17000000000000e+02 4.50478535342387e-01 1.16621180599633e+00 2.00629220653074e-01 +-1.14000000000000e+02 4.07345160141662e-01 1.22226984751125e+00 2.14906094089605e-01 +-1.11000000000000e+02 3.64212007755362e-01 1.27832746077970e+00 2.29193883251082e-01 +-1.08000000000000e+02 3.15783665079539e-01 1.32087403967776e+00 2.41716558401183e-01 +-1.05000000000000e+02 2.64707686941683e-01 1.35666499851025e+00 2.53364833576556e-01 +-1.02000000000000e+02 2.13632134040282e-01 1.39245554721333e+00 2.65031201575310e-01 +-9.90000000000000e+01 1.61623631750871e-01 1.41999044316543e+00 2.75316312995168e-01 +-9.60000000000000e+01 1.07749190274494e-01 1.43101367601985e+00 2.82819378442760e-01 +-9.30000000000000e+01 5.38747603685306e-02 1.44203682466298e+00 2.90359307559513e-01 +-9.00000000000000e+01 3.36247670192969e-07 1.45305993120123e+00 2.97951186065388e-01 +-8.70000000000000e+01 -5.38747052280345e-02 1.44203683594514e+00 3.01753424548436e-01 +-8.40000000000000e+01 -1.07749340919434e-01 1.43101364519643e+00 3.05884772088962e-01 +-8.10000000000000e+01 -1.61623165043989e-01 1.41999053865818e+00 3.10613470732064e-01 +-7.80000000000000e+01 -2.13631886668320e-01 1.39245572055610e+00 3.10674655777832e-01 +-7.50000000000000e+01 -2.64708024854679e-01 1.35666476172186e+00 3.08542976324719e-01 +-7.20000000000000e+01 -3.15783417710861e-01 1.32087421301878e+00 3.06409302975954e-01 +-6.90000000000000e+01 -3.64211634092392e-01 1.27832794640741e+00 3.03044729448568e-01 +-6.60000000000000e+01 -4.07345280750829e-01 1.22226969076263e+00 2.97219713108405e-01 +-6.30000000000000e+01 -4.50478820711274e-01 1.16621143511785e+00 2.91391620398543e-01 +-6.00000000000000e+01 -4.93612211692021e-01 1.11015306523689e+00 2.85560191488404e-01 +-5.70000000000000e+01 -5.25588901138117e-01 1.04076738901481e+00 2.77925669828566e-01 +-5.40000000000000e+01 -5.57565512726151e-01 9.71381447758911e-01 2.70286195661910e-01 +-5.10000000000000e+01 -5.89541968596878e-01 9.01994976431333e-01 2.62640680641497e-01 +-4.80000000000000e+01 -6.15651105875399e-01 8.29449803698678e-01 2.55153878770895e-01 +-4.50000000000000e+01 -6.38826678153933e-01 7.55325331028288e-01 2.47739559108878e-01 +-4.20000000000000e+01 -6.56940774711891e-01 6.81068699431397e-01 2.41608950158798e-01 +-3.90000000000000e+01 -6.74138230588866e-01 6.07210570957826e-01 2.36033756265024e-01 +-3.60000000000000e+01 -6.88800358432074e-01 5.34964795566947e-01 2.32526368115935e-01 +-3.30000000000000e+01 -7.02527481598747e-01 4.65352126226771e-01 2.31660096996564e-01 +-3.00000000000000e+01 -7.16750731841146e-01 3.98531895640176e-01 2.33717011176468e-01 +-2.93939393939394e+01 -7.20014368241707e-01 3.85709000620782e-01 2.34916176725143e-01 +-2.87878787878788e+01 -7.23278004642269e-01 3.72886105601387e-01 2.36115342273819e-01 +-2.81818181818182e+01 -7.26541641042830e-01 3.60063210581993e-01 2.37314507822494e-01 +-2.75757575757576e+01 -7.30215084645349e-01 3.47650566598554e-01 2.39067661935682e-01 +-2.69696969696970e+01 -7.34064174972939e-01 3.35413759571076e-01 2.41058260087479e-01 +-2.63636363636364e+01 -7.37913265300529e-01 3.23176952543597e-01 2.43048858239275e-01 +-2.57575757575758e+01 -7.42124844608794e-01 3.11199070884588e-01 2.45450980247116e-01 +-2.51515151515151e+01 -7.46880072905424e-01 2.99609516932444e-01 2.48470292128175e-01 +-2.45454545454545e+01 -7.51635301202054e-01 2.88019962980301e-01 2.51489604009234e-01 +-2.39393939393939e+01 -7.56524250108274e-01 2.76500794819509e-01 2.54645697570981e-01 +-2.33333333333333e+01 -7.62616710389763e-01 2.65615112407906e-01 2.59032852740507e-01 +-2.27272727272727e+01 -7.68709170671251e-01 2.54729429996303e-01 2.63911099891641e-01 +-2.21212121212121e+01 -7.74801630952739e-01 2.43843747584701e-01 2.68391913865235e-01 +-2.15151515151515e+01 -7.93896255075763e-01 2.34765567487007e-01 2.69219982182975e-01 +-2.09090909090909e+01 -8.19588776751072e-01 2.26139379234369e-01 2.68013679183985e-01 +-2.03030303030303e+01 -8.41755850773015e-01 2.17513190981731e-01 2.66455457580854e-01 +-1.96969696969697e+01 -8.57132969513166e-01 2.09138320990721e-01 2.57323288186467e-01 +-1.90909090909091e+01 -8.65913538616401e-01 2.01014755044168e-01 2.40703240782996e-01 +-1.84848484848485e+01 -8.74215029540216e-01 1.93152415327005e-01 2.24051125011634e-01 +-1.78787878787879e+01 -8.82246941494251e-01 1.85271935431753e-01 2.07713877216966e-01 +-1.72727272727273e+01 -8.90112513417619e-01 1.76753055824415e-01 1.91533915208804e-01 +-1.66666666666667e+01 -8.97867665288278e-01 1.69666716562767e-01 1.75354108708192e-01 +-1.60606060606061e+01 -9.05545956258092e-01 1.62769575158031e-01 1.59174429439710e-01 +-1.54545454545455e+01 -9.05500228357417e-01 1.54709519958352e-01 1.44263287105186e-01 +-1.48484848484848e+01 -9.00650490354814e-01 1.45972869299812e-01 1.30048437843628e-01 +-1.42424242424242e+01 -8.83881928212747e-01 1.35695161200991e-01 1.18061058367204e-01 +-1.36363636363636e+01 -8.65135255067798e-01 1.25196579166224e-01 1.06372832901923e-01 +-1.30303030303030e+01 -8.44949235869776e-01 1.14536353092698e-01 9.41922629526705e-02 +-1.24242424242424e+01 -8.23438097507769e-01 1.04071539255474e-01 8.07476005612591e-02 +-1.18181818181818e+01 -8.01578346336287e-01 9.39351009261381e-02 6.72989309058954e-02 +-1.12121212121212e+01 -7.79436133521223e-01 8.45784112226453e-02 5.39664027575017e-02 +-1.06060606060606e+01 -7.56125420814654e-01 7.56686775243057e-02 4.13015037835521e-02 +-1.00000000000000e+01 -7.31404178229205e-01 6.69542054267392e-02 2.90154450614047e-02 +-9.39393939393939e+00 -7.10908164656284e-01 5.62659422161747e-02 1.61336287291465e-02 +-8.78787878787879e+00 -6.93895499794178e-01 4.51632034246090e-02 3.66630892977488e-03 +-8.18181818181818e+00 -6.82305849045296e-01 3.46949966165822e-02 -8.06490144015382e-03 +-7.57575757575758e+00 -6.41809741158512e-01 2.77831234233813e-02 -1.41096615374045e-02 +-6.96969696969697e+00 -5.88143925838256e-01 2.28417438781606e-02 -1.78405462944423e-02 +-6.36363636363636e+00 -5.18595414594118e-01 1.94965813878357e-02 -2.29439868991729e-02 +-5.75757575757576e+00 -4.47723085873360e-01 1.68485236815072e-02 -2.81966573016451e-02 +-5.15151515151515e+00 -3.75142989396497e-01 1.49610810018752e-02 -3.47182225820690e-02 +-4.54545454545454e+00 -3.00787223897522e-01 1.34635952053030e-02 -4.14011501128667e-02 +-3.93939393939394e+00 -2.25750200730196e-01 1.21953572497309e-02 -4.79556483496797e-02 +-3.33333333333333e+00 -1.53097407752943e-01 1.17061671579090e-02 -5.41961908245246e-02 +-2.72727272727273e+00 -7.95718917516246e-02 1.12293922425528e-02 -5.97874291038278e-02 +-2.12121212121212e+00 -5.03539621814182e-03 1.07440480589344e-02 -6.48477030716386e-02 +-1.51515151515152e+00 7.10741171824617e-02 1.04901796827387e-02 -6.95072912947862e-02 +-9.09090909090912e-01 1.47800523968434e-01 1.03183543231236e-02 -7.40089097305715e-02 +-3.03030303030302e-01 2.25712116064930e-01 1.02530762212861e-02 -7.84452609734865e-02 + 3.03030303030302e-01 3.04012747719234e-01 1.02309881009218e-02 -8.25691600591865e-02 + 9.09090909090912e-01 3.82711307380014e-01 1.02503405435553e-02 -8.63962105538320e-02 + 1.51515151515152e+00 4.61756851424667e-01 1.03813057971860e-02 -9.01104450324160e-02 + 2.12121212121212e+00 5.40685036400329e-01 1.05415949817604e-02 -9.35850435449342e-02 + 2.72727272727273e+00 6.18886227271413e-01 1.07445792627915e-02 -9.62817005798321e-02 + 3.33333333333333e+00 6.96227792951118e-01 1.09887579176491e-02 -9.86711658811812e-02 + 3.93939393939394e+00 7.72883389885004e-01 1.12344879960209e-02 -1.00807961075492e-01 + 4.54545454545455e+00 8.47551890939517e-01 1.15551058195410e-02 -1.02885524901180e-01 + 5.15151515151515e+00 9.21271553826334e-01 1.18923634479442e-02 -1.04819428291073e-01 + 5.75757575757576e+00 9.92784335144794e-01 1.22610882531594e-02 -1.06359973327630e-01 + 6.36363636363637e+00 1.06131473281146e+00 1.27079774642478e-02 -1.07580975239224e-01 + 6.96969696969697e+00 1.12787422242318e+00 1.32063108971969e-02 -1.08587510060800e-01 + 7.57575757575757e+00 1.18885675085141e+00 1.38302419296642e-02 -1.09502885178324e-01 + 8.18181818181818e+00 1.24720837846946e+00 1.45051079826196e-02 -1.10383577044148e-01 + 8.78787878787879e+00 1.30109155320978e+00 1.52650096833159e-02 -1.11295079946526e-01 + 9.39393939393939e+00 1.34910270552171e+00 1.69597298070715e-02 -1.11617299458299e-01 + 1.00000000000000e+01 1.39122211758901e+00 1.92951287014474e-02 -1.11579588588804e-01 + 1.06060606060606e+01 1.41374692668675e+00 2.32087315726581e-02 -1.10700973175584e-01 + 1.12121212121212e+01 1.42235063763216e+00 2.80043073060677e-02 -1.09633362298298e-01 + 1.18181818181818e+01 1.40509952208549e+00 3.36675325297581e-02 -1.08071370626820e-01 + 1.24242424242424e+01 1.36098461886640e+00 4.53311237959958e-02 -1.09677679611616e-01 + 1.30303030303030e+01 1.27121985294027e+00 5.94850170456720e-02 -1.12451230995673e-01 + 1.36363636363636e+01 1.23331688079203e+00 7.12491888525373e-02 -1.11569128322250e-01 + 1.42424242424242e+01 1.19929983782480e+00 8.34701602960147e-02 -1.10866527861742e-01 + 1.48484848484848e+01 1.17429197921907e+00 9.63163863742802e-02 -1.10364535193828e-01 + 1.54545454545455e+01 1.15693155875190e+00 1.09918192046590e-01 -1.12997477778780e-01 + 1.60606060606061e+01 1.14266018641121e+00 1.23724487625457e-01 -1.16993403213071e-01 + 1.66666666666667e+01 1.13325405216419e+00 1.37104753717798e-01 -1.22803327538571e-01 + 1.72727272727273e+01 1.12686629586509e+00 1.50546395471717e-01 -1.28360097087402e-01 + 1.78787878787879e+01 1.12416770644291e+00 1.64063052701384e-01 -1.33607452032450e-01 + 1.84848484848485e+01 1.13139272733087e+00 1.78010604421774e-01 -1.37206719425119e-01 + 1.90909090909091e+01 1.13867731668370e+00 1.91501101195136e-01 -1.40692310188144e-01 + 1.96969696969697e+01 1.13223871836009e+00 2.01790232355546e-01 -1.45868712277606e-01 + 2.03030303030303e+01 1.12592570808589e+00 2.12197188791206e-01 -1.50881669040385e-01 + 2.09090909090909e+01 1.11973829296607e+00 2.22721977167913e-01 -1.55819852215318e-01 + 2.15151515151515e+01 1.11355087784625e+00 2.33246765544621e-01 -1.60788589705368e-01 + 2.21212121212121e+01 1.10686018543461e+00 2.43843747584701e-01 -1.65603019715883e-01 + 2.27272727272727e+01 1.09815690169093e+00 2.54729429996303e-01 -1.69822108656288e-01 + 2.33333333333333e+01 1.08945361794725e+00 2.65615112407906e-01 -1.74062570732705e-01 + 2.39393939393939e+01 1.08075033420357e+00 2.76500794819509e-01 -1.78427259605238e-01 + 2.45454545454545e+01 1.07376593672417e+00 2.88019962980301e-01 -1.82284015244859e-01 + 2.51515151515151e+01 1.06697252249912e+00 2.99609516932444e-01 -1.86084335072627e-01 + 2.57575757575758e+01 1.06017910827406e+00 3.11199070884588e-01 -1.89884654900395e-01 + 2.63636363636364e+01 1.05416214500944e+00 3.23176952543597e-01 -1.93462066542360e-01 + 2.69696969696970e+01 1.04866289615838e+00 3.35413759571076e-01 -1.96890849633946e-01 + 2.75757575757576e+01 1.04316364730731e+00 3.47650566598554e-01 -2.00319632725532e-01 + 2.81818181818182e+01 1.03791578996892e+00 3.60063210581993e-01 -2.03673565505490e-01 + 2.87878787878788e+01 1.03325446250951e+00 3.72886105601387e-01 -2.06852862539969e-01 + 2.93939393939394e+01 1.02859313505011e+00 3.85709000620782e-01 -2.10032159574448e-01 + 3.00000000000000e+01 1.02393180759070e+00 3.98531895640176e-01 -2.13211456608927e-01 + 3.30000000000000e+01 1.00360981651186e+00 4.65352126226771e-01 -2.27906428002545e-01 + 3.60000000000000e+01 9.84001264428555e-01 5.34964795566947e-01 -2.41925534967727e-01 + 3.90000000000000e+01 9.63054591373508e-01 6.07210570957826e-01 -2.55861101384382e-01 + 4.20000000000000e+01 9.38486939161695e-01 6.81068699431397e-01 -2.69396898615722e-01 + 4.50000000000000e+01 9.12610178291857e-01 7.55325331028288e-01 -2.82806077238433e-01 + 4.80000000000000e+01 8.79501806448111e-01 8.29449803698678e-01 -2.95759616602379e-01 + 5.10000000000000e+01 8.42202650323331e-01 9.01994976431333e-01 -3.08464526695633e-01 + 5.40000000000000e+01 7.96521656220475e-01 9.71381447758911e-01 -3.20679850937119e-01 + 5.70000000000000e+01 7.50841011093444e-01 1.04076738901481e+00 -3.32886639691835e-01 + 6.00000000000000e+01 7.05160540452998e-01 1.11015306523690e+00 -3.45085056710935e-01 + 6.30000000000000e+01 6.43541341893905e-01 1.16621143511785e+00 -3.55934491344085e-01 + 6.60000000000000e+01 5.81922006714618e-01 1.22226969076263e+00 -3.66774194260320e-01 + 6.90000000000000e+01 5.20302671535330e-01 1.27832794640741e+00 -3.77604487698421e-01 + 7.20000000000000e+01 4.51119501480277e-01 1.32087421301878e+00 -3.87119214978594e-01 + 7.50000000000000e+01 3.78154568829116e-01 1.35666476172186e+00 -3.95968866317771e-01 + 7.80000000000000e+01 3.05188640011092e-01 1.39245572055610e+00 -4.04806568926510e-01 + 8.10000000000000e+01 2.30890390081552e-01 1.41999053865818e+00 -4.12748066743701e-01 + 8.40000000000000e+01 1.53927589898212e-01 1.43101364519643e+00 -4.18906566709380e-01 + 8.70000000000000e+01 7.69638017609944e-02 1.44203683594514e+00 -4.25049810698846e-01 + 9.00000000000000e+01 -3.36247670426886e-07 1.45305993120123e+00 -4.31178399042578e-01 + 9.30000000000000e+01 -5.38747603685306e-02 1.44203682466298e+00 -4.34104668279932e-01 + 9.60000000000000e+01 -1.07749190274494e-01 1.43101367601985e+00 -4.37031487108267e-01 + 9.90000000000000e+01 -1.61623631750871e-01 1.41999044316543e+00 -4.39958819257674e-01 + 1.02000000000000e+02 -2.13632134040282e-01 1.39245554721333e+00 -4.39636233003905e-01 + 1.05000000000000e+02 -2.64707686941683e-01 1.35666499851025e+00 -4.37688769297266e-01 + 1.08000000000000e+02 -3.15783665079539e-01 1.32087403967776e+00 -4.35740818710456e-01 + 1.11000000000000e+02 -3.64212007755363e-01 1.27832746077970e+00 -4.32550227083959e-01 + 1.14000000000000e+02 -4.07345160141662e-01 1.22226984751125e+00 -4.26873946888224e-01 + 1.17000000000000e+02 -4.50478535342387e-01 1.16621180599633e+00 -4.21196949202848e-01 + 1.20000000000000e+02 -4.93612000135919e-01 1.11015352428889e+00 -4.15519446213869e-01 + 1.23000000000000e+02 -5.25588689582014e-01 1.04076784806681e+00 -4.08013919223535e-01 + 1.26000000000000e+02 -5.57565301171594e-01 9.71381906816171e-01 -4.00507231110389e-01 + 1.29000000000000e+02 -5.89541757042322e-01 9.01995435488592e-01 -3.92999135332578e-01 + 1.32000000000000e+02 -6.13964075900704e-01 8.29406104470312e-01 -3.86098598415459e-01 + 1.35000000000000e+02 -6.34609335202059e-01 7.55215347408169e-01 -3.79500308090265e-01 + 1.38000000000000e+02 -6.55253757939153e-01 6.81025000549314e-01 -3.72899876934706e-01 + 1.41000000000000e+02 -6.73790231192722e-01 6.08261461770757e-01 -3.68126222376485e-01 + 1.44000000000000e+02 -6.88110788374351e-01 5.38351550730586e-01 -3.67006301532646e-01 + 1.47000000000000e+02 -7.02430836152056e-01 4.68441880461646e-01 -3.65881031661847e-01 + 1.50000000000000e+02 -7.16750629236893e-01 3.98532330574024e-01 -3.64750607711192e-01 + 1.53000000000000e+02 -7.34878858674711e-01 3.42608943418167e-01 -3.80350965963448e-01 + 1.56000000000000e+02 -7.53007027741238e-01 2.86685655813922e-01 -3.95955856199125e-01 + 1.59000000000000e+02 -7.71564544817183e-01 2.30762502127974e-01 -4.11565385415533e-01 + 1.62000000000000e+02 -7.00256219005735e-01 1.90909397104532e-01 -4.33416022361716e-01 + 1.65000000000000e+02 -5.83546590903823e-01 1.59091452320285e-01 -4.58385560746469e-01 + 1.68000000000000e+02 -4.58125712100344e-01 1.27273272145471e-01 -4.83354146585932e-01 + 1.71000000000000e+02 -3.41045278744180e-01 9.54550237835969e-02 -4.50000513056908e-01 + 1.74000000000000e+02 -2.27363439140247e-01 6.36366390444162e-02 -2.99999717902353e-01 + 1.77000000000000e+02 -1.12541609339478e-01 5.25040908476199e-02 -1.48454173263684e-01 + 1.80000000000000e+02 0.00000000000000e+00 5.17338093025581e-02 0.00000000000000e+00 diff --git a/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_12.dat b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_12.dat new file mode 100644 index 00000000..43ee56ca --- /dev/null +++ b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_12.dat @@ -0,0 +1,254 @@ +! ------------ AirfoilInfo v1.01.x Input File ---------------------------------- +! AeroElasticSE FAST driver +! line +! line +! ------------------------------------------------------------------------------ +DEFAULT InterpOrd ! Interpolation order to use for quasi-steady table lookup {1=linear; 3=cubic spline; "default"} [default=3] +1 NonDimArea ! The non-dimensional area of the airfoil (area/chord^2) (set to 1.0 if unsure or unneeded) +@"NREL-2p8-127_AF12_Coords.txt" NumCoords ! The number of coordinates in the airfoil shape file. Set to zero if coordinates not included. +AF12_BL.txt BL_file ! The file name including the boundary layer characteristics of the profile. Ignored if the aeroacoustic module is not called. +1 NumTabs ! Number of airfoil tables in this file. Each table must have lines for Re and Ctrl. +! ------------------------------------------------------------------------------ +! data for table 1 +! ------------------------------------------------------------------------------ +6.000000 Re ! Reynolds number in millions +0 Ctrl ! Control setting (must be 0 for current AirfoilInfo) +True InclUAdata ! Is unsteady aerodynamics data included in this table? If TRUE, then include 30 UA coefficients below this line +!........................................ +-2.104210 alpha0 ! 0-lift angle of attack, depends on airfoil. +11.449404 alpha1 ! Angle of attack at f=0.7, (approximately the stall angle) for AOA>alpha0. (deg) +-8.941354 alpha2 ! Angle of attack at f=0.7, (approximately the stall angle) for AOA1] +0.000000 S2 ! Constant in the f curve best-fit for AOA> alpha1; by definition it depends on the airfoil. [ignored if UAMod<>1] +0.000000 S3 ! Constant in the f curve best-fit for alpha2<=AOA< alpha0; by definition it depends on the airfoil. [ignored if UAMod<>1] +0.000000 S4 ! Constant in the f curve best-fit for AOA< alpha2; by definition it depends on the airfoil. [ignored if UAMod<>1] +1.433280 Cn1 ! Critical value of C0n at leading edge separation. It should be extracted from airfoil data at a given Mach and Reynolds number. It can be calculated from the static value of Cn at either the break in the pitching moment or the loss of chord force at the onset of stall. It is close to the condition of maximum lift of the airfoil at low Mach numbers. +-1.020492 Cn2 ! As Cn1 for negative AOAs. +Default St_sh ! Strouhal's shedding frequency constant. [default = 0.19] +0.010714 Cd0 ! 2D drag coefficient value at 0-lift. +-0.072028 Cm0 ! 2D pitching moment coefficient about 1/4-chord location, at 0-lift, positive if nose up. [If the aerodynamics coefficients table does not include a column for Cm, this needs to be set to 0.0] +0.000000 k0 ! Constant in the \hat(x)_cp curve best-fit; = (\hat(x)_AC-0.25). [ignored if UAMod<>1] +0.000000 k1 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k2 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k3 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k1_hat ! Constant in the expression of Cc due to leading edge vortex effects. [ignored if UAMod<>1] +Default x_cp_bar ! Constant in the expression of \hat(x)_cp^v. [ignored if UAMod<>1, default = 0.2] +Default UACutout ! Angle of attack above which unsteady aerodynamics are disabled (deg). [Specifying the string "Default" sets UACutout to 45 degrees] +Default filtCutOff ! Cut-off frequency (-3 dB corner frequency) for low-pass filtering the AoA input to UA, as well as the 1st and 2nd derivatives (Hz) [default = 20] +!........................................ +! Table of aerodynamics coefficients +200 NumAlf ! Number of data lines in the following table +! Alpha Cl Cd Cm +! (deg) (-) (-) (-) +-1.80000000000000e+02 0.00000000000000e+00 5.02017886725028e-02 0.00000000000000e+00 +-1.77000000000000e+02 1.16814702114733e-01 5.02017886725028e-02 1.18974998388536e-01 +-1.74000000000000e+02 2.35757260050863e-01 6.02419881354083e-02 2.39999774321882e-01 +-1.71000000000000e+02 3.53636476996742e-01 9.03629161351898e-02 3.60000410445527e-01 +-1.68000000000000e+02 4.69829759859863e-01 1.20986055059121e-01 3.19692038335689e-01 +-1.65000000000000e+02 5.86100406969184e-01 1.51860293583585e-01 1.99231033151485e-01 +-1.62000000000000e+02 6.97207018087719e-01 1.82735181026080e-01 7.87690618632042e-02 +-1.59000000000000e+02 7.65053274169454e-01 2.21992372815171e-01 4.59488938113571e-04 +-1.56000000000000e+02 7.47840212628704e-01 2.78013889729193e-01 8.23826475941633e-03 +-1.53000000000000e+02 7.31315050935883e-01 3.34035434615955e-01 1.69033914984109e-02 +-1.50000000000000e+02 7.14789733419415e-01 3.90057026535133e-01 2.57900977189505e-02 +-1.47000000000000e+02 7.00700113478808e-01 4.60260101212902e-01 4.02282514210461e-02 +-1.44000000000000e+02 6.86610239724511e-01 5.30463342418639e-01 5.46749993729137e-02 +-1.41000000000000e+02 6.72519858324716e-01 6.00666916692206e-01 6.91319722248670e-02 +-1.38000000000000e+02 6.54157816774948e-01 6.73769502775919e-01 8.40066813863651e-02 +-1.35000000000000e+02 6.33659953815723e-01 7.48321588883743e-01 9.90913902837609e-02 +-1.32000000000000e+02 6.13161255971681e-01 8.22874224418487e-01 1.14182857514007e-01 +-1.29000000000000e+02 5.88869424113624e-01 8.95844660221988e-01 1.29408668138862e-01 +-1.26000000000000e+02 5.56991306252975e-01 9.65650689048611e-01 1.44894245978222e-01 +-1.23000000000000e+02 5.25113031922222e-01 1.03545618459309e+00 1.60385940835181e-01 +-1.20000000000000e+02 4.93234679359342e-01 1.10526141350648e+00 1.75884859665492e-01 +-1.17000000000000e+02 4.50165647641462e-01 1.16178301844503e+00 1.90450025251094e-01 +-1.14000000000000e+02 4.07096660176995e-01 1.21830438150688e+00 2.05022854430753e-01 +-1.11000000000000e+02 3.64027804983567e-01 1.27482531278278e+00 2.19604660336798e-01 +-1.08000000000000e+02 3.15645479300682e-01 1.31785592534089e+00 2.32463316412531e-01 +-1.05000000000000e+02 2.64606377915867e-01 1.35414127581743e+00 2.44466971927803e-01 +-1.02000000000000e+02 2.13567566267535e-01 1.39042621049931e+00 2.56485516539190e-01 +-9.90000000000000e+01 1.61587565629768e-01 1.41846067229841e+00 2.67134366691667e-01 +-9.60000000000000e+01 1.07725146245282e-01 1.42999383096059e+00 2.75027548957952e-01 +-9.30000000000000e+01 5.38627383393683e-02 1.44152690151593e+00 2.82950978094881e-01 +-9.00000000000000e+01 3.36172637297600e-07 1.45305992801866e+00 2.90917363787953e-01 +-8.70000000000000e+01 -5.38626832111768e-02 1.44152691331999e+00 2.94767512788956e-01 +-8.40000000000000e+01 -1.07725296856606e-01 1.42999379871131e+00 2.98897742164918e-01 +-8.10000000000000e+01 -1.61587099027032e-01 1.41846077220858e+00 3.03536772948404e-01 +-7.80000000000000e+01 -2.13567319073521e-01 1.39042638623652e+00 3.03702648984174e-01 +-7.50000000000000e+01 -2.64606715585627e-01 1.35414103575821e+00 3.01751455652536e-01 +-7.20000000000000e+01 -3.15645232110603e-01 1.31785610107633e+00 2.99797410104482e-01 +-6.90000000000000e+01 -3.64027431877603e-01 1.27482580242423e+00 2.96601873383554e-01 +-6.60000000000000e+01 -4.07096780606374e-01 1.21830422346273e+00 2.90925626936627e-01 +-6.30000000000000e+01 -4.50165932584065e-01 1.16178264450123e+00 2.85244623169737e-01 +-6.00000000000000e+01 -4.93234890264853e-01 1.10526095167874e+00 2.79558323005520e-01 +-5.70000000000000e+01 -5.25113242827733e-01 1.03545572276536e+00 2.72051789581655e-01 +-5.40000000000000e+01 -5.56991517156933e-01 9.65650227215581e-01 2.64537349061016e-01 +-5.10000000000000e+01 -5.88869635017581e-01 8.95844198388958e-01 2.57013385477719e-01 +-4.80000000000000e+01 -6.14858281985569e-01 8.22907477862781e-01 2.49649988716779e-01 +-4.50000000000000e+01 -6.37902288159362e-01 7.48405461801475e-01 2.42355684979480e-01 +-4.20000000000000e+01 -6.55854829508633e-01 6.73802755955525e-01 2.36361332357867e-01 +-3.90000000000000e+01 -6.72882108422873e-01 5.99606299882174e-01 2.30958164591745e-01 +-3.60000000000000e+01 -6.87344655388143e-01 5.27047589477837e-01 2.27795230971316e-01 +-3.30000000000000e+01 -7.00836969047683e-01 4.57145854597990e-01 2.27367173402586e-01 +-3.00000000000000e+01 -7.14789834137016e-01 3.90056589853572e-01 2.29972174924480e-01 +-2.93939393939394e+01 -7.17989820447135e-01 3.77183552479970e-01 2.31313103482737e-01 +-2.87878787878788e+01 -7.21189806757255e-01 3.64310515106369e-01 2.32654032040993e-01 +-2.81818181818182e+01 -7.24389793067374e-01 3.51437477732768e-01 2.33994960599249e-01 +-2.75757575757576e+01 -7.27993615957789e-01 3.38976887108657e-01 2.35912898360177e-01 +-2.69696969696970e+01 -7.31770526515904e-01 3.26693074541322e-01 2.38078146993880e-01 +-2.63636363636364e+01 -7.35547437074019e-01 3.14409261973987e-01 2.40243395627583e-01 +-2.57575757575758e+01 -7.39682607350460e-01 3.02385685277020e-01 2.42838068946369e-01 +-2.51515151515151e+01 -7.44355083707426e-01 2.90752401734336e-01 2.46076779209917e-01 +-2.45454545454545e+01 -7.49027560064392e-01 2.79119118191653e-01 2.49315489473464e-01 +-2.39393939393939e+01 -7.53832399461519e-01 2.67556547894255e-01 2.52697168932637e-01 +-2.33333333333333e+01 -7.59828531846218e-01 2.56630410494836e-01 2.57365598831951e-01 +-2.27272727272727e+01 -7.65824664230917e-01 2.45704273095417e-01 2.62833561583836e-01 +-2.21212121212121e+01 -7.71820796615617e-01 2.34778135695999e-01 2.67654474711527e-01 +-2.15151515151515e+01 -7.96443477215383e-01 2.26676404363075e-01 2.64351420041365e-01 +-2.09090909090909e+01 -8.30849944454416e-01 2.19280956225120e-01 2.57191864213633e-01 +-2.03030303030303e+01 -8.61239798275855e-01 2.11885508087165e-01 2.49459359740882e-01 +-1.96969696969697e+01 -8.86851353917406e-01 2.04664215991167e-01 2.36345486505374e-01 +-1.90909090909091e+01 -9.07849523166766e-01 1.97617070085050e-01 2.17989979126022e-01 +-1.84848484848485e+01 -9.28438728259752e-01 1.90994947917113e-01 1.99581867965191e-01 +-1.78787878787879e+01 -9.48798009848073e-01 1.84343308202159e-01 1.81686497656418e-01 +-1.72727272727273e+01 -9.69015714430469e-01 1.76652563396641e-01 1.64047931232961e-01 +-1.66666666666667e+01 -9.89139234078135e-01 1.70406496274106e-01 1.46409370226095e-01 +-1.60606060606061e+01 -1.00919719372332e+00 1.64405524173896e-01 1.28770813650940e-01 +-1.54545454545455e+01 -1.01540755504446e+00 1.56862910031355e-01 1.13470810022679e-01 +-1.48484848484848e+01 -1.01298433891169e+00 1.48403778032376e-01 9.94548755135208e-02 +-1.42424242424242e+01 -9.89203767259323e-01 1.37794975860024e-01 8.94257900471029e-02 +-1.36363636363636e+01 -9.62014659606293e-01 1.26881241910317e-01 7.98089478777152e-02 +-1.30303030303030e+01 -9.32449292572719e-01 1.15751868266820e-01 6.93414419906876e-02 +-1.24242424242424e+01 -9.00792491049511e-01 1.04900663581092e-01 5.67713948672409e-02 +-1.18181818181818e+01 -8.68848659795491e-01 9.45041039998393e-02 4.42375285802314e-02 +-1.12121212121212e+01 -8.36808576348847e-01 8.51661045609216e-02 3.19958406592258e-02 +-1.06060606060606e+01 -8.03284211237670e-01 7.64433166380479e-02 2.09106002122012e-02 +-1.00000000000000e+01 -7.68096954585546e-01 6.80130732444816e-02 1.04779161942864e-02 +-9.39393939393939e+00 -7.39737601227035e-01 5.68394250941624e-02 -1.00892879318824e-03 +-8.78787878787879e+00 -7.17791627668883e-01 4.50577060106998e-02 -1.17953152141081e-02 +-8.18181818181818e+00 -7.04457618185764e-01 3.35556812007792e-02 -2.13372325268140e-02 +-7.57575757575758e+00 -6.63232806034972e-01 2.62982027978296e-02 -2.60669251138793e-02 +-6.96969696969697e+00 -6.08991380617151e-01 2.14176171488251e-02 -2.89228360247444e-02 +-6.36363636363636e+00 -5.33652028186316e-01 1.85402907866192e-02 -3.37736937247221e-02 +-5.75757575757576e+00 -4.57645786576647e-01 1.62204582639942e-02 -3.87352025598183e-02 +-5.15151515151515e+00 -3.80878183776993e-01 1.45075217386201e-02 -4.47429870829259e-02 +-4.54545454545454e+00 -3.03328576206396e-01 1.31751950655347e-02 -5.08206305818731e-02 +-3.93939393939394e+00 -2.25638938079791e-01 1.20463073814285e-02 -5.67577483907786e-02 +-3.33333333333333e+00 -1.51759128742261e-01 1.15765523813214e-02 -6.23461963393866e-02 +-2.72727272727273e+00 -7.72803618184935e-02 1.11443927588391e-02 -6.73647853995964e-02 +-2.12121212121212e+00 -2.14165309152243e-03 1.07204811423473e-02 -7.19089758691984e-02 +-1.51515151515152e+00 7.42011233954975e-02 1.04829792545349e-02 -7.61446613489007e-02 +-9.09090909090912e-01 1.51109201168349e-01 1.03234088196644e-02 -8.02509486552512e-02 +-3.03030303030302e-01 2.29344027261245e-01 1.03026060888101e-02 -8.42792874035115e-02 + 3.03030303030302e-01 3.07759215649705e-01 1.03155825014327e-02 -8.80359990719921e-02 + 9.09090909090912e-01 3.86363579252603e-01 1.03591204387569e-02 -9.15396518680686e-02 + 1.51515151515152e+00 4.65155136112344e-01 1.04514380417906e-02 -9.48849911388328e-02 + 2.12121212121212e+00 5.43742423609011e-01 1.05708486137771e-02 -9.80280317259123e-02 + 2.72727272727273e+00 6.21355563499191e-01 1.07685455281878e-02 -1.00538334680120e-01 + 3.33333333333333e+00 6.98247696483015e-01 1.09884995827544e-02 -1.02768385980751e-01 + 3.93939393939394e+00 7.74577272776593e-01 1.12160604908465e-02 -1.04764162336771e-01 + 4.54545454545455e+00 8.49123646294387e-01 1.15084433622475e-02 -1.06669894654905e-01 + 5.15151515151515e+00 9.22768835492197e-01 1.18149173971583e-02 -1.08443519681338e-01 + 5.75757575757576e+00 9.94281779511649e-01 1.21556943938836e-02 -1.09866171766382e-01 + 6.36363636363637e+00 1.06310529013751e+00 1.25630225021709e-02 -1.10999261303783e-01 + 6.96969696969697e+00 1.13016792278117e+00 1.30120459327629e-02 -1.11939153730602e-01 + 7.57575757575757e+00 1.19235719212211e+00 1.35489371100261e-02 -1.12757130291620e-01 + 8.18181818181818e+00 1.25253452840185e+00 1.41028478529467e-02 -1.13550777719788e-01 + 8.78787878787879e+00 1.31022818965375e+00 1.46613278249224e-02 -1.14419167648035e-01 + 9.39393939393939e+00 1.36351139175394e+00 1.60081512284208e-02 -1.14359279394763e-01 + 1.00000000000000e+01 1.40997780157282e+00 1.78443424094440e-02 -1.13736890758993e-01 + 1.06060606060606e+01 1.43923730215627e+00 2.09588631373841e-02 -1.12187901895665e-01 + 1.12121212121212e+01 1.45625328102718e+00 2.47924700140119e-02 -1.10420788252029e-01 + 1.18181818181818e+01 1.45052843686856e+00 2.93047053533567e-02 -1.08130034479078e-01 + 1.24242424242424e+01 1.37738927101704e+00 4.26630642527924e-02 -1.10097235207091e-01 + 1.30303030303030e+01 1.25402046394694e+00 5.95100927900937e-02 -1.13671143573967e-01 + 1.36363636363636e+01 1.20642687925599e+00 7.05802370100983e-02 -1.12460113720568e-01 + 1.42424242424242e+01 1.16512824375798e+00 8.18308265484637e-02 -1.11416728271022e-01 + 1.48484848484848e+01 1.13845165437591e+00 9.33501183013086e-02 -1.10513745021243e-01 + 1.54545454545455e+01 1.12012151200243e+00 1.05371259823310e-01 -1.12074593125414e-01 + 1.60606060606061e+01 1.10521158214097e+00 1.17537515544027e-01 -1.14635056143715e-01 + 1.66666666666667e+01 1.09605105013413e+00 1.29504477189816e-01 -1.18698748541531e-01 + 1.72727272727273e+01 1.09038474770029e+00 1.41619143192006e-01 -1.22755992205202e-01 + 1.78787878787879e+01 1.08898921460796e+00 1.53914338613840e-01 -1.26805354000924e-01 + 1.84848484848485e+01 1.09852690400848e+00 1.67121306650109e-01 -1.30271150233030e-01 + 1.90909090909091e+01 1.10900797848342e+00 1.80185918785840e-01 -1.33848294218024e-01 + 1.96969696969697e+01 1.10934527307501e+00 1.91151684117947e-01 -1.38883475019382e-01 + 2.03030303030303e+01 1.10872617200819e+00 2.02082800980853e-01 -1.43953835687333e-01 + 2.09090909090909e+01 1.10715062117621e+00 2.12979267414367e-01 -1.49203757196069e-01 + 2.15151515151515e+01 1.10557507034423e+00 2.23875733847882e-01 -1.54503423314042e-01 + 2.21212121212121e+01 1.10260124642550e+00 2.34778135695999e-01 -1.59652147931712e-01 + 2.27272727272727e+01 1.09403576887978e+00 2.45704273095417e-01 -1.64232639974624e-01 + 2.33333333333333e+01 1.08547029133405e+00 2.56630410494836e-01 -1.68847929010858e-01 + 2.39393939393939e+01 1.07690481378832e+00 2.67556547894255e-01 -1.73665468151725e-01 + 2.45454545454545e+01 1.07004041681628e+00 2.79119118191653e-01 -1.77890036537271e-01 + 2.51515151515151e+01 1.06336502473105e+00 2.90752401734336e-01 -1.82048720700615e-01 + 2.57575757575758e+01 1.05668963264583e+00 3.02385685277020e-01 -1.86207404863960e-01 + 2.63636363636364e+01 1.05078168869387e+00 3.14409261973987e-01 -1.90102460494435e-01 + 2.69696969696970e+01 1.04538545633799e+00 3.26693074541322e-01 -1.93821736457880e-01 + 2.75757575757576e+01 1.03998922398212e+00 3.38976887108657e-01 -1.97541012421324e-01 + 2.81818181818182e+01 1.03484090277918e+00 3.51437477732768e-01 -2.01170473836824e-01 + 2.87878787878788e+01 1.03027099131248e+00 3.64310515106369e-01 -2.04590385950606e-01 + 2.93939393939394e+01 1.02570107984578e+00 3.77183552479970e-01 -2.08010298064387e-01 + 3.00000000000000e+01 1.02113116837907e+00 3.90056589853572e-01 -2.11430210178169e-01 + 3.30000000000000e+01 1.00119460561295e+00 4.57145854597991e-01 -2.27086388641851e-01 + 3.60000000000000e+01 9.81921720811872e-01 5.27047589477837e-01 -2.41904140621254e-01 + 3.90000000000000e+01 9.61260291943995e-01 5.99606299882174e-01 -2.56159440416738e-01 + 4.20000000000000e+01 9.36935736815422e-01 6.73802755955525e-01 -2.70019544874094e-01 + 4.50000000000000e+01 9.11289556833257e-01 7.48405461801475e-01 -2.83768812367968e-01 + 4.80000000000000e+01 8.78369078677083e-01 8.22907477862781e-01 -2.97042946965006e-01 + 5.10000000000000e+01 8.41242012973183e-01 8.95844198388958e-01 -3.10074656049880e-01 + 5.40000000000000e+01 7.95701501741868e-01 9.65650227215581e-01 -3.22614713534726e-01 + 5.70000000000000e+01 7.50161338413173e-01 1.03545572276536e+00 -3.35153534620333e-01 + 6.00000000000000e+01 7.04621349034462e-01 1.10526095167874e+00 -3.47689985564868e-01 + 6.30000000000000e+01 6.43094140155942e-01 1.16178264450123e+00 -3.58895514925207e-01 + 6.60000000000000e+01 5.81566794241577e-01 1.21830422346273e+00 -3.70096619015063e-01 + 6.90000000000000e+01 5.20039448327212e-01 1.27482580242423e+00 -3.81292926550571e-01 + 7.20000000000000e+01 4.50922061318250e-01 1.31785610107633e+00 -3.91197073364813e-01 + 7.50000000000000e+01 3.78009809140240e-01 1.35414103575821e+00 -4.00450410082631e-01 + 7.80000000000000e+01 3.05096426319516e-01 1.39042638623652e+00 -4.09696121786907e-01 + 8.10000000000000e+01 2.30838925091062e-01 1.41846077220858e+00 -4.18058441063076e-01 + 8.40000000000000e+01 1.53893279831030e-01 1.42999379871131e+00 -4.24659851438870e-01 + 8.70000000000000e+01 7.69466467481749e-02 1.44152691331999e+00 -4.31250229720335e-01 + 9.00000000000000e+01 -3.36172637530740e-07 1.45305992801866e+00 -4.37829850424638e-01 + 9.30000000000000e+01 -5.38627383393683e-02 1.44152690151593e+00 -4.40933372026436e-01 + 9.60000000000000e+01 -1.07725146245282e-01 1.42999383096059e+00 -4.44037873446937e-01 + 9.90000000000000e+01 -1.61587565629768e-01 1.41846067229841e+00 -4.47143282683005e-01 + 1.02000000000000e+02 -2.13567566267535e-01 1.39042621049931e+00 -4.46986201155388e-01 + 1.05000000000000e+02 -2.64606377915867e-01 1.35414127581743e+00 -4.45198189623654e-01 + 1.08000000000000e+02 -3.15645479300682e-01 1.31785592534089e+00 -4.43410060853994e-01 + 1.11000000000000e+02 -3.64027804983567e-01 1.27482531278278e+00 -4.40372525830713e-01 + 1.14000000000000e+02 -4.07096660176995e-01 1.21830438150688e+00 -4.34835474017044e-01 + 1.17000000000000e+02 -4.50165647641462e-01 1.16178301844503e+00 -4.29298134131730e-01 + 1.20000000000000e+02 -4.93234679359343e-01 1.10526141350648e+00 -4.23760689165608e-01 + 1.23000000000000e+02 -5.25113031922223e-01 1.03545618459309e+00 -4.16386674177567e-01 + 1.26000000000000e+02 -5.56991306252975e-01 9.65650689048611e-01 -4.09012018270847e-01 + 1.29000000000000e+02 -5.88869424113624e-01 8.95844660221987e-01 -4.01636451380112e-01 + 1.32000000000000e+02 -6.13161255971681e-01 8.22874224418486e-01 -3.94888279932588e-01 + 1.35000000000000e+02 -6.33659953815723e-01 7.48321588883743e-01 -3.88452749684788e-01 + 1.38000000000000e+02 -6.54157816774948e-01 6.73769502775918e-01 -3.82015808693097e-01 + 1.41000000000000e+02 -6.72519858324716e-01 6.00666916692205e-01 -3.77450446527224e-01 + 1.44000000000000e+02 -6.86610239724511e-01 5.30463342418639e-01 -3.76628216553060e-01 + 1.47000000000000e+02 -7.00700113478808e-01 4.60260101212902e-01 -3.75801923510001e-01 + 1.50000000000000e+02 -7.14789733419415e-01 3.90057026535133e-01 -3.74971722702591e-01 + 1.53000000000000e+02 -7.26083351466705e-01 3.34899268561139e-01 -3.90699237662118e-01 + 1.56000000000000e+02 -7.37376919859767e-01 2.79741654709182e-01 -4.06434613881277e-01 + 1.59000000000000e+02 -7.49369636696621e-01 2.24584258977831e-01 -4.22178074951782e-01 + 1.62000000000000e+02 -6.78487565748514e-01 1.85578685533409e-01 -4.41942545112509e-01 + 1.65000000000000e+02 -5.65406079877361e-01 1.54649159831924e-01 -4.63714630913619e-01 + 1.68000000000000e+02 -4.44894229884888e-01 1.23719388559455e-01 -4.85485784604534e-01 + 1.71000000000000e+02 -3.31496503011607e-01 9.27895975192221e-02 -4.50000513056908e-01 + 1.74000000000000e+02 -2.20997628314192e-01 6.18597669425397e-02 -2.99999717902353e-01 + 1.77000000000000e+02 -1.09575522573893e-01 5.10040358195194e-02 -1.48718747985670e-01 + 1.80000000000000e+02 0.00000000000000e+00 5.02017886725028e-02 0.00000000000000e+00 diff --git a/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_13.dat b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_13.dat new file mode 100644 index 00000000..92b13a2b --- /dev/null +++ b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_13.dat @@ -0,0 +1,254 @@ +! ------------ AirfoilInfo v1.01.x Input File ---------------------------------- +! AeroElasticSE FAST driver +! line +! line +! ------------------------------------------------------------------------------ +DEFAULT InterpOrd ! Interpolation order to use for quasi-steady table lookup {1=linear; 3=cubic spline; "default"} [default=3] +1 NonDimArea ! The non-dimensional area of the airfoil (area/chord^2) (set to 1.0 if unsure or unneeded) +@"NREL-2p8-127_AF13_Coords.txt" NumCoords ! The number of coordinates in the airfoil shape file. Set to zero if coordinates not included. +AF13_BL.txt BL_file ! The file name including the boundary layer characteristics of the profile. Ignored if the aeroacoustic module is not called. +1 NumTabs ! Number of airfoil tables in this file. Each table must have lines for Re and Ctrl. +! ------------------------------------------------------------------------------ +! data for table 1 +! ------------------------------------------------------------------------------ +6.000000 Re ! Reynolds number in millions +0 Ctrl ! Control setting (must be 0 for current AirfoilInfo) +True InclUAdata ! Is unsteady aerodynamics data included in this table? If TRUE, then include 30 UA coefficients below this line +!........................................ +-2.132099 alpha0 ! 0-lift angle of attack, depends on airfoil. +11.682019 alpha1 ! Angle of attack at f=0.7, (approximately the stall angle) for AOA>alpha0. (deg) +-9.246885 alpha2 ! Angle of attack at f=0.7, (approximately the stall angle) for AOA1] +0.000000 S2 ! Constant in the f curve best-fit for AOA> alpha1; by definition it depends on the airfoil. [ignored if UAMod<>1] +0.000000 S3 ! Constant in the f curve best-fit for alpha2<=AOA< alpha0; by definition it depends on the airfoil. [ignored if UAMod<>1] +0.000000 S4 ! Constant in the f curve best-fit for AOA< alpha2; by definition it depends on the airfoil. [ignored if UAMod<>1] +1.467246 Cn1 ! Critical value of C0n at leading edge separation. It should be extracted from airfoil data at a given Mach and Reynolds number. It can be calculated from the static value of Cn at either the break in the pitching moment or the loss of chord force at the onset of stall. It is close to the condition of maximum lift of the airfoil at low Mach numbers. +-1.116975 Cn2 ! As Cn1 for negative AOAs. +Default St_sh ! Strouhal's shedding frequency constant. [default = 0.19] +0.010706 Cd0 ! 2D drag coefficient value at 0-lift. +-0.078417 Cm0 ! 2D pitching moment coefficient about 1/4-chord location, at 0-lift, positive if nose up. [If the aerodynamics coefficients table does not include a column for Cm, this needs to be set to 0.0] +0.000000 k0 ! Constant in the \hat(x)_cp curve best-fit; = (\hat(x)_AC-0.25). [ignored if UAMod<>1] +0.000000 k1 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k2 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k3 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k1_hat ! Constant in the expression of Cc due to leading edge vortex effects. [ignored if UAMod<>1] +Default x_cp_bar ! Constant in the expression of \hat(x)_cp^v. [ignored if UAMod<>1, default = 0.2] +Default UACutout ! Angle of attack above which unsteady aerodynamics are disabled (deg). [Specifying the string "Default" sets UACutout to 45 degrees] +Default filtCutOff ! Cut-off frequency (-3 dB corner frequency) for low-pass filtering the AoA input to UA, as well as the 1st and 2nd derivatives (Hz) [default = 20] +!........................................ +! Table of aerodynamics coefficients +200 NumAlf ! Number of data lines in the following table +! Alpha Cl Cd Cm +! (deg) (-) (-) (-) +-1.80000000000000e+02 0.00000000000000e+00 4.87439042124992e-02 0.00000000000000e+00 +-1.77000000000000e+02 1.13601999469549e-01 4.87439042124992e-02 1.19176415715757e-01 +-1.74000000000000e+02 2.28858413112315e-01 5.84925712756744e-02 2.39999774321882e-01 +-1.71000000000000e+02 3.43288316600078e-01 8.77388925055090e-02 3.60000410445527e-01 +-1.68000000000000e+02 4.57070767928178e-01 1.17275421818159e-01 3.18708357160145e-01 +-1.65000000000000e+02 5.71129134749526e-01 1.46957051785061e-01 1.96771841693633e-01 +-1.62000000000000e+02 6.81811167127312e-01 1.76639445546079e-01 7.48344304685462e-02 +-1.59000000000000e+02 7.50644491717964e-01 2.14984200570790e-01 -5.07801650458084e-03 +-1.56000000000000e+02 7.37523770619090e-01 2.70653385079522e-01 1.06132839067504e-03 +-1.53000000000000e+02 7.25223845001242e-01 3.26322594869384e-01 8.04336961373999e-03 +-1.50000000000000e+02 7.12923727515902e-01 3.81991851817702e-01 1.50360358377684e-02 +-1.47000000000000e+02 6.99053142386901e-01 4.52474247296891e-01 2.96995895978959e-02 +-1.44000000000000e+02 6.85182304280847e-01 5.22956853217613e-01 4.43686473866053e-02 +-1.41000000000000e+02 6.71310960202625e-01 5.93439880036427e-01 5.90442691380621e-02 +-1.38000000000000e+02 6.53114909413893e-01 6.66865106551800e-01 7.40923427363092e-02 +-1.35000000000000e+02 6.32756514043044e-01 7.41761426946880e-01 8.93274281204840e-02 +-1.32000000000000e+02 6.12397285385553e-01 8.16658429255323e-01 1.04567050663022e-01 +-1.29000000000000e+02 5.88229626117782e-01 8.89991527762646e-01 1.19947402883451e-01 +-1.26000000000000e+02 5.56445087582313e-01 9.60196811237631e-01 1.35603342201244e-01 +-1.23000000000000e+02 5.24660391861842e-01 1.03040155838038e+00 1.51263206732352e-01 +-1.20000000000000e+02 4.92875617551808e-01 1.10060603736703e+00 1.66927716624602e-01 +-1.17000000000000e+02 4.49867900921898e-01 1.15756854481392e+00 1.81710954488631e-01 +-1.14000000000000e+02 4.06860185400029e-01 1.21453080878140e+00 1.96498840434726e-01 +-1.11000000000000e+02 3.63852515987308e-01 1.27149263759476e+00 2.11292122383483e-01 +-1.08000000000000e+02 3.15513980484258e-01 1.31498386088960e+00 2.24396145865201e-01 +-1.05000000000000e+02 2.64509971345682e-01 1.35173967885259e+00 2.36659399343987e-01 +-1.02000000000000e+02 2.13506123000612e-01 1.38849507562982e+00 2.48931685712608e-01 +-9.90000000000000e+01 1.61553244788091e-01 1.41700492873292e+00 2.59841073682875e-01 +-9.60000000000000e+01 1.07702265733195e-01 1.42902333732993e+00 2.68014448982559e-01 +-9.30000000000000e+01 5.38512980694728e-02 1.44104165411306e+00 2.76206223274710e-01 +-9.00000000000000e+01 3.36101235326894e-07 1.45305992499009e+00 2.84424528048508e-01 +-8.70000000000000e+01 -5.38512429529903e-02 1.44104166641377e+00 2.88179235636605e-01 +-8.40000000000000e+01 -1.07702416312529e-01 1.42902330372378e+00 2.92116238002531e-01 +-8.10000000000000e+01 -1.61552778284462e-01 1.41700503284675e+00 2.96384910251329e-01 +-7.80000000000000e+01 -2.13505875975934e-01 1.38849525364560e+00 2.96589518980285e-01 +-7.50000000000000e+01 -2.64510308783977e-01 1.35173943568081e+00 2.94839423717641e-01 +-7.20000000000000e+01 -3.15513733464136e-01 1.31498403890358e+00 2.93086106067290e-01 +-6.90000000000000e+01 -3.63852143411397e-01 1.27149313105570e+00 2.90081406410839e-01 +-6.60000000000000e+01 -4.06860305658320e-01 1.21453064950441e+00 2.84576673209790e-01 +-6.30000000000000e+01 -4.49868185458844e-01 1.15756816795312e+00 2.79066340953731e-01 +-6.00000000000000e+01 -4.92875827838210e-01 1.10060557289787e+00 2.73549730680385e-01 +-5.70000000000000e+01 -5.24660602148244e-01 1.03040109391122e+00 2.66198212861305e-01 +-5.40000000000000e+01 -5.56445297867155e-01 9.60196346763153e-01 2.58837329083779e-01 +-5.10000000000000e+01 -5.88229836402624e-01 8.89991063288168e-01 2.51465219825159e-01 +-4.80000000000000e+01 -6.14103823719259e-01 8.16681742398572e-01 2.44260248495120e-01 +-4.50000000000000e+01 -6.37022630417404e-01 7.41820452687947e-01 2.37125494405563e-01 +-4.20000000000000e+01 -6.54821434392937e-01 6.66888419508008e-01 2.31318374407913e-01 +-3.90000000000000e+01 -6.71686771395590e-01 5.92370007881034e-01 2.26128186404354e-01 +-3.60000000000000e+01 -6.85959395421995e-01 5.19513505734105e-01 2.23293038777573e-01 +-3.30000000000000e+01 -6.99228262265746e-01 4.49336693515259e-01 2.23281989121863e-01 +-3.00000000000000e+01 -7.12923826438148e-01 3.81991413473000e-01 2.26408555434034e-01 +-2.93939393939394e+01 -7.16063242755988e-01 3.69070660189083e-01 2.27884386933293e-01 +-2.87878787878788e+01 -7.19202659073829e-01 3.56149906905165e-01 2.29360218432552e-01 +-2.81818181818182e+01 -7.22342075391669e-01 3.43229153621248e-01 2.30836049931811e-01 +-2.75757575757576e+01 -7.25879646593120e-01 3.30722936547354e-01 2.32910797277799e-01 +-2.69696969696970e+01 -7.29587870240511e-01 3.18394393090142e-01 2.35242244863728e-01 +-2.63636363636364e+01 -7.33296093887901e-01 3.06065849632931e-01 2.37573692449656e-01 +-2.57575757575758e+01 -7.37358552649944e-01 2.93998789131352e-01 2.40351599308823e-01 +-2.51515151515151e+01 -7.41952281524987e-01 2.82323892121304e-01 2.43799091024856e-01 +-2.45454545454545e+01 -7.46546010400030e-01 2.70648995111257e-01 2.47246582740888e-01 +-2.39393939393939e+01 -7.51270810440089e-01 2.59045122954569e-01 2.50842931746802e-01 +-2.33333333333333e+01 -7.57175276341296e-01 2.48080488228869e-01 2.55779025181128e-01 +-2.27272727272727e+01 -7.63079742242504e-01 2.37115853503168e-01 2.61669103088351e-01 +-2.21212121212121e+01 -7.68984208143711e-01 2.26151218777467e-01 2.66787136053718e-01 +-2.15151515151515e+01 -7.98558741205574e-01 2.18978684775324e-01 2.59268734046189e-01 +-2.09090909090909e+01 -8.39976990506764e-01 2.12754419878834e-01 2.46412877782449e-01 +-2.03030303030303e+01 -8.77626065799621e-01 2.06530154982344e-01 2.32873392185209e-01 +-1.96969696969697e+01 -9.12482277726115e-01 2.00406617873157e-01 2.16079231533506e-01 +-1.90909090909091e+01 -9.44653374099275e-01 1.94383802853063e-01 1.96196944890485e-01 +-1.84848484848485e+01 -9.76556738297402e-01 1.88868061750279e-01 1.76251855690617e-01 +-1.78787878787879e+01 -1.00830988060465e+00 1.83317104202353e-01 1.56918611734039e-01 +-1.72727272727273e+01 -1.03997095936839e+00 1.76526361566991e-01 1.37892024373634e-01 +-1.66666666666667e+01 -1.07157049021422e+00 1.70932183497624e-01 1.18865299601930e-01 +-1.60606060606061e+01 -1.10312717894668e+00 1.65593044673498e-01 9.98384624039651e-02 +-1.54545454545455e+01 -1.11507119669234e+00 1.58446673227857e-01 8.41684149093784e-02 +-1.48484848484848e+01 -1.11477271836942e+00 1.50207476871942e-01 7.03417694480957e-02 +-1.42424242424242e+01 -1.08423257216199e+00 1.39348090503607e-01 6.20173634895011e-02 +-1.36363636363636e+01 -1.04896032877406e+00 1.28119902100447e-01 5.40305604199166e-02 +-1.30303030303030e+01 -1.01046372636334e+00 1.16637431776633e-01 4.49260984726437e-02 +-1.24242424242424e+01 -9.69201936614847e-01 1.05499178414566e-01 3.32219061711730e-02 +-1.18181818181818e+01 -9.27767400425763e-01 9.49119646912448e-02 2.16483145014490e-02 +-1.12121212121212e+01 -8.86480598336731e-01 8.55891565143775e-02 1.06380104995937e-02 +-1.06060606060606e+01 -8.43514329482308e-01 7.70087578463476e-02 1.14934323347435e-03 +-1.00000000000000e+01 -7.98856262424989e-01 6.88029421594717e-02 -7.48514667045178e-03 +-9.39393939393939e+00 -7.63413220908471e-01 5.72619896948118e-02 -1.75515357315967e-02 +-8.78787878787879e+00 -7.36855164567028e-01 4.49241428048966e-02 -2.67299768784618e-02 +-8.18181818181818e+00 -7.21915221248136e-01 3.22666539335863e-02 -3.43270785756021e-02 +-7.57575757575758e+00 -6.80107790322963e-01 2.47696277944221e-02 -3.79455763749705e-02 +-6.96969696969697e+00 -6.25477329057538e-01 2.00640152396707e-02 -4.00917938604969e-02 +-6.36363636363636e+00 -5.45385415536934e-01 1.76703500104717e-02 -4.47595761821227e-02 +-5.75757575757576e+00 -4.65240863542729e-01 1.56676325439870e-02 -4.94624634693340e-02 +-5.15151515151515e+00 -3.85177304810552e-01 1.41170830647471e-02 -5.47806233959061e-02 +-4.54545454545454e+00 -3.05186013364708e-01 1.29299720858053e-02 -6.00838561640560e-02 +-3.93939393939394e+00 -2.25496618815856e-01 1.19194070246950e-02 -6.52622261528225e-02 +-3.33333333333333e+00 -1.50095854632385e-01 1.14661881877472e-02 -7.00888229733615e-02 +-2.72727272727273e+00 -7.44807687769198e-02 1.10712748312864e-02 -7.44803490024561e-02 +-2.12121212121212e+00 1.36241455738510e-03 1.06994983826237e-02 -7.84888091237353e-02 +-1.51515151515152e+00 7.79762724684800e-02 1.04764559842521e-02 -8.22769309796209e-02 +-9.09090909090912e-01 1.55093196357546e-01 1.03282187235360e-02 -8.59707384355398e-02 +-3.03030303030302e-01 2.33690956667381e-01 1.03497391513504e-02 -8.95788413712978e-02 + 3.03030303030302e-01 3.12230375322369e-01 1.03960832854878e-02 -9.29631294177707e-02 + 9.09090909090912e-01 3.90723642801794e-01 1.04626363547074e-02 -9.61417302922719e-02 + 1.51515151515152e+00 4.69223374488536e-01 1.05181765096339e-02 -9.91269841658500e-02 + 2.12121212121212e+00 5.47419021984281e-01 1.05986866302366e-02 -1.01951326898863e-01 + 2.72727272727273e+00 6.24353465324347e-01 1.07913520395363e-02 -1.04285374966365e-01 + 3.33333333333333e+00 7.00719049213690e-01 1.09882631518878e-02 -1.06367221462522e-01 + 3.93939393939394e+00 7.76662113860127e-01 1.11995924883540e-02 -1.08233532083904e-01 + 4.54545454545455e+00 8.51062527788879e-01 1.14677130840408e-02 -1.09981051673887e-01 + 5.15151515151515e+00 9.24618318776539e-01 1.17484143214346e-02 -1.11607861589439e-01 + 5.75757575757576e+00 9.96131045922850e-01 1.20661413484365e-02 -1.12922063002211e-01 + 6.36363636363637e+00 1.06530124476682e+00 1.24411013682114e-02 -1.13971538180268e-01 + 6.96969696969697e+00 1.13294924210721e+00 1.28499924886479e-02 -1.14845663241843e-01 + 7.57575757575757e+00 1.19647826401428e+00 1.33185723521347e-02 -1.15548552499834e-01 + 8.18181818181818e+00 1.25852214595514e+00 1.37822042010170e-02 -1.16225412192196e-01 + 8.78787878787879e+00 1.31953258382690e+00 1.42014660644829e-02 -1.16973536925898e-01 + 9.39393939393939e+00 1.37722282574832e+00 1.52499336492677e-02 -1.16582058795787e-01 + 1.00000000000000e+01 1.42782587729733e+00 1.66203055937069e-02 -1.15506211836930e-01 + 1.06060606060606e+01 1.46349417020859e+00 1.89049864855517e-02 -1.13428166197566e-01 + 1.12121212121212e+01 1.48851533807067e+00 2.17360570752516e-02 -1.11086533657004e-01 + 1.18181818181818e+01 1.49375899629952e+00 2.51530002017571e-02 -1.08182154414350e-01 + 1.24242424242424e+01 1.39019183027460e+00 4.01241150571406e-02 -1.10396226977541e-01 + 1.30303030303030e+01 1.23558289690220e+00 5.95330302498055e-02 -1.14566124306707e-01 + 1.36363636363636e+01 1.17983620766855e+00 6.99436564860179e-02 -1.13107355391663e-01 + 1.42424242424242e+01 1.13261025086269e+00 8.02708219712224e-02 -1.11811426810697e-01 + 1.48484848484848e+01 1.10434568242928e+00 9.05273912159466e-02 -1.10627750277284e-01 + 1.54545454545455e+01 1.08509274406338e+00 1.01044358671353e-01 -1.11196367879537e-01 + 1.60606060606061e+01 1.06957515718470e+00 1.11649937873699e-01 -1.12390832093296e-01 + 1.66666666666667e+01 1.06064834245443e+00 1.22271986435775e-01 -1.14792794654718e-01 + 1.72727272727273e+01 1.05566858193663e+00 1.33123890508199e-01 -1.17423076146692e-01 + 1.78787878787879e+01 1.05551304883942e+00 1.44256732007905e-01 -1.20332417004491e-01 + 1.84848484848485e+01 1.06725149416938e+00 1.56758954022331e-01 -1.23671200892881e-01 + 1.90909090909091e+01 1.08077437232159e+00 1.69418290548337e-01 -1.27335467738334e-01 + 1.96969696969697e+01 1.08755966688782e+00 1.81027946977387e-01 -1.32236261105666e-01 + 2.03030303030303e+01 1.09235894047421e+00 1.92457859565650e-01 -1.37361247840428e-01 + 2.09090909090909e+01 1.09517208072444e+00 2.03708018144370e-01 -1.42882710356362e-01 + 2.15151515151515e+01 1.09798522097467e+00 2.14958176723090e-01 -1.48463527012242e-01 + 2.21212121212121e+01 1.09854840217806e+00 2.26151218777467e-01 -1.53912838053508e-01 + 2.27272727272727e+01 1.09011406223620e+00 2.37115853503168e-01 -1.58878474315141e-01 + 2.33333333333333e+01 1.08167972229433e+00 2.48080488228869e-01 -1.63885629560299e-01 + 2.39393939393939e+01 1.07324538235247e+00 2.59045122954570e-01 -1.69134105044946e-01 + 2.45454545454545e+01 1.06649517893070e+00 2.70648995111257e-01 -1.73708687311479e-01 + 2.51515151515151e+01 1.05993209776363e+00 2.82323892121304e-01 -1.78208394164471e-01 + 2.57575757575758e+01 1.05336901659657e+00 2.93998789131352e-01 -1.82708101017462e-01 + 2.63636363636364e+01 1.04756481639234e+00 3.06065849632931e-01 -1.86905429493079e-01 + 2.69696969696970e+01 1.04226661544969e+00 3.18394393090142e-01 -1.90901141057530e-01 + 2.75757575757576e+01 1.03696841450705e+00 3.30722936547354e-01 -1.94896852621981e-01 + 2.81818181818182e+01 1.03191481277606e+00 3.43229153621248e-01 -1.98788509538092e-01 + 2.87878787878788e+01 1.02743189358122e+00 3.56149906905165e-01 -2.02437393101785e-01 + 2.93939393939394e+01 1.02294897438639e+00 3.69070660189083e-01 -2.06086276665478e-01 + 3.00000000000000e+01 1.01846605519156e+00 3.81991413473000e-01 -2.09735160229171e-01 + 3.30000000000000e+01 9.98896269436472e-01 4.49336693515259e-01 -2.26306031891365e-01 + 3.60000000000000e+01 9.79942808607176e-01 5.19513505734105e-01 -2.41883781570832e-01 + 3.90000000000000e+01 9.59552820645265e-01 5.92370007881034e-01 -2.56418564967551e-01 + 4.20000000000000e+01 9.35459598863631e-01 6.66888419508008e-01 -2.70550711580551e-01 + 4.50000000000000e+01 9.10032841705360e-01 7.41820452687947e-01 -2.84583661386136e-01 + 4.80000000000000e+01 8.77291164853731e-01 8.16681742398572e-01 -2.98125199456282e-01 + 5.10000000000000e+01 8.40327861925211e-01 8.89991063288168e-01 -3.11430203584398e-01 + 5.40000000000000e+01 7.94921035444153e-01 9.60196346763153e-01 -3.24242564733735e-01 + 5.70000000000000e+01 7.49514555844441e-01 1.03040109391122e+00 -3.37060914767786e-01 + 6.00000000000000e+01 7.04108249684082e-01 1.10060557289787e+00 -3.49883096668555e-01 + 6.30000000000000e+01 6.42668579003910e-01 1.15756816795312e+00 -3.61391087463078e-01 + 6.60000000000000e+01 5.81228770892357e-01 1.21453064950441e+00 -3.72900577797390e-01 + 6.90000000000000e+01 5.19788962780805e-01 1.27149313105570e+00 -3.84410594625320e-01 + 7.20000000000000e+01 4.50734175503690e-01 1.31498403890358e+00 -3.94650756300015e-01 + 7.50000000000000e+01 3.77872054532562e-01 1.35173943568081e+00 -4.04254594429255e-01 + 7.80000000000000e+01 3.05008674950305e-01 1.38849525364560e+00 -4.13856378244412e-01 + 8.10000000000000e+01 2.30789950548293e-01 1.41700503284675e+00 -4.22588303462247e-01 + 8.40000000000000e+01 1.53860630065887e-01 1.42902330372378e+00 -4.29581922692123e-01 + 8.70000000000000e+01 7.69303218853695e-02 1.44104166641377e+00 -4.36570514980957e-01 + 9.00000000000000e+01 -3.36101235559296e-07 1.45305992499009e+00 -4.43554018258070e-01 + 9.30000000000000e+01 -5.38512980694728e-02 1.44104165411306e+00 -4.46821429870465e-01 + 9.60000000000000e+01 -1.07702265733195e-01 1.42902333732993e+00 -4.50090063193436e-01 + 9.90000000000000e+01 -1.61553244788092e-01 1.41700492873292e+00 -4.53359826724784e-01 + 1.02000000000000e+02 -2.13506123000612e-01 1.38849507562982e+00 -4.53358356880233e-01 + 1.05000000000000e+02 -2.64509971345682e-01 1.35173967885259e+00 -4.51721761227933e-01 + 1.08000000000000e+02 -3.15513980484258e-01 1.31498386088960e+00 -4.50085315220303e-01 + 1.11000000000000e+02 -3.63852515987308e-01 1.27149263759476e+00 -4.47194708590916e-01 + 1.14000000000000e+02 -4.06860185400029e-01 1.21453080878140e+00 -4.41794921939120e-01 + 1.17000000000000e+02 -4.49867900921898e-01 1.15756854481392e+00 -4.36395234719870e-01 + 1.20000000000000e+02 -4.92875617551808e-01 1.10060603736703e+00 -4.30995807908883e-01 + 1.23000000000000e+02 -5.24660391861842e-01 1.03040155838038e+00 -4.23756434063717e-01 + 1.26000000000000e+02 -5.56445087582313e-01 9.60196811237631e-01 -4.16516996565852e-01 + 1.29000000000000e+02 -5.88229626117782e-01 8.89991527762645e-01 -4.09277210165741e-01 + 1.32000000000000e+02 -6.12397285385553e-01 8.16658429255322e-01 -4.02686723110960e-01 + 1.35000000000000e+02 -6.32756514043044e-01 7.41761426946880e-01 -3.96420479648652e-01 + 1.38000000000000e+02 -6.53114909413893e-01 6.66865106551800e-01 -3.90153798231996e-01 + 1.41000000000000e+02 -6.71310960202625e-01 5.93439880036427e-01 -3.85803144277468e-01 + 1.44000000000000e+02 -6.85182304280847e-01 5.22956853217613e-01 -3.85284327936909e-01 + 1.47000000000000e+02 -6.99053142386901e-01 4.52474247296891e-01 -3.84763389697547e-01 + 1.50000000000000e+02 -7.12923727515902e-01 3.81991851817701e-01 -3.84240435098614e-01 + 1.53000000000000e+02 -7.17713468565102e-01 3.27562673383999e-01 -4.00044506289342e-01 + 1.56000000000000e+02 -7.22503170158526e-01 2.73133681485946e-01 -4.15858223301289e-01 + 1.59000000000000e+02 -7.28127146175927e-01 2.18704987836167e-01 -4.31681847835051e-01 + 1.62000000000000e+02 -6.57546925365099e-01 1.80505932981753e-01 -4.49567289106761e-01 + 1.65000000000000e+02 -5.47955571734396e-01 1.50421834782562e-01 -4.68480081499263e-01 + 1.68000000000000e+02 -4.33508829076636e-01 1.20337481324609e-01 -4.87391973738006e-01 + 1.71000000000000e+02 -3.23710952534405e-01 9.02531541751285e-02 -4.50000513056908e-01 + 1.74000000000000e+02 -2.15807282191796e-01 6.01688796438182e-02 -2.99999717902353e-01 + 1.77000000000000e+02 -1.07173368611120e-01 4.95765701106933e-02 -1.48970519644697e-01 + 1.80000000000000e+02 0.00000000000000e+00 4.87439042124992e-02 0.00000000000000e+00 diff --git a/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_14.dat b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_14.dat new file mode 100644 index 00000000..229833e5 --- /dev/null +++ b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_14.dat @@ -0,0 +1,254 @@ +! ------------ AirfoilInfo v1.01.x Input File ---------------------------------- +! AeroElasticSE FAST driver +! line +! line +! ------------------------------------------------------------------------------ +DEFAULT InterpOrd ! Interpolation order to use for quasi-steady table lookup {1=linear; 3=cubic spline; "default"} [default=3] +1 NonDimArea ! The non-dimensional area of the airfoil (area/chord^2) (set to 1.0 if unsure or unneeded) +@"NREL-2p8-127_AF14_Coords.txt" NumCoords ! The number of coordinates in the airfoil shape file. Set to zero if coordinates not included. +AF14_BL.txt BL_file ! The file name including the boundary layer characteristics of the profile. Ignored if the aeroacoustic module is not called. +1 NumTabs ! Number of airfoil tables in this file. Each table must have lines for Re and Ctrl. +! ------------------------------------------------------------------------------ +! data for table 1 +! ------------------------------------------------------------------------------ +6.000000 Re ! Reynolds number in millions +0 Ctrl ! Control setting (must be 0 for current AirfoilInfo) +True InclUAdata ! Is unsteady aerodynamics data included in this table? If TRUE, then include 30 UA coefficients below this line +!........................................ +-2.166094 alpha0 ! 0-lift angle of attack, depends on airfoil. +11.851014 alpha1 ! Angle of attack at f=0.7, (approximately the stall angle) for AOA>alpha0. (deg) +-9.637248 alpha2 ! Angle of attack at f=0.7, (approximately the stall angle) for AOA1] +0.000000 S2 ! Constant in the f curve best-fit for AOA> alpha1; by definition it depends on the airfoil. [ignored if UAMod<>1] +0.000000 S3 ! Constant in the f curve best-fit for alpha2<=AOA< alpha0; by definition it depends on the airfoil. [ignored if UAMod<>1] +0.000000 S4 ! Constant in the f curve best-fit for AOA< alpha2; by definition it depends on the airfoil. [ignored if UAMod<>1] +1.502705 Cn1 ! Critical value of C0n at leading edge separation. It should be extracted from airfoil data at a given Mach and Reynolds number. It can be calculated from the static value of Cn at either the break in the pitching moment or the loss of chord force at the onset of stall. It is close to the condition of maximum lift of the airfoil at low Mach numbers. +-1.198117 Cn2 ! As Cn1 for negative AOAs. +Default St_sh ! Strouhal's shedding frequency constant. [default = 0.19] +0.010692 Cd0 ! 2D drag coefficient value at 0-lift. +-0.084655 Cm0 ! 2D pitching moment coefficient about 1/4-chord location, at 0-lift, positive if nose up. [If the aerodynamics coefficients table does not include a column for Cm, this needs to be set to 0.0] +0.000000 k0 ! Constant in the \hat(x)_cp curve best-fit; = (\hat(x)_AC-0.25). [ignored if UAMod<>1] +0.000000 k1 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k2 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k3 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k1_hat ! Constant in the expression of Cc due to leading edge vortex effects. [ignored if UAMod<>1] +Default x_cp_bar ! Constant in the expression of \hat(x)_cp^v. [ignored if UAMod<>1, default = 0.2] +Default UACutout ! Angle of attack above which unsteady aerodynamics are disabled (deg). [Specifying the string "Default" sets UACutout to 45 degrees] +Default filtCutOff ! Cut-off frequency (-3 dB corner frequency) for low-pass filtering the AoA input to UA, as well as the 1st and 2nd derivatives (Hz) [default = 20] +!........................................ +! Table of aerodynamics coefficients +200 NumAlf ! Number of data lines in the following table +! Alpha Cl Cd Cm +! (deg) (-) (-) (-) +-1.80000000000000e+02 0.00000000000000e+00 4.74971586892991e-02 0.00000000000000e+00 +-1.77000000000000e+02 1.11000230721027e-01 4.74971586892991e-02 1.19348662665291e-01 +-1.74000000000000e+02 2.23249498352695e-01 5.69965146964868e-02 2.39999774321882e-01 +-1.71000000000000e+02 3.34875005612777e-01 8.54948945736924e-02 3.60000410445527e-01 +-1.68000000000000e+02 4.46351865610983e-01 1.14102183123101e-01 3.18009867522619e-01 +-1.65000000000000e+02 5.57999076618718e-01 1.42763924737488e-01 1.95025625752222e-01 +-1.62000000000000e+02 6.68256570415867e-01 1.71426528385083e-01 7.20405402903902e-02 +-1.59000000000000e+02 7.38112012967269e-01 2.08990990812950e-01 -9.03147344265643e-03 +-1.56000000000000e+02 7.28701413125268e-01 2.64358869655133e-01 -4.58368783527860e-03 +-1.53000000000000e+02 7.20014801391652e-01 3.19726771476650e-01 4.84852864421045e-04 +-1.50000000000000e+02 7.11327966966767e-01 3.75094720564407e-01 5.41799540089436e-03 +-1.47000000000000e+02 6.97644694809602e-01 4.45815984052867e-01 2.02835508949186e-02 +-1.44000000000000e+02 6.83961170390853e-01 5.16537495536617e-01 3.51512653382985e-02 +-1.41000000000000e+02 6.70277141430926e-01 5.87259503028655e-01 5.00215815438595e-02 +-1.38000000000000e+02 6.52223041697912e-01 6.60960643393727e-01 6.52179053138514e-02 +-1.35000000000000e+02 6.31983915443519e-01 7.36151344151820e-01 8.05776041224766e-02 +-1.32000000000000e+02 6.11743957269201e-01 8.11342840122296e-01 9.59393162430393e-02 +-1.29000000000000e+02 5.87682487226497e-01 8.84986078503406e-01 1.11444964032245e-01 +-1.26000000000000e+02 5.55977975337812e-01 9.55532794347773e-01 1.27236023845822e-01 +-1.23000000000000e+02 5.24273305652762e-01 1.02607897125153e+00 1.43028582986147e-01 +-1.20000000000000e+02 4.92568557072479e-01 1.09662487869506e+00 1.58822953785748e-01 +-1.17000000000000e+02 4.49613275538441e-01 1.15396443469656e+00 1.73777165711677e-01 +-1.14000000000000e+02 4.06657958215625e-01 1.21130374584807e+00 1.88732854747424e-01 +-1.11000000000000e+02 3.63702613318511e-01 1.26864261896506e+00 2.03690155444885e-01 +-1.08000000000000e+02 3.15401526057875e-01 1.31252774478765e+00 2.16985072342206e-01 +-1.05000000000000e+02 2.64427526911241e-01 1.34968589451878e+00 2.29449925939083e-01 +-1.02000000000000e+02 2.13453578289375e-01 1.38684361845383e+00 2.41917717292569e-01 +-9.90000000000000e+01 1.61523894481612e-01 1.41576001404799e+00 2.53026853626378e-01 +-9.60000000000000e+01 1.07682698904138e-01 1.42819339598511e+00 2.61414906151363e-01 +-9.30000000000000e+01 5.38415146430987e-02 1.44062668293820e+00 2.69809084986757e-01 +-9.00000000000000e+01 3.36040174186750e-07 1.45305992240014e+00 2.78212559061635e-01 +-8.70000000000000e+01 -5.38414595366295e-02 1.44062669566363e+00 2.81853755036713e-01 +-8.40000000000000e+01 -1.07682849456116e-01 1.42819336121861e+00 2.85569122512613e-01 +-8.10000000000000e+01 -1.61523428062735e-01 1.41576012175667e+00 2.89419982005163e-01 +-7.80000000000000e+01 -2.13453331409509e-01 1.38684379841819e+00 2.89665265635515e-01 +-7.50000000000000e+01 -2.64427864151593e-01 1.34968564868523e+00 2.88138738774038e-01 +-7.20000000000000e+01 -3.15401279183096e-01 1.31252792475019e+00 2.86609458179388e-01 +-6.90000000000000e+01 -3.63702241195888e-01 1.26864311569235e+00 2.83820667109906e-01 +-6.60000000000000e+01 -4.06658078327606e-01 1.21130358551679e+00 2.78515251076842e-01 +-6.30000000000000e+01 -4.49613559728479e-01 1.15396405534123e+00 2.73204848612241e-01 +-6.00000000000000e+01 -4.92568766829435e-01 1.09662441196703e+00 2.67888882389067e-01 +-5.70000000000000e+01 -5.24273515409718e-01 1.02607850452350e+00 2.60728337244673e-01 +-5.40000000000000e+01 -5.55978185093202e-01 9.55532327614396e-01 2.53559556903730e-01 +-5.10000000000000e+01 -5.87682696981887e-01 8.84985611770030e-01 2.46380928095060e-01 +-4.80000000000000e+01 -6.13458630295659e-01 8.11357652574190e-01 2.39383508326475e-01 +-4.50000000000000e+01 -6.36270369602626e-01 7.36189121222556e-01 2.32464914094013e-01 +-4.20000000000000e+01 -6.53937701306032e-01 6.60975455724981e-01 2.26919127213316e-01 +-3.90000000000000e+01 -6.70664549725515e-01 5.86181715938499e-01 2.21997712524231e-01 +-3.60000000000000e+01 -6.84774756509486e-01 5.13070549905569e-01 2.19442879100228e-01 +-3.30000000000000e+01 -6.97852537348206e-01 4.42658498578043e-01 2.19788443952018e-01 +-3.00000000000000e+01 -7.11328064353672e-01 3.75094280797430e-01 2.23361039140397e-01 +-2.93939393939394e+01 -7.14415682762428e-01 3.62132722086743e-01 2.24952236186361e-01 +-2.87878787878788e+01 -7.17503301171185e-01 3.49171163376055e-01 2.26543433232325e-01 +-2.81818181818182e+01 -7.20590919579942e-01 3.36209604665368e-01 2.28134630278289e-01 +-2.75757575757576e+01 -7.24071834030542e-01 3.23664369017940e-01 2.30343477172995e-01 +-2.69696969696970e+01 -7.27721318387681e-01 3.11297572847134e-01 2.32817053854427e-01 +-2.63636363636364e+01 -7.31370802744820e-01 2.98930776676328e-01 2.35290630535858e-01 +-2.57575757575758e+01 -7.35371080478430e-01 2.86826529936594e-01 2.38225234034872e-01 +-2.51515151515151e+01 -7.39897466519906e-01 2.75116046152996e-01 2.41851270312120e-01 +-2.45454545454545e+01 -7.44423852561381e-01 2.63405562369399e-01 2.45477306589367e-01 +-2.39393939393939e+01 -7.49080204989271e-01 2.51766369918421e-01 2.49257235504190e-01 +-2.33333333333333e+01 -7.54906280057009e-01 2.40768813263367e-01 2.54422227951541e-01 +-2.27272727272727e+01 -7.60732355124748e-01 2.29771256608312e-01 2.60428793385145e-01 +-2.21212121212121e+01 -7.66558430192487e-01 2.18773699953258e-01 2.65754286761814e-01 +-2.15151515151515e+01 -8.00687554276612e-01 2.12395791755905e-01 2.54131477053226e-01 +-2.09090909090909e+01 -8.47011591503202e-01 2.07173092829286e-01 2.36349555357985e-01 +-2.03030303030303e+01 -8.90594276628836e-01 2.01950393902668e-01 2.17964558879003e-01 +-1.96969696969697e+01 -9.33116480486079e-01 1.96765628796972e-01 1.98214287245217e-01 +-1.90909090909091e+01 -9.74622494568323e-01 1.91618795366269e-01 1.77245579244523e-01 +-1.84848484848485e+01 -1.01601768577475e+00 1.86919414620951e-01 1.56221773196698e-01 +-1.78787878787879e+01 -1.05735116332665e+00 1.82188959514290e-01 1.35737748819307e-01 +-1.72727272727273e+01 -1.09864750288064e+00 1.76364686193561e-01 1.15524161434742e-01 +-1.66666666666667e+01 -1.13991853932663e+00 1.71295280735592e-01 9.53103144961163e-02 +-1.60606060606061e+01 -1.18117196285153e+00 1.66429521167139e-01 7.50962551972795e-02 +-1.54545454545455e+01 -1.19791272454831e+00 1.59575377638483e-01 5.91097556474128e-02 +-1.48484848484848e+01 -1.19934186806973e+00 1.51502853954205e-01 4.54449853411950e-02 +-1.42424242424242e+01 -1.16297897530355e+00 1.40460445425891e-01 3.82990945588821e-02 +-1.36363636363636e+01 -1.12077036373998e+00 1.29002431424042e-01 3.11065404436185e-02 +-1.30303030303030e+01 -1.07463320183473e+00 1.17263267706531e-01 2.26980761363050e-02 +-1.24242424242424e+01 -1.02518157920182e+00 1.05918643160515e-01 1.17933498379386e-02 +-1.18181818181818e+01 -9.75681942398755e-01 9.51959685529269e-02 1.19873623725293e-03 +-1.12121212121212e+01 -9.26571076805030e-01 8.58848934178665e-02 -8.41861521656647e-03 +-1.06060606060606e+01 -8.75664896114804e-01 7.74090431182947e-02 -1.63777998285526e-02 +-1.00000000000000e+01 -8.23237071758609e-01 6.93728235267388e-02 -2.34138528773980e-02 +-9.39393939393939e+00 -7.82111343672048e-01 5.75636308912248e-02 -3.21020160083091e-02 +-8.78787878787879e+00 -7.51375159974407e-01 4.47516034625548e-02 -3.98906956582438e-02 +-8.18181818181818e+00 -7.35088054943470e-01 3.08041630438302e-02 -4.60682064471990e-02 +-7.57575757575758e+00 -6.92836122752420e-01 2.31579933295670e-02 -4.89829934537834e-02 +-6.96969696969697e+00 -6.37949933369482e-01 1.87032507714761e-02 -5.07384454242695e-02 +-6.36363636363636e+00 -5.54161342148495e-01 1.67784052774049e-02 -5.53503816254145e-02 +-5.75757575757576e+00 -4.70840124165288e-01 1.50845427200835e-02 -5.98951476736281e-02 +-5.15151515151515e+00 -3.88292011066822e-01 1.36982538638481e-02 -6.45572843794330e-02 +-4.54545454545454e+00 -3.06502440552051e-01 1.26562227449715e-02 -6.91008881961310e-02 +-3.93939393939394e+00 -2.25310842700356e-01 1.17673191515673e-02 -7.35346491057446e-02 +-3.33333333333333e+00 -1.47988215381915e-01 1.13325276777439e-02 -7.76194041395815e-02 +-2.72727272727273e+00 -7.09984158942061e-02 1.09783067702849e-02 -8.14085077704442e-02 +-2.12121212121212e+00 5.67824274921396e-03 1.06696224794102e-02 -8.49142606714796e-02 +-1.51515151515152e+00 8.26102586756291e-02 1.04667274124626e-02 -8.82711832196438e-02 +-9.09090909090912e-01 1.59969016769918e-01 1.03323320303745e-02 -9.15655050496302e-02 +-3.03030303030302e-01 2.38974448513455e-01 1.03900461416016e-02 -9.47661275562079e-02 + 3.03030303030302e-01 3.17646859605712e-01 1.04649254982203e-02 -9.77901212356652e-02 + 9.09090909090912e-01 3.96007393557534e-01 1.05511605199152e-02 -1.00651121145792e-01 + 1.51515151515152e+00 4.74169429973799e-01 1.05752495413395e-02 -1.03293525376690e-01 + 2.12121212121212e+00 5.51911940760023e-01 1.06224929903068e-02 -1.05813765929291e-01 + 2.72727272727273e+00 6.28056580841275e-01 1.08108555850528e-02 -1.07977517357485e-01 + 3.33333333333333e+00 7.03798053899655e-01 1.09879017716880e-02 -1.09916646422344e-01 + 3.93939393939394e+00 7.79276493869128e-01 1.11758838962833e-02 -1.11658275595353e-01 + 4.54545454545455e+00 8.53499796067138e-01 1.14129478363666e-02 -1.13253311951308e-01 + 5.15151515151515e+00 9.26946560290491e-01 1.16638391697767e-02 -1.14737019623995e-01 + 5.75757575757576e+00 9.98458448466187e-01 1.19568385022413e-02 -1.15939256762654e-01 + 6.36363636363637e+00 1.06804425733062e+00 1.22991453288649e-02 -1.16892495532205e-01 + 6.96969696969697e+00 1.13638020854557e+00 1.26698916273089e-02 -1.17681562497719e-01 + 7.57575757575757e+00 1.20139147533564e+00 1.30839223585554e-02 -1.18207998448365e-01 + 8.18181818181818e+00 1.26525870625966e+00 1.34927417386065e-02 -1.18675618171796e-01 + 8.78787878787879e+00 1.32856174203142e+00 1.38637786532075e-02 -1.19120015634172e-01 + 9.39393939393939e+00 1.38894849360344e+00 1.46729594502212e-02 -1.18422993276735e-01 + 1.00000000000000e+01 1.44308909541765e+00 1.56494510556849e-02 -1.17051335409731e-01 + 1.06060606060606e+01 1.48423802370368e+00 1.71908084497653e-02 -1.14598756389549e-01 + 1.12121212121212e+01 1.51610502455934e+00 1.91222908592098e-02 -1.11779817617528e-01 + 1.18181818181818e+01 1.53072866564893e+00 2.16025680835697e-02 -1.08254794802547e-01 + 1.24242424242424e+01 1.39977849156389e+00 3.79528706066007e-02 -1.10603299151591e-01 + 1.30303030303030e+01 1.21617535220138e+00 5.95675147584135e-02 -1.15202550970118e-01 + 1.36363636363636e+01 1.15533504132719e+00 6.93992690943369e-02 -1.13563572716609e-01 + 1.42424242424242e+01 1.10480169457590e+00 7.89367459341939e-02 -1.12086468683529e-01 + 1.48484848484848e+01 1.07517912705030e+00 8.81134671681645e-02 -1.10736245553130e-01 + 1.54545454545455e+01 1.05513703714054e+00 9.73441034120854e-02 -1.10445332098790e-01 + 1.60606060606061e+01 1.03909979751391e+00 1.06615031950527e-01 -1.10471629053083e-01 + 1.66666666666667e+01 1.03037285182419e+00 1.16086945222589e-01 -1.11452522736188e-01 + 1.72727272727273e+01 1.02598020440334e+00 1.25858967571876e-01 -1.12862502655475e-01 + 1.78787878787879e+01 1.02688508760461e+00 1.35997793709910e-01 -1.14796926748810e-01 + 1.84848484848485e+01 1.04050556314885e+00 1.47897334941441e-01 -1.18027092927592e-01 + 1.90909090909091e+01 1.05662971405014e+00 1.60210090125818e-01 -1.21765865016242e-01 + 1.96969696969697e+01 1.06892917336845e+00 1.72370385761586e-01 -1.26551733685257e-01 + 2.03030303030303e+01 1.07836210245173e+00 1.84226855703769e-01 -1.31723435235985e-01 + 2.09090909090909e+01 1.08492833913008e+00 1.95779482763855e-01 -1.37432962053028e-01 + 2.15151515151515e+01 1.09149457580843e+00 2.07332109823942e-01 -1.43194849094184e-01 + 2.21212121212121e+01 1.09508251337799e+00 2.18773699953258e-01 -1.48870391290255e-01 + 2.27272727272727e+01 1.08676031896276e+00 2.29771256608312e-01 -1.54237881279540e-01 + 2.33333333333333e+01 1.07843812454753e+00 2.40768813263367e-01 -1.59641997918361e-01 + 2.39393939393939e+01 1.07011593013229e+00 2.51766369918421e-01 -1.65258999148450e-01 + 2.45454545454545e+01 1.06346338211567e+00 2.63405562369399e-01 -1.70132904338816e-01 + 2.51515151515151e+01 1.05699634637488e+00 2.75116046152996e-01 -1.74924245078642e-01 + 2.57575757575758e+01 1.05052931063409e+00 2.86826529936594e-01 -1.79715585818468e-01 + 2.63636363636364e+01 1.04481382943098e+00 2.98930776676328e-01 -1.84171410304438e-01 + 2.69696969696970e+01 1.03959946244701e+00 3.11297572847134e-01 -1.88403522528518e-01 + 2.75757575757576e+01 1.03438509546304e+00 3.23664369017940e-01 -1.92635634752598e-01 + 2.81818181818182e+01 1.02941249540321e+00 3.36209604665368e-01 -1.96751514558490e-01 + 2.87878787878788e+01 1.02500396977555e+00 3.49171163376055e-01 -2.00596208653092e-01 + 2.93939393939394e+01 1.02059544414789e+00 3.62132722086743e-01 -2.04440902747695e-01 + 3.00000000000000e+01 1.01618691852022e+00 3.75094280797430e-01 -2.08285596842297e-01 + 3.30000000000000e+01 9.96930791089291e-01 4.42658498578043e-01 -2.25638690746125e-01 + 3.60000000000000e+01 9.78250493475424e-01 5.13070549905569e-01 -2.41866371031337e-01 + 3.90000000000000e+01 9.58092634837620e-01 5.86181715938499e-01 -2.56756566563372e-01 + 4.20000000000000e+01 9.34197243420856e-01 6.60975455724981e-01 -2.71189386382951e-01 + 4.50000000000000e+01 9.08958131052610e-01 7.36189121222556e-01 -2.85513863759938e-01 + 4.80000000000000e+01 8.76369360506042e-01 8.11357652574190e-01 -2.99318564738472e-01 + 5.10000000000000e+01 8.39546103316861e-01 8.84985611770030e-01 -3.12885528690573e-01 + 5.40000000000000e+01 7.94253600616922e-01 9.55532327614396e-01 -3.25953209472103e-01 + 5.70000000000000e+01 7.48961443924963e-01 1.02607850452350e+00 -3.39030396022098e-01 + 6.00000000000000e+01 7.03669460235677e-01 1.09662441196703e+00 -3.52114744115643e-01 + 6.30000000000000e+01 6.42304649985047e-01 1.15396405534123e+00 -3.63896004000846e-01 + 6.60000000000000e+01 5.80939701964786e-01 1.21130358551679e+00 -3.75682451037757e-01 + 6.90000000000000e+01 5.19574753944523e-01 1.26864311569235e+00 -3.87472927093907e-01 + 7.20000000000000e+01 4.50573500357888e-01 1.31252792475019e+00 -3.98011457008727e-01 + 7.50000000000000e+01 3.77754250313412e-01 1.34968564868523e+00 -4.07925210836086e-01 + 7.80000000000000e+01 3.04933632222489e-01 1.38684379841819e+00 -4.17841195787456e-01 + 8.10000000000000e+01 2.30748068771223e-01 1.41576012175667e+00 -4.26898468755288e-01 + 8.40000000000000e+01 1.53832708821342e-01 1.42819336121861e+00 -4.34236382280660e-01 + 8.70000000000000e+01 7.69163612800006e-02 1.44062669566363e+00 -4.41574423427714e-01 + 9.00000000000000e+01 -3.36040174418520e-07 1.45305992240014e+00 -4.48912349036806e-01 + 9.30000000000000e+01 -5.38415146430987e-02 1.44062668293820e+00 -4.52353830558963e-01 + 9.60000000000000e+01 -1.07682698904138e-01 1.42819339598511e+00 -4.55796422926281e-01 + 9.90000000000000e+01 -1.61523894481612e-01 1.41576001404799e+00 -4.59240045315168e-01 + 1.02000000000000e+02 -2.13453578289375e-01 1.38684361845383e+00 -4.59405772291525e-01 + 1.05000000000000e+02 -2.64427526911242e-01 1.34968589451878e+00 -4.57933058035756e-01 + 1.08000000000000e+02 -3.15401526057875e-01 1.31252774478765e+00 -4.56460500541016e-01 + 1.11000000000000e+02 -3.63702613318511e-01 1.26864261896506e+00 -4.53729817735206e-01 + 1.14000000000000e+02 -4.06657958215626e-01 1.21130374584807e+00 -4.48482124934980e-01 + 1.17000000000000e+02 -4.49613275538441e-01 1.15396443469656e+00 -4.43234672446104e-01 + 1.20000000000000e+02 -4.92568557072479e-01 1.09662487869506e+00 -4.37987618819821e-01 + 1.23000000000000e+02 -5.24273305652762e-01 1.02607897125153e+00 -4.30899900449802e-01 + 1.26000000000000e+02 -5.55977975337812e-01 9.55532794347773e-01 -4.23812474118514e-01 + 1.29000000000000e+02 -5.87682487226498e-01 8.84986078503406e-01 -4.16725057602321e-01 + 1.32000000000000e+02 -6.11743957269202e-01 8.11342840122296e-01 -4.10311145379585e-01 + 1.35000000000000e+02 -6.31983915443519e-01 7.36151344151820e-01 -4.04234114284225e-01 + 1.38000000000000e+02 -6.52223041697912e-01 6.60960643393727e-01 -3.98157422646348e-01 + 1.41000000000000e+02 -6.70277141430926e-01 5.87259503028655e-01 -3.94043626890889e-01 + 1.44000000000000e+02 -6.83961170390853e-01 5.16537495536617e-01 -3.93855328257089e-01 + 1.47000000000000e+02 -6.97644694809602e-01 4.45815984052867e-01 -3.93666633192198e-01 + 1.50000000000000e+02 -7.11327966966768e-01 3.75094720564406e-01 -3.93477629010198e-01 + 1.53000000000000e+02 -7.10555758661770e-01 3.21288604729336e-01 -4.09291401293984e-01 + 1.56000000000000e+02 -7.09783519622452e-01 2.67482711700951e-01 -4.25113789480059e-01 + 1.59000000000000e+02 -7.09747287572277e-01 2.13677185443974e-01 -4.40944959963481e-01 + 1.62000000000000e+02 -6.39242744263654e-01 1.76167844671200e-01 -4.56979587409322e-01 + 1.65000000000000e+02 -5.32702098344237e-01 1.46806734460832e-01 -4.73112741890976e-01 + 1.68000000000000e+02 -4.24165693368368e-01 1.17445360706964e-01 -4.89245046545928e-01 + 1.71000000000000e+02 -3.17540377497210e-01 8.80840526647858e-02 -4.50000513056908e-01 + 1.74000000000000e+02 -2.11693558985589e-01 5.87228760490535e-02 -2.99999717902353e-01 + 1.77000000000000e+02 -1.05275486594639e-01 4.83558379259246e-02 -1.49185828331614e-01 + 1.80000000000000e+02 0.00000000000000e+00 4.74971586892991e-02 0.00000000000000e+00 diff --git a/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_15.dat b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_15.dat new file mode 100644 index 00000000..8a6d71ed --- /dev/null +++ b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_15.dat @@ -0,0 +1,254 @@ +! ------------ AirfoilInfo v1.01.x Input File ---------------------------------- +! AeroElasticSE FAST driver +! line +! line +! ------------------------------------------------------------------------------ +DEFAULT InterpOrd ! Interpolation order to use for quasi-steady table lookup {1=linear; 3=cubic spline; "default"} [default=3] +1 NonDimArea ! The non-dimensional area of the airfoil (area/chord^2) (set to 1.0 if unsure or unneeded) +@"NREL-2p8-127_AF15_Coords.txt" NumCoords ! The number of coordinates in the airfoil shape file. Set to zero if coordinates not included. +AF15_BL.txt BL_file ! The file name including the boundary layer characteristics of the profile. Ignored if the aeroacoustic module is not called. +1 NumTabs ! Number of airfoil tables in this file. Each table must have lines for Re and Ctrl. +! ------------------------------------------------------------------------------ +! data for table 1 +! ------------------------------------------------------------------------------ +6.000000 Re ! Reynolds number in millions +0 Ctrl ! Control setting (must be 0 for current AirfoilInfo) +True InclUAdata ! Is unsteady aerodynamics data included in this table? If TRUE, then include 30 UA coefficients below this line +!........................................ +-2.208961 alpha0 ! 0-lift angle of attack, depends on airfoil. +11.877956 alpha1 ! Angle of attack at f=0.7, (approximately the stall angle) for AOA>alpha0. (deg) +-10.077196 alpha2 ! Angle of attack at f=0.7, (approximately the stall angle) for AOA1] +0.000000 S2 ! Constant in the f curve best-fit for AOA> alpha1; by definition it depends on the airfoil. [ignored if UAMod<>1] +0.000000 S3 ! Constant in the f curve best-fit for alpha2<=AOA< alpha0; by definition it depends on the airfoil. [ignored if UAMod<>1] +0.000000 S4 ! Constant in the f curve best-fit for AOA< alpha2; by definition it depends on the airfoil. [ignored if UAMod<>1] +1.523431 Cn1 ! Critical value of C0n at leading edge separation. It should be extracted from airfoil data at a given Mach and Reynolds number. It can be calculated from the static value of Cn at either the break in the pitching moment or the loss of chord force at the onset of stall. It is close to the condition of maximum lift of the airfoil at low Mach numbers. +-1.245136 Cn2 ! As Cn1 for negative AOAs. +Default St_sh ! Strouhal's shedding frequency constant. [default = 0.19] +0.010644 Cd0 ! 2D drag coefficient value at 0-lift. +-0.090826 Cm0 ! 2D pitching moment coefficient about 1/4-chord location, at 0-lift, positive if nose up. [If the aerodynamics coefficients table does not include a column for Cm, this needs to be set to 0.0] +0.000000 k0 ! Constant in the \hat(x)_cp curve best-fit; = (\hat(x)_AC-0.25). [ignored if UAMod<>1] +0.000000 k1 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k2 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k3 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k1_hat ! Constant in the expression of Cc due to leading edge vortex effects. [ignored if UAMod<>1] +Default x_cp_bar ! Constant in the expression of \hat(x)_cp^v. [ignored if UAMod<>1, default = 0.2] +Default UACutout ! Angle of attack above which unsteady aerodynamics are disabled (deg). [Specifying the string "Default" sets UACutout to 45 degrees] +Default filtCutOff ! Cut-off frequency (-3 dB corner frequency) for low-pass filtering the AoA input to UA, as well as the 1st and 2nd derivatives (Hz) [default = 20] +!........................................ +! Table of aerodynamics coefficients +200 NumAlf ! Number of data lines in the following table +! Alpha Cl Cd Cm +! (deg) (-) (-) (-) +-1.80000000000000e+02 0.00000000000000e+00 4.67684423893836e-02 0.00000000000000e+00 +-1.77000000000000e+02 1.09408903050313e-01 4.67684423893836e-02 1.19449340115019e-01 +-1.74000000000000e+02 2.19827919665962e-01 5.61220773758285e-02 2.39999774321882e-01 +-1.71000000000000e+02 3.29742593401240e-01 8.41832894069106e-02 3.60000410445527e-01 +-1.68000000000000e+02 4.39652946023446e-01 1.12247441543861e-01 3.17657026395814e-01 +-1.65000000000000e+02 5.49568920893405e-01 1.40313063699431e-01 1.94143527053385e-01 +-1.62000000000000e+02 6.59436266220261e-01 1.68379605308450e-01 7.06292113109056e-02 +-1.59000000000000e+02 7.30300487636504e-01 2.05487990755536e-01 -1.10385648721879e-02 +-1.56000000000000e+02 7.23544790871733e-01 2.60679757996445e-01 -8.60356910819995e-03 +-1.53000000000000e+02 7.16970142385750e-01 3.15871546871301e-01 -6.03641287104454e-03 +-1.50000000000000e+02 7.10395253192162e-01 3.71063383075396e-01 -3.53054989193793e-03 +-1.47000000000000e+02 6.96821464496714e-01 4.41924263677891e-01 1.15622643794935e-02 +-1.44000000000000e+02 6.83247423957872e-01 5.12785414225651e-01 2.66551539940038e-02 +-1.41000000000000e+02 6.69672879714259e-01 5.83647104683221e-01 4.17481792755350e-02 +-1.38000000000000e+02 6.51701749637977e-01 6.57509515264151e-01 5.71032192754300e-02 +-1.35000000000000e+02 6.31532335564314e-01 7.32872279819475e-01 7.25892986682547e-02 +-1.32000000000000e+02 6.11362090369567e-01 8.08235905809873e-01 8.80756349445296e-02 +-1.29000000000000e+02 5.87362687378832e-01 8.82060419340625e-01 1.03702753521495e-01 +-1.26000000000000e+02 5.55704950650637e-01 9.52806700636205e-01 1.19611333221862e-01 +-1.23000000000000e+02 5.24047055768739e-01 1.02355244146660e+00 1.35519828983413e-01 +-1.20000000000000e+02 4.92389081812946e-01 1.09429791207450e+00 1.51428303263083e-01 +-1.17000000000000e+02 4.49464448320822e-01 1.15185785100299e+00 1.66519076342545e-01 +-1.14000000000000e+02 4.06539757473919e-01 1.20941754428038e+00 1.81609537109452e-01 +-1.11000000000000e+02 3.63614995985125e-01 1.26697679783968e+00 1.96699434164473e-01 +-1.08000000000000e+02 3.15335797028190e-01 1.31109215764924e+00 2.10144017964703e-01 +-1.05000000000000e+02 2.64379338566390e-01 1.34848546821470e+00 2.22765790368656e-01 +-1.02000000000000e+02 2.13422866177849e-01 1.38587835028935e+00 2.35387244205176e-01 +-9.90000000000000e+01 1.61506739379516e-01 1.41503236786356e+00 2.46653165683191e-01 +-9.60000000000000e+01 1.07671262193915e-01 1.42770829956833e+00 2.55208020338782e-01 +-9.30000000000000e+01 5.38357962810632e-02 1.44038413443613e+00 2.63762460154027e-01 +-9.00000000000000e+01 3.36004484266645e-07 1.45305992088633e+00 2.72316549083834e-01 +-8.70000000000000e+01 -5.38357411804466e-02 1.44038414740981e+00 2.75975908689839e-01 +-8.40000000000000e+01 -1.07671412729903e-01 1.42770826412360e+00 2.79637509125723e-01 +-8.10000000000000e+01 -1.61506273010176e-01 1.41503247767341e+00 2.83303463358523e-01 +-7.80000000000000e+01 -2.13422619382625e-01 1.38587853139263e+00 2.83673895090911e-01 +-7.50000000000000e+01 -2.64379675691045e-01 1.34848522082535e+00 2.82397275634580e-01 +-7.20000000000000e+01 -3.15335550238364e-01 1.31109233875070e+00 2.81119990974020e-01 +-6.90000000000000e+01 -3.63614624127447e-01 1.26697729647612e+00 2.78579207220845e-01 +-6.60000000000000e+01 -4.06539877500383e-01 1.20941738333287e+00 2.73511947958626e-01 +-6.30000000000000e+01 -4.49464732308094e-01 1.15185747018962e+00 2.68443139589274e-01 +-6.00000000000000e+01 -4.92389291260444e-01 1.09429744402618e+00 2.63372775517188e-01 +-5.70000000000000e+01 -5.24047265216237e-01 1.02355197341827e+00 2.56458829905844e-01 +-5.40000000000000e+01 -5.55705160096565e-01 9.52806232582514e-01 2.49542806281396e-01 +-5.10000000000000e+01 -5.87362896824760e-01 8.82059951286934e-01 2.42624285718169e-01 +-4.80000000000000e+01 -6.13081518081798e-01 8.08245749651705e-01 2.35914730168143e-01 +-4.50000000000000e+01 -6.35830677053252e-01 7.32897637152475e-01 2.29306703335177e-01 +-4.20000000000000e+01 -6.53421163894653e-01 6.57519359024154e-01 2.24147571871917e-01 +-3.90000000000000e+01 -6.70067066454672e-01 5.82564691354695e-01 2.19583471937992e-01 +-3.60000000000000e+01 -6.84082341201795e-01 5.09304675599610e-01 2.17192480713428e-01 +-3.30000000000000e+01 -6.97048433260438e-01 4.38755128231645e-01 2.17746484897517e-01 +-3.00000000000000e+01 -7.10395349681667e-01 3.71062942477108e-01 2.21579781653519e-01 +-2.93939393939394e+01 -7.13452692480888e-01 3.58077533205854e-01 2.23238409263915e-01 +-2.87878787878788e+01 -7.16510035280109e-01 3.45092123934599e-01 2.24897036874312e-01 +-2.81818181818182e+01 -7.19567378079330e-01 3.32106714663345e-01 2.26555664484708e-01 +-2.75757575757576e+01 -7.23015176952550e-01 3.19538672861810e-01 2.28842891870977e-01 +-2.69696969696970e+01 -7.26630328498820e-01 3.07149518178065e-01 2.31399542272472e-01 +-2.63636363636364e+01 -7.30245480045089e-01 2.94760363494321e-01 2.33956192673967e-01 +-2.57575757575758e+01 -7.34209413289690e-01 2.82634381591017e-01 2.36982384547252e-01 +-2.51515151515151e+01 -7.38696437793794e-01 2.70903097522626e-01 2.40712779195633e-01 +-2.45454545454545e+01 -7.43183462297898e-01 2.59171813454235e-01 2.44443173844013e-01 +-2.39393939393939e+01 -7.47799807451049e-01 2.47511976474211e-01 2.48330404264612e-01 +-2.33333333333333e+01 -7.53580063482705e-01 2.36495177121992e-01 2.53629186999333e-01 +-2.27272727272727e+01 -7.59360319514362e-01 2.25478377769773e-01 2.59138821302601e-01 +-2.21212121212121e+01 -7.65140575546019e-01 2.14461578417554e-01 2.64477816678713e-01 +-2.15151515151515e+01 -8.03302749793657e-01 2.08548124886777e-01 2.49301560239203e-01 +-2.09090909090909e+01 -8.50824045909576e-01 2.03910836081233e-01 2.28513888557106e-01 +-2.03030303030303e+01 -8.97768386898726e-01 1.99273547275689e-01 2.07575119743590e-01 +-1.96969696969697e+01 -9.44678207213724e-01 1.94637489543005e-01 1.86538818608059e-01 +-1.90909090909091e+01 -9.91555050415259e-01 1.90002662813539e-01 1.65441760982968e-01 +-1.84848484848485e+01 -1.03842681336623e+00 1.85480504382984e-01 1.44332068966338e-01 +-1.78787878787879e+01 -1.08529649705215e+00 1.80950527403410e-01 1.23357644166816e-01 +-1.72727272727273e+01 -1.13216603243267e+00 1.76145971766597e-01 1.02450261417032e-01 +-1.66666666666667e+01 -1.17903468591979e+00 1.71473937535991e-01 8.15425477213738e-02 +-1.60606060606061e+01 -1.22590272554085e+00 1.66848907281323e-01 6.06345632546291e-02 +-1.54545454545455e+01 -1.24540579219954e+00 1.60147463320380e-01 4.44630991177370e-02 +-1.48484848484848e+01 -1.24781000746850e+00 1.52164045091083e-01 3.08929440011085e-02 +-1.42424242424242e+01 -1.20802738977228e+00 1.41026803742556e-01 2.37904766410137e-02 +-1.36363636363636e+01 -1.16175523534967e+00 1.29449635840845e-01 1.56762299252564e-02 +-1.30303030303030e+01 -1.11115112057063e+00 1.17578013100753e-01 6.58924652136504e-03 +-1.24242424242424e+01 -1.05692194409935e+00 1.06127950509725e-01 -3.71182830764803e-03 +-1.18181818181818e+01 -1.00272814309195e+00 9.53368098006124e-02 -1.33696206088078e-02 +-1.12121212121212e+01 -9.49076573968545e-01 8.60321040274192e-02 -2.13872923605838e-02 +-1.06060606060606e+01 -8.93581807311589e-01 7.76106753832643e-02 -2.80731947658556e-02 +-1.00000000000000e+01 -8.36985941927378e-01 6.96649134803325e-02 -3.40347701647619e-02 +-9.39393939393939e+00 -7.93166380537571e-01 5.77167470270437e-02 -4.15395521632745e-02 +-8.78787878787879e+00 -7.59169809540880e-01 4.45159809940110e-02 -4.84819804761218e-02 +-8.18181818181818e+00 -7.42105465881365e-01 2.91170572332394e-02 -5.43926186316557e-02 +-7.57575757575758e+00 -6.99614592258827e-01 2.14382481096017e-02 -5.74658684394408e-02 +-6.96969696969697e+00 -6.44608817122756e-01 1.72874428994890e-02 -5.94924254124929e-02 +-6.36363636363636e+00 -5.58802274186132e-01 1.57551020164310e-02 -6.43044689253696e-02 +-5.75757575757576e+00 -4.73764998472755e-01 1.43502448275924e-02 -6.89249208066366e-02 +-5.15151515151515e+00 -3.89894394333158e-01 1.31419672724884e-02 -7.32603190020164e-02 +-4.54545454545454e+00 -3.07166264437107e-01 1.22637086666309e-02 -7.73190401255010e-02 +-3.93939393939394e+00 -2.25054198114775e-01 1.15266148059250e-02 -8.12466599743608e-02 +-3.33333333333333e+00 -1.45172725478899e-01 1.11181586895799e-02 -8.48048561058059e-02 +-2.72727272727273e+00 -6.64481817059381e-02 1.08213328544847e-02 -8.81461929096935e-02 +-2.12121212121212e+00 1.12495325557481e-02 1.06139900247299e-02 -9.12799422030186e-02 +-1.51515151515152e+00 8.85670296087496e-02 1.04479884948180e-02 -9.42942439451978e-02 +-9.09090909090912e-01 1.66213270670549e-01 1.03347362369138e-02 -9.72595244702951e-02 +-3.03030303030302e-01 2.45681839335204e-01 1.04136053686051e-02 -1.00116736668253e-01 + 3.03030303030302e-01 3.24493811021227e-01 1.05051634149457e-02 -1.02832528533338e-01 + 9.09090909090912e-01 4.02689577361445e-01 1.06029024359060e-02 -1.05409582524880e-01 + 1.51515151515152e+00 4.80450558739067e-01 1.06086084327215e-02 -1.07756982884227e-01 + 2.12121212121212e+00 5.57655020416299e-01 1.06364076844461e-02 -1.10007533488911e-01 + 2.72727272727273e+00 6.32854110854688e-01 1.08222553063749e-02 -1.12010805967812e-01 + 3.33333333333333e+00 7.07829104208440e-01 1.09871939917408e-02 -1.13813398304224e-01 + 3.93939393939394e+00 7.82726097125106e-01 1.11313590740197e-02 -1.15433563257352e-01 + 4.54545454545455e+00 8.56725036367504e-01 1.13155452275198e-02 -1.16880352315399e-01 + 5.15151515151515e+00 9.30032793828029e-01 1.15208350124478e-02 -1.18219662619805e-01 + 5.75757575757576e+00 1.00154268140207e+00 1.17795522060827e-02 -1.19293155287934e-01 + 6.36363636363637e+00 1.07164671957996e+00 1.20808443869704e-02 -1.20114824732784e-01 + 6.96969696969697e+00 1.14081776942528e+00 1.24089124959070e-02 -1.20769509296104e-01 + 7.57575757575757e+00 1.20747309170393e+00 1.27841449542467e-02 -1.20984177116947e-01 + 8.18181818181818e+00 1.27293094202657e+00 1.31971119963991e-02 -1.21040387776290e-01 + 8.78787878787879e+00 1.33631723158136e+00 1.36879819805424e-02 -1.20797951715922e-01 + 9.39393939393939e+00 1.39580208572342e+00 1.43634591973061e-02 -1.19814227819290e-01 + 1.00000000000000e+01 1.45201036734241e+00 1.51114679774447e-02 -1.18417062091605e-01 + 1.06060606060606e+01 1.49636269861419e+00 1.62052841025846e-02 -1.15842476045504e-01 + 1.12121212121212e+01 1.53223105339179e+00 1.75945580457730e-02 -1.12669856479682e-01 + 1.18181818181818e+01 1.55233724587327e+00 1.95273589024484e-02 -1.08387441695462e-01 + 1.24242424242424e+01 1.40485306788269e+00 3.66837894727473e-02 -1.10705453199216e-01 + 1.30303030303030e+01 1.19641936134212e+00 5.96341107919704e-02 -1.15524471863464e-01 + 1.36363636363636e+01 1.13694346952033e+00 6.90810774839366e-02 -1.13792452322283e-01 + 1.42424242424242e+01 1.08854773748024e+00 7.81569854013355e-02 -1.12222962444976e-01 + 1.48484848484848e+01 1.05813142651997e+00 8.67025410668526e-02 -1.10869165205536e-01 + 1.54545454545455e+01 1.03762808162079e+00 9.51813233811173e-02 -1.10006355575461e-01 + 1.60606060606061e+01 1.02128710765488e+00 1.03672155520267e-01 -1.09349864817940e-01 + 1.66666666666667e+01 1.01267698438400e+00 1.12471820673251e-01 -1.09500151103095e-01 + 1.72727272727273e+01 1.00862750152695e+00 1.21612657749372e-01 -1.10196871074556e-01 + 1.78787878787879e+01 1.01015219256151e+00 1.31170487057709e-01 -1.11561461369328e-01 + 1.84848484848485e+01 1.02487270501671e+00 1.42717764493646e-01 -1.14728141059506e-01 + 1.90909090909091e+01 1.04251728636470e+00 1.54827944679204e-01 -1.18510461076852e-01 + 1.96969696969697e+01 1.05803974641611e+00 1.67310086078875e-01 -1.23229156855034e-01 + 2.03030303030303e+01 1.07018102313405e+00 1.79415876584770e-01 -1.28428162973701e-01 + 2.09090909090909e+01 1.07894092523283e+00 1.91145294905368e-01 -1.34145582008302e-01 + 2.15151515151515e+01 1.08770082733162e+00 2.02874713225965e-01 -1.39876119614393e-01 + 2.21212121212121e+01 1.09305671932835e+00 2.14461578417554e-01 -1.45612662747519e-01 + 2.27272727272727e+01 1.08480007339250e+00 2.25478377769773e-01 -1.51382551672362e-01 + 2.33333333333333e+01 1.07654342745665e+00 2.36495177121992e-01 -1.57161617206521e-01 + 2.39393939393939e+01 1.06828678152080e+00 2.47511976474211e-01 -1.62994019825784e-01 + 2.45454545454545e+01 1.06169131258261e+00 2.59171813454235e-01 -1.68042877714576e-01 + 2.51515151515151e+01 1.05528041489594e+00 2.70903097522626e-01 -1.73004676950534e-01 + 2.57575757575758e+01 1.04886951720927e+00 2.82634381591017e-01 -1.77966476186493e-01 + 2.63636363636364e+01 1.04320589180274e+00 2.94760363494321e-01 -1.82573390251451e-01 + 2.69696969696970e+01 1.03804052533334e+00 3.07149518178065e-01 -1.86943677436481e-01 + 2.75757575757576e+01 1.03287515886394e+00 3.19538672861810e-01 -1.91313964621511e-01 + 2.81818181818182e+01 1.02794990386129e+00 3.32106714663345e-01 -1.95560901544960e-01 + 2.87878787878788e+01 1.02358486088827e+00 3.45092123934599e-01 -1.99520045880541e-01 + 2.93939393939394e+01 1.01921981791524e+00 3.58077533205854e-01 -2.03479190216121e-01 + 3.00000000000000e+01 1.01485477494222e+00 3.71062942477108e-01 -2.07438334551702e-01 + 3.30000000000000e+01 9.95781979176941e-01 4.38755128231646e-01 -2.25248633303694e-01 + 3.60000000000000e+01 9.77261344047451e-01 5.09304675599610e-01 -2.41856194661193e-01 + 3.90000000000000e+01 9.57239163797111e-01 5.82564691354695e-01 -2.57340269463326e-01 + 4.20000000000000e+01 9.33459403203811e-01 6.57519359024154e-01 -2.72202941735538e-01 + 4.50000000000000e+01 9.08329968243298e-01 7.32897637152475e-01 -2.86898149313765e-01 + 4.80000000000000e+01 8.75830570639952e-01 8.08245749651705e-01 -3.01010122893952e-01 + 5.10000000000000e+01 8.39089169459949e-01 8.82059951286934e-01 -3.14864677792113e-01 + 5.40000000000000e+01 7.93863488417853e-01 9.52806232582514e-01 -3.28197186474091e-01 + 5.70000000000000e+01 7.48638152873260e-01 1.02355197341827e+00 -3.41532795817309e-01 + 6.00000000000000e+01 7.03412990076103e-01 1.09429744402618e+00 -3.54870873320022e-01 + 6.30000000000000e+01 6.42091935358749e-01 1.15185747018962e+00 -3.66903187497261e-01 + 6.60000000000000e+01 5.80770742674055e-01 1.20941738333287e+00 -3.78937520560764e-01 + 6.90000000000000e+01 5.19449549989362e-01 1.26697729647612e+00 -3.90973534083543e-01 + 7.20000000000000e+01 4.50479586567496e-01 1.31109233875070e+00 -4.01764478228043e-01 + 7.50000000000000e+01 3.77685394357568e-01 1.34848522082535e+00 -4.11933663285151e-01 + 7.80000000000000e+01 3.04889770136817e-01 1.38587853139263e+00 -4.22104253439653e-01 + 8.10000000000000e+01 2.30723589089482e-01 1.41503247767341e+00 -4.31419619766910e-01 + 8.40000000000000e+01 1.53816388998543e-01 1.42770826412360e+00 -4.39023497820268e-01 + 8.70000000000000e+01 7.69082013784813e-02 1.44038414740981e+00 -4.46628018116478e-01 + 9.00000000000000e+01 -3.36004484498046e-07 1.45305992088633e+00 -4.54233190688659e-01 + 9.30000000000000e+01 -5.38357962810632e-02 1.44038413443613e+00 -4.57885786719435e-01 + 9.60000000000000e+01 -1.07671262193915e-01 1.42770829956833e+00 -4.61538677552376e-01 + 9.90000000000000e+01 -1.61506739379516e-01 1.41503236786356e+00 -4.65191853174755e-01 + 1.02000000000000e+02 -2.13422866177849e-01 1.38587835028935e+00 -4.65561570743231e-01 + 1.05000000000000e+02 -2.64379338566390e-01 1.34848546821470e+00 -4.64289725865889e-01 + 1.08000000000000e+02 -3.15335797028190e-01 1.31109215764924e+00 -4.63017478275328e-01 + 1.11000000000000e+02 -3.63614995985125e-01 1.26697679783968e+00 -4.60482928481624e-01 + 1.14000000000000e+02 -4.06539757473920e-01 1.20941754428038e+00 -4.55423611669011e-01 + 1.17000000000000e+02 -4.49464448320822e-01 1.15185785100299e+00 -4.50364064972578e-01 + 1.20000000000000e+02 -4.92389081812947e-01 1.09429791207450e+00 -4.45304488017237e-01 + 1.23000000000000e+02 -5.24047055768740e-01 1.02355244146660e+00 -4.38404309098436e-01 + 1.26000000000000e+02 -5.55704950650637e-01 9.52806700636205e-01 -4.31504104372525e-01 + 1.29000000000000e+02 -5.87362687378832e-01 8.82060419340624e-01 -4.24603632838989e-01 + 1.32000000000000e+02 -6.11362090369567e-01 8.08235905809873e-01 -4.18403572366859e-01 + 1.35000000000000e+02 -6.31532335564314e-01 7.32872279819475e-01 -4.12553840848231e-01 + 1.38000000000000e+02 -6.51701749637977e-01 6.57509515264151e-01 -4.06704379408258e-01 + 1.41000000000000e+02 -6.69672879714259e-01 5.83647104683220e-01 -4.02869826230333e-01 + 1.44000000000000e+02 -6.83247423957872e-01 5.12785414225651e-01 -4.03065008320271e-01 + 1.47000000000000e+02 -6.96821464496714e-01 4.41924263677891e-01 -4.03260077987011e-01 + 1.50000000000000e+02 -7.10395253192162e-01 3.71063383075396e-01 -4.03455201443317e-01 + 1.53000000000000e+02 -7.06372114301663e-01 3.17621444101635e-01 -4.19162152168120e-01 + 1.56000000000000e+02 -7.02348949774489e-01 2.64179749134792e-01 -4.34871119537335e-01 + 1.59000000000000e+02 -6.98510217081455e-01 2.10738460990774e-01 -4.50581918807084e-01 + 1.62000000000000e+02 -6.27628255763012e-01 1.73632254525860e-01 -4.64655763669874e-01 + 1.65000000000000e+02 -5.23023338960169e-01 1.44693727049735e-01 -4.77910305590711e-01 + 1.68000000000000e+02 -4.18349440675210e-01 1.15754931187723e-01 -4.91164080985006e-01 + 1.71000000000000e+02 -3.13741957550692e-01 8.68162240683767e-02 -4.50000513056908e-01 + 1.74000000000000e+02 -2.09161222825938e-01 5.78776944385058e-02 -2.99999717902353e-01 + 1.77000000000000e+02 -1.04100854082611e-01 4.76423262875679e-02 -1.49311675143774e-01 + 1.80000000000000e+02 0.00000000000000e+00 4.67684423893836e-02 0.00000000000000e+00 diff --git a/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_16.dat b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_16.dat new file mode 100644 index 00000000..42e6caf1 --- /dev/null +++ b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_16.dat @@ -0,0 +1,254 @@ +! ------------ AirfoilInfo v1.01.x Input File ---------------------------------- +! AeroElasticSE FAST driver +! line +! line +! ------------------------------------------------------------------------------ +DEFAULT InterpOrd ! Interpolation order to use for quasi-steady table lookup {1=linear; 3=cubic spline; "default"} [default=3] +1 NonDimArea ! The non-dimensional area of the airfoil (area/chord^2) (set to 1.0 if unsure or unneeded) +@"NREL-2p8-127_AF16_Coords.txt" NumCoords ! The number of coordinates in the airfoil shape file. Set to zero if coordinates not included. +AF16_BL.txt BL_file ! The file name including the boundary layer characteristics of the profile. Ignored if the aeroacoustic module is not called. +1 NumTabs ! Number of airfoil tables in this file. Each table must have lines for Re and Ctrl. +! ------------------------------------------------------------------------------ +! data for table 1 +! ------------------------------------------------------------------------------ +6.000000 Re ! Reynolds number in millions +0 Ctrl ! Control setting (must be 0 for current AirfoilInfo) +True InclUAdata ! Is unsteady aerodynamics data included in this table? If TRUE, then include 30 UA coefficients below this line +!........................................ +-2.302844 alpha0 ! 0-lift angle of attack, depends on airfoil. +11.519512 alpha1 ! Angle of attack at f=0.7, (approximately the stall angle) for AOA>alpha0. (deg) +-10.603134 alpha2 ! Angle of attack at f=0.7, (approximately the stall angle) for AOA1] +0.000000 S2 ! Constant in the f curve best-fit for AOA> alpha1; by definition it depends on the airfoil. [ignored if UAMod<>1] +0.000000 S3 ! Constant in the f curve best-fit for alpha2<=AOA< alpha0; by definition it depends on the airfoil. [ignored if UAMod<>1] +0.000000 S4 ! Constant in the f curve best-fit for AOA< alpha2; by definition it depends on the airfoil. [ignored if UAMod<>1] +1.490978 Cn1 ! Critical value of C0n at leading edge separation. It should be extracted from airfoil data at a given Mach and Reynolds number. It can be calculated from the static value of Cn at either the break in the pitching moment or the loss of chord force at the onset of stall. It is close to the condition of maximum lift of the airfoil at low Mach numbers. +-1.228842 Cn2 ! As Cn1 for negative AOAs. +Default St_sh ! Strouhal's shedding frequency constant. [default = 0.19] +0.010387 Cd0 ! 2D drag coefficient value at 0-lift. +-0.097277 Cm0 ! 2D pitching moment coefficient about 1/4-chord location, at 0-lift, positive if nose up. [If the aerodynamics coefficients table does not include a column for Cm, this needs to be set to 0.0] +0.000000 k0 ! Constant in the \hat(x)_cp curve best-fit; = (\hat(x)_AC-0.25). [ignored if UAMod<>1] +0.000000 k1 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k2 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k3 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k1_hat ! Constant in the expression of Cc due to leading edge vortex effects. [ignored if UAMod<>1] +Default x_cp_bar ! Constant in the expression of \hat(x)_cp^v. [ignored if UAMod<>1, default = 0.2] +Default UACutout ! Angle of attack above which unsteady aerodynamics are disabled (deg). [Specifying the string "Default" sets UACutout to 45 degrees] +Default filtCutOff ! Cut-off frequency (-3 dB corner frequency) for low-pass filtering the AoA input to UA, as well as the 1st and 2nd derivatives (Hz) [default = 20] +!........................................ +! Table of aerodynamics coefficients +200 NumAlf ! Number of data lines in the following table +! Alpha Cl Cd Cm +! (deg) (-) (-) (-) +-1.80000000000000e+02 0.00000000000000e+00 4.74945271221455e-02 0.00000000000000e+00 +-1.77000000000000e+02 1.09026165719319e-01 4.74945271221455e-02 1.19452717008645e-01 +-1.74000000000000e+02 2.19050122417552e-01 5.69933789541972e-02 2.39999774321882e-01 +-1.71000000000000e+02 3.28575719604901e-01 8.54902462894429e-02 3.60000410445527e-01 +-1.68000000000000e+02 4.38106914174825e-01 1.13986527655115e-01 3.17778142294727e-01 +-1.65000000000000e+02 5.47644046044007e-01 1.42482516042840e-01 1.94446315387067e-01 +-1.62000000000000e+02 6.57185375418956e-01 1.70979335776501e-01 7.11135800063474e-02 +-1.59000000000000e+02 7.28986558567270e-01 2.08325862036029e-01 -1.07467958526159e-02 +-1.56000000000000e+02 7.23604309898402e-01 2.63371501965611e-01 -1.08174141591834e-02 +-1.53000000000000e+02 7.17767305056863e-01 3.18417162412815e-01 -1.14148679848354e-02 +-1.50000000000000e+02 7.12445310173410e-01 3.73462869777982e-01 -1.26457400718686e-02 +-1.47000000000000e+02 6.98630831673898e-01 4.44240664843570e-01 2.75536840347873e-03 +-1.44000000000000e+02 6.84816100411641e-01 5.15018714390009e-01 1.81567857412231e-02 +-1.41000000000000e+02 6.71000863605846e-01 5.85797272916321e-01 3.36066126261243e-02 +-1.38000000000000e+02 6.52847363996135e-01 6.59563695332857e-01 4.92127237288619e-02 +-1.35000000000000e+02 6.32524741785104e-01 7.34824043633297e-01 6.48870780422191e-02 +-1.32000000000000e+02 6.12201334294277e-01 8.10085206753381e-01 8.05597032537663e-02 +-1.29000000000000e+02 5.88065552379780e-01 8.83801868347751e-01 9.63550603105852e-02 +-1.26000000000000e+02 5.56305003551198e-01 9.54429519550126e-01 1.12398380329180e-01 +-1.23000000000000e+02 5.24544329085952e-01 1.02505663119359e+00 1.28440896746455e-01 +-1.20000000000000e+02 4.92783591804722e-01 1.09568347306768e+00 1.44482743848553e-01 +-1.17000000000000e+02 4.49791636415260e-01 1.15311205772626e+00 1.59698551465877e-01 +-1.14000000000000e+02 4.06799639145038e-01 1.21054039721062e+00 1.74914207352244e-01 +-1.11000000000000e+02 3.63807602041395e-01 1.26796829798034e+00 1.90129494093679e-01 +-1.08000000000000e+02 3.15480318387913e-01 1.31194660547628e+00 2.03701386725598e-01 +-1.05000000000000e+02 2.64485370834833e-01 1.34920001392269e+00 2.16452268723353e-01 +-1.02000000000000e+02 2.13490407640989e-01 1.38645299548144e+00 2.29203915346582e-01 +-9.90000000000000e+01 1.61544432084705e-01 1.41546560806078e+00 2.40600993496564e-01 +-9.60000000000000e+01 1.07696390610193e-01 1.42799712574756e+00 2.49288387037645e-01 +-9.30000000000000e+01 5.38483605044154e-02 1.44052854770060e+00 2.57977933040283e-01 +-9.00000000000000e+01 3.36082901150735e-07 1.45305992178765e+00 2.66670007912819e-01 +-8.70000000000000e+01 -5.38483053909395e-02 1.44052856052647e+00 2.70653828346413e-01 +-8.40000000000000e+01 -1.07696541181314e-01 1.42799709070664e+00 2.74632091077504e-01 +-8.10000000000000e+01 -1.61543965606523e-01 1.41546571661960e+00 2.78605161493305e-01 +-7.80000000000000e+01 -2.13490160659344e-01 1.38645317590716e+00 2.79287028552001e-01 +-7.50000000000000e+01 -2.64485708214139e-01 1.34919976745892e+00 2.78321604655193e-01 +-7.20000000000000e+01 -3.15480071411678e-01 1.31194678590016e+00 2.77352606273105e-01 +-6.90000000000000e+01 -3.63807229600907e-01 1.26796879547887e+00 2.75114638009095e-01 +-6.60000000000000e+01 -4.06799759359618e-01 1.21054023663040e+00 2.70342633491159e-01 +-6.30000000000000e+01 -4.49791920847929e-01 1.15311167778193e+00 2.65569198485011e-01 +-6.00000000000000e+01 -4.92783801932097e-01 1.09568300580419e+00 2.60795303619874e-01 +-5.70000000000000e+01 -5.24544539213326e-01 1.02505616393010e+00 2.54185204039382e-01 +-5.40000000000000e+01 -5.56305213677325e-01 9.54429052281285e-01 2.47577553322180e-01 +-5.10000000000000e+01 -5.88065762505907e-01 8.83801401078910e-01 2.40973778659848e-01 +-4.80000000000000e+01 -6.13910354720703e-01 8.10097993520892e-01 2.34611596779972e-01 +-4.50000000000000e+01 -6.36797063706404e-01 7.34856757216810e-01 2.28377676012707e-01 +-4.20000000000000e+01 -6.54556371048421e-01 6.59576481995557e-01 2.23680283338938e-01 +-3.90000000000000e+01 -6.71380181626923e-01 5.84717599999870e-01 2.19536883348591e-01 +-3.60000000000000e+01 -6.85604200137604e-01 5.11546160178582e-01 2.17305088035508e-01 +-3.30000000000000e+01 -6.98815713908257e-01 4.41078428348352e-01 2.18054288333084e-01 +-3.00000000000000e+01 -7.12445408634725e-01 3.73462429674547e-01 2.22124678427173e-01 +-2.93939393939394e+01 -7.15569260532856e-01 3.60491220538288e-01 2.23842948054128e-01 +-2.87878787878788e+01 -7.18693112430987e-01 3.47520011402029e-01 2.25561217681083e-01 +-2.81818181818182e+01 -7.21816964329118e-01 3.34548802265771e-01 2.27279487308038e-01 +-2.75757575757576e+01 -7.25337539045798e-01 3.21994339673895e-01 2.29635020906344e-01 +-2.69696969696970e+01 -7.29028152413596e-01 3.09618498066121e-01 2.32263691065060e-01 +-2.63636363636364e+01 -7.32718765781393e-01 2.97242656458348e-01 2.34892361223777e-01 +-2.57575757575758e+01 -7.36762602567382e-01 2.85129614107284e-01 2.37997233303781e-01 +-2.51515151515151e+01 -7.41336192157463e-01 2.73410709392586e-01 2.41816297280826e-01 +-2.45454545454545e+01 -7.45909781747544e-01 2.61691804677889e-01 2.45635361257870e-01 +-2.39393939393939e+01 -7.50627141320397e-01 2.50043674398799e-01 2.49515043488697e-01 +-2.33333333333333e+01 -7.56638458572749e-01 2.39032527742441e-01 2.53940301739542e-01 +-2.27272727272727e+01 -7.62649775825102e-01 2.28021381086083e-01 2.57853785491344e-01 +-2.21212121212121e+01 -7.68661093077454e-01 2.17010234429726e-01 2.62068606039781e-01 +-2.15151515151515e+01 -8.07233018911813e-01 2.10719432824284e-01 2.44666939257051e-01 +-2.09090909090909e+01 -8.50063944721421e-01 2.05609021115132e-01 2.23825168737330e-01 +-2.03030303030303e+01 -8.94818933511164e-01 2.00498609405980e-01 2.03531509688972e-01 +-1.96969696969697e+01 -9.39301590592824e-01 1.95388221736857e-01 1.83458906167973e-01 +-1.90909090909091e+01 -9.83659564135496e-01 1.90277858106401e-01 1.63473959738679e-01 +-1.84848484848485e+01 -1.02835646060585e+00 1.84862741269290e-01 1.43541881926139e-01 +-1.78787878787879e+01 -1.07312022949524e+00 1.79623630734647e-01 1.23006204069627e-01 +-1.72727272727273e+01 -1.11789561032257e+00 1.75305320947758e-01 1.02174031312229e-01 +-1.66666666666667e+01 -1.16291637243167e+00 1.70479646552578e-01 8.13469192385163e-02 +-1.60606060606061e+01 -1.20810673312181e+00 1.65435507128552e-01 6.05261011893848e-02 +-1.54545454545455e+01 -1.22780192188674e+00 1.58414016648205e-01 4.42999154215266e-02 +-1.48484848484848e+01 -1.23148075482471e+00 1.50176007301149e-01 3.06001307793610e-02 +-1.42424242424242e+01 -1.19557688058349e+00 1.38991906593942e-01 2.19117759370747e-02 +-1.36363636363636e+01 -1.15320275631460e+00 1.27391804267069e-01 1.07082871223446e-02 +-1.30303030303030e+01 -1.10624218648539e+00 1.15510306693132e-01 -8.83566244868970e-04 +-1.24242424242424e+01 -1.05404262149901e+00 1.03763709632377e-01 -1.08587103233837e-02 +-1.18181818181818e+01 -1.00136072816888e+00 9.26167355272088e-02 -1.96543223095588e-02 +-1.12121212121212e+01 -9.48585842590762e-01 8.31140514128371e-02 -2.58402153588698e-02 +-1.06060606060606e+01 -8.93667893889375e-01 7.46227143327008e-02 -3.16390840974881e-02 +-1.00000000000000e+01 -8.38065195025141e-01 6.66511845807474e-02 -3.72575661487416e-02 +-9.39393939393939e+00 -7.95410787978230e-01 5.51236226526759e-02 -4.38865668044484e-02 +-8.78787878787879e+00 -7.59114580119346e-01 4.22612717076337e-02 -5.05975414003474e-02 +-8.18181818181818e+00 -7.39908303358907e-01 2.65347518460736e-02 -5.75870121728342e-02 +-7.57575757575758e+00 -6.95515216031812e-01 1.93744036977655e-02 -6.18696615221871e-02 +-6.96969696969697e+00 -6.38970352980065e-01 1.56903682577269e-02 -6.50444957534814e-02 +-6.36363636363636e+00 -5.53050978116223e-01 1.44330515252630e-02 -7.04916309908320e-02 +-5.75757575757576e+00 -4.67855482297821e-01 1.32728500481496e-02 -7.56445389562658e-02 +-5.15151515151515e+00 -3.83761883334006e-01 1.22747621729221e-02 -8.03433974705679e-02 +-4.54545454545454e+00 -3.00853428667449e-01 1.15921315939537e-02 -8.44964464276008e-02 +-3.93939393939394e+00 -2.18316833870855e-01 1.10444241869388e-02 -8.84303296892449e-02 +-3.33333333333333e+00 -1.35802226396340e-01 1.06756393000342e-02 -9.19189227982073e-02 +-2.72727272727273e+00 -5.52401875853970e-02 1.04478510242675e-02 -9.51462086023917e-02 +-2.12121212121212e+00 2.36396912458736e-02 1.03604338233977e-02 -9.81888615779641e-02 +-1.51515151515152e+00 1.01484614889655e-01 1.02452048792184e-02 -1.01004246307992e-01 +-9.09090909090912e-01 1.79466580667274e-01 1.01619214134529e-02 -1.03750330378995e-01 +-3.03030303030302e-01 2.59087622411868e-01 1.02426571705537e-02 -1.06360316407136e-01 + 3.03030303030302e-01 3.37837592391149e-01 1.03303065575862e-02 -1.08843506321385e-01 + 9.09090909090912e-01 4.15789971549744e-01 1.04212147734708e-02 -1.11177829034995e-01 + 1.51515151515152e+00 4.93147895935465e-01 1.04236090925569e-02 -1.13298457665409e-01 + 2.12121212121212e+00 5.69859535842775e-01 1.04645134860512e-02 -1.15323446159398e-01 + 2.72727272727273e+00 6.44307642449725e-01 1.06495299479427e-02 -1.17170718042645e-01 + 3.33333333333333e+00 7.18600940028201e-01 1.08126791422125e-02 -1.18836030380812e-01 + 3.93939393939394e+00 7.92950170251859e-01 1.09043051654465e-02 -1.20329319459463e-01 + 4.54545454545455e+00 8.66750625755535e-01 1.10287283292864e-02 -1.21622097750385e-01 + 5.15151515151515e+00 9.39936884951220e-01 1.11859719302871e-02 -1.22800063053947e-01 + 5.75757575757576e+00 1.01143404956829e+00 1.14111475039848e-02 -1.23696733437718e-01 + 6.36363636363637e+00 1.08182810267221e+00 1.16720384522875e-02 -1.24300128967657e-01 + 6.96969696969697e+00 1.15154797840494e+00 1.19507072068761e-02 -1.24706383395138e-01 + 7.57575757575757e+00 1.21829984832910e+00 1.23111001660822e-02 -1.24318393141766e-01 + 8.18181818181818e+00 1.28284334003200e+00 1.28453551133823e-02 -1.23573477309161e-01 + 8.78787878787879e+00 1.34152950781049e+00 1.37024581751005e-02 -1.22008658301098e-01 + 9.39393939393939e+00 1.39175204718020e+00 1.50501911010927e-02 -1.20764566885121e-01 + 1.00000000000000e+01 1.44072055032551e+00 1.67619493434159e-02 -1.19700808310407e-01 + 1.06060606060606e+01 1.47445006881312e+00 1.86588668153617e-02 -1.17383563054315e-01 + 1.12121212121212e+01 1.50211111367966e+00 2.06442638039865e-02 -1.13986779446044e-01 + 1.18181818181818e+01 1.51849743382808e+00 2.27949008726186e-02 -1.08801154929910e-01 + 1.24242424242424e+01 1.38110104869832e+00 3.91932789258445e-02 -1.10609411291075e-01 + 1.30303030303030e+01 1.17394609485373e+00 6.11116586730917e-02 -1.14753045755195e-01 + 1.36363636363636e+01 1.12719502884985e+00 7.05126133472740e-02 -1.13285854419029e-01 + 1.42424242424242e+01 1.08888194901864e+00 7.96731387425781e-02 -1.11992721439345e-01 + 1.48484848484848e+01 1.06009153338648e+00 8.83736363016277e-02 -1.11029145646405e-01 + 1.54545454545455e+01 1.04088100180195e+00 9.68845274277538e-02 -1.10082901069663e-01 + 1.60606060606061e+01 1.02566184269085e+00 1.05353288508621e-01 -1.09447986832365e-01 + 1.66666666666667e+01 1.01747136523085e+00 1.14011650931451e-01 -1.09533721766659e-01 + 1.72727272727273e+01 1.01393796533581e+00 1.23111695493764e-01 -1.10194974676891e-01 + 1.78787878787879e+01 1.01620977550644e+00 1.32751579382771e-01 -1.11556728709361e-01 + 1.84848484848485e+01 1.03062727147662e+00 1.44357732350225e-01 -1.14737403733058e-01 + 1.90909090909091e+01 1.04771493788588e+00 1.56504624193137e-01 -1.18523866085458e-01 + 1.96969696969697e+01 1.06291878178938e+00 1.68930683382824e-01 -1.23167550096525e-01 + 2.03030303030303e+01 1.07502785257006e+00 1.81134979640342e-01 -1.28324656352032e-01 + 2.09090909090909e+01 1.08382115536938e+00 1.93117500419765e-01 -1.33815690623442e-01 + 2.15151515151515e+01 1.09214908926105e+00 2.05100021199187e-01 -1.39246581437727e-01 + 2.21212121212121e+01 1.09715356486127e+00 2.16895622980487e-01 -1.44828119061210e-01 + 2.27272727272727e+01 1.08886762688942e+00 2.27943741095172e-01 -1.50978244430421e-01 + 2.33333333333333e+01 1.08058168891757e+00 2.38991859209858e-01 -1.57084368281988e-01 + 2.39393939393939e+01 1.07229575094571e+00 2.50039977324543e-01 -1.62956004038701e-01 + 2.45454545454545e+01 1.06558611366856e+00 2.61691804677889e-01 -1.68040941931674e-01 + 2.51515151515151e+01 1.05905161714547e+00 2.73410709392586e-01 -1.73040662366437e-01 + 2.57575757575758e+01 1.05251712062237e+00 2.85129614107284e-01 -1.78042939631076e-01 + 2.63636363636364e+01 1.04673941380572e+00 2.97242656458348e-01 -1.82687214968074e-01 + 2.69696969696970e+01 1.04146631186305e+00 3.09618498066121e-01 -1.87092862759889e-01 + 2.75757575757576e+01 1.03619320992039e+00 3.21994339673895e-01 -1.91500121873642e-01 + 2.81818181818182e+01 1.03116398723408e+00 3.34548802265770e-01 -1.95783309953570e-01 + 2.87878787878788e+01 1.02670376733233e+00 3.47520011402030e-01 -1.99774488550039e-01 + 2.93939393939394e+01 1.02224354743058e+00 3.60491220538288e-01 -2.03766728259228e-01 + 3.00000000000000e+01 1.01778332752883e+00 3.73462429674547e-01 -2.07760038049125e-01 + 3.30000000000000e+01 9.98306668405358e-01 4.41078428348352e-01 -2.25710390737701e-01 + 3.60000000000000e+01 9.79435247436346e-01 5.11546160178582e-01 -2.42439672107783e-01 + 3.90000000000000e+01 9.59115016848787e-01 5.84717599999870e-01 -2.58725778460445e-01 + 4.20000000000000e+01 9.35081102871063e-01 6.59576481995558e-01 -2.74139975914325e-01 + 4.50000000000000e+01 9.09710553576705e-01 7.34856757216810e-01 -2.89288459990168e-01 + 4.80000000000000e+01 8.77014675428035e-01 8.10097993520892e-01 -3.03752712432158e-01 + 5.10000000000000e+01 8.40093342319397e-01 8.83801401078911e-01 -3.17922061767336e-01 + 5.40000000000000e+01 7.94720827645917e-01 9.54429052281285e-01 -3.31525536369943e-01 + 5.70000000000000e+01 7.49348627860369e-01 1.02505616393010e+00 -3.45117992160713e-01 + 6.00000000000000e+01 7.03976585517588e-01 1.09568300580419e+00 -3.58702045370939e-01 + 6.30000000000000e+01 6.42559375800653e-01 1.15311167778193e+00 -3.70952105943644e-01 + 6.60000000000000e+01 5.81142028551168e-01 1.21054023663040e+00 -3.83194946194241e-01 + 6.90000000000000e+01 5.19724681301684e-01 1.26796879547887e+00 -3.95431861953200e-01 + 7.20000000000000e+01 4.50686006342368e-01 1.31194678590016e+00 -4.06412636751425e-01 + 7.50000000000000e+01 3.77836823546866e-01 1.34919976745892e+00 -4.16762432040660e-01 + 7.80000000000000e+01 3.04986205955287e-01 1.38645317590716e+00 -4.27107489371432e-01 + 8.10000000000000e+01 2.30777377649507e-01 1.41546571661960e+00 -4.36589691718973e-01 + 8.40000000000000e+01 1.53852221672675e-01 1.42799709070664e+00 -4.44350170094074e-01 + 8.70000000000000e+01 7.69261097609987e-02 1.44052856052647e+00 -4.52106372914785e-01 + 9.00000000000000e+01 -3.36082901382020e-07 1.45305992178765e+00 -4.59858962710058e-01 + 9.30000000000000e+01 -5.38483605044154e-02 1.44052854770060e+00 -4.63848553313885e-01 + 9.60000000000000e+01 -1.07696390610194e-01 1.42799712574756e+00 -4.67844287195712e-01 + 9.90000000000000e+01 -1.61544432084705e-01 1.41546560806078e+00 -4.71846453257926e-01 + 1.02000000000000e+02 -2.13490407640989e-01 1.38645299548144e+00 -4.72567917825502e-01 + 1.05000000000000e+02 -2.64485370834833e-01 1.34920001392269e+00 -4.71652413145928e-01 + 1.08000000000000e+02 -3.15480318387913e-01 1.31194660547628e+00 -4.70694898637910e-01 + 1.11000000000000e+02 -3.63807602041395e-01 1.26796829798034e+00 -4.68443341138964e-01 + 1.14000000000000e+02 -4.06799639145038e-01 1.21054039721062e+00 -4.63658575489138e-01 + 1.17000000000000e+02 -4.49791636415260e-01 1.15311205772626e+00 -4.58872593540100e-01 + 1.20000000000000e+02 -4.92783591804723e-01 1.09568347306768e+00 -4.54085669273530e-01 + 1.23000000000000e+02 -5.24544329085952e-01 1.02505663119359e+00 -4.47459524176604e-01 + 1.26000000000000e+02 -5.56305003551198e-01 9.54429519550126e-01 -4.40832384971193e-01 + 1.29000000000000e+02 -5.88065552379780e-01 8.83801868347751e-01 -4.34204079889270e-01 + 1.32000000000000e+02 -6.12201334294277e-01 8.10085206753381e-01 -4.28311374168508e-01 + 1.35000000000000e+02 -6.32524741785104e-01 7.34824043633297e-01 -4.22785962751293e-01 + 1.38000000000000e+02 -6.52847363996135e-01 6.59563695332856e-01 -4.17259798695567e-01 + 1.41000000000000e+02 -6.71000863605846e-01 5.85797272916321e-01 -4.13816791549941e-01 + 1.44000000000000e+02 -6.84816100411641e-01 5.15018714390009e-01 -4.14540480801535e-01 + 1.47000000000000e+02 -6.98630831673898e-01 4.44240664843570e-01 -4.15262578060876e-01 + 1.50000000000000e+02 -7.12445310173410e-01 3.73462869777981e-01 -4.15983399559589e-01 + 1.53000000000000e+02 -7.07009533624438e-01 3.20145904015172e-01 -4.31332989170919e-01 + 1.56000000000000e+02 -7.02319196022267e-01 2.66829166731978e-01 -4.46674211305675e-01 + 1.59000000000000e+02 -6.97067607564390e-01 2.13512805022704e-01 -4.61700248148900e-01 + 1.62000000000000e+02 -6.25252484559990e-01 1.76166650176245e-01 -4.73355693794957e-01 + 1.65000000000000e+02 -5.21043473383171e-01 1.46805733824602e-01 -4.83347659534527e-01 + 1.68000000000000e+02 -4.16835056347187e-01 1.17444553927237e-01 -4.93339032716489e-01 + 1.71000000000000e+02 -3.12626441266809e-01 8.80834460119835e-02 -4.50000513056908e-01 + 1.74000000000000e+02 -2.08417430088600e-01 5.87224820643139e-02 -2.99999717902353e-01 + 1.77000000000000e+02 -1.03734285731640e-01 4.83552281802738e-02 -1.49315896260807e-01 + 1.80000000000000e+02 0.00000000000000e+00 4.74945271221455e-02 0.00000000000000e+00 diff --git a/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_17.dat b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_17.dat new file mode 100644 index 00000000..217af07d --- /dev/null +++ b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_17.dat @@ -0,0 +1,254 @@ +! ------------ AirfoilInfo v1.01.x Input File ---------------------------------- +! AeroElasticSE FAST driver +! line +! line +! ------------------------------------------------------------------------------ +DEFAULT InterpOrd ! Interpolation order to use for quasi-steady table lookup {1=linear; 3=cubic spline; "default"} [default=3] +1 NonDimArea ! The non-dimensional area of the airfoil (area/chord^2) (set to 1.0 if unsure or unneeded) +@"NREL-2p8-127_AF17_Coords.txt" NumCoords ! The number of coordinates in the airfoil shape file. Set to zero if coordinates not included. +AF17_BL.txt BL_file ! The file name including the boundary layer characteristics of the profile. Ignored if the aeroacoustic module is not called. +1 NumTabs ! Number of airfoil tables in this file. Each table must have lines for Re and Ctrl. +! ------------------------------------------------------------------------------ +! data for table 1 +! ------------------------------------------------------------------------------ +6.000000 Re ! Reynolds number in millions +0 Ctrl ! Control setting (must be 0 for current AirfoilInfo) +True InclUAdata ! Is unsteady aerodynamics data included in this table? If TRUE, then include 30 UA coefficients below this line +!........................................ +-2.516492 alpha0 ! 0-lift angle of attack, depends on airfoil. +10.239483 alpha1 ! Angle of attack at f=0.7, (approximately the stall angle) for AOA>alpha0. (deg) +-11.166956 alpha2 ! Angle of attack at f=0.7, (approximately the stall angle) for AOA1] +0.000000 S2 ! Constant in the f curve best-fit for AOA> alpha1; by definition it depends on the airfoil. [ignored if UAMod<>1] +0.000000 S3 ! Constant in the f curve best-fit for alpha2<=AOA< alpha0; by definition it depends on the airfoil. [ignored if UAMod<>1] +0.000000 S4 ! Constant in the f curve best-fit for AOA< alpha2; by definition it depends on the airfoil. [ignored if UAMod<>1] +1.381088 Cn1 ! Critical value of C0n at leading edge separation. It should be extracted from airfoil data at a given Mach and Reynolds number. It can be calculated from the static value of Cn at either the break in the pitching moment or the loss of chord force at the onset of stall. It is close to the condition of maximum lift of the airfoil at low Mach numbers. +-1.159496 Cn2 ! As Cn1 for negative AOAs. +Default St_sh ! Strouhal's shedding frequency constant. [default = 0.19] +0.009688 Cd0 ! 2D drag coefficient value at 0-lift. +-0.104313 Cm0 ! 2D pitching moment coefficient about 1/4-chord location, at 0-lift, positive if nose up. [If the aerodynamics coefficients table does not include a column for Cm, this needs to be set to 0.0] +0.000000 k0 ! Constant in the \hat(x)_cp curve best-fit; = (\hat(x)_AC-0.25). [ignored if UAMod<>1] +0.000000 k1 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k2 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k3 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k1_hat ! Constant in the expression of Cc due to leading edge vortex effects. [ignored if UAMod<>1] +Default x_cp_bar ! Constant in the expression of \hat(x)_cp^v. [ignored if UAMod<>1, default = 0.2] +Default UACutout ! Angle of attack above which unsteady aerodynamics are disabled (deg). [Specifying the string "Default" sets UACutout to 45 degrees] +Default filtCutOff ! Cut-off frequency (-3 dB corner frequency) for low-pass filtering the AoA input to UA, as well as the 1st and 2nd derivatives (Hz) [default = 20] +!........................................ +! Table of aerodynamics coefficients +200 NumAlf ! Number of data lines in the following table +! Alpha Cl Cd Cm +! (deg) (-) (-) (-) +-1.80000000000000e+02 0.00000000000000e+00 5.02376982549728e-02 0.00000000000000e+00 +-1.77000000000000e+02 1.08718036745927e-01 5.02376982549728e-02 1.19452717008645e-01 +-1.74000000000000e+02 2.18430776525163e-01 6.02851812182215e-02 2.39999774321882e-01 +-1.71000000000000e+02 3.27646531789012e-01 9.04279599581437e-02 3.60000410445527e-01 +-1.68000000000000e+02 4.36869311875493e-01 1.20570256132886e-01 3.18260147906390e-01 +-1.65000000000000e+02 5.46099384730567e-01 1.50712311030671e-01 1.95651323790509e-01 +-1.62000000000000e+02 6.55334540103918e-01 1.80854868202663e-01 7.30412515523047e-02 +-1.59000000000000e+02 7.28010405538067e-01 2.19127710006320e-01 -9.45584975904147e-03 +-1.56000000000000e+02 7.24644310916020e-01 2.73660846032009e-01 -1.21837323981812e-02 +-1.53000000000000e+02 7.21308604937496e-01 3.28193998660095e-01 -1.57136492042310e-02 +-1.50000000000000e+02 7.20052599183224e-01 3.82727196695211e-01 -2.24733180893469e-02 +-1.47000000000000e+02 7.05344979121394e-01 4.53184198414303e-01 -6.72063266750436e-03 +-1.44000000000000e+02 6.90637102885333e-01 5.23641395400969e-01 9.03246882847654e-03 +-1.41000000000000e+02 6.75928714282518e-01 5.94098982936728e-01 2.49798597818277e-02 +-1.38000000000000e+02 6.57098483724279e-01 6.67494798442362e-01 4.09475868870872e-02 +-1.35000000000000e+02 6.36207340549935e-01 7.42359721972419e-01 5.68857580517079e-02 +-1.32000000000000e+02 6.15315579547438e-01 8.17225281824516e-01 7.28165592297191e-02 +-1.29000000000000e+02 5.90673724574305e-01 8.90525522009492e-01 8.88369855206700e-02 +-1.26000000000000e+02 5.58531663885406e-01 9.60695115424263e-01 1.05046529374471e-01 +-1.23000000000000e+02 5.26389596453192e-01 1.03086417277945e+00 1.21252954182462e-01 +-1.20000000000000e+02 4.94247525649446e-01 1.10103296211486e+00 1.37456542318889e-01 +-1.17000000000000e+02 4.51005751931015e-01 1.15795443010112e+00 1.52804706847535e-01 +-1.14000000000000e+02 4.07763995533133e-01 1.21487565475428e+00 1.68151691714967e-01 +-1.11000000000000e+02 3.64522317186419e-01 1.27179644456681e+00 1.83497290780899e-01 +-1.08000000000000e+02 3.16016600929376e-01 1.31524560139462e+00 1.97190287375102e-01 +-1.05000000000000e+02 2.64878825634709e-01 1.35195883914965e+00 2.10057619315569e-01 +-1.02000000000000e+02 2.13741036335945e-01 1.38867165620685e+00 2.22925091726200e-01 +-9.90000000000000e+01 1.61684301770569e-01 1.41713830337121e+00 2.34432883783133e-01 +-9.60000000000000e+01 1.07789636867620e-01 1.42911225356491e+00 2.43221503139034e-01 +-9.30000000000000e+01 5.38949836895802e-02 1.44108611228438e+00 2.52012246779875e-01 +-9.00000000000000e+01 3.36373889682523e-07 1.45305992526757e+00 2.60805612076082e-01 +-8.70000000000000e+01 -5.38949285283857e-02 1.44108612453959e+00 2.65268702964392e-01 +-8.40000000000000e+01 -1.07789787569110e-01 1.42911222008308e+00 2.69705899355330e-01 +-8.10000000000000e+01 -1.61683834888495e-01 1.41713840709990e+00 2.74118148425682e-01 +-7.80000000000000e+01 -2.13740788662556e-01 1.38867183401641e+00 2.75218906403952e-01 +-7.50000000000000e+01 -2.64879163958945e-01 1.35195859625958e+00 2.74653513726577e-01 +-7.20000000000000e+01 -3.16016353261405e-01 1.31524577920238e+00 2.74066661635360e-01 +-6.90000000000000e+01 -3.64521942583287e-01 1.27179693767224e+00 2.72190520318518e-01 +-6.60000000000000e+01 -4.07764116445761e-01 1.21487549559204e+00 2.67758304954097e-01 +-6.30000000000000e+01 -4.51006038016469e-01 1.15795405351184e+00 2.63309723707785e-01 +-6.00000000000000e+01 -4.94247738299703e-01 1.10103249788183e+00 2.58846174876524e-01 +-5.70000000000000e+01 -5.26389809103449e-01 1.03086370854641e+00 2.52537766967854e-01 +-5.40000000000000e+01 -5.58531876535596e-01 9.60694651185909e-01 2.46218241369695e-01 +-5.10000000000000e+01 -5.90673937224495e-01 8.90525057771137e-01 2.39889401901766e-01 +-4.80000000000000e+01 -6.16985978521229e-01 8.17249434089066e-01 2.33807907536728e-01 +-4.50000000000000e+01 -6.40383103818546e-01 7.42420845191650e-01 2.27849917319468e-01 +-4.20000000000000e+01 -6.58768869626067e-01 6.67518950513351e-01 2.23456296897971e-01 +-3.90000000000000e+01 -6.76252856241839e-01 5.93029893358622e-01 2.19662575489263e-01 +-3.60000000000000e+01 -6.91251469843313e-01 5.20200446113040e-01 2.17992553881491e-01 +-3.30000000000000e+01 -7.05373690625492e-01 4.50048605759265e-01 2.19429640986969e-01 +-3.00000000000000e+01 -7.20052704961507e-01 3.82726758502379e-01 2.24334644865001e-01 +-2.93939393939394e+01 -7.23423358758069e-01 3.69810374707743e-01 2.26262638995891e-01 +-2.87878787878788e+01 -7.26794012554631e-01 3.56893990913108e-01 2.28190633126782e-01 +-2.81818181818182e+01 -7.30164666351193e-01 3.43977607118473e-01 2.30118627257672e-01 +-2.75757575757576e+01 -7.33955296036718e-01 3.31475572351972e-01 2.32714210527911e-01 +-2.69696969696970e+01 -7.37925930829896e-01 3.19151130974461e-01 2.35595927974075e-01 +-2.63636363636364e+01 -7.41896565623074e-01 3.06826689596951e-01 2.38477645420239e-01 +-2.57575757575758e+01 -7.46236904909058e-01 2.94763605830315e-01 2.41858864830355e-01 +-2.51515151515151e+01 -7.51131714769935e-01 2.83092497567289e-01 2.45989220771138e-01 +-2.45454545454545e+01 -7.56026524630811e-01 2.71421389304264e-01 2.50119576711921e-01 +-2.39393939393939e+01 -7.61117995847343e-01 2.59818577841106e-01 2.53958515768821e-01 +-2.33333333333333e+01 -7.67979457339360e-01 2.48830450799340e-01 2.55174646451070e-01 +-2.27272727272727e+01 -7.74840918831377e-01 2.37842323757575e-01 2.56491201944605e-01 +-2.21212121212121e+01 -7.81702380323394e-01 2.26854196715809e-01 2.57271002838526e-01 +-2.15151515151515e+01 -8.12448284285856e-01 2.19127250982838e-01 2.39096729103820e-01 +-2.09090909090909e+01 -8.46418529847557e-01 2.12215810350734e-01 2.19171773544913e-01 +-2.03030303030303e+01 -8.82410390516615e-01 2.05304369718630e-01 1.99907002060488e-01 +-1.96969696969697e+01 -9.17302460891263e-01 1.98393040992681e-01 1.80908557885250e-01 +-1.90909090909091e+01 -9.51690757109299e-01 1.91481824166556e-01 1.62015766540326e-01 +-1.84848484848485e+01 -9.87451060932182e-01 1.84488095751064e-01 1.43186155335470e-01 +-1.78787878787879e+01 -1.02348107734750e+00 1.78125103821018e-01 1.23309320342863e-01 +-1.72727272727273e+01 -1.05955430524795e+00 1.72667345635547e-01 1.02937199694708e-01 +-1.66666666666667e+01 -1.09661808800758e+00 1.66429075696717e-01 8.25865362857696e-02 +-1.60606060606061e+01 -1.13436650818888e+00 1.59785188254103e-01 6.22621217533182e-02 +-1.54545454545455e+01 -1.15393444133063e+00 1.51574659183086e-01 4.58165236508863e-02 +-1.48484848484848e+01 -1.16179648627071e+00 1.42415253094923e-01 3.15133238851397e-02 +-1.42424242424242e+01 -1.14050675694352e+00 1.31113076076399e-01 2.06305497523611e-02 +-1.36363636363636e+01 -1.11318982416965e+00 1.19491463618837e-01 6.42328479698607e-03 +-1.30303030303030e+01 -1.08076735917766e+00 1.07643742796169e-01 -7.83926565619422e-03 +-1.24242424242424e+01 -1.03727303023693e+00 9.49346653316282e-02 -1.75014551808433e-02 +-1.18181818181818e+01 -9.91440219649850e-01 8.26304983608341e-02 -2.54111950263429e-02 +-1.12121212121212e+01 -9.43045452072816e-01 7.24323611406984e-02 -2.97310850160300e-02 +-1.06060606060606e+01 -8.91357118244056e-01 6.36793113860100e-02 -3.46811573258460e-02 +-1.00000000000000e+01 -8.38640919151541e-01 5.56031252905086e-02 -4.00042772613043e-02 +-9.39393939393939e+00 -7.97154810810589e-01 4.56286447472684e-02 -4.58057854493708e-02 +-8.78787878787879e+00 -7.57700218153473e-01 3.48441279722901e-02 -5.20559338844009e-02 +-8.18181818181818e+00 -7.29615756802838e-01 2.21903132460571e-02 -5.98183982708405e-02 +-7.57575757575758e+00 -6.77769009447363e-01 1.66725656645290e-02 -6.52314095706447e-02 +-6.96969696969697e+00 -6.15253643707113e-01 1.38193953292020e-02 -6.96903302338436e-02 +-6.36363636363636e+00 -5.29222888480069e-01 1.28208124258429e-02 -7.60443151485867e-02 +-5.75757575757576e+00 -4.43714189157886e-01 1.18605164320041e-02 -8.20746230823483e-02 +-5.15151515151515e+00 -3.59021198798114e-01 1.11014093554157e-02 -8.75040133661531e-02 +-4.54545454545454e+00 -2.75625966933364e-01 1.06136414059815e-02 -9.20337243383322e-02 +-3.93939393939394e+00 -1.92587400034749e-01 1.02273414896665e-02 -9.62397074831400e-02 +-3.33333333333333e+00 -1.09292475701538e-01 9.90518405717358e-03 -9.99005436593104e-02 +-2.72727272727273e+00 -2.77772625212584e-02 9.71093449432091e-03 -1.03217781859456e-01 +-2.12121212121212e+00 5.20911798292055e-02 9.64590630058275e-03 -1.06366269240076e-01 +-1.51515151515152e+00 1.30586446388122e-01 9.55659941113129e-03 -1.09005739501319e-01 +-9.09090909090912e-01 2.08840498658564e-01 9.49982823781086e-03 -1.11539847170668e-01 +-3.03030303030302e-01 2.87578475260949e-01 9.58414006664110e-03 -1.13902065395105e-01 + 3.03030303030302e-01 3.65664552744906e-01 9.65560539372337e-03 -1.16149780563894e-01 + 9.09090909090912e-01 4.43204973276288e-01 9.71978591639622e-03 -1.18219507269873e-01 + 1.51515151515152e+00 5.20281024804697e-01 9.71394548831763e-03 -1.20121864462230e-01 + 2.12121212121212e+00 5.96811467615798e-01 9.80332128304454e-03 -1.21920157367353e-01 + 2.72727272727273e+00 6.71434914937960e-01 9.98488831915120e-03 -1.23594864438980e-01 + 3.33333333333333e+00 7.45656831699806e-01 1.01455835290262e-02 -1.25107525282158e-01 + 3.93939393939394e+00 8.19857800959508e-01 1.02378295152185e-02 -1.26457757043226e-01 + 4.54545454545455e+00 8.93627925198807e-01 1.03669090136902e-02 -1.27577353045154e-01 + 5.15151515151515e+00 9.66788832639503e-01 1.05314448784099e-02 -1.28565417198802e-01 + 5.75757575757576e+00 1.03821639854981e+00 1.07650302198420e-02 -1.29227175957820e-01 + 6.36363636363637e+00 1.10795832677679e+00 1.10272583218359e-02 -1.29514536462203e-01 + 6.96969696969697e+00 1.17694418225097e+00 1.12742209874335e-02 -1.29549901025754e-01 + 7.57575757575757e+00 1.23921531344826e+00 1.16670639800197e-02 -1.28261266809327e-01 + 8.18181818181818e+00 1.29706014706839e+00 1.24490049337565e-02 -1.26386684375794e-01 + 8.78787878787879e+00 1.34554047570179e+00 1.37772189838099e-02 -1.23143424626972e-01 + 9.39393939393939e+00 1.37610897192605e+00 1.75961680761005e-02 -1.21674324726306e-01 + 1.00000000000000e+01 1.39836265121160e+00 2.28583111147752e-02 -1.21039639768622e-01 + 1.06060606060606e+01 1.39287314658036e+00 2.77463509449118e-02 -1.19204194226554e-01 + 1.12121212121212e+01 1.39004598907911e+00 3.19782079487326e-02 -1.15663804195089e-01 + 1.18181818181818e+01 1.39216407137552e+00 3.49921524756390e-02 -1.09850755288886e-01 + 1.24242424242424e+01 1.29370295829420e+00 4.85210271088614e-02 -1.10247193463411e-01 + 1.30303030303030e+01 1.14384582375774e+00 6.62157966012066e-02 -1.11897572147813e-01 + 1.36363636363636e+01 1.11782919778447e+00 7.57838750439830e-02 -1.11408861155646e-01 + 1.42424242424242e+01 1.09289947478728e+00 8.53102626033743e-02 -1.11136178965314e-01 + 1.48484848484848e+01 1.07102348419001e+00 9.46544491998690e-02 -1.11159785150535e-01 + 1.54545454545455e+01 1.05696164008760e+00 1.03374871102944e-01 -1.10493943921915e-01 + 1.60606060606061e+01 1.04604302431932e+00 1.11858598309336e-01 -1.10049366517221e-01 + 1.66666666666667e+01 1.03932307570257e+00 1.20082914343280e-01 -1.09980310610667e-01 + 1.72727272727273e+01 1.03747930790449e+00 1.29111242533919e-01 -1.10591886748552e-01 + 1.78787878787879e+01 1.04205220466167e+00 1.39122262444516e-01 -1.12023579838031e-01 + 1.84848484848485e+01 1.05490344379951e+00 1.50986790721675e-01 -1.15270449343547e-01 + 1.90909090909091e+01 1.06946548085938e+00 1.63292698023894e-01 -1.19065362073820e-01 + 1.96969696969697e+01 1.08276085154215e+00 1.75474320562998e-01 -1.23397138492291e-01 + 2.03030303030303e+01 1.09403365481318e+00 1.88008089241998e-01 -1.28358085737133e-01 + 2.09090909090909e+01 1.10239238595793e+00 2.00894023983065e-01 -1.33614744559156e-01 + 2.15151515151515e+01 1.10887254746938e+00 2.13779958724133e-01 -1.38763402571504e-01 + 2.21212121212121e+01 1.11237585687728e+00 2.26320681259285e-01 -1.44191042062497e-01 + 2.27272727272727e+01 1.10397482083247e+00 2.37480910168700e-01 -1.50693555732446e-01 + 2.33333333333333e+01 1.09557378478766e+00 2.48641139078116e-01 -1.57112728954266e-01 + 2.39393939393939e+01 1.08717274874285e+00 2.59801367987532e-01 -1.63133329944962e-01 + 2.45454545454545e+01 1.08003882943089e+00 2.71421389304264e-01 -1.68354300674623e-01 + 2.51515151515151e+01 1.07304569783844e+00 2.83092497567289e-01 -1.73495272149449e-01 + 2.57575757575758e+01 1.06605256624600e+00 2.94763605830315e-01 -1.78646564861648e-01 + 2.63636363636364e+01 1.05985153546545e+00 3.06826689596951e-01 -1.83426648708445e-01 + 2.69696969696970e+01 1.05417865395407e+00 3.19151130974461e-01 -1.87959534349431e-01 + 2.75757575757576e+01 1.04850577244270e+00 3.31475572351972e-01 -1.92498924465493e-01 + 2.81818181818182e+01 1.04309074438137e+00 3.43977607118473e-01 -1.96910710531247e-01 + 2.87878787878788e+01 1.03827732275955e+00 3.56893990913108e-01 -2.01014545276943e-01 + 2.93939393939394e+01 1.03346390113772e+00 3.69810374707743e-01 -2.05122663450476e-01 + 3.00000000000000e+01 1.02865047951590e+00 3.82726758502379e-01 -2.09235101253211e-01 + 3.30000000000000e+01 1.00767522728702e+00 4.50048605759265e-01 -2.27666231032229e-01 + 3.60000000000000e+01 9.87502112870606e-01 5.20200446113040e-01 -2.44805976520978e-01 + 3.90000000000000e+01 9.66075877033301e-01 5.93029893358622e-01 -2.61539856917676e-01 + 4.20000000000000e+01 9.41098858571731e-01 6.67518950513352e-01 -2.77304866762762e-01 + 4.50000000000000e+01 9.14833592285066e-01 7.42420845191650e-01 -2.92778427054725e-01 + 4.80000000000000e+01 8.81408622533811e-01 8.17249434089067e-01 -3.07497585034756e-01 + 5.10000000000000e+01 8.43819604431597e-01 8.90525057771138e-01 -3.21903684993278e-01 + 5.40000000000000e+01 7.97902221930250e-01 9.60694651185909e-01 -3.35704391970839e-01 + 5.70000000000000e+01 7.51985042501660e-01 1.03086370854641e+00 -3.49495136575764e-01 + 6.00000000000000e+01 7.06067964608676e-01 1.10103249788183e+00 -3.63279172814127e-01 + 6.30000000000000e+01 6.44293944876385e-01 1.15795405351184e+00 -3.75684064171539e-01 + 6.60000000000000e+01 5.82519789224936e-01 1.21487549559204e+00 -3.88081898949555e-01 + 6.90000000000000e+01 5.20745633573486e-01 1.27179693767224e+00 -4.00474177818223e-01 + 7.20000000000000e+01 4.51451982439921e-01 1.31524577920238e+00 -4.11592132530663e-01 + 7.50000000000000e+01 3.78398737499386e-01 1.35195859625958e+00 -4.22069569360111e-01 + 7.80000000000000e+01 3.05344055424385e-01 1.38867183401641e+00 -4.32541989601588e-01 + 8.10000000000000e+01 2.30976975521496e-01 1.41713840709990e+00 -4.42143819760501e-01 + 8.40000000000000e+01 1.53985190557838e-01 1.42911222008308e+00 -4.50008085895448e-01 + 8.70000000000000e+01 7.69925651285527e-02 1.44108612453959e+00 -4.57867677290619e-01 + 9.00000000000000e+01 -3.36373889913427e-07 1.45305992526757e+00 -4.65723360969959e-01 + 9.30000000000000e+01 -5.38949836895802e-02 1.44108611228438e+00 -4.70213156857291e-01 + 9.60000000000000e+01 -1.07789636867620e-01 1.42911225356491e+00 -4.74730592511974e-01 + 9.90000000000000e+01 -1.61684301770570e-01 1.41713830337121e+00 -4.79276533058230e-01 + 1.02000000000000e+02 -2.13741036335945e-01 1.38867165620685e+00 -4.80562246931058e-01 + 1.05000000000000e+02 -2.64878825634710e-01 1.35195883914965e+00 -4.80232757378909e-01 + 1.08000000000000e+02 -3.16016600929376e-01 1.31524560139462e+00 -4.79737782066907e-01 + 1.11000000000000e+02 -3.64522317186419e-01 1.27179644456681e+00 -4.77863421662414e-01 + 1.14000000000000e+02 -4.07763995533133e-01 1.21487565475428e+00 -4.73449633291489e-01 + 1.17000000000000e+02 -4.51005751931015e-01 1.15795443010112e+00 -4.69034472019867e-01 + 1.20000000000000e+02 -4.94247525649446e-01 1.10103296211486e+00 -4.64618222554077e-01 + 1.23000000000000e+02 -5.26389596453192e-01 1.03086417277945e+00 -4.58370282910620e-01 + 1.26000000000000e+02 -5.58531663885406e-01 9.60695115424263e-01 -4.52121193405810e-01 + 1.29000000000000e+02 -5.90673724574306e-01 8.90525522009491e-01 -4.45870794666629e-01 + 1.32000000000000e+02 -6.15315579547438e-01 8.17225281824516e-01 -4.40405924630618e-01 + 1.35000000000000e+02 -6.36207340549935e-01 7.42359721972419e-01 -4.35333210353452e-01 + 1.38000000000000e+02 -6.57098483724280e-01 6.67494798442361e-01 -4.30259571411825e-01 + 1.41000000000000e+02 -6.75928714282518e-01 5.94098982936727e-01 -4.27362077072584e-01 + 1.44000000000000e+02 -6.90637102885333e-01 5.23641395400969e-01 -4.28817330039073e-01 + 1.47000000000000e+02 -7.05344979121394e-01 4.53184198414303e-01 -4.30270852318803e-01 + 1.50000000000000e+02 -7.20052599183224e-01 3.82727196695211e-01 -4.31722931389651e-01 + 1.53000000000000e+02 -7.10181631872742e-01 3.29822360950801e-01 -4.46423672577750e-01 + 1.56000000000000e+02 -7.03319879618389e-01 2.76917694334790e-01 -4.61114380563247e-01 + 1.59000000000000e+02 -6.96086980977297e-01 2.24013284168088e-01 -4.74558545497368e-01 + 1.62000000000000e+02 -6.23394384096259e-01 1.85740697616627e-01 -4.83189489859145e-01 + 1.65000000000000e+02 -5.19495002406176e-01 1.54784146617186e-01 -4.89493605397558e-01 + 1.68000000000000e+02 -4.15596211308916e-01 1.23827350356444e-01 -4.95797422538914e-01 + 1.71000000000000e+02 -3.11697223350018e-01 9.28705619946343e-02 -4.50000513056908e-01 + 1.74000000000000e+02 -2.07797841658894e-01 6.19137894310576e-02 -2.99999717902353e-01 + 1.77000000000000e+02 -1.03426007186958e-01 5.10483521183991e-02 -1.49315896260807e-01 + 1.80000000000000e+02 0.00000000000000e+00 5.02376982549728e-02 0.00000000000000e+00 diff --git a/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_18.dat b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_18.dat new file mode 100644 index 00000000..2754301a --- /dev/null +++ b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_18.dat @@ -0,0 +1,254 @@ +! ------------ AirfoilInfo v1.01.x Input File ---------------------------------- +! AeroElasticSE FAST driver +! line +! line +! ------------------------------------------------------------------------------ +DEFAULT InterpOrd ! Interpolation order to use for quasi-steady table lookup {1=linear; 3=cubic spline; "default"} [default=3] +1 NonDimArea ! The non-dimensional area of the airfoil (area/chord^2) (set to 1.0 if unsure or unneeded) +@"NREL-2p8-127_AF18_Coords.txt" NumCoords ! The number of coordinates in the airfoil shape file. Set to zero if coordinates not included. +AF18_BL.txt BL_file ! The file name including the boundary layer characteristics of the profile. Ignored if the aeroacoustic module is not called. +1 NumTabs ! Number of airfoil tables in this file. Each table must have lines for Re and Ctrl. +! ------------------------------------------------------------------------------ +! data for table 1 +! ------------------------------------------------------------------------------ +6.000000 Re ! Reynolds number in millions +0 Ctrl ! Control setting (must be 0 for current AirfoilInfo) +True InclUAdata ! Is unsteady aerodynamics data included in this table? If TRUE, then include 30 UA coefficients below this line +!........................................ +-2.792370 alpha0 ! 0-lift angle of attack, depends on airfoil. +9.587807 alpha1 ! Angle of attack at f=0.7, (approximately the stall angle) for AOA>alpha0. (deg) +-11.610700 alpha2 ! Angle of attack at f=0.7, (approximately the stall angle) for AOA1] +0.000000 S2 ! Constant in the f curve best-fit for AOA> alpha1; by definition it depends on the airfoil. [ignored if UAMod<>1] +0.000000 S3 ! Constant in the f curve best-fit for alpha2<=AOA< alpha0; by definition it depends on the airfoil. [ignored if UAMod<>1] +0.000000 S4 ! Constant in the f curve best-fit for AOA< alpha2; by definition it depends on the airfoil. [ignored if UAMod<>1] +1.342044 Cn1 ! Critical value of C0n at leading edge separation. It should be extracted from airfoil data at a given Mach and Reynolds number. It can be calculated from the static value of Cn at either the break in the pitching moment or the loss of chord force at the onset of stall. It is close to the condition of maximum lift of the airfoil at low Mach numbers. +-1.062317 Cn2 ! As Cn1 for negative AOAs. +Default St_sh ! Strouhal's shedding frequency constant. [default = 0.19] +0.008843 Cd0 ! 2D drag coefficient value at 0-lift. +-0.109829 Cm0 ! 2D pitching moment coefficient about 1/4-chord location, at 0-lift, positive if nose up. [If the aerodynamics coefficients table does not include a column for Cm, this needs to be set to 0.0] +0.000000 k0 ! Constant in the \hat(x)_cp curve best-fit; = (\hat(x)_AC-0.25). [ignored if UAMod<>1] +0.000000 k1 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k2 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k3 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k1_hat ! Constant in the expression of Cc due to leading edge vortex effects. [ignored if UAMod<>1] +Default x_cp_bar ! Constant in the expression of \hat(x)_cp^v. [ignored if UAMod<>1, default = 0.2] +Default UACutout ! Angle of attack above which unsteady aerodynamics are disabled (deg). [Specifying the string "Default" sets UACutout to 45 degrees] +Default filtCutOff ! Cut-off frequency (-3 dB corner frequency) for low-pass filtering the AoA input to UA, as well as the 1st and 2nd derivatives (Hz) [default = 20] +!........................................ +! Table of aerodynamics coefficients +200 NumAlf ! Number of data lines in the following table +! Alpha Cl Cd Cm +! (deg) (-) (-) (-) +-1.80000000000000e+02 0.00000000000000e+00 5.36137248474854e-02 0.00000000000000e+00 +-1.77000000000000e+02 1.08504173136844e-01 5.36137248474854e-02 1.19452717008645e-01 +-1.74000000000000e+02 2.18001573212032e-01 6.43364093197600e-02 2.39999774321882e-01 +-1.71000000000000e+02 3.27002606158882e-01 9.65048147530414e-02 3.60000410445527e-01 +-1.68000000000000e+02 4.36007303027872e-01 1.28672864881152e-01 3.18853353245729e-01 +-1.65000000000000e+02 5.45015893840642e-01 1.60840737360825e-01 1.97134330215277e-01 +-1.62000000000000e+02 6.54027865395150e-01 1.93008707125421e-01 7.54136410554247e-02 +-1.59000000000000e+02 7.27335195948828e-01 2.32421567454577e-01 -7.86707963484010e-03 +-1.56000000000000e+02 7.26473886558584e-01 2.86323963827313e-01 -1.32688253981472e-02 +-1.53000000000000e+02 7.26401782562124e-01 3.40226371983972e-01 -1.93321617932501e-02 +-1.50000000000000e+02 7.29414906072036e-01 3.94128823688151e-01 -3.04550520731389e-02 +-1.47000000000000e+02 7.13608094775223e-01 4.64191024348164e-01 -1.44069907171891e-02 +-1.44000000000000e+02 6.97801023105656e-01 5.34253347401846e-01 1.64143099960009e-03 +-1.41000000000000e+02 6.81993430671987e-01 6.04315915251604e-01 1.79777655646737e-02 +-1.38000000000000e+02 6.62330345884982e-01 6.77255624037684e-01 3.42196692787287e-02 +-1.35000000000000e+02 6.40739522742596e-01 7.51633897455329e-01 5.03555236432470e-02 +-1.32000000000000e+02 6.19148287855155e-01 8.26012587517633e-01 6.64803246966578e-02 +-1.29000000000000e+02 5.93883607684111e-01 8.98800336981566e-01 8.26682061752675e-02 +-1.26000000000000e+02 5.61272019531039e-01 9.68406197695395e-01 9.89967979935854e-02 +-1.23000000000000e+02 5.28660570956951e-01 1.03801152665627e+00 1.15320660255902e-01 +-1.20000000000000e+02 4.96049192169745e-01 1.10761658975060e+00 1.31640184505148e-01 +-1.17000000000000e+02 4.52499966498427e-01 1.16391394816134e+00 1.47076828299769e-01 +-1.14000000000000e+02 4.08950831006833e-01 1.22021106550486e+00 1.62511306961593e-01 +-1.11000000000000e+02 3.65401918647224e-01 1.27650775277552e+00 1.77943395962959e-01 +-1.08000000000000e+02 3.16676605002551e-01 1.31930568274196e+00 1.91712305326037e-01 +-1.05000000000000e+02 2.65363051300195e-01 1.35535413126937e+00 2.04649708702310e-01 +-1.02000000000000e+02 2.14049485607990e-01 1.39140216671678e+00 2.17585944039292e-01 +-9.90000000000000e+01 1.61856439692740e-01 1.41919689307479e+00 2.29156194914714e-01 +-9.60000000000000e+01 1.07904395236486e-01 1.43048464375975e+00 2.37995669823376e-01 +-9.30000000000000e+01 5.39523629434884e-02 1.44177230821265e+00 2.46835565853370e-01 +-9.00000000000000e+01 3.36732009892260e-07 1.45305992955031e+00 2.55676268872361e-01 +-8.70000000000000e+01 -5.39523077235666e-02 1.44177231976554e+00 2.60546156064344e-01 +-8.40000000000000e+01 -1.07904546098422e-01 1.43048461219668e+00 2.65376218554658e-01 +-8.10000000000000e+01 -1.61855972313595e-01 1.41919699085902e+00 2.70167661087483e-01 +-7.80000000000000e+01 -2.14049237083272e-01 1.39140234130663e+00 2.71634637929492e-01 +-7.50000000000000e+01 -2.65363390787359e-01 1.35535389277745e+00 2.71422475089917e-01 +-7.20000000000000e+01 -3.16676356483258e-01 1.31930585733004e+00 2.71175587395195e-01 +-6.90000000000000e+01 -3.65401541382520e-01 1.27650824047434e+00 2.69624220790176e-01 +-6.60000000000000e+01 -4.08950952778550e-01 1.22021090808774e+00 2.65499895797782e-01 +-6.30000000000000e+01 -4.52500254617964e-01 1.16391357570114e+00 2.61346777314543e-01 +-6.00000000000000e+01 -4.96049407924919e-01 1.10761612924714e+00 2.57166068579216e-01 +-5.70000000000000e+01 -5.28660786712125e-01 1.03801106615281e+00 2.51133429071216e-01 +-5.40000000000000e+01 -5.61272235287598e-01 9.68405737186667e-01 2.45075869286174e-01 +-5.10000000000000e+01 -5.93883823440670e-01 8.98799876472838e-01 2.38994436395362e-01 +-4.80000000000000e+01 -6.20771155324413e-01 8.26050727323750e-01 2.33161030617360e-01 +-4.50000000000000e+01 -6.44796451070394e-01 7.51729984474128e-01 2.27439298824510e-01 +-4.20000000000000e+01 -6.63953200654077e-01 6.77293763541013e-01 2.23291102757799e-01 +-3.90000000000000e+01 -6.82249667333847e-01 6.03259850610683e-01 2.19817265076178e-01 +-3.60000000000000e+01 -6.98201576773723e-01 5.30851294361004e-01 2.18838619571564e-01 +-3.30000000000000e+01 -7.13444606626873e-01 4.61088222324340e-01 2.21122290445851e-01 +-3.00000000000000e+01 -7.29415020855328e-01 3.94128387846700e-01 2.27054455296579e-01 +-2.93939393939394e+01 -7.33089414277251e-01 3.81279477717506e-01 2.29240557823958e-01 +-2.87878787878788e+01 -7.36763807699173e-01 3.68430567588313e-01 2.31426660351336e-01 +-2.81818181818182e+01 -7.40438201121096e-01 3.55581657459119e-01 2.33612762878715e-01 +-2.75757575757576e+01 -7.44561188035578e-01 3.43144145729673e-01 2.36503775794692e-01 +-2.69696969696970e+01 -7.48876445797132e-01 3.30882962725711e-01 2.39696919079866e-01 +-2.63636363636364e+01 -7.53191703558686e-01 3.18621779721749e-01 2.42890062365039e-01 +-2.57575757575758e+01 -7.57896949106898e-01 3.06620180092045e-01 2.46611383026609e-01 +-2.51515151515151e+01 -7.63187085443502e-01 2.95007895024532e-01 2.51124846654346e-01 +-2.45454545454545e+01 -7.68477221780106e-01 2.83395609957020e-01 2.55638310282083e-01 +-2.39393939393939e+01 -7.74029112998335e-01 2.71848572457760e-01 2.59427106627508e-01 +-2.33333333333333e+01 -7.81936848828191e-01 2.60888775705009e-01 2.56693757133074e-01 +-2.27272727272727e+01 -7.89844584658047e-01 2.49928978952259e-01 2.54973507041906e-01 +-2.21212121212121e+01 -7.97752320487903e-01 2.38969182199509e-01 2.51757698493230e-01 +-2.15151515151515e+01 -8.17245649453576e-01 2.29474770810752e-01 2.34218156316905e-01 +-2.09090909090909e+01 -8.40715821523898e-01 2.20346800023089e-01 2.15558365010287e-01 +-2.03030303030303e+01 -8.64893147204684e-01 2.11218829235425e-01 1.97258668465790e-01 +-1.96969696969697e+01 -8.87438946084652e-01 2.02091078490948e-01 1.79104249713839e-01 +-1.90909090909091e+01 -9.09237361854086e-01 1.92963547777208e-01 1.61007469502170e-01 +-1.84848484848485e+01 -9.33071785400616e-01 1.84171846523930e-01 1.42945493987761e-01 +-1.78787878787879e+01 -9.57306241435504e-01 1.76283936647877e-01 1.23884251763747e-01 +-1.72727272727273e+01 -9.81604014520295e-01 1.68616795799771e-01 1.04367473421751e-01 +-1.66666666666667e+01 -1.00737125830751e+00 1.60297507335738e-01 8.48827458147722e-02 +-1.60606060606061e+01 -1.03415415721149e+00 1.51566539016137e-01 6.54371368564537e-02 +-1.54545454545455e+01 -1.05213926667993e+00 1.41887359500634e-01 4.85999555851204e-02 +-1.48484848484848e+01 -1.06411426754698e+00 1.31650218002569e-01 3.32132244253039e-02 +-1.42424242424242e+01 -1.06085920517278e+00 1.20325281854275e-01 1.97519541398105e-02 +-1.36363636363636e+01 -1.05297179510023e+00 1.08818108910721e-01 3.34724170517964e-03 +-1.30303030303030e+01 -1.04038617850512e+00 9.71704693558744e-02 -1.30280274230778e-02 +-1.24242424242424e+01 -1.00963309974379e+00 8.35931628390448e-02 -2.24525867458495e-02 +-1.18181818181818e+01 -9.74392976542105e-01 7.02569290424257e-02 -2.96665236814477e-02 +-1.12121212121212e+01 -9.33183989496999e-01 5.92863820290872e-02 -3.25396861725729e-02 +-1.06060606060606e+01 -8.87095198505282e-01 5.02112419249079e-02 -3.68554806252278e-02 +-1.00000000000000e+01 -8.39030346732209e-01 4.20062550430957e-02 -4.19667667411679e-02 +-9.39393939393939e+00 -7.98355307687373e-01 3.39431550888320e-02 -4.71586015184073e-02 +-8.78787878787879e+00 -7.55075718086549e-01 2.58616329336961e-02 -5.31128483759924e-02 +-8.18181818181818e+00 -7.12760376198709e-01 1.76807004789459e-02 -6.15557949547917e-02 +-7.57575757575758e+00 -6.50212657860430e-01 1.40779977251651e-02 -6.80037285779409e-02 +-6.96969696969697e+00 -5.79316182872428e-01 1.20930353131595e-02 -7.36947785344258e-02 +-6.36363636363636e+00 -4.93332487227875e-01 1.12571113999265e-02 -8.08636763018482e-02 +-5.75757575757576e+00 -4.07625165812638e-01 1.04386697349651e-02 -8.76670243494600e-02 +-5.15151515151515e+00 -3.22375665042248e-01 9.89046924180047e-03 -9.37249643058138e-02 +-4.54545454545454e+00 -2.38569752393226e-01 9.55568172944726e-03 -9.85721042394988e-02 +-3.93939393939394e+00 -1.55278792252772e-01 9.28231334429143e-03 -1.03000270064649e-01 +-3.33333333333333e+00 -7.27588785201134e-02 9.00905966504459e-03 -1.06804167238102e-01 +-2.72727272727273e+00 8.75545142458852e-03 8.82260921114890e-03 -1.10193484668354e-01 +-2.12121212121212e+00 8.90951677107422e-02 8.71711984822585e-03 -1.13439603715240e-01 +-1.51515151515152e+00 1.68020877233593e-01 8.63506810960759e-03 -1.15955900231793e-01 +-9.09090909090912e-01 2.46284645308487e-01 8.59786619783916e-03 -1.18329762049110e-01 +-3.03030303030302e-01 3.23526927130680e-01 8.68469307519355e-03 -1.20499605866875e-01 + 3.03030303030302e-01 4.00568746060339e-01 8.73666462420641e-03 -1.22563336532720e-01 + 9.09090909090912e-01 4.77532382355605e-01 8.76693795829447e-03 -1.24415248851028e-01 + 1.51515151515152e+00 5.54310964834009e-01 8.75563015487188e-03 -1.26154371277845e-01 + 2.12121212121212e+00 6.30748642497307e-01 8.89942708059405e-03 -1.27777288327563e-01 + 2.72727272727273e+00 7.05967166479233e-01 9.07466954914071e-03 -1.29308981144731e-01 + 3.33333333333333e+00 7.80411644410489e-01 9.23152948118853e-03 -1.30694777177827e-01 + 3.93939393939394e+00 8.54634907157449e-01 9.35773501083766e-03 -1.31925075915747e-01 + 4.54545454545455e+00 9.28368090200400e-01 9.52948973845109e-03 -1.32899735261145e-01 + 5.15151515151515e+00 1.00145694605734e+00 9.73306782417346e-03 -1.33724225695198e-01 + 5.75757575757576e+00 1.07270733762567e+00 1.00006966462114e-02 -1.34169484840169e-01 + 6.36363636363637e+00 1.14127724503204e+00 1.02973665103093e-02 -1.34153350705440e-01 + 6.96969696969697e+00 1.20864942903410e+00 1.05582170564899e-02 -1.33827802118801e-01 + 7.57575757575757e+00 1.26443440681650e+00 1.10668993698580e-02 -1.31662626204201e-01 + 8.18181818181818e+00 1.31327712628436e+00 1.21179224024120e-02 -1.28718467346890e-01 + 8.78787878787879e+00 1.34931677106702e+00 1.38745085223537e-02 -1.24009773357878e-01 + 9.39393939393939e+00 1.35685700568352e+00 2.07295073959453e-02 -1.22353831339396e-01 + 1.00000000000000e+01 1.34623269398792e+00 3.03611166129043e-02 -1.22101994507537e-01 + 1.06060606060606e+01 1.29247625354756e+00 3.89303371400334e-02 -1.20772828739056e-01 + 1.12121212121212e+01 1.25212720004798e+00 4.59269172993146e-02 -1.17349872385937e-01 + 1.18181818181818e+01 1.23668533143930e+00 5.00033361654154e-02 -1.11373005101486e-01 + 1.24242424242424e+01 1.18614194111661e+00 6.00007067895342e-02 -1.09801411206576e-01 + 1.30303030303030e+01 1.11590193321859e+00 7.24445919904755e-02 -1.08383334659172e-01 + 1.36363636363636e+01 1.11070643578549e+00 8.22712281118321e-02 -1.09098841523507e-01 + 1.42424242424242e+01 1.10016431536211e+00 9.22478830207050e-02 -1.10082030306725e-01 + 1.48484848484848e+01 1.08932388927719e+00 1.02384259095179e-01 -1.11305168394289e-01 + 1.54545454545455e+01 1.08265839747059e+00 1.11362550974526e-01 -1.11223542069270e-01 + 1.60606060606061e+01 1.07750353752455e+00 1.19864697023678e-01 -1.11093423299158e-01 + 1.66666666666667e+01 1.07245197326073e+00 1.27554831236544e-01 -1.10774119006494e-01 + 1.72727272727273e+01 1.07224113795030e+00 1.36494897934856e-01 -1.11302931932702e-01 + 1.78787878787879e+01 1.07862447668773e+00 1.46962675742666e-01 -1.12850875597998e-01 + 1.84848484848485e+01 1.08861259617754e+00 1.59145187067245e-01 -1.16200177309305e-01 + 1.90909090909091e+01 1.09918905179666e+00 1.71646795036045e-01 -1.20001587294594e-01 + 1.96969696969697e+01 1.10912810899916e+00 1.83527588865384e-01 -1.23816697554203e-01 + 2.03030303030303e+01 1.11825522290028e+00 1.96466839959649e-01 -1.28421649372128e-01 + 2.09090909090909e+01 1.12524803924632e+00 2.10464608199569e-01 -1.33477817053054e-01 + 2.15151515151515e+01 1.12945414332918e+00 2.24462376439488e-01 -1.38427537382908e-01 + 2.21212121212121e+01 1.13110996428679e+00 2.37920120683396e-01 -1.43742831263358e-01 + 2.27272727272727e+01 1.12256727679690e+00 2.49218324588170e-01 -1.50497808264014e-01 + 2.33333333333333e+01 1.11402458930701e+00 2.60516528492943e-01 -1.57166764414652e-01 + 2.39393939393939e+01 1.10548190181713e+00 2.71814732397717e-01 -1.63463059451524e-01 + 2.45454545454545e+01 1.09782581769558e+00 2.83395609957020e-01 -1.68925418413166e-01 + 2.51515151515151e+01 1.09026824294031e+00 2.95007895024532e-01 -1.74308243109077e-01 + 2.57575757575758e+01 1.08271066818504e+00 3.06620180092045e-01 -1.79706378559642e-01 + 2.63636363636364e+01 1.07598865169483e+00 3.18621779721749e-01 -1.84704949130393e-01 + 2.69696969696970e+01 1.06982376061140e+00 3.30882962725711e-01 -1.89437565776199e-01 + 2.75757575757576e+01 1.06365886952798e+00 3.43144145729673e-01 -1.94179831305997e-01 + 2.81818181818182e+01 1.05776902996474e+00 3.55581657459119e-01 -1.98785028498289e-01 + 2.87878787878788e+01 1.05252092222901e+00 3.68430567588313e-01 -2.03055245546250e-01 + 2.93939393939394e+01 1.04727281449329e+00 3.81279477717506e-01 -2.07331816726986e-01 + 3.00000000000000e+01 1.04202470675756e+00 3.94128387846700e-01 -2.11614795742417e-01 + 3.30000000000000e+01 1.01920513278199e+00 4.61088222324340e-01 -2.30709635446696e-01 + 3.60000000000000e+01 9.97430021449977e-01 5.30851294361004e-01 -2.48389635018723e-01 + 3.90000000000000e+01 9.74642622581348e-01 6.03259850610683e-01 -2.65244377392235e-01 + 4.20000000000000e+01 9.48504923410187e-01 6.77293763541014e-01 -2.81146520062724e-01 + 4.50000000000000e+01 9.21138527003474e-01 7.51729984474128e-01 -2.96778859241448e-01 + 4.80000000000000e+01 8.86816262654281e-01 8.26050727323750e-01 -3.11620664341732e-01 + 5.10000000000000e+01 8.48405523199447e-01 8.98799876472838e-01 -3.26146108681646e-01 + 5.40000000000000e+01 8.01817570694549e-01 9.68405737186667e-01 -3.40039290927774e-01 + 5.70000000000000e+01 7.55229683651232e-01 1.03801106615281e+00 -3.53931325023812e-01 + 6.00000000000000e+01 7.08641829338459e-01 1.10761612924715e+00 -3.67824192591327e-01 + 6.30000000000000e+01 6.46428682755529e-01 1.16391357570114e+00 -3.80297188353490e-01 + 6.60000000000000e+01 5.84215402239047e-01 1.22021090808774e+00 -3.92768487627463e-01 + 6.90000000000000e+01 5.22002121722564e-01 1.27650824047434e+00 -4.05238805155188e-01 + 7.20000000000000e+01 4.52394670864868e-01 1.31930585733004e+00 -4.16419077136110e-01 + 7.50000000000000e+01 3.79090286205083e-01 1.35535389277745e+00 -4.26952712546759e-01 + 7.80000000000000e+01 3.05784461532969e-01 1.39140234130664e+00 -4.37484524738100e-01 + 8.10000000000000e+01 2.31222621050345e-01 1.41919699085902e+00 -4.47140901263708e-01 + 8.40000000000000e+01 1.54148835649795e-01 1.43048461219668e+00 -4.55046838069807e-01 + 8.70000000000000e+01 7.70743518918329e-02 1.44177231976554e+00 -4.62950611733494e-01 + 9.00000000000000e+01 -3.36732010122695e-07 1.45305992955031e+00 -4.70852706467098e-01 + 9.30000000000000e+01 -5.39523629434884e-02 1.44177230821265e+00 -4.75763515343477e-01 + 9.60000000000000e+01 -1.07904395236486e-01 1.43048464375975e+00 -4.80716438183718e-01 + 9.90000000000000e+01 -1.61856439692741e-01 1.41919689307479e+00 -4.85712617490280e-01 + 1.02000000000000e+02 -2.14049485607990e-01 1.39140216671678e+00 -4.87463918618097e-01 + 1.05000000000000e+02 -2.65363051300195e-01 1.35535413126937e+00 -4.87615426725982e-01 + 1.08000000000000e+02 -3.16676605002551e-01 1.31930568274196e+00 -4.87522734138826e-01 + 1.11000000000000e+02 -3.65401918647224e-01 1.27650775277552e+00 -4.85996410622861e-01 + 1.14000000000000e+02 -4.08950831006833e-01 1.22021106550486e+00 -4.81927358927190e-01 + 1.17000000000000e+02 -4.52499966498427e-01 1.16391394816134e+00 -4.77857363874255e-01 + 1.20000000000000e+02 -4.96049192169745e-01 1.10761658975060e+00 -4.73786676400946e-01 + 1.23000000000000e+02 -5.28660570956951e-01 1.03801152665627e+00 -4.67894035404986e-01 + 1.26000000000000e+02 -5.61272019531039e-01 9.68406197695395e-01 -4.62000666821961e-01 + 1.29000000000000e+02 -5.93883607684111e-01 8.98800336981565e-01 -4.56106383315202e-01 + 1.32000000000000e+02 -6.19148287855155e-01 8.26012587517633e-01 -4.51045249617514e-01 + 1.35000000000000e+02 -6.40739522742596e-01 7.51633897455329e-01 -4.46400358390250e-01 + 1.38000000000000e+02 -6.62330345884983e-01 6.77255624037683e-01 -4.41754984328411e-01 + 1.41000000000000e+02 -6.81993430671987e-01 6.04315915251604e-01 -4.39372656415041e-01 + 1.44000000000000e+02 -6.97801023105656e-01 5.34253347401846e-01 -4.41516679399736e-01 + 1.47000000000000e+02 -7.13608094775223e-01 4.64191024348164e-01 -4.43659776127911e-01 + 1.50000000000000e+02 -7.29414906072037e-01 3.94128823688151e-01 -4.45802094533083e-01 + 1.53000000000000e+02 -7.15037146111127e-01 3.41731197240688e-01 -4.59822411066617e-01 + 1.56000000000000e+02 -7.05123336765058e-01 2.89333666877955e-01 -4.73837152031237e-01 + 1.59000000000000e+02 -6.95414684317536e-01 2.36936246357618e-01 -4.86012649076484e-01 + 1.62000000000000e+02 -6.22098323807239e-01 1.97523498321224e-01 -4.91995579783009e-01 + 1.65000000000000e+02 -5.18414913187139e-01 1.64603196340870e-01 -4.94997251401146e-01 + 1.68000000000000e+02 -4.14732090684931e-01 1.31682671601892e-01 -4.97998891218103e-01 + 1.71000000000000e+02 -3.11049072145794e-01 9.87620758945397e-02 -4.50000513056908e-01 + 1.74000000000000e+02 -2.07365661523777e-01 6.58413382471257e-02 -2.99999717902353e-01 + 1.77000000000000e+02 -1.03210513612473e-01 5.43627855211274e-02 -1.49315896260807e-01 + 1.80000000000000e+02 0.00000000000000e+00 5.36137248474854e-02 0.00000000000000e+00 diff --git a/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_19.dat b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_19.dat new file mode 100644 index 00000000..de96b588 --- /dev/null +++ b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_19.dat @@ -0,0 +1,254 @@ +! ------------ AirfoilInfo v1.01.x Input File ---------------------------------- +! AeroElasticSE FAST driver +! line +! line +! ------------------------------------------------------------------------------ +DEFAULT InterpOrd ! Interpolation order to use for quasi-steady table lookup {1=linear; 3=cubic spline; "default"} [default=3] +1 NonDimArea ! The non-dimensional area of the airfoil (area/chord^2) (set to 1.0 if unsure or unneeded) +@"NREL-2p8-127_AF19_Coords.txt" NumCoords ! The number of coordinates in the airfoil shape file. Set to zero if coordinates not included. +AF19_BL.txt BL_file ! The file name including the boundary layer characteristics of the profile. Ignored if the aeroacoustic module is not called. +1 NumTabs ! Number of airfoil tables in this file. Each table must have lines for Re and Ctrl. +! ------------------------------------------------------------------------------ +! data for table 1 +! ------------------------------------------------------------------------------ +6.000000 Re ! Reynolds number in millions +0 Ctrl ! Control setting (must be 0 for current AirfoilInfo) +True InclUAdata ! Is unsteady aerodynamics data included in this table? If TRUE, then include 30 UA coefficients below this line +!........................................ +-3.045221 alpha0 ! 0-lift angle of attack, depends on airfoil. +9.266236 alpha1 ! Angle of attack at f=0.7, (approximately the stall angle) for AOA>alpha0. (deg) +-11.753418 alpha2 ! Angle of attack at f=0.7, (approximately the stall angle) for AOA1] +0.000000 S2 ! Constant in the f curve best-fit for AOA> alpha1; by definition it depends on the airfoil. [ignored if UAMod<>1] +0.000000 S3 ! Constant in the f curve best-fit for alpha2<=AOA< alpha0; by definition it depends on the airfoil. [ignored if UAMod<>1] +0.000000 S4 ! Constant in the f curve best-fit for AOA< alpha2; by definition it depends on the airfoil. [ignored if UAMod<>1] +1.340318 Cn1 ! Critical value of C0n at leading edge separation. It should be extracted from airfoil data at a given Mach and Reynolds number. It can be calculated from the static value of Cn at either the break in the pitching moment or the loss of chord force at the onset of stall. It is close to the condition of maximum lift of the airfoil at low Mach numbers. +-0.990977 Cn2 ! As Cn1 for negative AOAs. +Default St_sh ! Strouhal's shedding frequency constant. [default = 0.19] +0.008173 Cd0 ! 2D drag coefficient value at 0-lift. +-0.112549 Cm0 ! 2D pitching moment coefficient about 1/4-chord location, at 0-lift, positive if nose up. [If the aerodynamics coefficients table does not include a column for Cm, this needs to be set to 0.0] +0.000000 k0 ! Constant in the \hat(x)_cp curve best-fit; = (\hat(x)_AC-0.25). [ignored if UAMod<>1] +0.000000 k1 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k2 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k3 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k1_hat ! Constant in the expression of Cc due to leading edge vortex effects. [ignored if UAMod<>1] +Default x_cp_bar ! Constant in the expression of \hat(x)_cp^v. [ignored if UAMod<>1, default = 0.2] +Default UACutout ! Angle of attack above which unsteady aerodynamics are disabled (deg). [Specifying the string "Default" sets UACutout to 45 degrees] +Default filtCutOff ! Cut-off frequency (-3 dB corner frequency) for low-pass filtering the AoA input to UA, as well as the 1st and 2nd derivatives (Hz) [default = 20] +!........................................ +! Table of aerodynamics coefficients +200 NumAlf ! Number of data lines in the following table +! Alpha Cl Cd Cm +! (deg) (-) (-) (-) +-1.80000000000000e+02 0.00000000000000e+00 5.58151028351338e-02 0.00000000000000e+00 +-1.77000000000000e+02 1.08403822920070e-01 5.58151028351338e-02 1.19452717008645e-01 +-1.74000000000000e+02 2.17800459908011e-01 6.69780604209238e-02 2.39999774321882e-01 +-1.71000000000000e+02 3.26700878169450e-01 1.00467299648537e-01 3.60000410445527e-01 +-1.68000000000000e+02 4.35601558622185e-01 1.33956266552371e-01 3.19240159788981e-01 +-1.65000000000000e+02 5.44502718536549e-01 1.67445097297493e-01 1.98101342058805e-01 +-1.62000000000000e+02 6.53405489525881e-01 2.00933761249497e-01 7.69605856327805e-02 +-1.59000000000000e+02 7.27019339407255e-01 2.41089984114099e-01 -6.83110332274381e-03 +-1.56000000000000e+02 7.28728560841196e-01 2.94581099251365e-01 -1.48336824338646e-02 +-1.53000000000000e+02 7.31142347309657e-01 3.48072223030611e-01 -2.31137907275188e-02 +-1.50000000000000e+02 7.35519708784298e-01 4.01563389144863e-01 -3.46869785111124e-02 +-1.47000000000000e+02 7.18996156868714e-01 4.71368155114379e-01 -1.84787848110211e-02 +-1.44000000000000e+02 7.02472341842677e-01 5.41172995959272e-01 -2.27031145595949e-03 +-1.41000000000000e+02 6.85948000576950e-01 6.10977986560267e-01 1.41215595154545e-02 +-1.38000000000000e+02 6.65741843359713e-01 6.83620285576331e-01 3.03710500677338e-02 +-1.35000000000000e+02 6.43694785635686e-01 7.57681233044139e-01 4.65119317299114e-02 +-1.32000000000000e+02 6.21647450545519e-01 8.31742453913374e-01 6.26455676270925e-02 +-1.29000000000000e+02 5.95976649852831e-01 9.04196027753608e-01 7.88432528643242e-02 +-1.26000000000000e+02 5.63058900774808e-01 9.73434299905923e-01 9.51782729473790e-02 +-1.23000000000000e+02 5.30141386686949e-01 1.04267204311347e+00 1.11510014334606e-01 +-1.20000000000000e+02 4.97223990089781e-01 1.11190952185851e+00 1.27838839143617e-01 +-1.17000000000000e+02 4.53474286743658e-01 1.16779992225404e+00 1.43283454610664e-01 +-1.14000000000000e+02 4.09724721085944e-01 1.22369008305982e+00 1.58726450315576e-01 +-1.11000000000000e+02 3.65975473161876e-01 1.27957981690164e+00 1.74167578217843e-01 +-1.08000000000000e+02 3.17106968448641e-01 1.32195310670654e+00 1.87944896444489e-01 +-1.05000000000000e+02 2.65678796360799e-01 1.35756807157142e+00 2.00890123017622e-01 +-1.02000000000000e+02 2.14250613596524e-01 1.39318262832361e+00 2.13833889964470e-01 +-9.90000000000000e+01 1.61968684256675e-01 1.42053922078900e+00 2.25410295218944e-01 +-9.60000000000000e+01 1.07979224785424e-01 1.43137952698492e+00 2.34252955588311e-01 +-9.30000000000000e+01 5.39897777632595e-02 1.44221975036700e+00 2.43094929221455e-01 +-9.00000000000000e+01 3.36965526401992e-07 1.45305993234293e+00 2.51936472308407e-01 +-8.70000000000000e+01 -5.39897225050438e-02 1.44221976146193e+00 2.56931622255970e-01 +-8.40000000000000e+01 -1.07979375751980e-01 1.43137949667301e+00 2.61901020827721e-01 +-8.10000000000000e+01 -1.61968216553408e-01 1.42053931469708e+00 2.66845383648936e-01 +-7.80000000000000e+01 -2.14250364516685e-01 1.39318280081402e+00 2.68479729146681e-01 +-7.50000000000000e+01 -2.65679136606263e-01 1.35756783594738e+00 2.68447877672478e-01 +-7.20000000000000e+01 -3.17106719374234e-01 1.32195327919519e+00 2.68392871736955e-01 +-6.90000000000000e+01 -3.65975094161662e-01 1.27958030107501e+00 2.67043843374306e-01 +-6.60000000000000e+01 -4.09724843417841e-01 1.22368992678063e+00 2.63130341234035e-01 +-6.30000000000000e+01 -4.53474576189544e-01 1.16779955248625e+00 2.59197088106754e-01 +-6.00000000000000e+01 -4.97224207869552e-01 1.11190906378698e+00 2.55244704276654e-01 +-5.70000000000000e+01 -5.30141604466721e-01 1.04267158504194e+00 2.49454887071623e-01 +-5.40000000000000e+01 -5.63059118556911e-01 9.73433841829142e-01 2.43646817884402e-01 +-5.10000000000000e+01 -5.95976867634935e-01 9.04195569676826e-01 2.37820619877023e-01 +-4.80000000000000e+01 -6.23239324536221e-01 8.31789714461067e-01 2.32266352846812e-01 +-4.50000000000000e+01 -6.47674226237690e-01 7.57800118621131e-01 2.26836908914070e-01 +-4.20000000000000e+01 -6.67333704892715e-01 6.83667545750015e-01 2.23029606785968e-01 +-3.90000000000000e+01 -6.86159958788100e-01 6.09930414983374e-01 2.19918132247163e-01 +-3.60000000000000e+01 -7.02733476031370e-01 5.37796305675443e-01 2.19390306691080e-01 +-3.30000000000000e+01 -7.18707342668409e-01 4.68286734608672e-01 2.22226002504236e-01 +-3.00000000000000e+01 -7.35519829439412e-01 4.01562954836658e-01 2.28827939791023e-01 +-2.93939393939394e+01 -7.39392279869158e-01 3.88758041707422e-01 2.31182344944843e-01 +-2.87878787878788e+01 -7.43264730298904e-01 3.75953128578187e-01 2.33536750098664e-01 +-2.81818181818182e+01 -7.47137180728651e-01 3.63148215448951e-01 2.35891155252484e-01 +-2.75757575757576e+01 -7.51476885097161e-01 3.50752776727396e-01 2.38974806555987e-01 +-2.69696969696970e+01 -7.56016858332907e-01 3.38532842092560e-01 2.42371018735316e-01 +-2.63636363636364e+01 -7.60556831568653e-01 3.26312907457723e-01 2.45767230914644e-01 +-2.57575757575758e+01 -7.65500018552221e-01 3.14351399285216e-01 2.49710318611517e-01 +-2.51515151515151e+01 -7.71047932183450e-01 3.02777470576641e-01 2.54473592128438e-01 +-2.45454545454545e+01 -7.76595845814680e-01 2.91203541868066e-01 2.59236865645359e-01 +-2.39393939393939e+01 -7.82447959329456e-01 2.79692872440278e-01 2.62992965843921e-01 +-2.33333333333333e+01 -7.91037930690711e-01 2.68751548786870e-01 2.57684311183680e-01 +-2.27272727272727e+01 -7.99627902051967e-01 2.57810225133461e-01 2.53255349257629e-01 +-2.21212121212121e+01 -8.08217873413222e-01 2.46868901480052e-01 2.47684440936497e-01 +-2.15151515151515e+01 -8.19990478826953e-01 2.36221993248645e-01 2.31504471971342e-01 +-2.09090909090909e+01 -8.34647953216695e-01 2.25648707810846e-01 2.13702005243607e-01 +-2.03030303030303e+01 -8.49132464561041e-01 2.15075422373046e-01 1.95960374750995e-01 +-1.96969696969697e+01 -8.62578663351143e-01 2.04502427490460e-01 1.78243288992263e-01 +-1.90909090909091e+01 -8.75549253302963e-01 1.93929723146649e-01 1.60535941747677e-01 +-1.84848484848485e+01 -8.89815545281606e-01 1.83695365421934e-01 1.42835185458870e-01 +-1.78787878787879e+01 -9.04336378911458e-01 1.74027498768236e-01 1.24649099331343e-01 +-1.72727272727273e+01 -9.18897356865547e-01 1.64194842338135e-01 1.06248581428441e-01 +-1.66666666666667e+01 -9.34393729163051e-01 1.54084754485664e-01 8.78685062390541e-02 +-1.60606060606061e+01 -9.50536639664486e-01 1.43764438001973e-01 6.95133639931887e-02 +-1.54545454545455e+01 -9.64734821551149e-01 1.33117373956884e-01 5.21860598369796e-02 +-1.48484848484848e+01 -9.77391904313972e-01 1.22286093821075e-01 3.54343122342188e-02 +-1.42424242424242e+01 -9.85991220935185e-01 1.11183046356548e-01 1.93441677911052e-02 +-1.36363636363636e+01 -9.92508781462450e-01 1.00022677031595e-01 1.86113773658177e-03 +-1.30303030303030e+01 -9.96614484588265e-01 8.88116806333893e-02 -1.56141016371839e-02 +-1.24242424242424e+01 -9.78086134430020e-01 7.52791871427589e-02 -2.49185975754885e-02 +-1.18181818181818e+01 -9.53932069219898e-01 6.20273381259160e-02 -3.17721050900264e-02 +-1.12121212121212e+01 -9.20876137842797e-01 5.07143911844155e-02 -3.39028634816218e-02 +-1.06060606060606e+01 -8.81577109301206e-01 4.14292282661460e-02 -3.79021056900473e-02 +-1.00000000000000e+01 -8.39208813140256e-01 3.31402553113552e-02 -4.29111295394993e-02 +-9.39393939393939e+00 -7.98914426405686e-01 2.63234936305883e-02 -4.78020739246981e-02 +-8.78787878787879e+00 -7.51657176842035e-01 2.00389695291873e-02 -5.40250476091291e-02 +-8.18181818181818e+00 -6.93679577084241e-01 1.48308481680817e-02 -6.34207316233908e-02 +-7.57575757575758e+00 -6.21203231263108e-01 1.23436646598620e-02 -7.09002799417693e-02 +-6.96969696969697e+00 -5.42846056045475e-01 1.08867824056562e-02 -7.76381592574485e-02 +-6.36363636363636e+00 -4.57248717599494e-01 1.00699499146877e-02 -8.51835466097516e-02 +-5.75757575757576e+00 -3.71772773815341e-01 9.34966265890492e-03 -9.22149694821789e-02 +-5.15151515151515e+00 -2.86510321252854e-01 8.93727471505472e-03 -9.83419419547575e-02 +-4.54545454545454e+00 -2.02800521849721e-01 8.69069179286290e-03 -1.03107031002192e-01 +-3.93939393939394e+00 -1.19779247070242e-01 8.48574750992013e-03 -1.07388031434577e-01 +-3.33333333333333e+00 -3.84842209773342e-02 8.25863893989330e-03 -1.11024512192661e-01 +-2.72727272727273e+00 4.24696095161102e-02 8.07912598948857e-03 -1.14232025558283e-01 +-2.12121212121212e+00 1.22655957049352e-01 7.94212397685742e-03 -1.17344637430821e-01 +-1.51515151515152e+00 2.01513656509836e-01 7.86589688092029e-03 -1.19802686323078e-01 +-9.09090909090912e-01 2.79423697181455e-01 7.84144762810594e-03 -1.22095855725919e-01 +-3.03030303030302e-01 3.55313195985403e-01 7.92627146648238e-03 -1.24166876151792e-01 + 3.03030303030302e-01 4.31348608046625e-01 7.96635081424009e-03 -1.26135660486964e-01 + 9.09090909090912e-01 5.07641470964623e-01 7.97255718827600e-03 -1.27871042553699e-01 + 1.51515151515152e+00 5.83948077422797e-01 7.96669925131739e-03 -1.29528648870106e-01 + 2.12121212121212e+00 6.60075851841618e-01 8.13587472418758e-03 -1.31061713680780e-01 + 2.72727272727273e+00 7.35527633751173e-01 8.30297676364884e-03 -1.32516554910940e-01 + 3.33333333333333e+00 8.09980208614822e-01 8.45480310834448e-03 -1.33834053323750e-01 + 3.93939393939394e+00 8.84045273581437e-01 8.60887609936009e-03 -1.34999421375079e-01 + 4.54545454545455e+00 9.57533521208408e-01 8.81210276724078e-03 -1.35895700708834e-01 + 5.15151515151515e+00 1.03035843997482e+00 9.04375918791339e-03 -1.36630117116849e-01 + 5.75757575757576e+00 1.10131375775296e+00 9.33994000860195e-03 -1.36951375051287e-01 + 6.36363636363637e+00 1.16891066608882e+00 9.67833808285477e-03 -1.36757550838472e-01 + 6.96969696969697e+00 1.23465262669807e+00 1.00087887591604e-02 -1.36219258169966e-01 + 7.57575757575757e+00 1.28575742789560e+00 1.07210657691971e-02 -1.33537358220650e-01 + 8.18181818181818e+00 1.32822847132065e+00 1.19390938706417e-02 -1.29971609720980e-01 + 8.78787878787879e+00 1.35408256195699e+00 1.39481484368526e-02 -1.24516098191203e-01 + 9.39393939393939e+00 1.34430353385980e+00 2.27726382829582e-02 -1.22692829271057e-01 + 1.00000000000000e+01 1.31224074007862e+00 3.52534094952587e-02 -1.22656293137505e-01 + 1.06060606060606e+01 1.22701127443843e+00 4.62229873456646e-02 -1.21636756952509e-01 + 1.12121212121212e+01 1.16219562577377e+00 5.50223378711124e-02 -1.18681954879612e-01 + 1.18181818181818e+01 1.13530358391339e+00 5.97915556707085e-02 -1.12985606092307e-01 + 1.24242424242424e+01 1.11600551029910e+00 6.74861674225558e-02 -1.09510733624339e-01 + 1.30303030303030e+01 1.09983288203511e+00 7.64936470016543e-02 -1.06091834625369e-01 + 1.36363636363636e+01 1.10710335628616e+00 8.65013832514091e-02 -1.07592565956690e-01 + 1.42424242424242e+01 1.10938358437695e+00 9.67716403001183e-02 -1.09394660231539e-01 + 1.48484848484848e+01 1.11061811797752e+00 1.07424572874100e-01 -1.11514011821931e-01 + 1.54545454545455e+01 1.11082268580784e+00 1.16571011915171e-01 -1.12131429881359e-01 + 1.60606060606061e+01 1.11033605299743e+00 1.25085168188146e-01 -1.12361290382414e-01 + 1.66666666666667e+01 1.10609925661839e+00 1.32426982839510e-01 -1.11763403041033e-01 + 1.72727272727273e+01 1.10609074419205e+00 1.41309497589980e-01 -1.12196477228094e-01 + 1.78787878787879e+01 1.11168148131629e+00 1.52075109775884e-01 -1.13878511431696e-01 + 1.84848484848485e+01 1.11799563681487e+00 1.64464965699760e-01 -1.17335103628994e-01 + 1.90909090909091e+01 1.12427870883996e+00 1.77094182598103e-01 -1.21133211985493e-01 + 1.96969696969697e+01 1.13008308302165e+00 1.88778817516490e-01 -1.24354909490447e-01 + 2.03030303030303e+01 1.13565448667379e+00 2.01982468205630e-01 -1.28506406560087e-01 + 2.09090909090909e+01 1.14015133774343e+00 2.16705220601696e-01 -1.33414633720588e-01 + 2.15151515151515e+01 1.14287461583876e+00 2.31427972997762e-01 -1.38269729436345e-01 + 2.21212121212121e+01 1.14332576014604e+00 2.45483672070678e-01 -1.43529989407809e-01 + 2.27272727272727e+01 1.13469070715944e+00 2.56871844199725e-01 -1.50406733035442e-01 + 2.33333333333333e+01 1.12605565417285e+00 2.68260016328771e-01 -1.57238953577331e-01 + 2.39393939393939e+01 1.11742060118626e+00 2.79648188457818e-01 -1.63893422540327e-01 + 2.45454545454545e+01 1.10942403333740e+00 2.91203541868066e-01 -1.69656064509149e-01 + 2.51515151515151e+01 1.10149840675555e+00 3.02777470576641e-01 -1.75327968907266e-01 + 2.57575757575758e+01 1.09357278017371e+00 3.14351399285216e-01 -1.81009617670108e-01 + 2.63636363636364e+01 1.08651104880220e+00 3.26312907457723e-01 -1.86249835379891e-01 + 2.69696969696970e+01 1.08002533707003e+00 3.38532842092560e-01 -1.91196015332576e-01 + 2.75757575757576e+01 1.07353962533786e+00 3.50752776727396e-01 -1.96148336213444e-01 + 2.81818181818182e+01 1.06734017933048e+00 3.63148215448951e-01 -2.00947535149472e-01 + 2.87878787878788e+01 1.06180862938348e+00 3.75953128578187e-01 -2.05379818120139e-01 + 2.93939393939394e+01 1.05627707943649e+00 3.88758041707422e-01 -2.09816145110101e-01 + 3.00000000000000e+01 1.05074552948950e+00 4.01562954836658e-01 -2.14256550297368e-01 + 3.30000000000000e+01 1.02672334375004e+00 4.68286734608673e-01 -2.33923275085492e-01 + 3.60000000000000e+01 1.00390363142049e+00 5.37796305675443e-01 -2.52023342292616e-01 + 3.90000000000000e+01 9.80228670131175e-01 6.09930414983374e-01 -2.68877380086188e-01 + 4.20000000000000e+01 9.53334135403550e-01 6.83667545750015e-01 -2.84801740802117e-01 + 4.50000000000000e+01 9.25249734105174e-01 7.57800118621131e-01 -3.00471220322711e-01 + 4.80000000000000e+01 8.90342378222425e-01 8.31789714461067e-01 -3.15332659299714e-01 + 5.10000000000000e+01 8.51395825660653e-01 9.04195569676826e-01 -3.29875873212572e-01 + 5.40000000000000e+01 8.04370620070051e-01 9.73433841829142e-01 -3.43774687106004e-01 + 5.70000000000000e+01 7.57345390210040e-01 1.04267158504194e+00 -3.57676244146600e-01 + 6.00000000000000e+01 7.10320148215417e-01 1.11190906378698e+00 -3.71581147754796e-01 + 6.30000000000000e+01 6.47820663786416e-01 1.16779955248625e+00 -3.84050834181803e-01 + 6.60000000000000e+01 5.85321046718599e-01 1.22368992678063e+00 -3.96521729786065e-01 + 6.90000000000000e+01 5.22821429650782e-01 1.27958030107501e+00 -4.08993794958095e-01 + 7.20000000000000e+01 4.53009361979119e-01 1.32195327919519e+00 -4.20171504341749e-01 + 7.50000000000000e+01 3.79541218701137e-01 1.35756783594738e+00 -4.30701936371378e-01 + 7.80000000000000e+01 3.06071633534284e-01 1.39318280081402e+00 -4.41232525983427e-01 + 8.10000000000000e+01 2.31382797116840e-01 1.42053931469708e+00 -4.50887242301039e-01 + 8.40000000000000e+01 1.54255542363546e-01 1.43137949667301e+00 -4.58789175569348e-01 + 8.70000000000000e+01 7.71276819161773e-02 1.44221976146193e+00 -4.66690861017101e-01 + 9.00000000000000e+01 -3.36965526632122e-07 1.45305993234293e+00 -4.74592503766813e-01 + 9.30000000000000e+01 -5.39897777632595e-02 1.44221975036700e+00 -4.79614013589955e-01 + 9.60000000000000e+01 -1.07979224785424e-01 1.43137952698492e+00 -4.84662548255213e-01 + 9.90000000000000e+01 -1.61968684256675e-01 1.42053922078900e+00 -4.89738716026789e-01 + 1.02000000000000e+02 -2.14250613596524e-01 1.39318262832361e+00 -4.91556612878414e-01 + 1.05000000000000e+02 -2.65678796360800e-01 1.35756807157142e+00 -4.91759948361478e-01 + 1.08000000000000e+02 -3.17106968448641e-01 1.32195310670654e+00 -4.91808185319412e-01 + 1.11000000000000e+02 -3.65975473161876e-01 1.27957981690164e+00 -4.90481329182113e-01 + 1.14000000000000e+02 -4.09724721085945e-01 1.22369008305982e+00 -4.86610622674850e-01 + 1.17000000000000e+02 -4.53474286743658e-01 1.16779992225404e+00 -4.82739400053527e-01 + 1.20000000000000e+02 -4.97223990089781e-01 1.11190952185851e+00 -4.78867879128044e-01 + 1.23000000000000e+02 -5.30141386686949e-01 1.04267204311347e+00 -4.73180864409918e-01 + 1.26000000000000e+02 -5.63058900774808e-01 9.73434299905923e-01 -4.67493542642030e-01 + 1.29000000000000e+02 -5.95976649852831e-01 9.04196027753607e-01 -4.61805698033490e-01 + 1.32000000000000e+02 -6.21647450545520e-01 8.31742453913373e-01 -4.56978785337660e-01 + 1.35000000000000e+02 -6.43694785635686e-01 7.57681233044139e-01 -4.52582281581552e-01 + 1.38000000000000e+02 -6.65741843359713e-01 6.83620285576330e-01 -4.48185737640142e-01 + 1.41000000000000e+02 -6.85948000576951e-01 6.10977986560267e-01 -4.46102392733155e-01 + 1.44000000000000e+02 -7.02472341842677e-01 5.41172995959272e-01 -4.48645505252371e-01 + 1.47000000000000e+02 -7.18996156868714e-01 4.71368155114379e-01 -4.51188446648819e-01 + 1.50000000000000e+02 -7.35519708784299e-01 4.01563389144863e-01 -4.53731249233545e-01 + 1.53000000000000e+02 -7.20041338298566e-01 3.49496494506179e-01 -4.67335818397252e-01 + 1.56000000000000e+02 -7.07403995417188e-01 2.97429648323240e-01 -4.80939257564229e-01 + 1.59000000000000e+02 -6.95102717992735e-01 2.45362816385929e-01 -4.93374572820376e-01 + 1.62000000000000e+02 -6.21487493690614e-01 2.05206612595701e-01 -4.97977180373460e-01 + 1.65000000000000e+02 -5.17905869149982e-01 1.71005823609649e-01 -4.98735700762325e-01 + 1.68000000000000e+02 -4.14324831560763e-01 1.36804826538108e-01 -4.99494277943921e-01 + 1.71000000000000e+02 -3.10743598323177e-01 1.02603707071835e-01 -4.50000513056908e-01 + 1.74000000000000e+02 -2.07161973779746e-01 6.84023428103841e-02 -2.99999717902353e-01 + 1.77000000000000e+02 -1.03108758635925e-01 5.65240009423786e-02 -1.49315896260807e-01 + 1.80000000000000e+02 0.00000000000000e+00 5.58151028351338e-02 0.00000000000000e+00 diff --git a/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_20.dat b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_20.dat new file mode 100644 index 00000000..b86dcd63 --- /dev/null +++ b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_20.dat @@ -0,0 +1,254 @@ +! ------------ AirfoilInfo v1.01.x Input File ---------------------------------- +! AeroElasticSE FAST driver +! line +! line +! ------------------------------------------------------------------------------ +DEFAULT InterpOrd ! Interpolation order to use for quasi-steady table lookup {1=linear; 3=cubic spline; "default"} [default=3] +1 NonDimArea ! The non-dimensional area of the airfoil (area/chord^2) (set to 1.0 if unsure or unneeded) +@"NREL-2p8-127_AF20_Coords.txt" NumCoords ! The number of coordinates in the airfoil shape file. Set to zero if coordinates not included. +AF20_BL.txt BL_file ! The file name including the boundary layer characteristics of the profile. Ignored if the aeroacoustic module is not called. +1 NumTabs ! Number of airfoil tables in this file. Each table must have lines for Re and Ctrl. +! ------------------------------------------------------------------------------ +! data for table 1 +! ------------------------------------------------------------------------------ +6.000000 Re ! Reynolds number in millions +0 Ctrl ! Control setting (must be 0 for current AirfoilInfo) +True InclUAdata ! Is unsteady aerodynamics data included in this table? If TRUE, then include 30 UA coefficients below this line +!........................................ +-3.223506 alpha0 ! 0-lift angle of attack, depends on airfoil. +9.164046 alpha1 ! Angle of attack at f=0.7, (approximately the stall angle) for AOA>alpha0. (deg) +-11.802083 alpha2 ! Angle of attack at f=0.7, (approximately the stall angle) for AOA1] +0.000000 S2 ! Constant in the f curve best-fit for AOA> alpha1; by definition it depends on the airfoil. [ignored if UAMod<>1] +0.000000 S3 ! Constant in the f curve best-fit for alpha2<=AOA< alpha0; by definition it depends on the airfoil. [ignored if UAMod<>1] +0.000000 S4 ! Constant in the f curve best-fit for AOA< alpha2; by definition it depends on the airfoil. [ignored if UAMod<>1] +1.346223 Cn1 ! Critical value of C0n at leading edge separation. It should be extracted from airfoil data at a given Mach and Reynolds number. It can be calculated from the static value of Cn at either the break in the pitching moment or the loss of chord force at the onset of stall. It is close to the condition of maximum lift of the airfoil at low Mach numbers. +-0.953798 Cn2 ! As Cn1 for negative AOAs. +Default St_sh ! Strouhal's shedding frequency constant. [default = 0.19] +0.007766 Cd0 ! 2D drag coefficient value at 0-lift. +-0.112979 Cm0 ! 2D pitching moment coefficient about 1/4-chord location, at 0-lift, positive if nose up. [If the aerodynamics coefficients table does not include a column for Cm, this needs to be set to 0.0] +0.000000 k0 ! Constant in the \hat(x)_cp curve best-fit; = (\hat(x)_AC-0.25). [ignored if UAMod<>1] +0.000000 k1 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k2 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k3 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k1_hat ! Constant in the expression of Cc due to leading edge vortex effects. [ignored if UAMod<>1] +Default x_cp_bar ! Constant in the expression of \hat(x)_cp^v. [ignored if UAMod<>1, default = 0.2] +Default UACutout ! Angle of attack above which unsteady aerodynamics are disabled (deg). [Specifying the string "Default" sets UACutout to 45 degrees] +Default filtCutOff ! Cut-off frequency (-3 dB corner frequency) for low-pass filtering the AoA input to UA, as well as the 1st and 2nd derivatives (Hz) [default = 20] +!........................................ +! Table of aerodynamics coefficients +200 NumAlf ! Number of data lines in the following table +! Alpha Cl Cd Cm +! (deg) (-) (-) (-) +-1.80000000000000e+02 0.00000000000000e+00 5.60839860376548e-02 1.47167178040004e-03 +-1.77000000000000e+02 1.08689836995157e-01 5.60839860376548e-02 1.20045412825477e-01 +-1.74000000000000e+02 2.18375213642741e-01 6.73007199605437e-02 2.39999774321882e-01 +-1.71000000000000e+02 3.27563004817197e-01 1.00951289964885e-01 3.60000410445527e-01 +-1.68000000000000e+02 4.36467171182598e-01 1.34633335777690e-01 3.19169994146170e-01 +-1.65000000000000e+02 5.45229528453792e-01 1.68331119127359e-01 1.97925928770713e-01 +-1.62000000000000e+02 6.53993133012884e-01 2.02028691114530e-01 7.66798765295578e-02 +-1.59000000000000e+02 7.27503940714938e-01 2.42310026594573e-01 -7.27450282376270e-03 +-1.56000000000000e+02 7.31110795820098e-01 2.95758666342963e-01 -1.72902036375927e-02 +-1.53000000000000e+02 7.34319596822270e-01 3.49207314408847e-01 -2.71905033085442e-02 +-1.50000000000000e+02 7.36523173539597e-01 4.02656004658303e-01 -3.53620431597287e-02 +-1.47000000000000e+02 7.19881808024148e-01 4.72422936035072e-01 -1.91283433052972e-02 +-1.44000000000000e+02 7.03240180419886e-01 5.42189935051373e-01 -2.89438151512004e-03 +-1.41000000000000e+02 6.86598028619283e-01 6.11957069351567e-01 1.32352052371265e-02 +-1.38000000000000e+02 6.66302604968628e-01 6.84555659899671e-01 2.92408808365066e-02 +-1.35000000000000e+02 6.44180552804007e-01 7.58569972827814e-01 4.52061276876922e-02 +-1.32000000000000e+02 6.22058248103176e-01 8.32584537348692e-01 6.11744715260335e-02 +-1.29000000000000e+02 5.96320693031764e-01 9.04989003183199e-01 7.72346550841547e-02 +-1.26000000000000e+02 5.63352620077395e-01 9.74173264003827e-01 9.34737950291405e-02 +-1.23000000000000e+02 5.30384796680654e-01 1.04335699334894e+00 1.09713844738546e-01 +-1.20000000000000e+02 4.97417098058063e-01 1.11254045696623e+00 1.25955007125395e-01 +-1.17000000000000e+02 4.53634438299479e-01 1.16837104972410e+00 1.41339031769430e-01 +-1.14000000000000e+02 4.09851924952369e-01 1.22420140310934e+00 1.56723518860802e-01 +-1.11000000000000e+02 3.66069746716654e-01 1.28003132998751e+00 1.72108208755073e-01 +-1.08000000000000e+02 3.17177705557324e-01 1.32234220591584e+00 1.85841350669341e-01 +-1.05000000000000e+02 2.65730694027691e-01 1.35789345342785e+00 1.98749244923706e-01 +-1.02000000000000e+02 2.14283672037506e-01 1.39344429355730e+00 2.11656834470358e-01 +-9.90000000000000e+01 1.61987132519313e-01 1.42073648944996e+00 2.23201790003783e-01 +-9.60000000000000e+01 1.07991521148030e-01 1.43151103914374e+00 2.32020842715942e-01 +-9.30000000000000e+01 5.39959252161754e-02 1.44228550652603e+00 2.40839683380319e-01 +-9.00000000000000e+01 3.37003894400466e-07 1.45305993275333e+00 2.49658549004585e-01 +-8.70000000000000e+01 -5.39958699516678e-02 1.44228551755366e+00 2.54494482776028e-01 +-8.40000000000000e+01 -1.07991672131789e-01 1.43151100901570e+00 2.59343605608854e-01 +-8.10000000000000e+01 -1.61986664762753e-01 1.42073658278841e+00 2.64205569719769e-01 +-7.80000000000000e+01 -2.14283422866425e-01 1.39344446573911e+00 2.65795815265371e-01 +-7.50000000000000e+01 -2.65731034397795e-01 1.35789321822535e+00 2.65755918593268e-01 +-7.20000000000000e+01 -3.17177456391675e-01 1.32234237809590e+00 2.65727119737369e-01 +-6.90000000000000e+01 -3.66069367431166e-01 1.28003181364278e+00 2.64438345067420e-01 +-6.60000000000000e+01 -4.09852047376346e-01 1.22420124699738e+00 2.60617266085316e-01 +-6.30000000000000e+01 -4.53634727963402e-01 1.16837068035199e+00 2.56805932797703e-01 +-6.00000000000000e+01 -4.97417316170630e-01 1.11253999925206e+00 2.53004344403069e-01 +-5.70000000000000e+01 -5.30385014793222e-01 1.04335653563477e+00 2.47400711870632e-01 +-5.40000000000000e+01 -5.63352838192439e-01 9.74172806284381e-01 2.41806514160262e-01 +-5.10000000000000e+01 -5.96320911146808e-01 9.04988545463753e-01 2.36221437763850e-01 +-4.80000000000000e+01 -6.23645028218618e-01 8.32633137744547e-01 2.30956513607567e-01 +-4.50000000000000e+01 -6.48147258055512e-01 7.58692207540872e-01 2.25857970172168e-01 +-4.20000000000000e+01 -6.67889372666217e-01 6.84604259911055e-01 2.22474982226598e-01 +-3.90000000000000e+01 -6.86802709568193e-01 6.10910749328229e-01 2.19736387390917e-01 +-3.60000000000000e+01 -7.03478405910380e-01 5.38816968440485e-01 2.19280528126823e-01 +-3.30000000000000e+01 -7.19572395319055e-01 4.69344655336830e-01 2.22204576432948e-01 +-3.00000000000000e+01 -7.36523295159899e-01 4.02655570575433e-01 2.28913832317185e-01 +-2.93939393939394e+01 -7.40428301639941e-01 3.89857123435579e-01 2.31295215800378e-01 +-2.87878787878788e+01 -7.44333308119982e-01 3.77058676295725e-01 2.33676599283572e-01 +-2.81818181818182e+01 -7.48238314600024e-01 3.64260229155871e-01 2.36057982766765e-01 +-2.75757575757576e+01 -7.52613641879506e-01 3.51870974153269e-01 2.39172506623836e-01 +-2.69696969696970e+01 -7.57190552507842e-01 3.39657102253967e-01 2.42601260453133e-01 +-2.63636363636364e+01 -7.61767463136177e-01 3.27443230354664e-01 2.46030014282430e-01 +-2.57575757575758e+01 -7.66749761722573e-01 3.15487613973748e-01 2.50008630333910e-01 +-2.51515151515151e+01 -7.72340047765258e-01 3.03919320680690e-01 2.54811911566304e-01 +-2.45454545454545e+01 -7.77930333807944e-01 2.92351027387632e-01 2.59615192798699e-01 +-2.39393939393939e+01 -7.83831337974498e-01 2.80845692169765e-01 2.63368296589326e-01 +-2.33333333333333e+01 -7.92528865412384e-01 2.69906991817601e-01 2.57669600084677e-01 +-2.27272727272727e+01 -8.01226392850269e-01 2.58968291465437e-01 2.51477123925418e-01 +-2.21212121212121e+01 -8.09923920288154e-01 2.48029591113273e-01 2.45907124300863e-01 +-2.15151515151515e+01 -8.20235783478513e-01 2.37173728120076e-01 2.31168860674295e-01 +-2.09090909090909e+01 -8.29622622700524e-01 2.26338579795089e-01 2.13713746850245e-01 +-2.03030303030303e+01 -8.39213259378848e-01 2.15503431470102e-01 1.96258633026194e-01 +-1.96969696969697e+01 -8.49342921178197e-01 2.04670828846016e-01 1.78811743339257e-01 +-1.90909090909091e+01 -8.59723555494070e-01 1.93840771778819e-01 1.61373077324190e-01 +-1.84848484848485e+01 -8.69355568885329e-01 1.82817117288920e-01 1.43848790063230e-01 +-1.78787878787879e+01 -8.78841519111643e-01 1.71507191312464e-01 1.26522966331281e-01 +-1.72727272727273e+01 -8.88304094365764e-01 1.60344653968440e-01 1.09264562513686e-01 +-1.66666666666667e+01 -8.97226846531499e-01 1.49299202250655e-01 9.19320215375475e-02 +-1.60606060606061e+01 -9.05768732409721e-01 1.38352219033920e-01 7.45346221583764e-02 +-1.54545454545455e+01 -9.14769264432095e-01 1.27532003288276e-01 5.67050762225817e-02 +-1.48484848484848e+01 -9.24224518221895e-01 1.16781059230677e-01 3.86315588318540e-02 +-1.42424242424242e+01 -9.34933174803990e-01 1.06107627638312e-01 2.02903974043766e-02 +-1.36363636363636e+01 -9.46580047643885e-01 9.54549647670512e-02 2.58155653624406e-03 +-1.30303030303030e+01 -9.59376519315215e-01 8.48210475936575e-02 -1.51277660357559e-02 +-1.24242424242424e+01 -9.49137204600254e-01 7.23014208476810e-02 -2.45207730999593e-02 +-1.18181818181818e+01 -9.33511315858133e-01 6.03072372984705e-02 -3.14401400294280e-02 +-1.12121212121212e+01 -9.07412559417457e-01 4.91969779770790e-02 -3.36076468476470e-02 +-1.06060606060606e+01 -8.74358654564795e-01 3.98750651939524e-02 -3.77019772884650e-02 +-1.00000000000000e+01 -8.37436227745362e-01 3.15713217351823e-02 -4.28344259088231e-02 +-9.39393939393939e+00 -7.97360016762257e-01 2.49748326421447e-02 -4.78167321636766e-02 +-8.78787878787879e+00 -7.46918091090845e-01 1.90106766562991e-02 -5.49142422548264e-02 +-8.18181818181818e+00 -6.76385235190348e-01 1.41430349552736e-02 -6.55740988464556e-02 +-7.57575757575758e+00 -5.97548773054335e-01 1.16500159105889e-02 -7.40578404001251e-02 +-6.96969696969697e+00 -5.14687150181851e-01 1.02794635432385e-02 -8.15694642369420e-02 +-6.36363636363636e+00 -4.29783331561822e-01 9.37100611916169e-03 -8.89972589526919e-02 +-5.75757575757576e+00 -3.44985681028980e-01 8.72254512466363e-03 -9.56743162334849e-02 +-5.15151515151515e+00 -2.60342088083212e-01 8.36628808560654e-03 -1.01294050980689e-01 +-4.54545454545454e+00 -1.77283987129221e-01 8.15049198443473e-03 -1.05574157964945e-01 +-3.93939393939394e+00 -9.49967516754283e-02 7.98399273984275e-03 -1.09327817332233e-01 +-3.33333333333333e+00 -1.45488178579448e-02 7.79517199106549e-03 -1.12477093218156e-01 +-2.72727272727273e+00 6.57363122021591e-02 7.63446498473685e-03 -1.15244192981836e-01 +-2.12121212121212e+00 1.45332789615814e-01 7.51105279420149e-03 -1.17982678474176e-01 +-1.51515151515152e+00 2.23672723468766e-01 7.44827862315605e-03 -1.20431702659156e-01 +-9.09090909090912e-01 3.00978847690010e-01 7.43157561421629e-03 -1.22712093550068e-01 +-3.03030303030302e-01 3.76098908531403e-01 7.51006367733051e-03 -1.24767379670863e-01 + 3.03030303030302e-01 4.51444826699281e-01 7.54938811200737e-03 -1.26721030186769e-01 + 9.09090909090912e-01 5.27096787476172e-01 7.54812362715996e-03 -1.28437544066459e-01 + 1.51515151515152e+00 6.02777798759360e-01 7.55798597733358e-03 -1.30082417308287e-01 + 2.12121212121212e+00 6.78328119290960e-01 7.71509624311103e-03 -1.31599798151816e-01 + 2.72727272727273e+00 7.53369580256120e-01 7.87416012848208e-03 -1.33039382183475e-01 + 3.33333333333333e+00 8.27436011075852e-01 8.02072404030208e-03 -1.34343039337526e-01 + 3.93939393939394e+00 9.01064324481151e-01 8.17634754573474e-03 -1.35496483033582e-01 + 4.54545454545455e+00 9.74097640300264e-01 8.37626659639857e-03 -1.36379157527485e-01 + 5.15151515151515e+00 1.04648944718360e+00 8.60497543451105e-03 -1.37098870871982e-01 + 5.75757575757576e+00 1.11709742972339e+00 8.90798254151872e-03 -1.37401161602970e-01 + 6.36363636363637e+00 1.18428988344244e+00 9.27589711393541e-03 -1.37179374672226e-01 + 6.96969696969697e+00 1.24896889274954e+00 9.70884746672005e-03 -1.36604163101376e-01 + 7.57575757575757e+00 1.29881944271375e+00 1.06632766664296e-02 -1.33835538319740e-01 + 8.18181818181818e+00 1.33958725078695e+00 1.19126582890210e-02 -1.30168176642310e-01 + 8.78787878787879e+00 1.36005346559897e+00 1.39779508814557e-02 -1.24720046583824e-01 + 9.39393939393939e+00 1.34301374720075e+00 2.30914396203260e-02 -1.22744826084420e-01 + 1.00000000000000e+01 1.30753093113672e+00 3.60092777128439e-02 -1.22742898670035e-01 + 1.06060606060606e+01 1.21740138674990e+00 4.73489216901772e-02 -1.21777727655646e-01 + 1.12121212121212e+01 1.14876626618267e+00 5.64290043026546e-02 -1.19509336453563e-01 + 1.18181818181818e+01 1.12008684609046e+00 6.13613926416215e-02 -1.14351014023090e-01 + 1.24242424242424e+01 1.10641679635825e+00 6.86990657706108e-02 -1.09572759572039e-01 + 1.30303030303030e+01 1.10001146588234e+00 7.71321227342433e-02 -1.05827721623316e-01 + 1.36363636363636e+01 1.10899885123525e+00 8.72204117979317e-02 -1.07475148520177e-01 + 1.42424242424242e+01 1.12008882355609e+00 9.75650647021123e-02 -1.09425019423431e-01 + 1.48484848484848e+01 1.13075597639677e+00 1.08294194106513e-01 -1.11906001460801e-01 + 1.54545454545455e+01 1.13516931068150e+00 1.17464255427677e-01 -1.13115892870182e-01 + 1.60606060606061e+01 1.13676837338324e+00 1.25978158509963e-01 -1.13656640925689e-01 + 1.66666666666667e+01 1.13211072570407e+00 1.33262514337462e-01 -1.12840862880448e-01 + 1.72727272727273e+01 1.13058655438625e+00 1.42129358900706e-01 -1.13195774561728e-01 + 1.78787878787879e+01 1.13267144501086e+00 1.52930376429612e-01 -1.14987235036101e-01 + 1.84848484848485e+01 1.13534488348534e+00 1.65326800303123e-01 -1.18507779175190e-01 + 1.90909090909091e+01 1.13808110384824e+00 1.77947867911582e-01 -1.22278286215279e-01 + 1.96969696969697e+01 1.13996942404966e+00 1.89581788465173e-01 -1.25014693335627e-01 + 2.03030303030303e+01 1.14136257005177e+00 2.02809939468738e-01 -1.28759059263829e-01 + 2.09090909090909e+01 1.14278916134738e+00 2.17632411113615e-01 -1.33592215797638e-01 + 2.15151515151515e+01 1.14520088380394e+00 2.32454882758493e-01 -1.38449866850649e-01 + 2.21212121212121e+01 1.14534623034980e+00 2.46593134049512e-01 -1.43713984431992e-01 + 2.27272727272727e+01 1.13669195126191e+00 2.57995207937436e-01 -1.50603549902548e-01 + 2.33333333333333e+01 1.12803767217403e+00 2.69397281825361e-01 -1.57514015684770e-01 + 2.39393939393939e+01 1.11938339308615e+00 2.80799355713285e-01 -1.64504480543572e-01 + 2.45454545454545e+01 1.11133045136127e+00 2.92351027387632e-01 -1.70538137552357e-01 + 2.51515151515151e+01 1.10334432346167e+00 3.03919320680690e-01 -1.76461209319149e-01 + 2.57575757575758e+01 1.09535819556207e+00 3.15487613973748e-01 -1.82379292873812e-01 + 2.63636363636364e+01 1.08824062881607e+00 3.27443230354664e-01 -1.87812657912168e-01 + 2.69696969696970e+01 1.08170219282164e+00 3.39657102253967e-01 -1.92922675867797e-01 + 2.75757575757576e+01 1.07516375682721e+00 3.51870974153269e-01 -1.98029550237023e-01 + 2.81818181818182e+01 1.06891342259585e+00 3.64260229155871e-01 -2.02965263331226e-01 + 2.87878787878788e+01 1.06333526814667e+00 3.77058676295725e-01 -2.07506580463469e-01 + 2.93939393939394e+01 1.05775711369748e+00 3.89857123435579e-01 -2.12045827432426e-01 + 3.00000000000000e+01 1.05217895924830e+00 4.02655570575433e-01 -2.16582986742122e-01 + 3.30000000000000e+01 1.02795917310136e+00 4.69344655336830e-01 -2.36555351110227e-01 + 3.60000000000000e+01 1.00496772750934e+00 5.38816968440485e-01 -2.54825361123685e-01 + 3.90000000000000e+01 9.81146869188920e-01 6.10910749328229e-01 -2.71702784264139e-01 + 4.20000000000000e+01 9.54127928885481e-01 6.84604259911056e-01 -2.87623690411183e-01 + 4.50000000000000e+01 9.25925507989752e-01 7.58692207540872e-01 -3.03272921560484e-01 + 4.80000000000000e+01 8.90921980696787e-01 8.32633137744547e-01 -3.18102995823141e-01 + 5.10000000000000e+01 8.51887356225999e-01 9.04988545463753e-01 -3.32607858873096e-01 + 5.40000000000000e+01 8.04790278249480e-01 9.74172806284381e-01 -3.46467861120541e-01 + 5.70000000000000e+01 7.57693159426409e-01 1.04335653563477e+00 -3.60325018324970e-01 + 6.00000000000000e+01 7.10596020180217e-01 1.11253999925206e+00 -3.74179542354393e-01 + 6.30000000000000e+01 6.48049471053151e-01 1.16837068035199e+00 -3.86611182558364e-01 + 6.60000000000000e+01 5.85502788028442e-01 1.22420124699738e+00 -3.99041445615547e-01 + 6.90000000000000e+01 5.22956102060375e-01 1.28003181364278e+00 -4.11470147230388e-01 + 7.20000000000000e+01 4.53110398690217e-01 1.32234237809590e+00 -4.22612100063294e-01 + 7.50000000000000e+01 3.79615336039622e-01 1.35789321822535e+00 -4.33110599511480e-01 + 7.80000000000000e+01 3.06118835606714e-01 1.39344446573911e+00 -4.43608014083683e-01 + 8.10000000000000e+01 2.31409126413095e-01 1.42073658278841e+00 -4.53232613764225e-01 + 8.40000000000000e+01 1.54273083446276e-01 1.43151100901570e+00 -4.61112452060330e-01 + 8.70000000000000e+01 7.71364489011903e-02 1.44228551755366e+00 -4.68991671868026e-01 + 9.00000000000000e+01 -3.37003894630567e-07 1.45305993275333e+00 -4.76870426093284e-01 + 9.30000000000000e+01 -5.39959252161754e-02 1.44228550652603e+00 -4.81692680238558e-01 + 9.60000000000000e+01 -1.07991521148031e-01 1.43151103914374e+00 -4.86490823116468e-01 + 9.90000000000000e+01 -1.61987132519313e-01 1.42073648944996e+00 -4.91273974428200e-01 + 1.02000000000000e+02 -2.14283672037506e-01 1.39344429355730e+00 -4.92759271498875e-01 + 1.05000000000000e+02 -2.65730694027692e-01 1.35789345342785e+00 -4.92588207197183e-01 + 1.08000000000000e+02 -3.17177705557324e-01 1.32234220591584e+00 -4.92507133962652e-01 + 1.11000000000000e+02 -3.66069746716655e-01 1.28003132998751e+00 -4.91213114955779e-01 + 1.14000000000000e+02 -4.09851924952369e-01 1.22420140310934e+00 -4.87375141860954e-01 + 1.17000000000000e+02 -4.53634438299479e-01 1.16837104972410e+00 -4.83536739448328e-01 + 1.20000000000000e+02 -4.97417098058063e-01 1.11254045696623e+00 -4.79698118822128e-01 + 1.23000000000000e+02 -5.30384796680655e-01 1.04335699334894e+00 -4.74045178392828e-01 + 1.26000000000000e+02 -5.63352620077395e-01 9.74173264003827e-01 -4.68392016442808e-01 + 1.29000000000000e+02 -5.96320693031764e-01 9.04989003183198e-01 -4.62734898551017e-01 + 1.32000000000000e+02 -6.22058248103176e-01 8.32584537348691e-01 -4.57940896727791e-01 + 1.35000000000000e+02 -6.44180552804007e-01 7.58569972827814e-01 -4.53579623270348e-01 + 1.38000000000000e+02 -6.66302604968628e-01 6.84555659899671e-01 -4.49218395373695e-01 + 1.41000000000000e+02 -6.86598028619283e-01 6.11957069351566e-01 -4.47177800534488e-01 + 1.44000000000000e+02 -7.03240180419886e-01 5.42189935051373e-01 -4.49778490640875e-01 + 1.47000000000000e+02 -7.19881808024148e-01 4.72422936035072e-01 -4.52379161521216e-01 + 1.50000000000000e+02 -7.36523173539597e-01 4.02656004658303e-01 -4.54979822788877e-01 + 1.53000000000000e+02 -7.23995989268374e-01 3.50606387738054e-01 -4.68570401665813e-01 + 1.56000000000000e+02 -7.10014434000594e-01 2.98556810596401e-01 -4.82106047676863e-01 + 1.59000000000000e+02 -6.95822993804938e-01 2.46507230442391e-01 -4.96319099842072e-01 + 1.62000000000000e+02 -6.22266685072149e-01 2.06230353085240e-01 -5.00873829028078e-01 + 1.65000000000000e+02 -5.18715046462665e-01 1.71839926690689e-01 -5.00546173646419e-01 + 1.68000000000000e+02 -4.15163994460962e-01 1.37449294383709e-01 -5.00218470478517e-01 + 1.71000000000000e+02 -3.11516836116274e-01 1.03069943092153e-01 -4.50000513056908e-01 + 1.74000000000000e+02 -2.07677460598702e-01 6.87131543581221e-02 -2.99999717902353e-01 + 1.77000000000000e+02 -1.03365251644600e-01 5.67869836313884e-02 -1.48723200443975e-01 + 1.80000000000000e+02 0.00000000000000e+00 5.60839860376548e-02 1.47167178040004e-03 diff --git a/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_21.dat b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_21.dat new file mode 100644 index 00000000..b3de07d8 --- /dev/null +++ b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_21.dat @@ -0,0 +1,254 @@ +! ------------ AirfoilInfo v1.01.x Input File ---------------------------------- +! AeroElasticSE FAST driver +! line +! line +! ------------------------------------------------------------------------------ +DEFAULT InterpOrd ! Interpolation order to use for quasi-steady table lookup {1=linear; 3=cubic spline; "default"} [default=3] +1 NonDimArea ! The non-dimensional area of the airfoil (area/chord^2) (set to 1.0 if unsure or unneeded) +@"NREL-2p8-127_AF21_Coords.txt" NumCoords ! The number of coordinates in the airfoil shape file. Set to zero if coordinates not included. +AF21_BL.txt BL_file ! The file name including the boundary layer characteristics of the profile. Ignored if the aeroacoustic module is not called. +1 NumTabs ! Number of airfoil tables in this file. Each table must have lines for Re and Ctrl. +! ------------------------------------------------------------------------------ +! data for table 1 +! ------------------------------------------------------------------------------ +6.000000 Re ! Reynolds number in millions +0 Ctrl ! Control setting (must be 0 for current AirfoilInfo) +True InclUAdata ! Is unsteady aerodynamics data included in this table? If TRUE, then include 30 UA coefficients below this line +!........................................ +-3.391748 alpha0 ! 0-lift angle of attack, depends on airfoil. +9.217593 alpha1 ! Angle of attack at f=0.7, (approximately the stall angle) for AOA>alpha0. (deg) +-11.634112 alpha2 ! Angle of attack at f=0.7, (approximately the stall angle) for AOA1] +0.000000 S2 ! Constant in the f curve best-fit for AOA> alpha1; by definition it depends on the airfoil. [ignored if UAMod<>1] +0.000000 S3 ! Constant in the f curve best-fit for alpha2<=AOA< alpha0; by definition it depends on the airfoil. [ignored if UAMod<>1] +0.000000 S4 ! Constant in the f curve best-fit for AOA< alpha2; by definition it depends on the airfoil. [ignored if UAMod<>1] +1.356958 Cn1 ! Critical value of C0n at leading edge separation. It should be extracted from airfoil data at a given Mach and Reynolds number. It can be calculated from the static value of Cn at either the break in the pitching moment or the loss of chord force at the onset of stall. It is close to the condition of maximum lift of the airfoil at low Mach numbers. +-0.907795 Cn2 ! As Cn1 for negative AOAs. +Default St_sh ! Strouhal's shedding frequency constant. [default = 0.19] +0.007422 Cd0 ! 2D drag coefficient value at 0-lift. +-0.113062 Cm0 ! 2D pitching moment coefficient about 1/4-chord location, at 0-lift, positive if nose up. [If the aerodynamics coefficients table does not include a column for Cm, this needs to be set to 0.0] +0.000000 k0 ! Constant in the \hat(x)_cp curve best-fit; = (\hat(x)_AC-0.25). [ignored if UAMod<>1] +0.000000 k1 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k2 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k3 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k1_hat ! Constant in the expression of Cc due to leading edge vortex effects. [ignored if UAMod<>1] +Default x_cp_bar ! Constant in the expression of \hat(x)_cp^v. [ignored if UAMod<>1, default = 0.2] +Default UACutout ! Angle of attack above which unsteady aerodynamics are disabled (deg). [Specifying the string "Default" sets UACutout to 45 degrees] +Default filtCutOff ! Cut-off frequency (-3 dB corner frequency) for low-pass filtering the AoA input to UA, as well as the 1st and 2nd derivatives (Hz) [default = 20] +!........................................ +! Table of aerodynamics coefficients +200 NumAlf ! Number of data lines in the following table +! Alpha Cl Cd Cm +! (deg) (-) (-) (-) +-1.80000000000000e+02 0.00000000000000e+00 5.43028798119170e-02 2.26615932282131e-02 +-1.77000000000000e+02 1.13025106629939e-01 5.43028798119170e-02 1.28579365822585e-01 +-1.74000000000000e+02 2.27085486936604e-01 6.51633944994418e-02 2.39999774321882e-01 +-1.71000000000000e+02 3.40628485406802e-01 9.77452951033210e-02 3.60000410445527e-01 +-1.68000000000000e+02 4.49810292581463e-01 1.30815585114068e-01 3.17166481479515e-01 +-1.65000000000000e+02 5.56811555009885e-01 1.64130064128025e-01 1.92917170488019e-01 +-1.62000000000000e+02 6.63814055955440e-01 1.97444368137118e-01 6.86658789432206e-02 +-1.59000000000000e+02 7.35163378078923e-01 2.37618358711485e-01 -1.63189555213320e-02 +-1.56000000000000e+02 7.36658480852925e-01 2.91511490364540e-01 -2.43269386035842e-02 +-1.53000000000000e+02 7.37191671747579e-01 3.45404633730741e-01 -3.20559725750530e-02 +-1.50000000000000e+02 7.35295872691298e-01 3.99297820213560e-01 -3.53001565756154e-02 +-1.47000000000000e+02 7.18798588287585e-01 4.69181021715765e-01 -1.90934045495720e-02 +-1.44000000000000e+02 7.02301063534926e-01 5.39064308687913e-01 -2.88639524111870e-03 +-1.41000000000000e+02 6.85803058067216e-01 6.08947766606052e-01 1.29498269612823e-02 +-1.38000000000000e+02 6.65616813110053e-01 6.81680698854136e-01 2.86882702662571e-02 +-1.35000000000000e+02 6.43586455890160e-01 7.55838362486724e-01 4.44546354620422e-02 +-1.32000000000000e+02 6.21555858594649e-01 8.29996331514374e-01 6.02291708250731e-02 +-1.29000000000000e+02 5.95899961956707e-01 9.02551799836887e-01 7.61226856194456e-02 +-1.26000000000000e+02 5.62993449444218e-01 9.71902259143020e-01 9.22427459258282e-02 +-1.23000000000000e+02 5.30087151245601e-01 1.04125214332386e+00 1.08365878635908e-01 +-1.20000000000000e+02 4.97180960199916e-01 1.11060173995280e+00 1.24492137036960e-01 +-1.17000000000000e+02 4.53438556744641e-01 1.16661616454686e+00 1.39794623246837e-01 +-1.14000000000000e+02 4.09696303308865e-01 1.22263034910072e+00 1.55098596191987e-01 +-1.11000000000000e+02 3.65954392283428e-01 1.27864410574316e+00 1.70403792833604e-01 +-1.08000000000000e+02 3.17091142370324e-01 1.32114669115373e+00 1.84082975431326e-01 +-1.05000000000000e+02 2.65667184017510e-01 1.35689358806697e+00 1.96954679095920e-01 +-1.02000000000000e+02 2.14243214939976e-01 1.39264007535569e+00 2.09826696172051e-01 +-9.90000000000000e+01 1.61964542361192e-01 1.42013008159586e+00 2.21340640675138e-01 +-9.60000000000000e+01 1.07976425758201e-01 1.43110676810732e+00 2.30136989903572e-01 +-9.30000000000000e+01 5.39883669172201e-02 1.44208337076307e+00 2.38933482205731e-01 +-9.00000000000000e+01 3.36956720911094e-07 1.45305993149174e+00 2.47730362549832e-01 +-8.70000000000000e+01 -5.39883116604485e-02 1.44208338199759e+00 2.52366652228794e-01 +-8.40000000000000e+01 -1.07976576721003e-01 1.43110673741406e+00 2.57034873165347e-01 +-8.10000000000000e+01 -1.61964074669558e-01 1.42013017668539e+00 2.61734177795205e-01 +-7.80000000000000e+01 -2.14242965880546e-01 1.39264024848507e+00 2.63181349488851e-01 +-7.50000000000000e+01 -2.65667524235096e-01 1.35689335157008e+00 2.63016349820918e-01 +-7.20000000000000e+01 -3.17090893316325e-01 1.32114686428136e+00 2.62879007650853e-01 +-6.90000000000000e+01 -3.65954013346774e-01 1.27864459099094e+00 2.61500645209288e-01 +-6.60000000000000e+01 -4.09696425620247e-01 1.22263019247474e+00 2.57610540723508e-01 +-6.30000000000000e+01 -4.53438846142231e-01 1.16661579395854e+00 2.53744590647427e-01 +-6.00000000000000e+01 -4.97181177905552e-01 1.11060128113950e+00 2.49902512739027e-01 +-5.70000000000000e+01 -5.30087368951238e-01 1.04125168451056e+00 2.44282377435672e-01 +-5.40000000000000e+01 -5.62993667151980e-01 9.71901800324015e-01 2.38685350754697e-01 +-5.10000000000000e+01 -5.95900179664471e-01 9.02551341017881e-01 2.33110985323929e-01 +-4.80000000000000e+01 -6.23148878462794e-01 8.30040803802850e-01 2.27879411582758e-01 +-4.50000000000000e+01 -6.47568761333111e-01 7.55950278420295e-01 2.22834475134647e-01 +-4.20000000000000e+01 -6.67209820511491e-01 6.81725170790388e-01 2.19541528712913e-01 +-3.90000000000000e+01 -6.86016653934843e-01 6.07897658893372e-01 2.16860523607545e-01 +-3.60000000000000e+01 -7.02567434351865e-01 5.35679831809432e-01 2.16283272016665e-01 +-3.30000000000000e+01 -7.18514395643352e-01 4.66093046844495e-01 2.19061994245276e-01 +-3.00000000000000e+01 -7.35295993131416e-01 3.99297385438155e-01 2.25596659795295e-01 +-2.93939393939394e+01 -7.39161194393161e-01 3.86479064937486e-01 2.27934329427074e-01 +-2.87878787878788e+01 -7.43026395654906e-01 3.73660744436817e-01 2.30271999058854e-01 +-2.81818181818182e+01 -7.46891596916650e-01 3.60842423936148e-01 2.32609668690633e-01 +-2.75757575757576e+01 -7.51223361563041e-01 3.48434171659383e-01 2.35674061206088e-01 +-2.69696969696970e+01 -7.55755099099513e-01 3.36201677983836e-01 2.39049933104880e-01 +-2.63636363636364e+01 -7.60286836635986e-01 3.23969184308288e-01 2.42425805003671e-01 +-2.57575757575758e+01 -7.65221306359447e-01 3.11995455491433e-01 2.46346530788199e-01 +-2.51515151515151e+01 -7.70759780501553e-01 3.00409813654186e-01 2.51084410416232e-01 +-2.45454545454545e+01 -7.76298254643659e-01 2.88824171816938e-01 2.55822290044264e-01 +-2.39393939393939e+01 -7.82132311059061e-01 2.77302256598583e-01 2.59616206109365e-01 +-2.33333333333333e+01 -7.90626665160274e-01 2.66353893288030e-01 2.54914267352217e-01 +-2.27272727272727e+01 -7.99121019261486e-01 2.55405529977478e-01 2.49019152637843e-01 +-2.21212121212121e+01 -8.07615373362699e-01 2.44457166666925e-01 2.44656741536136e-01 +-2.15151515151515e+01 -8.17117669056492e-01 2.33552006854907e-01 2.32819418554197e-01 +-2.09090909090909e+01 -8.23661297618886e-01 2.22657650696563e-01 2.18130675248769e-01 +-2.03030303030303e+01 -8.30697385161204e-01 2.11763294538219e-01 2.03441931943341e-01 +-1.96969696969697e+01 -8.39130226130645e-01 2.00903773822104e-01 1.88879827702874e-01 +-1.90909090909091e+01 -8.48263760915409e-01 1.90079086577562e-01 1.74444355363349e-01 +-1.84848484848485e+01 -8.54491663822831e-01 1.78820853261852e-01 1.58678068289752e-01 +-1.78787878787879e+01 -8.60163856305434e-01 1.66900896684023e-01 1.43105400370003e-01 +-1.72727272727273e+01 -8.65742368749698e-01 1.55433036053471e-01 1.27344882544298e-01 +-1.66666666666667e+01 -8.69217768752512e-01 1.44247604332767e-01 1.10578705840612e-01 +-1.60606060606061e+01 -8.71119382404463e-01 1.33299705468418e-01 9.29795736467647e-02 +-1.54545454545455e+01 -8.74590802382996e-01 1.22693011692481e-01 7.42553100122313e-02 +-1.48484848484848e+01 -8.79448011540517e-01 1.12275192353923e-01 5.48980138044471e-02 +-1.42424242424242e+01 -8.88041287646387e-01 1.02097518094139e-01 3.47904219734257e-02 +-1.36363636363636e+01 -8.99011386472906e-01 9.19774216439529e-02 1.62310520565996e-02 +-1.30303030303030e+01 -9.12832326690409e-01 8.19089384860160e-02 -2.31248158698626e-03 +-1.24242424242424e+01 -9.05837733998151e-01 7.05955147275284e-02 -1.32519999298020e-02 +-1.18181818181818e+01 -8.94149738372733e-01 6.00304976315857e-02 -2.19483169052786e-02 +-1.12121212121212e+01 -8.72289143999857e-01 4.92518839816106e-02 -2.63426664394142e-02 +-1.06060606060606e+01 -8.43836935503105e-01 3.99601622843484e-02 -3.25182305032108e-02 +-1.00000000000000e+01 -8.11533667684698e-01 3.16634689071838e-02 -3.96531690559947e-02 +-9.39393939393939e+00 -7.73775299793918e-01 2.50351497976403e-02 -4.66232350387770e-02 +-8.78787878787879e+00 -7.24386153510650e-01 1.90363399048990e-02 -5.58158243641951e-02 +-8.18181818181818e+00 -6.51350581746786e-01 1.39307768873385e-02 -6.82565719779272e-02 +-7.57575757575758e+00 -5.70259292800422e-01 1.11966451026731e-02 -7.78318201646995e-02 +-6.96969696969697e+00 -4.84863483201162e-01 9.80210985000549e-03 -8.59002125918137e-02 +-6.36363636363636e+00 -4.01260274507495e-01 8.79364513160939e-03 -9.27920938216900e-02 +-5.75757575757576e+00 -3.17829037962407e-01 8.21072836680058e-03 -9.88413955927494e-02 +-5.15151515151515e+00 -2.34560631356565e-01 7.89417831655769e-03 -1.03830189790787e-01 +-4.54545454545454e+00 -1.52768219821946e-01 7.69629272463115e-03 -1.07609067491263e-01 +-3.93939393939394e+00 -7.17446885276158e-02 7.55980850277901e-03 -1.10714124632562e-01 +-3.33333333333333e+00 7.65266106535894e-03 7.40740590680152e-03 -1.13312526310592e-01 +-2.72727272727273e+00 8.69540435134952e-02 7.26852935125166e-03 -1.15619076304701e-01 +-2.12121212121212e+00 1.65602650506344e-01 7.16999070079818e-03 -1.17974728073125e-01 +-1.51515151515152e+00 2.43153008832856e-01 7.12240036540634e-03 -1.20398358450422e-01 +-9.09090909090912e-01 3.19690083645440e-01 7.11221121992558e-03 -1.22659469489510e-01 +-3.03030303030302e-01 3.94185583692908e-01 7.18341302084739e-03 -1.24698324985504e-01 + 3.03030303030302e-01 4.68902411410735e-01 7.22469085552886e-03 -1.26637855769298e-01 + 9.09090909090912e-01 5.43881635947123e-01 7.21999237311871e-03 -1.28343787287290e-01 + 1.51515151515152e+00 6.18852988644897e-01 7.24722163406657e-03 -1.29976534377553e-01 + 2.12121212121212e+00 6.93718405482782e-01 7.38406188230317e-03 -1.31468930098195e-01 + 2.72727272727273e+00 7.68149611769229e-01 7.53516389223080e-03 -1.32869142821252e-01 + 3.33333333333333e+00 8.41715172859199e-01 7.67641621971856e-03 -1.34133903242727e-01 + 3.93939393939394e+00 9.14829634658937e-01 7.82676312299375e-03 -1.35268602227928e-01 + 4.54545454545455e+00 9.87354918951398e-01 8.01392970071129e-03 -1.36139906970678e-01 + 5.15151515151515e+00 1.05927746446687e+00 8.23073134973320e-03 -1.36861989320736e-01 + 5.75757575757576e+00 1.12953343156332e+00 8.53450625263956e-03 -1.37191762867414e-01 + 6.36363636363637e+00 1.19646607280768e+00 8.93008691845142e-03 -1.37002644214539e-01 + 6.96969696969697e+00 1.26024731016983e+00 9.47027625942907e-03 -1.36418678279720e-01 + 7.57575757575757e+00 1.30971003050197e+00 1.06647324108263e-02 -1.33671247589578e-01 + 8.18181818181818e+00 1.35040217332210e+00 1.19527461931973e-02 -1.30058175517731e-01 + 8.78787878787879e+00 1.37091316495312e+00 1.39974785904022e-02 -1.24857926363025e-01 + 9.39393939393939e+00 1.35667712683307e+00 2.24354236046123e-02 -1.22733114545900e-01 + 1.00000000000000e+01 1.32700007053080e+00 3.43303944973221e-02 -1.22710273741457e-01 + 1.06060606060606e+01 1.24713203043916e+00 4.48348853319247e-02 -1.21775958563809e-01 + 1.12121212121212e+01 1.18632667549810e+00 5.33280007969130e-02 -1.20204637608153e-01 + 1.18181818181818e+01 1.16131302771668e+00 5.88308583503445e-02 -1.15957794313766e-01 + 1.24242424242424e+01 1.14844752198994e+00 6.69420911628980e-02 -1.11212235524214e-01 + 1.30303030303030e+01 1.14161039119524e+00 7.59411805359307e-02 -1.07908924395850e-01 + 1.36363636363636e+01 1.14446202808895e+00 8.67113082553106e-02 -1.09652277516758e-01 + 1.42424242424242e+01 1.15360925201834e+00 9.73732500785179e-02 -1.11627155262551e-01 + 1.48484848484848e+01 1.16355448827020e+00 1.07873104416001e-01 -1.14134059252607e-01 + 1.54545454545455e+01 1.16664773714290e+00 1.16951528881583e-01 -1.15612411766512e-01 + 1.60606060606061e+01 1.16661013255713e+00 1.25430946902501e-01 -1.16354027535650e-01 + 1.66666666666667e+01 1.15970818612903e+00 1.32782384020419e-01 -1.15612441871561e-01 + 1.72727272727273e+01 1.15449556243335e+00 1.41571380936791e-01 -1.15991269265136e-01 + 1.78787878787879e+01 1.15081418671560e+00 1.52117413613284e-01 -1.17753256291338e-01 + 1.84848484848485e+01 1.14958568526759e+00 1.64075993230739e-01 -1.21043159594879e-01 + 1.90909090909091e+01 1.14892881211198e+00 1.76252052672837e-01 -1.24587774021336e-01 + 1.96969696969697e+01 1.14714298858187e+00 1.87659451395701e-01 -1.27408729102206e-01 + 2.03030303030303e+01 1.14429050732898e+00 2.00561453897594e-01 -1.31242484394764e-01 + 2.09090909090909e+01 1.14266964540886e+00 2.14958144733618e-01 -1.36284282472763e-01 + 2.15151515151515e+01 1.14423506135131e+00 2.29354835569642e-01 -1.41385269444278e-01 + 2.21212121212121e+01 1.14307069922354e+00 2.43146307939168e-01 -1.46827329115247e-01 + 2.27272727272727e+01 1.13437676569340e+00 2.54517529167918e-01 -1.53633328645347e-01 + 2.33333333333333e+01 1.12568283216327e+00 2.65888750396669e-01 -1.60489831976375e-01 + 2.39393939393939e+01 1.11698889863313e+00 2.77259971625421e-01 -1.67539646177715e-01 + 2.45454545454545e+01 1.10899853924541e+00 2.88824171816938e-01 -1.73613983027854e-01 + 2.51515151515151e+01 1.10108635308077e+00 3.00409813654186e-01 -1.79569604350001e-01 + 2.57575757575758e+01 1.09317416691613e+00 3.11995455491433e-01 -1.85513172087669e-01 + 2.63636363636364e+01 1.08612496192253e+00 3.23969184308288e-01 -1.90961864811472e-01 + 2.69696969696970e+01 1.07965116711405e+00 3.36201677983836e-01 -1.96080224256372e-01 + 2.75757575757576e+01 1.07317737230558e+00 3.48434171659383e-01 -2.01190987495797e-01 + 2.81818181818182e+01 1.06698932003423e+00 3.60842423936148e-01 -2.06125820524907e-01 + 2.87878787878788e+01 1.06146794315678e+00 3.73660744436817e-01 -2.10662136737585e-01 + 2.93939393939394e+01 1.05594656627932e+00 3.86479064937486e-01 -2.15193450579188e-01 + 3.00000000000000e+01 1.05042518940186e+00 3.99297385438155e-01 -2.19719719772206e-01 + 3.30000000000000e+01 1.02644827609649e+00 4.66093046844495e-01 -2.39615606337711e-01 + 3.60000000000000e+01 1.00366641718899e+00 5.35679831809432e-01 -2.57787676201759e-01 + 3.90000000000000e+01 9.80023910642716e-01 6.07897658893372e-01 -2.74564735422046e-01 + 4.20000000000000e+01 9.53157091193240e-01 6.81725170790389e-01 -2.90390686664731e-01 + 4.50000000000000e+01 9.25099031707945e-01 7.55950278420295e-01 -3.05940905817259e-01 + 4.80000000000000e+01 8.90213156909925e-01 8.30040803802850e-01 -3.20687232891725e-01 + 5.10000000000000e+01 8.51286270268613e-01 9.02551341017882e-01 -3.35111108629908e-01 + 5.40000000000000e+01 8.04277100153241e-01 9.71901800324015e-01 -3.48903550668194e-01 + 5.70000000000000e+01 7.57267880913182e-01 1.04125168451056e+00 -3.62689866471288e-01 + 6.00000000000000e+01 7.10258637110966e-01 1.11060128113950e+00 -3.76470193714150e-01 + 6.30000000000000e+01 6.47769674730578e-01 1.16661579395854e+00 -3.88852281816777e-01 + 6.60000000000000e+01 5.85280557002702e-01 1.22263019247474e+00 -4.01231358690575e-01 + 6.90000000000000e+01 5.22791393951418e-01 1.27864459099094e+00 -4.13607260555449e-01 + 7.20000000000000e+01 4.52986794514127e-01 1.32114686428136e+00 -4.24708378476078e-01 + 7.50000000000000e+01 3.79524626640559e-01 1.35689335157008e+00 -4.35171875987646e-01 + 7.80000000000000e+01 3.06061084931655e-01 1.39264024848507e+00 -4.45633420993565e-01 + 8.10000000000000e+01 2.31376934566227e-01 1.42013017668539e+00 -4.55226551749704e-01 + 8.40000000000000e+01 1.54251651146622e-01 1.43110673741406e+00 -4.63084866775445e-01 + 8.70000000000000e+01 7.71257414576533e-02 1.44208338199759e+00 -4.70942168414430e-01 + 9.00000000000000e+01 -3.36956721141558e-07 1.45305993149174e+00 -4.78798611378502e-01 + 9.30000000000000e+01 -5.39883669172201e-02 1.44208337076307e+00 -4.83401960300538e-01 + 9.60000000000000e+01 -1.07976425758202e-01 1.43110676810732e+00 -4.87843492281115e-01 + 9.90000000000000e+01 -1.61964542361192e-01 1.42013008159586e+00 -4.92246671349029e-01 + 1.02000000000000e+02 -2.14243214939976e-01 1.39264007535569e+00 -4.93334961576679e-01 + 1.05000000000000e+02 -2.65667184017510e-01 1.35689358806697e+00 -4.92747792758473e-01 + 1.08000000000000e+02 -3.17091142370324e-01 1.32114669115373e+00 -4.92489218692733e-01 + 1.11000000000000e+02 -3.65954392283428e-01 1.27864410574316e+00 -4.91167327902475e-01 + 1.14000000000000e+02 -4.09696303308866e-01 1.22263034910072e+00 -4.87302639052758e-01 + 1.17000000000000e+02 -4.53438556744641e-01 1.16661616454686e+00 -4.83437520681149e-01 + 1.20000000000000e+02 -4.97180960199916e-01 1.11060173995280e+00 -4.79572183996746e-01 + 1.23000000000000e+02 -5.30087151245601e-01 1.04125214332386e+00 -4.73893974859065e-01 + 1.26000000000000e+02 -5.62993449444218e-01 9.71902259143020e-01 -4.68215548654545e-01 + 1.29000000000000e+02 -5.95899961956708e-01 9.02551799836887e-01 -4.62491545543420e-01 + 1.32000000000000e+02 -6.21555858594649e-01 8.29996331514373e-01 -4.57600132450428e-01 + 1.35000000000000e+02 -6.43586455890160e-01 7.55838362486724e-01 -4.53140066017817e-01 + 1.38000000000000e+02 -6.65616813110053e-01 6.81680698854136e-01 -4.48679982709285e-01 + 1.41000000000000e+02 -6.85803058067216e-01 6.08947766606052e-01 -4.46525550737110e-01 + 1.44000000000000e+02 -7.02301063534926e-01 5.39064308687913e-01 -4.48982440146784e-01 + 1.47000000000000e+02 -7.18798588287585e-01 4.69181021715765e-01 -4.51439319035616e-01 + 1.50000000000000e+02 -7.35295872691298e-01 3.99297820213560e-01 -4.53896192664215e-01 + 1.53000000000000e+02 -7.28330506319376e-01 3.46647734139971e-01 -4.68325381164791e-01 + 1.56000000000000e+02 -7.17850798388541e-01 2.93997685207009e-01 -4.82051328896962e-01 + 1.59000000000000e+02 -7.06863743588803e-01 2.41347630242394e-01 -4.98256732246163e-01 + 1.62000000000000e+02 -6.34811170157550e-01 2.01242252961188e-01 -5.03086039127970e-01 + 1.65000000000000e+02 -5.31470448900505e-01 1.67409320614642e-01 -5.01928907588892e-01 + 1.68000000000000e+02 -4.28130311834334e-01 1.33576175967328e-01 -5.00771566637685e-01 + 1.71000000000000e+02 -3.23313093840734e-01 9.99186368162403e-02 -4.50000513056908e-01 + 1.74000000000000e+02 -2.15541645031820e-01 6.66123168560943e-02 -2.99999717902353e-01 + 1.77000000000000e+02 -1.07279423135448e-01 5.50240468507236e-02 -1.40189247446868e-01 + 1.80000000000000e+02 0.00000000000000e+00 5.43028798119170e-02 2.26615932282131e-02 diff --git a/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_22.dat b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_22.dat new file mode 100644 index 00000000..c2189748 --- /dev/null +++ b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_22.dat @@ -0,0 +1,254 @@ +! ------------ AirfoilInfo v1.01.x Input File ---------------------------------- +! AeroElasticSE FAST driver +! line +! line +! ------------------------------------------------------------------------------ +DEFAULT InterpOrd ! Interpolation order to use for quasi-steady table lookup {1=linear; 3=cubic spline; "default"} [default=3] +1 NonDimArea ! The non-dimensional area of the airfoil (area/chord^2) (set to 1.0 if unsure or unneeded) +@"NREL-2p8-127_AF22_Coords.txt" NumCoords ! The number of coordinates in the airfoil shape file. Set to zero if coordinates not included. +AF22_BL.txt BL_file ! The file name including the boundary layer characteristics of the profile. Ignored if the aeroacoustic module is not called. +1 NumTabs ! Number of airfoil tables in this file. Each table must have lines for Re and Ctrl. +! ------------------------------------------------------------------------------ +! data for table 1 +! ------------------------------------------------------------------------------ +6.000000 Re ! Reynolds number in millions +0 Ctrl ! Control setting (must be 0 for current AirfoilInfo) +True InclUAdata ! Is unsteady aerodynamics data included in this table? If TRUE, then include 30 UA coefficients below this line +!........................................ +-3.566308 alpha0 ! 0-lift angle of attack, depends on airfoil. +9.412539 alpha1 ! Angle of attack at f=0.7, (approximately the stall angle) for AOA>alpha0. (deg) +-11.254245 alpha2 ! Angle of attack at f=0.7, (approximately the stall angle) for AOA1] +0.000000 S2 ! Constant in the f curve best-fit for AOA> alpha1; by definition it depends on the airfoil. [ignored if UAMod<>1] +0.000000 S3 ! Constant in the f curve best-fit for alpha2<=AOA< alpha0; by definition it depends on the airfoil. [ignored if UAMod<>1] +0.000000 S4 ! Constant in the f curve best-fit for AOA< alpha2; by definition it depends on the airfoil. [ignored if UAMod<>1] +1.372317 Cn1 ! Critical value of C0n at leading edge separation. It should be extracted from airfoil data at a given Mach and Reynolds number. It can be calculated from the static value of Cn at either the break in the pitching moment or the loss of chord force at the onset of stall. It is close to the condition of maximum lift of the airfoil at low Mach numbers. +-0.851187 Cn2 ! As Cn1 for negative AOAs. +Default St_sh ! Strouhal's shedding frequency constant. [default = 0.19] +0.007099 Cd0 ! 2D drag coefficient value at 0-lift. +-0.113167 Cm0 ! 2D pitching moment coefficient about 1/4-chord location, at 0-lift, positive if nose up. [If the aerodynamics coefficients table does not include a column for Cm, this needs to be set to 0.0] +0.000000 k0 ! Constant in the \hat(x)_cp curve best-fit; = (\hat(x)_AC-0.25). [ignored if UAMod<>1] +0.000000 k1 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k2 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k3 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k1_hat ! Constant in the expression of Cc due to leading edge vortex effects. [ignored if UAMod<>1] +Default x_cp_bar ! Constant in the expression of \hat(x)_cp^v. [ignored if UAMod<>1, default = 0.2] +Default UACutout ! Angle of attack above which unsteady aerodynamics are disabled (deg). [Specifying the string "Default" sets UACutout to 45 degrees] +Default filtCutOff ! Cut-off frequency (-3 dB corner frequency) for low-pass filtering the AoA input to UA, as well as the 1st and 2nd derivatives (Hz) [default = 20] +!........................................ +! Table of aerodynamics coefficients +200 NumAlf ! Number of data lines in the following table +! Alpha Cl Cd Cm +! (deg) (-) (-) (-) +-1.80000000000000e+02 0.00000000000000e+00 5.07556742159798e-02 6.34072788301272e-02 +-1.77000000000000e+02 1.21373168046836e-01 5.07556742159798e-02 1.44989137166855e-01 +-1.74000000000000e+02 2.43858124753276e-01 6.09067517869507e-02 2.39999774321882e-01 +-1.71000000000000e+02 3.65787584521499e-01 9.13603177509608e-02 3.60000410445527e-01 +-1.68000000000000e+02 4.75515174866590e-01 1.23180858733612e-01 3.13292467675056e-01 +-1.65000000000000e+02 5.79141972913914e-01 1.55684871270972e-01 1.83232181192322e-01 +-1.62000000000000e+02 6.82769984990416e-01 1.88188793392151e-01 5.31699414433441e-02 +-1.59000000000000e+02 7.49929094529181e-01 2.28115056904519e-01 -3.37679356965932e-02 +-1.56000000000000e+02 7.45401898546715e-01 2.82885752112716e-01 -3.57982585441417e-02 +-1.53000000000000e+02 7.40045790863415e-01 3.37656465738121e-01 -3.75882513662505e-02 +-1.50000000000000e+02 7.32596618631745e-01 3.92427224341668e-01 -3.50272634037363e-02 +-1.47000000000000e+02 7.16416220992227e-01 4.62548307459531e-01 -1.89393396903141e-02 +-1.44000000000000e+02 7.00235624959091e-01 5.32669512974126e-01 -2.85117921368804e-03 +-1.41000000000000e+02 6.84054632124555e-01 6.02790963290924e-01 1.27311247792732e-02 +-1.38000000000000e+02 6.64108508380734e-01 6.75798748422820e-01 2.82558445968883e-02 +-1.35000000000000e+02 6.42279826820249e-01 7.50249695107020e-01 4.38571814291932e-02 +-1.32000000000000e+02 6.20450921675678e-01 8.24701058603098e-01 5.94656947948800e-02 +-1.29000000000000e+02 5.94974616376641e-01 8.97565459936934e-01 7.52120953201059e-02 +-1.26000000000000e+02 5.62203493473854e-01 9.67255929411789e-01 9.12244354642672e-02 +-1.23000000000000e+02 5.29432511812518e-01 1.03694573967196e+00 1.07239613164941e-01 +-1.20000000000000e+02 4.96661600769268e-01 1.10663522033711e+00 1.23257579300455e-01 +-1.17000000000000e+02 4.53007747800845e-01 1.16302575005567e+00 1.38481557370608e-01 +-1.14000000000000e+02 4.09354049149219e-01 1.21941603836822e+00 1.53706780948661e-01 +-1.11000000000000e+02 3.65700701685022e-01 1.27580589589615e+00 1.68932988096397e-01 +-1.08000000000000e+02 3.16900772369631e-01 1.31870071696580e+00 1.82560097851392e-01 +-1.05000000000000e+02 2.65527512940554e-01 1.35484791704772e+00 1.95399125304991e-01 +-1.02000000000000e+02 2.14154242205798e-01 1.39099470291805e+00 2.08238303928547e-01 +-9.90000000000000e+01 1.61914865702625e-01 1.41888942602526e+00 2.19722912577175e-01 +-9.60000000000000e+01 1.07943240147024e-01 1.43027966616597e+00 2.28497123718656e-01 +-9.30000000000000e+01 5.39717537188113e-02 1.44166981929167e+00 2.37271383106753e-01 +-9.00000000000000e+01 3.36853033223878e-07 1.45305992891065e+00 2.46045939350736e-01 +-8.70000000000000e+01 -5.39716984790431e-02 1.44166983094945e+00 2.50473302115734e-01 +-8.40000000000000e+01 -1.07943391063713e-01 1.43027963431632e+00 2.54928173585132e-01 +-8.10000000000000e+01 -1.61914398153851e-01 1.41888952469734e+00 2.59409826519098e-01 +-7.80000000000000e+01 -2.14153993391912e-01 1.39099487798618e+00 2.60637456906859e-01 +-7.50000000000000e+01 -2.65527852822723e-01 1.35484767790248e+00 2.60250041617006e-01 +-7.20000000000000e+01 -3.16900523561175e-01 1.31870089203215e+00 2.59886362685276e-01 +-6.90000000000000e+01 -3.65700323515595e-01 1.27580638440210e+00 2.58282671903770e-01 +-6.60000000000000e+01 -4.09354171212959e-01 1.21941588069058e+00 2.54173349716066e-01 +-6.30000000000000e+01 -4.53008036612590e-01 1.16302537697905e+00 2.50084873782204e-01 +-6.00000000000000e+01 -4.96661817579899e-01 1.10663475927516e+00 2.46016982651216e-01 +-5.70000000000000e+01 -5.29432728623149e-01 1.03694527861001e+00 2.40180820587871e-01 +-5.40000000000000e+01 -5.62203710285886e-01 9.67255468343294e-01 2.34364534434322e-01 +-5.10000000000000e+01 -5.94974833188673e-01 8.97564998868439e-01 2.28567701938433e-01 +-4.80000000000000e+01 -6.22057662441151e-01 8.24737086109294e-01 2.23106850479156e-01 +-4.50000000000000e+01 -6.46296436287407e-01 7.50340502131161e-01 2.17827122416360e-01 +-4.20000000000000e+01 -6.65715236572083e-01 6.75834775642757e-01 2.14270938724142e-01 +-3.90000000000000e+01 -6.84287831284676e-01 6.01733100265088e-01 2.11324975236861e-01 +-3.60000000000000e+01 -7.00563864724568e-01 5.29261493580405e-01 2.10489244413362e-01 +-3.30000000000000e+01 -7.16187489056336e-01 4.59440503480610e-01 2.12957840755690e-01 +-3.00000000000000e+01 -7.32596736476158e-01 3.92426788149384e-01 2.19119564417483e-01 +-2.93939393939394e+01 -7.36374389172812e-01 3.79567808225057e-01 2.21363823380573e-01 +-2.87878787878788e+01 -7.40152041869467e-01 3.66708828300729e-01 2.23608082343664e-01 +-2.81818181818182e+01 -7.43929694566121e-01 3.53849848376402e-01 2.25852341306755e-01 +-2.75757575757576e+01 -7.48165648451628e-01 3.41402728220191e-01 2.28809630520161e-01 +-2.69696969696970e+01 -7.52598033982392e-01 3.29132134535727e-01 2.32072530342035e-01 +-2.63636363636364e+01 -7.57030419513156e-01 3.16861540851264e-01 2.35335430163909e-01 +-2.57575757575758e+01 -7.61859695409693e-01 3.04850755726473e-01 2.39132514207883e-01 +-2.51515151515151e+01 -7.67284214354563e-01 2.93229622889516e-01 2.43730750086607e-01 +-2.45454545454545e+01 -7.72708733299433e-01 2.81608490052560e-01 2.48328985965330e-01 +-2.39393939393939e+01 -7.78397371018865e-01 2.70052672159968e-01 2.52203196387113e-01 +-2.33333333333333e+01 -7.86463128844015e-01 2.59084701411948e-01 2.49561037521642e-01 +-2.27272727272727e+01 -7.94528886669166e-01 2.48116730663927e-01 2.45890720916381e-01 +-2.21212121212121e+01 -8.02594644494317e-01 2.37148759915907e-01 2.43586283408853e-01 +-2.15151515151515e+01 -8.10907795657620e-01 2.26212863295167e-01 2.36219129070528e-01 +-2.09090909090909e+01 -8.16516141250483e-01 2.15284987269397e-01 2.26807332042050e-01 +-2.03030303030303e+01 -8.22548837928087e-01 2.04357111243626e-01 2.17395535013573e-01 +-1.96969696969697e+01 -8.30002084619816e-01 1.93526156053271e-01 2.08338072839810e-01 +-1.90909090909091e+01 -8.38276075640665e-01 1.82792116215481e-01 1.99634925475900e-01 +-1.84848484848485e+01 -8.41525789425216e-01 1.71763238665119e-01 1.87206613897995e-01 +-1.78787878787879e+01 -8.43830658066113e-01 1.60232706599968e-01 1.74288223907780e-01 +-1.72727272727273e+01 -8.45969420405482e-01 1.49310415673877e-01 1.60399611180235e-01 +-1.66666666666667e+01 -8.44462724081164e-01 1.38631475065992e-01 1.43746150937375e-01 +-1.60606060606061e+01 -8.40100015006392e-01 1.28157201231612e-01 1.24821818047702e-01 +-1.54545454545455e+01 -8.37817603025782e-01 1.18032218056081e-01 1.04802159358542e-01 +-1.48484848484848e+01 -8.37183712471984e-01 1.08103958885772e-01 8.41678532118364e-02 +-1.42424242424242e+01 -8.40890120256044e-01 9.84661435612030e-02 6.27214130589554e-02 +-1.36363636363636e+01 -8.46817406852861e-01 8.88896748069138e-02 4.26434421043484e-02 +-1.30303030303030e+01 -8.55315988459211e-01 7.93654273525520e-02 2.26015400198430e-02 +-1.24242424242424e+01 -8.47245180473497e-01 6.91820678235402e-02 8.67599048926910e-03 +-1.18181818181818e+01 -8.35432683112564e-01 5.98195535661050e-02 -3.47219937244458e-03 +-1.12121212121212e+01 -8.15393459831635e-01 4.94939958051427e-02 -1.22220313441137e-02 +-1.06060606060606e+01 -7.90094798205374e-01 4.03354037886031e-02 -2.24327341739879e-02 +-1.00000000000000e+01 -7.61704104709643e-01 3.20697982337656e-02 -3.34296643848299e-02 +-9.39393939393939e+00 -7.28357715972300e-01 2.53011224655095e-02 -4.42541982301917e-02 +-8.78787878787879e+00 -6.84142454187570e-01 1.91495037741205e-02 -5.66943316671589e-02 +-8.18181818181818e+00 -6.17979429458198e-01 1.37667951514698e-02 -7.13770363239650e-02 +-7.57575757575758e+00 -5.38103979710377e-01 1.08227708003567e-02 -8.21189162256499e-02 +-6.96969696969697e+00 -4.51631211888217e-01 9.39164055487013e-03 -9.05502975056676e-02 +-6.36363636363636e+00 -3.69904831929908e-01 8.28680451711851e-03 -9.65427316699646e-02 +-5.75757575757576e+00 -2.88476726756192e-01 7.76135087915599e-03 -1.01757959286034e-01 +-5.15151515151515e+00 -2.07260475931238e-01 7.47535721667608e-03 -1.06060127684791e-01 +-4.54545454545454e+00 -1.27279930853378e-01 7.28615916745306e-03 -1.09371226057769e-01 +-3.93939393939394e+00 -4.80058499406509e-02 7.17092890724474e-03 -1.11865483581015e-01 +-3.33333333333333e+00 2.99773467049867e-02 7.05390574872594e-03 -1.13980246411455e-01 +-2.72727272727273e+00 1.07925041765181e-01 6.93627094208034e-03 -1.15908672907983e-01 +-2.12121212121212e+00 1.85286698580458e-01 6.86333451961630e-03 -1.17939670229949e-01 +-1.51515151515152e+00 2.61818679801486e-01 6.83016135377631e-03 -1.20251324856380e-01 +-9.09090909090912e-01 3.37437336745196e-01 6.82527631097856e-03 -1.22427420055716e-01 +-3.03030303030302e-01 4.11339964275432e-01 6.88875118426107e-03 -1.24393823575531e-01 + 3.03030303030302e-01 4.85425194785723e-01 6.93305859100922e-03 -1.26271092424251e-01 + 9.09090909090912e-01 5.59688748393245e-01 6.92641095940415e-03 -1.27930360286602e-01 + 1.51515151515152e+00 6.33889422008781e-01 6.97145778583218e-03 -1.29509636273062e-01 + 2.12121212121212e+00 7.08007295477312e-01 7.08503567582370e-03 -1.30948866987131e-01 + 2.72727272727273e+00 7.81743944095907e-01 7.22808542364998e-03 -1.32280278589569e-01 + 3.33333333333333e+00 8.54768718499635e-01 7.36394317569994e-03 -1.33476357648126e-01 + 3.93939393939394e+00 9.27343605653137e-01 7.50800878324420e-03 -1.34580752920963e-01 + 4.54545454545455e+00 9.99337144270299e-01 7.68025178023798e-03 -1.35437140997352e-01 + 5.15151515151515e+00 1.07077533588784e+00 7.88250770331053e-03 -1.36171448237875e-01 + 5.75757575757576e+00 1.14067573993544e+00 8.18560595986809e-03 -1.36563716920552e-01 + 6.36363636363637e+00 1.20738594989603e+00 8.61082274432950e-03 -1.36450536130407e-01 + 6.96969696969697e+00 1.27030534457503e+00 9.26154940433015e-03 -1.35865188748459e-01 + 7.57575757575757e+00 1.31967720204744e+00 1.06711516164033e-02 -1.33196036139163e-01 + 8.18181818181818e+00 1.36117901696138e+00 1.20457201580521e-02 -1.29734082098160e-01 + 8.78787878787879e+00 1.38645164475349e+00 1.40141299367242e-02 -1.24969368476653e-01 + 9.39393939393939e+00 1.38364788675440e+00 2.10604272519143e-02 -1.22681471706985e-01 + 1.00000000000000e+01 1.36632615029107e+00 3.08301921000425e-02 -1.22594505197778e-01 + 1.06060606060606e+01 1.30793900793488e+00 3.95953728731437e-02 -1.21768157631026e-01 + 1.12121212121212e+01 1.26354919483254e+00 4.68596237969062e-02 -1.20824315241689e-01 + 1.18181818181818e+01 1.24622078267823e+00 5.34209201004403e-02 -1.17862121865541e-01 + 1.24242424242424e+01 1.23316572300737e+00 6.31476016531568e-02 -1.14380907459069e-01 + 1.30303030303030e+01 1.22283883104523e+00 7.34240891191203e-02 -1.12038188702533e-01 + 1.36363636363636e+01 1.21302095714098e+00 8.54972535339130e-02 -1.13922354181064e-01 + 1.42424242424242e+01 1.20995851746224e+00 9.67529857851515e-02 -1.15899802821485e-01 + 1.48484848484848e+01 1.20957781975123e+00 1.06783261680667e-01 -1.18176308348192e-01 + 1.54545454545455e+01 1.20628232400092e+00 1.15676133910572e-01 -1.19630275206793e-01 + 1.60606060606061e+01 1.20129649682940e+00 1.24088573760305e-01 -1.20475625038284e-01 + 1.66666666666667e+01 1.19049649901642e+00 1.31588359571251e-01 -1.20087718033958e-01 + 1.72727272727273e+01 1.17964142895866e+00 1.40230863472286e-01 -1.20588628022729e-01 + 1.78787878787879e+01 1.16825933056011e+00 1.50270037306760e-01 -1.22187730969383e-01 + 1.84848484848485e+01 1.16279372315999e+00 1.61375170677979e-01 -1.24959559895277e-01 + 1.90909090909091e+01 1.15872202145603e+00 1.72688440191291e-01 -1.28082765397647e-01 + 1.96969696969697e+01 1.15339844517572e+00 1.83671166909384e-01 -1.31533890864235e-01 + 2.03030303030303e+01 1.14667353640152e+00 1.95931329664752e-01 -1.35939723395958e-01 + 2.09090909090909e+01 1.14214263161388e+00 2.09469000726538e-01 -1.41468507832042e-01 + 2.15151515151515e+01 1.14163199846552e+00 2.23006671788323e-01 -1.47048295239323e-01 + 2.21212121212121e+01 1.13801617834194e+00 2.36098095781483e-01 -1.52838501078495e-01 + 2.27272727272727e+01 1.12925112767887e+00 2.47404990655498e-01 -1.59470164140170e-01 + 2.33333333333333e+01 1.12048607701580e+00 2.58711885529513e-01 -1.66145346243189e-01 + 2.39393939393939e+01 1.11172102635272e+00 2.70018780403529e-01 -1.72987104001955e-01 + 2.45454545454545e+01 1.10386992919784e+00 2.81608490052560e-01 -1.78880886757862e-01 + 2.51515151515151e+01 1.09612038024829e+00 2.93229622889516e-01 -1.84660438598366e-01 + 2.57575757575758e+01 1.08837083129873e+00 3.04850755726473e-01 -1.90429603885151e-01 + 2.63636363636364e+01 1.08147195893053e+00 3.16861540851264e-01 -1.95726297856203e-01 + 2.69696969696970e+01 1.07514029241291e+00 3.29132134535727e-01 -2.00707647194441e-01 + 2.75757575757576e+01 1.06880862589528e+00 3.41402728220191e-01 -2.05682450895045e-01 + 2.81818181818182e+01 1.06275754212664e+00 3.53849848376402e-01 -2.10489790164498e-01 + 2.87878787878788e+01 1.05736109527898e+00 3.66708828300730e-01 -2.14916711454757e-01 + 2.93939393939394e+01 1.05196464843131e+00 3.79567808225057e-01 -2.19339322210173e-01 + 3.00000000000000e+01 1.04656820158365e+00 3.92426788149384e-01 -2.23757586000285e-01 + 3.30000000000000e+01 1.02312514415356e+00 4.59440503480610e-01 -2.43238943532748e-01 + 3.60000000000000e+01 1.00080435367758e+00 5.29261493580405e-01 -2.61084484698553e-01 + 3.90000000000000e+01 9.77554126454961e-01 6.01733100265088e-01 -2.77608856801414e-01 + 4.20000000000000e+01 9.51021881685284e-01 6.75834775642758e-01 -2.93234977723852e-01 + 4.50000000000000e+01 9.23281318212600e-01 7.50340502131161e-01 -3.08601809213403e-01 + 4.80000000000000e+01 8.88654194131487e-01 8.24737086109295e-01 -3.23208356054975e-01 + 5.10000000000000e+01 8.49964254625460e-01 8.97564998868439e-01 -3.37506814180089e-01 + 5.40000000000000e+01 8.03148423080423e-01 9.67255468343294e-01 -3.51200699120049e-01 + 5.70000000000000e+01 7.56332531480030e-01 1.03694527861001e+00 -3.64889313118346e-01 + 6.00000000000000e+01 7.09516609852189e-01 1.10663475927516e+00 -3.78572770796720e-01 + 6.30000000000000e+01 6.47154294385920e-01 1.16302537697905e+00 -3.90891753454121e-01 + 6.60000000000000e+01 5.84791782254718e-01 1.21941588069058e+00 -4.03208150894803e-01 + 6.90000000000000e+01 5.22429143308335e-01 1.27580638440210e+00 -4.15521834280170e-01 + 7.20000000000000e+01 4.52714954299060e-01 1.31870089203215e+00 -4.26575704118960e-01 + 7.50000000000000e+01 3.79325140754361e-01 1.35484767790248e+00 -4.36999473643461e-01 + 7.80000000000000e+01 3.05934076441010e-01 1.39099487798618e+00 -4.47421477951532e-01 + 8.10000000000000e+01 2.31306131004083e-01 1.41888952469734e+00 -4.56980574222415e-01 + 8.40000000000000e+01 1.54204508701838e-01 1.43027963431632e+00 -4.64815596729305e-01 + 8.70000000000000e+01 7.71021882732242e-02 1.44166983094945e+00 -4.72649698806517e-01 + 9.00000000000000e+01 -3.36853033455059e-07 1.45305992891065e+00 -4.80483033427282e-01 + 9.30000000000000e+01 -5.39717537188113e-02 1.44166981929167e+00 -4.84882001487256e-01 + 9.60000000000000e+01 -1.07943240147024e-01 1.43027966616597e+00 -4.88977291312720e-01 + 9.90000000000000e+01 -1.61914865702625e-01 1.41888942602526e+00 -4.93035304646623e-01 + 1.02000000000000e+02 -2.14154242205798e-01 1.39099470291805e+00 -4.93786567296916e-01 + 1.05000000000000e+02 -2.65527512940555e-01 1.35484791704772e+00 -4.92868936308638e-01 + 1.08000000000000e+02 -3.16900772369631e-01 1.31870071696580e+00 -4.92410220071252e-01 + 1.11000000000000e+02 -3.65700701685022e-01 1.27580589589615e+00 -4.90965426724924e-01 + 1.14000000000000e+02 -4.09354049149220e-01 1.21941603836822e+00 -4.86982932906717e-01 + 1.17000000000000e+02 -4.53007747800845e-01 1.16302575005567e+00 -4.83000008666658e-01 + 1.20000000000000e+02 -4.96661600769268e-01 1.10663522033711e+00 -4.79016865676293e-01 + 1.23000000000000e+02 -5.29432511812518e-01 1.03694573967196e+00 -4.73227232421762e-01 + 1.26000000000000e+02 -5.62203493473854e-01 9.67255929411789e-01 -4.67437401740092e-01 + 1.29000000000000e+02 -5.94974616376641e-01 8.97565459936934e-01 -4.61550294565979e-01 + 1.32000000000000e+02 -6.20450921675679e-01 8.24701058603098e-01 -4.56453890288661e-01 + 1.35000000000000e+02 -6.42279826820249e-01 7.50249695107020e-01 -4.51785141239963e-01 + 1.38000000000000e+02 -6.64108508380734e-01 6.75798748422819e-01 -4.47116255471473e-01 + 1.41000000000000e+02 -6.84054632124555e-01 6.02790963290923e-01 -4.44720379804122e-01 + 1.44000000000000e+02 -7.00235624959091e-01 5.32669512974126e-01 -4.46870542783319e-01 + 1.47000000000000e+02 -7.16416220992227e-01 4.62548307459531e-01 -4.49020707038669e-01 + 1.50000000000000e+02 -7.32596618631745e-01 3.92427224341668e-01 -4.51170871932074e-01 + 1.53000000000000e+02 -7.33272841626932e-01 3.38604126000068e-01 -4.67244946323259e-01 + 1.56000000000000e+02 -7.30920747814166e-01 2.84781062373784e-01 -4.81810042653382e-01 + 1.59000000000000e+02 -7.28131423029985e-01 2.30957992223316e-01 -4.99843304573404e-01 + 1.62000000000000e+02 -6.59004284451097e-01 1.91223709907543e-01 -5.04964107373118e-01 + 1.65000000000000e+02 -5.56057205936165e-01 1.58533940661002e-01 -5.03102799944957e-01 + 1.68000000000000e+02 -4.53110707101343e-01 1.25843946014156e-01 -5.01241125772289e-01 + 1.71000000000000e+02 -3.46031678268841e-01 9.36455360526948e-02 -4.50000513056908e-01 + 1.74000000000000e+02 -2.30687396505613e-01 6.24303184126113e-02 -2.99999717902353e-01 + 1.77000000000000e+02 -1.14817786337317e-01 5.15140111366759e-02 -1.23779476102597e-01 + 1.80000000000000e+02 0.00000000000000e+00 5.07556742159798e-02 6.34072788301272e-02 diff --git a/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_23.dat b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_23.dat new file mode 100644 index 00000000..1d9534a4 --- /dev/null +++ b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_23.dat @@ -0,0 +1,254 @@ +! ------------ AirfoilInfo v1.01.x Input File ---------------------------------- +! AeroElasticSE FAST driver +! line +! line +! ------------------------------------------------------------------------------ +DEFAULT InterpOrd ! Interpolation order to use for quasi-steady table lookup {1=linear; 3=cubic spline; "default"} [default=3] +1 NonDimArea ! The non-dimensional area of the airfoil (area/chord^2) (set to 1.0 if unsure or unneeded) +@"NREL-2p8-127_AF23_Coords.txt" NumCoords ! The number of coordinates in the airfoil shape file. Set to zero if coordinates not included. +AF23_BL.txt BL_file ! The file name including the boundary layer characteristics of the profile. Ignored if the aeroacoustic module is not called. +1 NumTabs ! Number of airfoil tables in this file. Each table must have lines for Re and Ctrl. +! ------------------------------------------------------------------------------ +! data for table 1 +! ------------------------------------------------------------------------------ +6.000000 Re ! Reynolds number in millions +0 Ctrl ! Control setting (must be 0 for current AirfoilInfo) +True InclUAdata ! Is unsteady aerodynamics data included in this table? If TRUE, then include 30 UA coefficients below this line +!........................................ +-3.734961 alpha0 ! 0-lift angle of attack, depends on airfoil. +9.697795 alpha1 ! Angle of attack at f=0.7, (approximately the stall angle) for AOA>alpha0. (deg) +-10.684389 alpha2 ! Angle of attack at f=0.7, (approximately the stall angle) for AOA1] +0.000000 S2 ! Constant in the f curve best-fit for AOA> alpha1; by definition it depends on the airfoil. [ignored if UAMod<>1] +0.000000 S3 ! Constant in the f curve best-fit for alpha2<=AOA< alpha0; by definition it depends on the airfoil. [ignored if UAMod<>1] +0.000000 S4 ! Constant in the f curve best-fit for AOA< alpha2; by definition it depends on the airfoil. [ignored if UAMod<>1] +1.401232 Cn1 ! Critical value of C0n at leading edge separation. It should be extracted from airfoil data at a given Mach and Reynolds number. It can be calculated from the static value of Cn at either the break in the pitching moment or the loss of chord force at the onset of stall. It is close to the condition of maximum lift of the airfoil at low Mach numbers. +-0.842106 Cn2 ! As Cn1 for negative AOAs. +Default St_sh ! Strouhal's shedding frequency constant. [default = 0.19] +0.006818 Cd0 ! 2D drag coefficient value at 0-lift. +-0.113242 Cm0 ! 2D pitching moment coefficient about 1/4-chord location, at 0-lift, positive if nose up. [If the aerodynamics coefficients table does not include a column for Cm, this needs to be set to 0.0] +0.000000 k0 ! Constant in the \hat(x)_cp curve best-fit; = (\hat(x)_AC-0.25). [ignored if UAMod<>1] +0.000000 k1 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k2 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k3 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k1_hat ! Constant in the expression of Cc due to leading edge vortex effects. [ignored if UAMod<>1] +Default x_cp_bar ! Constant in the expression of \hat(x)_cp^v. [ignored if UAMod<>1, default = 0.2] +Default UACutout ! Angle of attack above which unsteady aerodynamics are disabled (deg). [Specifying the string "Default" sets UACutout to 45 degrees] +Default filtCutOff ! Cut-off frequency (-3 dB corner frequency) for low-pass filtering the AoA input to UA, as well as the 1st and 2nd derivatives (Hz) [default = 20] +!........................................ +! Table of aerodynamics coefficients +200 NumAlf ! Number of data lines in the following table +! Alpha Cl Cd Cm +! (deg) (-) (-) (-) +-1.80000000000000e+02 0.00000000000000e+00 4.63087218239101e-02 1.12294918356446e-01 +-1.77000000000000e+02 1.31407871834538e-01 4.63087218239101e-02 1.64677969845384e-01 +-1.74000000000000e+02 2.64019510355404e-01 5.55704139343663e-02 2.39999774321882e-01 +-1.71000000000000e+02 3.96029843973720e-01 8.33557943190768e-02 3.60000410445527e-01 +-1.68000000000000e+02 5.06430868461261e-01 1.13562290370517e-01 3.08610785372619e-01 +-1.65000000000000e+02 6.06027490595898e-01 1.44979315997335e-01 1.71528030078362e-01 +-1.62000000000000e+02 7.05625285482958e-01 1.76396375603631e-01 3.44433778978911e-02 +-1.59000000000000e+02 7.67703923736826e-01 2.15960936619897e-01 -5.47934885866511e-02 +-1.56000000000000e+02 7.55397723550236e-01 2.71820224837142e-01 -4.90352678454869e-02 +-1.53000000000000e+02 7.42659054409641e-01 3.27679539787795e-01 -4.31517727134676e-02 +-1.50000000000000e+02 7.28828504793094e-01 3.83538902055256e-01 -3.44596878302946e-02 +-1.47000000000000e+02 7.13090480114408e-01 4.53967729130364e-01 -1.86189086211220e-02 +-1.44000000000000e+02 6.97352307618548e-01 5.24396727029221e-01 -2.77793532551869e-03 +-1.41000000000000e+02 6.81613839477788e-01 5.94826066587771e-01 1.25927965767874e-02 +-1.38000000000000e+02 6.62002920890116e-01 6.68189421819665e-01 2.79774029417006e-02 +-1.35000000000000e+02 6.40455784934676e-01 7.43019778936259e-01 4.34673885521046e-02 +-1.32000000000000e+02 6.18908433527060e-01 8.17850698969113e-01 5.89612242447798e-02 +-1.29000000000000e+02 5.93682830023854e-01 8.91114749342423e-01 7.46038609930899e-02 +-1.26000000000000e+02 5.61100704888174e-01 9.61245052954708e-01 9.05389699091404e-02 +-1.23000000000000e+02 5.28518625044670e-01 1.03137459621631e+00 1.06475722031366e-01 +-1.20000000000000e+02 4.95936567846408e-01 1.10150375931678e+00 1.22414010239834e-01 +-1.17000000000000e+02 4.52406347782145e-01 1.15838084536770e+00 1.37579477845402e-01 +-1.14000000000000e+02 4.08876283070132e-01 1.21525768824574e+00 1.52745471209185e-01 +-1.11000000000000e+02 3.65346571871469e-01 1.27213409662221e+00 1.67911731135092e-01 +-1.08000000000000e+02 3.16635035430310e-01 1.31553636143885e+00 1.81492961378994e-01 +-1.05000000000000e+02 2.65332546911451e-01 1.35220145187604e+00 1.94295080678717e-01 +-1.02000000000000e+02 2.14030046275947e-01 1.38886612216712e+00 2.07096904272415e-01 +-9.90000000000000e+01 1.61845527217881e-01 1.41728443461560e+00 2.18547504691698e-01 +-9.60000000000000e+01 1.07896933109836e-01 1.42920967418575e+00 2.27294974831625e-01 +-9.30000000000000e+01 5.39485757284989e-02 1.44113482265378e+00 2.36042235203500e-01 +-9.00000000000000e+01 3.36708372806976e-07 1.45305992557158e+00 2.44789532965389e-01 +-8.70000000000000e+01 -5.39485205124533e-02 1.44113483485913e+00 2.48978944307922e-01 +-8.40000000000000e+01 -1.07897083962124e-01 1.42920964084012e+00 2.53182684189232e-01 +-8.10000000000000e+01 -1.61845059868626e-01 1.41728453792232e+00 2.57400380355460e-01 +-7.80000000000000e+01 -2.14029797804819e-01 1.38886629974350e+00 2.58354097127670e-01 +-7.50000000000000e+01 -2.65332886325409e-01 1.35220120930450e+00 2.57682039063764e-01 +-7.20000000000000e+01 -3.16634786964608e-01 1.31553653901342e+00 2.57022063927401e-01 +-6.90000000000000e+01 -3.65346194773105e-01 1.27213458934316e+00 2.55116538347366e-01 +-6.60000000000000e+01 -4.08876404788159e-01 1.21525752920760e+00 2.50706504502961e-01 +-6.30000000000000e+01 -4.52406635775942e-01 1.15838046907205e+00 2.46307312278457e-01 +-6.00000000000000e+01 -4.95936783407592e-01 1.10150329534591e+00 2.41918834523807e-01 +-5.70000000000000e+01 -5.28518840605854e-01 1.03137413224544e+00 2.35766279929407e-01 +-5.40000000000000e+01 -5.61100920449807e-01 9.61244588976293e-01 2.29623980263181e-01 +-5.10000000000000e+01 -5.93683045585487e-01 8.91114285364008e-01 2.23491601843586e-01 +-4.80000000000000e+01 -6.20534325092436e-01 8.17875803160575e-01 2.17675688732665e-01 +-4.50000000000000e+01 -6.44520273887822e-01 7.43083281614397e-01 2.12024856819171e-01 +-4.20000000000000e+01 -6.63628799731457e-01 6.68214525810191e-01 2.08040444001537e-01 +-3.90000000000000e+01 -6.81874399513891e-01 5.93758161928647e-01 2.04674544610408e-01 +-3.60000000000000e+01 -6.97766871415788e-01 5.20958260992169e-01 2.03489583532797e-01 +-3.30000000000000e+01 -7.12939161093519e-01 4.50834279245390e-01 2.05538204979316e-01 +-3.00000000000000e+01 -7.28828619013840e-01 3.83538464029985e-01 2.11194373081700e-01 +-2.93939393939394e+01 -7.32484050886326e-01 3.70626883995265e-01 2.13311958401767e-01 +-2.87878787878788e+01 -7.36139482758811e-01 3.57715303960545e-01 2.15429543721834e-01 +-2.81818181818182e+01 -7.39794914631297e-01 3.44803723925826e-01 2.17547129041902e-01 +-2.75757575757576e+01 -7.43897116047021e-01 3.32306320069088e-01 2.20359205164668e-01 +-2.69696969696970e+01 -7.48190806550193e-01 3.19986435516351e-01 2.23468945736725e-01 +-2.63636363636364e+01 -7.52484497053364e-01 3.07666550963613e-01 2.26578686308783e-01 +-2.57575757575758e+01 -7.57166921645990e-01 2.95607827569598e-01 2.30208187650959e-01 +-2.51515151515151e+01 -7.62432356773396e-01 2.83940785046750e-01 2.34617209011481e-01 +-2.45454545454545e+01 -7.67697791900801e-01 2.72273742523902e-01 2.39026230372002e-01 +-2.39393939393939e+01 -7.73185913789781e-01 2.60674093105127e-01 2.42999615685138e-01 +-2.33333333333333e+01 -7.80678259646152e-01 2.49680994670638e-01 2.43052192230589e-01 +-2.27272727272727e+01 -7.88170605502522e-01 2.38687896236150e-01 2.42568426653275e-01 +-2.21212121212121e+01 -7.95662951358893e-01 2.27694797801661e-01 2.42847201975787e-01 +-2.15151515151515e+01 -8.03122917039084e-01 2.16821981366589e-01 2.40650679427694e-01 +-2.09090909090909e+01 -8.09131542492648e-01 2.05979243168443e-01 2.37504038302243e-01 +-2.03030303030303e+01 -8.15361532190997e-01 1.95136504970297e-01 2.34357397176791e-01 +-1.96969696969697e+01 -8.22724297362875e-01 1.84465173018459e-01 2.31838282654647e-01 +-1.90909090909091e+01 -8.30906925089566e-01 1.73965237616411e-01 2.29946659236386e-01 +-1.84848484848485e+01 -8.31918112583414e-01 1.63453683142057e-01 2.21457087959307e-01 +-1.78787878787879e+01 -8.31595126485506e-01 1.52804171278659e-01 2.11525887706305e-01 +-1.72727272727273e+01 -8.31031369674327e-01 1.42866609967544e-01 1.99629022620351e-01 +-1.66666666666667e+01 -8.25256436764452e-01 1.33056030411927e-01 1.82862818294272e-01 +-1.60606060606061e+01 -8.15283902136340e-01 1.23352246439714e-01 1.62108086965354e-01 +-1.54545454545455e+01 -8.07202667770935e-01 1.13892061964644e-01 1.40642855087825e-01 +-1.48484848484848e+01 -8.00484816929381e-01 1.04572113067813e-01 1.18780315352772e-01 +-1.42424242424242e+01 -7.97273008609856e-01 9.54960779870226e-02 9.63104203643558e-02 +-1.36363636363636e+01 -7.95411303466245e-01 8.64650864864851e-02 7.45927649489055e-02 +-1.30303030303030e+01 -7.95017738651442e-01 7.74696737429739e-02 5.29180621304360e-02 +-1.24242424242424e+01 -7.83491668219477e-01 6.82294219737490e-02 3.53906464364337e-02 +-1.18181818181818e+01 -7.69390633326341e-01 5.96867612177415e-02 1.90461834027338e-02 +-1.12121212121212e+01 -7.49852461255598e-01 4.99975509367422e-02 4.95579546151236e-03 +-1.06060606060606e+01 -7.26864172133525e-01 4.11158480572885e-02 -1.01481331303818e-02 +-1.00000000000000e+01 -7.01883025098080e-01 3.29149003627515e-02 -2.57966293458753e-02 +-9.39393939393939e+00 -6.73760079004400e-01 2.58543044614024e-02 -4.12961616654669e-02 +-8.78787878787879e+00 -6.36634699427489e-01 1.93848671125434e-02 -5.74839914192587e-02 +-8.18181818181818e+00 -5.81874634591272e-01 1.36623501221776e-02 -7.45539130446945e-02 +-7.57575757575758e+00 -5.05150686435173e-01 1.05716894357738e-02 -8.64279283248293e-02 +-6.96969696969697e+00 -4.18595232643061e-01 9.10734541656171e-03 -9.50674159963851e-02 +-6.36363636363636e+00 -3.38986978205484e-01 7.90162668231047e-03 -9.99599652998083e-02 +-5.75757575757576e+00 -2.59840510197803e-01 7.41964713494604e-03 -1.04208933106189e-01 +-5.15151515151515e+00 -1.80988998184422e-01 7.14720887337387e-03 -1.07763832355698e-01 +-4.54545454545454e+00 -1.03071489415176e-01 6.95243839815077e-03 -1.10602747534693e-01 +-3.93939393939394e+00 -2.57708400834061e-02 6.84633480589618e-03 -1.12642875373749e-01 +-3.33333333333333e+00 5.06291120206322e-02 6.76146535162503e-03 -1.14417763754454e-01 +-2.72727272727273e+00 1.27032191349935e-01 6.66325312920406e-03 -1.16093113518882e-01 +-2.12121212121212e+00 2.02920139434825e-01 6.61583701230752e-03 -1.17866755340555e-01 +-1.51515151515152e+00 2.78307232368702e-01 6.59553135545088e-03 -1.19945517730907e-01 +-9.09090909090912e-01 3.52936192696077e-01 6.59403346409144e-03 -1.21944793137844e-01 +-3.03030303030302e-01 4.26320562661541e-01 6.64943771563519e-03 -1.23760507757517e-01 + 3.03030303030302e-01 4.99818577478435e-01 6.69818073560818e-03 -1.25508281414915e-01 + 9.09090909090912e-01 5.73376543665411e-01 6.69183344611623e-03 -1.27070496093681e-01 + 1.51515151515152e+00 6.46799556143286e-01 6.75524511750563e-03 -1.28538560457679e-01 + 2.12121212121212e+00 7.20154880913483e-01 6.84155940142869e-03 -1.29906010197320e-01 + 2.72727272727273e+00 7.93147472633957e-01 6.97678572298154e-03 -1.31165648253112e-01 + 3.33333333333333e+00 8.65616018748002e-01 7.10739240893340e-03 -1.32288860283965e-01 + 3.93939393939394e+00 9.37648112828365e-01 7.24422887006074e-03 -1.33365853998558e-01 + 4.54545454545455e+00 1.00910358732349e+00 7.39983874217581e-03 -1.34215184053867e-01 + 5.15151515151515e+00 1.08005492256340e+00 7.58558750578516e-03 -1.34976127499023e-01 + 5.75757575757576e+00 1.14960510771521e+00 7.88653428093343e-03 -1.35458436688932e-01 + 6.36363636363637e+00 1.21615416551218e+00 8.34153340579227e-03 -1.35456842953982e-01 + 6.96969696969697e+00 1.27828480587284e+00 9.10488091440775e-03 -1.34893951393780e-01 + 7.57575757575757e+00 1.32797468584652e+00 1.06845025707761e-02 -1.32377276048360e-01 + 8.18181818181818e+00 1.37107050025369e+00 1.21820686740787e-02 -1.29169553035756e-01 + 8.78787878787879e+00 1.40369513738070e+00 1.40255937471439e-02 -1.25043047898281e-01 + 9.39393939393939e+00 1.41709683794245e+00 1.92334681728973e-02 -1.22574062592608e-01 + 1.00000000000000e+01 1.41645872036543e+00 2.62062454721527e-02 -1.22372841879845e-01 + 1.06060606060606e+01 1.38657460264657e+00 3.26763717983368e-02 -1.21751932897855e-01 + 1.12121212121212e+01 1.36400259487080e+00 3.83098431246971e-02 -1.21315233753301e-01 + 1.18181818181818e+01 1.35688821281416e+00 4.60809911460502e-02 -1.19819418114883e-01 + 1.24242424242424e+01 1.34089573725963e+00 5.79456504379348e-02 -1.18207966359576e-01 + 1.30303030303030e+01 1.32223161769021e+00 7.00497051047743e-02 -1.17191325445144e-01 + 1.36363636363636e+01 1.29585304328532e+00 8.36737099489719e-02 -1.19176336444020e-01 + 1.42424242424242e+01 1.27550502164861e+00 9.56164211836313e-02 -1.21085843980632e-01 + 1.48484848484848e+01 1.26031280258829e+00 1.05038483493522e-01 -1.22965364533929e-01 + 1.54545454545455e+01 1.24817918569169e+00 1.13694141927813e-01 -1.24250481062770e-01 + 1.60606060606061e+01 1.23659506592632e+00 1.22025178103146e-01 -1.25145411447740e-01 + 1.66666666666667e+01 1.22112439263804e+00 1.29733166820717e-01 -1.25238540045732e-01 + 1.72727272727273e+01 1.20372487247866e+00 1.38204896553668e-01 -1.25906002656970e-01 + 1.78787878787879e+01 1.18372803528903e+00 1.47610097212096e-01 -1.27281617838633e-01 + 1.84848484848485e+01 1.17400652248468e+00 1.57673262028419e-01 -1.29411130817857e-01 + 1.90909090909091e+01 1.16668752601417e+00 1.67940267889330e-01 -1.32031130540839e-01 + 1.96969696969697e+01 1.15802631000889e+00 1.78430476422176e-01 -1.36362103439965e-01 + 2.03030303030303e+01 1.14825771518914e+00 1.89897612594817e-01 -1.41556026190695e-01 + 2.09090909090909e+01 1.14104652446381e+00 2.02341731675555e-01 -1.47700684953726e-01 + 2.15151515151515e+01 1.13734479071489e+00 2.14785850756294e-01 -1.53871949597139e-01 + 2.21212121212121e+01 1.13089213779505e+00 2.26985477991913e-01 -1.60089208840245e-01 + 2.27272727272727e+01 1.12204977020079e+00 2.38207389411154e-01 -1.66490399157068e-01 + 2.33333333333333e+01 1.11320740260652e+00 2.49429300830395e-01 -1.72914291335786e-01 + 2.39393939393939e+01 1.10436503501225e+00 2.60651212249636e-01 -1.79425078294699e-01 + 2.45454545454545e+01 1.09671055899213e+00 2.72273742523902e-01 -1.85035919192311e-01 + 2.51515151515151e+01 1.08918806808547e+00 2.83940785046750e-01 -1.90542124148107e-01 + 2.57575757575758e+01 1.08166557717880e+00 2.95607827569598e-01 -1.96042910921405e-01 + 2.63636363636364e+01 1.07497654178085e+00 3.07666550963613e-01 -2.01108325476125e-01 + 2.69696969696970e+01 1.06884322973428e+00 3.19986435516351e-01 -2.05883282560142e-01 + 2.75757575757576e+01 1.06270991768772e+00 3.32306320069088e-01 -2.10654825089128e-01 + 2.81818181818182e+01 1.05685002491795e+00 3.44803723925826e-01 -2.15273237837376e-01 + 2.87878787878788e+01 1.05162805573452e+00 3.57715303960546e-01 -2.19539750840593e-01 + 2.93939393939394e+01 1.04640608655109e+00 3.70626883995265e-01 -2.23804015238057e-01 + 3.00000000000000e+01 1.04118411736767e+00 3.83538464029985e-01 -2.28066012025690e-01 + 3.30000000000000e+01 1.01848589840269e+00 4.50834279245390e-01 -2.46961206869889e-01 + 3.60000000000000e+01 9.96808909621796e-01 5.20958260992169e-01 -2.64359434793424e-01 + 3.90000000000000e+01 9.74106328942832e-01 5.93758161928647e-01 -2.80547282143363e-01 + 4.20000000000000e+01 9.48041157048807e-01 6.68214525810192e-01 -2.95913378121082e-01 + 4.50000000000000e+01 9.20743807181201e-01 7.43083281614397e-01 -3.11045980331182e-01 + 4.80000000000000e+01 8.86477884798320e-01 8.17875803160575e-01 -3.25477187585035e-01 + 5.10000000000000e+01 8.48118712495052e-01 8.91114285364008e-01 -3.39620328980538e-01 + 5.40000000000000e+01 8.01572777205266e-01 9.61244588976293e-01 -3.53193383869185e-01 + 5.70000000000000e+01 7.55026776527843e-01 1.03137413224544e+00 -3.66763595394112e-01 + 6.00000000000000e+01 7.08480743156850e-01 1.10150329534591e+00 -3.80331070227688e-01 + 6.30000000000000e+01 6.46295216458993e-01 1.15838046907205e+00 -3.92574049260776e-01 + 6.60000000000000e+01 5.84109443410254e-01 1.21525752920760e+00 -4.04815652134246e-01 + 6.90000000000000e+01 5.21923445770576e-01 1.27213458934316e+00 -4.17055794570706e-01 + 7.20000000000000e+01 4.52335480264868e-01 1.31553653901342e+00 -4.28053298659701e-01 + 7.50000000000000e+01 3.79046682354287e-01 1.35220120930450e+00 -4.38429394598601e-01 + 7.80000000000000e+01 3.05756781496138e-01 1.38886629974350e+00 -4.48804321680909e-01 + 8.10000000000000e+01 2.31207286740326e-01 1.41728453792232e+00 -4.58322686478495e-01 + 8.40000000000000e+01 1.54138691138483e-01 1.42920964084012e+00 -4.66128863644011e-01 + 8.70000000000000e+01 7.70693031576111e-02 1.44113483485913e+00 -4.73934397736458e-01 + 9.00000000000000e+01 -3.36708373039042e-07 1.45305992557158e+00 -4.81739438540332e-01 + 9.30000000000000e+01 -5.39485757284989e-02 1.44113482265378e+00 -4.85914001849487e-01 + 9.60000000000000e+01 -1.07896933109837e-01 1.42920967418575e+00 -4.89748119107250e-01 + 9.90000000000000e+01 -1.61845527217882e-01 1.41728443461560e+00 -4.93557987335880e-01 + 1.02000000000000e+02 -2.14030046275947e-01 1.38886612216712e+00 -4.94077965350438e-01 + 1.05000000000000e+02 -2.65332546911451e-01 1.35220145187604e+00 -4.92944920029321e-01 + 1.08000000000000e+02 -3.16635035430310e-01 1.31553636143885e+00 -4.92245915161826e-01 + 1.11000000000000e+02 -3.65346571871470e-01 1.27213409662221e+00 -4.90545503515274e-01 + 1.14000000000000e+02 -4.08876283070132e-01 1.21525768824574e+00 -4.86317993590270e-01 + 1.17000000000000e+02 -4.52406347782145e-01 1.15838084536770e+00 -4.82090051371639e-01 + 1.20000000000000e+02 -4.95936567846409e-01 1.10150375931678e+00 -4.77861889492743e-01 + 1.23000000000000e+02 -5.28518625044671e-01 1.03137459621631e+00 -4.71840511315534e-01 + 1.26000000000000e+02 -5.61100704888174e-01 9.61245052954708e-01 -4.65818976558725e-01 + 1.29000000000000e+02 -5.93682830023854e-01 8.91114749342422e-01 -4.59682348306178e-01 + 1.32000000000000e+02 -6.18908433527060e-01 8.17850698969113e-01 -4.54312399338742e-01 + 1.35000000000000e+02 -6.40455784934676e-01 7.43019778936259e-01 -4.49364062058548e-01 + 1.38000000000000e+02 -6.62002920890116e-01 6.68189421819664e-01 -4.44415444601716e-01 + 1.41000000000000e+02 -6.81613839477788e-01 5.94826066587770e-01 -4.41694691787043e-01 + 1.44000000000000e+02 -6.97352307618548e-01 5.24396727029221e-01 -4.43429686334623e-01 + 1.47000000000000e+02 -7.13090480114408e-01 4.53967729130364e-01 -4.45164688600493e-01 + 1.50000000000000e+02 -7.28828504793094e-01 3.83538902055256e-01 -4.46899694725369e-01 + 1.53000000000000e+02 -7.38250770119389e-01 3.28279710588330e-01 -4.64997809025810e-01 + 1.56000000000000e+02 -7.46093272753856e-01 2.73020555057756e-01 -4.81308204600343e-01 + 1.59000000000000e+02 -7.53707623020192e-01 2.17761400703393e-01 -5.00902986460923e-01 + 1.62000000000000e+02 -6.88143441383303e-01 1.78536848703957e-01 -5.06252966573203e-01 + 1.65000000000000e+02 -5.85650053883360e-01 1.47329733490110e-01 -5.03908411641623e-01 + 1.68000000000000e+02 -4.83157240864670e-01 1.16122375886185e-01 -5.01563371955391e-01 + 1.71000000000000e+02 -3.73345827031091e-01 8.57857267499245e-02 -4.50000513056908e-01 + 1.74000000000000e+02 -2.48896869884329e-01 5.71905351997449e-02 -2.99999717902353e-01 + 1.77000000000000e+02 -1.23881031171309e-01 4.71151394500337e-02 -1.04090643424068e-01 + 1.80000000000000e+02 0.00000000000000e+00 4.63087218239101e-02 1.12294918356446e-01 diff --git a/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_24.dat b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_24.dat new file mode 100644 index 00000000..59306058 --- /dev/null +++ b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_24.dat @@ -0,0 +1,254 @@ +! ------------ AirfoilInfo v1.01.x Input File ---------------------------------- +! AeroElasticSE FAST driver +! line +! line +! ------------------------------------------------------------------------------ +DEFAULT InterpOrd ! Interpolation order to use for quasi-steady table lookup {1=linear; 3=cubic spline; "default"} [default=3] +1 NonDimArea ! The non-dimensional area of the airfoil (area/chord^2) (set to 1.0 if unsure or unneeded) +@"NREL-2p8-127_AF24_Coords.txt" NumCoords ! The number of coordinates in the airfoil shape file. Set to zero if coordinates not included. +AF24_BL.txt BL_file ! The file name including the boundary layer characteristics of the profile. Ignored if the aeroacoustic module is not called. +1 NumTabs ! Number of airfoil tables in this file. Each table must have lines for Re and Ctrl. +! ------------------------------------------------------------------------------ +! data for table 1 +! ------------------------------------------------------------------------------ +6.000000 Re ! Reynolds number in millions +0 Ctrl ! Control setting (must be 0 for current AirfoilInfo) +True InclUAdata ! Is unsteady aerodynamics data included in this table? If TRUE, then include 30 UA coefficients below this line +!........................................ +-3.881348 alpha0 ! 0-lift angle of attack, depends on airfoil. +10.220205 alpha1 ! Angle of attack at f=0.7, (approximately the stall angle) for AOA>alpha0. (deg) +-10.228661 alpha2 ! Angle of attack at f=0.7, (approximately the stall angle) for AOA1] +0.000000 S2 ! Constant in the f curve best-fit for AOA> alpha1; by definition it depends on the airfoil. [ignored if UAMod<>1] +0.000000 S3 ! Constant in the f curve best-fit for alpha2<=AOA< alpha0; by definition it depends on the airfoil. [ignored if UAMod<>1] +0.000000 S4 ! Constant in the f curve best-fit for AOA< alpha2; by definition it depends on the airfoil. [ignored if UAMod<>1] +1.447089 Cn1 ! Critical value of C0n at leading edge separation. It should be extracted from airfoil data at a given Mach and Reynolds number. It can be calculated from the static value of Cn at either the break in the pitching moment or the loss of chord force at the onset of stall. It is close to the condition of maximum lift of the airfoil at low Mach numbers. +-0.835242 Cn2 ! As Cn1 for negative AOAs. +Default St_sh ! Strouhal's shedding frequency constant. [default = 0.19] +0.006598 Cd0 ! 2D drag coefficient value at 0-lift. +-0.113186 Cm0 ! 2D pitching moment coefficient about 1/4-chord location, at 0-lift, positive if nose up. [If the aerodynamics coefficients table does not include a column for Cm, this needs to be set to 0.0] +0.000000 k0 ! Constant in the \hat(x)_cp curve best-fit; = (\hat(x)_AC-0.25). [ignored if UAMod<>1] +0.000000 k1 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k2 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k3 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k1_hat ! Constant in the expression of Cc due to leading edge vortex effects. [ignored if UAMod<>1] +Default x_cp_bar ! Constant in the expression of \hat(x)_cp^v. [ignored if UAMod<>1, default = 0.2] +Default UACutout ! Angle of attack above which unsteady aerodynamics are disabled (deg). [Specifying the string "Default" sets UACutout to 45 degrees] +Default filtCutOff ! Cut-off frequency (-3 dB corner frequency) for low-pass filtering the AoA input to UA, as well as the 1st and 2nd derivatives (Hz) [default = 20] +!........................................ +! Table of aerodynamics coefficients +200 NumAlf ! Number of data lines in the following table +! Alpha Cl Cd Cm +! (deg) (-) (-) (-) +-1.80000000000000e+02 0.00000000000000e+00 4.20239297897650e-02 1.57138208863316e-01 +-1.77000000000000e+02 1.40632365655801e-01 4.20239297897650e-02 1.82737995898986e-01 +-1.74000000000000e+02 2.82553053900608e-01 5.04286683283111e-02 2.39999774321882e-01 +-1.71000000000000e+02 4.23830336360153e-01 7.56431598642469e-02 3.60000410445527e-01 +-1.68000000000000e+02 5.34869114486967e-01 1.04245693608263e-01 3.04280258541825e-01 +-1.65000000000000e+02 6.30788993375323e-01 1.34542208912873e-01 1.60701763545007e-01 +-1.62000000000000e+02 7.26709994336859e-01 1.64838896980479e-01 1.71214488498863e-02 +-1.59000000000000e+02 7.84071397760670e-01 2.04002209021424e-01 -7.41764661492530e-02 +-1.56000000000000e+02 7.64500626823811e-01 2.60898469061760e-01 -6.11103531608993e-02 +-1.53000000000000e+02 7.44806596412559e-01 3.17794763757350e-01 -4.80087218730144e-02 +-1.50000000000000e+02 7.24801607355001e-01 3.74691108028256e-01 -3.36803071761103e-02 +-1.47000000000000e+02 7.09536340567078e-01 4.45426278146463e-01 -1.81789006503532e-02 +-1.44000000000000e+02 6.94270972610212e-01 5.16161667949901e-01 -2.67735864084869e-03 +-1.41000000000000e+02 6.79005402308234e-01 5.86897497139490e-01 1.25267866649444e-02 +-1.38000000000000e+02 6.59752709771772e-01 6.60614800800240e-01 2.78426345762092e-02 +-1.35000000000000e+02 6.38506464206380e-01 7.35822835648326e-01 4.32768039375504e-02 +-1.32000000000000e+02 6.17259998089925e-01 8.11031580816670e-01 5.87121989579576e-02 +-1.29000000000000e+02 5.92302309505059e-01 8.84693447887175e-01 7.43012013825991e-02 +-1.26000000000000e+02 5.59922158385802e-01 9.55261551412121e-01 9.01959583834699e-02 +-1.23000000000000e+02 5.27541955630656e-01 1.02582880155467e+00 1.06091386661389e-01 +-1.20000000000000e+02 4.95161727058530e-01 1.09639562502197e+00 1.21987354023941e-01 +-1.17000000000000e+02 4.51763647235390e-01 1.15375704715292e+00 1.37121497118599e-01 +-1.14000000000000e+02 4.08365719274480e-01 1.21111822435222e+00 1.52255604498479e-01 +-1.11000000000000e+02 3.64968138119650e-01 1.26847896334996e+00 1.67389419062474e-01 +-1.08000000000000e+02 3.16351063621799e-01 1.31238637614246e+00 1.80934520183943e-01 +-1.05000000000000e+02 2.65124202709162e-01 1.34956702339128e+00 1.93694959616565e-01 +-1.02000000000000e+02 2.13897328813262e-01 1.38674724458622e+00 2.06454767299050e-01 +-9.90000000000000e+01 1.61771435376163e-01 1.41568677594618e+00 2.17866871578471e-01 +-9.60000000000000e+01 1.07847463915400e-01 1.42814457068853e+00 2.26583332591711e-01 +-9.30000000000000e+01 5.39238186798111e-02 1.44060227026035e+00 2.35299390910874e-01 +-9.00000000000000e+01 3.36553857038623e-07 1.45305992224777e+00 2.44015288398801e-01 +-8.70000000000000e+01 -5.39237634891041e-02 1.44060228301076e+00 2.47951662237116e-01 +-8.40000000000000e+01 -1.07847614698837e-01 1.42814453585376e+00 2.51892083934148e-01 +-8.10000000000000e+01 -1.61770968240210e-01 1.41568688386634e+00 2.55836458741642e-01 +-7.80000000000000e+01 -2.13897080708414e-01 1.38674742465954e+00 2.56509498151152e-01 +-7.50000000000000e+01 -2.65124541622777e-01 1.34956677740889e+00 2.55548599134485e-01 +-7.20000000000000e+01 -3.16350815522372e-01 1.31238655621395e+00 2.54590706463430e-01 +-6.90000000000000e+01 -3.64967762165930e-01 1.26847946026667e+00 2.52383955015723e-01 +-6.60000000000000e+01 -4.08365840623045e-01 1.21111806395980e+00 2.47675595024712e-01 +-6.30000000000000e+01 -4.51763934354955e-01 1.15375666765293e+00 2.42970286422080e-01 +-6.00000000000000e+01 -4.95161941284426e-01 1.09639515815556e+00 2.38268000115941e-01 +-5.70000000000000e+01 -5.27542169856552e-01 1.02582833468826e+00 2.31806506435537e-01 +-5.40000000000000e+01 -5.59922372611185e-01 9.55261084537245e-01 2.25347767167551e-01 +-5.10000000000000e+01 -5.92302523730443e-01 8.84692981012299e-01 2.18891521602934e-01 +-4.80000000000000e+01 -6.18906352581358e-01 8.11045812993734e-01 2.12734135842278e-01 +-4.50000000000000e+01 -6.42622113131780e-01 7.35859162213287e-01 2.06728126759377e-01 +-4.20000000000000e+01 -6.61399051379004e-01 6.60629032861292e-01 2.02335706314512e-01 +-3.90000000000000e+01 -6.79295197663792e-01 5.85819587866301e-01 1.98564860746646e-01 +-3.60000000000000e+01 -6.94777748193317e-01 5.12692903825368e-01 1.97017430019138e-01 +-3.30000000000000e+01 -7.09467742340985e-01 4.42267305815927e-01 1.98629231822253e-01 +-3.00000000000000e+01 -7.24801717703120e-01 3.74690668178350e-01 2.03759075670758e-01 +-2.93939393939394e+01 -7.28326530814462e-01 3.61726727869206e-01 2.05744738406902e-01 +-2.87878787878788e+01 -7.31851343925804e-01 3.48762787560061e-01 2.07730401143047e-01 +-2.81818181818182e+01 -7.35376157037146e-01 3.35798847250917e-01 2.09716063879191e-01 +-2.75757575757576e+01 -7.39335418161425e-01 3.23251387701133e-01 2.12376937449998e-01 +-2.69696969696970e+01 -7.43480887264291e-01 3.10882435217812e-01 2.15327211917801e-01 +-2.63636363636364e+01 -7.47626356367156e-01 2.98513482734492e-01 2.18277486385603e-01 +-2.57575757575758e+01 -7.52151842029857e-01 2.86407040228379e-01 2.21732543995886e-01 +-2.51515151515151e+01 -7.57247263964635e-01 2.74694301506801e-01 2.25944658673781e-01 +-2.45454545454545e+01 -7.62342685899414e-01 2.62981562785224e-01 2.30156773351676e-01 +-2.39393939393939e+01 -7.67618823549025e-01 2.51338309217338e-01 2.34224184613365e-01 +-2.33333333333333e+01 -7.74521437619550e-01 2.40320435485340e-01 2.36989237113918e-01 +-2.27272727272727e+01 -7.81424051690076e-01 2.29302561753342e-01 2.39601565570627e-01 +-2.21212121212121e+01 -7.88326665760601e-01 2.18284688021344e-01 2.42470674291164e-01 +-2.15151515151515e+01 -7.95622047703425e-01 2.07577437194191e-01 2.45095428001552e-01 +-2.09090909090909e+01 -8.02604681726082e-01 1.96947862073894e-01 2.47624260079401e-01 +-2.03030303030303e+01 -8.09650349475145e-01 1.86318286953598e-01 2.50153092157250e-01 +-1.96969696969697e+01 -8.17637506447164e-01 1.75928434913981e-01 2.53560038839616e-01 +-1.90909090909091e+01 -8.26477015311138e-01 1.65778292393816e-01 2.57845050451215e-01 +-1.84848484848485e+01 -8.26084809962742e-01 1.55849503459699e-01 2.52897003259897e-01 +-1.78787878787879e+01 -8.23983493243247e-01 1.46076930679257e-01 2.45664651306383e-01 +-1.72727272727273e+01 -8.21570138202451e-01 1.37130650088349e-01 2.35566574130545e-01 +-1.66666666666667e+01 -8.12443964880370e-01 1.28220565266013e-01 2.18667326209765e-01 +-1.60606060606061e+01 -7.97844348659724e-01 1.19340921345769e-01 1.96202242311259e-01 +-1.54545454545455e+01 -7.84422413764076e-01 1.10579594948523e-01 1.73424826407758e-01 +-1.48484848484848e+01 -7.71787584327422e-01 1.01887960544163e-01 1.50473470711618e-01 +-1.42424242424242e+01 -7.61134965931686e-01 9.33387624500803e-02 1.27203383377638e-01 +-1.36363636363636e+01 -7.51019037969479e-01 8.48128124492238e-02 1.04178189645314e-01 +-1.30303030303030e+01 -7.41421130409000e-01 7.63034135314191e-02 8.11835234005733e-02 +-1.24242424242424e+01 -7.26117069582958e-01 6.77522789215004e-02 6.03315753701249e-02 +-1.18181818181818e+01 -7.09450417189115e-01 5.96236347309660e-02 4.00791186975229e-02 +-1.12121212121212e+01 -6.90082557893989e-01 5.06890203132416e-02 2.09663498148639e-02 +-1.06060606060606e+01 -6.69006785525034e-01 4.21875347068638e-02 1.31821761243166e-03 +-1.00000000000000e+01 -6.46973736816406e-01 3.40753735771777e-02 -1.86162729145852e-02 +-9.39393939393939e+00 -6.23566521153584e-01 2.66139202130595e-02 -3.84582682239768e-02 +-8.78787878787879e+00 -5.93143909692991e-01 1.97080621922025e-02 -5.81227331911647e-02 +-8.18181818181818e+00 -5.49437129950642e-01 1.36122296354314e-02 -7.73434792653389e-02 +-7.57575757575758e+00 -4.76129595933123e-01 1.04462591632936e-02 -9.01887084685705e-02 +-6.96969696969697e+00 -3.89923494054396e-01 8.96219583042148e-03 -9.89373513292037e-02 +-6.36363636363636e+00 -3.12270511910677e-01 7.65469409261513e-03 -1.02756750711562e-01 +-5.75757575757576e+00 -2.35244495718475e-01 7.20033215041447e-03 -1.06054556847806e-01 +-5.15151515151515e+00 -1.58611001142337e-01 6.92443690785538e-03 -1.08867710719892e-01 +-4.54545454545454e+00 -8.26264788487249e-02 6.71182503055839e-03 -1.11241902473054e-01 +-3.93939393939394e+00 -7.17505732470964e-03 6.60399736858371e-03 -1.13032741919541e-01 +-3.33333333333333e+00 6.77399244143484e-02 6.54568110870987e-03 -1.14632383709498e-01 +-2.72727272727273e+00 1.42670380661859e-01 6.46364824529083e-03 -1.16181617095474e-01 +-2.12121212121212e+00 2.17139817585866e-01 6.43953237954945e-03 -1.17766630428816e-01 +-1.51515151515152e+00 2.91428740135327e-01 6.42972618595009e-03 -1.19525590995757e-01 +-9.09090909090912e-01 3.65128859297927e-01 6.42967209033216e-03 -1.21282061863669e-01 +-3.03030303030302e-01 4.38105121735726e-01 6.47736400956553e-03 -1.22890854235333e-01 + 3.03030303030302e-01 5.11112071056141e-01 6.53139868052610e-03 -1.24460808318302e-01 + 9.09090909090912e-01 5.84048322897008e-01 6.52730920651946e-03 -1.25889751980391e-01 + 1.51515151515152e+00 6.56771187401434e-01 6.60828592671719e-03 -1.27205103311759e-01 + 2.12121212121212e+00 7.29431355319300e-01 6.66584266708599e-03 -1.28498098736987e-01 + 2.72727272727273e+00 8.01715099938977e-01 6.79410605892685e-03 -1.29703511469116e-01 + 3.33333333333333e+00 8.73667737101458e-01 6.92003913189438e-03 -1.30770162129486e-01 + 3.93939393939394e+00 9.45203779381055e-01 7.04950954145510e-03 -1.31831672743512e-01 + 4.54545454545455e+00 1.01616262246952e+00 7.18868096099871e-03 -1.32686207865223e-01 + 5.15151515151515e+00 1.08666504585964e+00 7.35805565558534e-03 -1.33484479795433e-01 + 5.75757575757576e+00 1.15589713891403e+00 7.65596176371924e-03 -1.34065604697579e-01 + 6.36363636363637e+00 1.22235143346160e+00 8.13782849850763e-03 -1.34188428144082e-01 + 6.96969696969697e+00 1.28381732514628e+00 9.00700508163636e-03 -1.33672116338428e-01 + 7.57575757575757e+00 1.33414824858160e+00 1.07028357691023e-02 -1.31358398670661e-01 + 8.18181818181818e+00 1.37921530349790e+00 1.23338548134546e-02 -1.28462440465876e-01 + 8.78787878787879e+00 1.41929596248767e+00 1.40314224567824e-02 -1.25079434784614e-01 + 9.39393939393939e+00 1.44895179840671e+00 1.73667127363230e-02 -1.22426571069460e-01 + 1.00000000000000e+01 1.46562058968523e+00 2.15076283531428e-02 -1.22080342259589e-01 + 1.06060606060606e+01 1.46482275209920e+00 2.56482444467929e-02 -1.21729653497994e-01 + 1.12121212121212e+01 1.46455008673655e+00 2.96173727205461e-02 -1.21654814919871e-01 + 1.18181818181818e+01 1.46787480330173e+00 3.84335406340759e-02 -1.21545340375698e-01 + 1.24242424242424e+01 1.44626795909455e+00 5.24745071699755e-02 -1.21745587084181e-01 + 1.30303030303030e+01 1.41548464258938e+00 6.65727041455837e-02 -1.22132303153946e-01 + 1.36363636363636e+01 1.37245053342376e+00 8.16057042391146e-02 -1.24136435674557e-01 + 1.42424242424242e+01 1.33537840735922e+00 9.41511245499718e-02 -1.25907093812210e-01 + 1.48484848484848e+01 1.30613659580939e+00 1.02967015650268e-01 -1.27351580700688e-01 + 1.54545454545455e+01 1.28553302955425e+00 1.11389370579920e-01 -1.28462528314075e-01 + 1.60606060606061e+01 1.26758424346921e+00 1.19644615010785e-01 -1.29390414755028e-01 + 1.66666666666667e+01 1.24771591748635e+00 1.27576133928679e-01 -1.29935088016977e-01 + 1.72727272727273e+01 1.22417688851766e+00 1.35896595584476e-01 -1.30758578064231e-01 + 1.78787878787879e+01 1.19608311119412e+00 1.44692436629616e-01 -1.31924607905431e-01 + 1.84848484848485e+01 1.18255480628068e+00 1.53780455374608e-01 -1.33460435656660e-01 + 1.90909090909091e+01 1.17242740863741e+00 1.63075826898732e-01 -1.35618139566060e-01 + 1.96969696969697e+01 1.16082579219221e+00 1.73132593582544e-01 -1.40776664039364e-01 + 2.03030303030303e+01 1.14904324940101e+00 1.83847599384671e-01 -1.46705689236554e-01 + 2.09090909090909e+01 1.13954137740033e+00 1.95220881544062e-01 -1.53430242057478e-01 + 2.15151515151515e+01 1.13215807394264e+00 2.06594163703453e-01 -1.60162370933814e-01 + 2.21212121212121e+01 1.12321585235273e+00 2.17919889776365e-01 -1.66781417553110e-01 + 2.27272727272727e+01 1.11431119585911e+00 2.29055440435074e-01 -1.72948251497559e-01 + 2.33333333333333e+01 1.10540653936549e+00 2.40190991093782e-01 -1.79121549823611e-01 + 2.39393939393939e+01 1.09650188287188e+00 2.51326541752491e-01 -1.85319591539483e-01 + 2.45454545454545e+01 1.08905958113101e+00 2.62981562785224e-01 -1.90662311121533e-01 + 2.51515151515151e+01 1.08177975975634e+00 2.74694301506801e-01 -1.95908674546375e-01 + 2.57575757575758e+01 1.07449993838168e+00 2.86407040228379e-01 -2.01153495137443e-01 + 2.63636363636364e+01 1.06803512793561e+00 2.98513482734492e-01 -2.05997699680956e-01 + 2.69696969696970e+01 1.06211374254334e+00 3.10882435217812e-01 -2.10574738593792e-01 + 2.75757575757576e+01 1.05619235715106e+00 3.23251387701133e-01 -2.15150805208106e-01 + 2.81818181818182e+01 1.05053677218194e+00 3.35798847250917e-01 -2.19587044062714e-01 + 2.87878787878788e+01 1.04550133499893e+00 3.48762787560062e-01 -2.23698575936724e-01 + 2.93939393939394e+01 1.04046589781592e+00 3.61726727869206e-01 -2.27809467517628e-01 + 3.00000000000000e+01 1.03543046063291e+00 3.74690668178350e-01 -2.31919713393992e-01 + 3.30000000000000e+01 1.01352784881378e+00 4.42267305815928e-01 -2.50242753909780e-01 + 3.60000000000000e+01 9.92539022396652e-01 5.12692903825368e-01 -2.67200657190209e-01 + 3.90000000000000e+01 9.70421727927888e-01 5.85819587866301e-01 -2.83055031736328e-01 + 4.20000000000000e+01 9.44855717457034e-01 6.60629032861292e-01 -2.98162017656836e-01 + 4.50000000000000e+01 9.18032014729747e-01 7.35859162213287e-01 -3.13059792814360e-01 + 4.80000000000000e+01 8.84152091109475e-01 8.11045812993735e-01 -3.27314348631916e-01 + 5.10000000000000e+01 8.46146395641528e-01 8.84692981012299e-01 -3.41300099207024e-01 + 5.40000000000000e+01 7.99888891241725e-01 9.55261084537245e-01 -3.54749948670230e-01 + 5.70000000000000e+01 7.53631324948729e-01 1.02582833468826e+00 -3.68198870181370e-01 + 6.00000000000000e+01 7.07373727709371e-01 1.09639515815556e+00 -3.81646953266444e-01 + 6.30000000000000e+01 6.45377123529131e-01 1.15375666765293e+00 -3.93810500184529e-01 + 6.60000000000000e+01 5.83380227301456e-01 1.21111806395980e+00 -4.05973624922660e-01 + 6.90000000000000e+01 5.21383016795821e-01 1.26847946026667e+00 -4.18136288721357e-01 + 7.20000000000000e+01 4.51929954630524e-01 1.31238655621395e+00 -4.29073410119878e-01 + 7.50000000000000e+01 3.78749119266611e-01 1.34956677740889e+00 -4.39397752827040e-01 + 7.80000000000000e+01 3.05567316722722e-01 1.38674742465954e+00 -4.49721404047000e-01 + 8.10000000000000e+01 2.31101650731069e-01 1.41568688386634e+00 -4.59194843301813e-01 + 8.40000000000000e+01 1.54068346468134e-01 1.42814453585376e+00 -4.66968167272936e-01 + 8.70000000000000e+01 7.70341547111549e-02 1.44060228301076e+00 -4.74741064431118e-01 + 9.00000000000000e+01 -3.36553857271529e-07 1.45305992224777e+00 -4.82513681756923e-01 + 9.30000000000000e+01 -5.39238186798111e-02 1.44060227026035e+00 -4.86445774433152e-01 + 9.60000000000000e+01 -1.07847463915400e-01 1.42814457068853e+00 -4.90136599398835e-01 + 9.90000000000000e+01 -1.61771435376163e-01 1.41568677594618e+00 -4.93816587592719e-01 + 1.02000000000000e+02 -2.13897328813262e-01 1.38674724458622e+00 -4.94219233630832e-01 + 1.05000000000000e+02 -2.65124202709163e-01 1.34956702339128e+00 -4.92980933650800e-01 + 1.08000000000000e+02 -3.16351063621799e-01 1.31238637614246e+00 -4.92020295748683e-01 + 1.11000000000000e+02 -3.64968138119650e-01 1.26847896334996e+00 -4.89968875412941e-01 + 1.14000000000000e+02 -4.08365719274481e-01 1.21111822435222e+00 -4.85404915466942e-01 + 1.17000000000000e+02 -4.51763647235390e-01 1.15375704715292e+00 -4.80840520657040e-01 + 1.20000000000000e+02 -4.95161727058530e-01 1.09639562502197e+00 -4.76275904937341e-01 + 1.23000000000000e+02 -5.27541955630656e-01 1.02582880155467e+00 -4.69936300398934e-01 + 1.26000000000000e+02 -5.59922158385802e-01 9.55261551412121e-01 -4.63596595371752e-01 + 1.29000000000000e+02 -5.92302309505059e-01 8.84693447887175e-01 -4.57173092895786e-01 + 1.32000000000000e+02 -6.17259998089925e-01 8.11031580816670e-01 -4.51522499663600e-01 + 1.35000000000000e+02 -6.38506464206380e-01 7.35822835648326e-01 -4.46286234978398e-01 + 1.38000000000000e+02 -6.59752709771772e-01 6.60614800800239e-01 -4.41049558888129e-01 + 1.41000000000000e+02 -6.79005402308234e-01 5.86897497139489e-01 -4.37992891545696e-01 + 1.44000000000000e+02 -6.94270972610212e-01 5.16161667949901e-01 -4.39296259388551e-01 + 1.47000000000000e+02 -7.09536340567078e-01 4.45426278146463e-01 -4.40599632549160e-01 + 1.50000000000000e+02 -7.24801607355002e-01 3.74691108028256e-01 -4.41903008368551e-01 + 1.53000000000000e+02 -7.42599775012969e-01 3.18083719972620e-01 -4.61912096005589e-01 + 1.56000000000000e+02 -7.59948055761679e-01 2.61476373424413e-01 -4.80619093073397e-01 + 1.59000000000000e+02 -7.77231254388352e-01 2.04869044049550e-01 -5.01430259356238e-01 + 1.62000000000000e+02 -7.14992328958953e-01 1.66181531595306e-01 -5.06906825399297e-01 + 1.65000000000000e+02 -6.12895046906355e-01 1.36454079153225e-01 -5.04317113525236e-01 + 1.68000000000000e+02 -5.10798334796026e-01 1.06726367365571e-01 -5.01726853472064e-01 + 1.71000000000000e+02 -3.98460526443325e-01 7.82171286957471e-02 -4.50000513056908e-01 + 1.74000000000000e+02 -2.65640047479978e-01 5.21448931484207e-02 -2.99999717902353e-01 + 1.77000000000000e+02 -1.32214471307849e-01 4.28782038261505e-02 -8.60306173704663e-02 + 1.80000000000000e+02 0.00000000000000e+00 4.20239297897650e-02 1.57138208863316e-01 diff --git a/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_25.dat b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_25.dat new file mode 100644 index 00000000..5afdaa9e --- /dev/null +++ b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_25.dat @@ -0,0 +1,254 @@ +! ------------ AirfoilInfo v1.01.x Input File ---------------------------------- +! AeroElasticSE FAST driver +! line +! line +! ------------------------------------------------------------------------------ +DEFAULT InterpOrd ! Interpolation order to use for quasi-steady table lookup {1=linear; 3=cubic spline; "default"} [default=3] +1 NonDimArea ! The non-dimensional area of the airfoil (area/chord^2) (set to 1.0 if unsure or unneeded) +@"NREL-2p8-127_AF25_Coords.txt" NumCoords ! The number of coordinates in the airfoil shape file. Set to zero if coordinates not included. +AF25_BL.txt BL_file ! The file name including the boundary layer characteristics of the profile. Ignored if the aeroacoustic module is not called. +1 NumTabs ! Number of airfoil tables in this file. Each table must have lines for Re and Ctrl. +! ------------------------------------------------------------------------------ +! data for table 1 +! ------------------------------------------------------------------------------ +6.000000 Re ! Reynolds number in millions +0 Ctrl ! Control setting (must be 0 for current AirfoilInfo) +True InclUAdata ! Is unsteady aerodynamics data included in this table? If TRUE, then include 30 UA coefficients below this line +!........................................ +-3.985066 alpha0 ! 0-lift angle of attack, depends on airfoil. +10.901847 alpha1 ! Angle of attack at f=0.7, (approximately the stall angle) for AOA>alpha0. (deg) +-9.933710 alpha2 ! Angle of attack at f=0.7, (approximately the stall angle) for AOA1] +0.000000 S2 ! Constant in the f curve best-fit for AOA> alpha1; by definition it depends on the airfoil. [ignored if UAMod<>1] +0.000000 S3 ! Constant in the f curve best-fit for alpha2<=AOA< alpha0; by definition it depends on the airfoil. [ignored if UAMod<>1] +0.000000 S4 ! Constant in the f curve best-fit for AOA< alpha2; by definition it depends on the airfoil. [ignored if UAMod<>1] +1.525701 Cn1 ! Critical value of C0n at leading edge separation. It should be extracted from airfoil data at a given Mach and Reynolds number. It can be calculated from the static value of Cn at either the break in the pitching moment or the loss of chord force at the onset of stall. It is close to the condition of maximum lift of the airfoil at low Mach numbers. +-0.831442 Cn2 ! As Cn1 for negative AOAs. +Default St_sh ! Strouhal's shedding frequency constant. [default = 0.19] +0.006462 Cd0 ! 2D drag coefficient value at 0-lift. +-0.113020 Cm0 ! 2D pitching moment coefficient about 1/4-chord location, at 0-lift, positive if nose up. [If the aerodynamics coefficients table does not include a column for Cm, this needs to be set to 0.0] +0.000000 k0 ! Constant in the \hat(x)_cp curve best-fit; = (\hat(x)_AC-0.25). [ignored if UAMod<>1] +0.000000 k1 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k2 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k3 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k1_hat ! Constant in the expression of Cc due to leading edge vortex effects. [ignored if UAMod<>1] +Default x_cp_bar ! Constant in the expression of \hat(x)_cp^v. [ignored if UAMod<>1, default = 0.2] +Default UACutout ! Angle of attack above which unsteady aerodynamics are disabled (deg). [Specifying the string "Default" sets UACutout to 45 degrees] +Default filtCutOff ! Cut-off frequency (-3 dB corner frequency) for low-pass filtering the AoA input to UA, as well as the 1st and 2nd derivatives (Hz) [default = 20] +!........................................ +! Table of aerodynamics coefficients +200 NumAlf ! Number of data lines in the following table +! Alpha Cl Cd Cm +! (deg) (-) (-) (-) +-1.80000000000000e+02 0.00000000000000e+00 3.88896555692602e-02 1.88439381768847e-01 +-1.77000000000000e+02 1.47085076149199e-01 3.88896555692602e-02 1.95344118058902e-01 +-1.74000000000000e+02 2.95517626324669e-01 4.66675428003909e-02 2.39999774321882e-01 +-1.71000000000000e+02 4.43277326259944e-01 7.00014598350941e-02 3.60000410445527e-01 +-1.68000000000000e+02 5.54775230424015e-01 9.73983403883863e-02 3.01232293768575e-01 +-1.65000000000000e+02 6.48142659931080e-01 1.26826655280201e-01 1.53081887186124e-01 +-1.62000000000000e+02 7.41511167200111e-01 1.56255257014288e-01 4.92973254323252e-03 +-1.59000000000000e+02 7.95540100041439e-01 1.95090056664802e-01 -8.77735264750430e-02 +-1.56000000000000e+02 7.70906453274779e-01 2.52736933946693e-01 -6.95971986266622e-02 +-1.53000000000000e+02 7.46262520842411e-01 3.10383851618106e-01 -5.14181728633164e-02 +-1.50000000000000e+02 7.21593009442639e-01 3.68030820520305e-01 -3.29558765859875e-02 +-1.47000000000000e+02 7.06704434537952e-01 4.38996595677444e-01 -1.77699153461743e-02 +-1.44000000000000e+02 6.91815791203747e-01 5.09962627721908e-01 -2.58387309352737e-03 +-1.41000000000000e+02 6.76927011005616e-01 5.80929173559367e-01 1.25078923479111e-02 +-1.38000000000000e+02 6.57959749926485e-01 6.54912916084138e-01 2.78036722103928e-02 +-1.35000000000000e+02 6.36953256680495e-01 7.30405250831853e-01 4.32213182447573e-02 +-1.32000000000000e+02 6.15946530568564e-01 8.05898408123014e-01 5.86392271290690e-02 +-1.29000000000000e+02 5.91202311709038e-01 8.79859730223254e-01 7.42120371863231e-02 +-1.26000000000000e+02 5.58983089632388e-01 9.50757374661013e-01 9.00945304458618e-02 +-1.23000000000000e+02 5.26763742046105e-01 1.02165410059611e+00 1.05977334757586e-01 +-1.20000000000000e+02 4.94544331707351e-01 1.09255036729705e+00 1.21860311283846e-01 +-1.17000000000000e+02 4.51251550031352e-01 1.15027637837716e+00 1.36984793751777e-01 +-1.14000000000000e+02 4.07958914685959e-01 1.20800214320170e+00 1.52109035307253e-01 +-1.11000000000000e+02 3.64666615300881e-01 1.26572746703947e+00 1.67232779609297e-01 +-1.08000000000000e+02 3.16124806380124e-01 1.31001514786660e+00 1.80754313543723e-01 +-1.05000000000000e+02 2.64958202719693e-01 1.34758390486677e+00 1.93478045106979e-01 +-1.02000000000000e+02 2.13791585385510e-01 1.38515223136569e+00 2.06201034298060e-01 +-9.90000000000000e+01 1.61712404778857e-01 1.41448412769015e+00 2.17579378110101e-01 +-9.60000000000000e+01 1.07808058099348e-01 1.42734280690261e+00 2.26268358308198e-01 +-9.30000000000000e+01 5.39041000974291e-02 1.44020138788200e+00 2.34956873390276e-01 +-9.00000000000000e+01 3.36430787768757e-07 1.45305991974575e+00 2.43645159242670e-01 +-8.70000000000000e+01 -5.39040449269041e-02 1.44020140104271e+00 2.47370504797659e-01 +-8.40000000000000e+01 -1.07808208827910e-01 1.42734277094688e+00 2.51096140965095e-01 +-8.10000000000000e+01 -1.61711937812911e-01 1.41448423908313e+00 2.54822075502831e-01 +-7.80000000000000e+01 -2.13791337572500e-01 1.38515241331870e+00 2.55274888244729e-01 +-7.50000000000000e+01 -2.64958541234654e-01 1.34758365631669e+00 2.54091230125327e-01 +-7.20000000000000e+01 -3.16124558572532e-01 1.31001532981777e+00 2.52907274609395e-01 +-6.90000000000000e+01 -3.64666240259218e-01 1.26572796711458e+00 2.50475282099874e-01 +-6.60000000000000e+01 -4.07959035740134e-01 1.20800198178982e+00 2.45546802529565e-01 +-6.30000000000000e+01 -4.51251836454270e-01 1.15027599646507e+00 2.40618557245280e-01 +-6.00000000000000e+01 -4.94544544869283e-01 1.09254989825106e+00 2.35690538113475e-01 +-5.70000000000000e+01 -5.26763955208036e-01 1.02165363155013e+00 2.29009342263561e-01 +-5.40000000000000e+01 -5.58983302793074e-01 9.50756905605912e-01 2.22328163344933e-01 +-5.10000000000000e+01 -5.91202524869724e-01 8.79859261168152e-01 2.15646770887959e-01 +-4.80000000000000e+01 -6.17609187893117e-01 8.05904457214662e-01 2.09254779518151e-01 +-4.50000000000000e+01 -6.41109664805937e-01 7.30421122636189e-01 2.03007644172430e-01 +-4.20000000000000e+01 -6.59622394239239e-01 6.54918965123690e-01 1.98342023604304e-01 +-3.90000000000000e+01 -6.77240098048986e-01 5.79843727554838e-01 1.94293653388780e-01 +-3.60000000000000e+01 -6.92396015978899e-01 5.06471062583234e-01 1.92463840058657e-01 +-3.30000000000000e+01 -7.06701742382219e-01 4.35818415197548e-01 1.93734767779497e-01 +-3.00000000000000e+01 -7.21593116705023e-01 3.68030379296879e-01 1.98453590087422e-01 +-2.93939393939394e+01 -7.25013851405679e-01 3.55027024133188e-01 2.00336203048920e-01 +-2.87878787878788e+01 -7.28434586106336e-01 3.42023668969498e-01 2.02218816010418e-01 +-2.81818181818182e+01 -7.31855320806992e-01 3.29020313805808e-01 2.04101428971916e-01 +-2.75757575757576e+01 -7.35700687071979e-01 3.16435173390334e-01 2.06644209454419e-01 +-2.69696969696970e+01 -7.39728053905235e-01 3.04029283243158e-01 2.09469943146406e-01 +-2.63636363636364e+01 -7.43755420738490e-01 2.91623393095983e-01 2.12295676838393e-01 +-2.57575757575758e+01 -7.48155857417494e-01 2.79481029799510e-01 2.15614520779263e-01 +-2.51515151515151e+01 -7.53115811916466e-01 2.67733895360822e-01 2.19672915167868e-01 +-2.45454545454545e+01 -7.58075766415437e-01 2.55986760922134e-01 2.23731309556473e-01 +-2.39393939393939e+01 -7.63184374708742e-01 2.44310701465517e-01 2.27866482494864e-01 +-2.33333333333333e+01 -7.69630895931130e-01 2.33274330608002e-01 2.32692677246016e-01 +-2.27272727272727e+01 -7.76077417153518e-01 2.22237959750487e-01 2.37506340633904e-01 +-2.21212121212121e+01 -7.82523938375906e-01 2.11201588892972e-01 2.42358034603878e-01 +-2.15151515151515e+01 -7.90135337461922e-01 2.00684998703353e-01 2.48462729786897e-01 +-2.09090909090909e+01 -7.98004310296648e-01 1.90298387115310e-01 2.54903342970304e-01 +-2.03030303030303e+01 -8.05878455195337e-01 1.79911775527268e-01 2.61343956153712e-01 +-1.96969696969697e+01 -8.14697917585567e-01 1.69812568423152e-01 2.68837595176999e-01 +-1.90909090909091e+01 -8.24455334435024e-01 1.60000749544382e-01 2.77384200470083e-01 +-1.84848484848485e+01 -8.23371484569383e-01 1.50522208073122e-01 2.74858417075755e-01 +-1.78787878787879e+01 -8.20283137594642e-01 1.41330694311538e-01 2.69517114356924e-01 +-1.72727272727273e+01 -8.16827722657021e-01 1.33081595034303e-01 2.60706462733926e-01 +-1.66666666666667e+01 -8.05487645465897e-01 1.24835482427222e-01 2.43743487370455e-01 +-1.60606060606061e+01 -7.87698090979399e-01 1.16591881249401e-01 2.20110391522602e-01 +-1.54545454545455e+01 -7.70279194203751e-01 1.08379515150144e-01 1.96405027014696e-01 +-1.48484848484848e+01 -7.53095337434051e-01 1.00185501796409e-01 1.72659305608295e-01 +-1.42424242424242e+01 -7.36494264951863e-01 9.20339115415058e-02 1.48824706874429e-01 +-1.36363636363636e+01 -7.20003204011376e-01 8.38888551728098e-02 1.25023839281306e-01 +-1.30303030303030e+01 -7.03596374099641e-01 7.57475802314855e-02 1.01231760751629e-01 +-1.24242424242424e+01 -6.85592076723291e-01 6.76111043119601e-02 7.80448576791677e-02 +-1.18181818181818e+01 -6.67194751585540e-01 5.96056150740760e-02 5.50235291976979e-02 +-1.12121212121212e+01 -6.48063815783503e-01 5.13317377912542e-02 3.23188744507143e-02 +-1.06060606060606e+01 -6.28468277340486e-01 4.31836623215413e-02 9.45993928821119e-03 +-1.00000000000000e+01 -6.08620538268602e-01 3.51540278791994e-02 -1.34796433221792e-02 +-9.39393939393939e+00 -5.88452257587033e-01 2.73199794208228e-02 -3.63905317831286e-02 +-8.78787878787879e+00 -5.62689873667493e-01 2.00084704728355e-02 -5.85506772245690e-02 +-8.18181818181818e+00 -5.26523769001160e-01 1.35978263788546e-02 -7.93058161363485e-02 +-7.57575757575758e+00 -4.55695305492732e-01 1.04092109922848e-02 -9.28284077848926e-02 +-6.96969696969697e+00 -3.69845487410935e-01 8.91871368739218e-03 -1.01630482628221e-01 +-6.36363636363636e+00 -2.93598733915834e-01 7.52845137064097e-03 -1.04647217860029e-01 +-5.75757575757576e+00 -2.18105319246992e-01 7.08800169590747e-03 -1.07214517170429e-01 +-5.15151515151515e+00 -1.43086395099137e-01 6.80050156749210e-03 -1.09441582594168e-01 +-4.54545454545454e+00 -6.85129984815250e-02 6.56750484797770e-03 -1.11442618030446e-01 +-3.93939393939394e+00 5.58385912432804e-03 6.45301670656877e-03 -1.13148191085356e-01 +-3.33333333333333e+00 7.94070262060676e-02 6.41289348325262e-03 -1.14695006520256e-01 +-2.72727272727273e+00 1.53241011838806e-01 6.34203948696765e-03 -1.16207049641120e-01 +-2.12121212121212e+00 2.26643908165568e-01 6.33526268400175e-03 -1.17673564802273e-01 +-1.51515151515152e+00 3.00105384199722e-01 6.33260375138770e-03 -1.19135271104034e-01 +-9.09090909090912e-01 3.73112750667490e-01 6.33272155108629e-03 -1.20666056314306e-01 +-3.03030303030302e-01 4.45821550130321e-01 6.37447853784405e-03 -1.22082515446199e-01 + 3.03030303030302e-01 5.18490342544224e-01 6.43313505799646e-03 -1.23487187085283e-01 + 9.09090909090912e-01 5.90981181373800e-01 6.43182319665414e-03 -1.24792255974836e-01 + 1.51515151515152e+00 6.63194082651710e-01 6.52639345810673e-03 -1.25965661272832e-01 + 2.12121212121212e+00 7.35342582721669e-01 6.56033089540737e-03 -1.27200682447364e-01 + 2.72727272727273e+00 8.07087488554538e-01 6.68351242329311e-03 -1.28376340413356e-01 + 3.33333333333333e+00 8.78653932202791e-01 6.80603711634661e-03 -1.29410676299065e-01 + 3.93939393939394e+00 9.49821767187520e-01 6.92963005547727e-03 -1.30468108847082e-01 + 4.54545454545455e+00 1.02040859265783e+00 7.05596856935910e-03 -1.31334420191275e-01 + 5.15151515151515e+00 1.09057426257294e+00 7.21258284329372e-03 -1.32167739152710e-01 + 5.75757575757576e+00 1.15956993076019e+00 7.50770133128459e-03 -1.32829150435812e-01 + 6.36363636363637e+00 1.22598231576016e+00 8.00921749308073e-03 -1.33054200393040e-01 + 6.96969696969697e+00 1.28698208452707e+00 8.95907167395873e-03 -1.32588516874154e-01 + 7.57575757575757e+00 1.33798080221868e+00 1.07198763892550e-02 -1.30460457192223e-01 + 8.18181818181818e+00 1.38474488602779e+00 1.24584314382430e-02 -1.27836892595172e-01 + 8.78787878787879e+00 1.43030567824273e+00 1.40331639261087e-02 -1.25090100383291e-01 + 9.39393939393939e+00 1.47200490845414e+00 1.59305690309036e-02 -1.22289478404177e-01 + 1.00000000000000e+01 1.50215101421504e+00 1.79091658579838e-02 -1.21813999638841e-01 + 1.06060606060606e+01 1.52370646388859e+00 2.02673536853439e-02 -1.21708944902389e-01 + 1.12121212121212e+01 1.54059319776331e+00 2.29572858937563e-02 -1.21848482617505e-01 + 1.18181818181818e+01 1.55195059906285e+00 3.24577496194005e-02 -1.22761051253168e-01 + 1.24242424242424e+01 1.52438898981163e+00 4.81678475665162e-02 -1.24233830041100e-01 + 1.30303030303030e+01 1.48202855383678e+00 6.38795341948320e-02 -1.25730475238576e-01 + 1.36363636363636e+01 1.42634733955077e+00 7.98865843582198e-02 -1.27696791571033e-01 + 1.42424242424242e+01 1.37740933666151e+00 9.28335727033232e-02 -1.29317173288097e-01 + 1.48484848484848e+01 1.33848755611934e+00 1.01192691262027e-01 -1.30420940714982e-01 + 1.54545454545455e+01 1.31190755280546e+00 1.09441241406769e-01 -1.31424351641477e-01 + 1.60606060606061e+01 1.28938235719693e+00 1.17642799704135e-01 -1.32380797174879e-01 + 1.66666666666667e+01 1.26634018563845e+00 1.25753041098846e-01 -1.33237196626024e-01 + 1.72727272727273e+01 1.23834102937778e+00 1.33971665700699e-01 -1.34168012171228e-01 + 1.78787878787879e+01 1.20427767029161e+00 1.42322760041168e-01 -1.35189926091386e-01 + 1.84848484848485e+01 1.18799320204888e+00 1.50716604683360e-01 -1.36311946607811e-01 + 1.90909090909091e+01 1.17586795447335e+00 1.59325448714249e-01 -1.38145765919180e-01 + 1.96969696969697e+01 1.16211889516567e+00 1.69092448832339e-01 -1.43872565373133e-01 + 2.03030303030303e+01 1.14927412966545e+00 1.79265230696872e-01 -1.50302804965374e-01 + 2.09090909090909e+01 1.13814235040425e+00 1.89843817264378e-01 -1.57438574430759e-01 + 2.15151515151515e+01 1.12766323714321e+00 2.00422403831884e-01 -1.64574965529124e-01 + 2.21212121212121e+01 1.11706175944146e+00 2.11099174825611e-01 -1.71481480893725e-01 + 2.27272727272727e+01 1.10811964282661e+00 2.22168582499681e-01 -1.77468729848466e-01 + 2.33333333333333e+01 1.09917752621176e+00 2.33237990173751e-01 -1.83456509220763e-01 + 2.39393939393939e+01 1.09023540959691e+00 2.44307397847821e-01 -1.89446318845786e-01 + 2.45454545454545e+01 1.08296339319592e+00 2.55986760922134e-01 -1.94609075142135e-01 + 2.51515151515151e+01 1.07587693949360e+00 2.67733895360822e-01 -1.99679830094226e-01 + 2.57575757575758e+01 1.06879048579128e+00 2.79481029799510e-01 -2.04750458453214e-01 + 2.63636363636364e+01 1.06250432210796e+00 2.91623393095983e-01 -2.09443081756152e-01 + 2.69696969696970e+01 1.05675176801362e+00 3.04029283243158e-01 -2.13883658690320e-01 + 2.75757575757576e+01 1.05099921391928e+00 3.16435173390334e-01 -2.18324155845132e-01 + 2.81818181818182e+01 1.04550641150444e+00 3.29020313805808e-01 -2.22633305796399e-01 + 2.87878787878788e+01 1.04061964435123e+00 3.42023668969498e-01 -2.26636130753221e-01 + 2.93939393939394e+01 1.03573287719801e+00 3.55027024133188e-01 -2.30638903172504e-01 + 3.00000000000000e+01 1.03084611004479e+00 3.68030379296879e-01 -2.34641622610226e-01 + 3.30000000000000e+01 1.00957720103222e+00 4.35818415197548e-01 -2.52554076744310e-01 + 3.60000000000000e+01 9.89136784047915e-01 5.06471062583234e-01 -2.69189950621486e-01 + 3.90000000000000e+01 9.67485857943026e-01 5.79843727554838e-01 -2.84796609339440e-01 + 4.20000000000000e+01 9.42317581833575e-01 6.54918965123690e-01 -2.99708632363911e-01 + 4.50000000000000e+01 9.15871274073578e-01 7.30421122636189e-01 -3.14427587661614e-01 + 4.80000000000000e+01 8.82298905466505e-01 8.05904457214662e-01 -3.28546217819211e-01 + 5.10000000000000e+01 8.44574853445087e-01 8.79859261168152e-01 -3.42409667613951e-01 + 5.40000000000000e+01 7.98547167692681e-01 9.50756905605912e-01 -3.55762881953981e-01 + 5.70000000000000e+01 7.52519428332893e-01 1.02165363155013e+00 -3.69115906506285e-01 + 6.00000000000000e+01 7.06491662169616e-01 1.09254989825106e+00 -3.82468805440661e-01 + 6.30000000000000e+01 6.44645585302091e-01 1.15027599646507e+00 -3.94568162072562e-01 + 6.60000000000000e+01 5.82799184406010e-01 1.20800198178982e+00 -4.06667464188502e-01 + 6.90000000000000e+01 5.20952406629315e-01 1.26572796711458e+00 -4.18766708415905e-01 + 7.20000000000000e+01 4.51606840984605e-01 1.31001532981777e+00 -4.29653737684229e-01 + 7.50000000000000e+01 3.78512034916063e-01 1.34758365631669e+00 -4.39934681615426e-01 + 7.80000000000000e+01 3.05416356557281e-01 1.38515241331870e+00 -4.50215120171697e-01 + 8.10000000000000e+01 2.31017478817704e-01 1.41448423908313e+00 -4.59650318443595e-01 + 8.40000000000000e+01 1.54012292275277e-01 1.42734277094688e+00 -4.67395115002369e-01 + 8.70000000000000e+01 7.70061458096371e-02 1.44020140104271e+00 -4.75139563653944e-01 + 9.00000000000000e+01 -3.36430788002270e-07 1.45305991974575e+00 -4.82883809780470e-01 + 9.30000000000000e+01 -5.39041000974291e-02 1.44020138788200e+00 -4.86608736540749e-01 + 9.60000000000000e+01 -1.07808058099348e-01 1.42734280690261e+00 -4.90252008054739e-01 + 9.90000000000000e+01 -1.61712404778857e-01 1.41448412769015e+00 -4.93892480524254e-01 + 1.02000000000000e+02 -2.13791585385510e-01 1.38515223136569e+00 -4.94260121211006e-01 + 1.05000000000000e+02 -2.64958202719694e-01 1.34758390486677e+00 -4.92991191870403e-01 + 1.08000000000000e+02 -3.16124806380124e-01 1.31001514786660e+00 -4.91810583583353e-01 + 1.11000000000000e+02 -3.64666615300881e-01 1.26572746703946e+00 -4.89432902349955e-01 + 1.14000000000000e+02 -4.07958914685959e-01 1.20800214320170e+00 -4.84556213718753e-01 + 1.17000000000000e+02 -4.51251550031352e-01 1.15027637837716e+00 -4.79679087834588e-01 + 1.20000000000000e+02 -4.94544331707352e-01 1.09255036729705e+00 -4.74801739879191e-01 + 1.23000000000000e+02 -5.26763742046105e-01 1.02165410059611e+00 -4.68166345460196e-01 + 1.26000000000000e+02 -5.58983089632388e-01 9.50757374661013e-01 -4.61530902688578e-01 + 1.29000000000000e+02 -5.91202311709038e-01 8.79859730223253e-01 -4.54866722642821e-01 + 1.32000000000000e+02 -6.15946530568564e-01 8.05898408123014e-01 -4.48999508288356e-01 + 1.35000000000000e+02 -6.36953256680495e-01 7.30405250831853e-01 -4.43540325890876e-01 + 1.38000000000000e+02 -6.57959749926485e-01 6.54912916084137e-01 -4.38080640740675e-01 + 1.41000000000000e+02 -6.76927011005616e-01 5.80929173559366e-01 -4.34763066576705e-01 + 1.44000000000000e+02 -6.91815791203747e-01 5.09962627721908e-01 -4.35729731767291e-01 + 1.47000000000000e+02 -7.06704434537952e-01 4.38996595677444e-01 -4.36696394806281e-01 + 1.50000000000000e+02 -7.21593009442639e-01 3.68030820520304e-01 -4.37663056769512e-01 + 1.53000000000000e+02 -7.45653551873146e-01 3.10460824874659e-01 -4.59043940512908e-01 + 1.56000000000000e+02 -7.69677114596338e-01 2.52890877728508e-01 -4.79978567205265e-01 + 1.59000000000000e+02 -7.93695164530012e-01 1.95320965150743e-01 -5.01585589518735e-01 + 1.62000000000000e+02 -7.33817088309609e-01 1.57056754662604e-01 -5.07101903167502e-01 + 1.65000000000000e+02 -6.31982311416204e-01 1.28445558491906e-01 -5.04439049525879e-01 + 1.68000000000000e+02 -5.30148101457015e-01 9.98340901844233e-02 -5.01775628100030e-01 + 1.71000000000000e+02 -4.16032857149841e-01 7.26838423842623e-02 -4.50000513056908e-01 + 1.74000000000000e+02 -2.77354970782234e-01 4.84561038187240e-02 -2.99999717902353e-01 + 1.77000000000000e+02 -1.38045242443721e-01 3.97799508651227e-02 -7.34244952105506e-02 + 1.80000000000000e+02 0.00000000000000e+00 3.88896555692602e-02 1.88439381768847e-01 diff --git a/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_26.dat b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_26.dat new file mode 100644 index 00000000..dbffc457 --- /dev/null +++ b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_26.dat @@ -0,0 +1,254 @@ +! ------------ AirfoilInfo v1.01.x Input File ---------------------------------- +! AeroElasticSE FAST driver +! line +! line +! ------------------------------------------------------------------------------ +DEFAULT InterpOrd ! Interpolation order to use for quasi-steady table lookup {1=linear; 3=cubic spline; "default"} [default=3] +1 NonDimArea ! The non-dimensional area of the airfoil (area/chord^2) (set to 1.0 if unsure or unneeded) +@"NREL-2p8-127_AF26_Coords.txt" NumCoords ! The number of coordinates in the airfoil shape file. Set to zero if coordinates not included. +AF26_BL.txt BL_file ! The file name including the boundary layer characteristics of the profile. Ignored if the aeroacoustic module is not called. +1 NumTabs ! Number of airfoil tables in this file. Each table must have lines for Re and Ctrl. +! ------------------------------------------------------------------------------ +! data for table 1 +! ------------------------------------------------------------------------------ +6.000000 Re ! Reynolds number in millions +0 Ctrl ! Control setting (must be 0 for current AirfoilInfo) +True InclUAdata ! Is unsteady aerodynamics data included in this table? If TRUE, then include 30 UA coefficients below this line +!........................................ +-4.024504 alpha0 ! 0-lift angle of attack, depends on airfoil. +11.306876 alpha1 ! Angle of attack at f=0.7, (approximately the stall angle) for AOA>alpha0. (deg) +-9.832558 alpha2 ! Angle of attack at f=0.7, (approximately the stall angle) for AOA1] +0.000000 S2 ! Constant in the f curve best-fit for AOA> alpha1; by definition it depends on the airfoil. [ignored if UAMod<>1] +0.000000 S3 ! Constant in the f curve best-fit for alpha2<=AOA< alpha0; by definition it depends on the airfoil. [ignored if UAMod<>1] +0.000000 S4 ! Constant in the f curve best-fit for AOA< alpha2; by definition it depends on the airfoil. [ignored if UAMod<>1] +1.557234 Cn1 ! Critical value of C0n at leading edge separation. It should be extracted from airfoil data at a given Mach and Reynolds number. It can be calculated from the static value of Cn at either the break in the pitching moment or the loss of chord force at the onset of stall. It is close to the condition of maximum lift of the airfoil at low Mach numbers. +-0.830241 Cn2 ! As Cn1 for negative AOAs. +Default St_sh ! Strouhal's shedding frequency constant. [default = 0.19] +0.006417 Cd0 ! 2D drag coefficient value at 0-lift. +-0.112920 Cm0 ! 2D pitching moment coefficient about 1/4-chord location, at 0-lift, positive if nose up. [If the aerodynamics coefficients table does not include a column for Cm, this needs to be set to 0.0] +0.000000 k0 ! Constant in the \hat(x)_cp curve best-fit; = (\hat(x)_AC-0.25). [ignored if UAMod<>1] +0.000000 k1 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k2 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k3 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k1_hat ! Constant in the expression of Cc due to leading edge vortex effects. [ignored if UAMod<>1] +Default x_cp_bar ! Constant in the expression of \hat(x)_cp^v. [ignored if UAMod<>1, default = 0.2] +Default UACutout ! Angle of attack above which unsteady aerodynamics are disabled (deg). [Specifying the string "Default" sets UACutout to 45 degrees] +Default filtCutOff ! Cut-off frequency (-3 dB corner frequency) for low-pass filtering the AoA input to UA, as well as the 1st and 2nd derivatives (Hz) [default = 20] +!........................................ +! Table of aerodynamics coefficients +200 NumAlf ! Number of data lines in the following table +! Alpha Cl Cd Cm +! (deg) (-) (-) (-) +-1.80000000000000e+02 0.00000000000000e+00 3.76960235595695e-02 1.99999773877240e-01 +-1.77000000000000e+02 1.49471735352601e-01 3.76960235595695e-02 1.99999908932130e-01 +-1.74000000000000e+02 3.00312823771888e-01 4.52351857356452e-02 2.39999774321882e-01 +-1.71000000000000e+02 4.50470172837611e-01 6.78529197680463e-02 3.60000410445527e-01 +-1.68000000000000e+02 5.62141155839517e-01 9.47828831363562e-02 3.00100260054970e-01 +-1.65000000000000e+02 6.54569405002126e-01 1.23868910842549e-01 1.50251816114612e-01 +-1.62000000000000e+02 7.46998713314856e-01 1.52955271849131e-01 4.01655036174478e-04 +-1.59000000000000e+02 7.99786871669241e-01 1.91656566827607e-01 -9.28122671239639e-02 +-1.56000000000000e+02 7.73294071101042e-01 2.49587404486670e-01 -7.27556273551054e-02 +-1.53000000000000e+02 7.46801068143765e-01 3.07518284704543e-01 -5.26992343631414e-02 +-1.50000000000000e+02 7.20307991381284e-01 3.65449216784473e-01 -3.26429713183966e-02 +-1.47000000000000e+02 7.05570279118452e-01 4.36504377442686e-01 -1.75932612156202e-02 +-1.44000000000000e+02 6.90832510562523e-01 5.07559809506317e-01 -2.54349362777964e-03 +-1.41000000000000e+02 6.76094629416376e-01 5.78615784400165e-01 1.25063869759018e-02 +-1.38000000000000e+02 6.57241681367617e-01 6.52702801625277e-01 2.78005506087723e-02 +-1.35000000000000e+02 6.36331208215415e-01 7.28305333867222e-01 4.32168556727977e-02 +-1.32000000000000e+02 6.15420495447980e-01 8.03908732446007e-01 5.86333373939491e-02 +-1.29000000000000e+02 5.90761768946044e-01 8.77986125240427e-01 7.42048196933668e-02 +-1.26000000000000e+02 5.58606997203396e-01 9.49011499212308e-01 9.00863038811510e-02 +-1.23000000000000e+02 5.26452071104699e-01 1.02003593058481e+00 1.05968066745090e-01 +-1.20000000000000e+02 4.94297067830864e-01 1.09105989067524e+00 1.21849968941896e-01 +-1.17000000000000e+02 4.51046459413193e-01 1.14892722035528e+00 1.36973650595313e-01 +-1.14000000000000e+02 4.07795994504977e-01 1.20679430326659e+00 1.52097072994041e-01 +-1.11000000000000e+02 3.64545860001903e-01 1.26466094411154e+00 1.67219979864857e-01 +-1.08000000000000e+02 3.16034194150131e-01 1.30909602388533e+00 1.80733002070115e-01 +-1.05000000000000e+02 2.64891722560637e-01 1.34681522084817e+00 1.93441069750703e-01 +-1.02000000000000e+02 2.13749237020859e-01 1.38453398558587e+00 2.06148391816051e-01 +-9.90000000000000e+01 1.61688764627702e-01 1.41401796960994e+00 2.17512374667702e-01 +-9.60000000000000e+01 1.07792278764948e-01 1.42703203551508e+00 2.26189620904871e-01 +-9.30000000000000e+01 5.38962046405121e-02 1.44004600200010e+00 2.34866400852709e-01 +-9.00000000000000e+01 3.36381509980986e-07 1.45305991877594e+00 2.43542947660101e-01 +-8.70000000000000e+01 -5.38961494780680e-02 1.44004601531985e+00 2.47180800161873e-01 +-8.40000000000000e+01 -1.07792429471529e-01 1.42703199912486e+00 2.50818607319856e-01 +-8.10000000000000e+01 -1.61688297729853e-01 1.41401808234901e+00 2.54456386687213e-01 +-7.80000000000000e+01 -2.13748989324725e-01 1.38453416826749e+00 2.54821414135407e-01 +-7.50000000000000e+01 -2.64892060915943e-01 1.34681497130280e+00 2.53550009143848e-01 +-7.20000000000000e+01 -3.16033946459415e-01 1.30909620656510e+00 2.52278018725637e-01 +-6.90000000000000e+01 -3.64545485325515e-01 1.26466144541088e+00 2.49759250841147e-01 +-6.60000000000000e+01 -4.07796115441250e-01 1.20679414145955e+00 2.44746825927138e-01 +-6.30000000000000e+01 -4.51046745557096e-01 1.14892683750823e+00 2.39734401012678e-01 +-6.00000000000000e+01 -4.94297280566681e-01 1.09105942078444e+00 2.34721961096712e-01 +-5.70000000000000e+01 -5.26452283840516e-01 1.02003546069401e+00 2.27959404332693e-01 +-5.40000000000000e+01 -5.58607209937681e-01 9.49011029312154e-01 2.21196621737505e-01 +-5.10000000000000e+01 -5.90761981680330e-01 8.77985655340273e-01 2.14433387476536e-01 +-4.80000000000000e+01 -6.17089681519895e-01 8.03911609903610e-01 2.07957006233653e-01 +-4.50000000000000e+01 -6.40503939057214e-01 7.28313277731023e-01 2.01624046889681e-01 +-4.20000000000000e+01 -6.58910854376636e-01 6.52705679055557e-01 1.96862418589880e-01 +-3.90000000000000e+01 -6.76417043986716e-01 5.77527415759156e-01 1.92714525781683e-01 +-3.60000000000000e+01 -6.91442145788392e-01 5.04059407890188e-01 1.90773036499847e-01 +-3.30000000000000e+01 -7.05593980685524e-01 4.33318752640849e-01 1.91909028051921e-01 +-3.00000000000000e+01 -7.20308097407842e-01 3.65448775028654e-01 1.96465078139101e-01 +-2.93939393939394e+01 -7.23687148982083e-01 3.52430142214952e-01 1.98306875240709e-01 +-2.87878787878788e+01 -7.27066200556324e-01 3.39411509401249e-01 2.00148672342317e-01 +-2.81818181818182e+01 -7.30445252130566e-01 3.26392876587547e-01 2.01990469443925e-01 +-2.75757575757576e+01 -7.34245004132877e-01 3.13793130446363e-01 2.04486479544941e-01 +-2.69696969696970e+01 -7.38225071786241e-01 3.01372922565738e-01 2.07262890698687e-01 +-2.63636363636364e+01 -7.42205139439605e-01 2.88952714685113e-01 2.10039301852433e-01 +-2.57575757575758e+01 -7.46555494689374e-01 2.76796428164473e-01 2.13304205864706e-01 +-2.51515151515151e+01 -7.51461195033535e-01 2.65035962173593e-01 2.17301735315320e-01 +-2.45454545454545e+01 -7.56366895377697e-01 2.53275496182714e-01 2.21299264765933e-01 +-2.39393939393939e+01 -7.61408712929841e-01 2.41586724908869e-01 2.25459999520073e-01 +-2.33333333333333e+01 -7.67675611706775e-01 2.30543219968779e-01 2.31089613603274e-01 +-2.27272727272727e+01 -7.73942510483708e-01 2.19499715028689e-01 2.36719227686470e-01 +-2.21212121212121e+01 -7.80209409260641e-01 2.08456210088599e-01 2.42348842244097e-01 +-2.15151515151515e+01 -7.88045843131190e-01 1.98028913518013e-01 2.49772937268922e-01 +-2.09090909090909e+01 -7.96274761734597e-01 1.87755708677063e-01 2.57645768551195e-01 +-2.03030303030303e+01 -8.04503680338007e-01 1.77482503836112e-01 2.65518599833468e-01 +-1.96969696969697e+01 -8.13721581766036e-01 1.67514312390042e-01 2.74509055953088e-01 +-1.90909090909091e+01 -8.23928410071538e-01 1.57851117084127e-01 2.84617073685583e-01 +-1.84848484848485e+01 -8.22646776262130e-01 1.48546940538688e-01 2.82973389715262e-01 +-1.78787878787879e+01 -8.19241192016627e-01 1.39555178352410e-01 2.78335523489406e-01 +-1.72727272727273e+01 -8.15446589363820e-01 1.31559887902139e-01 2.70012950129364e-01 +-1.66666666666667e+01 -8.03296483777369e-01 1.23564597452339e-01 2.53038201146750e-01 +-1.60606060606061e+01 -7.84310128533453e-01 1.15569307002924e-01 2.28984472824905e-01 +-1.54545454545455e+01 -7.65324759977866e-01 1.07574974865435e-01 2.04931438081052e-01 +-1.48484848484848e+01 -7.46339081540475e-01 9.95804834752580e-02 1.80878286802668e-01 +-1.42424242424242e+01 -7.27352144425903e-01 9.15851948410960e-02 1.56824554692099e-01 +-1.36363636363636e+01 -7.08366589041831e-01 8.35901811716822e-02 1.32771649802369e-01 +-1.30303030303030e+01 -6.89379329405081e-01 7.55946407967314e-02 1.08716220908226e-01 +-1.24242424242424e+01 -6.70394070681262e-01 6.75996503421858e-02 8.46633366461469e-02 +-1.18181818181818e+01 -6.51407025524249e-01 5.96041815994357e-02 6.06090692018439e-02 +-1.12121212121212e+01 -6.32421761536482e-01 5.16093484929349e-02 3.65561615953677e-02 +-1.06060606060606e+01 -6.13435225841655e-01 4.36139224210943e-02 1.25016108288645e-02 +-1.00000000000000e+01 -5.94449142982321e-01 3.56199339544178e-02 -1.15512079994493e-02 +-9.39393939393939e+00 -5.75463842145924e-01 2.76249494874552e-02 -3.56050262327576e-02 +-8.78787878787879e+00 -5.51403957680999e-01 2.01382266354268e-02 -5.87079502546054e-02 +-8.18181818181818e+00 -5.17926474912583e-01 1.35966762681344e-02 -8.00434679031281e-02 +-7.57575757575758e+00 -4.48013073952105e-01 1.04062079021587e-02 -9.38202181483299e-02 +-6.96969696969697e+00 -3.62306704515139e-01 8.91516259682469e-03 -1.02639355883834e-01 +-6.36363636363636e+00 -2.86592646559465e-01 7.49092009640339e-03 -1.05345389259135e-01 +-5.75757575757576e+00 -2.11681427543666e-01 7.05454354406601e-03 -1.07624248784689e-01 +-5.15151515151515e+00 -1.37278368249321e-01 6.76061495526902e-03 -1.09615083165669e-01 +-4.54545454545454e+00 -6.32446849221684e-02 6.51817990062387e-03 -1.11463657718864e-01 +-3.93939393939394e+00 1.03326039502837e-02 6.40000102450966e-03 -1.13157562089362e-01 +-3.33333333333333e+00 8.37357402666289e-02 6.36666345248257e-03 -1.14700049263230e-01 +-2.72727272727273e+00 1.57144890016423e-01 6.30000080854981e-03 -1.16209080405868e-01 +-2.12121212121212e+00 2.30132013733438e-01 6.30000067359949e-03 -1.17633366714045e-01 +-1.51515151515152e+00 3.03270133033896e-01 6.30000062134854e-03 -1.18966679175655e-01 +-9.09090909090912e-01 3.76007831012725e-01 6.30000062466049e-03 -1.20399983368341e-01 +-3.03030303030302e-01 4.48619593833060e-01 6.33939706788298e-03 -1.21733367482865e-01 + 3.03030303030302e-01 5.21162110305859e-01 6.40000063237506e-03 -1.23066648228140e-01 + 9.09090909090912e-01 5.93482962845902e-01 6.40000060506645e-03 -1.24318211551559e-01 + 1.51515151515152e+00 6.65499465508473e-01 6.50000049630823e-03 -1.25430305714767e-01 + 2.12121212121212e+00 7.37449721921112e-01 6.52424015611961e-03 -1.26642406027256e-01 + 2.72727272727273e+00 8.08982255779155e-01 6.64545608432346e-03 -1.27809109728731e-01 + 3.33333333333333e+00 8.80397540133069e-01 6.76666331848451e-03 -1.28833312226978e-01 + 3.93939393939394e+00 9.51421795343730e-01 6.88788064407856e-03 -1.29890930275742e-01 + 4.54545454545455e+00 1.02186277965824e+00 7.00909038513147e-03 -1.30763637928484e-01 + 5.15151515151515e+00 1.09189625174699e+00 7.16061521492726e-03 -1.31612160993914e-01 + 5.75757575757576e+00 1.16079950494080e+00 7.45454396592225e-03 -1.32306067865226e-01 + 6.36363636363637e+00 1.22720136736217e+00 7.96365014632842e-03 -1.32572739637886e-01 + 6.96969696969697e+00 1.28802461132675e+00 8.94546191359972e-03 -1.32130308376179e-01 + 7.57575757575757e+00 1.33932328366435e+00 1.07272367904880e-02 -1.30081875964063e-01 + 8.18181818181818e+00 1.38679182149843e+00 1.25091238234984e-02 -1.27572684159305e-01 + 8.78787878787879e+00 1.43442621343129e+00 1.40333059500536e-02 -1.25090961368079e-01 + 9.39393939393939e+00 1.48072468189907e+00 1.53666957749600e-02 -1.22230263597817e-01 + 1.00000000000000e+01 1.51619948622988e+00 1.65000203201040e-02 -1.21700002321685e-01 + 1.06060606060606e+01 1.54652613869201e+00 1.81605911900563e-02 -1.21700000182581e-01 + 1.12121212121212e+01 1.57015106631391e+00 2.03485522545774e-02 -1.21912123883377e-01 + 1.18181818181818e+01 1.58466270949876e+00 3.00903977018941e-02 -1.23218106611257e-01 + 1.24242424242424e+01 1.55439005671114e+00 4.64546703161752e-02 -1.25157568402582e-01 + 1.30303030303030e+01 1.50697011272490e+00 6.28179584205508e-02 -1.27096913764242e-01 + 1.36363636363636e+01 1.44636122440245e+00 7.91823777231142e-02 -1.29036401923583e-01 + 1.42424242424242e+01 1.39302933029550e+00 9.22728672271796e-02 -1.30587869102437e-01 + 1.48484848484848e+01 1.35060444483994e+00 1.00454826054870e-01 -1.31557584992825e-01 + 1.54545454545455e+01 1.32181783503487e+00 1.08636431096634e-01 -1.32527257164245e-01 + 1.60606060606061e+01 1.29757628829158e+00 1.16817964892734e-01 -1.33496920105626e-01 + 1.66666666666667e+01 1.27333348139179e+00 1.24999918769171e-01 -1.34466631124069e-01 + 1.72727272727273e+01 1.24363607861721e+00 1.33181874793555e-01 -1.35436343590531e-01 + 1.78787878787879e+01 1.20727187838534e+00 1.41363833443233e-01 -1.36406057826813e-01 + 1.84848484848485e+01 1.18992975180798e+00 1.49497904111867e-01 -1.37375729577547e-01 + 1.90909090909091e+01 1.17704327758037e+00 1.57851104306908e-01 -1.39089566615125e-01 + 1.96969696969697e+01 1.16246123156071e+00 1.67514298578136e-01 -1.45021783264679e-01 + 2.03030303030303e+01 1.14929279501434e+00 1.77482491349607e-01 -1.51632325921770e-01 + 2.09090909090909e+01 1.13753806488326e+00 1.87755699876179e-01 -1.58921232961736e-01 + 2.15151515151515e+01 1.12578334814572e+00 1.98028908402751e-01 -1.66210140001703e-01 + 2.21212121212121e+01 1.11458879313232e+00 2.08456208053037e-01 -1.73224589305943e-01 + 2.27272727272727e+01 1.10563435435787e+00 2.19499713649760e-01 -1.79141490064069e-01 + 2.33333333333333e+01 1.09667991558342e+00 2.30543219246483e-01 -1.85058390822194e-01 + 2.39393939393939e+01 1.08772547680897e+00 2.41586724843207e-01 -1.90975291580320e-01 + 2.45454545454545e+01 1.08052192847356e+00 2.53275496182714e-01 -1.96074563757929e-01 + 2.51515151515151e+01 1.07351291933540e+00 2.65035962173593e-01 -2.01082990269719e-01 + 2.57575757575758e+01 1.06650391019725e+00 2.76796428164473e-01 -2.06091416781509e-01 + 2.63636363636364e+01 1.06028929009176e+00 2.88952714685113e-01 -2.10729582407184e-01 + 2.69696969696970e+01 1.05460434497302e+00 3.01372922565738e-01 -2.15120869083270e-01 + 2.75757575757576e+01 1.04891939985428e+00 3.13793130446363e-01 -2.19512155759356e-01 + 2.81818181818182e+01 1.04349178876274e+00 3.26392876587547e-01 -2.23774943907361e-01 + 2.87878787878788e+01 1.03866457222799e+00 3.39411509401249e-01 -2.27737927876115e-01 + 2.93939393939394e+01 1.03383735569325e+00 3.52430142214952e-01 -2.31700911844869e-01 + 3.00000000000000e+01 1.02901013915851e+00 3.65448775028654e-01 -2.35663895813623e-01 + 3.30000000000000e+01 1.00799497239599e+00 4.33318752640849e-01 -2.53423032735973e-01 + 3.60000000000000e+01 9.87774208309456e-01 5.04059407890188e-01 -2.69936839647807e-01 + 3.90000000000000e+01 9.66310062840480e-01 5.77527415759156e-01 -2.85448460530465e-01 + 4.20000000000000e+01 9.41301077680331e-01 6.52705679055557e-01 -3.00284956735113e-01 + 4.50000000000000e+01 9.15005912938840e-01 7.28313277731023e-01 -3.14934033957096e-01 + 4.80000000000000e+01 8.81556716458514e-01 8.03911609903610e-01 -3.28999148408511e-01 + 5.10000000000000e+01 8.43945459545643e-01 8.77985655340274e-01 -3.42814120520528e-01 + 5.40000000000000e+01 7.98009814198267e-01 9.49011029312154e-01 -3.56128791872664e-01 + 5.70000000000000e+01 7.52074119773438e-01 1.02003546069401e+00 -3.69443361508008e-01 + 6.00000000000000e+01 7.06138400810069e-01 1.09105942078444e+00 -3.82757880285344e-01 + 6.30000000000000e+01 6.44352607936286e-01 1.14892683750823e+00 -3.94831155449636e-01 + 6.60000000000000e+01 5.82566479201223e-01 1.20679414145955e+00 -4.06904419974219e-01 + 6.90000000000000e+01 5.20779950464649e-01 1.26466144541088e+00 -4.18977684498238e-01 + 7.20000000000000e+01 4.51477437795751e-01 1.30909620656510e+00 -4.29844047643928e-01 + 7.50000000000000e+01 3.78417087022892e-01 1.34681497130280e+00 -4.40106984807332e-01 + 7.80000000000000e+01 3.05355899035943e-01 1.38453416826749e+00 -4.50369439573171e-01 + 8.10000000000000e+01 2.30983768185259e-01 1.41401808234901e+00 -4.59788640889162e-01 + 8.40000000000000e+01 1.53989842100278e-01 1.42703199912486e+00 -4.67521393514335e-01 + 8.70000000000000e+01 7.69949278241990e-02 1.44004601531985e+00 -4.75253805212904e-01 + 9.00000000000000e+01 -3.36381510214729e-07 1.45305991877594e+00 -4.82986020891325e-01 + 9.30000000000000e+01 -5.38962046405121e-02 1.44004600200010e+00 -4.86623800258682e-01 + 9.60000000000000e+01 -1.07792278764948e-01 1.42703203551508e+00 -4.90261391797100e-01 + 9.90000000000000e+01 -1.61688764627702e-01 1.41401796960994e+00 -4.93898611078009e-01 + 1.02000000000000e+02 -2.13749237020859e-01 1.38453398558587e+00 -4.94263399100741e-01 + 1.05000000000000e+02 -2.64891722560637e-01 1.34681522084817e+00 -4.92992006930170e-01 + 1.08000000000000e+02 -3.16034194150131e-01 1.30909602388533e+00 -4.91720002039579e-01 + 1.11000000000000e+02 -3.64545860001904e-01 1.26466094411154e+00 -4.89201398052675e-01 + 1.14000000000000e+02 -4.07795994504977e-01 1.20679430326659e+00 -4.84189631673154e-01 + 1.17000000000000e+02 -4.51046459413193e-01 1.14892722035528e+00 -4.79177427008757e-01 + 1.20000000000000e+02 -4.94297067830864e-01 1.09105989067524e+00 -4.74164999771467e-01 + 1.23000000000000e+02 -5.26452071104699e-01 1.02003593058481e+00 -4.67401844027926e-01 + 1.26000000000000e+02 -5.58606997203396e-01 9.49011499212308e-01 -4.60638662451069e-01 + 1.29000000000000e+02 -5.90761768946045e-01 8.77986125240427e-01 -4.53875428596403e-01 + 1.32000000000000e+02 -6.15420495447981e-01 8.03908732446007e-01 -4.47922999380913e-01 + 1.35000000000000e+02 -6.36331208215415e-01 7.28305333867222e-01 -4.42375971721764e-01 + 1.38000000000000e+02 -6.57241681367618e-01 6.52702801625276e-01 -4.36828407635875e-01 + 1.41000000000000e+02 -6.76094629416376e-01 5.78615784400164e-01 -4.33407828184422e-01 + 1.44000000000000e+02 -6.90832510562523e-01 5.07559809506317e-01 -4.34241235261194e-01 + 1.47000000000000e+02 -7.05570279118452e-01 4.36504377442686e-01 -4.35074635971279e-01 + 1.50000000000000e+02 -7.20307991381284e-01 3.65449216784472e-01 -4.35908033498135e-01 + 1.53000000000000e+02 -7.46801056114916e-01 3.07518286202364e-01 -4.57805090339867e-01 + 1.56000000000000e+02 -7.73294047043302e-01 2.49587407482254e-01 -4.79701903131578e-01 + 1.59000000000000e+02 -7.99786835582591e-01 1.91656571320831e-01 -5.01598162643685e-01 + 1.62000000000000e+02 -7.40790686340429e-01 1.53560875453361e-01 -5.07117800599876e-01 + 1.65000000000000e+02 -6.39049345205277e-01 1.25382917483086e-01 -5.04448986449598e-01 + 1.68000000000000e+02 -5.37308569933658e-01 9.72046824115369e-02 -5.01779602888075e-01 + 1.71000000000000e+02 -4.22533354527340e-01 7.05773220395183e-02 -4.50000513056908e-01 + 1.74000000000000e+02 -2.81688650312917e-01 4.70517834722228e-02 -2.99999717902353e-01 + 1.77000000000000e+02 -1.40202209005507e-01 3.86002803503690e-02 -6.87687043373218e-02 + 1.80000000000000e+02 0.00000000000000e+00 3.76960235595695e-02 1.99999773877240e-01 diff --git a/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_27.dat b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_27.dat new file mode 100644 index 00000000..e92595fb --- /dev/null +++ b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_27.dat @@ -0,0 +1,254 @@ +! ------------ AirfoilInfo v1.01.x Input File ---------------------------------- +! AeroElasticSE FAST driver +! line +! line +! ------------------------------------------------------------------------------ +DEFAULT InterpOrd ! Interpolation order to use for quasi-steady table lookup {1=linear; 3=cubic spline; "default"} [default=3] +1 NonDimArea ! The non-dimensional area of the airfoil (area/chord^2) (set to 1.0 if unsure or unneeded) +@"NREL-2p8-127_AF27_Coords.txt" NumCoords ! The number of coordinates in the airfoil shape file. Set to zero if coordinates not included. +AF27_BL.txt BL_file ! The file name including the boundary layer characteristics of the profile. Ignored if the aeroacoustic module is not called. +1 NumTabs ! Number of airfoil tables in this file. Each table must have lines for Re and Ctrl. +! ------------------------------------------------------------------------------ +! data for table 1 +! ------------------------------------------------------------------------------ +6.000000 Re ! Reynolds number in millions +0 Ctrl ! Control setting (must be 0 for current AirfoilInfo) +True InclUAdata ! Is unsteady aerodynamics data included in this table? If TRUE, then include 30 UA coefficients below this line +!........................................ +-4.024505 alpha0 ! 0-lift angle of attack, depends on airfoil. +11.306884 alpha1 ! Angle of attack at f=0.7, (approximately the stall angle) for AOA>alpha0. (deg) +-9.832557 alpha2 ! Angle of attack at f=0.7, (approximately the stall angle) for AOA1] +0.000000 S2 ! Constant in the f curve best-fit for AOA> alpha1; by definition it depends on the airfoil. [ignored if UAMod<>1] +0.000000 S3 ! Constant in the f curve best-fit for alpha2<=AOA< alpha0; by definition it depends on the airfoil. [ignored if UAMod<>1] +0.000000 S4 ! Constant in the f curve best-fit for AOA< alpha2; by definition it depends on the airfoil. [ignored if UAMod<>1] +1.557235 Cn1 ! Critical value of C0n at leading edge separation. It should be extracted from airfoil data at a given Mach and Reynolds number. It can be calculated from the static value of Cn at either the break in the pitching moment or the loss of chord force at the onset of stall. It is close to the condition of maximum lift of the airfoil at low Mach numbers. +-0.830241 Cn2 ! As Cn1 for negative AOAs. +Default St_sh ! Strouhal's shedding frequency constant. [default = 0.19] +0.006417 Cd0 ! 2D drag coefficient value at 0-lift. +-0.112920 Cm0 ! 2D pitching moment coefficient about 1/4-chord location, at 0-lift, positive if nose up. [If the aerodynamics coefficients table does not include a column for Cm, this needs to be set to 0.0] +0.000000 k0 ! Constant in the \hat(x)_cp curve best-fit; = (\hat(x)_AC-0.25). [ignored if UAMod<>1] +0.000000 k1 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k2 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k3 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k1_hat ! Constant in the expression of Cc due to leading edge vortex effects. [ignored if UAMod<>1] +Default x_cp_bar ! Constant in the expression of \hat(x)_cp^v. [ignored if UAMod<>1, default = 0.2] +Default UACutout ! Angle of attack above which unsteady aerodynamics are disabled (deg). [Specifying the string "Default" sets UACutout to 45 degrees] +Default filtCutOff ! Cut-off frequency (-3 dB corner frequency) for low-pass filtering the AoA input to UA, as well as the 1st and 2nd derivatives (Hz) [default = 20] +!........................................ +! Table of aerodynamics coefficients +200 NumAlf ! Number of data lines in the following table +! Alpha Cl Cd Cm +! (deg) (-) (-) (-) +-1.80000000000000e+02 0.00000000000000e+00 3.76960000000000e-02 2.00000000000000e-01 +-1.77000000000000e+02 1.49471782056503e-01 3.76960000000000e-02 2.00000000000000e-01 +-1.74000000000000e+02 3.00312917607843e-01 4.52351574641884e-02 2.39999774321882e-01 +-1.71000000000000e+02 4.50470313592540e-01 6.78528773607728e-02 3.60000410445527e-01 +-1.68000000000000e+02 5.62141300000530e-01 9.47828314689296e-02 3.00100237874998e-01 +-1.65000000000000e+02 6.54569530813285e-01 1.23868852352745e-01 1.50251760664942e-01 +-1.62000000000000e+02 7.46998820775784e-01 1.52955206537882e-01 4.01566317437541e-04 +-1.59000000000000e+02 7.99786954801670e-01 1.91656498833410e-01 -9.28123657821359e-02 +-1.56000000000000e+02 7.73294117948629e-01 2.49587342086377e-01 -7.27556892942309e-02 +-1.53000000000000e+02 7.46801078706125e-01 3.07518227898197e-01 -5.26992595835046e-02 +-1.50000000000000e+02 7.20307965658325e-01 3.65449165572087e-01 -3.26429649313102e-02 +-1.47000000000000e+02 7.05570256415403e-01 4.36504328003481e-01 -1.75932576097200e-02 +-1.44000000000000e+02 6.90832490879619e-01 5.07559761840581e-01 -2.54349280354572e-03 +-1.41000000000000e+02 6.76094612754094e-01 5.78615738508475e-01 1.25063869759013e-02 +-1.38000000000000e+02 6.57241666993606e-01 6.52702757782292e-01 2.78005506087711e-02 +-1.35000000000000e+02 6.36331195763501e-01 7.28305292210269e-01 4.32168556727960e-02 +-1.32000000000000e+02 6.15420484918018e-01 8.03908692975958e-01 5.86333373939468e-02 +-1.29000000000000e+02 5.90761760127430e-01 8.77986088072914e-01 7.42048196933640e-02 +-1.26000000000000e+02 5.58606989674918e-01 9.49011464578596e-01 9.00863038811478e-02 +-1.23000000000000e+02 5.26452064865786e-01 1.02003589848443e+00 1.05968066745086e-01 +-1.20000000000000e+02 4.94297062881228e-01 1.09105986110795e+00 1.21849968941892e-01 +-1.17000000000000e+02 4.51046455307775e-01 1.14892719359139e+00 1.36973650595308e-01 +-1.14000000000000e+02 4.07795991243718e-01 1.20679427930608e+00 1.52097072994036e-01 +-1.11000000000000e+02 3.64545857584686e-01 1.26466092295440e+00 1.67219979864852e-01 +-1.08000000000000e+02 3.16034192336304e-01 1.30909600565222e+00 1.80733001904303e-01 +-1.05000000000000e+02 2.64891721229873e-01 1.34681520559943e+00 1.93441069265733e-01 +-1.02000000000000e+02 2.13749236173153e-01 1.38453397332146e+00 2.06148391012093e-01 +-9.90000000000000e+01 1.61688764154489e-01 1.41401796036258e+00 2.17512373571396e-01 +-9.60000000000000e+01 1.07792278449096e-01 1.42703202935019e+00 2.26189619569497e-01 +-9.30000000000000e+01 5.38962044824732e-02 1.44004599891764e+00 2.34866399278379e-01 +-9.00000000000000e+01 3.36381508994621e-07 1.45305991877593e+00 2.43542945846872e-01 +-8.70000000000000e+01 -5.38961493200293e-02 1.44004601223740e+00 2.47180796579284e-01 +-8.40000000000000e+01 -1.07792429155678e-01 1.42703199295995e+00 2.50818601967904e-01 +-8.10000000000000e+01 -1.61688297256642e-01 1.41401807310167e+00 2.54456379565910e-01 +-7.80000000000000e+01 -2.13748988477021e-01 1.38453415600310e+00 2.54821405258420e-01 +-7.50000000000000e+01 -2.64892059585176e-01 1.34681495605404e+00 2.53549998518008e-01 +-7.20000000000000e+01 -3.16033944645590e-01 1.30909618833200e+00 2.52278006351131e-01 +-6.90000000000000e+01 -3.64545482908305e-01 1.26466142425377e+00 2.49759236748571e-01 +-6.60000000000000e+01 -4.07796112179989e-01 1.20679411749904e+00 2.44746810177687e-01 +-6.30000000000000e+01 -4.51046741451673e-01 1.14892681074432e+00 2.39734383606802e-01 +-6.00000000000000e+01 -4.94297275617037e-01 1.09105939121714e+00 2.34721942034639e-01 +-5.70000000000000e+01 -5.26452277601595e-01 1.02003542859361e+00 2.27959383679512e-01 +-5.40000000000000e+01 -5.58607202409195e-01 9.49010994678426e-01 2.21196599493265e-01 +-5.10000000000000e+01 -5.90761972861707e-01 8.77985618172743e-01 2.14433363641336e-01 +-4.80000000000000e+01 -6.17089671120620e-01 8.03911570370645e-01 2.07956980763680e-01 +-4.50000000000000e+01 -6.40503926932036e-01 7.28313235916803e-01 2.01624019763027e-01 +-4.20000000000000e+01 -6.58910840133311e-01 6.52705635149657e-01 1.96862389618034e-01 +-3.90000000000000e+01 -6.76417027511146e-01 5.77527369809482e-01 1.92714494884031e-01 +-3.60000000000000e+01 -6.91442126694186e-01 5.04059360049167e-01 1.90773003374389e-01 +-3.30000000000000e+01 -7.05593958510807e-01 4.33318703053973e-01 1.91908992233939e-01 +-3.00000000000000e+01 -7.20308071684859e-01 3.65448723816258e-01 1.96465039072780e-01 +-2.93939393939394e+01 -7.23687122424702e-01 3.52430090699486e-01 1.98306835359819e-01 +-2.87878787878788e+01 -7.27066173164544e-01 3.39411457582714e-01 2.00148631646857e-01 +-2.81818181818182e+01 -7.30445223904387e-01 3.26392824465942e-01 2.01990427933895e-01 +-2.75757575757576e+01 -7.34244974993610e-01 3.13793078035017e-01 2.04486437101527e-01 +-2.69696969696970e+01 -7.38225041700157e-01 3.01372869870364e-01 2.07262847270964e-01 +-2.63636363636364e+01 -7.42205108406705e-01 2.88952661705710e-01 2.10039257440401e-01 +-2.57575757575758e+01 -7.46555462653963e-01 2.76796374908870e-01 2.13304160376248e-01 +-2.51515151515151e+01 -7.51461161912085e-01 2.65035908653530e-01 2.17301688612281e-01 +-2.45454545454545e+01 -7.56366861170206e-01 2.53275442398190e-01 2.21299216848314e-01 +-2.39393939393939e+01 -7.61408677387006e-01 2.41586670872199e-01 2.25459952105595e-01 +-2.33333333333333e+01 -7.67675572584808e-01 2.30543165790786e-01 2.31089582151761e-01 +-2.27272727272727e+01 -7.73942467782610e-01 2.19499660709374e-01 2.36719212197927e-01 +-2.21212121212121e+01 -7.80209362980412e-01 2.08456155627962e-01 2.42348842244093e-01 +-2.15151515151515e+01 -7.88045801889462e-01 1.98028860914946e-01 2.49772963288095e-01 +-2.09090909090909e+01 -7.96274727686348e-01 1.87755658431417e-01 2.57645822511188e-01 +-2.03030303030303e+01 -8.04503653483233e-01 1.77482455947888e-01 2.65518681734281e-01 +-1.96969696969697e+01 -8.13721563222721e-01 1.67514267203666e-01 2.74509167058282e-01 +-1.90909090909091e+01 -8.23928400957602e-01 1.57851074944005e-01 2.84617215258648e-01 +-1.84848484848485e+01 -8.22646763588942e-01 1.48546901850923e-01 2.82973548468764e-01 +-1.78787878787879e+01 -8.19241173382965e-01 1.39555143470384e-01 2.78335696038153e-01 +-1.72727272727273e+01 -8.15446564330172e-01 1.31559857952983e-01 2.70013132308244e-01 +-1.66666666666667e+01 -8.03296442896411e-01 1.23564572435581e-01 2.53038383173389e-01 +-1.60606060606061e+01 -7.84310064075638e-01 1.15569286918180e-01 2.28984646695628e-01 +-1.54545454545455e+01 -7.65324664303493e-01 1.07574959135167e-01 2.04931605118311e-01 +-1.48484848484848e+01 -7.46338949873589e-01 9.95804717419686e-02 1.80878447733115e-01 +-1.42424242424242e+01 -7.27351964982053e-01 9.15851862245671e-02 1.56824711255353e-01 +-1.36363636363636e+01 -7.08366360011050e-01 8.35901755495681e-02 1.32771801638210e-01 +-1.30303030303030e+01 -6.89379049576426e-01 7.55946380877238e-02 1.08716367776058e-01 +-1.24242424242424e+01 -6.70393771825338e-01 6.75996503421813e-02 8.46634665540094e-02 +-1.18181818181818e+01 -6.51406715493019e-01 5.96041815994351e-02 6.06091788446317e-02 +-1.12121212121212e+01 -6.32421454753742e-01 5.16093541595814e-02 3.65562447387649e-02 +-1.06060606060606e+01 -6.13434931389144e-01 4.36139312036515e-02 1.25016705283901e-02 +-1.00000000000000e+01 -5.94448865749824e-01 3.56199434645880e-02 -1.15511700947924e-02 +-9.39393939393939e+00 -5.75463587974779e-01 2.76249557125666e-02 -3.56050107398163e-02 +-8.78787878787879e+00 -5.51403736673166e-01 2.01382292840361e-02 -5.87079533337773e-02 +-8.18181818181818e+00 -5.17926305822838e-01 1.35966762681340e-02 -8.00434824257992e-02 +-7.57575757575758e+00 -4.48012922709353e-01 1.04062079021576e-02 -9.38202376741164e-02 +-6.96969696969697e+00 -3.62306556115099e-01 8.91516259682331e-03 -1.02639375733790e-01 +-6.36363636363636e+00 -2.86592508663283e-01 7.49091941073086e-03 -1.05345402946346e-01 +-5.75757575757576e+00 -2.11681301136276e-01 7.05454293237208e-03 -1.07624256716558e-01 +-5.15151515151515e+00 -1.37278254009080e-01 6.76061420557612e-03 -1.09615086355391e-01 +-4.54545454545454e+00 -6.32445813538124e-02 6.51817895525840e-03 -1.11463657835562e-01 +-3.93939393939394e+00 1.03326972358679e-02 6.40000000000000e-03 -1.13157562089366e-01 +-3.33333333333333e+00 8.37358252318253e-02 6.36666256139732e-03 -1.14700049263232e-01 +-2.72727272727273e+00 1.57144966549608e-01 6.30000000000000e-03 -1.16209080405869e-01 +-2.12121212121212e+00 2.30132082000148e-01 6.30000000000000e-03 -1.17633365893514e-01 +-1.51515151515152e+00 3.03270194866406e-01 6.30000000000000e-03 -1.18966675734322e-01 +-9.09090909090912e-01 3.76007887483945e-01 6.30000000000000e-03 -1.20399977937206e-01 +-3.03030303030302e-01 4.48619648411214e-01 6.33939639599868e-03 -1.21733360355986e-01 + 3.03030303030302e-01 5.21162162400790e-01 6.40000000000000e-03 -1.23066639644014e-01 + 9.09090909090912e-01 5.93483011578421e-01 6.40000000000000e-03 -1.24318201875268e-01 + 1.51515151515152e+00 6.65499510346614e-01 6.50000000000000e-03 -1.25430294786980e-01 + 2.12121212121212e+00 7.37449762821818e-01 6.52423946422604e-03 -1.26642394642260e-01 + 2.72727272727273e+00 8.08982292442682e-01 6.64545535339469e-03 -1.27809098180552e-01 + 3.33333333333333e+00 8.80397573785818e-01 6.76666256139732e-03 -1.28833300491179e-01 + 3.93939393939394e+00 9.51421826139261e-01 6.88787983927956e-03 -1.29890918553516e-01 + 4.54545454545455e+00 1.02186280754731e+00 7.00908947762920e-03 -1.30763626343404e-01 + 5.15151515151515e+00 1.09189627700035e+00 7.16061420557612e-03 -1.31612149719516e-01 + 5.75757575757576e+00 1.16079952835358e+00 7.45454293237208e-03 -1.32306057243163e-01 + 6.36363636363637e+00 1.22720139059598e+00 7.96364926341358e-03 -1.32572729852683e-01 + 6.96969696969697e+00 1.28802463107430e+00 8.94546166938641e-03 -1.32130299072563e-01 + 7.57575757575757e+00 1.33932330958836e+00 1.07272369407300e-02 -1.30081868282978e-01 + 8.18181818181818e+00 1.38679186165234e+00 1.25091248425769e-02 -1.27572678796319e-01 + 8.78787878787879e+00 1.43442629439737e+00 1.40333059500537e-02 -1.25090961368079e-01 + 9.39393939393939e+00 1.48072485366775e+00 1.53666845487907e-02 -1.22230262389112e-01 + 1.00000000000000e+01 1.51619976429293e+00 1.64999922859505e-02 -1.21700000000000e-01 + 1.06060606060606e+01 1.54652659135150e+00 1.81605492792916e-02 -1.21700000000000e-01 + 1.12121212121212e+01 1.57015165312925e+00 2.03485003516014e-02 -1.21912125087900e-01 + 1.18181818181818e+01 1.58466335911404e+00 3.00903504536651e-02 -1.23218115609323e-01 + 1.24242424242424e+01 1.55439065028940e+00 4.64546360854226e-02 -1.25157586499013e-01 + 1.30303030303030e+01 1.50697060273102e+00 6.28179372626244e-02 -1.27096940712607e-01 + 1.36363636363636e+01 1.44636161651328e+00 7.91823635414146e-02 -1.29036428271575e-01 + 1.42424242424242e+01 1.39302963646758e+00 9.22728558241098e-02 -1.30587894023598e-01 + 1.48484848484848e+01 1.35060468299441e+00 1.00454811136793e-01 -1.31557607245842e-01 + 1.54545454545455e+01 1.32181803006545e+00 1.08636414852911e-01 -1.32527278797382e-01 + 1.60606060606061e+01 1.29757644961134e+00 1.16817948256172e-01 -1.33496942015546e-01 + 1.66666666666667e+01 1.27333361905524e+00 1.24999903568856e-01 -1.34466655237790e-01 + 1.72727272727273e+01 1.24363618274871e+00 1.33181858881539e-01 -1.35436368460034e-01 + 1.78787878787879e+01 1.20727193691457e+00 1.41363814194223e-01 -1.36406081682278e-01 + 1.84848484848485e+01 1.18992978938591e+00 1.49497879761678e-01 -1.37375750456550e-01 + 1.90909090909091e+01 1.17704330010331e+00 1.57851074944005e-01 -1.39089585145003e-01 + 1.96969696969697e+01 1.16246123752382e+00 1.67514267203666e-01 -1.45021805782080e-01 + 2.03030303030303e+01 1.14929279501435e+00 1.77482455947888e-01 -1.51632351934001e-01 + 2.09090909090909e+01 1.13753805254846e+00 1.87755658431417e-01 -1.58921261976074e-01 + 2.15151515151515e+01 1.12578331008257e+00 1.98028860914946e-01 -1.66210172018147e-01 + 2.21212121212121e+01 1.11458874358451e+00 2.08456155627962e-01 -1.73224623443957e-01 + 2.27272727272727e+01 1.10563430457793e+00 2.19499660709374e-01 -1.79141522802416e-01 + 2.33333333333333e+01 1.09667986557135e+00 2.30543165790786e-01 -1.85058422160874e-01 + 2.39393939393939e+01 1.08772542656477e+00 2.41586670872199e-01 -1.90975321519332e-01 + 2.45454545454545e+01 1.08052187960139e+00 2.53275442398190e-01 -1.96074592475065e-01 + 2.51515151515151e+01 1.07351287201350e+00 2.65035908653530e-01 -2.01083017784734e-01 + 2.57575757575758e+01 1.06650386442561e+00 2.76796374908870e-01 -2.06091443094404e-01 + 2.63636363636364e+01 1.06028924575223e+00 2.88952661705710e-01 -2.10729607665482e-01 + 2.69696969696970e+01 1.05460430198682e+00 3.01372869870364e-01 -2.15120893385337e-01 + 2.75757575757576e+01 1.04891935822142e+00 3.13793078035017e-01 -2.19512179105193e-01 + 2.81818181818182e+01 1.04349174843484e+00 3.26392824465942e-01 -2.23774966350859e-01 + 2.87878787878788e+01 1.03866453309221e+00 3.39411457582714e-01 -2.27737949543009e-01 + 2.93939393939394e+01 1.03383731774957e+00 3.52430090699486e-01 -2.31700932735158e-01 + 3.00000000000000e+01 1.02901010240694e+00 3.65448723816258e-01 -2.35663915927308e-01 + 3.30000000000000e+01 1.00799494072346e+00 4.33318703053973e-01 -2.53423049843193e-01 + 3.60000000000000e+01 9.87774181033947e-01 5.04059360049167e-01 -2.69936854350083e-01 + 3.90000000000000e+01 9.66310039303889e-01 5.77527369809482e-01 -2.85448473353340e-01 + 4.20000000000000e+01 9.41301057332367e-01 6.52705635149657e-01 -3.00284968060017e-01 + 4.50000000000000e+01 9.15005895616392e-01 7.28313235916803e-01 -3.14934043892456e-01 + 4.80000000000000e+01 8.81556701601667e-01 8.03911570370646e-01 -3.28999157277327e-01 + 5.10000000000000e+01 8.43945446946677e-01 8.77985618172744e-01 -3.42814128421300e-01 + 5.40000000000000e+01 7.98009803441727e-01 9.49010994678426e-01 -3.56128799002399e-01 + 5.70000000000000e+01 7.52074110859421e-01 1.02003542859361e+00 -3.69443367867275e-01 + 6.00000000000000e+01 7.06138393738624e-01 1.09105939121714e+00 -3.82757885874428e-01 + 6.30000000000000e+01 6.44352602071576e-01 1.14892681074432e+00 -3.94831160514253e-01 + 6.60000000000000e+01 5.82566474543015e-01 1.20679411749904e+00 -4.06904424514653e-01 + 6.90000000000000e+01 5.20779947012492e-01 1.26466142425377e+00 -4.18977688515053e-01 + 7.20000000000000e+01 4.51477435205418e-01 1.30909618833200e+00 -4.29844051243441e-01 + 7.50000000000000e+01 3.78417085122278e-01 1.34681495605404e+00 -4.40106988042700e-01 + 7.80000000000000e+01 3.05355897825734e-01 1.38453415600310e+00 -4.50369442444556e-01 + 8.10000000000000e+01 2.30983767510451e-01 1.41401807310167e+00 -4.59788643436343e-01 + 8.40000000000000e+01 1.53989841650875e-01 1.42703199295995e+00 -4.67521395816866e-01 + 8.70000000000000e+01 7.69949275996385e-02 1.44004601223740e+00 -4.75253807270785e-01 + 9.00000000000000e+01 -3.36381509228363e-07 1.45305991877593e+00 -4.82986022704544e-01 + 9.30000000000000e+01 -5.38962044824732e-02 1.44004599891764e+00 -4.86623800302551e-01 + 9.60000000000000e+01 -1.07792278449097e-01 1.42703202935019e+00 -4.90261391797104e-01 + 9.90000000000000e+01 -1.61688764154490e-01 1.41401796036258e+00 -4.93898611078011e-01 + 1.02000000000000e+02 -2.13749236173153e-01 1.38453397332146e+00 -4.94263399100743e-01 + 1.05000000000000e+02 -2.64891721229873e-01 1.34681520559943e+00 -4.92992006930171e-01 + 1.08000000000000e+02 -3.16034192336304e-01 1.30909600565222e+00 -4.91720000190610e-01 + 1.11000000000000e+02 -3.64545857584686e-01 1.26466092295440e+00 -4.89201393327162e-01 + 1.14000000000000e+02 -4.07795991243718e-01 1.20679427930608e+00 -4.84189624190406e-01 + 1.17000000000000e+02 -4.51046455307775e-01 1.14892719359139e+00 -4.79177416768754e-01 + 1.20000000000000e+02 -4.94297062881228e-01 1.09105986110795e+00 -4.74164986774198e-01 + 1.23000000000000e+02 -5.26452064865786e-01 1.02003589848443e+00 -4.67401828422766e-01 + 1.26000000000000e+02 -5.58606989674918e-01 9.49011464578596e-01 -4.60638644238479e-01 + 1.29000000000000e+02 -5.90761760127430e-01 8.77986088072913e-01 -4.53875408386550e-01 + 1.32000000000000e+02 -6.15420484918018e-01 8.03908692975958e-01 -4.47922977473614e-01 + 1.35000000000000e+02 -6.36331195763501e-01 7.28305292210269e-01 -4.42375948063776e-01 + 1.38000000000000e+02 -6.57241666993606e-01 6.52702757782291e-01 -4.36828382226539e-01 + 1.41000000000000e+02 -6.76094612754094e-01 5.78615738508474e-01 -4.33407800721224e-01 + 1.44000000000000e+02 -6.90832490879619e-01 5.07559761840581e-01 -4.34241205139103e-01 + 1.47000000000000e+02 -7.05570256415403e-01 4.36504328003481e-01 -4.35074603190205e-01 + 1.50000000000000e+02 -7.20307965658325e-01 3.65449165572087e-01 -4.35907998058031e-01 + 1.53000000000000e+02 -7.46801078706125e-01 3.07518227898197e-01 -4.57805065052203e-01 + 1.56000000000000e+02 -7.73294117948629e-01 2.49587342086377e-01 -4.79701897484255e-01 + 1.59000000000000e+02 -7.99786954801670e-01 1.91656498833410e-01 -5.01598162643690e-01 + 1.62000000000000e+02 -7.40790822868899e-01 1.53560806333696e-01 -5.07117800599882e-01 + 1.65000000000000e+02 -6.39049483540701e-01 1.25382856960915e-01 -5.04448986449602e-01 + 1.68000000000000e+02 -5.37308710076014e-01 9.72046304867630e-02 -5.01779602888076e-01 + 1.71000000000000e+02 -4.22533481739914e-01 7.05772804657932e-02 -4.50000513056908e-01 + 1.74000000000000e+02 -2.81688735121593e-01 4.70517557569334e-02 -2.99999717902353e-01 + 1.77000000000000e+02 -1.40202251216632e-01 3.86002570677554e-02 -6.87686132694523e-02 + 1.80000000000000e+02 0.00000000000000e+00 3.76960000000000e-02 2.00000000000000e-01 diff --git a/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_28.dat b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_28.dat new file mode 100644 index 00000000..1adeee56 --- /dev/null +++ b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_28.dat @@ -0,0 +1,254 @@ +! ------------ AirfoilInfo v1.01.x Input File ---------------------------------- +! AeroElasticSE FAST driver +! line +! line +! ------------------------------------------------------------------------------ +DEFAULT InterpOrd ! Interpolation order to use for quasi-steady table lookup {1=linear; 3=cubic spline; "default"} [default=3] +1 NonDimArea ! The non-dimensional area of the airfoil (area/chord^2) (set to 1.0 if unsure or unneeded) +@"NREL-2p8-127_AF28_Coords.txt" NumCoords ! The number of coordinates in the airfoil shape file. Set to zero if coordinates not included. +AF28_BL.txt BL_file ! The file name including the boundary layer characteristics of the profile. Ignored if the aeroacoustic module is not called. +1 NumTabs ! Number of airfoil tables in this file. Each table must have lines for Re and Ctrl. +! ------------------------------------------------------------------------------ +! data for table 1 +! ------------------------------------------------------------------------------ +6.000000 Re ! Reynolds number in millions +0 Ctrl ! Control setting (must be 0 for current AirfoilInfo) +True InclUAdata ! Is unsteady aerodynamics data included in this table? If TRUE, then include 30 UA coefficients below this line +!........................................ +-4.024505 alpha0 ! 0-lift angle of attack, depends on airfoil. +11.306884 alpha1 ! Angle of attack at f=0.7, (approximately the stall angle) for AOA>alpha0. (deg) +-9.832557 alpha2 ! Angle of attack at f=0.7, (approximately the stall angle) for AOA1] +0.000000 S2 ! Constant in the f curve best-fit for AOA> alpha1; by definition it depends on the airfoil. [ignored if UAMod<>1] +0.000000 S3 ! Constant in the f curve best-fit for alpha2<=AOA< alpha0; by definition it depends on the airfoil. [ignored if UAMod<>1] +0.000000 S4 ! Constant in the f curve best-fit for AOA< alpha2; by definition it depends on the airfoil. [ignored if UAMod<>1] +1.557235 Cn1 ! Critical value of C0n at leading edge separation. It should be extracted from airfoil data at a given Mach and Reynolds number. It can be calculated from the static value of Cn at either the break in the pitching moment or the loss of chord force at the onset of stall. It is close to the condition of maximum lift of the airfoil at low Mach numbers. +-0.830241 Cn2 ! As Cn1 for negative AOAs. +Default St_sh ! Strouhal's shedding frequency constant. [default = 0.19] +0.006417 Cd0 ! 2D drag coefficient value at 0-lift. +-0.112920 Cm0 ! 2D pitching moment coefficient about 1/4-chord location, at 0-lift, positive if nose up. [If the aerodynamics coefficients table does not include a column for Cm, this needs to be set to 0.0] +0.000000 k0 ! Constant in the \hat(x)_cp curve best-fit; = (\hat(x)_AC-0.25). [ignored if UAMod<>1] +0.000000 k1 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k2 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k3 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k1_hat ! Constant in the expression of Cc due to leading edge vortex effects. [ignored if UAMod<>1] +Default x_cp_bar ! Constant in the expression of \hat(x)_cp^v. [ignored if UAMod<>1, default = 0.2] +Default UACutout ! Angle of attack above which unsteady aerodynamics are disabled (deg). [Specifying the string "Default" sets UACutout to 45 degrees] +Default filtCutOff ! Cut-off frequency (-3 dB corner frequency) for low-pass filtering the AoA input to UA, as well as the 1st and 2nd derivatives (Hz) [default = 20] +!........................................ +! Table of aerodynamics coefficients +200 NumAlf ! Number of data lines in the following table +! Alpha Cl Cd Cm +! (deg) (-) (-) (-) +-1.80000000000000e+02 0.00000000000000e+00 3.76960000000000e-02 2.00000000000000e-01 +-1.77000000000000e+02 1.49471782056503e-01 3.76960000000000e-02 2.00000000000000e-01 +-1.74000000000000e+02 3.00312917607843e-01 4.52351574641884e-02 2.39999774321882e-01 +-1.71000000000000e+02 4.50470313592540e-01 6.78528773607728e-02 3.60000410445527e-01 +-1.68000000000000e+02 5.62141300000530e-01 9.47828314689296e-02 3.00100237874998e-01 +-1.65000000000000e+02 6.54569530813285e-01 1.23868852352745e-01 1.50251760664942e-01 +-1.62000000000000e+02 7.46998820775784e-01 1.52955206537882e-01 4.01566317437541e-04 +-1.59000000000000e+02 7.99786954801670e-01 1.91656498833410e-01 -9.28123657821359e-02 +-1.56000000000000e+02 7.73294117948629e-01 2.49587342086377e-01 -7.27556892942309e-02 +-1.53000000000000e+02 7.46801078706125e-01 3.07518227898197e-01 -5.26992595835046e-02 +-1.50000000000000e+02 7.20307965658325e-01 3.65449165572087e-01 -3.26429649313102e-02 +-1.47000000000000e+02 7.05570256415403e-01 4.36504328003481e-01 -1.75932576097200e-02 +-1.44000000000000e+02 6.90832490879619e-01 5.07559761840581e-01 -2.54349280354572e-03 +-1.41000000000000e+02 6.76094612754094e-01 5.78615738508475e-01 1.25063869759013e-02 +-1.38000000000000e+02 6.57241666993606e-01 6.52702757782292e-01 2.78005506087711e-02 +-1.35000000000000e+02 6.36331195763501e-01 7.28305292210269e-01 4.32168556727960e-02 +-1.32000000000000e+02 6.15420484918018e-01 8.03908692975958e-01 5.86333373939468e-02 +-1.29000000000000e+02 5.90761760127430e-01 8.77986088072914e-01 7.42048196933640e-02 +-1.26000000000000e+02 5.58606989674918e-01 9.49011464578596e-01 9.00863038811478e-02 +-1.23000000000000e+02 5.26452064865786e-01 1.02003589848443e+00 1.05968066745086e-01 +-1.20000000000000e+02 4.94297062881228e-01 1.09105986110795e+00 1.21849968941892e-01 +-1.17000000000000e+02 4.51046455307775e-01 1.14892719359139e+00 1.36973650595308e-01 +-1.14000000000000e+02 4.07795991243718e-01 1.20679427930608e+00 1.52097072994036e-01 +-1.11000000000000e+02 3.64545857584686e-01 1.26466092295440e+00 1.67219979864852e-01 +-1.08000000000000e+02 3.16034192336304e-01 1.30909600565222e+00 1.80733001904303e-01 +-1.05000000000000e+02 2.64891721229873e-01 1.34681520559943e+00 1.93441069265733e-01 +-1.02000000000000e+02 2.13749236173153e-01 1.38453397332146e+00 2.06148391012093e-01 +-9.90000000000000e+01 1.61688764154489e-01 1.41401796036258e+00 2.17512373571396e-01 +-9.60000000000000e+01 1.07792278449096e-01 1.42703202935019e+00 2.26189619569497e-01 +-9.30000000000000e+01 5.38962044824732e-02 1.44004599891764e+00 2.34866399278379e-01 +-9.00000000000000e+01 3.36381508994621e-07 1.45305991877593e+00 2.43542945846872e-01 +-8.70000000000000e+01 -5.38961493200293e-02 1.44004601223740e+00 2.47180796579284e-01 +-8.40000000000000e+01 -1.07792429155678e-01 1.42703199295995e+00 2.50818601967904e-01 +-8.10000000000000e+01 -1.61688297256642e-01 1.41401807310167e+00 2.54456379565910e-01 +-7.80000000000000e+01 -2.13748988477021e-01 1.38453415600310e+00 2.54821405258420e-01 +-7.50000000000000e+01 -2.64892059585176e-01 1.34681495605404e+00 2.53549998518008e-01 +-7.20000000000000e+01 -3.16033944645590e-01 1.30909618833200e+00 2.52278006351131e-01 +-6.90000000000000e+01 -3.64545482908305e-01 1.26466142425377e+00 2.49759236748571e-01 +-6.60000000000000e+01 -4.07796112179989e-01 1.20679411749904e+00 2.44746810177687e-01 +-6.30000000000000e+01 -4.51046741451673e-01 1.14892681074432e+00 2.39734383606802e-01 +-6.00000000000000e+01 -4.94297275617037e-01 1.09105939121714e+00 2.34721942034639e-01 +-5.70000000000000e+01 -5.26452277601595e-01 1.02003542859361e+00 2.27959383679512e-01 +-5.40000000000000e+01 -5.58607202409195e-01 9.49010994678426e-01 2.21196599493265e-01 +-5.10000000000000e+01 -5.90761972861707e-01 8.77985618172743e-01 2.14433363641336e-01 +-4.80000000000000e+01 -6.17089671120620e-01 8.03911570370645e-01 2.07956980763680e-01 +-4.50000000000000e+01 -6.40503926932036e-01 7.28313235916803e-01 2.01624019763027e-01 +-4.20000000000000e+01 -6.58910840133311e-01 6.52705635149657e-01 1.96862389618034e-01 +-3.90000000000000e+01 -6.76417027511146e-01 5.77527369809482e-01 1.92714494884031e-01 +-3.60000000000000e+01 -6.91442126694186e-01 5.04059360049167e-01 1.90773003374389e-01 +-3.30000000000000e+01 -7.05593958510807e-01 4.33318703053973e-01 1.91908992233939e-01 +-3.00000000000000e+01 -7.20308071684859e-01 3.65448723816258e-01 1.96465039072780e-01 +-2.93939393939394e+01 -7.23687122424702e-01 3.52430090699486e-01 1.98306835359819e-01 +-2.87878787878788e+01 -7.27066173164544e-01 3.39411457582714e-01 2.00148631646857e-01 +-2.81818181818182e+01 -7.30445223904387e-01 3.26392824465942e-01 2.01990427933895e-01 +-2.75757575757576e+01 -7.34244974993610e-01 3.13793078035017e-01 2.04486437101527e-01 +-2.69696969696970e+01 -7.38225041700157e-01 3.01372869870364e-01 2.07262847270964e-01 +-2.63636363636364e+01 -7.42205108406705e-01 2.88952661705710e-01 2.10039257440401e-01 +-2.57575757575758e+01 -7.46555462653963e-01 2.76796374908870e-01 2.13304160376248e-01 +-2.51515151515151e+01 -7.51461161912085e-01 2.65035908653530e-01 2.17301688612281e-01 +-2.45454545454545e+01 -7.56366861170206e-01 2.53275442398190e-01 2.21299216848314e-01 +-2.39393939393939e+01 -7.61408677387006e-01 2.41586670872199e-01 2.25459952105595e-01 +-2.33333333333333e+01 -7.67675572584808e-01 2.30543165790786e-01 2.31089582151761e-01 +-2.27272727272727e+01 -7.73942467782610e-01 2.19499660709374e-01 2.36719212197927e-01 +-2.21212121212121e+01 -7.80209362980412e-01 2.08456155627962e-01 2.42348842244093e-01 +-2.15151515151515e+01 -7.88045801889462e-01 1.98028860914946e-01 2.49772963288095e-01 +-2.09090909090909e+01 -7.96274727686348e-01 1.87755658431417e-01 2.57645822511188e-01 +-2.03030303030303e+01 -8.04503653483233e-01 1.77482455947888e-01 2.65518681734281e-01 +-1.96969696969697e+01 -8.13721563222721e-01 1.67514267203666e-01 2.74509167058282e-01 +-1.90909090909091e+01 -8.23928400957602e-01 1.57851074944005e-01 2.84617215258648e-01 +-1.84848484848485e+01 -8.22646763588942e-01 1.48546901850923e-01 2.82973548468764e-01 +-1.78787878787879e+01 -8.19241173382965e-01 1.39555143470384e-01 2.78335696038153e-01 +-1.72727272727273e+01 -8.15446564330172e-01 1.31559857952983e-01 2.70013132308244e-01 +-1.66666666666667e+01 -8.03296442896411e-01 1.23564572435581e-01 2.53038383173389e-01 +-1.60606060606061e+01 -7.84310064075638e-01 1.15569286918180e-01 2.28984646695628e-01 +-1.54545454545455e+01 -7.65324664303493e-01 1.07574959135167e-01 2.04931605118311e-01 +-1.48484848484848e+01 -7.46338949873589e-01 9.95804717419686e-02 1.80878447733115e-01 +-1.42424242424242e+01 -7.27351964982053e-01 9.15851862245671e-02 1.56824711255353e-01 +-1.36363636363636e+01 -7.08366360011050e-01 8.35901755495681e-02 1.32771801638210e-01 +-1.30303030303030e+01 -6.89379049576426e-01 7.55946380877238e-02 1.08716367776058e-01 +-1.24242424242424e+01 -6.70393771825338e-01 6.75996503421813e-02 8.46634665540094e-02 +-1.18181818181818e+01 -6.51406715493019e-01 5.96041815994351e-02 6.06091788446317e-02 +-1.12121212121212e+01 -6.32421454753742e-01 5.16093541595814e-02 3.65562447387649e-02 +-1.06060606060606e+01 -6.13434931389144e-01 4.36139312036515e-02 1.25016705283901e-02 +-1.00000000000000e+01 -5.94448865749824e-01 3.56199434645880e-02 -1.15511700947924e-02 +-9.39393939393939e+00 -5.75463587974779e-01 2.76249557125666e-02 -3.56050107398163e-02 +-8.78787878787879e+00 -5.51403736673166e-01 2.01382292840361e-02 -5.87079533337773e-02 +-8.18181818181818e+00 -5.17926305822838e-01 1.35966762681340e-02 -8.00434824257992e-02 +-7.57575757575758e+00 -4.48012922709353e-01 1.04062079021576e-02 -9.38202376741164e-02 +-6.96969696969697e+00 -3.62306556115099e-01 8.91516259682331e-03 -1.02639375733790e-01 +-6.36363636363636e+00 -2.86592508663283e-01 7.49091941073086e-03 -1.05345402946346e-01 +-5.75757575757576e+00 -2.11681301136276e-01 7.05454293237208e-03 -1.07624256716558e-01 +-5.15151515151515e+00 -1.37278254009080e-01 6.76061420557612e-03 -1.09615086355391e-01 +-4.54545454545454e+00 -6.32445813538124e-02 6.51817895525840e-03 -1.11463657835562e-01 +-3.93939393939394e+00 1.03326972358679e-02 6.40000000000000e-03 -1.13157562089366e-01 +-3.33333333333333e+00 8.37358252318253e-02 6.36666256139732e-03 -1.14700049263232e-01 +-2.72727272727273e+00 1.57144966549608e-01 6.30000000000000e-03 -1.16209080405869e-01 +-2.12121212121212e+00 2.30132082000148e-01 6.30000000000000e-03 -1.17633365893514e-01 +-1.51515151515152e+00 3.03270194866406e-01 6.30000000000000e-03 -1.18966675734322e-01 +-9.09090909090912e-01 3.76007887483945e-01 6.30000000000000e-03 -1.20399977937206e-01 +-3.03030303030302e-01 4.48619648411214e-01 6.33939639599868e-03 -1.21733360355986e-01 + 3.03030303030302e-01 5.21162162400790e-01 6.40000000000000e-03 -1.23066639644014e-01 + 9.09090909090912e-01 5.93483011578421e-01 6.40000000000000e-03 -1.24318201875268e-01 + 1.51515151515152e+00 6.65499510346614e-01 6.50000000000000e-03 -1.25430294786980e-01 + 2.12121212121212e+00 7.37449762821818e-01 6.52423946422604e-03 -1.26642394642260e-01 + 2.72727272727273e+00 8.08982292442682e-01 6.64545535339469e-03 -1.27809098180552e-01 + 3.33333333333333e+00 8.80397573785818e-01 6.76666256139732e-03 -1.28833300491179e-01 + 3.93939393939394e+00 9.51421826139261e-01 6.88787983927956e-03 -1.29890918553516e-01 + 4.54545454545455e+00 1.02186280754731e+00 7.00908947762920e-03 -1.30763626343404e-01 + 5.15151515151515e+00 1.09189627700035e+00 7.16061420557612e-03 -1.31612149719516e-01 + 5.75757575757576e+00 1.16079952835358e+00 7.45454293237208e-03 -1.32306057243163e-01 + 6.36363636363637e+00 1.22720139059598e+00 7.96364926341358e-03 -1.32572729852683e-01 + 6.96969696969697e+00 1.28802463107430e+00 8.94546166938641e-03 -1.32130299072563e-01 + 7.57575757575757e+00 1.33932330958836e+00 1.07272369407300e-02 -1.30081868282978e-01 + 8.18181818181818e+00 1.38679186165234e+00 1.25091248425769e-02 -1.27572678796319e-01 + 8.78787878787879e+00 1.43442629439737e+00 1.40333059500537e-02 -1.25090961368079e-01 + 9.39393939393939e+00 1.48072485366775e+00 1.53666845487907e-02 -1.22230262389112e-01 + 1.00000000000000e+01 1.51619976429293e+00 1.64999922859505e-02 -1.21700000000000e-01 + 1.06060606060606e+01 1.54652659135150e+00 1.81605492792916e-02 -1.21700000000000e-01 + 1.12121212121212e+01 1.57015165312925e+00 2.03485003516014e-02 -1.21912125087900e-01 + 1.18181818181818e+01 1.58466335911404e+00 3.00903504536651e-02 -1.23218115609323e-01 + 1.24242424242424e+01 1.55439065028940e+00 4.64546360854226e-02 -1.25157586499013e-01 + 1.30303030303030e+01 1.50697060273102e+00 6.28179372626244e-02 -1.27096940712607e-01 + 1.36363636363636e+01 1.44636161651328e+00 7.91823635414146e-02 -1.29036428271575e-01 + 1.42424242424242e+01 1.39302963646758e+00 9.22728558241098e-02 -1.30587894023598e-01 + 1.48484848484848e+01 1.35060468299441e+00 1.00454811136793e-01 -1.31557607245842e-01 + 1.54545454545455e+01 1.32181803006545e+00 1.08636414852911e-01 -1.32527278797382e-01 + 1.60606060606061e+01 1.29757644961134e+00 1.16817948256172e-01 -1.33496942015546e-01 + 1.66666666666667e+01 1.27333361905524e+00 1.24999903568856e-01 -1.34466655237790e-01 + 1.72727272727273e+01 1.24363618274871e+00 1.33181858881539e-01 -1.35436368460034e-01 + 1.78787878787879e+01 1.20727193691457e+00 1.41363814194223e-01 -1.36406081682278e-01 + 1.84848484848485e+01 1.18992978938591e+00 1.49497879761678e-01 -1.37375750456550e-01 + 1.90909090909091e+01 1.17704330010331e+00 1.57851074944005e-01 -1.39089585145003e-01 + 1.96969696969697e+01 1.16246123752382e+00 1.67514267203666e-01 -1.45021805782080e-01 + 2.03030303030303e+01 1.14929279501435e+00 1.77482455947888e-01 -1.51632351934001e-01 + 2.09090909090909e+01 1.13753805254846e+00 1.87755658431417e-01 -1.58921261976074e-01 + 2.15151515151515e+01 1.12578331008257e+00 1.98028860914946e-01 -1.66210172018147e-01 + 2.21212121212121e+01 1.11458874358451e+00 2.08456155627962e-01 -1.73224623443957e-01 + 2.27272727272727e+01 1.10563430457793e+00 2.19499660709374e-01 -1.79141522802416e-01 + 2.33333333333333e+01 1.09667986557135e+00 2.30543165790786e-01 -1.85058422160874e-01 + 2.39393939393939e+01 1.08772542656477e+00 2.41586670872199e-01 -1.90975321519332e-01 + 2.45454545454545e+01 1.08052187960139e+00 2.53275442398190e-01 -1.96074592475065e-01 + 2.51515151515151e+01 1.07351287201350e+00 2.65035908653530e-01 -2.01083017784734e-01 + 2.57575757575758e+01 1.06650386442561e+00 2.76796374908870e-01 -2.06091443094404e-01 + 2.63636363636364e+01 1.06028924575223e+00 2.88952661705710e-01 -2.10729607665482e-01 + 2.69696969696970e+01 1.05460430198682e+00 3.01372869870364e-01 -2.15120893385337e-01 + 2.75757575757576e+01 1.04891935822142e+00 3.13793078035017e-01 -2.19512179105193e-01 + 2.81818181818182e+01 1.04349174843484e+00 3.26392824465942e-01 -2.23774966350859e-01 + 2.87878787878788e+01 1.03866453309221e+00 3.39411457582714e-01 -2.27737949543009e-01 + 2.93939393939394e+01 1.03383731774957e+00 3.52430090699486e-01 -2.31700932735158e-01 + 3.00000000000000e+01 1.02901010240694e+00 3.65448723816258e-01 -2.35663915927308e-01 + 3.30000000000000e+01 1.00799494072346e+00 4.33318703053973e-01 -2.53423049843193e-01 + 3.60000000000000e+01 9.87774181033947e-01 5.04059360049167e-01 -2.69936854350083e-01 + 3.90000000000000e+01 9.66310039303889e-01 5.77527369809482e-01 -2.85448473353340e-01 + 4.20000000000000e+01 9.41301057332367e-01 6.52705635149657e-01 -3.00284968060017e-01 + 4.50000000000000e+01 9.15005895616392e-01 7.28313235916803e-01 -3.14934043892456e-01 + 4.80000000000000e+01 8.81556701601667e-01 8.03911570370646e-01 -3.28999157277327e-01 + 5.10000000000000e+01 8.43945446946677e-01 8.77985618172744e-01 -3.42814128421300e-01 + 5.40000000000000e+01 7.98009803441727e-01 9.49010994678426e-01 -3.56128799002399e-01 + 5.70000000000000e+01 7.52074110859421e-01 1.02003542859361e+00 -3.69443367867275e-01 + 6.00000000000000e+01 7.06138393738624e-01 1.09105939121714e+00 -3.82757885874428e-01 + 6.30000000000000e+01 6.44352602071576e-01 1.14892681074432e+00 -3.94831160514253e-01 + 6.60000000000000e+01 5.82566474543015e-01 1.20679411749904e+00 -4.06904424514653e-01 + 6.90000000000000e+01 5.20779947012492e-01 1.26466142425377e+00 -4.18977688515053e-01 + 7.20000000000000e+01 4.51477435205418e-01 1.30909618833200e+00 -4.29844051243441e-01 + 7.50000000000000e+01 3.78417085122278e-01 1.34681495605404e+00 -4.40106988042700e-01 + 7.80000000000000e+01 3.05355897825734e-01 1.38453415600310e+00 -4.50369442444556e-01 + 8.10000000000000e+01 2.30983767510451e-01 1.41401807310167e+00 -4.59788643436343e-01 + 8.40000000000000e+01 1.53989841650875e-01 1.42703199295995e+00 -4.67521395816866e-01 + 8.70000000000000e+01 7.69949275996385e-02 1.44004601223740e+00 -4.75253807270785e-01 + 9.00000000000000e+01 -3.36381509228363e-07 1.45305991877593e+00 -4.82986022704544e-01 + 9.30000000000000e+01 -5.38962044824732e-02 1.44004599891764e+00 -4.86623800302551e-01 + 9.60000000000000e+01 -1.07792278449097e-01 1.42703202935019e+00 -4.90261391797104e-01 + 9.90000000000000e+01 -1.61688764154490e-01 1.41401796036258e+00 -4.93898611078011e-01 + 1.02000000000000e+02 -2.13749236173153e-01 1.38453397332146e+00 -4.94263399100743e-01 + 1.05000000000000e+02 -2.64891721229873e-01 1.34681520559943e+00 -4.92992006930171e-01 + 1.08000000000000e+02 -3.16034192336304e-01 1.30909600565222e+00 -4.91720000190610e-01 + 1.11000000000000e+02 -3.64545857584686e-01 1.26466092295440e+00 -4.89201393327162e-01 + 1.14000000000000e+02 -4.07795991243718e-01 1.20679427930608e+00 -4.84189624190406e-01 + 1.17000000000000e+02 -4.51046455307775e-01 1.14892719359139e+00 -4.79177416768754e-01 + 1.20000000000000e+02 -4.94297062881228e-01 1.09105986110795e+00 -4.74164986774198e-01 + 1.23000000000000e+02 -5.26452064865786e-01 1.02003589848443e+00 -4.67401828422766e-01 + 1.26000000000000e+02 -5.58606989674918e-01 9.49011464578596e-01 -4.60638644238479e-01 + 1.29000000000000e+02 -5.90761760127430e-01 8.77986088072913e-01 -4.53875408386550e-01 + 1.32000000000000e+02 -6.15420484918018e-01 8.03908692975958e-01 -4.47922977473614e-01 + 1.35000000000000e+02 -6.36331195763501e-01 7.28305292210269e-01 -4.42375948063776e-01 + 1.38000000000000e+02 -6.57241666993606e-01 6.52702757782291e-01 -4.36828382226539e-01 + 1.41000000000000e+02 -6.76094612754094e-01 5.78615738508474e-01 -4.33407800721224e-01 + 1.44000000000000e+02 -6.90832490879619e-01 5.07559761840581e-01 -4.34241205139103e-01 + 1.47000000000000e+02 -7.05570256415403e-01 4.36504328003481e-01 -4.35074603190205e-01 + 1.50000000000000e+02 -7.20307965658325e-01 3.65449165572087e-01 -4.35907998058031e-01 + 1.53000000000000e+02 -7.46801078706125e-01 3.07518227898197e-01 -4.57805065052203e-01 + 1.56000000000000e+02 -7.73294117948629e-01 2.49587342086377e-01 -4.79701897484255e-01 + 1.59000000000000e+02 -7.99786954801670e-01 1.91656498833410e-01 -5.01598162643690e-01 + 1.62000000000000e+02 -7.40790822868899e-01 1.53560806333696e-01 -5.07117800599882e-01 + 1.65000000000000e+02 -6.39049483540701e-01 1.25382856960915e-01 -5.04448986449602e-01 + 1.68000000000000e+02 -5.37308710076014e-01 9.72046304867630e-02 -5.01779602888076e-01 + 1.71000000000000e+02 -4.22533481739914e-01 7.05772804657932e-02 -4.50000513056908e-01 + 1.74000000000000e+02 -2.81688735121593e-01 4.70517557569334e-02 -2.99999717902353e-01 + 1.77000000000000e+02 -1.40202251216632e-01 3.86002570677554e-02 -6.87686132694523e-02 + 1.80000000000000e+02 0.00000000000000e+00 3.76960000000000e-02 2.00000000000000e-01 diff --git a/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_29.dat b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_29.dat new file mode 100644 index 00000000..31764aed --- /dev/null +++ b/Test_Cases/NREL_2p8_127/Airfoils/NREL-2p8-127_AeroDyn15_Polar_29.dat @@ -0,0 +1,254 @@ +! ------------ AirfoilInfo v1.01.x Input File ---------------------------------- +! AeroElasticSE FAST driver +! line +! line +! ------------------------------------------------------------------------------ +DEFAULT InterpOrd ! Interpolation order to use for quasi-steady table lookup {1=linear; 3=cubic spline; "default"} [default=3] +1 NonDimArea ! The non-dimensional area of the airfoil (area/chord^2) (set to 1.0 if unsure or unneeded) +@"NREL-2p8-127_AF29_Coords.txt" NumCoords ! The number of coordinates in the airfoil shape file. Set to zero if coordinates not included. +AF29_BL.txt BL_file ! The file name including the boundary layer characteristics of the profile. Ignored if the aeroacoustic module is not called. +1 NumTabs ! Number of airfoil tables in this file. Each table must have lines for Re and Ctrl. +! ------------------------------------------------------------------------------ +! data for table 1 +! ------------------------------------------------------------------------------ +6.000000 Re ! Reynolds number in millions +0 Ctrl ! Control setting (must be 0 for current AirfoilInfo) +True InclUAdata ! Is unsteady aerodynamics data included in this table? If TRUE, then include 30 UA coefficients below this line +!........................................ +-4.024505 alpha0 ! 0-lift angle of attack, depends on airfoil. +11.306884 alpha1 ! Angle of attack at f=0.7, (approximately the stall angle) for AOA>alpha0. (deg) +-9.832557 alpha2 ! Angle of attack at f=0.7, (approximately the stall angle) for AOA1] +0.000000 S2 ! Constant in the f curve best-fit for AOA> alpha1; by definition it depends on the airfoil. [ignored if UAMod<>1] +0.000000 S3 ! Constant in the f curve best-fit for alpha2<=AOA< alpha0; by definition it depends on the airfoil. [ignored if UAMod<>1] +0.000000 S4 ! Constant in the f curve best-fit for AOA< alpha2; by definition it depends on the airfoil. [ignored if UAMod<>1] +1.557235 Cn1 ! Critical value of C0n at leading edge separation. It should be extracted from airfoil data at a given Mach and Reynolds number. It can be calculated from the static value of Cn at either the break in the pitching moment or the loss of chord force at the onset of stall. It is close to the condition of maximum lift of the airfoil at low Mach numbers. +-0.830241 Cn2 ! As Cn1 for negative AOAs. +Default St_sh ! Strouhal's shedding frequency constant. [default = 0.19] +0.006417 Cd0 ! 2D drag coefficient value at 0-lift. +-0.112920 Cm0 ! 2D pitching moment coefficient about 1/4-chord location, at 0-lift, positive if nose up. [If the aerodynamics coefficients table does not include a column for Cm, this needs to be set to 0.0] +0.000000 k0 ! Constant in the \hat(x)_cp curve best-fit; = (\hat(x)_AC-0.25). [ignored if UAMod<>1] +0.000000 k1 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k2 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k3 ! Constant in the \hat(x)_cp curve best-fit. [ignored if UAMod<>1] +0.000000 k1_hat ! Constant in the expression of Cc due to leading edge vortex effects. [ignored if UAMod<>1] +Default x_cp_bar ! Constant in the expression of \hat(x)_cp^v. [ignored if UAMod<>1, default = 0.2] +Default UACutout ! Angle of attack above which unsteady aerodynamics are disabled (deg). [Specifying the string "Default" sets UACutout to 45 degrees] +Default filtCutOff ! Cut-off frequency (-3 dB corner frequency) for low-pass filtering the AoA input to UA, as well as the 1st and 2nd derivatives (Hz) [default = 20] +!........................................ +! Table of aerodynamics coefficients +200 NumAlf ! Number of data lines in the following table +! Alpha Cl Cd Cm +! (deg) (-) (-) (-) +-1.80000000000000e+02 0.00000000000000e+00 3.76960000000000e-02 2.00000000000000e-01 +-1.77000000000000e+02 1.49471782056503e-01 3.76960000000000e-02 2.00000000000000e-01 +-1.74000000000000e+02 3.00312917607843e-01 4.52351574641884e-02 2.39999774321882e-01 +-1.71000000000000e+02 4.50470313592540e-01 6.78528773607728e-02 3.60000410445527e-01 +-1.68000000000000e+02 5.62141300000530e-01 9.47828314689296e-02 3.00100237874998e-01 +-1.65000000000000e+02 6.54569530813285e-01 1.23868852352745e-01 1.50251760664942e-01 +-1.62000000000000e+02 7.46998820775784e-01 1.52955206537882e-01 4.01566317437541e-04 +-1.59000000000000e+02 7.99786954801670e-01 1.91656498833410e-01 -9.28123657821359e-02 +-1.56000000000000e+02 7.73294117948629e-01 2.49587342086377e-01 -7.27556892942309e-02 +-1.53000000000000e+02 7.46801078706125e-01 3.07518227898197e-01 -5.26992595835046e-02 +-1.50000000000000e+02 7.20307965658325e-01 3.65449165572087e-01 -3.26429649313102e-02 +-1.47000000000000e+02 7.05570256415403e-01 4.36504328003481e-01 -1.75932576097200e-02 +-1.44000000000000e+02 6.90832490879619e-01 5.07559761840581e-01 -2.54349280354572e-03 +-1.41000000000000e+02 6.76094612754094e-01 5.78615738508475e-01 1.25063869759013e-02 +-1.38000000000000e+02 6.57241666993606e-01 6.52702757782292e-01 2.78005506087711e-02 +-1.35000000000000e+02 6.36331195763501e-01 7.28305292210269e-01 4.32168556727960e-02 +-1.32000000000000e+02 6.15420484918018e-01 8.03908692975958e-01 5.86333373939468e-02 +-1.29000000000000e+02 5.90761760127430e-01 8.77986088072914e-01 7.42048196933640e-02 +-1.26000000000000e+02 5.58606989674918e-01 9.49011464578596e-01 9.00863038811478e-02 +-1.23000000000000e+02 5.26452064865786e-01 1.02003589848443e+00 1.05968066745086e-01 +-1.20000000000000e+02 4.94297062881228e-01 1.09105986110795e+00 1.21849968941892e-01 +-1.17000000000000e+02 4.51046455307775e-01 1.14892719359139e+00 1.36973650595308e-01 +-1.14000000000000e+02 4.07795991243718e-01 1.20679427930608e+00 1.52097072994036e-01 +-1.11000000000000e+02 3.64545857584686e-01 1.26466092295440e+00 1.67219979864852e-01 +-1.08000000000000e+02 3.16034192336304e-01 1.30909600565222e+00 1.80733001904303e-01 +-1.05000000000000e+02 2.64891721229873e-01 1.34681520559943e+00 1.93441069265733e-01 +-1.02000000000000e+02 2.13749236173153e-01 1.38453397332146e+00 2.06148391012093e-01 +-9.90000000000000e+01 1.61688764154489e-01 1.41401796036258e+00 2.17512373571396e-01 +-9.60000000000000e+01 1.07792278449096e-01 1.42703202935019e+00 2.26189619569497e-01 +-9.30000000000000e+01 5.38962044824732e-02 1.44004599891764e+00 2.34866399278379e-01 +-9.00000000000000e+01 3.36381508994621e-07 1.45305991877593e+00 2.43542945846872e-01 +-8.70000000000000e+01 -5.38961493200293e-02 1.44004601223740e+00 2.47180796579284e-01 +-8.40000000000000e+01 -1.07792429155678e-01 1.42703199295995e+00 2.50818601967904e-01 +-8.10000000000000e+01 -1.61688297256642e-01 1.41401807310167e+00 2.54456379565910e-01 +-7.80000000000000e+01 -2.13748988477021e-01 1.38453415600310e+00 2.54821405258420e-01 +-7.50000000000000e+01 -2.64892059585176e-01 1.34681495605404e+00 2.53549998518008e-01 +-7.20000000000000e+01 -3.16033944645590e-01 1.30909618833200e+00 2.52278006351131e-01 +-6.90000000000000e+01 -3.64545482908305e-01 1.26466142425377e+00 2.49759236748571e-01 +-6.60000000000000e+01 -4.07796112179989e-01 1.20679411749904e+00 2.44746810177687e-01 +-6.30000000000000e+01 -4.51046741451673e-01 1.14892681074432e+00 2.39734383606802e-01 +-6.00000000000000e+01 -4.94297275617037e-01 1.09105939121714e+00 2.34721942034639e-01 +-5.70000000000000e+01 -5.26452277601595e-01 1.02003542859361e+00 2.27959383679512e-01 +-5.40000000000000e+01 -5.58607202409195e-01 9.49010994678426e-01 2.21196599493265e-01 +-5.10000000000000e+01 -5.90761972861707e-01 8.77985618172743e-01 2.14433363641336e-01 +-4.80000000000000e+01 -6.17089671120620e-01 8.03911570370645e-01 2.07956980763680e-01 +-4.50000000000000e+01 -6.40503926932036e-01 7.28313235916803e-01 2.01624019763027e-01 +-4.20000000000000e+01 -6.58910840133311e-01 6.52705635149657e-01 1.96862389618034e-01 +-3.90000000000000e+01 -6.76417027511146e-01 5.77527369809482e-01 1.92714494884031e-01 +-3.60000000000000e+01 -6.91442126694186e-01 5.04059360049167e-01 1.90773003374389e-01 +-3.30000000000000e+01 -7.05593958510807e-01 4.33318703053973e-01 1.91908992233939e-01 +-3.00000000000000e+01 -7.20308071684859e-01 3.65448723816258e-01 1.96465039072780e-01 +-2.93939393939394e+01 -7.23687122424702e-01 3.52430090699486e-01 1.98306835359819e-01 +-2.87878787878788e+01 -7.27066173164544e-01 3.39411457582714e-01 2.00148631646857e-01 +-2.81818181818182e+01 -7.30445223904387e-01 3.26392824465942e-01 2.01990427933895e-01 +-2.75757575757576e+01 -7.34244974993610e-01 3.13793078035017e-01 2.04486437101527e-01 +-2.69696969696970e+01 -7.38225041700157e-01 3.01372869870364e-01 2.07262847270964e-01 +-2.63636363636364e+01 -7.42205108406705e-01 2.88952661705710e-01 2.10039257440401e-01 +-2.57575757575758e+01 -7.46555462653963e-01 2.76796374908870e-01 2.13304160376248e-01 +-2.51515151515151e+01 -7.51461161912085e-01 2.65035908653530e-01 2.17301688612281e-01 +-2.45454545454545e+01 -7.56366861170206e-01 2.53275442398190e-01 2.21299216848314e-01 +-2.39393939393939e+01 -7.61408677387006e-01 2.41586670872199e-01 2.25459952105595e-01 +-2.33333333333333e+01 -7.67675572584808e-01 2.30543165790786e-01 2.31089582151761e-01 +-2.27272727272727e+01 -7.73942467782610e-01 2.19499660709374e-01 2.36719212197927e-01 +-2.21212121212121e+01 -7.80209362980412e-01 2.08456155627962e-01 2.42348842244093e-01 +-2.15151515151515e+01 -7.88045801889462e-01 1.98028860914946e-01 2.49772963288095e-01 +-2.09090909090909e+01 -7.96274727686348e-01 1.87755658431417e-01 2.57645822511188e-01 +-2.03030303030303e+01 -8.04503653483233e-01 1.77482455947888e-01 2.65518681734281e-01 +-1.96969696969697e+01 -8.13721563222721e-01 1.67514267203666e-01 2.74509167058282e-01 +-1.90909090909091e+01 -8.23928400957602e-01 1.57851074944005e-01 2.84617215258648e-01 +-1.84848484848485e+01 -8.22646763588942e-01 1.48546901850923e-01 2.82973548468764e-01 +-1.78787878787879e+01 -8.19241173382965e-01 1.39555143470384e-01 2.78335696038153e-01 +-1.72727272727273e+01 -8.15446564330172e-01 1.31559857952983e-01 2.70013132308244e-01 +-1.66666666666667e+01 -8.03296442896411e-01 1.23564572435581e-01 2.53038383173389e-01 +-1.60606060606061e+01 -7.84310064075638e-01 1.15569286918180e-01 2.28984646695628e-01 +-1.54545454545455e+01 -7.65324664303493e-01 1.07574959135167e-01 2.04931605118311e-01 +-1.48484848484848e+01 -7.46338949873589e-01 9.95804717419686e-02 1.80878447733115e-01 +-1.42424242424242e+01 -7.27351964982053e-01 9.15851862245671e-02 1.56824711255353e-01 +-1.36363636363636e+01 -7.08366360011050e-01 8.35901755495681e-02 1.32771801638210e-01 +-1.30303030303030e+01 -6.89379049576426e-01 7.55946380877238e-02 1.08716367776058e-01 +-1.24242424242424e+01 -6.70393771825338e-01 6.75996503421813e-02 8.46634665540094e-02 +-1.18181818181818e+01 -6.51406715493019e-01 5.96041815994351e-02 6.06091788446317e-02 +-1.12121212121212e+01 -6.32421454753742e-01 5.16093541595814e-02 3.65562447387649e-02 +-1.06060606060606e+01 -6.13434931389144e-01 4.36139312036515e-02 1.25016705283901e-02 +-1.00000000000000e+01 -5.94448865749824e-01 3.56199434645880e-02 -1.15511700947924e-02 +-9.39393939393939e+00 -5.75463587974779e-01 2.76249557125666e-02 -3.56050107398163e-02 +-8.78787878787879e+00 -5.51403736673166e-01 2.01382292840361e-02 -5.87079533337773e-02 +-8.18181818181818e+00 -5.17926305822838e-01 1.35966762681340e-02 -8.00434824257992e-02 +-7.57575757575758e+00 -4.48012922709353e-01 1.04062079021576e-02 -9.38202376741164e-02 +-6.96969696969697e+00 -3.62306556115099e-01 8.91516259682331e-03 -1.02639375733790e-01 +-6.36363636363636e+00 -2.86592508663283e-01 7.49091941073086e-03 -1.05345402946346e-01 +-5.75757575757576e+00 -2.11681301136276e-01 7.05454293237208e-03 -1.07624256716558e-01 +-5.15151515151515e+00 -1.37278254009080e-01 6.76061420557612e-03 -1.09615086355391e-01 +-4.54545454545454e+00 -6.32445813538124e-02 6.51817895525840e-03 -1.11463657835562e-01 +-3.93939393939394e+00 1.03326972358679e-02 6.40000000000000e-03 -1.13157562089366e-01 +-3.33333333333333e+00 8.37358252318253e-02 6.36666256139732e-03 -1.14700049263232e-01 +-2.72727272727273e+00 1.57144966549608e-01 6.30000000000000e-03 -1.16209080405869e-01 +-2.12121212121212e+00 2.30132082000148e-01 6.30000000000000e-03 -1.17633365893514e-01 +-1.51515151515152e+00 3.03270194866406e-01 6.30000000000000e-03 -1.18966675734322e-01 +-9.09090909090912e-01 3.76007887483945e-01 6.30000000000000e-03 -1.20399977937206e-01 +-3.03030303030302e-01 4.48619648411214e-01 6.33939639599868e-03 -1.21733360355986e-01 + 3.03030303030302e-01 5.21162162400790e-01 6.40000000000000e-03 -1.23066639644014e-01 + 9.09090909090912e-01 5.93483011578421e-01 6.40000000000000e-03 -1.24318201875268e-01 + 1.51515151515152e+00 6.65499510346614e-01 6.50000000000000e-03 -1.25430294786980e-01 + 2.12121212121212e+00 7.37449762821818e-01 6.52423946422604e-03 -1.26642394642260e-01 + 2.72727272727273e+00 8.08982292442682e-01 6.64545535339469e-03 -1.27809098180552e-01 + 3.33333333333333e+00 8.80397573785818e-01 6.76666256139732e-03 -1.28833300491179e-01 + 3.93939393939394e+00 9.51421826139261e-01 6.88787983927956e-03 -1.29890918553516e-01 + 4.54545454545455e+00 1.02186280754731e+00 7.00908947762920e-03 -1.30763626343404e-01 + 5.15151515151515e+00 1.09189627700035e+00 7.16061420557612e-03 -1.31612149719516e-01 + 5.75757575757576e+00 1.16079952835358e+00 7.45454293237208e-03 -1.32306057243163e-01 + 6.36363636363637e+00 1.22720139059598e+00 7.96364926341358e-03 -1.32572729852683e-01 + 6.96969696969697e+00 1.28802463107430e+00 8.94546166938641e-03 -1.32130299072563e-01 + 7.57575757575757e+00 1.33932330958836e+00 1.07272369407300e-02 -1.30081868282978e-01 + 8.18181818181818e+00 1.38679186165234e+00 1.25091248425769e-02 -1.27572678796319e-01 + 8.78787878787879e+00 1.43442629439737e+00 1.40333059500537e-02 -1.25090961368079e-01 + 9.39393939393939e+00 1.48072485366775e+00 1.53666845487907e-02 -1.22230262389112e-01 + 1.00000000000000e+01 1.51619976429293e+00 1.64999922859505e-02 -1.21700000000000e-01 + 1.06060606060606e+01 1.54652659135150e+00 1.81605492792916e-02 -1.21700000000000e-01 + 1.12121212121212e+01 1.57015165312925e+00 2.03485003516014e-02 -1.21912125087900e-01 + 1.18181818181818e+01 1.58466335911404e+00 3.00903504536651e-02 -1.23218115609323e-01 + 1.24242424242424e+01 1.55439065028940e+00 4.64546360854226e-02 -1.25157586499013e-01 + 1.30303030303030e+01 1.50697060273102e+00 6.28179372626244e-02 -1.27096940712607e-01 + 1.36363636363636e+01 1.44636161651328e+00 7.91823635414146e-02 -1.29036428271575e-01 + 1.42424242424242e+01 1.39302963646758e+00 9.22728558241098e-02 -1.30587894023598e-01 + 1.48484848484848e+01 1.35060468299441e+00 1.00454811136793e-01 -1.31557607245842e-01 + 1.54545454545455e+01 1.32181803006545e+00 1.08636414852911e-01 -1.32527278797382e-01 + 1.60606060606061e+01 1.29757644961134e+00 1.16817948256172e-01 -1.33496942015546e-01 + 1.66666666666667e+01 1.27333361905524e+00 1.24999903568856e-01 -1.34466655237790e-01 + 1.72727272727273e+01 1.24363618274871e+00 1.33181858881539e-01 -1.35436368460034e-01 + 1.78787878787879e+01 1.20727193691457e+00 1.41363814194223e-01 -1.36406081682278e-01 + 1.84848484848485e+01 1.18992978938591e+00 1.49497879761678e-01 -1.37375750456550e-01 + 1.90909090909091e+01 1.17704330010331e+00 1.57851074944005e-01 -1.39089585145003e-01 + 1.96969696969697e+01 1.16246123752382e+00 1.67514267203666e-01 -1.45021805782080e-01 + 2.03030303030303e+01 1.14929279501435e+00 1.77482455947888e-01 -1.51632351934001e-01 + 2.09090909090909e+01 1.13753805254846e+00 1.87755658431417e-01 -1.58921261976074e-01 + 2.15151515151515e+01 1.12578331008257e+00 1.98028860914946e-01 -1.66210172018147e-01 + 2.21212121212121e+01 1.11458874358451e+00 2.08456155627962e-01 -1.73224623443957e-01 + 2.27272727272727e+01 1.10563430457793e+00 2.19499660709374e-01 -1.79141522802416e-01 + 2.33333333333333e+01 1.09667986557135e+00 2.30543165790786e-01 -1.85058422160874e-01 + 2.39393939393939e+01 1.08772542656477e+00 2.41586670872199e-01 -1.90975321519332e-01 + 2.45454545454545e+01 1.08052187960139e+00 2.53275442398190e-01 -1.96074592475065e-01 + 2.51515151515151e+01 1.07351287201350e+00 2.65035908653530e-01 -2.01083017784734e-01 + 2.57575757575758e+01 1.06650386442561e+00 2.76796374908870e-01 -2.06091443094404e-01 + 2.63636363636364e+01 1.06028924575223e+00 2.88952661705710e-01 -2.10729607665482e-01 + 2.69696969696970e+01 1.05460430198682e+00 3.01372869870364e-01 -2.15120893385337e-01 + 2.75757575757576e+01 1.04891935822142e+00 3.13793078035017e-01 -2.19512179105193e-01 + 2.81818181818182e+01 1.04349174843484e+00 3.26392824465942e-01 -2.23774966350859e-01 + 2.87878787878788e+01 1.03866453309221e+00 3.39411457582714e-01 -2.27737949543009e-01 + 2.93939393939394e+01 1.03383731774957e+00 3.52430090699486e-01 -2.31700932735158e-01 + 3.00000000000000e+01 1.02901010240694e+00 3.65448723816258e-01 -2.35663915927308e-01 + 3.30000000000000e+01 1.00799494072346e+00 4.33318703053973e-01 -2.53423049843193e-01 + 3.60000000000000e+01 9.87774181033947e-01 5.04059360049167e-01 -2.69936854350083e-01 + 3.90000000000000e+01 9.66310039303889e-01 5.77527369809482e-01 -2.85448473353340e-01 + 4.20000000000000e+01 9.41301057332367e-01 6.52705635149657e-01 -3.00284968060017e-01 + 4.50000000000000e+01 9.15005895616392e-01 7.28313235916803e-01 -3.14934043892456e-01 + 4.80000000000000e+01 8.81556701601667e-01 8.03911570370646e-01 -3.28999157277327e-01 + 5.10000000000000e+01 8.43945446946677e-01 8.77985618172744e-01 -3.42814128421300e-01 + 5.40000000000000e+01 7.98009803441727e-01 9.49010994678426e-01 -3.56128799002399e-01 + 5.70000000000000e+01 7.52074110859421e-01 1.02003542859361e+00 -3.69443367867275e-01 + 6.00000000000000e+01 7.06138393738624e-01 1.09105939121714e+00 -3.82757885874428e-01 + 6.30000000000000e+01 6.44352602071576e-01 1.14892681074432e+00 -3.94831160514253e-01 + 6.60000000000000e+01 5.82566474543015e-01 1.20679411749904e+00 -4.06904424514653e-01 + 6.90000000000000e+01 5.20779947012492e-01 1.26466142425377e+00 -4.18977688515053e-01 + 7.20000000000000e+01 4.51477435205418e-01 1.30909618833200e+00 -4.29844051243441e-01 + 7.50000000000000e+01 3.78417085122278e-01 1.34681495605404e+00 -4.40106988042700e-01 + 7.80000000000000e+01 3.05355897825734e-01 1.38453415600310e+00 -4.50369442444556e-01 + 8.10000000000000e+01 2.30983767510451e-01 1.41401807310167e+00 -4.59788643436343e-01 + 8.40000000000000e+01 1.53989841650875e-01 1.42703199295995e+00 -4.67521395816866e-01 + 8.70000000000000e+01 7.69949275996385e-02 1.44004601223740e+00 -4.75253807270785e-01 + 9.00000000000000e+01 -3.36381509228363e-07 1.45305991877593e+00 -4.82986022704544e-01 + 9.30000000000000e+01 -5.38962044824732e-02 1.44004599891764e+00 -4.86623800302551e-01 + 9.60000000000000e+01 -1.07792278449097e-01 1.42703202935019e+00 -4.90261391797104e-01 + 9.90000000000000e+01 -1.61688764154490e-01 1.41401796036258e+00 -4.93898611078011e-01 + 1.02000000000000e+02 -2.13749236173153e-01 1.38453397332146e+00 -4.94263399100743e-01 + 1.05000000000000e+02 -2.64891721229873e-01 1.34681520559943e+00 -4.92992006930171e-01 + 1.08000000000000e+02 -3.16034192336304e-01 1.30909600565222e+00 -4.91720000190610e-01 + 1.11000000000000e+02 -3.64545857584686e-01 1.26466092295440e+00 -4.89201393327162e-01 + 1.14000000000000e+02 -4.07795991243718e-01 1.20679427930608e+00 -4.84189624190406e-01 + 1.17000000000000e+02 -4.51046455307775e-01 1.14892719359139e+00 -4.79177416768754e-01 + 1.20000000000000e+02 -4.94297062881228e-01 1.09105986110795e+00 -4.74164986774198e-01 + 1.23000000000000e+02 -5.26452064865786e-01 1.02003589848443e+00 -4.67401828422766e-01 + 1.26000000000000e+02 -5.58606989674918e-01 9.49011464578596e-01 -4.60638644238479e-01 + 1.29000000000000e+02 -5.90761760127430e-01 8.77986088072913e-01 -4.53875408386550e-01 + 1.32000000000000e+02 -6.15420484918018e-01 8.03908692975958e-01 -4.47922977473614e-01 + 1.35000000000000e+02 -6.36331195763501e-01 7.28305292210269e-01 -4.42375948063776e-01 + 1.38000000000000e+02 -6.57241666993606e-01 6.52702757782291e-01 -4.36828382226539e-01 + 1.41000000000000e+02 -6.76094612754094e-01 5.78615738508474e-01 -4.33407800721224e-01 + 1.44000000000000e+02 -6.90832490879619e-01 5.07559761840581e-01 -4.34241205139103e-01 + 1.47000000000000e+02 -7.05570256415403e-01 4.36504328003481e-01 -4.35074603190205e-01 + 1.50000000000000e+02 -7.20307965658325e-01 3.65449165572087e-01 -4.35907998058031e-01 + 1.53000000000000e+02 -7.46801078706125e-01 3.07518227898197e-01 -4.57805065052203e-01 + 1.56000000000000e+02 -7.73294117948629e-01 2.49587342086377e-01 -4.79701897484255e-01 + 1.59000000000000e+02 -7.99786954801670e-01 1.91656498833410e-01 -5.01598162643690e-01 + 1.62000000000000e+02 -7.40790822868899e-01 1.53560806333696e-01 -5.07117800599882e-01 + 1.65000000000000e+02 -6.39049483540701e-01 1.25382856960915e-01 -5.04448986449602e-01 + 1.68000000000000e+02 -5.37308710076014e-01 9.72046304867630e-02 -5.01779602888076e-01 + 1.71000000000000e+02 -4.22533481739914e-01 7.05772804657932e-02 -4.50000513056908e-01 + 1.74000000000000e+02 -2.81688735121593e-01 4.70517557569334e-02 -2.99999717902353e-01 + 1.77000000000000e+02 -1.40202251216632e-01 3.86002570677554e-02 -6.87686132694523e-02 + 1.80000000000000e+02 0.00000000000000e+00 3.76960000000000e-02 2.00000000000000e-01 diff --git a/Test_Cases/NREL_2p8_127/NREL-2.8-127.xlsx b/Test_Cases/NREL_2p8_127/NREL-2.8-127.xlsx new file mode 100644 index 0000000000000000000000000000000000000000..5d5d8946639878b3e2597fa3f73ca99c53f5af73 GIT binary patch literal 14107 zcmeHu1$P`tvUQ6ki!8F(VrC|bnVFfHnJsEb7BkBNibyZdI>JKryO zulk&>Q=JvJvm)bWL}f(ENrHi+0w4j<004jhz|ZDCVFLmHfI|QPC;(_sO+i~5Cu18Y zT_txrV@GXTH)|{W9B@$bECA^H{r`9TFV;Y*(vVFz{l_-dLtdeFmC)?q;$mo=W*kl8 zeW+x&ST*AMT}<+4Z!!~kH>T_Rp~xFXFFSD7~cE`kEJO0KE)5l{SZcp5cJ zyUGlcQxK2OycDF+nh_6<2?+DCiUIW!-}Eaa9no6za3kY~o@F;Ly(3YK=8T>4dS~5d zF8`_MaOEu7xoX!Yi=R=jS1FEH$IOFyWuY{~8pg*mcQCJR7{*>Vw$wka(ETR%@iQ5s zFWlP#p&fxA&DQ|y%_m6LIF4nY`!E;RDs1TI=uhzok+baVQR&NoBv*a(m~ze=IB-9> zV?hVA#oKV4hmsY9wTv8oyv@W51nk#$p1r++0p$LJrgh5nMAz@OC-vS6`%Y6`2V*No zI@&+J|Bs&ki#hpkk6s!pE!#s62Rsvd4j#OlTZ{fEAnD34)u^$a*#Oz#gj5% zWdmE*VcbNT??Ph!0X%OAht%$OQq8W#Ir9q|xC!xEpkyYoF zP+AAdix-Vd`k(?KGx9y-gy;ZC){U=5E%U`lhI=m?Oi#(+`H+7YUg7$?$NF!QU@Mfb zrhowe_3y3?@m(`+R&=hm4weSCww8bRu~KDC+Y_VB2dDj<8wzqFec8v$smt zGEc}w4xJP#fSP{hqT;I!S1AFH6>VcrR*B<9L!S1O2NSPHYfaT<6g1qOF{J^r{PHQ% zJqXLs1&>kgKrihhV)G9Q7eJXC)8&JWai6ynr=C8Kp$84HulZ?*dGXd}7}`41sZM0A zdGKl~TC+mk3SY3asmLjsV-?g@fySws@+kBBT!C^p0bQz8i8FzF-qP4jU`Vxu$osA& zmMutS<57Mkp=x(D!|rRKy|KztJcwD%DtlWGhCLAKDx0^TT9#Eh7Xt8D^(*_?{0?SH zED~YYFA~0hm>G&b#=R{v)BB+NpX_1a1pmbF=V3_b0i)XTj!AIsywvHcd>Apq_`zaE z61eG&G{$XLb6qooRL`Bx)Q zTLp^eUzhMbtBl}*6NzZt$*U9MFWoavHCk?%oWA zy7ZAEQ`-{-0^at9Ab#E?e&J8#m+WhYNf*SbdYSx5*o#QFK6*jQ#3qn`#6FnP$Mn;X zjlT+glf6cP3wHGTX83t`dYn$8CkVxU(JA?mFSB;+iCLG)V$F6!e^}ESK8r7g$cpT4 zrA2~kxJ|QaQBhufo2hgco8sCn4PL9q=Y`YCRk(Ril|kfQtYie7rIQ!_B}16_s-qI= zLJDE);tnY-vMZW&d|r5ipTy-+{^VDaaGEjPBcu4CaelEEz?sPezZH7RF*)&uVnsu< zH;d0XrIv(BXCL?aVpi(suWyfNzH#2gBNL%Jo9=S$#HGDX;UPUAUV*AwF4zjf#rnLemO1(AR7%v zL<><;*yNm;r?Ual>?8cbVO+WN_v(^T5+{|NCXZQ09 z_9yq$bi8x)zgg_Z6Q6YT-qQT;>aYONAnz>xhqwE8F8|B(fxHK%?{mTb?xR#eTC(>& zFoS&!rgu$qK|@+{q9Z(3K0<^Zs-;*VC1CQo-oU18)>fOBqyw`Bx}S{=xZJTIY=fcP zbWs(4Lk9Oiu{z^|upPS^1A{g=Df{d%3W0)re0WrH0*jF9h|O>mvVs^qzStA6d$N0YHFvUr z82t7;@T|@GrE!DWhL^5fwP6G?*q7!E(f8pV&)4&9z~bfUrD4~>@oUh^6JqcNYg)@r zZtl~F?MPZ*oBA4!?ZZ&g+@nd=R@702=$-4)?)KHaB-?`M`m&o-O=C0nss_7GM_>Qp zNK(nju9fq{i-~*75|%n$1v>V;@7u}Y>Fd<;*skX28ufgKZ-=LAQ*%>KZ$ZgX$(U~L zR8K(K$j((oL&?qd49nR|!4Y~AlyCXN_r0^z3x*wE+e{}%=O&%Cigqiw#He~p8(m(! z-Q2$2xV+n!4Ws@W(WBicD*MeEinlYGp&&BN*Cn+(TdXkIexsK8fsG0tU-oC+4KlW& z`3}je@s6Vcn@id}b2s!IqhF*mOQqlY-?*OdU$4+UCpK`Z(RFySKhNR4&EEuz;%!7h z?faG|`mUnC`BbWVJw9D}xHqX^esp!i-@BTzxM=}QJji~EyCdS0qNQb1R5liJB+H?om;TQ{v1(vA&2Ap zYFXdf@iYF?Zl`Bv+B9rzd*|uqFbeF;IP1m+4YAK^mEjWI+u^`n66h-$^ZcoM0v=w5 zx9@d8pY|nNeaz2af}EC%a@{vzr1 zA%#e$GzOC)SD#{-w{wJzBJQoj?6&Q8F*!_a@9MI6aa?jMO4d^2d9fi46|1u+rkr0U z_bfE?N!UT_*P+sY_#H+ixTzE)^C5j-gkBH4YZEkOB`S}gc3viL=9hgi6v|zUb^O6f z+@42-H&zZIWF_sK@h4^#i`0e+))BfCE{0ah@4lQ`~wdak}JOmN8nFUNN{d z$*y&}pyem1?&#>CUB{_POK{wB42-*SDEp+v%h?7D@dV-+kafrl>%lk+GIBU;+xZOo zNf*@{srX;%DWH1|C+c3&u26oKne}iq{UYfih_`67(AWrm=4203uC4V-ozjVU47Fh2 zTzX`kfH9sxFmo}k{asNeRJw3{E~wwZhCa0=TefZDxN8K{d2yu2-{;!SmT;mH2_2C- zY;ZC%Eq;^MrIQQWKTLb?h`J<;HZ2f6_KYYS(=p+P2}v>rYug?%Tq)5_!de_MmUbsC zDbX8##w-XUT~}9cr1fbIE-?B@u4C04rkwk|GcoW2QE`gffubAWRg6aLAonAedg#HU zy2>9dulY1a30$*BaOHJdW4;+=H`z{%y?4f*9+v{52bV!Awe-#^r?V?{y$=;=1_o;x z>kM;>5;IyPW>YzJYnNYKny4p=YqzbF_L%Hd*s%KpoNQ0(kOLJbbkcP$COK)+tdN4o zrB}B;RJ*kPsTO=eM`dDl*Vq`Ej*L-l(~C<&Bkq!x`7uIg+|ylsazbaE0l2;*MS$b5 z8!8Ti>rWIJ>ejjyoGnGA*{@6{)1FAN$+d_*1jJj_M=?V4zh$=@_1gS z-{$53Df^y9Uw_10Wv)Yknf1;Nver}M^U}DO3NQp5+w)shk`#(nM&BQQ$>UO6=^1zl z?R(7_+!mE7jZOaaBS|ZvCsbgEIUtRHQf?Q}N(vhEd6a|)tOD6+jj)@+INf4Y1H!hX3Eq#xYmeFRHQ9rxFsE+W6 zRa-!-LHL%8n5W;`H+6p3&cwm2KZCZyPVG$0Jcc>KaZZvD7RX5-AeG6-l5S$FFQ`>_ z5G{^t=oZkImYr+(v@K%CrlhHPT1sEFUSpwu36G?>Z`2yZ-sg9tun-KiqH@|fbpUhe zZ(t2-Q8zfN&dulAAZ`fz@T%f^w!qBg$J?CtN+vOwzX{{Kg@Z<qD}l}f5ukU{+VNIr)8Db@6n&ln9Es-$AUK8NNm(O-HnA7gOO*)p&4+_*V=KS*+_ z0scmwQ+dCCZP(<)#WnPk$xbleCuBlVpm}nNPqlkVi+t2=sEr?QOIi(HsU1wcznwX< zM`(WEIgphcNDNWcEtApR%$zKycU4Va(>$cGI4)1l*-d9htzZ_i8d@*qOdkW`HqBg` z*73-x# zVnTi=yImQqBdOD}p!ZR_4kq`<%}vAJ!g> zIKQ>z8X>N;lAH>y0E5%oiOAwo#KEo2lFp!Ye})*a|M1(3|1i5KmQJ}6(NkBXon02h z*bEtK@*UU}*Gg%8D8PF+=I+ItH=3X^#up8aJ~%XKN@<@qkN_@H&*lwJbN0bV{S(LNkRsiT)t?ols4Y}=@+yr<+4q% zrF+O`J`qXQVAOQhJObTRCFdb&5nn3lg2Hx@;xYyiDCZ5a1A9tsraL*cP2#MdjeviB zd8mzXk{8I!Fo<;K2e~r0@`bPJsaf(ZqnOeq^Ha>JM0@gtlfpoRdELDqOhM}>FA|!L zZak91DCO(KGqA=uXGDTol;HcZxoz(1#I6#WD<_^b*hARUiCZ`_MrPg>O7z**Ag_W@ z2q+eT@du6Z0|tgMPp_KFkVQu|AV zxGV`BB>h>!LR6z#XN$Q6Ilu14On&UAfK1r^qbt5;KSIxUjJLPsaKr=Z{L8~@EWV3- zNp;F`iw#snh_@oIyJUVvdfg{6LW}(L3|ABzIE(BWBocYcIL(JowlOU`ccYzaT-go4 zmltL4kKp4~+`j-94iqe!uuC3Jy=j&|5u4*AOvq;n0r>P;j6Nz7n>$Ro zLo90QY`xofjqY5VHIW%v`3P!@E~grKuftnMxb;NcgezrpxcIT( zO6{7hnmeWdL=y>(niscMhkuT-|Hd3bER>r3cp4ypLMtRO0G50< z*asBxtl0DxRTB@*(wag=mCqv5DROM_E@xq;O*Tp<$3!Jv74ixVQVbhFQX$gzEg!#| zO;Ur=h+|?_$fr>lEa@r|sM+nGhLKChENU>EN3r%i@>Y8B<0!XW9MH;kb=MuS{fOm( zA@)Jq(sN`-O5J36GNL_nPl3d5S`8cGtvH zfp^7^=CyV@Wx^#)a-0ZSlB)K2`U{flt{bpSBa!8Orw>n?9`foi_{jQeqpFE0p>g;k zRC+UMLb~PK1joYYe#Kd~Z2Gz#>k|rX-QRriA-XGfMIw$(QS=Hz{zqS>-a13 z*i+2KfzfRuYc_?M%Lo*mj9vnMS%`)zcNUXWyEY9wb8W@r^eX&&_-$RhB>`MpIY#z^ z7TDK>{aextQkMB2UiLj}6Zy;Q>)Pq89jlw@2|&3d@H!?F-GkPF+z)XiEWOs{^Ho&) zb2e^09~vP5Yfd`8bY9<-*TrtbVuAKAye?8j5^F#MQ+Xo)cbD`7$Ziu zbgB32LR7KVZ3d`lO4$lIv>4(}lO!~6?sST*a(BS637JOP+ouaF71p+toyf^gS05~v zw9PS_^`f`?*AWC}3cbmeZ}(k3h~cvee>C&gY1=}0x6o^1`Y$#H3gJb=&XY-MHX8EV z@}+VW!VJY5=UQc$v_wI~-Ljx#vvL%s=q$;a2;i{tviOrpt^FsrC|9kYR`=%{`#Oac z)EvC`%yTMNj5c6=gpRyZD39l_(n(Xk4zYwjVx^1RIUttr*r0-^xU?C&@1`~!WTJ^i zQh6I5x!(Y}zUZC+uW91lXd~z3-SZQ1hz0HWW5SU4k>pyx5oS;^rw5-0?Z`I`7$VEA z&#`IE(G9+=N0ukk5NyDfc?hpwJi&MpJ;xMtNzCiXUqiZNsM>^jQ^;7aA?^lh^;o8P zu`Ac(AppFo;m{~*#_lDUufb}t^iv%&)UlSDs}%Pcu2X#NI%3o{6*>1FXKQ(4P*VGZ{fWJF;OP3B(2I&A3#wr1%!eP48 z*xry`zmm8&c$D6ej?JC1BAyHF=DGi_FbkC-*%N4~mUniRl4bxd!{p>IOJPHlCIm0 zd5!5A%#F0RcK9mbm;)#8XEsWsLF^B_v0Pa};iDQ|Bj}fchncK*O$VvNgI>IZ{~!pL zIIU97)Q0zyMh#Z$>&j-JYg?pakjZTZW}bc;SGNNSO@|%ia36S&j$9VgkH7$+*trM7 zqU`ojJe+8SAndpE(LBW_yP0%9v{px$nQ zhY*t9v?V^*u0g%coDQB0h;(OAFl*2?lne=bbrLcKv%(g#@ZRIebmxKReGAXH)>>KL z@-IX_zCn>+mJ2}%o`xoqtOK}|;ngNQD% z*7DCMei^-c68G_vdMf>O@A0F;=dti|=nhJXBsDqRLQ~V%ag2mNTQieg(JTaNnSogY zQX8&j#m!gzAeSKDFa}FQ^_4rGr_Dl1lbNR%(JGgHK5^nY(#{@xTu1;2kSH^w?9gBV z4+CAlY5g2Q!WOAB_$Z-b+)W&eU@wQo+`1w1d^@vufMZnGBB$u~6>2O4``ruM63Y`*YtR^iioy1jP1Im9zog^N7;LmnVm- zms7pE_HD<53(Z%=VAqlxleWg?^FYG~J1_57_b2g_nYXLXfj6kXTWjh<|JW|`-qMf% zN5cHiwI(MsV{2o&KfnK6W;#|M3&UnZ?LdFzg>!U$X4#1%S>K$nid!Q#%819Qt3Q@k zVPcGJ#YO=o;kZ#C|B;s@V9Omp%?AeGb{z#nTzh~wMK-obRJKc;W+kEF0v{&&+E!3- zm+9ki<#aLKmh2BH)>sM{`g$(;C79Wme3}f>EOZ_al^4-S) z$$AKSU=i#=$SOM#Pn=_g@>3r)Fs8B7gxzn0G<-m;o9O$e0UX?b_2f@fc?xA1M6vfe z{swZM-i!o9$M6XfzMe&`vRe!>0`TGF8>+=sB-vFvJ=FpsLHi1)xCG0W`k4$|pSL}y z@5qsneas$6UiQ!%=sr!UkP7WWstej=y)iaP>3OM5IbI%gSxn4Ft%4cr{P zXmr$17l4>C`zPerFLE9w*hK5Y%RSCzx2T>ek9=C6)YYzO!Yz&pTF6rJtpwu1HE#;T zR`65sX!QhVm=u^EEo7nUYW6Hhp6JLmTwBTsi90j`X@lx4T$`5BjJo$DQP$xC_}gMB zCgh{xOO6#3rPK)7b~VCJ8F>I-K^2I_w}<-RWGA7k8^g#sHhWh{W}uO6fyktKjY<^o z63X`#JbthFMBnP^8Gj^b>xHUeE8Myn^bSeYKT~DRvEkEYa(lj>A6x}@aQj~GKlJEU zH`P%}+CY&gDxS_o>At zp>KHK?8!#qF0bI=CZ7|8R-Kn`8J>}b>H8r(U4Zar^wJCT#_}QUyA+;|41(%t;vaT9 zSDtjQ;HdROw0`NZTx!OGAw|3WBWASn#|j)m3@o_qVMae0 z9ele)Nz3Vog*?7dTs<062TK0p48FnQ@Av?>gYfiOyO%Xq(qVtPDGY-thTCN^Lhg&> zvQ+F~uMa5#fpCm#fH=BW)Do8vw;+yOHN$EHOnvu@31K6|Pm9!evXDpPaonob@RT+@ zbSMAHFyrMf^^0|5p-fzyS49cSEf|VU;r$q%4Lpu&lln{}drecSgn9|M#}cJfgX79K z>3Sf>vBj426b?zyRK|A~@z#~5w)XyRpU6XzHhw%{39U(Jv+t%Wd1OQ)NN=)$?&AFn zo1s{M*r$(e=@37PfL1q6^7wS>rEN#$V_P$zr@PL5(hiR4Wr2x*+i*MfQQp%3i#`zg z104FAe+b&EmQY5ChSh0&+F}|jA{eTON*hYt&xpQ>&}y=0*Wu5uAdZj_QJNP|@tkSo z#(P43H86L0)RrD*nX8?4v89gl?#hljbN6pg#U?X4JQc>{mMK>n{WrHa{1z##UVg)* zXP5h#vaMCSOa$?#BM^Np0#%rDF-=uDo+?YtS41WYWQ=xsIEPIlFOp?go z*Wf-|FPlB`*;jH^Pl6<0n!(VQGQpO2#*o)V5J1&24b)jmQJZp7o020C3u!mw#lFg+kxpY0ujkln2@Z|kCaq#vX{%| zq0R!jfs%;X@&RQZqi4YlvWaL`6Fo<<(FIdH)8^h)KM@nXI#?*4Q!7qp7?L3-*)zVE zMwiAn0iJmZC&!vf_3K9-jh$3JD!erNk4{{JZj4<-=D;-!`Aiu+zb(abyVv5r4ct=V zC7kXyyojhaFwQ+Tq#tT(bW~80p(SAuT2D@#OU1P(W8+L>=|7DurM|n8w6n7BJ^%K72 zQgF7KGSB8khQ^`XlC}u}dCpy;b!*l;46KWu=KCn4w0f&d&$pTy`ITBGYG^pwS=M`N zXAySpi*hpF!HiK2XFlp9iH!Tl;nmhT6DU`|FCKQj>;($@asswVMC6at*n{z`dSR<^ z>JiWztsG=DZ$1=OP-_y4H1Sya9Uqkf6ta=(OM+Z5R7PGZwGN#r5jXW>KXis-`X~u$(!os9V~t_tz9gFOzODF!P{hV zCy(bjgLKL?&)_}QDyMM1oVO9dBP`F^$Q`kLsB>u0gtj0t_Q_Q*gi4U$Dr~@h$$G)3 zGSu6p@HT1(+*!2Lzx{2FA2Y}eRp33x|NNfghyREBb#!vKGIsnUzcZ?$Z97Ac>Mgp> ztL8ItS@okAe`XS3+4 zRPrc2_2Ep8$CdQR5109|5^*$8#btQ0ICZa5P=#}3WEnT;y#BiyEXB;|Uyq8bjW}Ks zPP?@miSc3p55{6XKRvqIS{fdM#Ij2c{L~-pu#zNFA$Kk4r2Xmq3gNph!<2N5O_KPw z^i{FgHYWY-D(@GiceL#DVn7b?9WsQG`JZqtyO&g$TFQw1FAQxFO0yL`7s)Vs*Rixm za!r{Y)x&L^>ZI)wA@nPu87)71uT4wHUmyJ9H+{os2(bOiw&R7|w;tUeZ3DDO>7vBy zcOAg$Cdp=ewCtIVYoU^k^!dpB#+S=ZRcbZYjA9<5Gyg(8>Y}Dsokc@~`~{Zl8b-fF zT(tbD6SqMEUGAnptIB*TZ8~{o8c=L9H|`TrT!v^2rzC=f9n9yFhi(PxM=i)wzoM26WOf4i9wzkVH8U^1+jDlBNgR4% z#WepCP5U5N_XW7yqa6&(;|GCMrFIwdw4^ysNnzGO5Rr}ZM6paU*51XhIiSL7_1&Sz zfonpa_hh7s1`iRf@{t$X#Uh|Rj<`8VV9$u}wodFEYDJB`)jlB0ti^Pd{(+|>GFMrI5XBVLf`5)NQZe_;X4Rp{P$i7qQzw@ezkndM%Qry|)mCGXZdFEWlTV(r$Y#1n$73)-C-qi)Q`VauJva9-~95DrtZVe>f; zC`?|^OJN_ML_*{+onTDckY*~1DvM4^DK98mN=>}d9Co0F0Xm<#6=1O5fi*=-tR#G= z^s+72?JT}#J!Ro@qHfq1;kbf$yzm(~F2L9astb~Y_yUJXnP&gZn<)xQ%J~N{aFyds zQ6+c;e?q)heSbVB3jw?hmE-wbK^_o1gGrE&w}?NPPJeCrfXA0jcXA3U_k4iAfySQ+ zjpO~rl8I&zNZq2_z;K<6JKVJ>V_kSK^5asaoUMe5qqbIA%>Pji3#!`#o@TiE#+Vuk z#=lit8@5yl_OXY^WJpWOG>I4Zqx;2`gwZGL8TaoL&t=Uh+4Zh)fp_H-{X_A8R6qPP zq5Y3?h`-X>e-=XoMskUa4VMvqVLQdJ~OQ8dr5CGk*q`k{v~?8(w%3+qc=s9HLix-;sZ-l_qd+zRTi z$C2K6Uu<$a#>Flt0>wF^^>}i`I0l7JF25S^AGzLUT6!aZ=Ub1CT;0O_od#<02o3w+ zpPm{G03iE^2JGH#&dJz8(b&o9596cz?V5qsz})6IenN6Z4`ZOi+UdwcUVpQ%CmL5s z!^(WsMbW&vjEI3iyl(`-cnm*FT%4$S2y(k)3vb(AH0lY=Wu3qO6+rjsZO|9dMQ(+@ z<*u9gh4<>GH*alJ82DKX!Oj5fH zFp#6A(iwa9+0T6Ty7#ykdAv~VPZvk1Ytd1ldOZ{h>kwZ;^8MWE+t1*{wx-x=y}?y5@$$(^TD@l3C=_0t<0;*qR_w%Gb!2;I zvqTAK9t=McdAV?2J%ook-Hs+I$3(ndor+u*7&|i^9i4*>`NF5nQdT{02-*+CyX0&T z%kH-1{gG#Uj7i|ZAGSp_hrHOAX;{O3D`_^vqp_*Gn7Y37(9pAjA>qdOBZ^&_A0gng z1F?w7&+Jlv+z%XeN!;!66@;f(UqYd9;_gH)`QL4CuD4jwvr5M?$I*%me&24G+i_H7 zDOYNtLMR-CC|Cu(T26#5!FERD{;II)%JEtJ1k3W*Go_W6qMsVh`08F{=V|dZ;@1!X z_GMKLii)_FryJx1%%SRJt$`)045UWU7?2yIs<#egImMqSd)YE zD>V>Py{^;;iLE!4&Ns}iCJrf$IbMjWpPF6rIE?t|>GmijzJ|l8dmTO1Cl|V#g9-tT zZHa!H;I_D??Slpp3sZN&z(*4Kbz4N&OCb#h#mM0+geZ8akYv1yLXLGdQ==Y7<#g{V z<~Hk@u@#o-7VB~n0_adlb!(y>J~Yd0(g7-Yey_4D9(-9Y?)|yFs}x-6Ttj?o4e&nk zv7m;-z^d@xr*bnPJ?z^-y`FA$ZZ2&?dV_^!L@*1~QNJ5F$p+-%=h4dA2z$)BL-VUpH&joO|n!km(ZFq+BQ=Rgf#Q;dQcN>b!l=;WU8kSgT~9A;;ag<()8{C>Z)) zKY<>o{uYk?-XPek1uN+cSMLbN#UTBK4Eu_oEvMr+n@)=CBbg^|i&1w>km5~Gkg1ng zi<>31&VoCS(#pJ1;RA%s5fA(>p+rq literal 0 HcmV?d00001 diff --git a/Test_Cases/NREL_2p8_127/NREL-2.8-127_pitch-speed.csv b/Test_Cases/NREL_2p8_127/NREL-2.8-127_pitch-speed.csv new file mode 100644 index 00000000..8a37882c --- /dev/null +++ b/Test_Cases/NREL_2p8_127/NREL-2.8-127_pitch-speed.csv @@ -0,0 +1,31 @@ +mps,pitch,speed +3,0,5 +3.889649963,0,5 +4.684006997,0,5.638983608 +5.377830234,0,6.474263714 +5.966542092,0,7.183002305 +6.446258474,0,7.760523392 +6.813814392,0,8.20301671 +7.066784852,0,8.507562856 +7.203500851,0,8.67215255 +7.223060389,0,8.695699891 +7.320786359,0,8.813350259 +7.535153079,0,9.071422123 +7.864746237,0,9.468212823 +8.307391303,1.972625303,10.00110448 +8.860167873,3.729032675,10.66658129 +9.519428937,5.277405528,11.46025268 +10.28082494,6.571034001,12.0388027 +10.68187298,7.135654103,12.0388027 +11.13933248,8.260696288,12.0388027 +12.08928745,10.26526353,12.0388027 +13.1244224,12.14867141,12.0388027 +14.23790791,13.95715081,12.0388027 +15.42239763,15.71431664,12.0388027 +16.67007674,17.45490652,12.0388027 +17.97271352,19.14151062,12.0388027 +19.32171368,20.8231505,12.0388027 +20.70817701,22.44383927,12.0388027 +22.12295617,24.03032967,12.0388027 +23.55671697,25.61093372,12.0388027 +25,27.13341342,12.0388027 diff --git a/Test_Cases/NREL_2p8_127/NREL-2p8-127.fst b/Test_Cases/NREL_2p8_127/NREL-2p8-127.fst new file mode 100644 index 00000000..c177d10c --- /dev/null +++ b/Test_Cases/NREL_2p8_127/NREL-2p8-127.fst @@ -0,0 +1,71 @@ +------- OpenFAST INPUT FILE ------------------------------------------- +Generated with AeroElasticSE FAST driver +---------------------- SIMULATION CONTROL -------------------------------------- +False Echo - Echo input data to .ech (flag) +"FATAL" AbortLevel - Error level when simulation should abort (string) {"WARNING", "SEVERE", "FATAL"} +300.0 TMax - Total run time (s) +0.005 DT - Recommended module time step (s) +2 InterpOrder - Interpolation order for input/output time history (-) {1=linear, 2=quadratic} +0 NumCrctn - Number of correction iterations (-) {0=explicit calculation, i.e., no corrections} +99999.0 DT_UJac - Time between calls to get Jacobians (s) +1000000.0 UJacSclFact - Scaling factor used in Jacobians (-) +---------------------- FEATURE SWITCHES AND FLAGS ------------------------------ +1 CompElast - Compute structural dynamics (switch) {1=ElastoDyn; 2=ElastoDyn + BeamDyn for blades} +1 CompInflow - Compute inflow wind velocities (switch) {0=still air; 1=InflowWind; 2=external from OpenFOAM} +2 CompAero - Compute aerodynamic loads (switch) {0=None; 1=AeroDyn v14; 2=AeroDyn v15} +1 CompServo - Compute control and electrical-drive dynamics (switch) {0=None; 1=ServoDyn} +0 CompHydro - Compute hydrodynamic loads (switch) {0=None; 1=HydroDyn} +0 CompSub - Compute sub-structural dynamics (switch) {0=None; 1=SubDyn; 2=External Platform MCKF} +0 CompMooring - Compute mooring system (switch) {0=None; 1=MAP++; 2=FEAMooring; 3=MoorDyn; 4=OrcaFlex} +0 CompIce - Compute ice loads (switch) {0=None; 1=IceFloe; 2=IceDyn} +0 MHK - MHK turbine type (switch) {0=Not an MHK turbine; 1=Fixed MHK turbine; 2=Floating MHK turbine} +---------------------- ENVIRONMENTAL CONDITIONS -------------------------------- + 9.80665 Gravity - Gravitational acceleration (m/s^2) + 1.225 AirDens - Air density (kg/m^3) + 0 WtrDens - Water density (kg/m^3) + 1.464E-05 KinVisc - Kinematic viscosity of working fluid (m^2/s) + 335 SpdSound - Speed of sound in working fluid (m/s) + 103500 Patm - Atmospheric pressure (Pa) [used only for an MHK turbine cavitation check] + 1700 Pvap - Vapour pressure of working fluid (Pa) [used only for an MHK turbine cavitation check] + 0 WtrDpth - Water depth (m) + 0 MSL2SWL - Offset between still-water level and mean sea level (m) [positive upward] +---------------------- INPUT FILES --------------------------------------------- +"NREL-2p8-127_ElastoDyn.dat" EDFile - Name of file containing ElastoDyn input parameters (quoted string) +"none" BDBldFile(1) - Name of file containing BeamDyn input parameters for blade 1 (quoted string) +"none" BDBldFile(2) - Name of file containing BeamDyn input parameters for blade 2 (quoted string) +"none" BDBldFile(3) - Name of file containing BeamDyn input parameters for blade 3 (quoted string) +"NREL-2p8-127_InflowFile.dat" InflowFile - Name of file containing inflow wind input parameters (quoted string) +"NREL-2p8-127_AeroDyn15.dat" AeroFile - Name of file containing aerodynamic input parameters (quoted string) +"NREL-2p8-127_ServoDyn.dat" ServoFile - Name of file containing control and electrical-drive input parameters (quoted string) +"none" HydroFile - Name of file containing hydrodynamic input parameters (quoted string) +"none" SubFile - Name of file containing sub-structural input parameters (quoted string) +"none" MooringFile - Name of file containing mooring system input parameters (quoted string) +"none" IceFile - Name of file containing ice input parameters (quoted string) +---------------------- OUTPUT -------------------------------------------------- +False SumPrint - Print summary data to ".sum" (flag) +10.0 SttsTime - Amount of time between screen status messages (s) +99999.0 ChkptTime - Amount of time between creating checkpoint files for potential restart (s) +default DT_Out - Time step for tabular output (s) (or "default") +0.0 TStart - Time to begin tabular output (s) +1 OutFileFmt - Format for tabular (time-marching) output file (switch) {1: text file [.out], 2: binary file [.outb], 3: both} +True TabDelim - Use tab delimiters in text tabular output file? (flag) {uses spaces if false} +"ES10.3E2" OutFmt - Format used for text tabular output, excluding the time channel. Resulting field should be 10 characters. (quoted string) +---------------------- LINEARIZATION ------------------------------------------- +False Linearize - Linearization analysis (flag) +False CalcSteady - Calculate a steady-state periodic operating point before linearization? [unused if Linearize=False] (flag) +3 TrimCase - Controller parameter to be trimmed {1:yaw; 2:torque; 3:pitch} [used only if CalcSteady=True] (-) +0.001 TrimTol - Tolerance for the rotational speed convergence [used only if CalcSteady=True] (-) +0.01 TrimGain - Proportional gain for the rotational speed error (>0) [used only if CalcSteady=True] (rad/(rad/s) for yaw or pitch; Nm/(rad/s) for torque) +0.0 Twr_Kdmp - Damping factor for the tower [used only if CalcSteady=True] (N/(m/s)) +0.0 Bld_Kdmp - Damping factor for the blades [used only if CalcSteady=True] (N/(m/s)) +2 NLinTimes - Number of times to linearize (-) [>=1] [unused if Linearize=False] +30.000000, 60.000000 LinTimes - List of times at which to linearize (s) [1 to NLinTimes] [used only when Linearize=True and CalcSteady=False] +1 LinInputs - Inputs included in linearization (switch) {0=none; 1=standard; 2=all module inputs (debug)} [unused if Linearize=False] +1 LinOutputs - Outputs included in linearization (switch) {0=none; 1=from OutList(s); 2=all module outputs (debug)} [unused if Linearize=False] +False LinOutJac - Include full Jacobians in linearization output (for debug) (flag) [unused if Linearize=False; used only if LinInputs=LinOutputs=2] +False LinOutMod - Write module-level linearization output files in addition to output for full system? (flag) [unused if Linearize=False] +---------------------- VISUALIZATION ------------------------------------------ +0 WrVTK - VTK visualization data output: (switch) {0=none; 1=initialization data only; 2=animation} +2 VTK_type - Type of VTK visualization data: (switch) {1=surfaces; 2=basic meshes (lines/points); 3=all meshes (debug)} [unused if WrVTK=0] +False VTK_fields - Write mesh fields to VTK data files? (flag) {true/false} [unused if WrVTK=0] +10.0 VTK_fps - Frame rate for VTK output (frames per second){will use closest integer multiple of DT} [used only if WrVTK=2] diff --git a/Test_Cases/NREL_2p8_127/NREL-2p8-127_AeroDyn15.dat b/Test_Cases/NREL_2p8_127/NREL-2p8-127_AeroDyn15.dat new file mode 100644 index 00000000..a3742899 --- /dev/null +++ b/Test_Cases/NREL_2p8_127/NREL-2p8-127_AeroDyn15.dat @@ -0,0 +1,134 @@ +------- AERODYN v15.03.* INPUT FILE ------------------------------------------------ +Generated with AeroElasticSE FAST driver +====== General Options ============================================================================ +False Echo - Echo the input to ".AD.ech"? (flag) +default DTAero - Time interval for aerodynamic calculations {or "default"} (s) +1 WakeMod - Type of wake/induction model (switch) {0=none, 1=BEMT, 2=DBEMT, 3=OLAF} [WakeMod cannot be 2 or 3 when linearizing] +2 AFAeroMod - Type of blade airfoil aerodynamics model (switch) {1=steady model, 2=Beddoes-Leishman unsteady model} [AFAeroMod must be 1 when linearizing] +0 TwrPotent - Type tower influence on wind based on potential flow around the tower (switch) {0=none, 1=baseline potential flow, 2=potential flow with Bak correction} +0 TwrShadow - Calculate tower influence on wind based on downstream tower shadow (switch) {0=none, 1=Powles model, 2=Eames model} +False TwrAero - Calculate tower aerodynamic loads? (flag) +False FrozenWake - Assume frozen wake during linearization? (flag) [used only when WakeMod=1 and when linearizing] +False CavitCheck - Perform cavitation check? (flag) [AFAeroMod must be 1 when CavitCheck=true] +False Buoyancy - Include buoyancy effects? (flag) +False CompAA - Flag to compute AeroAcoustics calculation [only used when WakeMod=1 or 2] +AeroAcousticsInput.dat AA_InputFile - AeroAcoustics input file [used only when CompAA=true] +====== Environmental Conditions =================================================================== +"default" AirDens - Air density (kg/m^3) +"default" KinVisc - Kinematic air viscosity (m^2/s) +"default" SpdSound - Speed of sound (m/s) +"default" Patm - Atmospheric pressure (Pa) [used only when CavitCheck=True] +"default" Pvap - Vapour pressure of fluid (Pa) [used only when CavitCheck=True] +====== Blade-Element/Momentum Theory Options ====================================================== [used only when WakeMod=1] +2 SkewMod - Type of skewed-wake correction model (switch) {1=uncoupled, 2=Pitt/Peters, 3=coupled} [unused when WakeMod=0 or 3] +1.4726215563702154 SkewModFactor - Constant used in Pitt/Peters skewed wake model {or "default" is 15/32*pi} (-) [used only when SkewMod=2; unused when WakeMod=0 or 3] +True TipLoss - Use the Prandtl tip-loss model? (flag) [unused when WakeMod=0 or 3] +True HubLoss - Use the Prandtl hub-loss model? (flag) [unused when WakeMod=0 or 3] +True TanInd - Include tangential induction in BEMT calculations? (flag) [unused when WakeMod=0 or 3] +True AIDrag - Include the drag term in the axial-induction calculation? (flag) [unused when WakeMod=0 or 3] +True TIDrag - Include the drag term in the tangential-induction calculation? (flag) [unused when WakeMod=0,3 or TanInd=FALSE] +default IndToler - Convergence tolerance for BEMT nonlinear solve residual equation {or "default"} (-) [unused when WakeMod=0 or 3] +500 MaxIter - Maximum number of iteration steps (-) [unused when WakeMod=0] +====== Dynamic Blade-Element/Momentum Theory Options ====================================================== [used only when WakeMod=1] +2 DBEMT_Mod - Type of dynamic BEMT (DBEMT) model {1=constant tau1, 2=time-dependent tau1} (-) [used only when WakeMod=2] +2.0 tau1_const - Time constant for DBEMT (s) [used only when WakeMod=2 and DBEMT_Mod=1] +====== OLAF -- cOnvecting LAgrangian Filaments (Free Vortex Wake) Theory Options ================== [used only when WakeMod=3] +NREL-2p8-127_OLAF.dat OLAFInputFileName - Input file for OLAF [used only when WakeMod=3] +====== Beddoes-Leishman Unsteady Airfoil Aerodynamics Options ===================================== [used only when AFAeroMod=2] +3 UAMod - Unsteady Aero Model Switch (switch) {1=Baseline model (Original), 2=Gonzalez's variant (changes in Cn,Cc,Cm), 3=Minnema/Pierce variant (changes in Cc and Cm)} [used only when AFAeroMod=2] +True FLookup - Flag to indicate whether a lookup for f' will be calculated (TRUE) or whether best-fit exponential equations will be used (FALSE); if FALSE S1-S4 must be provided in airfoil input files (flag) [used only when AFAeroMod=2] +====== Airfoil Information ========================================================================= +1 AFTabMod - Interpolation method for multiple airfoil tables {1=1D interpolation on AoA (first table only); 2=2D interpolation on AoA and Re; 3=2D interpolation on AoA and UserProp} (-) +1 InCol_Alfa - The column in the airfoil tables that contains the angle of attack (-) +2 InCol_Cl - The column in the airfoil tables that contains the lift coefficient (-) +3 InCol_Cd - The column in the airfoil tables that contains the drag coefficient (-) +4 InCol_Cm - The column in the airfoil tables that contains the pitching-moment coefficient; use zero if there is no Cm column (-) +0 InCol_Cpmin - The column in the airfoil tables that contains the Cpmin coefficient; use zero if there is no Cpmin column (-) +30 NumAFfiles - Number of airfoil files used (-) +"Airfoils/NREL-2p8-127_AeroDyn15_Polar_00.dat" AFNames - Airfoil file names (NumAFfiles lines) (quoted strings) +"Airfoils/NREL-2p8-127_AeroDyn15_Polar_01.dat" +"Airfoils/NREL-2p8-127_AeroDyn15_Polar_02.dat" +"Airfoils/NREL-2p8-127_AeroDyn15_Polar_03.dat" +"Airfoils/NREL-2p8-127_AeroDyn15_Polar_04.dat" +"Airfoils/NREL-2p8-127_AeroDyn15_Polar_05.dat" +"Airfoils/NREL-2p8-127_AeroDyn15_Polar_06.dat" +"Airfoils/NREL-2p8-127_AeroDyn15_Polar_07.dat" +"Airfoils/NREL-2p8-127_AeroDyn15_Polar_08.dat" +"Airfoils/NREL-2p8-127_AeroDyn15_Polar_09.dat" +"Airfoils/NREL-2p8-127_AeroDyn15_Polar_10.dat" +"Airfoils/NREL-2p8-127_AeroDyn15_Polar_11.dat" +"Airfoils/NREL-2p8-127_AeroDyn15_Polar_12.dat" +"Airfoils/NREL-2p8-127_AeroDyn15_Polar_13.dat" +"Airfoils/NREL-2p8-127_AeroDyn15_Polar_14.dat" +"Airfoils/NREL-2p8-127_AeroDyn15_Polar_15.dat" +"Airfoils/NREL-2p8-127_AeroDyn15_Polar_16.dat" +"Airfoils/NREL-2p8-127_AeroDyn15_Polar_17.dat" +"Airfoils/NREL-2p8-127_AeroDyn15_Polar_18.dat" +"Airfoils/NREL-2p8-127_AeroDyn15_Polar_19.dat" +"Airfoils/NREL-2p8-127_AeroDyn15_Polar_20.dat" +"Airfoils/NREL-2p8-127_AeroDyn15_Polar_21.dat" +"Airfoils/NREL-2p8-127_AeroDyn15_Polar_22.dat" +"Airfoils/NREL-2p8-127_AeroDyn15_Polar_23.dat" +"Airfoils/NREL-2p8-127_AeroDyn15_Polar_24.dat" +"Airfoils/NREL-2p8-127_AeroDyn15_Polar_25.dat" +"Airfoils/NREL-2p8-127_AeroDyn15_Polar_26.dat" +"Airfoils/NREL-2p8-127_AeroDyn15_Polar_27.dat" +"Airfoils/NREL-2p8-127_AeroDyn15_Polar_28.dat" +"Airfoils/NREL-2p8-127_AeroDyn15_Polar_29.dat" +====== Rotor/Blade Properties ===================================================================== +True UseBlCm - Include aerodynamic pitching moment in calculations? (flag) +"NREL-2p8-127_AeroDyn15_blade.dat" ADBlFile(1) - Name of file containing distributed aerodynamic properties for Blade #1 (-) +"NREL-2p8-127_AeroDyn15_blade.dat" ADBlFile(2) - Name of file containing distributed aerodynamic properties for Blade #2 (-) [unused if NumBl < 2] +"NREL-2p8-127_AeroDyn15_blade.dat" ADBlFile(3) - Name of file containing distributed aerodynamic properties for Blade #3 (-) [unused if NumBl < 3] +====== Hub Properties ============================================================================== [used only when Buoyancy=True] +0.0 VolHub - Hub volume (m^3) +0.0 HubCenBx - Hub center of buoyancy x direction offset (m) +====== Nacelle Properties ========================================================================== [used only when Buoyancy=True] +0.0 VolNac - Nacelle volume (m^3) +0,0,0 NacCenB - Position of nacelle center of buoyancy from yaw bearing in nacelle coordinates (m) +====== Tail fin Aerodynamics ======================================================================== +False TFinAero - Calculate tail fin aerodynamics model (flag) +"unused" TFinFile - Input file for tail fin aerodynamics [used only when TFinAero=True] +====== Tower Influence and Aerodynamics ============================================================= [used only when TwrPotent/=0, TwrShadow/=0, or TwrAero=True] +10 NumTwrNds - Number of tower nodes used in the analysis (-) [used only when TwrPotent/=0, TwrShadow/=0, or TwrAero=True] +TwrElev TwrDiam TwrCd TwrTI TwrCb !TwrTI used only with TwrShadow=2, TwrCb used only with Buoyancy=True +(m) (m) (-) (-) (-) + 8.650000000000000e+00 3.999999999999999e+00 5.000000000000000e-01 1.000000000000000e-01 0.0 + 1.730800925925926e+01 4.000000000000000e+00 5.000000000000000e-01 1.000000000000000e-01 0.0 + 2.595800925925926e+01 4.000000000000000e+00 5.000000000000000e-01 1.000000000000000e-01 0.0 + 3.461601851851852e+01 3.953273204469021e+00 5.000000000000000e-01 1.000000000000000e-01 0.0 + 4.326601851851852e+01 3.712118013878008e+00 5.000000000000000e-01 1.000000000000000e-01 0.0 + 5.191601851851851e+01 3.433099970059946e+00 5.000000000000000e-01 1.000000000000000e-01 0.0 + 6.057402777777778e+01 3.130385763598736e+00 5.000000000000000e-01 1.000000000000000e-01 0.0 + 6.922402777777778e+01 2.796113422345067e+00 5.000000000000000e-01 1.000000000000000e-01 0.0 + 7.787402777777778e+01 2.382646880140990e+00 5.000000000000000e-01 1.000000000000000e-01 0.0 + 8.650000000000000e+01 2.324880163918676e+00 5.000000000000000e-01 1.000000000000000e-01 0.0 +====== Outputs ==================================================================================== +False SumPrint - Generate a summary file listing input options and interpolated properties to ".AD.sum"? (flag) +0 NBlOuts - Number of blade node outputs [0 - 9] (-) +4, 7, 10, 13, 15, 18, 21, 24, 27 BlOutNd - Blade nodes whose values will be output (-) +0 NTwOuts - Number of tower node outputs [0 - 9] (-) +0 TwOutNd - Tower nodes whose values will be output (-) + OutList - The next line(s) contains a list of output parameters. See OutListParameters.xlsx for a listing of available output channels, (-) +"B1Azimuth" +"B2Azimuth" +"B3Azimuth" +END of input file (the word "END" must appear in the first 3 columns of this last OutList line) +====== Outputs for all blade stations (same ending as above for B1N1.... =========================== [optional section] +3 BldNd_BladesOut - Number of blades to output all node information at. Up to number of blades on turbine. (-) +"All" BldNd_BlOutNd - Future feature will allow selecting a portion of the nodes to output. Not implemented yet. (-) + OutList - The next line(s) contains a list of output parameters. See OutListParameters.xlsx for a listing of available output channels, (-) +"Fx, Fy" +"Vx, Vy" +Vrel +TnInd +AxInd +Theta +Phi +Vindx +Vindy +Alpha +Fl +Fd +END (the word "END" must appear in the first 3 columns of this last OutList line in the optional nodal output section) +--------------------------------------------------------------------------------------- diff --git a/Test_Cases/NREL_2p8_127/NREL-2p8-127_AeroDyn15_blade.dat b/Test_Cases/NREL_2p8_127/NREL-2p8-127_AeroDyn15_blade.dat new file mode 100644 index 00000000..fd4b728f --- /dev/null +++ b/Test_Cases/NREL_2p8_127/NREL-2p8-127_AeroDyn15_blade.dat @@ -0,0 +1,36 @@ +------- AERODYN v15.00.* BLADE DEFINITION INPUT FILE ------------------------------------- +Generated with AeroElasticSE FAST driver +====== Blade Properties ================================================================= +30 NumBlNds - Number of blade nodes used in the analysis (-) + BlSpn BlCrvAC BlSwpAC BlCrvAng BlTwist BlChord BlAFID + (m) (m) (m) (deg) (deg) (m) (-) + 0.000000000000000e+00 0.000000000000000e+00 0.000000000000000e+00 0.000000000000000e+00 1.999622705006573e+01 2.565746018075444e+00 1 + 2.119199517912653e+00 0.000000000000000e+00 0.000000000000000e+00 0.000000000000000e+00 1.931018243810786e+01 3.361938565422448e+00 2 + 4.238399035825307e+00 0.000000000000000e+00 0.000000000000000e+00 -2.621743302803628e-03 1.831714953780435e+01 4.045185045024725e+00 3 + 6.357598553737958e+00 -1.939408866995070e-04 0.000000000000000e+00 -6.412784123456707e-02 1.708763041181490e+01 4.534861529323176e+00 4 + 8.476798071650611e+00 -4.743793103448273e-03 0.000000000000000e+00 -1.978684279841359e-01 1.569212712279918e+01 4.750344090758699e+00 5 + 1.059599758956327e+01 -1.483103448275862e-02 0.000000000000000e+00 -3.150569530999122e-01 1.382289586770404e+01 4.737620755206947e+00 6 + 1.271519710747592e+01 -2.804970443349753e-02 0.000000000000000e+00 -4.200820236296363e-01 1.124554309027298e+01 4.683448688307037e+00 7 + 1.483439662538857e+01 -4.590591133004925e-02 0.000000000000000e+00 -5.312359339597873e-01 8.602632953470145e+00 4.602338372007760e+00 8 + 1.695359614330122e+01 -6.734679802955665e-02 0.000000000000000e+00 -6.413089831677180e-01 6.549224739725965e+00 4.505595976960268e+00 9 + 1.907279566121387e+01 -9.334512315270936e-02 0.000000000000000e+00 -7.594874026577699e-01 5.408188380153923e+00 4.380463162058345e+00 10 + 2.119199517912653e+01 -1.235274876847291e-01 0.000000000000000e+00 -8.814019981123943e-01 4.552816793256156e+00 4.183546777131121e+00 11 + 2.331119469703918e+01 -1.585433990147783e-01 0.000000000000000e+00 -1.022348344095032e+00 3.850103071189125e+00 3.945902894366683e+00 12 + 2.543039421495183e+01 -1.991506896551724e-01 0.000000000000000e+00 -1.183293448295596e+00 3.210053831367405e+00 3.702763428157307e+00 13 + 2.754959373286449e+01 -2.460701477832512e-01 0.000000000000000e+00 -1.342781789240282e+00 2.548277995517243e+00 3.476193009639851e+00 14 + 2.966879325077715e+01 -2.984725615763546e-01 0.000000000000000e+00 -1.515812813319435e+00 1.868987870564891e+00 3.235485886652345e+00 15 + 3.178799276868979e+01 -3.581878325123153e-01 0.000000000000000e+00 -1.698337241682368e+00 1.247026288989173e+00 2.994660335764964e+00 16 + 3.390719228660245e+01 -4.240869950738916e-01 0.000000000000000e+00 -1.908238044665007e+00 7.591906266374636e-01 2.774705218558286e+00 17 + 3.602639180451509e+01 -4.993217733990146e-01 0.000000000000000e+00 -2.133886441082087e+00 4.659000465949885e-01 2.591930205580583e+00 18 + 3.814559132242776e+01 -5.819026600985221e-01 0.000000000000000e+00 -2.384324918476038e+00 2.731580237682558e-01 2.424912635092513e+00 19 + 4.026479084034041e+01 -6.756489655172412e-01 0.000000000000000e+00 -2.659453831887105e+00 1.231485664729688e-01 2.273929330687443e+00 20 + 4.238399035825307e+01 -7.785625123152710e-01 0.000000000000000e+00 -2.957313507988756e+00 -1.889923787502366e-02 2.146862384202469e+00 21 + 4.450318987616572e+01 -8.943162068965517e-01 0.000000000000000e+00 -3.294896483624423e+00 -1.841259535939614e-01 2.051800999525918e+00 22 + 4.662238939407835e+01 -1.022164926108374e+00 0.000000000000000e+00 -3.676725314021781e+00 -3.432314804149588e-01 1.991284282831078e+00 23 + 4.874158891199102e+01 -1.166111724137931e+00 0.000000000000000e+00 -4.102651579820645e+00 -5.034899071419768e-01 1.944879951099011e+00 24 + 5.086078842990366e+01 -1.325395270935961e+00 0.000000000000000e+00 -4.585680344442696e+00 -6.944182383563149e-01 1.888109521438915e+00 25 + 5.297998794781633e+01 -1.504970886699507e+00 0.000000000000000e+00 -5.166689492052464e+00 -9.464479611794926e-01 1.795137265041130e+00 26 + 5.509918746572898e+01 -1.707078275862069e+00 0.000000000000000e+00 -5.829761241403034e+00 -1.331448785580028e+00 1.572950482786750e+00 27 + 5.721838698364163e+01 -1.935478029556650e+00 0.000000000000000e+00 -6.607040906671076e+00 -1.857716459023805e+00 1.205686533770803e+00 28 + 5.933758650155428e+01 -2.194745172413793e+00 0.000000000000000e+00 -7.654100340223317e+00 -2.493070572147947e+00 7.343636341297369e-01 29 + 6.145678601946693e+01 -2.500000000000000e+00 0.000000000000000e+00 -8.281837270494590e+00 -3.205330715589577e+00 1.999999999999999e-01 30 diff --git a/Test_Cases/NREL_2p8_127/NREL-2p8-127_Cp_Ct_Cq.txt b/Test_Cases/NREL_2p8_127/NREL-2p8-127_Cp_Ct_Cq.txt new file mode 100644 index 00000000..2268df83 --- /dev/null +++ b/Test_Cases/NREL_2p8_127/NREL-2p8-127_Cp_Ct_Cq.txt @@ -0,0 +1,111 @@ +# ----- Rotor performance tables for the WISDEM tuning wind turbine ----- +# ------------ Written on Jul-01-21 using the ROSCO toolbox ------------ + +# Pitch angle vector, 30 entries - x axis (matrix columns) (deg) +-5.0 -3.793 -2.586 -1.379 -0.1724 1.034 2.241 3.448 4.655 5.862 7.069 8.276 9.483 10.69 11.9 13.1 14.31 15.52 16.72 17.93 19.14 20.34 21.55 22.76 23.97 25.17 26.38 27.59 28.79 30.0 +# TSR vector, 30 entries - y axis (matrix rows) (-) +2.0 2.345 2.69 3.034 3.379 3.724 4.069 4.414 4.759 5.103 5.448 5.793 6.138 6.483 6.828 7.172 7.517 7.862 8.207 8.552 8.897 9.241 9.586 9.931 10.28 10.62 10.97 11.31 11.66 12.0 +# Wind speed vector - z axis (m/s) +10.68 + +# Power coefficient + +0.005733 0.008358 0.010931 0.013451 0.015923 0.018353 0.020747 0.023112 0.025459 0.027794 0.030128 0.032473 0.034841 0.037250 0.039720 0.042275 0.044947 0.047736 0.050369 0.052438 0.053782 0.054536 0.054902 0.055053 0.055070 0.054924 0.054451 0.053413 0.051671 0.049088 +0.010473 0.014052 0.017571 0.021038 0.024463 0.027857 0.031232 0.034602 0.037982 0.041391 0.044855 0.048407 0.052073 0.055894 0.059917 0.063725 0.066595 0.068386 0.069435 0.070068 0.070525 0.070875 0.070899 0.070223 0.068520 0.065563 0.061477 0.056461 0.050687 0.044351 +0.016648 0.021451 0.026198 0.030903 0.035583 0.040258 0.044950 0.049690 0.054525 0.059496 0.064610 0.069956 0.075525 0.080323 0.083509 0.085464 0.086777 0.087879 0.088967 0.089747 0.089510 0.087678 0.083964 0.078635 0.072110 0.064721 0.056667 0.048586 0.039467 0.029816 +0.024451 0.030790 0.037088 0.043370 0.049664 0.056017 0.062499 0.069156 0.075949 0.082980 0.090401 0.096848 0.101076 0.103789 0.105878 0.107957 0.110172 0.111665 0.111132 0.107849 0.102059 0.094460 0.085644 0.075982 0.066327 0.055369 0.043639 0.032509 0.020157 0.007204 +0.034042 0.042277 0.050504 0.058774 0.067185 0.075810 0.084575 0.093427 0.102846 0.111995 0.118495 0.122686 0.126019 0.129475 0.133430 0.136352 0.136037 0.131773 0.124323 0.114686 0.103692 0.091818 0.079871 0.066581 0.053315 0.038287 0.023162 0.007449 -0.008632 -0.024586 +0.045585 0.056130 0.066777 0.077664 0.088762 0.099834 0.111077 0.123170 0.133767 0.140785 0.145956 0.151011 0.157146 0.162829 0.164232 0.160094 0.151678 0.140464 0.127481 0.113476 0.099240 0.083738 0.067897 0.050473 0.032437 0.013439 -0.006199 -0.025342 -0.045516 -0.065143 +0.059260 0.072709 0.086474 0.100339 0.113961 0.127912 0.142939 0.155463 0.163934 0.171005 0.179040 0.188615 0.194301 0.192393 0.184326 0.172304 0.157818 0.142304 0.125481 0.108163 0.089149 0.070050 0.048899 0.026622 0.003778 -0.018932 -0.042759 -0.066818 -0.089995 -0.111563 +0.075452 0.092497 0.109469 0.125954 0.142837 0.161240 0.176710 0.187609 0.197446 0.209785 0.222490 0.226531 0.221214 0.209858 0.194803 0.177987 0.159296 0.139878 0.119164 0.097278 0.073947 0.048842 0.022621 -0.004023 -0.031153 -0.059069 -0.087357 -0.114578 -0.140484 -0.164736 +0.094511 0.115022 0.134762 0.154737 0.176972 0.196672 0.211032 0.224473 0.242210 0.257277 0.259309 0.251325 0.237445 0.219974 0.200798 0.179364 0.157090 0.133189 0.107637 0.080632 0.051709 0.021678 -0.009667 -0.041001 -0.073080 -0.105950 -0.138447 -0.169104 -0.197971 -0.224775 +0.115766 0.139262 0.162531 0.188762 0.214007 0.233062 0.250893 0.274820 0.291963 0.292630 0.283030 0.267459 0.248387 0.227009 0.203460 0.177863 0.150485 0.121761 0.090582 0.058077 0.023979 -0.011436 -0.047266 -0.084214 -0.121988 -0.160064 -0.196335 -0.230319 -0.262503 -0.292769 +0.138202 0.165180 0.195145 0.226872 0.252196 0.275177 0.305983 0.325658 0.326244 0.316157 0.300345 0.280365 0.256598 0.230927 0.201729 0.171679 0.139290 0.105344 0.069408 0.031095 -0.008598 -0.049591 -0.091288 -0.133915 -0.178094 -0.220525 -0.260789 -0.299211 -0.335296 -0.368913 +0.161551 0.194903 0.233072 0.266466 0.295512 0.333944 0.357168 0.359266 0.350611 0.334697 0.314121 0.289567 0.260693 0.230418 0.196940 0.161915 0.124757 0.085182 0.042894 -0.000790 -0.046411 -0.092800 -0.140820 -0.191037 -0.240613 -0.287931 -0.333389 -0.376354 -0.416036 -0.453961 +0.187222 0.230589 0.273386 0.309857 0.356719 0.384733 0.390248 0.383896 0.370565 0.350414 0.324413 0.295499 0.262058 0.226919 0.188856 0.149185 0.106270 0.060944 0.012546 -0.037082 -0.088941 -0.142059 -0.197711 -0.254659 -0.309941 -0.363301 -0.414317 -0.461320 -0.506034 -0.548809 +0.218182 0.270155 0.315870 0.371977 0.406056 0.416968 0.415541 0.404376 0.386195 0.360803 0.331422 0.297575 0.260704 0.220885 0.178443 0.132842 0.084899 0.032868 -0.022005 -0.078304 -0.136540 -0.197173 -0.261078 -0.325020 -0.387095 -0.447192 -0.502963 -0.555496 -0.605861 -0.653204 +0.254532 0.310663 0.376823 0.417704 0.436754 0.440281 0.435650 0.419393 0.397694 0.368784 0.336011 0.298185 0.257418 0.212716 0.165233 0.114373 0.059332 0.000710 -0.060597 -0.123897 -0.189821 -0.259087 -0.331270 -0.402899 -0.472743 -0.538898 -0.600642 -0.659473 -0.715589 -0.767490 +0.291345 0.362540 0.414077 0.442759 0.456364 0.457699 0.448489 0.431127 0.405674 0.375079 0.338260 0.297381 0.251595 0.202536 0.149608 0.092156 0.031270 -0.034407 -0.103383 -0.174606 -0.248877 -0.327443 -0.408776 -0.488867 -0.566514 -0.639447 -0.707853 -0.773526 -0.835768 -0.891588 +0.334267 0.392389 0.429122 0.454490 0.467414 0.468861 0.458486 0.439783 0.413047 0.379503 0.339810 0.294277 0.244514 0.190251 0.131042 0.067919 -0.000899 -0.074042 -0.150532 -0.230353 -0.313772 -0.402998 -0.493743 -0.583001 -0.669214 -0.748849 -0.825066 -0.898389 -0.966410 -1.025596 +0.357581 0.399673 0.430692 0.453633 0.471348 0.474079 0.465908 0.446519 0.418911 0.382644 0.339619 0.290170 0.235615 0.175506 0.110900 0.039947 -0.035948 -0.117185 -0.202556 -0.291136 -0.385516 -0.485608 -0.586336 -0.686466 -0.780338 -0.868234 -0.953223 -1.034163 -1.107681 -1.169678 +0.359089 0.395909 0.422920 0.446887 0.467916 0.476719 0.470246 0.452129 0.422792 0.384528 0.337886 0.284550 0.224670 0.159553 0.087437 0.009559 -0.074879 -0.164757 -0.258939 -0.357948 -0.463740 -0.575130 -0.688215 -0.798454 -0.900816 -0.998198 -1.092491 -1.181114 -1.259757 -1.324162 +0.352122 0.384922 0.412733 0.437293 0.459923 0.475065 0.473237 0.455603 0.425796 0.384974 0.335221 0.277195 0.212880 0.140688 0.062025 -0.024286 -0.117337 -0.216450 -0.320583 -0.430204 -0.548805 -0.673230 -0.799147 -0.919437 -1.031241 -1.139238 -1.243211 -1.339491 -1.422841 -1.489579 +0.337476 0.371192 0.400519 0.426291 0.450198 0.470638 0.473926 0.458015 0.427354 0.384641 0.331021 0.269346 0.198533 0.120306 0.033570 -0.061171 -0.163388 -0.272615 -0.386793 -0.509148 -0.641390 -0.779702 -0.918883 -1.049570 -1.172336 -1.291740 -1.405715 -1.509537 -1.597202 -1.666605 +0.318547 0.355113 0.386350 0.414679 0.439769 0.463178 0.472160 0.458769 0.428164 0.383342 0.326610 0.259227 0.183042 0.097321 0.002524 -0.100828 -0.213043 -0.332841 -0.458853 -0.594695 -0.741354 -0.895436 -1.047980 -1.189453 -1.324645 -1.456077 -1.580322 -1.691499 -1.783230 -1.855996 +0.296861 0.336357 0.371125 0.401227 0.428782 0.453625 0.468379 0.458572 0.427993 0.381040 0.320153 0.248295 0.165371 0.072165 -0.031080 -0.144120 -0.266822 -0.398094 -0.536575 -0.686751 -0.849789 -1.020458 -1.186248 -1.339816 -1.488593 -1.632618 -1.767333 -1.885639 -1.981441 -2.058554 +0.272813 0.316283 0.353808 0.387167 0.416653 0.443733 0.462868 0.457131 0.426821 0.377287 0.313149 0.235527 0.145893 0.044924 -0.067233 -0.190687 -0.324377 -0.467771 -0.619850 -0.786143 -0.967008 -1.154934 -1.333959 -1.501288 -1.664564 -1.821724 -1.967047 -2.092251 -2.192423 -2.275093 +0.246069 0.293978 0.335450 0.371711 0.404252 0.432681 0.455569 0.454421 0.424708 0.373151 0.304575 0.221274 0.124762 0.015593 -0.106430 -0.240075 -0.386009 -0.542363 -0.709498 -0.892981 -1.093361 -1.298929 -1.491618 -1.674356 -1.852938 -2.023747 -2.179757 -2.311694 -2.416806 -2.506397 +0.216826 0.269453 0.315238 0.355775 0.390496 0.421499 0.446849 0.450470 0.421163 0.367613 0.294770 0.205703 0.101961 -0.016317 -0.147823 -0.293601 -0.452261 -0.622484 -0.805520 -1.007723 -1.229078 -1.452472 -1.659852 -1.859420 -2.054090 -2.239027 -2.405773 -2.544411 -2.655240 -2.753201 +0.185378 0.242932 0.294130 0.338148 0.376456 0.409645 0.437023 0.444746 0.416677 0.361007 0.283893 0.188900 0.076999 -0.050213 -0.192792 -0.350430 -0.522552 -0.707567 -0.908176 -1.130888 -1.374382 -1.615659 -1.839260 -2.056853 -2.268390 -2.467901 -2.645409 -2.790903 -2.908382 -3.016187 +0.151541 0.215077 0.270909 0.319887 0.361564 0.397134 0.425931 0.437697 0.411248 0.353437 0.271813 0.170258 0.050180 -0.086481 -0.240782 -0.411284 -0.597745 -0.798619 -1.017747 -1.262940 -1.529489 -1.788749 -2.030361 -2.267024 -2.496202 -2.710710 -2.898994 -3.051693 -3.176877 -3.295979 +0.116719 0.184724 0.246682 0.300410 0.345826 0.383484 0.414182 0.429382 0.404775 0.344986 0.258834 0.150170 0.022144 -0.125552 -0.291478 -0.476005 -0.677661 -0.895479 -1.134529 -1.404210 -1.694559 -1.972164 -2.233589 -2.490305 -2.737888 -2.967794 -3.166880 -3.327314 -3.461362 -3.593163 +0.083160 0.153221 0.220860 0.279749 0.328690 0.369159 0.401864 0.419718 0.397476 0.335735 0.244382 0.129245 -0.008566 -0.166737 -0.345714 -0.544710 -0.762454 -0.998353 -1.258854 -1.554935 -1.869688 -2.166410 -2.449315 -2.727062 -2.993813 -3.239497 -3.449471 -3.618299 -3.762458 -3.908311 + + +# Thrust coefficient + +0.092617 0.091973 0.091282 0.090551 0.089789 0.089009 0.088223 0.087443 0.086683 0.085957 0.085280 0.084668 0.084140 0.083714 0.083409 0.083241 0.083187 0.083136 0.082900 0.082292 0.081228 0.079766 0.078062 0.076284 0.074489 0.072639 0.070589 0.068103 0.065041 0.061235 +0.107807 0.107099 0.106370 0.105637 0.104916 0.104226 0.103585 0.103012 0.102531 0.102166 0.101942 0.101882 0.102014 0.102313 0.102613 0.102616 0.102036 0.100793 0.099051 0.097090 0.095137 0.093216 0.091122 0.088501 0.085056 0.080536 0.075010 0.068694 0.061744 0.054369 +0.125690 0.125020 0.124378 0.123788 0.123275 0.122867 0.122595 0.122492 0.122590 0.122922 0.123517 0.124280 0.124878 0.124839 0.123887 0.122169 0.120092 0.118075 0.116232 0.114243 0.111480 0.107417 0.101732 0.094621 0.086475 0.077627 0.068292 0.059385 0.049429 0.039068 +0.146469 0.145968 0.145568 0.145305 0.145219 0.145353 0.145746 0.146440 0.147476 0.148736 0.149769 0.149930 0.148898 0.147006 0.144888 0.143119 0.141664 0.139693 0.136101 0.130177 0.122042 0.112323 0.101588 0.090223 0.079407 0.067285 0.054557 0.043004 0.030260 0.017273 +0.170322 0.170162 0.170211 0.170521 0.171142 0.172124 0.173518 0.175280 0.176969 0.177796 0.177163 0.175410 0.173408 0.172028 0.171348 0.169865 0.165714 0.158160 0.147807 0.135540 0.122189 0.108233 0.094835 0.080132 0.065961 0.050014 0.034389 0.018544 0.003193 -0.010886 +0.197455 0.197860 0.198615 0.199780 0.201413 0.203541 0.205932 0.207836 0.208292 0.207137 0.205373 0.204234 0.204557 0.204565 0.200976 0.192600 0.180449 0.165872 0.149876 0.133238 0.117061 0.099744 0.082616 0.064007 0.045159 0.025713 0.006302 -0.011125 -0.028289 -0.044210 +0.228108 0.229335 0.231075 0.233378 0.236206 0.239147 0.241258 0.241561 0.240420 0.239344 0.240052 0.242465 0.241498 0.233969 0.220968 0.204514 0.186057 0.167281 0.147603 0.127937 0.106751 0.086199 0.063660 0.040417 0.017219 -0.004685 -0.025932 -0.045670 -0.063692 -0.079450 +0.262520 0.264837 0.267792 0.271266 0.274765 0.277277 0.277848 0.277232 0.277418 0.280948 0.284986 0.281401 0.269491 0.252166 0.231752 0.210486 0.187865 0.165132 0.141511 0.117131 0.091777 0.064983 0.037642 0.010798 -0.015186 -0.039683 -0.062267 -0.082642 -0.100832 -0.116042 +0.300899 0.304470 0.308545 0.312661 0.315868 0.317175 0.317479 0.319387 0.326537 0.331420 0.324563 0.308564 0.287341 0.263390 0.239016 0.212699 0.186421 0.158835 0.130094 0.100520 0.069495 0.038176 0.006565 -0.023392 -0.051487 -0.077331 -0.101050 -0.121896 -0.139281 -0.152655 +0.343271 0.347913 0.352697 0.356873 0.359360 0.360881 0.364797 0.376183 0.381530 0.371589 0.352097 0.327447 0.300692 0.272771 0.243417 0.212456 0.180280 0.147567 0.112935 0.077849 0.042129 0.006311 -0.028141 -0.060918 -0.090649 -0.117951 -0.142121 -0.162077 -0.177778 -0.190200 +0.389280 0.394727 0.400026 0.404078 0.407075 0.413055 0.429223 0.435350 0.423077 0.400722 0.374104 0.344727 0.312349 0.279252 0.242837 0.206780 0.169140 0.130977 0.091820 0.051267 0.010784 -0.029060 -0.066758 -0.100984 -0.132612 -0.160509 -0.184044 -0.202810 -0.217522 -0.228949 +0.438633 0.445040 0.450918 0.455672 0.463524 0.485007 0.492799 0.479208 0.455888 0.426352 0.393770 0.358519 0.319308 0.280331 0.238875 0.197193 0.154621 0.110858 0.065544 0.020470 -0.024506 -0.067347 -0.107384 -0.144048 -0.176562 -0.204438 -0.227047 -0.244755 -0.258294 -0.268897 +0.491706 0.499452 0.506279 0.515668 0.542884 0.553453 0.539904 0.515588 0.485998 0.450602 0.410018 0.368368 0.323023 0.277884 0.231163 0.184623 0.136206 0.086882 0.036071 -0.013663 -0.062666 -0.108746 -0.151171 -0.189073 -0.222113 -0.249567 -0.271188 -0.287669 -0.300602 -0.310227 +0.549345 0.558514 0.569279 0.602408 0.616664 0.604690 0.582220 0.550051 0.512271 0.468142 0.422118 0.373239 0.323447 0.272627 0.221194 0.168412 0.115188 0.059566 0.003362 -0.051146 -0.103573 -0.152467 -0.196894 -0.235916 -0.269224 -0.295885 -0.316232 -0.332225 -0.344350 -0.352382 +0.612101 0.624375 0.664085 0.681142 0.674153 0.650222 0.621076 0.578484 0.533557 0.482845 0.431122 0.376532 0.321741 0.265249 0.208409 0.150399 0.090234 0.028797 -0.032224 -0.091118 -0.147230 -0.198731 -0.244615 -0.284679 -0.317626 -0.343032 -0.363010 -0.378328 -0.389183 -0.395374 +0.681140 0.722494 0.744937 0.741819 0.723240 0.692359 0.650892 0.603471 0.550332 0.495575 0.437299 0.378355 0.317265 0.255902 0.193374 0.128796 0.063320 -0.003921 -0.070382 -0.133867 -0.193205 -0.246832 -0.294513 -0.334907 -0.366839 -0.391968 -0.411381 -0.425701 -0.435248 -0.438943 +0.784148 0.809192 0.808836 0.792982 0.766161 0.727627 0.678346 0.624772 0.566940 0.506098 0.442987 0.377600 0.311662 0.244545 0.175539 0.105591 0.033001 -0.039972 -0.111103 -0.178920 -0.241079 -0.297271 -0.346084 -0.386032 -0.417835 -0.442342 -0.461133 -0.474603 -0.482332 -0.482920 +0.878798 0.878837 0.863060 0.835105 0.802967 0.756008 0.703552 0.644299 0.581942 0.515391 0.446747 0.375978 0.304277 0.230822 0.156465 0.079145 0.000687 -0.078083 -0.154487 -0.225874 -0.291394 -0.349551 -0.398730 -0.438965 -0.470211 -0.494454 -0.512604 -0.524870 -0.530317 -0.527179 +0.954018 0.939321 0.909436 0.873286 0.832514 0.783431 0.725750 0.663095 0.594833 0.523420 0.448910 0.372835 0.294905 0.216166 0.134425 0.050923 -0.034393 -0.118873 -0.199777 -0.275311 -0.343458 -0.403080 -0.453308 -0.493210 -0.524351 -0.548257 -0.565667 -0.576443 -0.579083 -0.571691 +1.023567 0.991396 0.952287 0.906521 0.858662 0.807150 0.747584 0.679776 0.607111 0.529975 0.450234 0.367981 0.284931 0.198845 0.110913 0.020042 -0.071681 -0.161822 -0.247543 -0.326338 -0.397314 -0.458714 -0.509404 -0.549186 -0.580227 -0.603771 -0.620315 -0.629247 -0.628527 -0.616549 +1.082395 1.041804 0.991706 0.937500 0.883506 0.829745 0.767582 0.695892 0.617983 0.535899 0.450029 0.362870 0.272561 0.180369 0.084918 -0.012918 -0.111052 -0.207054 -0.296861 -0.379668 -0.453228 -0.515758 -0.566811 -0.606870 -0.637885 -0.661022 -0.676524 -0.683203 -0.678594 -0.661917 +1.139470 1.088591 1.028946 0.968630 0.908004 0.850049 0.785703 0.710556 0.628371 0.540937 0.449853 0.355602 0.259321 0.159705 0.057014 -0.047554 -0.152331 -0.253888 -0.348541 -0.434946 -0.510661 -0.574581 -0.626062 -0.666337 -0.697360 -0.720024 -0.734260 -0.738241 -0.729302 -0.707987 +1.193356 1.132284 1.066459 0.998428 0.932385 0.868695 0.802509 0.724743 0.637956 0.545168 0.447725 0.347749 0.244209 0.137366 0.027344 -0.084534 -0.195804 -0.303098 -0.402185 -0.491831 -0.569969 -0.635054 -0.687035 -0.727643 -0.758678 -0.780783 -0.793478 -0.794302 -0.780726 -0.754961 +1.246139 1.176860 1.102810 1.028791 0.956073 0.887434 0.818433 0.738064 0.646836 0.548098 0.445275 0.338296 0.227647 0.113522 -0.003991 -0.123338 -0.241002 -0.353871 -0.457470 -0.550699 -0.630979 -0.697211 -0.749803 -0.790834 -0.821861 -0.843294 -0.854136 -0.851351 -0.832973 -0.803032 +1.297833 1.220927 1.139862 1.058606 0.980276 0.905327 0.833196 0.750616 0.655027 0.550899 0.441477 0.327617 0.209871 0.088199 -0.037295 -0.163462 -0.287985 -0.406413 -0.514793 -0.611346 -0.693698 -0.761096 -0.814426 -0.855942 -0.886923 -0.907540 -0.916195 -0.909382 -0.886156 -0.852355 +1.349499 1.264699 1.176444 1.089146 1.003822 0.923619 0.847140 0.762383 0.662108 0.552546 0.436663 0.315954 0.190856 0.061078 -0.071728 -0.205866 -0.337083 -0.461115 -0.573945 -0.673753 -0.758148 -0.826758 -0.880950 -0.922989 -0.953877 -0.973504 -0.979625 -0.968430 -0.940389 -0.903039 +1.401303 1.308592 1.213895 1.119148 1.027971 0.941861 0.860452 0.772903 0.668581 0.553361 0.431060 0.303363 0.170279 0.032750 -0.108329 -0.249749 -0.387655 -0.517261 -0.634906 -0.737912 -0.824352 -0.894252 -0.949413 -0.991994 -1.022726 -1.041166 -1.044395 -1.028546 -0.995775 -0.955152 +1.452242 1.353400 1.250891 1.149892 1.052236 0.960061 0.872934 0.782638 0.674455 0.553511 0.424528 0.289397 0.148463 0.002987 -0.146530 -0.295534 -0.440250 -0.575517 -0.697662 -0.803821 -0.892330 -0.963626 -1.019849 -1.062972 -1.093473 -1.110511 -1.110480 -1.089791 -1.052396 -1.008724 +1.502155 1.397642 1.288756 1.180858 1.076625 0.977784 0.885198 0.791667 0.679649 0.553086 0.417399 0.274454 0.126013 -0.028498 -0.185977 -0.343001 -0.494588 -0.635562 -0.762201 -0.871489 -0.962109 -1.034918 -1.092283 -1.135935 -1.166113 -1.181520 -1.177866 -1.152220 -1.110323 -1.063759 +1.548197 1.442437 1.326903 1.212074 1.100665 0.995531 0.897392 0.799857 0.684430 0.552127 0.409217 0.259083 0.101756 -0.061061 -0.227233 -0.392126 -0.550655 -0.697385 -0.828511 -0.940928 -1.033720 -1.108161 -1.166734 -1.210891 -1.240644 -1.254176 -1.246561 -1.215880 -1.169616 -1.120255 + + +# Torque coefficient + +0.002876 0.004193 0.005484 0.006749 0.007989 0.009208 0.010409 0.011596 0.012773 0.013945 0.015116 0.016292 0.017480 0.018689 0.019929 0.021210 0.022551 0.023950 0.025271 0.026309 0.026984 0.027362 0.027545 0.027621 0.027630 0.027557 0.027319 0.026798 0.025925 0.024629 +0.004482 0.006014 0.007519 0.009003 0.010469 0.011921 0.013366 0.014808 0.016254 0.017713 0.019195 0.020715 0.022284 0.023919 0.025641 0.027270 0.028499 0.029265 0.029714 0.029985 0.030180 0.030330 0.030340 0.030051 0.029322 0.028057 0.026309 0.024162 0.021691 0.018980 +0.006211 0.008003 0.009774 0.011529 0.013275 0.015019 0.016770 0.018538 0.020342 0.022197 0.024104 0.026099 0.028177 0.029967 0.031155 0.031885 0.032374 0.032786 0.033192 0.033483 0.033394 0.032711 0.031325 0.029337 0.026902 0.024146 0.021141 0.018126 0.014724 0.011124 +0.008085 0.010182 0.012264 0.014342 0.016423 0.018524 0.020667 0.022868 0.025115 0.027440 0.029894 0.032026 0.033424 0.034321 0.035012 0.035699 0.036432 0.036925 0.036749 0.035664 0.033749 0.031236 0.028321 0.025126 0.021933 0.018310 0.014430 0.010750 0.006666 0.002382 +0.010108 0.012554 0.014996 0.017452 0.019950 0.022511 0.025113 0.027742 0.030539 0.033256 0.035186 0.036430 0.037420 0.038446 0.039620 0.040488 0.040395 0.039128 0.036916 0.034054 0.030790 0.027264 0.023717 0.019770 0.015831 0.011369 0.006878 0.002212 -0.002563 -0.007300 +0.012283 0.015124 0.017993 0.020926 0.023916 0.026900 0.029929 0.033187 0.036043 0.037934 0.039327 0.040689 0.042342 0.043873 0.044251 0.043136 0.040869 0.037847 0.034349 0.030575 0.026740 0.022563 0.018294 0.013600 0.008740 0.003621 -0.001670 -0.006828 -0.012264 -0.017552 +0.014614 0.017931 0.021325 0.024745 0.028104 0.031544 0.035250 0.038339 0.040428 0.042171 0.044153 0.046514 0.047916 0.047446 0.045456 0.042492 0.038919 0.035093 0.030945 0.026674 0.021985 0.017275 0.012059 0.006565 0.000932 -0.004669 -0.010545 -0.016478 -0.022194 -0.027513 +0.017154 0.021028 0.024887 0.028635 0.032473 0.036657 0.040174 0.042652 0.044888 0.047693 0.050582 0.051500 0.050292 0.047710 0.044287 0.040464 0.036215 0.031800 0.027091 0.022115 0.016811 0.011104 0.005143 -0.000914 -0.007082 -0.013429 -0.019860 -0.026048 -0.031938 -0.037452 +0.019929 0.024255 0.028417 0.032629 0.037318 0.041472 0.044500 0.047334 0.051075 0.054252 0.054680 0.052997 0.050070 0.046386 0.042342 0.037822 0.033125 0.028085 0.022697 0.017003 0.010904 0.004571 -0.002038 -0.008646 -0.015410 -0.022342 -0.029194 -0.035659 -0.041746 -0.047398 +0.022762 0.027382 0.031957 0.037115 0.042078 0.045825 0.049331 0.054035 0.057406 0.057537 0.055650 0.052588 0.048838 0.044635 0.040005 0.034972 0.029588 0.023941 0.017810 0.011419 0.004715 -0.002249 -0.009294 -0.016558 -0.023985 -0.031472 -0.038603 -0.045286 -0.051614 -0.057565 +0.025454 0.030422 0.035941 0.041785 0.046449 0.050681 0.056355 0.059978 0.060087 0.058229 0.055317 0.051637 0.047259 0.042531 0.037154 0.031619 0.025654 0.019402 0.012783 0.005727 -0.001584 -0.009134 -0.016813 -0.024664 -0.032801 -0.040616 -0.048031 -0.055108 -0.061754 -0.067945 +0.027983 0.033760 0.040371 0.046156 0.051187 0.057844 0.061866 0.062230 0.060731 0.057974 0.054410 0.050157 0.045156 0.039912 0.034113 0.028046 0.021610 0.014755 0.007430 -0.000137 -0.008039 -0.016074 -0.024392 -0.033090 -0.041677 -0.049874 -0.057748 -0.065190 -0.072063 -0.078632 +0.030608 0.037697 0.044694 0.050656 0.058317 0.062897 0.063799 0.062760 0.060581 0.057286 0.053036 0.048309 0.042842 0.037097 0.030875 0.024389 0.017373 0.009963 0.002051 -0.006062 -0.014540 -0.023224 -0.032322 -0.041632 -0.050670 -0.059393 -0.067733 -0.075418 -0.082728 -0.089721 +0.033772 0.041816 0.048892 0.057577 0.062852 0.064541 0.064320 0.062592 0.059778 0.055847 0.051300 0.046061 0.040353 0.034190 0.027621 0.020562 0.013141 0.005088 -0.003406 -0.012120 -0.021134 -0.030520 -0.040411 -0.050309 -0.059917 -0.069219 -0.077852 -0.085983 -0.093779 -0.101107 +0.037408 0.045658 0.055381 0.061390 0.064189 0.064708 0.064027 0.061638 0.058449 0.054200 0.049383 0.043824 0.037832 0.031263 0.024284 0.016809 0.008720 0.000104 -0.008906 -0.018209 -0.027898 -0.038078 -0.048686 -0.059214 -0.069479 -0.079201 -0.088276 -0.096922 -0.105169 -0.112797 +0.040760 0.050721 0.057931 0.061943 0.063847 0.064034 0.062745 0.060316 0.056755 0.052475 0.047324 0.041605 0.035199 0.028335 0.020931 0.012893 0.004375 -0.004814 -0.014464 -0.024428 -0.034819 -0.045810 -0.057189 -0.068394 -0.079257 -0.089461 -0.099031 -0.108219 -0.116927 -0.124736 +0.044620 0.052378 0.057282 0.060668 0.062393 0.062586 0.061201 0.058705 0.055136 0.050658 0.045360 0.039282 0.032639 0.025396 0.017492 0.009066 -0.000120 -0.009884 -0.020094 -0.030749 -0.041884 -0.053794 -0.065908 -0.077822 -0.089331 -0.099961 -0.110134 -0.119922 -0.129002 -0.136902 +0.045638 0.051011 0.054970 0.057898 0.060159 0.060507 0.059464 0.056990 0.053466 0.048837 0.043346 0.037035 0.030072 0.022400 0.014154 0.005098 -0.004588 -0.014956 -0.025852 -0.037158 -0.049204 -0.061979 -0.074835 -0.087614 -0.099595 -0.110814 -0.121661 -0.131991 -0.141374 -0.149287 +0.043905 0.048407 0.051710 0.054640 0.057211 0.058288 0.057496 0.055281 0.051694 0.047016 0.041313 0.034791 0.027470 0.019508 0.010691 0.001169 -0.009155 -0.020145 -0.031660 -0.043766 -0.056701 -0.070320 -0.084147 -0.097626 -0.110141 -0.122048 -0.133577 -0.144413 -0.154028 -0.161903 +0.041317 0.045166 0.048429 0.051311 0.053967 0.055743 0.055529 0.053460 0.049962 0.045172 0.039334 0.032526 0.024979 0.016508 0.007278 -0.002850 -0.013768 -0.025398 -0.037617 -0.050479 -0.064396 -0.078996 -0.093770 -0.107885 -0.121004 -0.133676 -0.145876 -0.157174 -0.166954 -0.174785 +0.038064 0.041867 0.045175 0.048081 0.050778 0.053083 0.053454 0.051660 0.048201 0.043384 0.037336 0.030380 0.022393 0.013569 0.003786 -0.006900 -0.018429 -0.030748 -0.043627 -0.057427 -0.072343 -0.087943 -0.103641 -0.118381 -0.132228 -0.145696 -0.158551 -0.170261 -0.180149 -0.187977 +0.034588 0.038559 0.041951 0.045027 0.047751 0.050293 0.051268 0.049814 0.046491 0.041624 0.035464 0.028147 0.019875 0.010567 0.000274 -0.010948 -0.023133 -0.036140 -0.049823 -0.064573 -0.080497 -0.097228 -0.113791 -0.129153 -0.143832 -0.158103 -0.171594 -0.183666 -0.193626 -0.201527 +0.031074 0.035208 0.038848 0.041999 0.044883 0.047484 0.049028 0.048001 0.044800 0.039886 0.033512 0.025991 0.017310 0.007554 -0.003253 -0.015086 -0.027930 -0.041671 -0.056166 -0.071886 -0.088952 -0.106817 -0.124171 -0.140246 -0.155820 -0.170896 -0.184997 -0.197381 -0.207409 -0.215481 +0.027565 0.031958 0.035749 0.039120 0.042099 0.044835 0.046769 0.046189 0.043127 0.038122 0.031641 0.023798 0.014741 0.004539 -0.006793 -0.019267 -0.032775 -0.047264 -0.062630 -0.079433 -0.097708 -0.116696 -0.134785 -0.151692 -0.168190 -0.184069 -0.198753 -0.211404 -0.221525 -0.229878 +0.024029 0.028707 0.032757 0.036298 0.039475 0.042252 0.044487 0.044375 0.041473 0.036438 0.029742 0.021608 0.012183 0.001523 -0.010393 -0.023443 -0.037694 -0.052962 -0.069283 -0.087200 -0.106767 -0.126841 -0.145657 -0.163502 -0.180941 -0.197620 -0.212855 -0.225738 -0.236003 -0.244751 +0.020486 0.025458 0.029784 0.033614 0.036894 0.039823 0.042218 0.042560 0.039792 0.034732 0.027850 0.019435 0.009633 -0.001542 -0.013966 -0.027739 -0.042730 -0.058812 -0.076106 -0.095210 -0.116123 -0.137230 -0.156823 -0.175678 -0.194071 -0.211544 -0.227298 -0.240396 -0.250867 -0.260123 +0.016964 0.022230 0.026916 0.030944 0.034449 0.037486 0.039992 0.040698 0.038130 0.033035 0.025979 0.017286 0.007046 -0.004595 -0.017642 -0.032068 -0.047818 -0.064749 -0.083106 -0.103486 -0.125768 -0.147847 -0.168309 -0.188221 -0.207578 -0.225835 -0.242079 -0.255393 -0.266143 -0.276008 +0.013445 0.019081 0.024035 0.028380 0.032078 0.035233 0.037788 0.038832 0.036486 0.031357 0.024115 0.015105 0.004452 -0.007673 -0.021362 -0.036489 -0.053031 -0.070853 -0.090294 -0.112047 -0.135695 -0.158696 -0.180132 -0.201128 -0.221461 -0.240492 -0.257196 -0.270744 -0.281850 -0.292416 +0.010049 0.015904 0.021238 0.025864 0.029774 0.033016 0.035659 0.036967 0.034849 0.029701 0.022284 0.012929 0.001906 -0.010809 -0.025095 -0.040981 -0.058343 -0.077096 -0.097676 -0.120894 -0.145892 -0.169792 -0.192299 -0.214401 -0.235717 -0.255510 -0.272650 -0.286463 -0.298004 -0.309351 +0.006954 0.012812 0.018468 0.023393 0.027485 0.030869 0.033604 0.035097 0.033237 0.028074 0.020435 0.010808 -0.000716 -0.013943 -0.028909 -0.045549 -0.063757 -0.083483 -0.105266 -0.130024 -0.156344 -0.181156 -0.204813 -0.228038 -0.250344 -0.270888 -0.288446 -0.302563 -0.314618 -0.326814 + diff --git a/Test_Cases/NREL_2p8_127/NREL-2p8-127_DISCON.IN b/Test_Cases/NREL_2p8_127/NREL-2p8-127_DISCON.IN new file mode 100644 index 00000000..60215d61 --- /dev/null +++ b/Test_Cases/NREL_2p8_127/NREL-2p8-127_DISCON.IN @@ -0,0 +1,171 @@ +! Controller parameter input file for the NREL-2p8-127 wind turbine +! - File written using ROSCO version 2.7.0 controller tuning logic on 03/30/23 + +!------- DEBUG ------------------------------------------------------------ +1 ! LoggingLevel - (0: write no debug files, 1: write standard output .dbg-file, 2: LoggingLevel 1 + ROSCO LocalVars (.dbg2) 3: LoggingLevel 2 + complete avrSWAP-array (.dbg3)) +0 ! Echo - (0 - no Echo, 1 - Echo input data to .echo) + +!------- 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 and/or tower fore-aft motion (for floating) {0: disable, 1: generator speed, 2: tower-top fore-aft motion, 3: generator speed and tower-top fore-aft motion} +0 ! IPC_ControlMode - Turn Individual Pitch Control (IPC) for fatigue load reductions (pitch contribution) {0: off, 1: 1P reductions, 2: 1P+2P reductions} +3 ! VS_ControlMode - Generator torque control mode in above rated conditions {0: constant torque, 1: constant power, 2: TSR tracking PI control with constant torque, 3: TSR tracking PI control with constant power} +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: Immersion and Invariance Estimator, 2: Extended Kalman Filter} +1 ! PS_Mode - Pitch saturation mode {0: no pitch saturation, 1: implement pitch saturation} +0 ! SD_Mode - Shutdown mode {0: no shutdown procedure, 1: pitch to max pitch at shutdown} +0 ! Fl_Mode - Floating specific feedback mode {0: no nacelle velocity feedback, 1: feed back translational velocity, 2: feed back rotational veloicty} +0 ! TD_Mode - Tower damper mode {0: no tower damper, 1: feed back translational nacelle accelleration to pitch angle} +0 ! Flp_Mode - Flap control mode {0: no flap control, 1: steady state flap angle, 2: Proportional flap control, 2: Cyclic (1P) flap control} +0 ! OL_Mode - Open loop control mode {0: no open loop control, 1: open loop control vs. time} +0 ! PA_Mode - Pitch actuator mode {0 - not used, 1 - first order filter, 2 - second order filter} +0 ! PF_Mode - Pitch fault mode {0 - not used, 1 - constant offset on one or more blades} +0 ! AWC_Mode - Active wake control {0 - not used, 1 - complex number method, 2 - Coleman transform method} +0 ! Ext_Mode - External control mode {0 - not used, 1 - call external dynamic library} +0 ! ZMQ_Mode - Fuse ZeroMQ interface {0: unused, 1: Yaw Control} +0 ! CC_Mode - Cable control mode [0- unused, 1- User defined, 2- Position control (not yet implemented)] +0 ! StC_Mode - Structural control mode [0- unused, 1- User defined] + +!------- FILTERS ---------------------------------------------------------- +2.07080 ! F_LPFCornerFreq - Corner frequency (-3dB point) in the low-pass filters, [rad/s] +0.00000 ! F_LPFDamping - Damping coefficient {used only when F_FilterType = 2} [-] +0.00000 ! F_NotchCornerFreq - Natural frequency of the notch filter, [rad/s] +0.000000 0.250000 ! F_NotchBetaNumDen - Two notch damping values (numerator and denominator, resp) - determines the width and depth of the notch, [-] +0.62830 ! F_SSCornerFreq - Corner frequency (-3dB point) in the first order low pass filter for the setpoint smoother, [rad/s]. +0.20944 ! F_WECornerFreq - Corner frequency (-3dB point) in the first order low pass filter for the wind speed estimate [rad/s]. +0.17952 ! F_YawErr - Low pass filter corner frequency for yaw controller [rad/s]. +0.000000 1.000000 ! F_FlCornerFreq - Natural frequency and damping in the second order low pass filter of the tower-top fore-aft motion for floating feedback control [rad/s, -]. +0.01042 ! F_FlHighPassFreq - Natural frequency of first-order high-pass filter for nacelle fore-aft motion [rad/s]. +0.000000 1.000000 ! F_FlpCornerFreq - Corner frequency and damping in the second order low pass filter of the blade root bending moment for flap control [rad/s, -]. + +!------- BLADE PITCH CONTROL ---------------------------------------------- +30 ! PC_GS_n - Amount of gain-scheduling table entries +0.075990 0.104503 0.127446 0.147544 0.164940 0.181678 0.197073 0.211624 0.225753 0.238993 0.252021 0.264458 0.276515 0.288229 0.299596 0.310932 0.321646 0.332112 0.342584 0.353105 0.363012 0.373072 0.382733 0.392195 0.401619 0.411107 0.420504 0.429096 0.437752 0.446357 ! PC_GS_angles - Gain-schedule table: pitch angles [rad]. +-0.024441 -0.021943 -0.019855 -0.018085 -0.016566 -0.015246 -0.014091 -0.013070 -0.012161 -0.011347 -0.010614 -0.009951 -0.009347 -0.008795 -0.008289 -0.007824 -0.007394 -0.006995 -0.006625 -0.006280 -0.005958 -0.005657 -0.005375 -0.005109 -0.004860 -0.004624 -0.004401 -0.004191 -0.003991 -0.003802 ! PC_GS_KP - Gain-schedule table: pitch controller kp gains [s]. +-0.000804 -0.000732 -0.000672 -0.000621 -0.000577 -0.000539 -0.000505 -0.000476 -0.000450 -0.000426 -0.000405 -0.000386 -0.000369 -0.000353 -0.000338 -0.000325 -0.000312 -0.000301 -0.000290 -0.000280 -0.000271 -0.000262 -0.000254 -0.000246 -0.000239 -0.000232 -0.000226 -0.000220 -0.000214 -0.000209 ! PC_GS_KI - Gain-schedule table: pitch controller ki gains [-]. +0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 ! PC_GS_KD - Gain-schedule table: pitch controller kd gains +0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 ! PC_GS_TF - Gain-schedule table: pitch controller tf gains (derivative filter) +1.570000000000 ! PC_MaxPit - Maximum physical pitch limit, [rad]. +-0.17453000000 ! PC_MinPit - Minimum physical pitch limit, [rad]. +0.174500000000 ! PC_MaxRat - Maximum pitch rate (in absolute value) in pitch controller, [rad/s]. +-0.17450000000 ! PC_MinRat - Minimum pitch rate (in absolute value) in pitch controller, [rad/s]. +122.9096700000 ! PC_RefSpd - Desired (reference) HSS speed for pitch controller, [rad/s]. +0.000000000000 ! PC_FinePit - Record 5: Below-rated pitch angle set-point, [rad] +0.017450000000 ! PC_Switch - Angle above lowest minimum pitch angle for switch, [rad] + +!------- INDIVIDUAL PITCH CONTROL ----------------------------------------- +9.120000 11.400000 ! IPC_Vramp - Start and end wind speeds for cut-in ramp function. First entry: IPC inactive, second entry: IPC fully active. [m/s] +2 ! IPC_SatMode - IPC Saturation method (0 - no saturation (except by PC_MinPit), 1 - saturate by PS_BldPitchMin, 2 - saturate sotfly (full IPC cycle) by PC_MinPit, 3 - saturate softly by PS_BldPitchMin) +0.3 ! IPC_IntSat - Integrator saturation (maximum signal amplitude contribution to pitch from IPC), [rad] +0.000e+00 0.000e+00 ! IPC_KP - Proportional gain for the individual pitch controller: first parameter for 1P reductions, second for 2P reductions, [-] +0.000e+00 0.000e+00 ! IPC_KI - Integral gain for the individual pitch controller: first parameter for 1P reductions, second for 2P reductions, [-] +0.000000 0.000000 ! 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 ------------------------------------------------ +93.94773000000 ! VS_GenEff - Generator efficiency mechanical power -> electrical power, [should match the efficiency defined in the generator properties!], [%] +24248.54567000 ! VS_ArSatTq - Above rated generator torque PI control saturation, [Nm] +1500000.000000 ! VS_MaxRat - Maximum torque rate (in absolute value) in torque controller, [Nm/s]. +26673.40024000 ! VS_MaxTq - Maximum generator torque in Region 3 (HSS side), [Nm]. +0.000000000000 ! VS_MinTq - Minimum generator torque (HSS side), [Nm]. +37.81562000000 ! VS_MinOMSpd - Minimum generator speed [rad/s] +1.931170000000 ! VS_Rgn2K - Generator torque constant in Region 2 (HSS side), [Nm/(rad/s)^2] +2800000.000000 ! VS_RtPwr - Wind turbine rated power [W] +24248.54567000 ! VS_RtTq - Rated torque, [Nm]. +122.9096700000 ! VS_RefSpd - Rated generator speed [rad/s] +1 ! VS_n - Number of generator PI torque controller gains +-600.450450000 ! VS_KP - Proportional gain for generator PI torque controller [-]. (Only used in the transitional 2.5 region if VS_ControlMode =/ 2) +-85.3230300000 ! VS_KI - Integral gain for generator PI torque controller [s]. (Only used in the transitional 2.5 region if VS_ControlMode =/ 2) +8.25 ! VS_TSRopt - Power-maximizing region 2 tip-speed-ratio [rad]. + +!------- SETPOINT SMOOTHER --------------------------------------------- +1.00000 ! SS_VSGain - Variable speed torque controller setpoint smoother gain, [-]. +0.00100 ! SS_PCGain - Collective pitch controller setpoint smoother gain, [-]. + +!------- WIND SPEED ESTIMATOR --------------------------------------------- +63.457 ! WE_BladeRadius - Blade length (distance from hub center to blade tip), [m] +1 ! WE_CP_n - Amount of parameters in the Cp array +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], [-] +66347470.49793 ! 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] +"NREL-2p8-127_Cp_Ct_Cq.txt" ! PerfFileName - File containing rotor performance tables (Cp,Ct,Cq) (absolute path or relative to this file) +30 30 ! PerfTableSize - Size of rotor performance tables, first number refers to number of blade pitch angles, second number referse to number of tip-speed ratios +60 ! WE_FOPoles_N - Number of first-order system poles used in EKF +3.0000 3.2897 3.5793 3.8690 4.1586 4.4483 4.7379 5.0276 5.3172 5.6069 5.8966 6.1862 6.4759 6.7655 7.0552 7.3448 7.6345 7.9241 8.2138 8.5034 8.7931 9.0828 9.3724 9.6621 9.9517 10.2414 10.5310 10.8207 11.1103 11.4000 11.8533 12.3067 12.7600 13.2133 13.6667 14.1200 14.5733 15.0267 15.4800 15.9333 16.3867 16.8400 17.2933 17.7467 18.2000 18.6533 19.1067 19.5600 20.0133 20.4667 20.9200 21.3733 21.8267 22.2800 22.7333 23.1867 23.6400 24.0933 24.5467 25.0000 ! WE_FOPoles_v - Wind speeds corresponding to first-order system poles [m/s] +-0.01246409 -0.01366752 -0.01487095 -0.01607438 -0.01727781 -0.01848123 -0.01968466 -0.02088809 -0.02209152 -0.02329495 -0.02449838 -0.02570181 -0.02690524 -0.02810867 -0.02931210 -0.03051553 -0.03171896 -0.03292239 -0.03412582 -0.03532924 -0.03653267 -0.03773610 -0.03893953 -0.04014296 -0.03876534 -0.03527029 -0.03014051 -0.02417865 -0.01714772 -0.00815401 0.00419449 -0.00048731 -0.00466276 -0.01071643 -0.01560323 -0.02192148 -0.02762358 -0.03415246 -0.03995877 -0.04666898 -0.05357684 -0.06017881 -0.06783693 -0.07545934 -0.08285355 -0.09099765 -0.09868985 -0.10643139 -0.11560625 -0.12454786 -0.13353192 -0.14319807 -0.15242426 -0.16161402 -0.17122186 -0.18158081 -0.19160223 -0.20032125 -0.20983653 -0.21909214 ! WE_FOPoles - First order system poles [1/s] + +!------- YAW CONTROL ------------------------------------------------------ +0.00000 ! Y_uSwitch - Wind speed to switch between Y_ErrThresh. If zero, only the second value of Y_ErrThresh is used [m/s] +4.000000 8.000000 ! Y_ErrThresh - Yaw error threshold/deadbands. Turbine begins to yaw when it passes this. If Y_uSwitch is zero, only the second value is used. [deg]. +0.00870 ! Y_Rate - Yaw rate [rad/s] +0.00000 ! Y_MErrSet - Integrator saturation (maximum signal amplitude contribution to pitch from yaw-by-IPC), [rad] +0.00000 ! Y_IPC_IntSat - Integrator saturation (maximum signal amplitude contribution to pitch from yaw-by-IPC), [rad] +0.00000 ! Y_IPC_KP - Yaw-by-IPC proportional controller gain Kp +0.00000 ! Y_IPC_KI - Yaw-by-IPC integral controller gain Ki + +!------- TOWER FORE-AFT DAMPING ------------------------------------------- +-1.00000 ! FA_KI - Integral gain for the fore-aft tower damper controller [rad s/m] +0.0 ! FA_HPFCornerFreq - 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] + +!------- MINIMUM PITCH SATURATION ------------------------------------------- +60 ! PS_BldPitchMin_N - Number of values in minimum blade pitch lookup table (should equal number of values in PS_WindSpeeds and PS_BldPitchMin) +3.0000 3.2897 3.5793 3.8690 4.1586 4.4483 4.7379 5.0276 5.3172 5.6069 5.8966 6.1862 6.4759 6.7655 7.0552 7.3448 7.6345 7.9241 8.2138 8.5034 8.7931 9.0828 9.3724 9.6621 9.9517 10.2414 10.5310 10.8207 11.1103 11.4000 11.8533 12.3067 12.7600 13.2133 13.6667 14.1200 14.5733 15.0267 15.4800 15.9333 16.3867 16.8400 17.2933 17.7467 18.2000 18.6533 19.1067 19.5600 20.0133 20.4667 20.9200 21.3733 21.8267 22.2800 22.7333 23.1867 23.6400 24.0933 24.5467 25.0000 ! PS_WindSpeeds - Wind speeds corresponding to minimum blade pitch angles [m/s] +0.00000000 0.00000000 0.00000000 0.00000000 0.00000000 0.00000000 0.00000000 0.00000000 0.00000000 0.00000000 0.00000000 0.00000000 0.00000000 0.00000000 0.00000000 0.00000000 0.00000000 0.00000000 0.00000000 0.00000000 0.00000000 0.00000000 0.00000000 0.01902632 0.03121162 0.04101621 0.04957537 0.05812141 0.06604528 0.07366393 0.08564088 0.09644430 0.10731742 0.11740081 0.12723365 0.13691718 0.14655371 0.15552079 0.16457871 0.17358206 0.18261499 0.19163393 0.20072294 0.20968649 0.21849678 0.22748802 0.23597095 0.24444734 0.25312967 0.26178025 0.27046099 0.27863869 0.28691931 0.29527580 0.30349928 0.31191439 0.32017189 0.32834804 0.33653924 0.34452172 ! PS_BldPitchMin - Minimum blade pitch angles [rad] + +!------- SHUTDOWN ----------------------------------------------------------- +0.436300000000 ! SD_MaxPit - Maximum blade pitch angle to initiate shutdown, [rad] +0.418880000000 ! SD_CornerFreq - Cutoff Frequency for first order low-pass filter for blade pitch angle, [rad/s] + +!------- Floating ----------------------------------------------------------- +0.000000000000 ! Fl_Kp - Nacelle velocity proportional feedback gain [s] + +!------- FLAP ACTUATION ----------------------------------------------------- +0.000000000000 ! Flp_Angle - Initial or steady state flap angle [rad] +0.00000000e+00 ! Flp_Kp - Blade root bending moment proportional gain for flap control [s] +0.00000000e+00 ! Flp_Ki - Flap displacement integral gain for flap control [-] +0.174500000000 ! Flp_MaxPit - Maximum (and minimum) flap pitch angle [rad] + +!------- Open Loop Control ----------------------------------------------------- +"unused" ! OL_Filename - Input file with open loop timeseries (absolute path or relative to this file) +0 ! Ind_Breakpoint - The column in OL_Filename that contains the breakpoint (time if OL_Mode = 1) +0 ! Ind_BldPitch - The column in OL_Filename that contains the blade pitch input in rad +0 ! Ind_GenTq - The column in OL_Filename that contains the generator torque in Nm +0 ! Ind_YawRate - The column in OL_Filename that contains the generator torque in Nm + +!------- Pitch Actuator Model ----------------------------------------------------- +3.140000000000 ! PA_CornerFreq - Pitch actuator bandwidth/cut-off frequency [rad/s] +0.707000000000 ! PA_Damping - Pitch actuator damping ratio [-, unused if PA_Mode = 1] + +!------- Pitch Actuator Faults ----------------------------------------------------- +0.00000000 0.00000000 0.00000000 ! PF_Offsets - Constant blade pitch offsets for blades 1-3 [rad] + +!------- Active Wake Control ----------------------------------------------------- +1 ! AWC_NumModes - Number of user-defined AWC forcing modes +1 ! AWC_n - Azimuthal mode number(s) (i.e., the number and direction of the lobes of the wake structure) +1 ! AWC_harmonic - Harmonic(s) to apply in the AWC Inverse Coleman Transformation (only used when AWC_Mode = 2) +0.0500 ! AWC_freq - Frequency(s) of forcing mode(s) [Hz] +1.0000 ! AWC_amp - Pitch amplitude(s) of individual forcing mode(s) [deg] +0.0000 ! AWC_clockangle - Initial angle(s) of forcing mode(s) [deg] + +!------- External Controller Interface ----------------------------------------------------- +"unused" ! DLL_FileName - Name/location of the dynamic library in the Bladed-DLL format +"unused" ! DLL_InFile - Name of input file sent to the DLL (-) +"DISCON" ! DLL_ProcName - Name of procedure in DLL to be called (-) + +!------- ZeroMQ Interface --------------------------------------------------------- +"tcp://localhost:5555" ! ZMQ_CommAddress - Communication address for ZMQ server, (e.g. "tcp://localhost:5555") +2 ! ZMQ_UpdatePeriod - Call ZeroMQ every [x] seconds, [s] + +!------- Cable Control --------------------------------------------------------- +1 ! CC_Group_N - Number of cable control groups + 0 ! CC_GroupIndex - First index for cable control group, should correspond to deltaL +20.000000 ! CC_ActTau - Time constant for line actuator [s] + +!------- Structural Controllers --------------------------------------------------------- +1 ! StC_Group_N - Number of cable control groups + 0 ! StC_GroupIndex - First index for structural control group, options specified in ServoDyn summary output diff --git a/Test_Cases/NREL_2p8_127/NREL-2p8-127_ElastoDyn.dat b/Test_Cases/NREL_2p8_127/NREL-2p8-127_ElastoDyn.dat new file mode 100644 index 00000000..6cced857 --- /dev/null +++ b/Test_Cases/NREL_2p8_127/NREL-2p8-127_ElastoDyn.dat @@ -0,0 +1,210 @@ +------- ELASTODYN v1.03.* INPUT FILE ------------------------------------------- +Generated with AeroElasticSE FAST driver +---------------------- SIMULATION CONTROL -------------------------------------- +False Echo - Echo input data to ".ech" (flag) +3 Method - Integration method: {1: RK4, 2: AB4, or 3: ABM4} (-) +default DT Integration time step (s) +---------------------- DEGREES OF FREEDOM -------------------------------------- +True FlapDOF1 - First flapwise blade mode DOF (flag) +True FlapDOF2 - Second flapwise blade mode DOF (flag) +True EdgeDOF - First edgewise blade mode DOF (flag) +False TeetDOF - Rotor-teeter DOF (flag) [unused for 3 blades] +False DrTrDOF - Drivetrain rotational-flexibility DOF (flag) +True GenDOF - Generator DOF (flag) +False YawDOF - Yaw DOF (flag) +False TwFADOF1 - First fore-aft tower bending-mode DOF (flag) +False TwFADOF2 - Second fore-aft tower bending-mode DOF (flag) +False TwSSDOF1 - First side-to-side tower bending-mode DOF (flag) +False TwSSDOF2 - Second side-to-side tower bending-mode DOF (flag) +False PtfmSgDOF - Platform horizontal surge translation DOF (flag) +False PtfmSwDOF - Platform horizontal sway translation DOF (flag) +False PtfmHvDOF - Platform vertical heave translation DOF (flag) +False PtfmRDOF - Platform roll tilt rotation DOF (flag) +False PtfmPDOF - Platform pitch tilt rotation DOF (flag) +False PtfmYDOF - Platform yaw rotation DOF (flag) +---------------------- INITIAL CONDITIONS -------------------------------------- +0.0 OoPDefl - Initial out-of-plane blade-tip displacement (meters) +0.0 IPDefl - Initial in-plane blade-tip deflection (meters) +0.0 BlPitch(1) - Blade 1 initial pitch (degrees) +0.0 BlPitch(2) - Blade 2 initial pitch (degrees) +0.0 BlPitch(3) - Blade 3 initial pitch (degrees) [unused for 2 blades] +0.0 TeetDefl - Initial or fixed teeter angle (degrees) [unused for 3 blades] +0.0 Azimuth - Initial azimuth angle for blade 1 (degrees) +7.223281620282807 RotSpeed - Initial or fixed rotor speed (rpm) +0.0 NacYaw - Initial or fixed nacelle-yaw angle (degrees) +0.0 TTDspFA - Initial fore-aft tower-top displacement (meters) +0.0 TTDspSS - Initial side-to-side tower-top displacement (meters) +0.0 PtfmSurge - Initial or fixed horizontal surge translational displacement of platform (meters) +0.0 PtfmSway - Initial or fixed horizontal sway translational displacement of platform (meters) +0.0 PtfmHeave - Initial or fixed vertical heave translational displacement of platform (meters) +0.0 PtfmRoll - Initial or fixed roll tilt rotational displacement of platform (degrees) +0.0 PtfmPitch - Initial or fixed pitch tilt rotational displacement of platform (degrees) +0.0 PtfmYaw - Initial or fixed yaw rotational displacement of platform (degrees) +---------------------- TURBINE CONFIGURATION ----------------------------------- +3 NumBl - Number of blades (-) +63.45678601946693 TipRad - The distance from the rotor apex to the blade tip (meters) +2.0 HubRad - The distance from the rotor apex to the blade root (meters) +-3.0 PreCone(1) - Blade 1 cone angle (degrees) +-3.0 PreCone(2) - Blade 2 cone angle (degrees) +-3.0 PreCone(3) - Blade 3 cone angle (degrees) [unused for 2 blades] +0.0 HubCM - Distance from rotor apex to hub mass [positive downwind] (meters) +0.0 UndSling - Undersling length [distance from teeter pin to the rotor apex] (meters) [unused for 3 blades] +0.0 Delta3 - Delta-3 angle for teetering rotors (degrees) [unused for 3 blades] +0.0 AzimB1Up - Azimuth value to use for I/O when blade 1 points up (degrees) +-5.0 OverHang - Distance from yaw axis to rotor apex [3 blades] or teeter pin [2 blades] (meters) +0.0 ShftGagL - Distance from rotor apex [3 blades] or teeter pin [2 blades] to shaft strain gages [positive for upwind rotors] (meters) +-4.999629720311564 ShftTilt - Rotor shaft tilt angle (degrees) +0.8829822658380706 NacCMxn - Downwind distance from the tower-top to the nacelle CM (meters) +-0.08924556522324154 NacCMyn - Lateral distance from the tower-top to the nacelle CM (meters) +0.8326312050685473 NacCMzn - Vertical distance from the tower-top to the nacelle CM (meters) +0.0 NcIMUxn - Downwind distance from the tower-top to the nacelle IMU (meters) +0.0 NcIMUyn - Lateral distance from the tower-top to the nacelle IMU (meters) +0.0 NcIMUzn - Vertical distance from the tower-top to the nacelle IMU (meters) +1.1177004388298077 Twr2Shft - Vertical distance from the tower-top to the rotor shaft (meters) +86.5 TowerHt - Height of tower above ground level [onshore] or MSL [offshore] (meters) +0.0 TowerBsHt - Height of tower base above ground level [onshore] or MSL [offshore] (meters) +0.0 PtfmCMxt - Downwind distance from the ground level [onshore] or MSL [offshore] to the platform CM (meters) +0.0 PtfmCMyt - Lateral distance from the ground level [onshore] or MSL [offshore] to the platform CM (meters) +0.0 PtfmCMzt - Vertical distance from the ground level [onshore] or MSL [offshore] to the platform CM (meters) +0.0 PtfmRefzt - Vertical distance from the ground level [onshore] or MSL [offshore] to the platform reference point (meters) +---------------------- MASS AND INERTIA ---------------------------------------- +0.0 TipMass(1) - Tip-brake mass, blade 1 (kg) +0.0 TipMass(2) - Tip-brake mass, blade 2 (kg) +0.0 TipMass(3) - Tip-brake mass, blade 3 (kg) [unused for 2 blades] +7482.264184443234 HubMass - Hub mass (kg) +28639.287453422658 HubIner - Hub inertia about rotor axis [3 blades] or teeter axis [2 blades] (kg m^2) +4940.938090969189 GenIner - Generator inertia about HSS (kg m^2) +113487.2812241146 NacMass - Nacelle mass (kg) +693579.6265889656 NacYIner - Nacelle inertia about yaw axis (kg m^2) +3353.0472655982394 YawBrMass - Yaw bearing mass (kg) +0.0 PtfmMass - Platform mass (kg) +0.0 PtfmRIner - Platform inertia for roll tilt rotation about the platform CM (kg m^2) +0.0 PtfmPIner - Platform inertia for pitch tilt rotation about the platform CM (kg m^2) +0.0 PtfmYIner - Platform inertia for yaw rotation about the platform CM (kg m^2) +---------------------- BLADE --------------------------------------------------- +50 BldNodes - Number of blade nodes (per blade) used for analysis (-) +"NREL-2p8-127_ElastoDyn_blade.dat" BldFile1 - Name of file containing properties for blade 1 (quoted string) +"NREL-2p8-127_ElastoDyn_blade.dat" BldFile2 - Name of file containing properties for blade 2 (quoted string) +"NREL-2p8-127_ElastoDyn_blade.dat" BldFile3 - Name of file containing properties for blade 3 (quoted string) [unused for 2 blades] +---------------------- ROTOR-TEETER -------------------------------------------- +0 TeetMod - Rotor-teeter spring/damper model {0: none, 1: standard, 2: user-defined from routine UserTeet} (switch) [unused for 3 blades] +0.0 TeetDmpP - Rotor-teeter damper position (degrees) [used only for 2 blades and when TeetMod=1] +0.0 TeetDmp - Rotor-teeter damping constant (N-m/(rad/s)) [used only for 2 blades and when TeetMod=1] +0.0 TeetCDmp - Rotor-teeter rate-independent Coulomb-damping moment (N-m) [used only for 2 blades and when TeetMod=1] +0.0 TeetSStP - Rotor-teeter soft-stop position (degrees) [used only for 2 blades and when TeetMod=1] +0.0 TeetHStP - Rotor-teeter hard-stop position (degrees) [used only for 2 blades and when TeetMod=1] +0.0 TeetSSSp - Rotor-teeter soft-stop linear-spring constant (N-m/rad) [used only for 2 blades and when TeetMod=1] +0.0 TeetHSSp - Rotor-teeter hard-stop linear-spring constant (N-m/rad) [used only for 2 blades and when TeetMod=1] +---------------------- DRIVETRAIN ---------------------------------------------- +95.5 GBoxEff - Gearbox efficiency (%) +97.0 GBRatio - Gearbox ratio (-) +283287696.9043701 DTTorSpr - Drivetrain torsional spring (N-m/rad) +1500541.6644456587 DTTorDmp - Drivetrain torsional damper (N-m/(rad/s)) +---------------------- FURLING ------------------------------------------------- +False Furling - Read in additional model properties for furling turbine (flag) [must currently be FALSE) +"none" FurlFile - Name of file containing furling properties (quoted string) [unused when Furling=False] +---------------------- TOWER --------------------------------------------------- +20 TwrNodes - Number of tower nodes used for analysis (-) +"NREL-2p8-127_ElastoDyn_tower.dat" TwrFile - Name of file containing tower properties (quoted string) +---------------------- OUTPUT -------------------------------------------------- +False SumPrint - Print summary data to ".sum" (flag) +1 OutFile - Switch to determine where output will be placed: {1: in module output file only; 2: in glue code output file only; 3: both} (currently unused) +True TabDelim - Use tab delimiters in text tabular output file? (flag) (currently unused) +"ES10.3E2" OutFmt - Format used for text tabular output (except time). Resulting field should be 10 characters. (quoted string) (currently unused) +0.0 TStart - Time to begin tabular output (s) (currently unused) +1 DecFact - Decimation factor for tabular output {1: output every time step} (-) (currently unused) +9 NTwGages - Number of tower nodes that have strain gages for output [0 to 9] (-) +2, 4, 6, 8, 10, 12, 14, 16, 18 TwrGagNd - List of tower nodes that have strain gages [1 to TwrNodes] (-) [unused if NTwGages=0] +9 NBlGages - Number of blade nodes that have strain gages for output [0 to 9] (-) +6, 11, 16, 21, 26, 31, 36, 41, 46 BldGagNd - List of blade nodes that have strain gages [1 to BldNodes] (-) [unused if NBlGages=0] + OutList - The next line(s) contains a list of output parameters. See OutListParameters.xlsx for a listing of available output channels, (-) +"Azimuth" +"BldPitch1" +"BldPitch2" +"BldPitch3" +"GenSpeed" +"LSSTipMys" +"LSSTipMzs" +"LSShftFys" +"LSShftFzs" +"NacYaw" +"RootFxb1" +"RootFxb2" +"RootFxb3" +"RootFxc1" +"RootFxc2" +"RootFxc3" +"RootFyb1" +"RootFyb2" +"RootFyb3" +"RootFyc1" +"RootFyc2" +"RootFyc3" +"RootFzb1" +"RootFzb2" +"RootFzb3" +"RootFzc1" +"RootFzc2" +"RootFzc3" +"RootMxb1" +"RootMxb2" +"RootMxb3" +"RootMxc1" +"RootMxc2" +"RootMxc3" +"RootMyb1" +"RootMyb2" +"RootMyb3" +"RootMyc1" +"RootMyc2" +"RootMyc3" +"RootMzb1" +"RootMzb2" +"RootMzb3" +"RootMzc1" +"RootMzc2" +"RootMzc3" +"RotSpeed" +"RotThrust" +"RotTorq" +"Spn1MLxb1" +"Spn1MLyb1" +"Spn2MLxb1" +"Spn2MLyb1" +"Spn3MLxb1" +"Spn3MLyb1" +"Spn4MLxb1" +"Spn4MLyb1" +"Spn5MLxb1" +"Spn5MLyb1" +"Spn6MLxb1" +"Spn6MLyb1" +"Spn7MLxb1" +"Spn7MLyb1" +"Spn8MLxb1" +"Spn8MLyb1" +"Spn9MLxb1" +"Spn9MLyb1" +"TipDxb1" +"TipDxb2" +"TipDxb3" +"TipDxc1" +"TipDxc2" +"TipDxc3" +"TipDyb1" +"TipDyb2" +"TipDyb3" +"TipDyc1" +"TipDyc2" +"TipDyc3" +"TipDzb1" +"TipDzb2" +"TipDzb3" +"TipDzc1" +"TipDzc2" +"TipDzc3" +"TwrBsMxt" +"TwrBsMyt" +"TwrBsMzt" +END of input file (the word "END" must appear in the first 3 columns of this last OutList line) +--------------------------------------------------------------------------------------- diff --git a/Test_Cases/NREL_2p8_127/NREL-2p8-127_ElastoDyn_blade.dat b/Test_Cases/NREL_2p8_127/NREL-2p8-127_ElastoDyn_blade.dat new file mode 100644 index 00000000..662c3af1 --- /dev/null +++ b/Test_Cases/NREL_2p8_127/NREL-2p8-127_ElastoDyn_blade.dat @@ -0,0 +1,62 @@ +------- ELASTODYN V1.00.* INDIVIDUAL BLADE INPUT FILE -------------------------- +Generated with AeroElasticSE FAST driver +---------------------- BLADE PARAMETERS ---------------------------------------- +30 NBlInpSt - Number of blade input stations (-) +1.0 BldFlDmp1 - Blade flap mode #1 structural damping in percent of critical (%) +1.0 BldFlDmp2 - Blade flap mode #2 structural damping in percent of critical (%) +1.0 BldEdDmp1 - Blade edge mode #1 structural damping in percent of critical (%) +---------------------- BLADE ADJUSTMENT FACTORS -------------------------------- +1.0 FlStTunr1 - Blade flapwise modal stiffness tuner, 1st mode (-) +1.0 FlStTunr2 - Blade flapwise modal stiffness tuner, 2nd mode (-) +1.0 AdjBlMs - Factor to adjust blade mass density (-) +1.0 AdjFlSt - Factor to adjust blade flap stiffness (-) +1.0 AdjEdSt - Factor to adjust blade edge stiffness (-) +---------------------- DISTRIBUTED BLADE PROPERTIES ---------------------------- + BlFract PitchAxis StrcTwst BMassDen FlpStff EdgStff + (-) (-) (deg) (kg/m) (Nm^2) (Nm^2) + 0.000000000000000e+00 5.000000000000000e-01 1.999622705006573e+01 9.710303775720137e+02 8.916645581889803e+09 8.916996828171421e+09 + 3.448275862068966e-02 4.797651657064801e-01 1.931018243810786e+01 9.360384963432447e+02 1.473326655503917e+10 1.503401326999529e+10 + 6.896551724137932e-02 4.100052021425268e-01 1.831714953780435e+01 7.384411481979697e+02 1.350641277548294e+10 1.668758117393011e+10 + 1.034482758620690e-01 3.512493343557562e-01 1.708763041181490e+01 5.242503736808504e+02 7.750625550591639e+09 1.313891689544163e+10 + 1.379310344827586e-01 3.110092285118687e-01 1.569212712279918e+01 4.095720481213451e+02 4.517970071596079e+09 1.065397599903997e+10 + 1.724137931034483e-01 2.834806852225638e-01 1.382289586770404e+01 2.986034040547503e+02 2.639603257135735e+09 7.691984348826207e+09 + 2.068965517241379e-01 2.649028377616424e-01 1.124554309027298e+01 2.242709960488304e+02 1.722995952419500e+09 5.352469758607450e+09 + 2.413793103448276e-01 2.524820938264642e-01 8.602632953470145e+00 2.129606273581960e+02 1.483184105878141e+09 4.327677642529569e+09 + 2.758620689655172e-01 2.449189056667618e-01 6.549224739725965e+00 2.091698491908484e+02 1.365990134494710e+09 3.614205549153540e+09 + 3.103448275862069e-01 2.413757812153578e-01 5.408188380153923e+00 1.968505270832688e+02 1.161884350732890e+09 3.059348888224575e+09 + 3.448275862068965e-01 2.409997816578705e-01 4.552816793256156e+00 1.840381495123537e+02 9.314103670023195e+08 2.635487762688528e+09 + 3.793103448275861e-01 2.438939371115084e-01 3.850103071189125e+00 1.707777565800272e+02 7.316000308334582e+08 2.188136539118910e+09 + 4.137931034482759e-01 2.495413982689942e-01 3.210053831367405e+00 1.577448933617357e+02 5.813400904874783e+08 1.847593613150510e+09 + 4.482758620689655e-01 2.579313748558032e-01 2.548277995517243e+00 1.472572881966913e+02 4.757592505107988e+08 1.631226610849327e+09 + 4.827586206896552e-01 2.680075313847211e-01 1.868987870564891e+00 1.385288690289785e+02 3.862376543475163e+08 1.405932074273394e+09 + 5.172413793103448e-01 2.786890302281694e-01 1.247026288989173e+00 1.303134456935171e+02 3.086236872618167e+08 1.086079003669758e+09 + 5.517241379310345e-01 2.889455550381649e-01 7.591906266374636e-01 1.214132928926456e+02 2.441246000330141e+08 7.279449241103762e+08 + 5.862068965517241e-01 2.981867550411185e-01 4.659000465949885e-01 1.130051988362277e+02 1.889011712485603e+08 4.718010458987974e+08 + 6.206896551724138e-01 3.061372927610646e-01 2.731580237682558e-01 1.057369028682480e+02 1.426024838771875e+08 3.311232129595062e+08 + 6.551724137931035e-01 3.119763987397355e-01 1.231485664729688e-01 9.974549711305480e+01 1.081121588014881e+08 2.531064287089206e+08 + 6.896551724137934e-01 3.154698036179193e-01 -1.889923787502366e-02 9.455111640202743e+01 8.496507419955346e+07 1.976683193694704e+08 + 7.241379310344830e-01 3.174252972719749e-01 -1.841259535939614e-01 8.918927437076574e+01 6.699354322582775e+07 1.803010747112424e+08 + 7.586206896551723e-01 3.157084507688791e-01 -3.432314804149588e-01 8.015835414506564e+01 5.106806818035772e+07 1.739724378313888e+08 + 7.931034482758621e-01 3.095467116664537e-01 -5.034899071419768e-01 7.140526341375902e+01 3.929235153694874e+07 1.684420237335510e+08 + 8.275862068965517e-01 2.996558060513167e-01 -6.944182383563149e-01 5.563937030326857e+01 2.849850000919442e+07 7.873543089740016e+07 + 8.620689655172414e-01 2.881116856742882e-01 -9.464479611794926e-01 4.591127859162181e+01 1.982854313004774e+07 6.415110790287662e+07 + 8.965517241379312e-01 2.777712184636389e-01 -1.331448785580028e+00 3.521480844524145e+01 1.075138794875714e+07 4.514001039735875e+07 + 9.310344827586208e-01 2.706279229199988e-01 -1.857716459023805e+00 2.414179066974884e+01 3.638232945365374e+06 2.616242592743580e+07 + 9.655172413793103e-01 2.665260978643628e-01 -2.493070572147947e+00 3.678240377890068e+00 8.650778718250984e+04 1.574666086617074e+06 + 1.000000000000000e+00 2.500000000000000e-01 -3.205330715589577e+00 1.002353815775734e+00 1.628296293397697e+03 3.168732291579445e+04 +---------------------- BLADE MODE SHAPES --------------------------------------- +0.004521475330089924 BldFl1Sh(2) - Flap mode 1, coeff of x^2 +1.0698094815587011 BldFl1Sh(3) - , coeff of x^3 +-0.1043639462789789 BldFl1Sh(4) - , coeff of x^4 +0.7886224122132662 BldFl1Sh(5) - , coeff of x^5 +-0.7585894228230783 BldFl1Sh(6) - , coeff of x^6 +-0.5138424457535536 BldFl2Sh(2) - Flap mode 2, coeff of x^2 +2.93531699885226 BldFl2Sh(3) - , coeff of x^3 +-19.409314950811712 BldFl2Sh(4) - , coeff of x^4 +32.48595903814384 BldFl2Sh(5) - , coeff of x^5 +-14.498118640430834 BldFl2Sh(6) - , coeff of x^6 +0.17685846482119558 BldEdgSh(2) - Edge mode 1, coeff of x^2 +1.9926745320317614 BldEdgSh(3) - , coeff of x^3 +-4.492670447108128 BldEdgSh(4) - , coeff of x^4 +6.331998738711197 BldEdgSh(5) - , coeff of x^5 +-3.0088612884560257 BldEdgSh(6) - , coeff of x^6 diff --git a/Test_Cases/NREL_2p8_127/NREL-2p8-127_ElastoDyn_tower.dat b/Test_Cases/NREL_2p8_127/NREL-2p8-127_ElastoDyn_tower.dat new file mode 100644 index 00000000..670d3ccc --- /dev/null +++ b/Test_Cases/NREL_2p8_127/NREL-2p8-127_ElastoDyn_tower.dat @@ -0,0 +1,50 @@ +------- ELASTODYN V1.00.* TOWER INPUT FILE ------------------------------------- +Generated with AeroElasticSE FAST driver +---------------------- TOWER PARAMETERS ---------------------------------------- +9 NTwInpSt - Number of input stations to specify tower geometry +1.0 TwrFADmp(1) - Tower 1st fore-aft mode structural damping ratio (%) +1.0 TwrFADmp(2) - Tower 2nd fore-aft mode structural damping ratio (%) +1.0 TwrSSDmp(1) - Tower 1st side-to-side mode structural damping ratio (%) +1.0 TwrSSDmp(2) - Tower 2nd side-to-side mode structural damping ratio (%) +---------------------- TOWER ADJUSTMUNT FACTORS -------------------------------- +1.0 FAStTunr(1) - Tower fore-aft modal stiffness tuner, 1st mode (-) +1.0 FAStTunr(2) - Tower fore-aft modal stiffness tuner, 2nd mode (-) +1.0 SSStTunr(1) - Tower side-to-side stiffness tuner, 1st mode (-) +1.0 SSStTunr(2) - Tower side-to-side stiffness tuner, 2nd mode (-) +1.0 AdjTwMa - Factor to adjust tower mass density (-) +1.0 AdjFASt - Factor to adjust tower fore-aft stiffness (-) +1.0 AdjSSSt - Factor to adjust tower side-to-side stiffness (-) +---------------------- DISTRIBUTED TOWER PROPERTIES ---------------------------- + HtFract TMassDen TwFAStif TwSSStif + (-) (kg/m) (Nm^2) (Nm^2) + 0.000000000000000e+00 3.027735301310815e+03 1.474853951124582e+11 1.474853951124582e+11 + 1.250433977548895e-01 2.718841246770161e+03 1.326329677125010e+11 1.326329677125010e+11 + 2.500867955097790e-01 2.405464101729817e+03 1.161354662267779e+11 1.161354662267779e+11 + 3.751301932646685e-01 2.112377458665061e+03 9.479550671463214e+10 9.479550671463214e+10 + 5.001157273463720e-01 1.947002758491315e+03 7.586780853389151e+10 7.586780853389151e+10 + 6.251591251012615e-01 1.783363103134093e+03 5.857866350808070e+10 5.857866350808070e+10 + 7.502025228561510e-01 1.603905893716689e+03 4.289862070041790e+10 4.289862070041790e+10 + 8.751880569378545e-01 1.409173987955922e+03 2.871944175926664e+10 2.871944175926664e+10 + 1.000000000000000e+00 1.161806938102961e+03 1.956567246347168e+10 1.956567246347168e+10 +---------------------- TOWER FORE-AFT MODE SHAPES ------------------------------ +1.0623105807354711 TwFAM1Sh(2) - Mode 1, coefficient of x^2 term +-0.12782107145017788 TwFAM1Sh(3) - , coefficient of x^3 term +-0.11374039457578099 TwFAM1Sh(4) - , coefficient of x^4 term +0.4380734650926717 TwFAM1Sh(5) - , coefficient of x^5 term +-0.2588225798021839 TwFAM1Sh(6) - , coefficient of x^6 term +916.0158542297875 TwFAM2Sh(2) - Mode 2, coefficient of x^2 term +-524.0268078619857 TwFAM2Sh(3) - , coefficient of x^3 term +-620.6941658768418 TwFAM2Sh(4) - , coefficient of x^4 term +844.0762210901079 TwFAM2Sh(5) - , coefficient of x^5 term +-614.3711015810677 TwFAM2Sh(6) - , coefficient of x^6 term +---------------------- TOWER SIDE-TO-SIDE MODE SHAPES -------------------------- +1.0569471838310198 TwSSM1Sh(2) - Mode 1, coefficient of x^2 term +-0.1296167767277 TwSSM1Sh(3) - , coefficient of x^3 term +-0.09657367230257455 TwSSM1Sh(4) - , coefficient of x^4 term +0.4145201607812788 TwSSM1Sh(5) - , coefficient of x^5 term +-0.24527689558202392 TwSSM1Sh(6) - , coefficient of x^6 term +66.717537330485 TwSSM2Sh(2) - Mode 2, coefficient of x^2 term +-28.88940079202735 TwSSM2Sh(3) - , coefficient of x^3 term +-68.66726547883196 TwSSM2Sh(4) - , coefficient of x^4 term +94.08317763633714 TwSSM2Sh(5) - , coefficient of x^5 term +-62.24404869596283 TwSSM2Sh(6) - , coefficient of x^6 term diff --git a/Test_Cases/NREL_2p8_127/NREL-2p8-127_InflowFile.dat b/Test_Cases/NREL_2p8_127/NREL-2p8-127_InflowFile.dat new file mode 100644 index 00000000..401fd0a0 --- /dev/null +++ b/Test_Cases/NREL_2p8_127/NREL-2p8-127_InflowFile.dat @@ -0,0 +1,57 @@ +------- InflowWind v3.01.* INPUT FILE ------------------------------------------------------------------------- +Generated with AeroElasticSE FAST driver +--------------------------------------------------------------------------------------------------------------- +False Echo - Echo input data to .ech (flag) +1 WindType - switch for wind file type (1=steady; 2=uniform; 3=binary TurbSim FF; 4=binary Bladed-style FF; 5=HAWC format; 6=User defined; 7=native Bladed FF) +0.0 PropagationDir - Direction of wind propagation (meteoroligical rotation from aligned with X (positive rotates towards -Y) -- degrees) +0.0 VFlowAng - Upflow angle (degrees) (not used for native Bladed format WindType=7) +1 NWindVel - Number of points to output the wind velocity (0 to 9) +0.0 WindVxiList - List of coordinates in the inertial X direction (m) +0.0 WindVyiList - List of coordinates in the inertial Y direction (m) +88.5 WindVziList - List of coordinates in the inertial Z direction (m) +================== Parameters for Steady Wind Conditions [used only for WindType = 1] ========================= +6.0 HWindSpeed - Horizontal windspeed (m/s) +87.66 RefHt - Reference height for horizontal wind speed (m) +0.0 PLexp - Power law exponent (-) +================== Parameters for Uniform wind file [used only for WindType = 2] ============================ +"none" Filename_Uni - Filename of time series data for uniform wind field. (-) +87.66 RefHt_Uni - Reference height for horizontal wind speed (m) +1.0 RefLength - Reference length for linear horizontal and vertical sheer (-) +================== Parameters for Binary TurbSim Full-Field files [used only for WindType = 3] ============== +"none" FileName_BTS - Name of the Full field wind file to use (.bts) +================== Parameters for Binary Bladed-style Full-Field files [used only for WindType = 4] ========= +"none" FilenameRoot - Rootname of the full-field wind file to use (.wnd, .sum) +False TowerFile - Have tower file (.twr) (flag) +================== Parameters for HAWC-format binary files [Only used with WindType = 5] ===================== +"none" FileName_u - name of the file containing the u-component fluctuating wind (.bin) +"none" FileName_v - name of the file containing the v-component fluctuating wind (.bin) +"none" FileName_w - name of the file containing the w-component fluctuating wind (.bin) +2 nx - number of grids in the x direction (in the 3 files above) (-) +2 ny - number of grids in the y direction (in the 3 files above) (-) +2 nz - number of grids in the z direction (in the 3 files above) (-) +10 dx - distance (in meters) between points in the x direction (m) +10 dy - distance (in meters) between points in the y direction (m) +10 dz - distance (in meters) between points in the z direction (m) +0.0 RefHt_Hawc - reference height; the height (in meters) of the vertical center of the grid (m) +------------- Scaling parameters for turbulence --------------------------------------------------------- +0 ScaleMethod - Turbulence scaling method [0 = none, 1 = direct scaling, 2 = calculate scaling factor based on a desired standard deviation] +1.0 SFx - Turbulence scaling factor for the x direction (-) [ScaleMethod=1] +1.0 SFy - Turbulence scaling factor for the y direction (-) [ScaleMethod=1] +1.0 SFz - Turbulence scaling factor for the z direction (-) [ScaleMethod=1] +1.0 SigmaFx - Turbulence standard deviation to calculate scaling from in x direction (m/s) [ScaleMethod=2] +1.0 SigmaFy - Turbulence standard deviation to calculate scaling from in y direction (m/s) [ScaleMethod=2] +1.0 SigmaFz - Turbulence standard deviation to calculate scaling from in z direction (m/s) [ScaleMethod=2] +------------- Mean wind profile parameters (added to HAWC-format files) --------------------------------- +0.0 URef - Mean u-component wind speed at the reference height (m/s) +0 WindProfile - Wind profile type (0=constant;1=logarithmic,2=power law) +0.0 PLExp_Hawc - Power law exponent (-) (used for PL wind profile type only) +0.0 Z0 - Surface roughness length (m) (used for LG wind profile type only) +0 XOffset - Initial offset in +x direction (shift of wind box) (-) +====================== OUTPUT ================================================== +False SumPrint - Print summary data to .IfW.sum (flag) +OutList - The next line(s) contains a list of output parameters. See OutListParameters.xlsx for a listing of available output channels, (-) +"Wind1Velx" +"Wind1Vely" +"Wind1Velz" +END of input file (the word "END" must appear in the first 3 columns of this last OutList line) +--------------------------------------------------------------------------------------- diff --git a/Test_Cases/NREL_2p8_127/NREL-2p8-127_ServoDyn.dat b/Test_Cases/NREL_2p8_127/NREL-2p8-127_ServoDyn.dat new file mode 100644 index 00000000..bdc2d74d --- /dev/null +++ b/Test_Cases/NREL_2p8_127/NREL-2p8-127_ServoDyn.dat @@ -0,0 +1,110 @@ +------- SERVODYN v1.05.* INPUT FILE -------------------------------------------- +Generated with AeroElasticSE FAST driver +---------------------- SIMULATION CONTROL -------------------------------------- +False Echo - Echo input data to .ech (flag) +default DT - Communication interval for controllers (s) (or "default") +---------------------- PITCH CONTROL ------------------------------------------- +5 PCMode - Pitch control mode {0: none, 3: user-defined from routine PitchCntrl, 4: user-defined from Simulink/Labview, 5: user-defined from Bladed-style DLL} (switch) +0.0 TPCOn - Time to enable active pitch control (s) [unused when PCMode=0] +99999.0 TPitManS(1) - Time to start override pitch maneuver for blade 1 and end standard pitch control (s) +99999.0 TPitManS(2) - Time to start override pitch maneuver for blade 2 and end standard pitch control (s) +99999.0 TPitManS(3) - Time to start override pitch maneuver for blade 3 and end standard pitch control (s) [unused for 2 blades] +7.0 PitManRat(1) - Pitch rate at which override pitch maneuver heads toward final pitch angle for blade 1 (deg/s) +7.0 PitManRat(2) - Pitch rate at which override pitch maneuver heads toward final pitch angle for blade 2 (deg/s) +7.0 PitManRat(3) - Pitch rate at which override pitch maneuver heads toward final pitch angle for blade 3 (deg/s) [unused for 2 blades] +90.0 BlPitchF(1) - Blade 1 final pitch for pitch maneuvers (degrees) +90.0 BlPitchF(2) - Blade 2 final pitch for pitch maneuvers (degrees) +90.0 BlPitchF(3) - Blade 3 final pitch for pitch maneuvers (degrees) [unused for 2 blades] +---------------------- GENERATOR AND TORQUE CONTROL ---------------------------- +5 VSContrl - Variable-speed control mode {0: none, 1: simple VS, 3: user-defined from routine UserVSCont, 4: user-defined from Simulink/Labview, 5: user-defined from Bladed-style DLL} (switch) +1 GenModel - Generator model {1: simple, 2: Thevenin, 3: user-defined from routine UserGen} (switch) [used only when VSContrl=0] +93.94772808556249 GenEff - Generator efficiency [ignored by the Thevenin and user-defined generator models] (%) +True GenTiStr - Method to start the generator {T: timed using TimGenOn, F: generator speed using SpdGenOn} (flag) +True GenTiStp - Method to stop the generator {T: timed using TimGenOf, F: when generator power = 0} (flag) +99999.0 SpdGenOn - Generator speed to turn on the generator for a startup (HSS speed) (rpm) [used only when GenTiStr=False] +0.0 TimGenOn - Time to turn on the generator for a startup (s) [used only when GenTiStr=True] +99999.0 TimGenOf - Time to turn off the generator (s) [used only when GenTiStp=True] +---------------------- SIMPLE VARIABLE-SPEED TORQUE CONTROL -------------------- +99999.0 VS_RtGnSp - Rated generator speed for simple variable-speed generator control (HSS side) (rpm) [used only when VSContrl=1] +99999.0 VS_RtTq - Rated generator torque/constant generator torque in Region 3 for simple variable-speed generator control (HSS side) (N-m) [used only when VSContrl=1] +99999.0 VS_Rgn2K - Generator torque constant in Region 2 for simple variable-speed generator control (HSS side) (N-m/rpm^2) [used only when VSContrl=1] +99999.0 VS_SlPc - Rated generator slip percentage in Region 2 1/2 for simple variable-speed generator control (%) [used only when VSContrl=1] +---------------------- SIMPLE INDUCTION GENERATOR ------------------------------ +99999.0 SIG_SlPc - Rated generator slip percentage (%) [used only when VSContrl=0 and GenModel=1] +99999.0 SIG_SySp - Synchronous (zero-torque) generator speed (rpm) [used only when VSContrl=0 and GenModel=1] +99999.0 SIG_RtTq - Rated torque (N-m) [used only when VSContrl=0 and GenModel=1] +99999.0 SIG_PORt - Pull-out ratio (Tpullout/Trated) (-) [used only when VSContrl=0 and GenModel=1] +---------------------- THEVENIN-EQUIVALENT INDUCTION GENERATOR ----------------- +99999.0 TEC_Freq - Line frequency [50 or 60] (Hz) [used only when VSContrl=0 and GenModel=2] +0 TEC_NPol - Number of poles [even integer > 0] (-) [used only when VSContrl=0 and GenModel=2] +99999.0 TEC_SRes - Stator resistance (ohms) [used only when VSContrl=0 and GenModel=2] +99999.0 TEC_RRes - Rotor resistance (ohms) [used only when VSContrl=0 and GenModel=2] +99999.0 TEC_VLL - Line-to-line RMS voltage (volts) [used only when VSContrl=0 and GenModel=2] +99999.0 TEC_SLR - Stator leakage reactance (ohms) [used only when VSContrl=0 and GenModel=2] +99999.0 TEC_RLR - Rotor leakage reactance (ohms) [used only when VSContrl=0 and GenModel=2] +99999.0 TEC_MR - Magnetizing reactance (ohms) [used only when VSContrl=0 and GenModel=2] +---------------------- HIGH-SPEED SHAFT BRAKE ---------------------------------- +0 HSSBrMode - HSS brake model {0: none, 1: simple, 3: user-defined from routine UserHSSBr, 4: user-defined from Simulink/Labview, 5: user-defined from Bladed-style DLL} (switch) +99999.0 THSSBrDp - Time to initiate deployment of the HSS brake (s) +99999.0 HSSBrDT - Time for HSS-brake to reach full deployment once initiated (sec) [used only when HSSBrMode=1] +99999.0 HSSBrTqF - Fully deployed HSS-brake torque (N-m) +---------------------- NACELLE-YAW CONTROL ------------------------------------- +0 YCMode - Yaw control mode {0: none, 3: user-defined from routine UserYawCont, 4: user-defined from Simulink/Labview, 5: user-defined from Bladed-style DLL} (switch) +99999.0 TYCOn - Time to enable active yaw control (s) [unused when YCMode=0] +0.0 YawNeut - Neutral yaw position--yaw spring force is zero at this yaw (degrees) +496739375.65069634 YawSpr - Nacelle-yaw spring constant (N-m/rad) +187442.5509148155 YawDamp - Nacelle-yaw damping constant (N-m/(rad/s)) +99999.0 TYawManS - Time to start override yaw maneuver and end standard yaw control (s) +0.25 YawManRat - Yaw maneuver rate (in absolute value) (deg/s) +0.0 NacYawF - Final yaw angle for override yaw maneuvers (degrees) +---------------------- AERODYNAMIC FLOW CONTROL -------------------------------- + 0 AfCmode - Airfoil control mode {0: none, 1: cosine wave cycle, 4: user-defined from Simulink/Labview, 5: user-defined from Bladed-style DLL} (switch) + 0 AfC_Mean - Mean level for cosine cycling or steady value (-) [used only with AfCmode==1] + 0 AfC_Amp - Amplitude for for cosine cycling of flap signal (-) [used only with AfCmode==1] + 0 AfC_Phase - Phase relative to the blade azimuth (0 is vertical) for for cosine cycling of flap signal (deg) [used only with AfCmode==1] +---------------------- STRUCTURAL CONTROL -------------------------------------- +0 NumBStC - Number of blade structural controllers (integer) +"unused" BStCfiles - Name of the files for blade structural controllers (quoted strings) [unused when NumBStC==0] +0 NumNStC - Number of nacelle structural controllers (integer) +"unused" NStCfiles - Name of the files for nacelle structural controllers (quoted strings) [unused when NumNStC==0] +0 NumTStC - Number of tower structural controllers (integer) +"unused" TStCfiles - Name of the files for tower structural controllers (quoted strings) [unused when NumTStC==0] +0 NumSStC - Number of substructure structural controllers (integer) +"unused" SStCfiles - Name of the files for substructure structural controllers (quoted strings) [unused when NumSStC==0] +---------------------- CABLE CONTROL ------------------------------------------- + 0 CCmode - Cable control mode {0: none, 4: user-defined from Simulink/Labview, 5: user-defined from Bladed-style DLL} (switch) +---------------------- BLADED INTERFACE ---------------------------------------- [used only with Bladed Interface] +"/pscratch/ndeveld/awc/ROSCO_B/ROSCO/build/libdiscon.so" DLL_FileName - Name/location of the dynamic library {.dll [Windows] or .so [Linux]} in the Bladed-DLL format (-) [used only with Bladed Interface] +"NREL-2p8-127_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] +False DLL_Ramp - Whether a linear ramp should be used between DLL_DT time steps [introduces time shift when true] (flag) [used only with Bladed Interface] +99999.0 BPCutoff - Cuttoff frequency for low-pass filter on blade pitch from DLL (Hz) [used only with Bladed Interface] +0.0 NacYaw_North - Reference yaw angle of the nacelle when the upwind end points due North (deg) [used only with Bladed Interface] +1 Ptch_Cntrl - Record 28: Use individual pitch control {0: collective pitch; 1: individual pitch control} (switch) [used only with Bladed Interface] +0.0 Ptch_SetPnt - Record 5: Below-rated pitch angle set-point (deg) [used only with Bladed Interface] +0.0 Ptch_Min - Record 6: Minimum pitch angle (deg) [used only with Bladed Interface] +0.0 Ptch_Max - Record 7: Maximum pitch angle (deg) [used only with Bladed Interface] +0.0 PtchRate_Min - Record 8: Minimum pitch rate (most negative value allowed) (deg/s) [used only with Bladed Interface] +0.0 PtchRate_Max - Record 9: Maximum pitch rate (deg/s) [used only with Bladed Interface] +0.0 Gain_OM - Record 16: Optimal mode gain (Nm/(rad/s)^2) [used only with Bladed Interface] +0.0 GenSpd_MinOM - Record 17: Minimum generator speed (rpm) [used only with Bladed Interface] +0.0 GenSpd_MaxOM - Record 18: Optimal mode maximum speed (rpm) [used only with Bladed Interface] +0.0 GenSpd_Dem - Record 19: Demanded generator speed above rated (rpm) [used only with Bladed Interface] +0.0 GenTrq_Dem - Record 22: Demanded generator torque above rated (Nm) [used only with Bladed Interface] +0.0 GenPwr_Dem - Record 13: Demanded power (W) [used only with Bladed Interface] +---------------------- BLADED INTERFACE TORQUE-SPEED LOOK-UP TABLE ------------- +0 DLL_NumTrq - Record 26: No. of points in torque-speed look-up table {0 = none and use the optimal mode parameters; nonzero = ignore the optimal mode PARAMETERs by setting Record 16 to 0.0} (-) [used only with Bladed Interface] +GenSpd_TLU GenTrq_TLU +(rpm) (Nm) +---------------------- OUTPUT -------------------------------------------------- +False SumPrint - Print summary data to .sum (flag) (currently unused) +1 OutFile - Switch to determine where output will be placed: {1: in module output file only; 2: in glue code output file only; 3: both} (currently unused) +True TabDelim - Use tab delimiters in text tabular output file? (flag) (currently unused) +"ES10.3E2" OutFmt - Format used for text tabular output (except time). Resulting field should be 10 characters. (quoted string) (currently unused) +0.0 TStart - Time to begin tabular output (s) (currently unused) + OutList - The next line(s) contains a list of output parameters. See OutListParameters.xlsx for a listing of available output channels, (-) +"GenPwr" +"GenTq" +END of input file (the word "END" must appear in the first 3 columns of this last OutList line) +--------------------------------------------------------------------------------------- diff --git a/Test_Cases/update_rosco_discons.py b/Test_Cases/update_rosco_discons.py index ca08ea31..9a299991 100644 --- a/Test_Cases/update_rosco_discons.py +++ b/Test_Cases/update_rosco_discons.py @@ -12,7 +12,8 @@ map_rel = { 'NREL5MW.yaml': 'NREL-5MW/DISCON.IN', 'IEA15MW.yaml': 'IEA-15-240-RWT-UMaineSemi/DISCON-UMaineSemi.IN', - 'BAR.yaml': 'BAR_10/BAR_10_DISCON.IN' + 'BAR.yaml': 'BAR_10/BAR_10_DISCON.IN', + 'NREL2p8.yaml': 'NREL_2p8_127/NREL-2p8-127_DISCON.IN', } # Directories diff --git a/Tune_Cases/NREL2p8.yaml b/Tune_Cases/NREL2p8.yaml new file mode 100644 index 00000000..bbba19a2 --- /dev/null +++ b/Tune_Cases/NREL2p8.yaml @@ -0,0 +1,65 @@ +path_params: {FAST_InputFile: NREL-2p8-127.fst, FAST_directory: ../Test_Cases/NREL_2p8_127, rotor_performance_filename: NREL-2p8-127_Cp_Ct_Cq.txt} +controller_params: + LoggingLevel: 2 + F_LPFType: 1 + F_NotchType: 0 + IPC_ControlMode: 1 + VS_ControlMode: 3 + PC_ControlMode: 1 + Y_ControlMode: 0 + SS_Mode: 1 + WE_Mode: 2 + PS_Mode: 1 + SD_Mode: 0 + Fl_Mode: 0 + Flp_Mode: 0 + zeta_pc: [2.0062413749856227] + omega_pc: [0.13653659182284006] + zeta_vs: 0.465 + omega_vs: 0.11 + twr_freq: 0.4499 + ptfm_freq: 0.2 + ps_percent: 0.8 + sd_maxpit: 0.4363 + DISCON: {PC_MinPit: -0.1745329, PC_FinePit: 0.0, DLL_FileName: unused, DLL_InFile: unused, DLL_ProcName: DISCON} + TD_Mode: 0 + PwC_Mode: 0 + ZMQ_Mode: 0 + PA_Mode: 0 + Ext_Mode: 0 + U_pc: [12] + interp_type: sigma + max_pitch: 1.57 + min_pitch: 0.0 + vs_minspd: 0.0 + ss_vsgain: 1.0 + ss_pcgain: 0.001 + flp_maxpit: 0.1745 + WS_GS_n: 60 + PC_GS_n: 30 + tune_Fl: true + max_torque_factor: 1.1 + IPC_Kp1p: 0.0 + IPC_Kp2p: 0.0 + IPC_Ki1p: 5.2e-9 + IPC_Ki2p: 0.0 + IPC_Vramp: [0.0, 0.0] + filter_params: {f_we_cornerfreq: 0.20944, f_fl_highpassfreq: 0.01042, f_ss_cornerfreq: 0.6283, f_yawerr: 0.17952, f_sd_cornerfreq: 0.41888} + open_loop: {flag: false, filename: unused, OL_Ind_Breakpoint: 1, OL_Ind_BldPitch: 0, OL_Ind_GenTq: 0, OL_Ind_YawRate: 0} + PA_CornerFreq: 3.14 + PA_Damping: 0.707 + linmodel_tuning: + type: none + linfile_path: none + lintune_outpath: lintune_outfiles + load_parallel: false + stability_margin: 0.1 + omega_pc: {} + flag: true + tuning_yaml: /home/dzalkind/Tools/ROSCO/Tune_Cases/NREL2p8.yaml + n_pitch: 30 + n_tsr: 30 + n_U: 1 + omega_flp: 0.0 + zeta_flp: 0.0 +turbine_params: {rotor_inertia: 19858184.0, rated_rotor_speed: 1.26711, v_min: 3.0, v_rated: 11.4, v_max: 25.0, max_pitch_rate: 0.1745, max_torque_rate: 1500000.0, rated_power: 2800000.0, bld_edgewise_freq: 8.2831853, bld_flapwise_freq: 0.0, TSR_operational: 0} diff --git a/docs/source/api_change.rst b/docs/source/api_change.rst index c3463bf7..0dc00253 100644 --- a/docs/source/api_change.rst +++ b/docs/source/api_change.rst @@ -16,6 +16,8 @@ Optional Inputs - Input requirements depend on control modes. E.g., open loop inputs are not required if `OL_Mode = 0`` IPC Saturation Modes - Added options for saturating the IPC command with the peak shaving limit +Active wake control +- Added Active Wake Control (AWC) implementation ====== ================= ====================================================================================================================================================================================================== New in ROSCO develop @@ -24,16 +26,25 @@ Line Input Name Example Value ====== ================= ====================================================================================================================================================================================================== 6 Echo 0 ! Echo - (0 - no Echo, 1 - Echo input data to .echo) 24 CC_Mode 0 ! CC_Mode - Cable control mode [0- unused, 1- User defined, 2- Position control (not yet implemented)] -28 StC_Mode 0 ! StC_Mode - Structural control mode [0- unused, 1- User defined] -154 Empty Line -155 CC_Section !------- Cable Control --------------------------------------------------------- -156 CC_Group_N 3 ! CC_Group_N - Number of cable control groups -157 CC_GroupIndex 2601 2603 2605 ! CC_GroupIndex - First index for cable control group, should correspond to deltaL -158 CC_ActTau 20.000000 ! CC_ActTau - Time constant for line actuator [s] -159 Empty Line -160 StC_Section !------- Structural Controllers --------------------------------------------------------- -161 StC_Group_N 3 ! StC_Group_N - Number of cable control groups -162 StC_GroupIndex 2818 2838 2858 ! StC_GroupIndex - First index for structural control group, options specified in ServoDyn summary output +25 AWC_Mode 0 ! AWC_Mode - Active wake control mode [0 - not used, 1 - complex number method, 2 - Coleman transform method] +29 StC_Mode 0 ! StC_Mode - Structural control mode [0- unused, 1- User defined] +146 Empty Line +147 AWC_Section !------- Active Wake Control ----------------------------------------------------- +148 AWC_NumModes 1 ! AWC_NumModes - AWC- Number of modes to include [-] +149 AWC_n 1 ! AWC_n - AWC azimuthal mode [-] (only used in complex number method) +150 AWC_harmonic 1 ! AWC_harmonic - AWC Coleman transform harmonic [-] (only used in Coleman transform method) +151 AWC_NumModes 0.03 ! AWC_freq - AWC frequency [Hz] +152 AWC_NumModes 2.0 ! AWC_amp - AWC amplitude [deg] +153 AWC_NumModes 0.0 ! AWC_clockangle - AWC clock angle [deg] +163 Empty Line +164 CC_Section !------- Cable Control --------------------------------------------------------- +165 CC_Group_N 3 ! CC_Group_N - Number of cable control groups +166 CC_GroupIndex 2601 2603 2605 ! CC_GroupIndex - First index for cable control group, should correspond to deltaL +167 CC_ActTau 20.000000 ! CC_ActTau - Time constant for line actuator [s] +168 Empty Line +169 StC_Section !------- Structural Controllers --------------------------------------------------------- +170 StC_Group_N 3 ! StC_Group_N - Number of cable control groups +171 StC_GroupIndex 2818 2838 2858 ! StC_GroupIndex - First index for structural control group, options specified in ServoDyn summary output ====== ================= ====================================================================================================================================================================================================== diff --git a/setup.py b/setup.py index 70fa943f..ef0e507f 100644 --- a/setup.py +++ b/setup.py @@ -43,16 +43,17 @@ REQUIRED = [ 'matplotlib', 'numpy', - 'pytest', + #'pytest', 'scipy', 'pyYAML', - 'future', + #'future', 'pandas' ] # For the CMake Extensions this_directory = os.path.abspath(os.path.dirname(__file__)) + class CMakeExtension(Extension): def __init__(self, name, sourcedir='', **kwa): From 8a39f3cc7d1b38cbb2ba3bdbc73f326039f6d3f4 Mon Sep 17 00:00:00 2001 From: dzalkind Date: Mon, 3 Apr 2023 17:51:09 -0600 Subject: [PATCH 095/224] Update example with ramp, reference --- Examples/24_power_ref_control.py | 31 +++++++++++++++---------------- 1 file changed, 15 insertions(+), 16 deletions(-) diff --git a/Examples/24_power_ref_control.py b/Examples/24_power_ref_control.py index d6e8ee3a..e309ae02 100644 --- a/Examples/24_power_ref_control.py +++ b/Examples/24_power_ref_control.py @@ -47,7 +47,7 @@ def main(): # Create rotor speed table - controller, turbine, path_params = yaml_to_objs(parameter_filename) + controller, _, _ = yaml_to_objs(parameter_filename) # plot original ops @@ -71,28 +71,27 @@ def main(): # plot new lookup plt.plot(v,omega,linestyle='--') - - # simulation set up r = run_FAST_ROSCO() r.tuning_yaml = parameter_filename - r.wind_case_fcn = cl.simp_step # single step wind input - r.wind_case_fcn = cl.power_curve + r.wind_case_fcn = cl.ramp # single step wind input r.wind_case_opts = { - 'U': [9], - 'T_max': 100, + 'U_start': 5, # from 10 to 15 m/s + 'U_end': 35, + 't_start': 100, + 't_end': 2500, } - r.case_inputs = {} r.save_dir = run_dir - # r.controller_params = { - # 'OD_Mode': 1, - # 'DISCON': { - # 'Echo': True, - # }} # Use OutData in control r.rosco_dir = rosco_dir - + r.controller_params = { + 'PRC_Mode': 1, + 'DISCON': { + 'PRC_Mode': 1, + 'PRC_n': len(v), + 'PRC_WindSpeeds': v, + 'PRC_RotorSpeeds': omega, + + }} # Use OutData in control r.run_FAST() - - if __name__=="__main__": main() \ No newline at end of file From de15e52d405b648e84123a43c551ccb3ea5dc902 Mon Sep 17 00:00:00 2001 From: dzalkind <65573423+dzalkind@users.noreply.github.com> Date: Tue, 4 Apr 2023 11:50:23 -0600 Subject: [PATCH 096/224] Various bug fixes (#233) * Allow optional UAStart/EndRad * Re-wind file read if the input is not there * Set avrSWAP(79) to 4 to follow Bladed API * Update documentation with new example names --- ROSCO/src/ReadSetParameters.f90 | 2 +- ROSCO_toolbox/ofTools/fast_io/FAST_reader.py | 17 ++++++++++-- docs/source/standard_use.rst | 29 ++++++++++---------- 3 files changed, 30 insertions(+), 18 deletions(-) diff --git a/ROSCO/src/ReadSetParameters.f90 b/ROSCO/src/ReadSetParameters.f90 index dcaecbc1..603a9b32 100644 --- a/ROSCO/src/ReadSetParameters.f90 +++ b/ROSCO/src/ReadSetParameters.f90 @@ -163,7 +163,7 @@ SUBROUTINE SetParameters(avrSWAP, accINFILE, size_avcMSG, CntrPar, LocalVar, obj avrSWAP(56) = 0.0 ! Torque override: 0=yes avrSWAP(65) = 0.0 ! Number of variables returned for logging avrSWAP(72) = 0.0 ! Generator start-up resistance - avrSWAP(79) = 0.0 ! Request for loads: 0=none + avrSWAP(79) = 4.0 ! Request for loads: 0=none avrSWAP(80) = 0.0 ! Variable slip current status avrSWAP(81) = 0.0 ! Variable slip current demand diff --git a/ROSCO_toolbox/ofTools/fast_io/FAST_reader.py b/ROSCO_toolbox/ofTools/fast_io/FAST_reader.py index adf08ae2..fe4fc0b5 100644 --- a/ROSCO_toolbox/ofTools/fast_io/FAST_reader.py +++ b/ROSCO_toolbox/ofTools/fast_io/FAST_reader.py @@ -797,8 +797,21 @@ def read_AeroDyn15(self): f.readline() self.fst_vt['AeroDyn15']['UAMod'] = int(f.readline().split()[0]) self.fst_vt['AeroDyn15']['FLookup'] = bool_read(f.readline().split()[0]) - #self.fst_vt['AeroDyn15']['UAStartRad'] = float_read(f.readline().split()[0]) - #self.fst_vt['AeroDyn15']['UAEndRad'] = float_read(f.readline().split()[0]) + + file_pos = f.tell() + line = f.readline() + if 'UAStartRad' in line: + self.fst_vt['AeroDyn15']['UAStartRad'] = float_read(line.split()[0]) + else: + f.seek(file_pos) + + file_pos = f.tell() + line = f.readline() + if 'UAEndRad' in line: + self.fst_vt['AeroDyn15']['UAEndRad'] = float_read(line.split()[0]) + else: + f.seek(file_pos) + # Airfoil Information f.readline() diff --git a/docs/source/standard_use.rst b/docs/source/standard_use.rst index e96c4f52..a23310dc 100644 --- a/docs/source/standard_use.rst +++ b/docs/source/standard_use.rst @@ -16,12 +16,11 @@ Several OpenFAST inputs are located in `Test_Cases/ `_. A detailed description of the ROSCO control inputs and tuning :code:`.yaml` are provided in :ref:`discon_in` and :ref:`rt_tuning_yaml`, respectively. -* :code:`example_01.py` loads an OpenFAST turbine model and displays a summary of its information -* :code:`example_02.py` plots the :math:`C_p` surface of a turbine +* :code:`01_turbine_model.py` loads an OpenFAST turbine model and displays a summary of its information ROSCO requires the power and thrust coefficients for tuning control inputs and running the extended Kalman filter wind speed estimator. -* :code:`example_03.py` runs cc-blade, a blade element momentum solver from WISDEM, to generate a :math:`C_p` surface. +* :code:`02_ccblade.py` runs cc-blade, a blade element momentum solver from WISDEM, to generate a :math:`C_p` surface. The :code:`Cp_Cq_Ct.txt` (or similar) file contains the rotor performance tables that are necessary to run the ROSCO controller. This file can be located wherever you desire, just be sure to point to it properly with the :code:`PerfFileName` parameter in :code:`DISCON.IN`. @@ -36,9 +35,9 @@ Generally :code:`omega_*` increases the responsiveness of the controller, reduci :code:`zeta_*` changes the damping of the controller and is generally less important of a tuning parameter, but could also help with loading. The default parameters in `Tune_Cases/ `_ are known to work well with the turbines in this repository. -* :code:`example_04.py` loads a turbine and tunes the PI control gains -* :code:`example_05.py` tunes a controller and runs a simple simualtion (not using OpenFAST) -* :code:`example_06.py` loads a turbine, tunes a controller, and runs an OpenFAST simulation +* :code:`03_tune_controller.py` loads a turbine and tunes the PI control gains +* :code:`04_simple_sim.py` tunes a controller and runs a simple simualtion (not using OpenFAST) +* :code:`05_openfast_sim.py` loads a turbine, tunes a controller, and runs an OpenFAST simulation Each of these examples generates a :code:`DISCON.IN` file, which is an input to libdiscon.*. When running the controller in OpenFAST, :code:`DISCON.IN` must be appropriately named using the :code:`DLL_FileName` parameter in ServoDyn. @@ -51,18 +50,18 @@ OpenFAST can be installed from `source `_ ROSCO can implement peak shaving (or thrust clipping) by changing the minimum pitch angle based on the estimated wind speed: -* :code:`example_07.py` loads a turbine and tunes a controller with peak shaving. +* :code:`06_peak_shaving.py` loads a turbine and tunes a controller with peak shaving. By setting the :code:`ps_percent` value in the tuning yaml, the minimum pitch versus wind speed table changes and is updated in the :code:`DISCON.IN` file. ROSCO also contains a method for distributed aerodynamic control (e.g., via trailing edge flaps): -* :code:`example_10.py` tunes a controller for distributed aerodynamic control +* :code:`09_distributed_aero.py` tunes a controller for distributed aerodynamic control The ROSCO toolbox also contains methods for working with OpenFAST linear models -* :code:`example_11.py` exports a file of the parameters used for the simplified linear models used to tune ROSCO -* :code:`example_12.py` shows how linear models generated using OpenFAST can be used to tune controllers with robust stability properties. -* :code:`example_13.py` shows the tuning procedure for IPC +* :code:`10_linear_params.py` exports a file of the parameters used for the simplified linear models used to tune ROSCO +* :code:`11_robust_tuning.py` shows how linear models generated using OpenFAST can be used to tune controllers with robust stability properties. +* :code:`12_tune_ipc.py` shows the tuning procedure for IPC Running OpenFAST Simulations ---------------------------- @@ -81,10 +80,10 @@ The ROSCO_toolbox has methods for running OpenFAST (and other) binary executable Several example scripts are set up to quickly simulate ROSCO with OpenFAST: -* :code:`example_06.py` loads a turbine, tunes a controller, and runs an OpenFAST simulation -* :code:`example_08.py` loads the OpenFAST output files and plots the results -* :code:`example_09.py` runs TurbSim, for generating turbulent wind inputs -* :code:`example_14.py` runs an OpenFAST simulation with ROSCO providing open loop control inputs +* :code:`05_openfast_sim.py` loads a turbine, tunes a controller, and runs an OpenFAST simulation +* :code:`07_openfast_outputs.py` loads the OpenFAST output files and plots the results +* :code:`08_run_turbsim.py` runs TurbSim, for generating turbulent wind inputs +* :code:`14_open_loop_control.py` runs an OpenFAST simulation with ROSCO providing open loop control inputs Testing ROSCO From ac14b174d362ad470dfbb7f71a94bf5aa93029e7 Mon Sep 17 00:00:00 2001 From: dzalkind Date: Wed, 5 Apr 2023 12:07:43 -0600 Subject: [PATCH 097/224] Init PC_RefSpeed if no PRC --- ROSCO/src/ControllerBlocks.f90 | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/ROSCO/src/ControllerBlocks.f90 b/ROSCO/src/ControllerBlocks.f90 index f146d692..83890433 100644 --- a/ROSCO/src/ControllerBlocks.f90 +++ b/ROSCO/src/ControllerBlocks.f90 @@ -39,13 +39,13 @@ SUBROUTINE ComputeVariablesSetpoints(CntrPar, LocalVar, objInst, ErrVar) ! Power reference tracking rotor speed IF (CntrPar%PRC_Mode == 1) THEN LocalVar%PC_RefSpd = interp1d(CntrPar%PRC_WindSpeeds,CntrPar%PRC_RotorSpeeds,LocalVar%WE_Vw_F,ErrVar) * CntrPar%WE_GearboxRatio + ELSE + LocalVar%PC_RefSpd = CntrPar%PC_RefSpd ENDIF ! Implement setpoint smoothing IF (LocalVar%SS_DelOmegaF < 0) THEN LocalVar%PC_RefSpd = LocalVar%PC_RefSpd - LocalVar%SS_DelOmegaF - ELSE - LocalVar%PC_RefSpd = LocalVar%PC_RefSpd ENDIF ! Compute error for pitch controller From 60b366d0aec0cb25e3b743bbba699daa8d39714c Mon Sep 17 00:00:00 2001 From: dzalkind Date: Wed, 5 Apr 2023 12:31:06 -0600 Subject: [PATCH 098/224] Revert openfast changes --- .../IEA-15-240-RWT-UMaineSemi.fst | 4 ++-- .../IEA-15-240-RWT-UMaineSemi_ElastoDyn.dat | 12 ++++++------ 2 files changed, 8 insertions(+), 8 deletions(-) diff --git a/Test_Cases/IEA-15-240-RWT-UMaineSemi/IEA-15-240-RWT-UMaineSemi.fst b/Test_Cases/IEA-15-240-RWT-UMaineSemi/IEA-15-240-RWT-UMaineSemi.fst index aff9b66e..a2684323 100644 --- a/Test_Cases/IEA-15-240-RWT-UMaineSemi/IEA-15-240-RWT-UMaineSemi.fst +++ b/Test_Cases/IEA-15-240-RWT-UMaineSemi/IEA-15-240-RWT-UMaineSemi.fst @@ -14,9 +14,9 @@ False Echo - Echo input data to .ech (flag) 1 CompInflow - Compute inflow wind velocities (switch) {0=still air; 1=InflowWind; 2=external from OpenFOAM} 2 CompAero - Compute aerodynamic loads (switch) {0=None; 1=AeroDyn v14; 2=AeroDyn v15} 1 CompServo - Compute control and electrical-drive dynamics (switch) {0=None; 1=ServoDyn} - 0 CompHydro - Compute hydrodynamic loads (switch) {0=None; 1=HydroDyn} + 1 CompHydro - Compute hydrodynamic loads (switch) {0=None; 1=HydroDyn} 0 CompSub - Compute sub-structural dynamics (switch) {0=None; 1=SubDyn} - 0 CompMooring - Compute mooring system (switch) {0=None; 1=MAP++; 2=FEAMooring; 3=MoorDyn; 4=OrcaFlex} + 3 CompMooring - Compute mooring system (switch) {0=None; 1=MAP++; 2=FEAMooring; 3=MoorDyn; 4=OrcaFlex} 0 CompIce - Compute ice loads (switch) {0=None; 1=IceFloe; 2=IceDyn} 0 MHK - MHK turbine type (switch) {0=Not an MHK turbine; 1=Fixed MHK turbine; 2=Floating MHK turbine} ---------------------- ENVIRONMENTAL CONDITIONS -------------------------------- diff --git a/Test_Cases/IEA-15-240-RWT-UMaineSemi/IEA-15-240-RWT-UMaineSemi_ElastoDyn.dat b/Test_Cases/IEA-15-240-RWT-UMaineSemi/IEA-15-240-RWT-UMaineSemi_ElastoDyn.dat index 6f5ad8b4..c0f6fbe7 100644 --- a/Test_Cases/IEA-15-240-RWT-UMaineSemi/IEA-15-240-RWT-UMaineSemi_ElastoDyn.dat +++ b/Test_Cases/IEA-15-240-RWT-UMaineSemi/IEA-15-240-RWT-UMaineSemi_ElastoDyn.dat @@ -16,12 +16,12 @@ True TwFADOF1 - First fore-aft tower bending-mode DOF (flag) True TwFADOF2 - Second fore-aft tower bending-mode DOF (flag) True TwSSDOF1 - First side-to-side tower bending-mode DOF (flag) True TwSSDOF2 - Second side-to-side tower bending-mode DOF (flag) -False PtfmSgDOF - Platform horizontal surge translation DOF (flag) -False PtfmSwDOF - Platform horizontal sway translation DOF (flag) -False PtfmHvDOF - Platform vertical heave translation DOF (flag) -False PtfmRDOF - Platform roll tilt rotation DOF (flag) -False PtfmPDOF - Platform pitch tilt rotation DOF (flag) -False PtfmYDOF - Platform yaw rotation DOF (flag) +True PtfmSgDOF - Platform horizontal surge translation DOF (flag) +True PtfmSwDOF - Platform horizontal sway translation DOF (flag) +True PtfmHvDOF - Platform vertical heave translation DOF (flag) +True PtfmRDOF - Platform roll tilt rotation DOF (flag) +True PtfmPDOF - Platform pitch tilt rotation DOF (flag) +True PtfmYDOF - Platform yaw rotation DOF (flag) ---------------------- INITIAL CONDITIONS -------------------------------------- 0 OoPDefl - Initial out-of-plane blade-tip displacement (meters) 0 IPDefl - Initial in-plane blade-tip deflection (meters) From 24bded08fb453bc4426033b094d3ee6103f2484e Mon Sep 17 00:00:00 2001 From: dzalkind Date: Wed, 5 Apr 2023 12:34:18 -0600 Subject: [PATCH 099/224] Add note about offset --- Examples/18_pitch_offsets.py | 2 ++ 1 file changed, 2 insertions(+) diff --git a/Examples/18_pitch_offsets.py b/Examples/18_pitch_offsets.py index ace996c5..1a13752b 100644 --- a/Examples/18_pitch_offsets.py +++ b/Examples/18_pitch_offsets.py @@ -74,6 +74,8 @@ def main(): offset_3 = fastout[0]['BldPitch3'] - fastout[0]['BldPitch1'] # check that offset (min,max) is very close to prescribed values + # Note that some OpenFAST configurations (e.g., fixed bottom) do not apply offet on + # first timestep and this example may fail np.testing.assert_almost_equal(offset_2.max(),pitch2_offset,decimal=3) np.testing.assert_almost_equal(offset_2.min(),pitch2_offset,decimal=3) np.testing.assert_almost_equal(offset_3.max(),pitch3_offset,decimal=3) From 585e2c8b1a59ee9d945ce93514a4bf0af4623d15 Mon Sep 17 00:00:00 2001 From: dzalkind <65573423+dzalkind@users.noreply.github.com> Date: Mon, 10 Apr 2023 15:47:17 -0600 Subject: [PATCH 100/224] Open loop platform control (#236) * Add open loop cable example * Add open loop cable and StC control in ROSCO * Add open loop cable control in toolbox * Init Ind_Cable/Struct Control * Add openfast_exe as run_FAST attribute * Tidy input writing * Regenerate DISCONs * Update API change docs --- Examples/22_cable_control.py | 60 +++++++--- ROSCO/rosco_registry/rosco_types.yaml | 18 ++- ROSCO/src/Controllers.f90 | 31 +++-- ROSCO/src/DISCON.F90 | 2 +- ROSCO/src/ROSCO_Helpers.f90 | 10 +- ROSCO/src/ROSCO_Types.f90 | 6 +- ROSCO/src/ReadSetParameters.f90 | 107 ++++++++++++++++-- ROSCO_toolbox/controller.py | 54 ++++++++- ROSCO_toolbox/inputs/toolbox_schema.yaml | 20 +++- ROSCO_toolbox/ofTools/case_gen/run_FAST.py | 3 +- ROSCO_toolbox/utilities.py | 6 +- Test_Cases/BAR_10/BAR_10_DISCON.IN | 10 +- .../DISCON-UMaineSemi.IN | 10 +- Test_Cases/NREL-5MW/DISCON.IN | 10 +- .../NREL_2p8_127/NREL-2p8-127_DISCON.IN | 16 +-- docs/source/api_change.rst | 42 +++---- 16 files changed, 320 insertions(+), 85 deletions(-) diff --git a/Examples/22_cable_control.py b/Examples/22_cable_control.py index 8c808200..4965e135 100644 --- a/Examples/22_cable_control.py +++ b/Examples/22_cable_control.py @@ -15,6 +15,7 @@ from ROSCO_toolbox.ofTools.fast_io.FAST_reader import InputReader_OpenFAST from ROSCO_toolbox.inputs.validation import load_rosco_yaml import matplotlib.pyplot as plt +from ROSCO_toolbox.controller import OpenLoopControl ''' ROSCO currently supports user-defined hooks for cable control actuation, if CC_Mode = 1. @@ -34,19 +35,11 @@ example_out_dir = os.path.join(this_dir,'examples_out') os.makedirs(example_out_dir,exist_ok=True) -if platform.system() == 'Windows': - lib_name = os.path.realpath(os.path.join(this_dir, '../ROSCO/build/libdiscon.dll')) -elif platform.system() == 'Darwin': - lib_name = os.path.realpath(os.path.join(this_dir, '../ROSCO/build/libdiscon.dylib')) -else: - lib_name = os.path.realpath(os.path.join(this_dir, '../ROSCO/build/libdiscon.so')) - - def main(): # Input yaml and output directory parameter_filename = os.path.join(rosco_dir,'Tune_Cases/IEA15MW_cable.yaml') - run_dir = os.path.join(example_out_dir,'22_cable_control') + run_dir = os.path.join(example_out_dir,'22_cable_control_OL_1') os.makedirs(run_dir,exist_ok=True) # Read initial input file @@ -72,18 +65,59 @@ def main(): # Set up ServoDyn for cable control reader.fst_vt['ServoDyn']['CCmode'] = 5 + # Set heading + heading = 40 # deg + reader.fst_vt['ServoDyn']['YawNeut'] = heading + reader.fst_vt['ElastoDyn']['NacYaw'] = heading + reader.fst_vt['InflowWind']['PropagationDir'] = -heading + + t_trans = 100 + t_sigma = 20 + t_max = 200 + + line_ends = [-14.51, 1.58, 10.33] + + olc = OpenLoopControl(t_max=t_max) + olc.interp_timeseries( + 'cable_control_1', + [0,t_trans,t_trans+t_sigma], + [0,0,line_ends[0]] , + 'sigma' + ) + + olc.interp_timeseries( + 'cable_control_2', + [0,t_trans,t_trans+t_sigma], + [0,0,line_ends[1]] , + 'sigma' + ) + + olc.interp_timeseries( + 'cable_control_3', + [0,t_trans,t_trans+t_sigma], + [0,0,line_ends[2]] , + 'sigma' + ) + + + ol_params = olc.write_input(os.path.join(run_dir,'open_loop_cable.dat')) + + controller_params = {} + controller_params['open_loop'] = ol_params + controller_params['CC_Mode'] = 2 + # simulation set up r = run_FAST_ROSCO() r.tuning_yaml = parameter_filename r.wind_case_fcn = cl.simp_step # single step wind input r.wind_case_fcn = cl.power_curve r.wind_case_opts = { - 'U': [9], - 'T_max': 100, + 'U': [8], + 'TMax': t_max, } r.case_inputs = {} r.fst_vt = reader.fst_vt - # r.controller_params = controller_params + r.controller_params = controller_params r.save_dir = run_dir r.rosco_dir = rosco_dir @@ -111,7 +145,7 @@ def main(): plt.savefig(os.path.join(example_out_dir,'22_cable_control.png')) # Check that the last segment of line 1 shrinks by 10 m - np.testing.assert_almost_equal(md_out[0]['Seg20Lst'][-1] - md_out[0]['Seg20Lst'][0], -10, 2) + np.testing.assert_almost_equal(md_out[0]['Seg20Lst'][-1] - md_out[0]['Seg20Lst'][0], line_ends[0], 2) diff --git a/ROSCO/rosco_registry/rosco_types.yaml b/ROSCO/rosco_registry/rosco_types.yaml index d2d5fa60..759c9d0a 100644 --- a/ROSCO/rosco_registry/rosco_types.yaml +++ b/ROSCO/rosco_registry/rosco_types.yaml @@ -417,6 +417,14 @@ ControlParameters: Ind_YawRate: <<: *integer description: The column in OL_Filename that contains the generator torque in Nm + Ind_CableControl: + <<: *integer + allocatable: True + description: The column in OL_Filename that contains the cable control inputs in m + Ind_StructControl: + <<: *integer + allocatable: True + description: The column in OL_Filename that contains the structural control inputs in various units OL_Breakpoints: <<: *real allocatable: True @@ -425,6 +433,14 @@ ControlParameters: <<: *real allocatable: True description: Open blade pitch timeseries + OL_CableControl: + <<: *real + allocatable: True + dimension: (:,:) + OL_StructControl: + <<: *real + allocatable: True + dimension: (:,:) OL_GenTq: <<: *real allocatable: True @@ -561,7 +577,7 @@ ControlParameters: # StC Control StC_Mode: <<: *integer - description: Flag for ZeroMQ (0-off, 1-yaw} + description: Flag for StC Control StC_Group_N: <<: *integer diff --git a/ROSCO/src/Controllers.f90 b/ROSCO/src/Controllers.f90 index c966ac20..221dd16b 100644 --- a/ROSCO/src/Controllers.f90 +++ b/ROSCO/src/Controllers.f90 @@ -670,7 +670,7 @@ SUBROUTINE ActiveWakeControl(CntrPar, LocalVar, DebugVar) END SUBROUTINE ActiveWakeControl !------------------------------------------------------------------------------------------------------------------------------- - SUBROUTINE CableControl(avrSWAP, CntrPar, LocalVar, objInst) + SUBROUTINE CableControl(avrSWAP, CntrPar, LocalVar, objInst, ErrVar) ! Cable controller ! CC_Mode = 0, No cable control, this code not executed ! CC_Mode = 1, User-defined cable control @@ -678,13 +678,14 @@ SUBROUTINE CableControl(avrSWAP, CntrPar, LocalVar, objInst) ! ! Note that LocalVar%CC_Actuated*(), and CC_Desired() has a fixed max size of 12, which can be increased in rosco_types.yaml ! - USE ROSCO_Types, ONLY : ControlParameters, LocalVariables, ObjectInstances + USE ROSCO_Types, ONLY : ControlParameters, LocalVariables, ObjectInstances, ErrorVariables REAL(ReKi), INTENT(INOUT) :: avrSWAP(*) ! The swap array, used to pass data to, and receive data from, the DLL controller. TYPE(ControlParameters), INTENT(INOUT) :: CntrPar TYPE(LocalVariables), INTENT(INOUT) :: LocalVar TYPE(ObjectInstances), INTENT(INOUT) :: objInst + TYPE(ErrorVariables), INTENT(INOUT) :: ErrVar ! Internal Variables Integer(IntKi) :: I_GROUP @@ -693,13 +694,28 @@ SUBROUTINE CableControl(avrSWAP, CntrPar, LocalVar, objInst) IF (CntrPar%CC_Mode == 1) THEN ! User defined control - IF (LocalVar%Time > 50) THEN + IF (LocalVar%Time > 500) THEN ! Shorten first group by 4 m - LocalVar%CC_DesiredL(1) = -10 + LocalVar%CC_DesiredL(1) = -14.51 + LocalVar%CC_DesiredL(2) = 1.58 + LocalVar%CC_DesiredL(3) = -10.332 END IF + ELSEIF (CntrPar%CC_Mode == 2) THEN + ! Open loop control + ! DO I_GROUP = 1, CntrPar%CC_Group_N + ! LocalVar%CC_DesiredL(I_GROUP) = interp1d(x,y,eq,ErrVar) + + DO I_GROUP = 1,CntrPar%CC_Group_N + IF (CntrPar%Ind_CableControl(I_GROUP) > 0) THEN + LocalVar%CC_DesiredL(I_GROUP) = interp1d(CntrPar%OL_Breakpoints, & + CntrPar%OL_CableControl(I_GROUP,:), & + LocalVar%Time,ErrVar) + ENDIF + ENDDO + END IF @@ -753,10 +769,11 @@ SUBROUTINE StructuralControl(avrSWAP, CntrPar, LocalVar, objInst) IF (CntrPar%StC_Mode == 1) THEN ! User defined control - IF (LocalVar%Time > 50) THEN + IF (LocalVar%Time > 500) THEN ! Step change in input of -4500 N - LocalVar%StC_Input(1) = -4e5 - + LocalVar%StC_Input(1) = -1.234e+06 + LocalVar%StC_Input(2) = 2.053e+06 + LocalVar%StC_Input(3) = -7.795e+05 END IF diff --git a/ROSCO/src/DISCON.F90 b/ROSCO/src/DISCON.F90 index 9482ca51..3b0f7291 100644 --- a/ROSCO/src/DISCON.F90 +++ b/ROSCO/src/DISCON.F90 @@ -119,7 +119,7 @@ SUBROUTINE DISCON(avrSWAP, aviFAIL, accINFILE, avcOUTNAME, avcMSG) BIND (C, NAME ! Cable control IF (CntrPar%CC_Mode > 0) THEN - CALL CableControl(avrSWAP,CntrPar,LocalVar, objInst) + CALL CableControl(avrSWAP,CntrPar,LocalVar, objInst, ErrVar) END IF ! Structural control diff --git a/ROSCO/src/ROSCO_Helpers.f90 b/ROSCO/src/ROSCO_Helpers.f90 index a10a1b72..13f9d2d6 100644 --- a/ROSCO/src/ROSCO_Helpers.f90 +++ b/ROSCO/src/ROSCO_Helpers.f90 @@ -159,7 +159,7 @@ subroutine ParseInput_Int_Opt(FileLines, VarName, Variable, FileName, ErrVar, Al ENDIF Variable = 0 ! Default of integer inputs is 0 for now - PRINT *, "Did not find "//TRIM( VarName )//" in input file. Using default value of ", Variable + PRINT *, "ROSCO Warning: Did not find "//TRIM( VarName )//" in input file. Using default value of ", Variable ENDIF ! Debugging: show what's being read, turn into Echo later @@ -241,7 +241,7 @@ subroutine ParseInput_Dbl_Opt(FileLines, VarName, Variable, FileName, ErrVar, Al ENDIF Variable = 0 ! Default of integer inputs is 0 for now - PRINT *, "Did not find "//TRIM( VarName )//" in input file. Using default value of ", Variable + PRINT *, "ROSCO Warning: Did not find "//TRIM( VarName )//" in input file. Using default value of ", Variable ENDIF ! Debugging: show what's being read, turn into Echo later @@ -322,7 +322,7 @@ subroutine ParseInput_Str_Opt(FileLines, VarName, Variable, FileName, ErrVar, Al ENDIF Variable = 'unused' ! Default of string input is unused for now - PRINT *, "Did not find "//TRIM( VarName )//" in input file. Using default value of ", TRIM(Variable) + PRINT *, "ROSCO Warning: Did not find "//TRIM( VarName )//" in input file. Using default value of ", TRIM(Variable) ENDIF ! Debugging: show what's being read, turn into Echo later @@ -804,7 +804,7 @@ SUBROUTINE ParseInAry_Opt( FileLines, ParamName, Ary, AryLen, FileName, ErrVar, ENDIF Ary = 0 ! Default of allocatable arrays is 0 for now - PRINT *, "Did not find "//TRIM( ParamName )//" in input file. Using default value of [", Ary, "]" + PRINT *, "ROSCO Warning: Did not find correct size "//TRIM( ParamName )//" in input file. Using default value of [", Ary, "]" ENDIF IF (FoundLine) THEN @@ -943,7 +943,7 @@ SUBROUTINE ParseDbAry_Opt ( FileLines, ParamName, Ary, AryLen, FileName, ErrVar, ENDIF Ary = 0 ! Default of allocatable arrays is 0 for now - PRINT *, "Did not find "//TRIM( ParamName )//" in input file. Using default value of [", Ary, "]" + PRINT *, "ROSCO Warning: Did not find correct size"//TRIM( ParamName )//" in input file. Using default value of [", Ary, "]" ENDIF IF (FoundLine) THEN diff --git a/ROSCO/src/ROSCO_Types.f90 b/ROSCO/src/ROSCO_Types.f90 index 987f1a6c..7aa6bfdf 100644 --- a/ROSCO/src/ROSCO_Types.f90 +++ b/ROSCO/src/ROSCO_Types.f90 @@ -107,8 +107,12 @@ MODULE ROSCO_Types INTEGER(IntKi) :: Ind_BldPitch ! The column in OL_Filename that contains the blade pitch input in rad INTEGER(IntKi) :: Ind_GenTq ! The column in OL_Filename that contains the generator torque in Nm INTEGER(IntKi) :: Ind_YawRate ! The column in OL_Filename that contains the generator torque in Nm + INTEGER(IntKi), DIMENSION(:), ALLOCATABLE :: Ind_CableControl ! The column in OL_Filename that contains the cable control inputs in m + INTEGER(IntKi), DIMENSION(:), ALLOCATABLE :: Ind_StructControl ! The column in OL_Filename that contains the structural control inputs in various units REAL(DbKi), DIMENSION(:), ALLOCATABLE :: OL_Breakpoints ! Open loop breakpoints in timeseries REAL(DbKi), DIMENSION(:), ALLOCATABLE :: OL_BldPitch ! Open blade pitch timeseries + REAL(DbKi), DIMENSION(:,:), ALLOCATABLE :: OL_CableControl ! None + REAL(DbKi), DIMENSION(:,:), ALLOCATABLE :: OL_StructControl ! None REAL(DbKi), DIMENSION(:), ALLOCATABLE :: OL_GenTq ! Open generator torque timeseries REAL(DbKi), DIMENSION(:), ALLOCATABLE :: OL_YawRate ! Open yaw rate timeseries REAL(DbKi), DIMENSION(:,:), ALLOCATABLE :: OL_Channels ! Open loop channels in timeseries @@ -135,7 +139,7 @@ MODULE ROSCO_Types INTEGER(IntKi) :: CC_Group_N ! Number of cable control groups REAL(DbKi) :: CC_ActTau ! Time constant for line actuator [s] INTEGER(IntKi), DIMENSION(:), ALLOCATABLE :: CC_GroupIndex ! Cable control group indices - INTEGER(IntKi) :: StC_Mode ! Flag for ZeroMQ (0-off, 1-yaw} + INTEGER(IntKi) :: StC_Mode ! Flag for StC Control INTEGER(IntKi) :: StC_Group_N ! Number of cable control groups INTEGER(IntKi), DIMENSION(:), ALLOCATABLE :: StC_GroupIndex ! Cable control group indices REAL(DbKi) :: PC_RtTq99 ! 99% of the rated torque value, using for switching between pitch and torque control, [Nm]. diff --git a/ROSCO/src/ReadSetParameters.f90 b/ROSCO/src/ReadSetParameters.f90 index 603a9b32..23a5bde7 100644 --- a/ROSCO/src/ReadSetParameters.f90 +++ b/ROSCO/src/ReadSetParameters.f90 @@ -130,10 +130,13 @@ SUBROUTINE SetParameters(avrSWAP, accINFILE, size_avcMSG, CntrPar, LocalVar, obj CHARACTER(NINT(avrSWAP(50))-1), INTENT(IN) :: RootName - INTEGER(IntKi) :: K ! Index used for looping through blades. + INTEGER(IntKi) :: K, I, I_OL ! Index used for looping through blades. CHARACTER(1024) :: OL_String ! Open description loop string INTEGER(IntKi) :: OL_Count ! Number of open loop channels + INTEGER(IntKi) :: N_OL_Cables + INTEGER(IntKi) :: N_OL_StCs + CHARACTER(*), PARAMETER :: RoutineName = 'SetParameters' @@ -246,6 +249,29 @@ SUBROUTINE SetParameters(avrSWAP, accINFILE, size_avcMSG, CntrPar, LocalVar, obj OL_Count = OL_Count + 1 ENDIF + N_OL_Cables = 0 + IF (ANY(CntrPar%Ind_CableControl > 0)) THEN + DO I = 1,SIZE(CntrPar%Ind_CableControl) + IF (CntrPar%Ind_CableControl(I) > 0) THEN + OL_String = TRIM(OL_String)//' Cable'//TRIM(Int2LStr(I))//' ' + OL_Count = OL_Count + 1 + N_OL_Cables = N_OL_Cables + 1 + ENDIF + ENDDO + ENDIF + + N_OL_StCs = 0 + IF (ANY(CntrPar%Ind_StructControl > 0)) THEN + DO I = 1,SIZE(CntrPar%Ind_StructControl) + IF (CntrPar%Ind_StructControl(I) > 0) THEN + OL_String = TRIM(OL_String)//' StC'//TRIM(Int2LStr(I))//' ' + OL_Count = OL_Count + 1 + N_OL_StCs = N_OL_StCs + 1 + ENDIF + ENDDO + ENDIF + + PRINT *, 'ROSCO: Implementing open loop control for'//TRIM(OL_String) CALL Read_OL_Input(CntrPar%OL_Filename,110_IntKi,OL_Count,CntrPar%OL_Channels, ErrVar) @@ -262,6 +288,29 @@ SUBROUTINE SetParameters(avrSWAP, accINFILE, size_avcMSG, CntrPar, LocalVar, obj IF (CntrPar%Ind_YawRate > 0) THEN CntrPar%OL_YawRate = CntrPar%OL_Channels(:,CntrPar%Ind_YawRate) ENDIF + + IF (ANY(CntrPar%Ind_CableControl > 0)) THEN + ALLOCATE(CntrPar%OL_CableControl(N_OL_Cables,SIZE(CntrPar%OL_Channels,DIM=1))) + I_OL = 1 + DO I = 1,SIZE(CntrPar%Ind_CableControl) + IF (CntrPar%Ind_CableControl(I) > 0) THEN + CntrPar%OL_CableControl(I_OL,:) = CntrPar%OL_Channels(:,CntrPar%Ind_CableControl(I)) + I_OL = I_OL + 1 + ENDIF + ENDDO + ENDIF + + IF (ANY(CntrPar%Ind_StructControl > 0)) THEN + ALLOCATE(CntrPar%OL_StructControl(N_OL_StCs,SIZE(CntrPar%OL_Channels,DIM=1))) + I_OL = 1 + DO I = 1,SIZE(CntrPar%Ind_StructControl) + IF (CntrPar%Ind_StructControl(I) > 0) THEN + CntrPar%OL_StructControl(I_OL,:) = CntrPar%OL_Channels(:,CntrPar%Ind_StructControl(I)) + I_OL = I_OL + 1 + ENDIF + ENDDO + ENDIF + END IF @@ -496,6 +545,7 @@ SUBROUTINE ReadControlParameterFileSub(CntrPar, zmqVar, accINFILE, accINFILE_siz CALL ParseInput(FileLines, 'Ind_YawRate', CntrPar%Ind_YawRate, accINFILE(1), ErrVar, UnEc=UnEc) IF (ErrVar%aviFAIL < 0) RETURN + !------------ Pitch Actuator Inputs ------------ CALL ParseInput(FileLines, 'PA_CornerFreq', CntrPar%PA_CornerFreq, accINFILE(1), ErrVar, CntrPar%PA_Mode == 0, UnEc) CALL ParseInput(FileLines, 'PA_Damping', CntrPar%PA_Damping, accINFILE(1), ErrVar, CntrPar%PA_Mode == 0, UnEc) @@ -536,6 +586,11 @@ SUBROUTINE ReadControlParameterFileSub(CntrPar, zmqVar, accINFILE, accINFILE_siz CALL ParseAry( FileLines, 'StC_GroupIndex', CntrPar%StC_GroupIndex, CntrPar%StC_Group_N, accINFILE(1), ErrVar, CntrPar%StC_Mode == 0, UnEc) IF (ErrVar%aviFAIL < 0) RETURN + ! Open loop cable, structural control, needs number of groups + CALL ParseAry( FileLines, 'Ind_CableControl', CntrPar%Ind_CableControl, CntrPar%CC_Group_N, accINFILE(1), ErrVar, CntrPar%CC_Mode .NE. 2, UnEc=UnEc) + CALL ParseAry( FileLines, 'Ind_StructControl', CntrPar%Ind_StructControl, CntrPar%StC_Group_N, accINFILE(1), ErrVar, CntrPar%StC_Mode .NE. 2, UnEc=UnEc) + IF (ErrVar%aviFAIL < 0) RETURN + IF (UnEc > 0) CLOSE(UnEc) ! Close echo file !!!!!!!!!!!!!!!!!!!!!!!!!!!!!!! @@ -655,6 +710,7 @@ SUBROUTINE CheckInputs(LocalVar, CntrPar, avrSWAP, ErrVar, size_avcMSG) ! Local INTEGER(IntKi) :: I + INTEGER(IntKi), ALLOCATABLE :: All_OL_Indices(:) !.............................................................................................................................. ! Check validity of input parameters: @@ -1021,7 +1077,6 @@ SUBROUTINE CheckInputs(LocalVar, CntrPar, avrSWAP, ErrVar, size_avcMSG) ! WE_FOPoles_v IF (CntrPar%WE_Mode == 2 .AND. .NOT. NonDecreasing(CntrPar%WE_FOPoles_v)) THEN ErrVar%aviFAIL = -1 - write(400,*) CntrPar%WE_FOPoles_v ErrVar%ErrMsg = 'WE_FOPoles_v must be non-decreasing.' ENDIF @@ -1068,10 +1123,21 @@ SUBROUTINE CheckInputs(LocalVar, CntrPar, avrSWAP, ErrVar, size_avcMSG) ! --- Open loop control --- IF (CntrPar%OL_Mode > 0) THEN - IF (((CntrPar%Ind_Breakpoint) < 0) .OR. & - (CntrPar%Ind_BldPitch < 0) .OR. & - (CntrPar%Ind_GenTq < 0) .OR. & - (CntrPar%Ind_YawRate < 0)) THEN + ! Get all open loop indices + ALLOCATE(All_OL_Indices(3)) ! Will need to increase to 5 when IPC + All_OL_Indices = (/CntrPar%Ind_BldPitch, & + CntrPar%Ind_GenTq, & + CntrPar%Ind_YawRate/) + + DO I = 1,SIZE(CntrPar%Ind_CableControl) + Call AddToList(All_OL_Indices, CntrPar%Ind_CableControl(I)) + ENDDO + + DO I = 1,SIZE(CntrPar%Ind_StructControl) + Call AddToList(All_OL_Indices, CntrPar%Ind_StructControl(I)) + ENDDO + + IF (ANY(All_OL_Indices < 0)) THEN ErrVar%aviFAIL = -1 ErrVar%ErrMsg = 'All open loop control indices must be greater than zero' ENDIF @@ -1081,12 +1147,22 @@ SUBROUTINE CheckInputs(LocalVar, CntrPar, avrSWAP, ErrVar, size_avcMSG) ErrVar%ErrMsg = 'Ind_Breakpoint must be non-zero if OL_Mode is non-zero' ENDIF - IF ((CntrPar%Ind_BldPitch < 1) .AND. & - (CntrPar%Ind_GenTq < 1) .AND. & - (CntrPar%Ind_YawRate < 1)) THEN + IF (ALL(All_OL_Indices < 1)) THEN ErrVar%aviFAIL = -1 ErrVar%ErrMsg = 'At least one open loop input channel must be non-zero' ENDIF + + IF (ANY(CntrPar%Ind_CableControl > 0) .AND. CntrPar%CC_Mode .NE. 2) THEN + ErrVar%aviFAIL = -1 + ErrVar%ErrMsg = 'CC_Mode must be 2 if using open loop cable control via Ind_CableControl' + ENDIF + + IF (ANY(CntrPar%Ind_StructControl > 0) .AND. CntrPar%StC_Mode .NE. 2) THEN + ErrVar%aviFAIL = -1 + ErrVar%ErrMsg = 'CC_Mode must be 2 if using open loop struct control via Ind_StructControl' + ENDIF + + ENDIF ! ---- AWC vs. IPC @@ -1153,7 +1229,7 @@ SUBROUTINE CheckInputs(LocalVar, CntrPar, avrSWAP, ErrVar, size_avcMSG) END IF END IF - IF ((CntrPar%CC_Mode < 0) .OR. (CntrPar%CC_Mode > 1)) THEN + IF ((CntrPar%CC_Mode < 0) .OR. (CntrPar%CC_Mode > 2)) THEN ErrVar%aviFAIL = -1 ErrVar%ErrMsg = 'CC_Mode must be 0 or 1' END IF @@ -1180,6 +1256,17 @@ SUBROUTINE CheckInputs(LocalVar, CntrPar, avrSWAP, ErrVar, size_avcMSG) END IF END DO END IF + + ! Check that open loop control active if using open loop cable/struct control + IF (CntrPar%CC_Mode == 2 .AND. CntrPar%OL_Mode .NE. 1) THEN + ErrVar%aviFAIL = -1 + ErrVar%ErrMsg = 'OL_Mode must be 1 if using CC_Mode = 2 (open loop)' + END IF + + IF (CntrPar%StC_Mode == 2 .AND. CntrPar%OL_Mode .NE. 1) THEN + ErrVar%aviFAIL = -1 + ErrVar%ErrMsg = 'OL_Mode must be 1 if using StC_Mode = 2 (open loop)' + END IF diff --git a/ROSCO_toolbox/controller.py b/ROSCO_toolbox/controller.py index 13672371..c5896517 100644 --- a/ROSCO_toolbox/controller.py +++ b/ROSCO_toolbox/controller.py @@ -142,6 +142,8 @@ def __init__(self, controller_params): self.OL_Mode = int(controller_params['open_loop']['flag']) self.OL_Filename = controller_params['open_loop']['filename'] self.OL_Ind_Breakpoint = self.OL_Ind_BldPitch = self.OL_Ind_GenTq = self.OL_Ind_YawRate = 0 + self.OL_Ind_CableControl = [0] + self.OL_Ind_StructControl = [0] if self.OL_Mode: ol_params = controller_params['open_loop'] @@ -149,6 +151,8 @@ def __init__(self, controller_params): self.OL_Ind_BldPitch = ol_params['OL_Ind_BldPitch'] self.OL_Ind_GenTq = ol_params['OL_Ind_GenTq'] self.OL_Ind_YawRate = ol_params['OL_Ind_YawRate'] + self.OL_Ind_CableControl = ol_params['OL_Ind_CableControl'] + self.OL_Ind_StructControl = ol_params['OL_Ind_StructControl'] # Check that file exists because we won't write it if not os.path.exists(self.OL_Filename): @@ -668,7 +672,7 @@ def __init__(self, **kwargs): self.ol_timeseries = {} self.ol_timeseries['time'] = np.arange(0,self.t_max,self.dt) - self.allowed_controls = ['blade_pitch','generator_torque','nacelle_yaw','nacelle_yaw_rate'] + self.allowed_controls = ['blade_pitch','generator_torque','nacelle_yaw','nacelle_yaw_rate','cable_control','struct_control'] def const_timeseries(self,control,value): @@ -687,7 +691,8 @@ def interp_timeseries(self,control,breakpoints,values,method='sigma'): if len(breakpoints) != len(values): raise Exception('Open loop breakpoints and values do not have the same length') - if control not in self.allowed_controls: + # Check if control in allowed controls, cable_control_* is in cable_control + if not any([ac in control for ac in self.allowed_controls]): raise Exception(f'Open loop control of {control} is not allowed') else: @@ -752,8 +757,11 @@ def write_input(self,ol_filename): ol_timeseries = self.ol_timeseries + # Init indices OL_Ind_Breakpoint = 1 OL_Ind_BldPitch = OL_Ind_GenTq = OL_Ind_YawRate = 0 + OL_Ind_CableControl = [] + OL_Ind_StructControl = [] self.OL_Ind_Breakpoint = 1 ol_index_counter = 2 # start input index at 2 @@ -785,6 +793,32 @@ def write_input(self,ol_filename): if 'nacelle_yaw' in ol_timeseries and 'nacelle_yaw_rate' not in ol_timeseries: raise Exception('nacelle_yaw is in ol_timeseries and nacelle_yaw_rate is not. ROSCO can only command yaw rate. Use compute_yaw_rate() to convert.') + # Cable control + is_cable_chan = np.array(['cable_control' in ol_chan for ol_chan in ol_timeseries.keys()]) + if any(is_cable_chan): + # if any channels are cable_control_* + n_cable_chan = np.sum(is_cable_chan) + cable_chan_names = np.array(list(ol_timeseries.keys()))[is_cable_chan] + + # Let's assume they are 1-indexed and all there, otherwise a key error will be thrown + for cable_chan in cable_chan_names: + ol_control_array = np.c_[ol_control_array,ol_timeseries[cable_chan]] + OL_Ind_CableControl.append(ol_index_counter) + ol_index_counter += 1 + + # Struct control + is_struct_chan = ['struct_control' in ol_chan for ol_chan in ol_timeseries.keys()] + if any(is_struct_chan): + # if any channels are struct_control_* + n_struct_chan = np.sum(np.array(is_struct_chan)) + + # Let's assume they are 1-indexed and all there, otherwise a key error will be thrown + for i_chan in range(1,n_struct_chan+1): + ol_control_array = np.c_[ol_control_array,ol_timeseries[f'struct_control_{i_chan}']] + OL_Ind_StructControl.append(ol_index_counter) + ol_index_counter += 1 + + # Open file if not os.path.exists(os.path.dirname(os.path.abspath(ol_filename))): os.makedirs(os.path.dirname(os.path.abspath(ol_filename))) @@ -805,6 +839,20 @@ def write_input(self,ol_filename): header_line += '\t\tYawRate' unit_line += '\t\t(rad/s)' + if OL_Ind_CableControl: + for i_chan in range(1,n_cable_chan+1): + header_line += f'\t\tCable{i_chan}' + unit_line += '\t\t(m)' + else: + OL_Ind_CableControl = [0] + + if OL_Ind_StructControl: + for i_chan in range(1,n_struct_chan+1): + header_line += f'\t\tStruct{i_chan}' + unit_line += '\t\t(m)' + else: + OL_Ind_StructControl = [0] + header_line += '\n' unit_line += '\n' @@ -824,6 +872,8 @@ def write_input(self,ol_filename): open_loop['OL_Ind_BldPitch'] = OL_Ind_BldPitch open_loop['OL_Ind_GenTq'] = OL_Ind_GenTq open_loop['OL_Ind_YawRate'] = OL_Ind_YawRate + open_loop['OL_Ind_CableControl'] = OL_Ind_CableControl + open_loop['OL_Ind_StructControl'] = OL_Ind_StructControl return open_loop diff --git a/ROSCO_toolbox/inputs/toolbox_schema.yaml b/ROSCO_toolbox/inputs/toolbox_schema.yaml index c5d08c74..80a5486d 100644 --- a/ROSCO_toolbox/inputs/toolbox_schema.yaml +++ b/ROSCO_toolbox/inputs/toolbox_schema.yaml @@ -218,15 +218,15 @@ properties: CC_Mode: type: number minimum: 0 - maximum: 1 + maximum: 2 default: 0 - description: Cable control mode [0- unused, 1- User defined, 2- Position control (not yet implemented)] + description: Cable control mode [0- unused, 1- User defined, 2- Open loop control] StC_Mode: type: number minimum: 0 - maximum: 1 + maximum: 2 default: 0 - description: Structural control mode [0- unused, 1- User defined] + description: Structural control mode [0- unused, 1- User defined, 2- Open loop control] U_pc: type: array description: List of wind speeds to schedule pitch control zeta and omega @@ -868,6 +868,18 @@ properties: Ind_YawRate: type: number description: The column in OL_Filename that contains the generator torque in Nm + Ind_CableControl: + type: array + items: + type: number + description: The column in OL_Filename that contains the cable control inputs in m + # default: [0] # No default because it's defined in controller and DISCON_Dict + Ind_StructControl: + type: array + items: + type: number + description: The column in OL_Filename that contains the structural control inputs in various units + # default: [0] # No default because it's defined in controller and DISCON_Dict DLL_FileName: type: string description: Name/location of the dynamic library {.dll [Windows] or .so [Linux]} in the Bladed-DLL format diff --git a/ROSCO_toolbox/ofTools/case_gen/run_FAST.py b/ROSCO_toolbox/ofTools/case_gen/run_FAST.py index e26c6f86..acff382f 100644 --- a/ROSCO_toolbox/ofTools/case_gen/run_FAST.py +++ b/ROSCO_toolbox/ofTools/case_gen/run_FAST.py @@ -37,6 +37,7 @@ def __init__(self): self.base_name = '' self.controller_params = {} self.fst_vt = {} + self.openfast_exe = 'openfast' # Directories self.tune_case_dir = '' @@ -172,7 +173,7 @@ def run_FAST(self): fastBatch.case_list = case_list fastBatch.case_name_list = case_name_list fastBatch.fst_vt = self.fst_vt - fastBatch.FAST_exe = 'openfast' + fastBatch.FAST_exe = self.openfast_exe if MPI: fastBatch.run_mpi(comm_map_down) diff --git a/ROSCO_toolbox/utilities.py b/ROSCO_toolbox/utilities.py index b15b46e2..cf7f3218 100644 --- a/ROSCO_toolbox/utilities.py +++ b/ROSCO_toolbox/utilities.py @@ -226,7 +226,9 @@ def write_DISCON(turbine, controller, param_file='DISCON.IN', txt_filename='Cp_C file.write('{0:<12d} ! Ind_Breakpoint - The column in OL_Filename that contains the breakpoint (time if OL_Mode = 1)\n'.format(int(rosco_vt['Ind_Breakpoint']))) file.write('{0:<12d} ! Ind_BldPitch - The column in OL_Filename that contains the blade pitch input in rad\n'.format(int(rosco_vt['Ind_BldPitch']))) file.write('{0:<12d} ! Ind_GenTq - The column in OL_Filename that contains the generator torque in Nm\n'.format(int(rosco_vt['Ind_GenTq']))) - file.write('{0:<12d} ! Ind_YawRate - The column in OL_Filename that contains the generator torque in Nm\n'.format(int(rosco_vt['Ind_YawRate']))) + file.write('{0:<12d} ! Ind_YawRate - The column in OL_Filename that contains the nacelle yaw rate rad/s\n'.format(int(rosco_vt['Ind_YawRate']))) + file.write('{} ! Ind_CableControl - The column(s) in OL_Filename that contains the cable control inputs in m [Used with CC_Mode = 2, must be the same size as CC_Group_N]\n'.format(write_array(rosco_vt['Ind_CableControl'],'<4d'))) + file.write('{} ! Ind_StructControl - The column(s) in OL_Filename that contains the structural control inputs [Used with StC_Mode = 2, must be the same size as StC_Group_N]\n'.format(write_array(rosco_vt['Ind_StructControl'],'<4d'))) file.write('\n') file.write('!------- Pitch Actuator Model -----------------------------------------------------\n') file.write('{:<014.5f} ! PA_CornerFreq - Pitch actuator bandwidth/cut-off frequency [rad/s]\n'.format(rosco_vt['PA_CornerFreq'])) @@ -563,6 +565,8 @@ def DISCON_dict(turbine, controller, txt_filename=None): DISCON_dict['Ind_BldPitch'] = controller.OL_Ind_BldPitch DISCON_dict['Ind_GenTq'] = controller.OL_Ind_GenTq DISCON_dict['Ind_YawRate'] = controller.OL_Ind_YawRate + DISCON_dict['Ind_CableControl'] = controller.OL_Ind_CableControl + DISCON_dict['Ind_StructControl'] = controller.OL_Ind_StructControl # ------- Pitch Actuator ------- DISCON_dict['PA_Mode'] = controller.PA_Mode DISCON_dict['PA_CornerFreq'] = controller.PA_CornerFreq diff --git a/Test_Cases/BAR_10/BAR_10_DISCON.IN b/Test_Cases/BAR_10/BAR_10_DISCON.IN index 6bdb4e12..e1df6715 100644 --- a/Test_Cases/BAR_10/BAR_10_DISCON.IN +++ b/Test_Cases/BAR_10/BAR_10_DISCON.IN @@ -1,5 +1,5 @@ ! Controller parameter input file for the BAR_10 wind turbine -! - File written using ROSCO version 2.7.0 controller tuning logic on 03/20/23 +! - File written using ROSCO version 2.7.0 controller tuning logic on 04/10/23 !------- DEBUG ------------------------------------------------------------ 1 ! LoggingLevel - (0: write no debug files, 1: write standard output .dbg-file, 2: LoggingLevel 1 + ROSCO LocalVars (.dbg2) 3: LoggingLevel 2 + complete avrSWAP-array (.dbg3)) @@ -25,8 +25,8 @@ 0 ! AWC_Mode - Active wake control {0 - not used, 1 - complex number method, 2 - Coleman transform method} 0 ! Ext_Mode - External control mode {0 - not used, 1 - call external dynamic library} 0 ! ZMQ_Mode - Fuse ZeroMQ interface {0: unused, 1: Yaw Control} -0 ! CC_Mode - Cable control mode [0- unused, 1- User defined, 2- Position control (not yet implemented)] -0 ! StC_Mode - Structural control mode [0- unused, 1- User defined] +0 ! CC_Mode - Cable control mode [0- unused, 1- User defined, 2- Open loop control] +0 ! StC_Mode - Structural control mode [0- unused, 1- User defined, 2- Open loop control] !------- FILTERS ---------------------------------------------------------- 0.81771 ! F_LPFCornerFreq - Corner frequency (-3dB point) in the low-pass filters, [rad/s] @@ -135,7 +135,9 @@ 0 ! Ind_Breakpoint - The column in OL_Filename that contains the breakpoint (time if OL_Mode = 1) 0 ! Ind_BldPitch - The column in OL_Filename that contains the blade pitch input in rad 0 ! Ind_GenTq - The column in OL_Filename that contains the generator torque in Nm -0 ! Ind_YawRate - The column in OL_Filename that contains the generator torque in Nm +0 ! Ind_YawRate - The column in OL_Filename that contains the nacelle yaw rate rad/s +0 ! Ind_CableControl - The column(s) in OL_Filename that contains the cable control inputs in m [Used with CC_Mode = 2, must be the same size as CC_Group_N] +0 ! Ind_StructControl - The column(s) in OL_Filename that contains the structural control inputs [Used with StC_Mode = 2, must be the same size as StC_Group_N] !------- Pitch Actuator Model ----------------------------------------------------- 3.140000000000 ! PA_CornerFreq - Pitch actuator bandwidth/cut-off frequency [rad/s] diff --git a/Test_Cases/IEA-15-240-RWT-UMaineSemi/DISCON-UMaineSemi.IN b/Test_Cases/IEA-15-240-RWT-UMaineSemi/DISCON-UMaineSemi.IN index 078319ac..f35af5df 100644 --- a/Test_Cases/IEA-15-240-RWT-UMaineSemi/DISCON-UMaineSemi.IN +++ b/Test_Cases/IEA-15-240-RWT-UMaineSemi/DISCON-UMaineSemi.IN @@ -1,5 +1,5 @@ ! Controller parameter input file for the IEA-15-240-RWT-UMaineSemi wind turbine -! - File written using ROSCO version 2.7.0 controller tuning logic on 03/20/23 +! - File written using ROSCO version 2.7.0 controller tuning logic on 04/10/23 !------- DEBUG ------------------------------------------------------------ 2 ! LoggingLevel - (0: write no debug files, 1: write standard output .dbg-file, 2: LoggingLevel 1 + ROSCO LocalVars (.dbg2) 3: LoggingLevel 2 + complete avrSWAP-array (.dbg3)) @@ -25,8 +25,8 @@ 0 ! AWC_Mode - Active wake control {0 - not used, 1 - complex number method, 2 - Coleman transform method} 0 ! Ext_Mode - External control mode {0 - not used, 1 - call external dynamic library} 0 ! ZMQ_Mode - Fuse ZeroMQ interface {0: unused, 1: Yaw Control} -0 ! CC_Mode - Cable control mode [0- unused, 1- User defined, 2- Position control (not yet implemented)] -0 ! StC_Mode - Structural control mode [0- unused, 1- User defined] +0 ! CC_Mode - Cable control mode [0- unused, 1- User defined, 2- Open loop control] +0 ! StC_Mode - Structural control mode [0- unused, 1- User defined, 2- Open loop control] !------- FILTERS ---------------------------------------------------------- 1.00810 ! F_LPFCornerFreq - Corner frequency (-3dB point) in the low-pass filters, [rad/s] @@ -135,7 +135,9 @@ 0 ! Ind_Breakpoint - The column in OL_Filename that contains the breakpoint (time if OL_Mode = 1) 0 ! Ind_BldPitch - The column in OL_Filename that contains the blade pitch input in rad 0 ! Ind_GenTq - The column in OL_Filename that contains the generator torque in Nm -0 ! Ind_YawRate - The column in OL_Filename that contains the generator torque in Nm +0 ! Ind_YawRate - The column in OL_Filename that contains the nacelle yaw rate rad/s +0 ! Ind_CableControl - The column(s) in OL_Filename that contains the cable control inputs in m [Used with CC_Mode = 2, must be the same size as CC_Group_N] +0 ! Ind_StructControl - The column(s) in OL_Filename that contains the structural control inputs [Used with StC_Mode = 2, must be the same size as StC_Group_N] !------- Pitch Actuator Model ----------------------------------------------------- 1.570800000000 ! PA_CornerFreq - Pitch actuator bandwidth/cut-off frequency [rad/s] diff --git a/Test_Cases/NREL-5MW/DISCON.IN b/Test_Cases/NREL-5MW/DISCON.IN index 60775ec0..f2c1d47d 100644 --- a/Test_Cases/NREL-5MW/DISCON.IN +++ b/Test_Cases/NREL-5MW/DISCON.IN @@ -1,5 +1,5 @@ ! Controller parameter input file for the NREL-5MW wind turbine -! - File written using ROSCO version 2.7.0 controller tuning logic on 03/20/23 +! - File written using ROSCO version 2.7.0 controller tuning logic on 04/10/23 !------- DEBUG ------------------------------------------------------------ 1 ! LoggingLevel - (0: write no debug files, 1: write standard output .dbg-file, 2: LoggingLevel 1 + ROSCO LocalVars (.dbg2) 3: LoggingLevel 2 + complete avrSWAP-array (.dbg3)) @@ -25,8 +25,8 @@ 0 ! AWC_Mode - Active wake control {0 - not used, 1 - complex number method, 2 - Coleman transform method} 0 ! Ext_Mode - External control mode {0 - not used, 1 - call external dynamic library} 0 ! ZMQ_Mode - Fuse ZeroMQ interface {0: unused, 1: Yaw Control} -0 ! CC_Mode - Cable control mode [0- unused, 1- User defined, 2- Position control (not yet implemented)] -0 ! StC_Mode - Structural control mode [0- unused, 1- User defined] +0 ! CC_Mode - Cable control mode [0- unused, 1- User defined, 2- Open loop control] +0 ! StC_Mode - Structural control mode [0- unused, 1- User defined, 2- Open loop control] !------- FILTERS ---------------------------------------------------------- 1.57080 ! F_LPFCornerFreq - Corner frequency (-3dB point) in the low-pass filters, [rad/s] @@ -135,7 +135,9 @@ 0 ! Ind_Breakpoint - The column in OL_Filename that contains the breakpoint (time if OL_Mode = 1) 0 ! Ind_BldPitch - The column in OL_Filename that contains the blade pitch input in rad 0 ! Ind_GenTq - The column in OL_Filename that contains the generator torque in Nm -0 ! Ind_YawRate - The column in OL_Filename that contains the generator torque in Nm +0 ! Ind_YawRate - The column in OL_Filename that contains the nacelle yaw rate rad/s +0 ! Ind_CableControl - The column(s) in OL_Filename that contains the cable control inputs in m [Used with CC_Mode = 2, must be the same size as CC_Group_N] +0 ! Ind_StructControl - The column(s) in OL_Filename that contains the structural control inputs [Used with StC_Mode = 2, must be the same size as StC_Group_N] !------- Pitch Actuator Model ----------------------------------------------------- 3.140000000000 ! PA_CornerFreq - Pitch actuator bandwidth/cut-off frequency [rad/s] diff --git a/Test_Cases/NREL_2p8_127/NREL-2p8-127_DISCON.IN b/Test_Cases/NREL_2p8_127/NREL-2p8-127_DISCON.IN index 60215d61..5b86e5ea 100644 --- a/Test_Cases/NREL_2p8_127/NREL-2p8-127_DISCON.IN +++ b/Test_Cases/NREL_2p8_127/NREL-2p8-127_DISCON.IN @@ -1,14 +1,14 @@ ! Controller parameter input file for the NREL-2p8-127 wind turbine -! - File written using ROSCO version 2.7.0 controller tuning logic on 03/30/23 +! - File written using ROSCO version 2.7.0 controller tuning logic on 04/10/23 !------- DEBUG ------------------------------------------------------------ -1 ! LoggingLevel - (0: write no debug files, 1: write standard output .dbg-file, 2: LoggingLevel 1 + ROSCO LocalVars (.dbg2) 3: LoggingLevel 2 + complete avrSWAP-array (.dbg3)) +2 ! LoggingLevel - (0: write no debug files, 1: write standard output .dbg-file, 2: LoggingLevel 1 + ROSCO LocalVars (.dbg2) 3: LoggingLevel 2 + complete avrSWAP-array (.dbg3)) 0 ! Echo - (0 - no Echo, 1 - Echo input data to .echo) !------- 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 and/or tower fore-aft motion (for floating) {0: disable, 1: generator speed, 2: tower-top fore-aft motion, 3: generator speed and tower-top fore-aft motion} -0 ! IPC_ControlMode - Turn Individual Pitch Control (IPC) for fatigue load reductions (pitch contribution) {0: off, 1: 1P reductions, 2: 1P+2P reductions} +1 ! IPC_ControlMode - Turn Individual Pitch Control (IPC) for fatigue load reductions (pitch contribution) {0: off, 1: 1P reductions, 2: 1P+2P reductions} 3 ! VS_ControlMode - Generator torque control mode in above rated conditions {0: constant torque, 1: constant power, 2: TSR tracking PI control with constant torque, 3: TSR tracking PI control with constant power} 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} @@ -25,8 +25,8 @@ 0 ! AWC_Mode - Active wake control {0 - not used, 1 - complex number method, 2 - Coleman transform method} 0 ! Ext_Mode - External control mode {0 - not used, 1 - call external dynamic library} 0 ! ZMQ_Mode - Fuse ZeroMQ interface {0: unused, 1: Yaw Control} -0 ! CC_Mode - Cable control mode [0- unused, 1- User defined, 2- Position control (not yet implemented)] -0 ! StC_Mode - Structural control mode [0- unused, 1- User defined] +0 ! CC_Mode - Cable control mode [0- unused, 1- User defined, 2- Open loop control] +0 ! StC_Mode - Structural control mode [0- unused, 1- User defined, 2- Open loop control] !------- FILTERS ---------------------------------------------------------- 2.07080 ! F_LPFCornerFreq - Corner frequency (-3dB point) in the low-pass filters, [rad/s] @@ -60,7 +60,7 @@ 2 ! IPC_SatMode - IPC Saturation method (0 - no saturation (except by PC_MinPit), 1 - saturate by PS_BldPitchMin, 2 - saturate sotfly (full IPC cycle) by PC_MinPit, 3 - saturate softly by PS_BldPitchMin) 0.3 ! IPC_IntSat - Integrator saturation (maximum signal amplitude contribution to pitch from IPC), [rad] 0.000e+00 0.000e+00 ! IPC_KP - Proportional gain for the individual pitch controller: first parameter for 1P reductions, second for 2P reductions, [-] -0.000e+00 0.000e+00 ! IPC_KI - Integral gain for the individual pitch controller: first parameter for 1P reductions, second for 2P reductions, [-] +5.200e-09 0.000e+00 ! IPC_KI - Integral gain for the individual pitch controller: first parameter for 1P reductions, second for 2P reductions, [-] 0.000000 0.000000 ! 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] @@ -135,7 +135,9 @@ 0 ! Ind_Breakpoint - The column in OL_Filename that contains the breakpoint (time if OL_Mode = 1) 0 ! Ind_BldPitch - The column in OL_Filename that contains the blade pitch input in rad 0 ! Ind_GenTq - The column in OL_Filename that contains the generator torque in Nm -0 ! Ind_YawRate - The column in OL_Filename that contains the generator torque in Nm +0 ! Ind_YawRate - The column in OL_Filename that contains the nacelle yaw rate rad/s +0 ! Ind_CableControl - The column(s) in OL_Filename that contains the cable control inputs in m [Used with CC_Mode = 2, must be the same size as CC_Group_N] +0 ! Ind_StructControl - The column(s) in OL_Filename that contains the structural control inputs [Used with StC_Mode = 2, must be the same size as StC_Group_N] !------- Pitch Actuator Model ----------------------------------------------------- 3.140000000000 ! PA_CornerFreq - Pitch actuator bandwidth/cut-off frequency [rad/s] diff --git a/docs/source/api_change.rst b/docs/source/api_change.rst index 0dc00253..a804857b 100644 --- a/docs/source/api_change.rst +++ b/docs/source/api_change.rst @@ -25,26 +25,28 @@ New in ROSCO develop Line Input Name Example Value ====== ================= ====================================================================================================================================================================================================== 6 Echo 0 ! Echo - (0 - no Echo, 1 - Echo input data to .echo) -24 CC_Mode 0 ! CC_Mode - Cable control mode [0- unused, 1- User defined, 2- Position control (not yet implemented)] -25 AWC_Mode 0 ! AWC_Mode - Active wake control mode [0 - not used, 1 - complex number method, 2 - Coleman transform method] -29 StC_Mode 0 ! StC_Mode - Structural control mode [0- unused, 1- User defined] -146 Empty Line -147 AWC_Section !------- Active Wake Control ----------------------------------------------------- -148 AWC_NumModes 1 ! AWC_NumModes - AWC- Number of modes to include [-] -149 AWC_n 1 ! AWC_n - AWC azimuthal mode [-] (only used in complex number method) -150 AWC_harmonic 1 ! AWC_harmonic - AWC Coleman transform harmonic [-] (only used in Coleman transform method) -151 AWC_NumModes 0.03 ! AWC_freq - AWC frequency [Hz] -152 AWC_NumModes 2.0 ! AWC_amp - AWC amplitude [deg] -153 AWC_NumModes 0.0 ! AWC_clockangle - AWC clock angle [deg] -163 Empty Line -164 CC_Section !------- Cable Control --------------------------------------------------------- -165 CC_Group_N 3 ! CC_Group_N - Number of cable control groups -166 CC_GroupIndex 2601 2603 2605 ! CC_GroupIndex - First index for cable control group, should correspond to deltaL -167 CC_ActTau 20.000000 ! CC_ActTau - Time constant for line actuator [s] -168 Empty Line -169 StC_Section !------- Structural Controllers --------------------------------------------------------- -170 StC_Group_N 3 ! StC_Group_N - Number of cable control groups -171 StC_GroupIndex 2818 2838 2858 ! StC_GroupIndex - First index for structural control group, options specified in ServoDyn summary output +25 AWC_Mode 0 ! AWC_Mode - Active wake control mode [0 - not used, 1 - complex number method, 2 - Coleman transform method] +28 CC_Mode 0 ! CC_Mode - Cable control mode [0- unused, 1- User defined, 2- Open loop control] +29 StC_Mode 0 ! StC_Mode - Structural control mode [0- unused, 1- User defined, 2- Open loop control] +139 Ind_CableControl 0 ! Ind_CableControl - The column(s) in OL_Filename that contains the cable control inputs in m [Used with CC_Mode = 2, must be the same size as CC_Group_N] +140 Ind_StructControl 0 ! Ind_StructControl - The column(s) in OL_Filename that contains the structural control inputs [Used with StC_Mode = 2, must be the same size as StC_Group_N] +148 Empty Line +149 AWC_Section !------- Active Wake Control ----------------------------------------------------- +150 AWC_NumModes 1 ! AWC_NumModes - AWC- Number of modes to include [-] +151 AWC_n 1 ! AWC_n - AWC azimuthal mode [-] (only used in complex number method) +152 AWC_harmonic 1 ! AWC_harmonic - AWC Coleman transform harmonic [-] (only used in Coleman transform method) +153 AWC_freq 0.03 ! AWC_freq - AWC frequency [Hz] +154 AWC_amp 2.0 ! AWC_amp - AWC amplitude [deg] +155 AWC_clockangle 0.0 ! AWC_clockangle - AWC clock angle [deg] +165 Empty Line +166 CC_Section !------- Cable Control --------------------------------------------------------- +167 CC_Group_N 3 ! CC_Group_N - Number of cable control groups +168 CC_GroupIndex 2601 2603 2605 ! CC_GroupIndex - First index for cable control group, should correspond to deltaL +169 CC_ActTau 20.000000 ! CC_ActTau - Time constant for line actuator [s] +170 Empty Line +171 StC_Section !------- Structural Controllers --------------------------------------------------------- +172 StC_Group_N 3 ! StC_Group_N - Number of cable control groups +173 StC_GroupIndex 2818 2838 2858 ! StC_GroupIndex - First index for structural control group, options specified in ServoDyn summary output ====== ================= ====================================================================================================================================================================================================== From 339ad539172775d5ce0268ff00016008da549785 Mon Sep 17 00:00:00 2001 From: dzalkind Date: Mon, 10 Apr 2023 15:52:06 -0600 Subject: [PATCH 101/224] Tidy example output --- Examples/22_cable_control.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Examples/22_cable_control.py b/Examples/22_cable_control.py index 4965e135..467ed629 100644 --- a/Examples/22_cable_control.py +++ b/Examples/22_cable_control.py @@ -39,7 +39,7 @@ def main(): # Input yaml and output directory parameter_filename = os.path.join(rosco_dir,'Tune_Cases/IEA15MW_cable.yaml') - run_dir = os.path.join(example_out_dir,'22_cable_control_OL_1') + run_dir = os.path.join(example_out_dir,'22_cable_control') os.makedirs(run_dir,exist_ok=True) # Read initial input file From 79426f799ca385ff2b78ac57ddc855d0802d9dc8 Mon Sep 17 00:00:00 2001 From: dzalkind Date: Mon, 10 Apr 2023 15:52:34 -0600 Subject: [PATCH 102/224] Increment version number --- ROSCO/CMakeLists.txt | 2 +- ROSCO/src/Constants.f90 | 2 +- ROSCO/src/ROSCO_IO.f90 | 2 +- ROSCO/src/ROSCO_Types.f90 | 2 +- ROSCO_toolbox/__init__.py | 2 +- Test_Cases/BAR_10/BAR_10_DISCON.IN | 2 +- .../IEA-15-240-RWT-UMaineSemi/DISCON-UMaineSemi.IN | 2 +- Test_Cases/NREL-5MW/DISCON.IN | 2 +- Test_Cases/NREL_2p8_127/NREL-2p8-127_DISCON.IN | 2 +- docs/source/api_change.rst | 10 ++++++---- 10 files changed, 15 insertions(+), 13 deletions(-) diff --git a/ROSCO/CMakeLists.txt b/ROSCO/CMakeLists.txt index b69aa02d..b450a30f 100644 --- a/ROSCO/CMakeLists.txt +++ b/ROSCO/CMakeLists.txt @@ -1,5 +1,5 @@ cmake_minimum_required(VERSION 3.6) -project(ROSCO VERSION 2.7.0 LANGUAGES Fortran C) +project(ROSCO VERSION 2.8.0 LANGUAGES Fortran C) set(CMAKE_Fortran_MODULE_DIRECTORY "${CMAKE_BINARY_DIR}/ftnmods") diff --git a/ROSCO/src/Constants.f90 b/ROSCO/src/Constants.f90 index 7f519985..b85eefaa 100644 --- a/ROSCO/src/Constants.f90 +++ b/ROSCO/src/Constants.f90 @@ -14,7 +14,7 @@ MODULE Constants USE, INTRINSIC :: ISO_C_Binding - Character(*), PARAMETER :: rosco_version = 'v2.7.0' ! ROSCO version + Character(*), PARAMETER :: rosco_version = 'v2.8.0' ! ROSCO version INTEGER, PARAMETER :: DbKi = C_DOUBLE !< Default kind for double floating-point numbers INTEGER, PARAMETER :: ReKi = C_FLOAT !< Default kind for single floating-point numbers INTEGER, PARAMETER :: IntKi = C_INT !< Default kind for integer numbers diff --git a/ROSCO/src/ROSCO_IO.f90 b/ROSCO/src/ROSCO_IO.f90 index 5f53a1ce..fc05e7b1 100644 --- a/ROSCO/src/ROSCO_IO.f90 +++ b/ROSCO/src/ROSCO_IO.f90 @@ -1,5 +1,5 @@ ! ROSCO IO -! This file is automatically generated by write_registry.py using ROSCO v2.7.0 +! This file is automatically generated by write_registry.py using ROSCO v2.8.0 ! For any modification to the registry, please edit the rosco_types.yaml accordingly MODULE ROSCO_IO diff --git a/ROSCO/src/ROSCO_Types.f90 b/ROSCO/src/ROSCO_Types.f90 index 7aa6bfdf..ec19d6b8 100644 --- a/ROSCO/src/ROSCO_Types.f90 +++ b/ROSCO/src/ROSCO_Types.f90 @@ -1,5 +1,5 @@ ! ROSCO Registry -! This file is automatically generated by write_registry.py using ROSCO v2.7.0 +! This file is automatically generated by write_registry.py using ROSCO v2.8.0 ! For any modification to the registry, please edit the rosco_types.yaml accordingly MODULE ROSCO_Types diff --git a/ROSCO_toolbox/__init__.py b/ROSCO_toolbox/__init__.py index 092377ed..e200b2d2 100644 --- a/ROSCO_toolbox/__init__.py +++ b/ROSCO_toolbox/__init__.py @@ -3,4 +3,4 @@ __author__ = """Nikhar J. Abbas and Daniel S. Zalkind""" __email__ = 'daniel.zalkind@nrel.gov' -__version__ = '2.7.0' +__version__ = '2.8.0' diff --git a/Test_Cases/BAR_10/BAR_10_DISCON.IN b/Test_Cases/BAR_10/BAR_10_DISCON.IN index e1df6715..f750015d 100644 --- a/Test_Cases/BAR_10/BAR_10_DISCON.IN +++ b/Test_Cases/BAR_10/BAR_10_DISCON.IN @@ -1,5 +1,5 @@ ! Controller parameter input file for the BAR_10 wind turbine -! - File written using ROSCO version 2.7.0 controller tuning logic on 04/10/23 +! - File written using ROSCO version 2.8.0 controller tuning logic on 04/10/23 !------- DEBUG ------------------------------------------------------------ 1 ! LoggingLevel - (0: write no debug files, 1: write standard output .dbg-file, 2: LoggingLevel 1 + ROSCO LocalVars (.dbg2) 3: LoggingLevel 2 + complete avrSWAP-array (.dbg3)) diff --git a/Test_Cases/IEA-15-240-RWT-UMaineSemi/DISCON-UMaineSemi.IN b/Test_Cases/IEA-15-240-RWT-UMaineSemi/DISCON-UMaineSemi.IN index f35af5df..17c96a1e 100644 --- a/Test_Cases/IEA-15-240-RWT-UMaineSemi/DISCON-UMaineSemi.IN +++ b/Test_Cases/IEA-15-240-RWT-UMaineSemi/DISCON-UMaineSemi.IN @@ -1,5 +1,5 @@ ! Controller parameter input file for the IEA-15-240-RWT-UMaineSemi wind turbine -! - File written using ROSCO version 2.7.0 controller tuning logic on 04/10/23 +! - File written using ROSCO version 2.8.0 controller tuning logic on 04/10/23 !------- DEBUG ------------------------------------------------------------ 2 ! LoggingLevel - (0: write no debug files, 1: write standard output .dbg-file, 2: LoggingLevel 1 + ROSCO LocalVars (.dbg2) 3: LoggingLevel 2 + complete avrSWAP-array (.dbg3)) diff --git a/Test_Cases/NREL-5MW/DISCON.IN b/Test_Cases/NREL-5MW/DISCON.IN index f2c1d47d..0ddb6aa4 100644 --- a/Test_Cases/NREL-5MW/DISCON.IN +++ b/Test_Cases/NREL-5MW/DISCON.IN @@ -1,5 +1,5 @@ ! Controller parameter input file for the NREL-5MW wind turbine -! - File written using ROSCO version 2.7.0 controller tuning logic on 04/10/23 +! - File written using ROSCO version 2.8.0 controller tuning logic on 04/10/23 !------- DEBUG ------------------------------------------------------------ 1 ! LoggingLevel - (0: write no debug files, 1: write standard output .dbg-file, 2: LoggingLevel 1 + ROSCO LocalVars (.dbg2) 3: LoggingLevel 2 + complete avrSWAP-array (.dbg3)) diff --git a/Test_Cases/NREL_2p8_127/NREL-2p8-127_DISCON.IN b/Test_Cases/NREL_2p8_127/NREL-2p8-127_DISCON.IN index 5b86e5ea..ec720eb5 100644 --- a/Test_Cases/NREL_2p8_127/NREL-2p8-127_DISCON.IN +++ b/Test_Cases/NREL_2p8_127/NREL-2p8-127_DISCON.IN @@ -1,5 +1,5 @@ ! Controller parameter input file for the NREL-2p8-127 wind turbine -! - File written using ROSCO version 2.7.0 controller tuning logic on 04/10/23 +! - File written using ROSCO version 2.8.0 controller tuning logic on 04/10/23 !------- DEBUG ------------------------------------------------------------ 2 ! LoggingLevel - (0: write no debug files, 1: write standard output .dbg-file, 2: LoggingLevel 1 + ROSCO LocalVars (.dbg2) 3: LoggingLevel 2 + complete avrSWAP-array (.dbg3)) diff --git a/docs/source/api_change.rst b/docs/source/api_change.rst index a804857b..4fecc5a6 100644 --- a/docs/source/api_change.rst +++ b/docs/source/api_change.rst @@ -9,18 +9,20 @@ The changes are tabulated according to the line number, and flag name. The line number corresponds to the resulting line number after all changes are implemented. Thus, be sure to implement each in order so that subsequent line numbers are correct. -2.7.0 to develop +2.7.0 to 2.8.0 ------------------------------- Optional Inputs - ROSCO now reads in the whole input file and searches for keywords to set the inputs. Blank spaces and specific ordering are no longer required. - Input requirements depend on control modes. E.g., open loop inputs are not required if `OL_Mode = 0`` -IPC Saturation Modes -- Added options for saturating the IPC command with the peak shaving limit +Cable Control +- Can control OpenFAST cables (MoorDyn or SubDyn) using ROSCO +Structural Control +- Can control OpenFAST structural control elements (ServoDyn) using ROSCO Active wake control - Added Active Wake Control (AWC) implementation ====== ================= ====================================================================================================================================================================================================== -New in ROSCO develop +New in ROSCO 2.8.0 ---------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- Line Input Name Example Value ====== ================= ====================================================================================================================================================================================================== From 5fd97e254371554d1a3dee5ff544c96d50039260 Mon Sep 17 00:00:00 2001 From: dzalkind Date: Thu, 8 Jun 2023 15:51:59 -0600 Subject: [PATCH 103/224] Increment version number --- setup.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/setup.py b/setup.py index 3af0995a..f86cf03c 100644 --- a/setup.py +++ b/setup.py @@ -36,7 +36,7 @@ EMAIL = 'daniel.zalkind@nrel.gov' AUTHOR = 'NREL, National Wind Technology Center' REQUIRES_PYTHON = '>=3.8' -VERSION = '2.7.0' +VERSION = '2.8.0' # These packages are required for all of the code to be executed. # - Maybe you can get away with older versions... From e5b1af5383757f4ad1b98ab36a1e7093b51b8365 Mon Sep 17 00:00:00 2001 From: dzalkind <65573423+dzalkind@users.noreply.github.com> Date: Fri, 9 Jun 2023 14:31:18 -0600 Subject: [PATCH 104/224] Yaw Rate Bug Fix (#239) * Add back open loop yaw rate control * Check OL outputs in example * Update CI to use mamba, first attempt * Install extras when environment first set up * Remove potential libpython typo * Remove more potential typos * Use mamba in compile, too * Use environment.yml file * Remove conda installs from rosco-compile * Clean up CI scripts * Update mamba install in CI * Remove petsc and mpi * Revert CI back to conda --- Examples/14_open_loop_control.py | 16 ++++++++++++++++ ROSCO/src/Controllers.f90 | 8 ++++++++ 2 files changed, 24 insertions(+) diff --git a/Examples/14_open_loop_control.py b/Examples/14_open_loop_control.py index 7ca79462..cbc20f5d 100644 --- a/Examples/14_open_loop_control.py +++ b/Examples/14_open_loop_control.py @@ -145,6 +145,22 @@ fastout = op.load_fast_out(out_file, tmin=0) fig, ax = op.plot_fast_out(cases=cases,showplot=False) +# Check that open loop commands are close to control outputs from OpenFAST +fo = fastout[0] +tt = fo['Time'] +valid_ind = tt > 2 # first few timesteps can differ, depending on OpenFAST solve config + +# Computer errors +nacelle_yaw_diff = fo['NacYaw'][valid_ind] - np.degrees(np.interp(tt[valid_ind],olc.ol_timeseries['time'],olc.ol_timeseries['nacelle_yaw'])) +bld_pitch_diff = fo['BldPitch1'][valid_ind] - np.degrees(np.interp(tt[valid_ind],olc.ol_timeseries['time'],olc.ol_timeseries['blade_pitch'])) +gen_tq_diff = fo['GenTq'][valid_ind] - np.interp(tt[valid_ind],olc.ol_timeseries['time'],olc.ol_timeseries['generator_torque'])/1e3 + +# Check diff timeseries +np.testing.assert_allclose(nacelle_yaw_diff, 0, atol = 1e-1) # yaw has dynamics and integration error, tolerance higher +np.testing.assert_allclose(bld_pitch_diff, 0, atol = 1e-3) +np.testing.assert_allclose(gen_tq_diff, 0, atol = 1e-3) + + if False: plt.show() else: diff --git a/ROSCO/src/Controllers.f90 b/ROSCO/src/Controllers.f90 index 221dd16b..c8a73e35 100644 --- a/ROSCO/src/Controllers.f90 +++ b/ROSCO/src/Controllers.f90 @@ -371,6 +371,14 @@ SUBROUTINE YawRateControl(avrSWAP, CntrPar, LocalVar, objInst, zmqVar, DebugVar, ! Output yaw rate command in rad/s avrSWAP(48) = YawRateCom * D2R + ! If using open loop yaw rate control, overwrite controlled output + ! Open loop torque control + IF ((CntrPar%OL_Mode == 1) .AND. (CntrPar%Ind_YawRate > 0)) THEN + IF (LocalVar%Time >= CntrPar%OL_Breakpoints(1)) THEN + avrSWAP(48) = interp1d(CntrPar%OL_Breakpoints,CntrPar%OL_YawRate,LocalVar%Time, ErrVar) + ENDIF + ENDIF + ! Save for debug DebugVar%YawRateCom = YawRateCom DebugVar%NacHeadingTarget = NacHeadingTarget From c701f67767ebb53426c582d1e663ea2a7e1543eb Mon Sep 17 00:00:00 2001 From: dzalkind <65573423+dzalkind@users.noreply.github.com> Date: Mon, 10 Jul 2023 15:23:59 -0600 Subject: [PATCH 105/224] OpenFAST 3.5.0 (#246) * Add back open loop yaw rate control * Check OL outputs in example * Update CI to use mamba, first attempt * Install extras when environment first set up * Remove potential libpython typo * Remove more potential typos * Use mamba in compile, too * Use environment.yml file * Remove conda installs from rosco-compile * Clean up CI scripts * Update BAR_10_InflowFile.dat added VelInterpCubic and LiDAR Parameters to the InflowFile * Update IEA-15-240-RWT_InflowFile.dat added VelInterpCubic and LiDAR Parameters to the InflowFile * Update NRELOffshrBsline5MW_InflowWind.dat added VelInterpCubic and LiDAR Parameters to the InflowFile * Update BAR_10_InflowFile.dat added VelInterpCubic and LiDAR Parameters to the InflowFile * Update NREL-2p8-127_InflowFile.dat added VelInterpCubic and LiDAR Parameters to the InflowFile * Update NREL-2p8-127_InflowFile.dat added VelInterpCubic and LiDAR Parameters to the InflowFile * Update IEA-15-240-RWT_InflowFile.dat added VelInterpCubic and LiDAR Parameters to the InflowFile * Update NRELOffshrBsline5MW_InflowWind.dat added VelInterpCubic and LiDAR Parameters to the InflowFile * Update NREL-2p8-127_InflowFile.dat added VelInterpCubic and LiDAR Parameters to the InflowFile * Update StC-Force-Col1.dat adjusted comment on StC_DOF_MODE * Update StC-Force-Col2.dat adjusted comment on StC_DOF_MODE * Update StC-Force-Col3.dat adjusted comment on StC_DOF_MODE * Update FAST_reader.py added parsing of cubic interpolation for velocity and LIDAR parameters in read_InflowWind method for the InflowWind data file * Update FAST_writer.py added writing of cubic interpolation for velocity and LIDAR parameters in write_InflowWind method for the InflowWind data file * Update mamba install in CI * Remove petsc and mpi * Revert CI back to conda * Sync FAST_reader/writer with WEIS versions * Increment openfast version in CI * Add nodes to FAST_vars_out * Add nodes to vartree * Remove duplicated F_NotchType check * Sync FAST_vars_out more * Add MoorDyn outlist params to FstOutput * Remove numpy from DISCON_dict * Add open loop control of StCs * Remove numpy from read_DISCON * Add struct control example to CI * Remove openfast_exe used locally * Fix run_dir naming in 23_ example --------- Co-authored-by: Rudy <107142607+Yuksel-Rudy@users.noreply.github.com> --- .github/workflows/CI_rosco-pytools.yml | 4 +- Examples/23_structural_control.py | 54 +- Examples/test_examples.py | 1 + ROSCO/src/Controllers.f90 | 34 +- ROSCO/src/DISCON.F90 | 2 +- ROSCO/src/ReadSetParameters.f90 | 6 - ROSCO_toolbox/ofTools/fast_io/FAST_reader.py | 94 +- .../ofTools/fast_io/FAST_vars_out.py | 1576 ++++++++++++++++- ROSCO_toolbox/ofTools/fast_io/FAST_writer.py | 116 +- ROSCO_toolbox/utilities.py | 5 +- Test_Cases/BAR_10/BAR_10_InflowFile.dat | 14 + .../IEA-15-240-RWT_InflowFile.dat | 14 + .../StC-Force-Col1.dat | 4 +- .../StC-Force-Col2.dat | 4 +- .../StC-Force-Col3.dat | 4 +- .../NRELOffshrBsline5MW_InflowWind.dat | 14 + .../NREL_2p8_127/NREL-2p8-127_InflowFile.dat | 14 + 17 files changed, 1845 insertions(+), 115 deletions(-) diff --git a/.github/workflows/CI_rosco-pytools.yml b/.github/workflows/CI_rosco-pytools.yml index dbfe77ab..178bc730 100644 --- a/.github/workflows/CI_rosco-pytools.yml +++ b/.github/workflows/CI_rosco-pytools.yml @@ -129,7 +129,7 @@ jobs: # Install OpenFAST - name: Install OpenFAST run: | - conda install openfast==3.4 + conda install openfast==3.5 # Run examples - name: Run examples @@ -194,7 +194,7 @@ jobs: # Install OpenFAST - name: Install OpenFAST run: | - conda install openfast==3.4 + conda install openfast==3.5 # Run ROSCO Testing - name: Run ROSCO testing diff --git a/Examples/23_structural_control.py b/Examples/23_structural_control.py index 2a49b0f5..a10a406b 100644 --- a/Examples/23_structural_control.py +++ b/Examples/23_structural_control.py @@ -13,6 +13,8 @@ import numpy as np from ROSCO_toolbox.ofTools.fast_io.FAST_reader import InputReader_OpenFAST from ROSCO_toolbox.inputs.validation import load_rosco_yaml +from ROSCO_toolbox.controller import OpenLoopControl + ''' ROSCO currently supports user-defined hooks for structural control control actuation, if StC_Mode = 1. @@ -20,10 +22,10 @@ In the DISCON input, users must specify StC_GroupIndex relating to the control ChannelID. These indices can be found in the ServoDyn summary file (*SrvD.sum) -In the example below (and hard-coded in ROSCO) a step change of -4e5 N on the first structural controller -is applied at 50 sec. +In the example below, we implement a smooth step change mimicing the exchange of ballast from the +upwind column to the down wind columns -The develop branch (as of Mar 3, 2023) of OpenFAST (v3.5.0, upcoming) is required to run this example +OpenFAST v3.5.0 is required to run this example ''' @@ -65,6 +67,41 @@ def main(): for StC_file in reader.fst_vt['ServoDyn']['SStCfiles']: reader.fst_vt['SStC'].append(reader.read_StC(StC_file)) + # Set up open loop inputs to ROSCO + t_trans = 60 + t_sigma = 80 + t_max = 200 + + applied_force = [-2e6, 1e6, 1e6] + + olc = OpenLoopControl(t_max=t_max) + olc.interp_timeseries( + 'struct_control_1', + [0,t_trans,t_trans+t_sigma], + [0,0,applied_force[0]] , + 'sigma' + ) + + olc.interp_timeseries( + 'struct_control_2', + [0,t_trans,t_trans+t_sigma], + [0,0,applied_force[1]] , + 'sigma' + ) + + olc.interp_timeseries( + 'struct_control_3', + [0,t_trans,t_trans+t_sigma], + [0,0,applied_force[2]] , + 'sigma' + ) + + + ol_params = olc.write_input(os.path.join(run_dir,'open_loop_ballast.dat')) + + controller_params = {} + controller_params['open_loop'] = ol_params + controller_params['StC_Mode'] = 2 # simulation set up r = run_FAST_ROSCO() @@ -73,16 +110,15 @@ def main(): r.wind_case_fcn = cl.power_curve r.wind_case_opts = { 'U': [9], - 'T_max': 100, + 'TMax': t_max, } r.case_inputs = {} - r.fst_vt = reader.fst_vt - r.save_dir = run_dir - r.rosco_dir = rosco_dir - + r.fst_vt = reader.fst_vt + r.save_dir = run_dir + r.rosco_dir = rosco_dir + r.controller_params = controller_params r.run_FAST() - if __name__=="__main__": main() \ No newline at end of file diff --git a/Examples/test_examples.py b/Examples/test_examples.py index 0bd6840e..c23b0804 100644 --- a/Examples/test_examples.py +++ b/Examples/test_examples.py @@ -25,6 +25,7 @@ '20_active_wake_control', '21_optional_inputs', '22_cable_control', + '23_structural_control', 'update_rosco_discons', ] diff --git a/ROSCO/src/Controllers.f90 b/ROSCO/src/Controllers.f90 index c8a73e35..dde72431 100644 --- a/ROSCO/src/Controllers.f90 +++ b/ROSCO/src/Controllers.f90 @@ -697,6 +697,8 @@ SUBROUTINE CableControl(avrSWAP, CntrPar, LocalVar, objInst, ErrVar) ! Internal Variables Integer(IntKi) :: I_GROUP + CHARACTER(*), PARAMETER :: RoutineName = 'StructuralControl' + IF (CntrPar%CC_Mode == 1) THEN @@ -751,10 +753,15 @@ SUBROUTINE CableControl(avrSWAP, CntrPar, LocalVar, objInst, ErrVar) END DO + ! Add RoutineName to error message + IF (ErrVar%aviFAIL < 0) THEN + ErrVar%ErrMsg = RoutineName//':'//TRIM(ErrVar%ErrMsg) + ENDIF + END SUBROUTINE CableControl !------------------------------------------------------------------------------------------------------------------------------- -SUBROUTINE StructuralControl(avrSWAP, CntrPar, LocalVar, objInst) +SUBROUTINE StructuralControl(avrSWAP, CntrPar, LocalVar, objInst, ErrVar) ! Cable controller ! StC_Mode = 0, No cable control, this code not executed ! StC_Mode = 1, User-defined cable control @@ -762,20 +769,24 @@ SUBROUTINE StructuralControl(avrSWAP, CntrPar, LocalVar, objInst) ! ! Note that LocalVar%StC_Input() has a fixed max size of 12, which can be increased in rosco_types.yaml ! - USE ROSCO_Types, ONLY : ControlParameters, LocalVariables, ObjectInstances + USE ROSCO_Types, ONLY : ControlParameters, LocalVariables, ObjectInstances, ErrorVariables REAL(ReKi), INTENT(INOUT) :: avrSWAP(*) ! The swap array, used to pass data to, and receive data from, the DLL controller. TYPE(ControlParameters), INTENT(INOUT) :: CntrPar TYPE(LocalVariables), INTENT(INOUT) :: LocalVar TYPE(ObjectInstances), INTENT(INOUT) :: objInst + TYPE(ErrorVariables), INTENT(INOUT) :: ErrVar + ! Internal Variables Integer(IntKi) :: I_GROUP + CHARACTER(*), PARAMETER :: RoutineName = 'StructuralControl' + IF (CntrPar%StC_Mode == 1) THEN - ! User defined control + ! User defined control, step example IF (LocalVar%Time > 500) THEN ! Step change in input of -4500 N @@ -786,6 +797,18 @@ SUBROUTINE StructuralControl(avrSWAP, CntrPar, LocalVar, objInst) END IF + ELSEIF (CntrPar%StC_Mode == 2) THEN + + + DO I_GROUP = 1,CntrPar%StC_Group_N + IF (CntrPar%Ind_StructControl(I_GROUP) > 0) THEN + LocalVar%StC_Input(I_GROUP) = interp1d(CntrPar%OL_Breakpoints, & + CntrPar%OL_StructControl(I_GROUP,:), & + LocalVar%Time,ErrVar) + ENDIF + ENDDO + + END IF @@ -795,6 +818,11 @@ SUBROUTINE StructuralControl(avrSWAP, CntrPar, LocalVar, objInst) avrSWAP(CntrPar%StC_GroupIndex(I_GROUP)) = LocalVar%StC_Input(I_GROUP) END DO + ! Add RoutineName to error message + IF (ErrVar%aviFAIL < 0) THEN + ErrVar%ErrMsg = RoutineName//':'//TRIM(ErrVar%ErrMsg) + ENDIF + END SUBROUTINE StructuralControl !------------------------------------------------------------------------------------------------------------------------------- END MODULE Controllers diff --git a/ROSCO/src/DISCON.F90 b/ROSCO/src/DISCON.F90 index 3b0f7291..577cd530 100644 --- a/ROSCO/src/DISCON.F90 +++ b/ROSCO/src/DISCON.F90 @@ -124,7 +124,7 @@ SUBROUTINE DISCON(avrSWAP, aviFAIL, accINFILE, avcOUTNAME, avcMSG) BIND (C, NAME ! Structural control IF (CntrPar%StC_Mode > 0) THEN - CALL StructuralControl(avrSWAP,CntrPar,LocalVar, objInst) + CALL StructuralControl(avrSWAP,CntrPar,LocalVar, objInst, ErrVar) END IF IF ( CntrPar%LoggingLevel > 0 ) THEN diff --git a/ROSCO/src/ReadSetParameters.f90 b/ROSCO/src/ReadSetParameters.f90 index 23a5bde7..1b29ab0e 100644 --- a/ROSCO/src/ReadSetParameters.f90 +++ b/ROSCO/src/ReadSetParameters.f90 @@ -738,12 +738,6 @@ SUBROUTINE CheckInputs(LocalVar, CntrPar, avrSWAP, ErrVar, size_avcMSG) ErrVar%ErrMsg = 'F_NotchType must be 0, 1, 2, or 3.' ENDIF - ! F_NotchType - IF ((CntrPar%F_NotchType < 0) .OR. (CntrPar%F_NotchType > 2)) THEN - ErrVar%aviFAIL = -1 - ErrVar%ErrMsg = 'F_NotchType must be 0, 1, or 2.' - ENDIF - ! IPC_ControlMode IF ((CntrPar%IPC_ControlMode < 0) .OR. (CntrPar%IPC_ControlMode > 2)) THEN ErrVar%aviFAIL = -1 diff --git a/ROSCO_toolbox/ofTools/fast_io/FAST_reader.py b/ROSCO_toolbox/ofTools/fast_io/FAST_reader.py index fe4fc0b5..7b9130f6 100644 --- a/ROSCO_toolbox/ofTools/fast_io/FAST_reader.py +++ b/ROSCO_toolbox/ofTools/fast_io/FAST_reader.py @@ -409,6 +409,30 @@ def read_ElastoDyn(self, ed_file): self.set_outlist(self.fst_vt['outlist']['ElastoDyn'], channel_list) data = f.readline() + + # ElastoDyn optional outlist + try: + f.readline() + self.fst_vt['ElastoDyn']['BldNd_BladesOut'] = int(f.readline().split()[0]) + self.fst_vt['ElastoDyn']['BldNd_BlOutNd'] = f.readline().split()[0] + + f.readline() + data = f.readline() + while data.split()[0] != 'END': + if data.find('"')>=0: + channels = data.split('"') + opt_channel_list = channels[1].split(',') + else: + row_string = data.split(',') + if len(row_string)==1: + opt_channel_list = row_string[0].split('\n')[0] + else: + opt_channel_list = row_string + self.set_outlist(self.fst_vt['outlist']['ElastoDyn_Nodes'], opt_channel_list) + data = f.readline() + except: + # The optinal outlist does not exist. + None f.close() @@ -601,6 +625,30 @@ def read_BeamDyn(self, bd_file): channel_list = channels[1].split(',') self.set_outlist(self.fst_vt['outlist']['BeamDyn'], channel_list) data = f.readline() + + # BeamDyn optional outlist + try: + f.readline() + # self.fst_vt['BeamDyn']['BldNd_BladesOut'] = int(f.readline().split()[0]) + self.fst_vt['BeamDyn']['BldNd_BlOutNd'] = f.readline().split()[0] + + f.readline() + data = f.readline() + while data.split()[0] != 'END': + if data.find('"')>=0: + channels = data.split('"') + opt_channel_list = channels[1].split(',') + else: + row_string = data.split(',') + if len(row_string)==1: + opt_channel_list = row_string[0].split('\n')[0] + else: + opt_channel_list = row_string + self.set_outlist(self.fst_vt['outlist']['BeamDyn_Nodes'], opt_channel_list) + data = f.readline() + except: + # The optinal outlist does not exist. + None f.close() @@ -661,6 +709,7 @@ def read_InflowWind(self): self.fst_vt['InflowWind']['WindType'] = int(f.readline().split()[0]) self.fst_vt['InflowWind']['PropagationDir'] = float_read(f.readline().split()[0]) self.fst_vt['InflowWind']['VFlowAng'] = float_read(f.readline().split()[0]) + self.fst_vt['InflowWind']['VelInterpCubic'] = bool_read(f.readline().split()[0]) self.fst_vt['InflowWind']['NWindVel'] = int(f.readline().split()[0]) self.fst_vt['InflowWind']['WindVxiList'] = float_read(f.readline().split()[0]) self.fst_vt['InflowWind']['WindVyiList'] = float_read(f.readline().split()[0]) @@ -717,6 +766,21 @@ def read_InflowWind(self): self.fst_vt['InflowWind']['Z0'] = float_read(f.readline().split()[0]) self.fst_vt['InflowWind']['XOffset'] = float_read(f.readline().split()[0]) + # LIDAR parameters + f.readline() + self.fst_vt['InflowWind']['SensorType'] = int(f.readline().split()[0]) + self.fst_vt['InflowWind']['NumPulseGate'] = int(f.readline().split()[0]) + self.fst_vt['InflowWind']['PulseSpacing'] = float_read(f.readline().split()[0]) + self.fst_vt['InflowWind']['NumBeam'] = int(f.readline().split()[0]) + self.fst_vt['InflowWind']['FocalDistanceX'] = float_read(f.readline().split()[0]) + self.fst_vt['InflowWind']['FocalDistanceY'] = float_read(f.readline().split()[0]) + self.fst_vt['InflowWind']['FocalDistanceZ'] = float_read(f.readline().split()[0]) + self.fst_vt['InflowWind']['RotorApexOffsetPos'] = [idx.strip() for idx in f.readline().split('RotorApexOffsetPos')[0].split(',')] + self.fst_vt['InflowWind']['URefLid'] = float_read(f.readline().split()[0]) + self.fst_vt['InflowWind']['MeasurementInterval'] = float_read(f.readline().split()[0]) + self.fst_vt['InflowWind']['LidRadialVel'] = bool_read(f.readline().split()[0]) + self.fst_vt['InflowWind']['ConsiderHubMotion'] = int(f.readline().split()[0]) + # Inflow Wind Output Parameters (inflow_out_params) f.readline() self.fst_vt['InflowWind']['SumPrint'] = bool_read(f.readline().split()[0]) @@ -889,6 +953,30 @@ def read_AeroDyn15(self): self.set_outlist(self.fst_vt['outlist']['AeroDyn'], channel_list) data = f.readline() + # AeroDyn15 optional outlist + try: + f.readline() + self.fst_vt['AeroDyn15']['BldNd_BladesOut'] = int(f.readline().split()[0]) + self.fst_vt['AeroDyn15']['BldNd_BlOutNd'] = f.readline().split()[0] + + f.readline() + data = f.readline() + while data.split()[0] != 'END': + if data.find('"')>=0: + channels = data.split('"') + opt_channel_list = channels[1].split(',') + else: + row_string = data.split(',') + if len(row_string)==1: + opt_channel_list = row_string[0].split('\n')[0] + else: + opt_channel_list = row_string + self.set_outlist(self.fst_vt['outlist']['AeroDyn_Nodes'], opt_channel_list) + data = f.readline() + except: + # The optinal outlist does not exist. + None + f.close() self.read_AeroDyn15Blade() @@ -1082,11 +1170,11 @@ def read_AeroDyn15OLAF(self, olaf_filename): f.readline() self.fst_vt['AeroDyn15']['OLAF']['VelocityMethod'] = int_read(f.readline().split()[0]) self.fst_vt['AeroDyn15']['OLAF']['TreeBranchFactor']= float_read(f.readline().split()[0]) - self.fst_vt['AeroDyn15']['OLAF']['PartPerSegment'] = int(f.readline().split()[0]) + self.fst_vt['AeroDyn15']['OLAF']['PartPerSegment'] = int_read(f.readline().split()[0]) f.readline() f.readline() - self.fst_vt['AeroDyn15']['OLAF']['WrVTk'] = int(f.readline().split()[0]) - self.fst_vt['AeroDyn15']['OLAF']['nVTKBlades'] = int(f.readline().split()[0]) + self.fst_vt['AeroDyn15']['OLAF']['WrVTk'] = int_read(f.readline().split()[0]) + self.fst_vt['AeroDyn15']['OLAF']['nVTKBlades'] = int_read(f.readline().split()[0]) self.fst_vt['AeroDyn15']['OLAF']['VTKCoord'] = int_read(f.readline().split()[0]) self.fst_vt['AeroDyn15']['OLAF']['VTK_fps'] = float_read(f.readline().split()[0]) self.fst_vt['AeroDyn15']['OLAF']['nGridOut'] = int_read(f.readline().split()[0]) diff --git a/ROSCO_toolbox/ofTools/fast_io/FAST_vars_out.py b/ROSCO_toolbox/ofTools/fast_io/FAST_vars_out.py index 358af810..91d1b4b3 100644 --- a/ROSCO_toolbox/ofTools/fast_io/FAST_vars_out.py +++ b/ROSCO_toolbox/ofTools/fast_io/FAST_vars_out.py @@ -414,6 +414,12 @@ ElastoDyn['YawAccel'] = False # (deg/s^2); Nacelle yaw angular acceleration; About the zn- and zp-axes # Tower-Top / Yaw Bearing Motions +ElastoDyn['TwrTpTDxi'] = False # (m); Tower-top / yaw bearing fore-aft (translational) deflection (relative to the undeflected position) including all platform motions; Directed along the xi-axis +ElastoDyn['YawBrTDxi'] = False # (m); Tower-top / yaw bearing fore-aft (translational) deflection (relative to the undeflected position) including all platform motions; Directed along the xi-axis +ElastoDyn['TwrTpTDyi'] = False # (m); Tower-top / yaw bearing side-to-side (translational) deflection (relative to the undeflected position) including all platform motions; Directed along the yi-axis +ElastoDyn['YawBrTDyi'] = False # (m); Tower-top / yaw bearing side-to-side (translational) deflection (relative to the undeflected position) including all platform motions; Directed along the yi-axis +ElastoDyn['TwrTpTDzi'] = False # (m); Tower-top / yaw bearing axial (translational) deflection (relative to the undeflected position) including all platform motions; Directed along the zi-axis +ElastoDyn['YawBrTDzi'] = False # (m); Tower-top / yaw bearing axial (translational) deflection (relative to the undeflected position) including all platform motions; Directed along the zi-axis ElastoDyn['YawBrTDxp'] = False # (m); Tower-top / yaw bearing fore-aft (translational) deflection (relative to the undeflected position); Directed along the xp-axis ElastoDyn['YawBrTDyp'] = False # (m); Tower-top / yaw bearing side-to-side (translational) deflection (relative to the undeflected position); Directed along the yp-axis ElastoDyn['YawBrTDzp'] = False # (m); Tower-top / yaw bearing axial (translational) deflection (relative to the undeflected position); Directed along the zp-axis @@ -423,6 +429,9 @@ ElastoDyn['TTDspSS'] = False # (m); Tower-top / yaw bearing side-to-side (translation) deflection (relative to the undeflected position); Directed along the yt-axis ElastoDyn['YawBrTDzt'] = False # (m); Tower-top / yaw bearing axial (translational) deflection (relative to the undeflected position); Directed along the zt-axis ElastoDyn['TTDspAx'] = False # (m); Tower-top / yaw bearing axial (translational) deflection (relative to the undeflected position); Directed along the zt-axis +ElastoDyn['YawBrTVxp'] = False # (m/s); Tower-top / yaw bearing fore-aft (translational) velocity (absolute); Directed along the xp-axis +ElastoDyn['YawBrTVyp'] = False # (m/s); Tower-top / yaw bearing side-to-side (translational) velocity (absolute); Directed along the yp-axis +ElastoDyn['YawBrTVzp'] = False # (m/s); Tower-top / yaw bearing axial (translational) velocity (absolute); Directed along the zp-axis ElastoDyn['YawBrTAxp'] = False # (m/s^2); Tower-top / yaw bearing fore-aft (translational) acceleration (absolute); Directed along the xp-axis ElastoDyn['YawBrTAyp'] = False # (m/s^2); Tower-top / yaw bearing side-to-side (translational) acceleration (absolute); Directed along the yp-axis ElastoDyn['YawBrTAzp'] = False # (m/s^2); Tower-top / yaw bearing axial (translational) acceleration (absolute); Directed along the zp-axis @@ -1426,17 +1435,519 @@ ServoDyn['YawMomCom'] = False # (kN m); Nacelle yaw moment command; About the zn- and zp-axes ServoDyn['YawMom'] = False # (kN m); Nacelle yaw moment command; About the zn- and zp-axes -# Nacelle Tuned Mass Damper (TMD) -ServoDyn['NTMD_XQ'] = False # (m); Nacelle X TMD position (displacement); Relative to rest position -ServoDyn['NTMD_XQD'] = False # (m/s); Nacelle X TMD velocity; Relative to nacelle -ServoDyn['NTMD_YQ'] = False # (m); Nacelle Y TMD position (displacement); Relative to rest position -ServoDyn['NTMD_YQD'] = False # (m/s); Nacelle Y TMD velocity; Relative to nacelle +# Nacelle Structural Control (StC) +ServoDyn['NStC1_XQ'] = False # (m); Nacelle StC #1 -- X position (displacement); Relative to rest position in StC reference frame +ServoDyn['NStC1_XQD'] = False # (m/s); Nacelle StC #1 -- X velocity; Relative to nacelle in StC reference frame +ServoDyn['NStC1_YQ'] = False # (m); Nacelle StC #1 -- Y position (displacement); Relative to rest position in StC reference frame +ServoDyn['NStC1_YQD'] = False # (m/s); Nacelle StC #1 -- Y velocity; Relative to nacelle in StC reference frame +ServoDyn['NStC1_ZQ'] = False # (m); Nacelle StC #1 -- Z position (displacement); Relative to rest position in StC reference frame +ServoDyn['NStC1_ZQD'] = False # (m/s); Nacelle StC #1 -- Z velocity; Relative to nacelle in StC reference frame +ServoDyn['NStC1_Fxi'] = False # (kN); Nacelle StC #1 -- X resulting force; Inertial (global) coordinates +ServoDyn['NStC1_Fyi'] = False # (kN); Nacelle StC #1 -- Y resulting force; Inertial (global) coordinates +ServoDyn['NStC1_Fzi'] = False # (kN); Nacelle StC #1 -- Z resulting force; Inertial (global) coordinates +ServoDyn['NStC1_Mxi'] = False # (kN-m); Nacelle StC #1 -- X resulting moment; Inertial (global) coordinates +ServoDyn['NStC1_Myi'] = False # (kN-m); Nacelle StC #1 -- Y resulting moment; Inertial (global) coordinates +ServoDyn['NStC1_Mzi'] = False # (kN-m); Nacelle StC #1 -- Z resulting moment; Inertial (global) coordinates +ServoDyn['NStC1_Fxl'] = False # (kN); Nacelle StC #1 -- X resulting force; Local StC coordinates +ServoDyn['NStC1_Fyl'] = False # (kN); Nacelle StC #1 -- Y resulting force; Local StC coordinates +ServoDyn['NStC1_Fzl'] = False # (kN); Nacelle StC #1 -- Z resulting force; Local StC coordinates +ServoDyn['NStC1_Mxl'] = False # (kN-m); Nacelle StC #1 -- X resulting moment; Local StC coordinates +ServoDyn['NStC1_Myl'] = False # (kN-m); Nacelle StC #1 -- Y resulting moment; Local StC coordinates +ServoDyn['NStC1_Mzl'] = False # (kN-m); Nacelle StC #1 -- Z resulting moment; Local StC coordinates +ServoDyn['NStC2_XQ'] = False # (m); Nacelle StC #2 -- X position (displacement); Relative to rest position in StC reference frame +ServoDyn['NStC2_XQD'] = False # (m/s); Nacelle StC #2 -- X velocity; Relative to nacelle in StC reference frame +ServoDyn['NStC2_YQ'] = False # (m); Nacelle StC #2 -- Y position (displacement); Relative to rest position in StC reference frame +ServoDyn['NStC2_YQD'] = False # (m/s); Nacelle StC #2 -- Y velocity; Relative to nacelle in StC reference frame +ServoDyn['NStC2_ZQ'] = False # (m); Nacelle StC #2 -- Z position (displacement); Relative to rest position in StC reference frame +ServoDyn['NStC2_ZQD'] = False # (m/s); Nacelle StC #2 -- Z velocity; Relative to nacelle in StC reference frame +ServoDyn['NStC2_Fxi'] = False # (kN); Nacelle StC #2 -- X resulting force; Inertial (global) coordinates +ServoDyn['NStC2_Fyi'] = False # (kN); Nacelle StC #2 -- Y resulting force; Inertial (global) coordinates +ServoDyn['NStC2_Fzi'] = False # (kN); Nacelle StC #2 -- Z resulting force; Inertial (global) coordinates +ServoDyn['NStC2_Mxi'] = False # (kN-m); Nacelle StC #2 -- X resulting moment; Inertial (global) coordinates +ServoDyn['NStC2_Myi'] = False # (kN-m); Nacelle StC #2 -- Y resulting moment; Inertial (global) coordinates +ServoDyn['NStC2_Mzi'] = False # (kN-m); Nacelle StC #2 -- Z resulting moment; Inertial (global) coordinates +ServoDyn['NStC2_Fxl'] = False # (kN); Nacelle StC #2 -- X resulting force; Local StC coordinates +ServoDyn['NStC2_Fyl'] = False # (kN); Nacelle StC #2 -- Y resulting force; Local StC coordinates +ServoDyn['NStC2_Fzl'] = False # (kN); Nacelle StC #2 -- Z resulting force; Local StC coordinates +ServoDyn['NStC2_Mxl'] = False # (kN-m); Nacelle StC #2 -- X resulting moment; Local StC coordinates +ServoDyn['NStC2_Myl'] = False # (kN-m); Nacelle StC #2 -- Y resulting moment; Local StC coordinates +ServoDyn['NStC2_Mzl'] = False # (kN-m); Nacelle StC #2 -- Z resulting moment; Local StC coordinates +ServoDyn['NStC3_XQ'] = False # (m); Nacelle StC #3 -- X position (displacement); Relative to rest position in StC reference frame +ServoDyn['NStC3_XQD'] = False # (m/s); Nacelle StC #3 -- X velocity; Relative to nacelle in StC reference frame +ServoDyn['NStC3_YQ'] = False # (m); Nacelle StC #3 -- Y position (displacement); Relative to rest position in StC reference frame +ServoDyn['NStC3_YQD'] = False # (m/s); Nacelle StC #3 -- Y velocity; Relative to nacelle in StC reference frame +ServoDyn['NStC3_ZQ'] = False # (m); Nacelle StC #3 -- Z position (displacement); Relative to rest position in StC reference frame +ServoDyn['NStC3_ZQD'] = False # (m/s); Nacelle StC #3 -- Z velocity; Relative to nacelle in StC reference frame +ServoDyn['NStC3_Fxi'] = False # (kN); Nacelle StC #3 -- X resulting force; Inertial (global) coordinates +ServoDyn['NStC3_Fyi'] = False # (kN); Nacelle StC #3 -- Y resulting force; Inertial (global) coordinates +ServoDyn['NStC3_Fzi'] = False # (kN); Nacelle StC #3 -- Z resulting force; Inertial (global) coordinates +ServoDyn['NStC3_Mxi'] = False # (kN-m); Nacelle StC #3 -- X resulting moment; Inertial (global) coordinates +ServoDyn['NStC3_Myi'] = False # (kN-m); Nacelle StC #3 -- Y resulting moment; Inertial (global) coordinates +ServoDyn['NStC3_Mzi'] = False # (kN-m); Nacelle StC #3 -- Z resulting moment; Inertial (global) coordinates +ServoDyn['NStC3_Fxl'] = False # (kN); Nacelle StC #3 -- X resulting force; Local StC coordinates +ServoDyn['NStC3_Fyl'] = False # (kN); Nacelle StC #3 -- Y resulting force; Local StC coordinates +ServoDyn['NStC3_Fzl'] = False # (kN); Nacelle StC #3 -- Z resulting force; Local StC coordinates +ServoDyn['NStC3_Mxl'] = False # (kN-m); Nacelle StC #3 -- X resulting moment; Local StC coordinates +ServoDyn['NStC3_Myl'] = False # (kN-m); Nacelle StC #3 -- Y resulting moment; Local StC coordinates +ServoDyn['NStC3_Mzl'] = False # (kN-m); Nacelle StC #3 -- Z resulting moment; Local StC coordinates +ServoDyn['NStC4_XQ'] = False # (m); Nacelle StC #4 -- X position (displacement); Relative to rest position in StC reference frame +ServoDyn['NStC4_XQD'] = False # (m/s); Nacelle StC #4 -- X velocity; Relative to nacelle in StC reference frame +ServoDyn['NStC4_YQ'] = False # (m); Nacelle StC #4 -- Y position (displacement); Relative to rest position in StC reference frame +ServoDyn['NStC4_YQD'] = False # (m/s); Nacelle StC #4 -- Y velocity; Relative to nacelle in StC reference frame +ServoDyn['NStC4_ZQ'] = False # (m); Nacelle StC #4 -- Z position (displacement); Relative to rest position in StC reference frame +ServoDyn['NStC4_ZQD'] = False # (m/s); Nacelle StC #4 -- Z velocity; Relative to nacelle in StC reference frame +ServoDyn['NStC4_Fxi'] = False # (kN); Nacelle StC #4 -- X resulting force; Inertial (global) coordinates +ServoDyn['NStC4_Fyi'] = False # (kN); Nacelle StC #4 -- Y resulting force; Inertial (global) coordinates +ServoDyn['NStC4_Fzi'] = False # (kN); Nacelle StC #4 -- Z resulting force; Inertial (global) coordinates +ServoDyn['NStC4_Mxi'] = False # (kN-m); Nacelle StC #4 -- X resulting moment; Inertial (global) coordinates +ServoDyn['NStC4_Myi'] = False # (kN-m); Nacelle StC #4 -- Y resulting moment; Inertial (global) coordinates +ServoDyn['NStC4_Mzi'] = False # (kN-m); Nacelle StC #4 -- Z resulting moment; Inertial (global) coordinates +ServoDyn['NStC4_Fxl'] = False # (kN); Nacelle StC #4 -- X resulting force; Local StC coordinates +ServoDyn['NStC4_Fyl'] = False # (kN); Nacelle StC #4 -- Y resulting force; Local StC coordinates +ServoDyn['NStC4_Fzl'] = False # (kN); Nacelle StC #4 -- Z resulting force; Local StC coordinates +ServoDyn['NStC4_Mxl'] = False # (kN-m); Nacelle StC #4 -- X resulting moment; Local StC coordinates +ServoDyn['NStC4_Myl'] = False # (kN-m); Nacelle StC #4 -- Y resulting moment; Local StC coordinates +ServoDyn['NStC4_Mzl'] = False # (kN-m); Nacelle StC #4 -- Z resulting moment; Local StC coordinates + +# Tower Structural Control (StC) +ServoDyn['TStC1_XQ'] = False # (m); Tower StC #1 -- X position (displacement); Relative to rest position in StC reference frame +ServoDyn['TStC1_XQD'] = False # (m/s); Tower StC #1 -- X velocity; Relative to nacelle in StC reference frame +ServoDyn['TStC1_YQ'] = False # (m); Tower StC #1 -- Y position (displacement); Relative to rest position in StC reference frame +ServoDyn['TStC1_YQD'] = False # (m/s); Tower StC #1 -- Y velocity; Relative to nacelle in StC reference frame +ServoDyn['TStC1_ZQ'] = False # (m); Tower StC #1 -- Z position (displacement); Relative to rest position in StC reference frame +ServoDyn['TStC1_ZQD'] = False # (m/s); Tower StC #1 -- Z velocity; Relative to nacelle in StC reference frame +ServoDyn['TStC1_Fxi'] = False # (kN); Tower StC #1 -- X resulting force; Inertial (global) coordinates +ServoDyn['TStC1_Fyi'] = False # (kN); Tower StC #1 -- Y resulting force; Inertial (global) coordinates +ServoDyn['TStC1_Fzi'] = False # (kN); Tower StC #1 -- Z resulting force; Inertial (global) coordinates +ServoDyn['TStC1_Mxi'] = False # (kN-m); Tower StC #1 -- X resulting moment; Inertial (global) coordinates +ServoDyn['TStC1_Myi'] = False # (kN-m); Tower StC #1 -- Y resulting moment; Inertial (global) coordinates +ServoDyn['TStC1_Mzi'] = False # (kN-m); Tower StC #1 -- Z resulting moment; Inertial (global) coordinates +ServoDyn['TStC1_Fxl'] = False # (kN); Tower StC #1 -- X resulting force; Local StC coordinates +ServoDyn['TStC1_Fyl'] = False # (kN); Tower StC #1 -- Y resulting force; Local StC coordinates +ServoDyn['TStC1_Fzl'] = False # (kN); Tower StC #1 -- Z resulting force; Local StC coordinates +ServoDyn['TStC1_Mxl'] = False # (kN-m); Tower StC #1 -- X resulting moment; Local StC coordinates +ServoDyn['TStC1_Myl'] = False # (kN-m); Tower StC #1 -- Y resulting moment; Local StC coordinates +ServoDyn['TStC1_Mzl'] = False # (kN-m); Tower StC #1 -- Z resulting moment; Local StC coordinates +ServoDyn['TStC2_XQ'] = False # (m); Tower StC #2 -- X position (displacement); Relative to rest position in StC reference frame +ServoDyn['TStC2_XQD'] = False # (m/s); Tower StC #2 -- X velocity; Relative to nacelle in StC reference frame +ServoDyn['TStC2_YQ'] = False # (m); Tower StC #2 -- Y position (displacement); Relative to rest position in StC reference frame +ServoDyn['TStC2_YQD'] = False # (m/s); Tower StC #2 -- Y velocity; Relative to nacelle in StC reference frame +ServoDyn['TStC2_ZQ'] = False # (m); Tower StC #2 -- Z position (displacement); Relative to rest position in StC reference frame +ServoDyn['TStC2_ZQD'] = False # (m/s); Tower StC #2 -- Z velocity; Relative to nacelle in StC reference frame +ServoDyn['TStC2_Fxi'] = False # (kN); Tower StC #2 -- X resulting force; Inertial (global) coordinates +ServoDyn['TStC2_Fyi'] = False # (kN); Tower StC #2 -- Y resulting force; Inertial (global) coordinates +ServoDyn['TStC2_Fzi'] = False # (kN); Tower StC #2 -- Z resulting force; Inertial (global) coordinates +ServoDyn['TStC2_Mxi'] = False # (kN-m); Tower StC #2 -- X resulting moment; Inertial (global) coordinates +ServoDyn['TStC2_Myi'] = False # (kN-m); Tower StC #2 -- Y resulting moment; Inertial (global) coordinates +ServoDyn['TStC2_Mzi'] = False # (kN-m); Tower StC #2 -- Z resulting moment; Inertial (global) coordinates +ServoDyn['TStC2_Fxl'] = False # (kN); Tower StC #2 -- X resulting force; Local StC coordinates +ServoDyn['TStC2_Fyl'] = False # (kN); Tower StC #2 -- Y resulting force; Local StC coordinates +ServoDyn['TStC2_Fzl'] = False # (kN); Tower StC #2 -- Z resulting force; Local StC coordinates +ServoDyn['TStC2_Mxl'] = False # (kN-m); Tower StC #2 -- X resulting moment; Local StC coordinates +ServoDyn['TStC2_Myl'] = False # (kN-m); Tower StC #2 -- Y resulting moment; Local StC coordinates +ServoDyn['TStC2_Mzl'] = False # (kN-m); Tower StC #2 -- Z resulting moment; Local StC coordinates +ServoDyn['TStC3_XQ'] = False # (m); Tower StC #3 -- X position (displacement); Relative to rest position in StC reference frame +ServoDyn['TStC3_XQD'] = False # (m/s); Tower StC #3 -- X velocity; Relative to nacelle in StC reference frame +ServoDyn['TStC3_YQ'] = False # (m); Tower StC #3 -- Y position (displacement); Relative to rest position in StC reference frame +ServoDyn['TStC3_YQD'] = False # (m/s); Tower StC #3 -- Y velocity; Relative to nacelle in StC reference frame +ServoDyn['TStC3_ZQ'] = False # (m); Tower StC #3 -- Z position (displacement); Relative to rest position in StC reference frame +ServoDyn['TStC3_ZQD'] = False # (m/s); Tower StC #3 -- Z velocity; Relative to nacelle in StC reference frame +ServoDyn['TStC3_Fxi'] = False # (kN); Tower StC #3 -- X resulting force; Inertial (global) coordinates +ServoDyn['TStC3_Fyi'] = False # (kN); Tower StC #3 -- Y resulting force; Inertial (global) coordinates +ServoDyn['TStC3_Fzi'] = False # (kN); Tower StC #3 -- Z resulting force; Inertial (global) coordinates +ServoDyn['TStC3_Mxi'] = False # (kN-m); Tower StC #3 -- X resulting moment; Inertial (global) coordinates +ServoDyn['TStC3_Myi'] = False # (kN-m); Tower StC #3 -- Y resulting moment; Inertial (global) coordinates +ServoDyn['TStC3_Mzi'] = False # (kN-m); Tower StC #3 -- Z resulting moment; Inertial (global) coordinates +ServoDyn['TStC3_Fxl'] = False # (kN); Tower StC #3 -- X resulting force; Local StC coordinates +ServoDyn['TStC3_Fyl'] = False # (kN); Tower StC #3 -- Y resulting force; Local StC coordinates +ServoDyn['TStC3_Fzl'] = False # (kN); Tower StC #3 -- Z resulting force; Local StC coordinates +ServoDyn['TStC3_Mxl'] = False # (kN-m); Tower StC #3 -- X resulting moment; Local StC coordinates +ServoDyn['TStC3_Myl'] = False # (kN-m); Tower StC #3 -- Y resulting moment; Local StC coordinates +ServoDyn['TStC3_Mzl'] = False # (kN-m); Tower StC #3 -- Z resulting moment; Local StC coordinates +ServoDyn['TStC4_XQ'] = False # (m); Tower StC #4 -- X position (displacement); Relative to rest position in StC reference frame +ServoDyn['TStC4_XQD'] = False # (m/s); Tower StC #4 -- X velocity; Relative to nacelle in StC reference frame +ServoDyn['TStC4_YQ'] = False # (m); Tower StC #4 -- Y position (displacement); Relative to rest position in StC reference frame +ServoDyn['TStC4_YQD'] = False # (m/s); Tower StC #4 -- Y velocity; Relative to nacelle in StC reference frame +ServoDyn['TStC4_ZQ'] = False # (m); Tower StC #4 -- Z position (displacement); Relative to rest position in StC reference frame +ServoDyn['TStC4_ZQD'] = False # (m/s); Tower StC #4 -- Z velocity; Relative to nacelle in StC reference frame +ServoDyn['TStC4_Fxi'] = False # (kN); Tower StC #4 -- X resulting force; Inertial (global) coordinates +ServoDyn['TStC4_Fyi'] = False # (kN); Tower StC #4 -- Y resulting force; Inertial (global) coordinates +ServoDyn['TStC4_Fzi'] = False # (kN); Tower StC #4 -- Z resulting force; Inertial (global) coordinates +ServoDyn['TStC4_Mxi'] = False # (kN-m); Tower StC #4 -- X resulting moment; Inertial (global) coordinates +ServoDyn['TStC4_Myi'] = False # (kN-m); Tower StC #4 -- Y resulting moment; Inertial (global) coordinates +ServoDyn['TStC4_Mzi'] = False # (kN-m); Tower StC #4 -- Z resulting moment; Inertial (global) coordinates +ServoDyn['TStC4_Fxl'] = False # (kN); Tower StC #4 -- X resulting force; Local StC coordinates +ServoDyn['TStC4_Fyl'] = False # (kN); Tower StC #4 -- Y resulting force; Local StC coordinates +ServoDyn['TStC4_Fzl'] = False # (kN); Tower StC #4 -- Z resulting force; Local StC coordinates +ServoDyn['TStC4_Mxl'] = False # (kN-m); Tower StC #4 -- X resulting moment; Local StC coordinates +ServoDyn['TStC4_Myl'] = False # (kN-m); Tower StC #4 -- Y resulting moment; Local StC coordinates +ServoDyn['TStC4_Mzl'] = False # (kN-m); Tower StC #4 -- Z resulting moment; Local StC coordinates + +# Blade Structural Control (StC) +ServoDyn['BStC1_B1_XQ'] = False # (m); Blade StC #1 Blade #1 -- X position (displacement); Relative to rest position in StC reference frame +ServoDyn['BStC1_B1_XQD'] = False # (m/s); Blade StC #1 Blade #1 -- X velocity; Relative to nacelle in StC reference frame +ServoDyn['BStC1_B1_YQ'] = False # (m); Blade StC #1 Blade #1 -- Y position (displacement); Relative to rest position in StC reference frame +ServoDyn['BStC1_B1_YQD'] = False # (m/s); Blade StC #1 Blade #1 -- Y velocity; Relative to nacelle in StC reference frame +ServoDyn['BStC1_B1_ZQ'] = False # (m); Blade StC #1 Blade #1 -- Z position (displacement); Relative to rest position in StC reference frame +ServoDyn['BStC1_B1_ZQD'] = False # (m/s); Blade StC #1 Blade #1 -- Z velocity; Relative to nacelle in StC reference frame +ServoDyn['BStC1_B1_Fxi'] = False # (kN); Blade StC #1 Blade #1 -- X resulting force; Inertial (global) coordinates +ServoDyn['BStC1_B1_Fyi'] = False # (kN); Blade StC #1 Blade #1 -- Y resulting force; Inertial (global) coordinates +ServoDyn['BStC1_B1_Fzi'] = False # (kN); Blade StC #1 Blade #1 -- Z resulting force; Inertial (global) coordinates +ServoDyn['BStC1_B1_Mxi'] = False # (kN-m); Blade StC #1 Blade #1 -- X resulting moment; Inertial (global) coordinates +ServoDyn['BStC1_B1_Myi'] = False # (kN-m); Blade StC #1 Blade #1 -- Y resulting moment; Inertial (global) coordinates +ServoDyn['BStC1_B1_Mzi'] = False # (kN-m); Blade StC #1 Blade #1 -- Z resulting moment; Inertial (global) coordinates +ServoDyn['BStC1_B1_Fxl'] = False # (kN); Blade StC #1 Blade #1 -- X resulting force; Local StC coordinates +ServoDyn['BStC1_B1_Fyl'] = False # (kN); Blade StC #1 Blade #1 -- Y resulting force; Local StC coordinates +ServoDyn['BStC1_B1_Fzl'] = False # (kN); Blade StC #1 Blade #1 -- Z resulting force; Local StC coordinates +ServoDyn['BStC1_B1_Mxl'] = False # (kN-m); Blade StC #1 Blade #1 -- X resulting moment; Local StC coordinates +ServoDyn['BStC1_B1_Myl'] = False # (kN-m); Blade StC #1 Blade #1 -- Y resulting moment; Local StC coordinates +ServoDyn['BStC1_B1_Mzl'] = False # (kN-m); Blade StC #1 Blade #1 -- Z resulting moment; Local StC coordinates +ServoDyn['BStC2_B1_XQ'] = False # (m); Blade StC #2 Blade #1 -- X position (displacement); Relative to rest position in StC reference frame +ServoDyn['BStC2_B1_XQD'] = False # (m/s); Blade StC #2 Blade #1 -- X velocity; Relative to nacelle in StC reference frame +ServoDyn['BStC2_B1_YQ'] = False # (m); Blade StC #2 Blade #1 -- Y position (displacement); Relative to rest position in StC reference frame +ServoDyn['BStC2_B1_YQD'] = False # (m/s); Blade StC #2 Blade #1 -- Y velocity; Relative to nacelle in StC reference frame +ServoDyn['BStC2_B1_ZQ'] = False # (m); Blade StC #2 Blade #1 -- Z position (displacement); Relative to rest position in StC reference frame +ServoDyn['BStC2_B1_ZQD'] = False # (m/s); Blade StC #2 Blade #1 -- Z velocity; Relative to nacelle in StC reference frame +ServoDyn['BStC2_B1_Fxi'] = False # (kN); Blade StC #2 Blade #1 -- X resulting force; Inertial (global) coordinates +ServoDyn['BStC2_B1_Fyi'] = False # (kN); Blade StC #2 Blade #1 -- Y resulting force; Inertial (global) coordinates +ServoDyn['BStC2_B1_Fzi'] = False # (kN); Blade StC #2 Blade #1 -- Z resulting force; Inertial (global) coordinates +ServoDyn['BStC2_B1_Mxi'] = False # (kN-m); Blade StC #2 Blade #1 -- X resulting moment; Inertial (global) coordinates +ServoDyn['BStC2_B1_Myi'] = False # (kN-m); Blade StC #2 Blade #1 -- Y resulting moment; Inertial (global) coordinates +ServoDyn['BStC2_B1_Mzi'] = False # (kN-m); Blade StC #2 Blade #1 -- Z resulting moment; Inertial (global) coordinates +ServoDyn['BStC2_B1_Fxl'] = False # (kN); Blade StC #2 Blade #1 -- X resulting force; Local StC coordinates +ServoDyn['BStC2_B1_Fyl'] = False # (kN); Blade StC #2 Blade #1 -- Y resulting force; Local StC coordinates +ServoDyn['BStC2_B1_Fzl'] = False # (kN); Blade StC #2 Blade #1 -- Z resulting force; Local StC coordinates +ServoDyn['BStC2_B1_Mxl'] = False # (kN-m); Blade StC #2 Blade #1 -- X resulting moment; Local StC coordinates +ServoDyn['BStC2_B1_Myl'] = False # (kN-m); Blade StC #2 Blade #1 -- Y resulting moment; Local StC coordinates +ServoDyn['BStC2_B1_Mzl'] = False # (kN-m); Blade StC #2 Blade #1 -- Z resulting moment; Local StC coordinates +ServoDyn['BStC3_B1_XQ'] = False # (m); Blade StC #3 Blade #1 -- X position (displacement); Relative to rest position in StC reference frame +ServoDyn['BStC3_B1_XQD'] = False # (m/s); Blade StC #3 Blade #1 -- X velocity; Relative to nacelle in StC reference frame +ServoDyn['BStC3_B1_YQ'] = False # (m); Blade StC #3 Blade #1 -- Y position (displacement); Relative to rest position in StC reference frame +ServoDyn['BStC3_B1_YQD'] = False # (m/s); Blade StC #3 Blade #1 -- Y velocity; Relative to nacelle in StC reference frame +ServoDyn['BStC3_B1_ZQ'] = False # (m); Blade StC #3 Blade #1 -- Z position (displacement); Relative to rest position in StC reference frame +ServoDyn['BStC3_B1_ZQD'] = False # (m/s); Blade StC #3 Blade #1 -- Z velocity; Relative to nacelle in StC reference frame +ServoDyn['BStC3_B1_Fxi'] = False # (kN); Blade StC #3 Blade #1 -- X resulting force; Inertial (global) coordinates +ServoDyn['BStC3_B1_Fyi'] = False # (kN); Blade StC #3 Blade #1 -- Y resulting force; Inertial (global) coordinates +ServoDyn['BStC3_B1_Fzi'] = False # (kN); Blade StC #3 Blade #1 -- Z resulting force; Inertial (global) coordinates +ServoDyn['BStC3_B1_Mxi'] = False # (kN-m); Blade StC #3 Blade #1 -- X resulting moment; Inertial (global) coordinates +ServoDyn['BStC3_B1_Myi'] = False # (kN-m); Blade StC #3 Blade #1 -- Y resulting moment; Inertial (global) coordinates +ServoDyn['BStC3_B1_Mzi'] = False # (kN-m); Blade StC #3 Blade #1 -- Z resulting moment; Inertial (global) coordinates +ServoDyn['BStC3_B1_Fxl'] = False # (kN); Blade StC #3 Blade #1 -- X resulting force; Local StC coordinates +ServoDyn['BStC3_B1_Fyl'] = False # (kN); Blade StC #3 Blade #1 -- Y resulting force; Local StC coordinates +ServoDyn['BStC3_B1_Fzl'] = False # (kN); Blade StC #3 Blade #1 -- Z resulting force; Local StC coordinates +ServoDyn['BStC3_B1_Mxl'] = False # (kN-m); Blade StC #3 Blade #1 -- X resulting moment; Local StC coordinates +ServoDyn['BStC3_B1_Myl'] = False # (kN-m); Blade StC #3 Blade #1 -- Y resulting moment; Local StC coordinates +ServoDyn['BStC3_B1_Mzl'] = False # (kN-m); Blade StC #3 Blade #1 -- Z resulting moment; Local StC coordinates +ServoDyn['BStC4_B1_XQ'] = False # (m); Blade StC #4 Blade #1 -- X position (displacement); Relative to rest position in StC reference frame +ServoDyn['BStC4_B1_XQD'] = False # (m/s); Blade StC #4 Blade #1 -- X velocity; Relative to nacelle in StC reference frame +ServoDyn['BStC4_B1_YQ'] = False # (m); Blade StC #4 Blade #1 -- Y position (displacement); Relative to rest position in StC reference frame +ServoDyn['BStC4_B1_YQD'] = False # (m/s); Blade StC #4 Blade #1 -- Y velocity; Relative to nacelle in StC reference frame +ServoDyn['BStC4_B1_ZQ'] = False # (m); Blade StC #4 Blade #1 -- Z position (displacement); Relative to rest position in StC reference frame +ServoDyn['BStC4_B1_ZQD'] = False # (m/s); Blade StC #4 Blade #1 -- Z velocity; Relative to nacelle in StC reference frame +ServoDyn['BStC4_B1_Fxi'] = False # (kN); Blade StC #4 Blade #1 -- X resulting force; Inertial (global) coordinates +ServoDyn['BStC4_B1_Fyi'] = False # (kN); Blade StC #4 Blade #1 -- Y resulting force; Inertial (global) coordinates +ServoDyn['BStC4_B1_Fzi'] = False # (kN); Blade StC #4 Blade #1 -- Z resulting force; Inertial (global) coordinates +ServoDyn['BStC4_B1_Mxi'] = False # (kN-m); Blade StC #4 Blade #1 -- X resulting moment; Inertial (global) coordinates +ServoDyn['BStC4_B1_Myi'] = False # (kN-m); Blade StC #4 Blade #1 -- Y resulting moment; Inertial (global) coordinates +ServoDyn['BStC4_B1_Mzi'] = False # (kN-m); Blade StC #4 Blade #1 -- Z resulting moment; Inertial (global) coordinates +ServoDyn['BStC4_B1_Fxl'] = False # (kN); Blade StC #4 Blade #1 -- X resulting force; Local StC coordinates +ServoDyn['BStC4_B1_Fyl'] = False # (kN); Blade StC #4 Blade #1 -- Y resulting force; Local StC coordinates +ServoDyn['BStC4_B1_Fzl'] = False # (kN); Blade StC #4 Blade #1 -- Z resulting force; Local StC coordinates +ServoDyn['BStC4_B1_Mxl'] = False # (kN-m); Blade StC #4 Blade #1 -- X resulting moment; Local StC coordinates +ServoDyn['BStC4_B1_Myl'] = False # (kN-m); Blade StC #4 Blade #1 -- Y resulting moment; Local StC coordinates +ServoDyn['BStC4_B1_Mzl'] = False # (kN-m); Blade StC #4 Blade #1 -- Z resulting moment; Local StC coordinates +ServoDyn['BStC1_B2_XQ'] = False # (m); Blade StC #1 Blade #2 -- X position (displacement); Relative to rest position in StC reference frame +ServoDyn['BStC1_B2_XQD'] = False # (m/s); Blade StC #1 Blade #2 -- X velocity; Relative to nacelle in StC reference frame +ServoDyn['BStC1_B2_YQ'] = False # (m); Blade StC #1 Blade #2 -- Y position (displacement); Relative to rest position in StC reference frame +ServoDyn['BStC1_B2_YQD'] = False # (m/s); Blade StC #1 Blade #2 -- Y velocity; Relative to nacelle in StC reference frame +ServoDyn['BStC1_B2_ZQ'] = False # (m); Blade StC #1 Blade #2 -- Z position (displacement); Relative to rest position in StC reference frame +ServoDyn['BStC1_B2_ZQD'] = False # (m/s); Blade StC #1 Blade #2 -- Z velocity; Relative to nacelle in StC reference frame +ServoDyn['BStC1_B2_Fxi'] = False # (kN); Blade StC #1 Blade #2 -- X resulting force; Inertial (global) coordinates +ServoDyn['BStC1_B2_Fyi'] = False # (kN); Blade StC #1 Blade #2 -- Y resulting force; Inertial (global) coordinates +ServoDyn['BStC1_B2_Fzi'] = False # (kN); Blade StC #1 Blade #2 -- Z resulting force; Inertial (global) coordinates +ServoDyn['BStC1_B2_Mxi'] = False # (kN-m); Blade StC #1 Blade #2 -- X resulting moment; Inertial (global) coordinates +ServoDyn['BStC1_B2_Myi'] = False # (kN-m); Blade StC #1 Blade #2 -- Y resulting moment; Inertial (global) coordinates +ServoDyn['BStC1_B2_Mzi'] = False # (kN-m); Blade StC #1 Blade #2 -- Z resulting moment; Inertial (global) coordinates +ServoDyn['BStC1_B2_Fxl'] = False # (kN); Blade StC #1 Blade #2 -- X resulting force; Local StC coordinates +ServoDyn['BStC1_B2_Fyl'] = False # (kN); Blade StC #1 Blade #2 -- Y resulting force; Local StC coordinates +ServoDyn['BStC1_B2_Fzl'] = False # (kN); Blade StC #1 Blade #2 -- Z resulting force; Local StC coordinates +ServoDyn['BStC1_B2_Mxl'] = False # (kN-m); Blade StC #1 Blade #2 -- X resulting moment; Local StC coordinates +ServoDyn['BStC1_B2_Myl'] = False # (kN-m); Blade StC #1 Blade #2 -- Y resulting moment; Local StC coordinates +ServoDyn['BStC1_B2_Mzl'] = False # (kN-m); Blade StC #1 Blade #2 -- Z resulting moment; Local StC coordinates +ServoDyn['BStC2_B2_XQ'] = False # (m); Blade StC #2 Blade #2 -- X position (displacement); Relative to rest position in StC reference frame +ServoDyn['BStC2_B2_XQD'] = False # (m/s); Blade StC #2 Blade #2 -- X velocity; Relative to nacelle in StC reference frame +ServoDyn['BStC2_B2_YQ'] = False # (m); Blade StC #2 Blade #2 -- Y position (displacement); Relative to rest position in StC reference frame +ServoDyn['BStC2_B2_YQD'] = False # (m/s); Blade StC #2 Blade #2 -- Y velocity; Relative to nacelle in StC reference frame +ServoDyn['BStC2_B2_ZQ'] = False # (m); Blade StC #2 Blade #2 -- Z position (displacement); Relative to rest position in StC reference frame +ServoDyn['BStC2_B2_ZQD'] = False # (m/s); Blade StC #2 Blade #2 -- Z velocity; Relative to nacelle in StC reference frame +ServoDyn['BStC2_B2_Fxi'] = False # (kN); Blade StC #2 Blade #2 -- X resulting force; Inertial (global) coordinates +ServoDyn['BStC2_B2_Fyi'] = False # (kN); Blade StC #2 Blade #2 -- Y resulting force; Inertial (global) coordinates +ServoDyn['BStC2_B2_Fzi'] = False # (kN); Blade StC #2 Blade #2 -- Z resulting force; Inertial (global) coordinates +ServoDyn['BStC2_B2_Mxi'] = False # (kN-m); Blade StC #2 Blade #2 -- X resulting moment; Inertial (global) coordinates +ServoDyn['BStC2_B2_Myi'] = False # (kN-m); Blade StC #2 Blade #2 -- Y resulting moment; Inertial (global) coordinates +ServoDyn['BStC2_B2_Mzi'] = False # (kN-m); Blade StC #2 Blade #2 -- Z resulting moment; Inertial (global) coordinates +ServoDyn['BStC2_B2_Fxl'] = False # (kN); Blade StC #2 Blade #2 -- X resulting force; Local StC coordinates +ServoDyn['BStC2_B2_Fyl'] = False # (kN); Blade StC #2 Blade #2 -- Y resulting force; Local StC coordinates +ServoDyn['BStC2_B2_Fzl'] = False # (kN); Blade StC #2 Blade #2 -- Z resulting force; Local StC coordinates +ServoDyn['BStC2_B2_Mxl'] = False # (kN-m); Blade StC #2 Blade #2 -- X resulting moment; Local StC coordinates +ServoDyn['BStC2_B2_Myl'] = False # (kN-m); Blade StC #2 Blade #2 -- Y resulting moment; Local StC coordinates +ServoDyn['BStC2_B2_Mzl'] = False # (kN-m); Blade StC #2 Blade #2 -- Z resulting moment; Local StC coordinates +ServoDyn['BStC3_B2_XQ'] = False # (m); Blade StC #3 Blade #2 -- X position (displacement); Relative to rest position in StC reference frame +ServoDyn['BStC3_B2_XQD'] = False # (m/s); Blade StC #3 Blade #2 -- X velocity; Relative to nacelle in StC reference frame +ServoDyn['BStC3_B2_YQ'] = False # (m); Blade StC #3 Blade #2 -- Y position (displacement); Relative to rest position in StC reference frame +ServoDyn['BStC3_B2_YQD'] = False # (m/s); Blade StC #3 Blade #2 -- Y velocity; Relative to nacelle in StC reference frame +ServoDyn['BStC3_B2_ZQ'] = False # (m); Blade StC #3 Blade #2 -- Z position (displacement); Relative to rest position in StC reference frame +ServoDyn['BStC3_B2_ZQD'] = False # (m/s); Blade StC #3 Blade #2 -- Z velocity; Relative to nacelle in StC reference frame +ServoDyn['BStC3_B2_Fxi'] = False # (kN); Blade StC #3 Blade #2 -- X resulting force; Inertial (global) coordinates +ServoDyn['BStC3_B2_Fyi'] = False # (kN); Blade StC #3 Blade #2 -- Y resulting force; Inertial (global) coordinates +ServoDyn['BStC3_B2_Fzi'] = False # (kN); Blade StC #3 Blade #2 -- Z resulting force; Inertial (global) coordinates +ServoDyn['BStC3_B2_Mxi'] = False # (kN-m); Blade StC #3 Blade #2 -- X resulting moment; Inertial (global) coordinates +ServoDyn['BStC3_B2_Myi'] = False # (kN-m); Blade StC #3 Blade #2 -- Y resulting moment; Inertial (global) coordinates +ServoDyn['BStC3_B2_Mzi'] = False # (kN-m); Blade StC #3 Blade #2 -- Z resulting moment; Inertial (global) coordinates +ServoDyn['BStC3_B2_Fxl'] = False # (kN); Blade StC #3 Blade #2 -- X resulting force; Local StC coordinates +ServoDyn['BStC3_B2_Fyl'] = False # (kN); Blade StC #3 Blade #2 -- Y resulting force; Local StC coordinates +ServoDyn['BStC3_B2_Fzl'] = False # (kN); Blade StC #3 Blade #2 -- Z resulting force; Local StC coordinates +ServoDyn['BStC3_B2_Mxl'] = False # (kN-m); Blade StC #3 Blade #2 -- X resulting moment; Local StC coordinates +ServoDyn['BStC3_B2_Myl'] = False # (kN-m); Blade StC #3 Blade #2 -- Y resulting moment; Local StC coordinates +ServoDyn['BStC3_B2_Mzl'] = False # (kN-m); Blade StC #3 Blade #2 -- Z resulting moment; Local StC coordinates +ServoDyn['BStC4_B2_XQ'] = False # (m); Blade StC #4 Blade #2 -- X position (displacement); Relative to rest position in StC reference frame +ServoDyn['BStC4_B2_XQD'] = False # (m/s); Blade StC #4 Blade #2 -- X velocity; Relative to nacelle in StC reference frame +ServoDyn['BStC4_B2_YQ'] = False # (m); Blade StC #4 Blade #2 -- Y position (displacement); Relative to rest position in StC reference frame +ServoDyn['BStC4_B2_YQD'] = False # (m/s); Blade StC #4 Blade #2 -- Y velocity; Relative to nacelle in StC reference frame +ServoDyn['BStC4_B2_ZQ'] = False # (m); Blade StC #4 Blade #2 -- Z position (displacement); Relative to rest position in StC reference frame +ServoDyn['BStC4_B2_ZQD'] = False # (m/s); Blade StC #4 Blade #2 -- Z velocity; Relative to nacelle in StC reference frame +ServoDyn['BStC4_B2_Fxi'] = False # (kN); Blade StC #4 Blade #2 -- X resulting force; Inertial (global) coordinates +ServoDyn['BStC4_B2_Fyi'] = False # (kN); Blade StC #4 Blade #2 -- Y resulting force; Inertial (global) coordinates +ServoDyn['BStC4_B2_Fzi'] = False # (kN); Blade StC #4 Blade #2 -- Z resulting force; Inertial (global) coordinates +ServoDyn['BStC4_B2_Mxi'] = False # (kN-m); Blade StC #4 Blade #2 -- X resulting moment; Inertial (global) coordinates +ServoDyn['BStC4_B2_Myi'] = False # (kN-m); Blade StC #4 Blade #2 -- Y resulting moment; Inertial (global) coordinates +ServoDyn['BStC4_B2_Mzi'] = False # (kN-m); Blade StC #4 Blade #2 -- Z resulting moment; Inertial (global) coordinates +ServoDyn['BStC4_B2_Fxl'] = False # (kN); Blade StC #4 Blade #2 -- X resulting force; Local StC coordinates +ServoDyn['BStC4_B2_Fyl'] = False # (kN); Blade StC #4 Blade #2 -- Y resulting force; Local StC coordinates +ServoDyn['BStC4_B2_Fzl'] = False # (kN); Blade StC #4 Blade #2 -- Z resulting force; Local StC coordinates +ServoDyn['BStC4_B2_Mxl'] = False # (kN-m); Blade StC #4 Blade #2 -- X resulting moment; Local StC coordinates +ServoDyn['BStC4_B2_Myl'] = False # (kN-m); Blade StC #4 Blade #2 -- Y resulting moment; Local StC coordinates +ServoDyn['BStC4_B2_Mzl'] = False # (kN-m); Blade StC #4 Blade #2 -- Z resulting moment; Local StC coordinates +ServoDyn['BStC1_B3_XQ'] = False # (m); Blade StC #1 Blade #3 -- X position (displacement); Relative to rest position in StC reference frame +ServoDyn['BStC1_B3_XQD'] = False # (m/s); Blade StC #1 Blade #3 -- X velocity; Relative to nacelle in StC reference frame +ServoDyn['BStC1_B3_YQ'] = False # (m); Blade StC #1 Blade #3 -- Y position (displacement); Relative to rest position in StC reference frame +ServoDyn['BStC1_B3_YQD'] = False # (m/s); Blade StC #1 Blade #3 -- Y velocity; Relative to nacelle in StC reference frame +ServoDyn['BStC1_B3_ZQ'] = False # (m); Blade StC #1 Blade #3 -- Z position (displacement); Relative to rest position in StC reference frame +ServoDyn['BStC1_B3_ZQD'] = False # (m/s); Blade StC #1 Blade #3 -- Z velocity; Relative to nacelle in StC reference frame +ServoDyn['BStC1_B3_Fxi'] = False # (kN); Blade StC #1 Blade #3 -- X resulting force; Inertial (global) coordinates +ServoDyn['BStC1_B3_Fyi'] = False # (kN); Blade StC #1 Blade #3 -- Y resulting force; Inertial (global) coordinates +ServoDyn['BStC1_B3_Fzi'] = False # (kN); Blade StC #1 Blade #3 -- Z resulting force; Inertial (global) coordinates +ServoDyn['BStC1_B3_Mxi'] = False # (kN-m); Blade StC #1 Blade #3 -- X resulting moment; Inertial (global) coordinates +ServoDyn['BStC1_B3_Myi'] = False # (kN-m); Blade StC #1 Blade #3 -- Y resulting moment; Inertial (global) coordinates +ServoDyn['BStC1_B3_Mzi'] = False # (kN-m); Blade StC #1 Blade #3 -- Z resulting moment; Inertial (global) coordinates +ServoDyn['BStC1_B3_Fxl'] = False # (kN); Blade StC #1 Blade #3 -- X resulting force; Local StC coordinates +ServoDyn['BStC1_B3_Fyl'] = False # (kN); Blade StC #1 Blade #3 -- Y resulting force; Local StC coordinates +ServoDyn['BStC1_B3_Fzl'] = False # (kN); Blade StC #1 Blade #3 -- Z resulting force; Local StC coordinates +ServoDyn['BStC1_B3_Mxl'] = False # (kN-m); Blade StC #1 Blade #3 -- X resulting moment; Local StC coordinates +ServoDyn['BStC1_B3_Myl'] = False # (kN-m); Blade StC #1 Blade #3 -- Y resulting moment; Local StC coordinates +ServoDyn['BStC1_B3_Mzl'] = False # (kN-m); Blade StC #1 Blade #3 -- Z resulting moment; Local StC coordinates +ServoDyn['BStC2_B3_XQ'] = False # (m); Blade StC #2 Blade #3 -- X position (displacement); Relative to rest position in StC reference frame +ServoDyn['BStC2_B3_XQD'] = False # (m/s); Blade StC #2 Blade #3 -- X velocity; Relative to nacelle in StC reference frame +ServoDyn['BStC2_B3_YQ'] = False # (m); Blade StC #2 Blade #3 -- Y position (displacement); Relative to rest position in StC reference frame +ServoDyn['BStC2_B3_YQD'] = False # (m/s); Blade StC #2 Blade #3 -- Y velocity; Relative to nacelle in StC reference frame +ServoDyn['BStC2_B3_ZQ'] = False # (m); Blade StC #2 Blade #3 -- Z position (displacement); Relative to rest position in StC reference frame +ServoDyn['BStC2_B3_ZQD'] = False # (m/s); Blade StC #2 Blade #3 -- Z velocity; Relative to nacelle in StC reference frame +ServoDyn['BStC2_B3_Fxi'] = False # (kN); Blade StC #2 Blade #3 -- X resulting force; Inertial (global) coordinates +ServoDyn['BStC2_B3_Fyi'] = False # (kN); Blade StC #2 Blade #3 -- Y resulting force; Inertial (global) coordinates +ServoDyn['BStC2_B3_Fzi'] = False # (kN); Blade StC #2 Blade #3 -- Z resulting force; Inertial (global) coordinates +ServoDyn['BStC2_B3_Mxi'] = False # (kN-m); Blade StC #2 Blade #3 -- X resulting moment; Inertial (global) coordinates +ServoDyn['BStC2_B3_Myi'] = False # (kN-m); Blade StC #2 Blade #3 -- Y resulting moment; Inertial (global) coordinates +ServoDyn['BStC2_B3_Mzi'] = False # (kN-m); Blade StC #2 Blade #3 -- Z resulting moment; Inertial (global) coordinates +ServoDyn['BStC2_B3_Fxl'] = False # (kN); Blade StC #2 Blade #3 -- X resulting force; Local StC coordinates +ServoDyn['BStC2_B3_Fyl'] = False # (kN); Blade StC #2 Blade #3 -- Y resulting force; Local StC coordinates +ServoDyn['BStC2_B3_Fzl'] = False # (kN); Blade StC #2 Blade #3 -- Z resulting force; Local StC coordinates +ServoDyn['BStC2_B3_Mxl'] = False # (kN-m); Blade StC #2 Blade #3 -- X resulting moment; Local StC coordinates +ServoDyn['BStC2_B3_Myl'] = False # (kN-m); Blade StC #2 Blade #3 -- Y resulting moment; Local StC coordinates +ServoDyn['BStC2_B3_Mzl'] = False # (kN-m); Blade StC #2 Blade #3 -- Z resulting moment; Local StC coordinates +ServoDyn['BStC3_B3_XQ'] = False # (m); Blade StC #3 Blade #3 -- X position (displacement); Relative to rest position in StC reference frame +ServoDyn['BStC3_B3_XQD'] = False # (m/s); Blade StC #3 Blade #3 -- X velocity; Relative to nacelle in StC reference frame +ServoDyn['BStC3_B3_YQ'] = False # (m); Blade StC #3 Blade #3 -- Y position (displacement); Relative to rest position in StC reference frame +ServoDyn['BStC3_B3_YQD'] = False # (m/s); Blade StC #3 Blade #3 -- Y velocity; Relative to nacelle in StC reference frame +ServoDyn['BStC3_B3_ZQ'] = False # (m); Blade StC #3 Blade #3 -- Z position (displacement); Relative to rest position in StC reference frame +ServoDyn['BStC3_B3_ZQD'] = False # (m/s); Blade StC #3 Blade #3 -- Z velocity; Relative to nacelle in StC reference frame +ServoDyn['BStC3_B3_Fxi'] = False # (kN); Blade StC #3 Blade #3 -- X resulting force; Inertial (global) coordinates +ServoDyn['BStC3_B3_Fyi'] = False # (kN); Blade StC #3 Blade #3 -- Y resulting force; Inertial (global) coordinates +ServoDyn['BStC3_B3_Fzi'] = False # (kN); Blade StC #3 Blade #3 -- Z resulting force; Inertial (global) coordinates +ServoDyn['BStC3_B3_Mxi'] = False # (kN-m); Blade StC #3 Blade #3 -- X resulting moment; Inertial (global) coordinates +ServoDyn['BStC3_B3_Myi'] = False # (kN-m); Blade StC #3 Blade #3 -- Y resulting moment; Inertial (global) coordinates +ServoDyn['BStC3_B3_Mzi'] = False # (kN-m); Blade StC #3 Blade #3 -- Z resulting moment; Inertial (global) coordinates +ServoDyn['BStC3_B3_Fxl'] = False # (kN); Blade StC #3 Blade #3 -- X resulting force; Local StC coordinates +ServoDyn['BStC3_B3_Fyl'] = False # (kN); Blade StC #3 Blade #3 -- Y resulting force; Local StC coordinates +ServoDyn['BStC3_B3_Fzl'] = False # (kN); Blade StC #3 Blade #3 -- Z resulting force; Local StC coordinates +ServoDyn['BStC3_B3_Mxl'] = False # (kN-m); Blade StC #3 Blade #3 -- X resulting moment; Local StC coordinates +ServoDyn['BStC3_B3_Myl'] = False # (kN-m); Blade StC #3 Blade #3 -- Y resulting moment; Local StC coordinates +ServoDyn['BStC3_B3_Mzl'] = False # (kN-m); Blade StC #3 Blade #3 -- Z resulting moment; Local StC coordinates +ServoDyn['BStC4_B3_XQ'] = False # (m); Blade StC #4 Blade #3 -- X position (displacement); Relative to rest position in StC reference frame +ServoDyn['BStC4_B3_XQD'] = False # (m/s); Blade StC #4 Blade #3 -- X velocity; Relative to nacelle in StC reference frame +ServoDyn['BStC4_B3_YQ'] = False # (m); Blade StC #4 Blade #3 -- Y position (displacement); Relative to rest position in StC reference frame +ServoDyn['BStC4_B3_YQD'] = False # (m/s); Blade StC #4 Blade #3 -- Y velocity; Relative to nacelle in StC reference frame +ServoDyn['BStC4_B3_ZQ'] = False # (m); Blade StC #4 Blade #3 -- Z position (displacement); Relative to rest position in StC reference frame +ServoDyn['BStC4_B3_ZQD'] = False # (m/s); Blade StC #4 Blade #3 -- Z velocity; Relative to nacelle in StC reference frame +ServoDyn['BStC4_B3_Fxi'] = False # (kN); Blade StC #4 Blade #3 -- X resulting force; Inertial (global) coordinates +ServoDyn['BStC4_B3_Fyi'] = False # (kN); Blade StC #4 Blade #3 -- Y resulting force; Inertial (global) coordinates +ServoDyn['BStC4_B3_Fzi'] = False # (kN); Blade StC #4 Blade #3 -- Z resulting force; Inertial (global) coordinates +ServoDyn['BStC4_B3_Mxi'] = False # (kN-m); Blade StC #4 Blade #3 -- X resulting moment; Inertial (global) coordinates +ServoDyn['BStC4_B3_Myi'] = False # (kN-m); Blade StC #4 Blade #3 -- Y resulting moment; Inertial (global) coordinates +ServoDyn['BStC4_B3_Mzi'] = False # (kN-m); Blade StC #4 Blade #3 -- Z resulting moment; Inertial (global) coordinates +ServoDyn['BStC4_B3_Fxl'] = False # (kN); Blade StC #4 Blade #3 -- X resulting force; Local StC coordinates +ServoDyn['BStC4_B3_Fyl'] = False # (kN); Blade StC #4 Blade #3 -- Y resulting force; Local StC coordinates +ServoDyn['BStC4_B3_Fzl'] = False # (kN); Blade StC #4 Blade #3 -- Z resulting force; Local StC coordinates +ServoDyn['BStC4_B3_Mxl'] = False # (kN-m); Blade StC #4 Blade #3 -- X resulting moment; Local StC coordinates +ServoDyn['BStC4_B3_Myl'] = False # (kN-m); Blade StC #4 Blade #3 -- Y resulting moment; Local StC coordinates +ServoDyn['BStC4_B3_Mzl'] = False # (kN-m); Blade StC #4 Blade #3 -- Z resulting moment; Local StC coordinates +ServoDyn['BStC1_B4_XQ'] = False # (m); Blade StC #1 Blade #4 -- X position (displacement); Relative to rest position in StC reference frame +ServoDyn['BStC1_B4_XQD'] = False # (m/s); Blade StC #1 Blade #4 -- X velocity; Relative to nacelle in StC reference frame +ServoDyn['BStC1_B4_YQ'] = False # (m); Blade StC #1 Blade #4 -- Y position (displacement); Relative to rest position in StC reference frame +ServoDyn['BStC1_B4_YQD'] = False # (m/s); Blade StC #1 Blade #4 -- Y velocity; Relative to nacelle in StC reference frame +ServoDyn['BStC1_B4_ZQ'] = False # (m); Blade StC #1 Blade #4 -- Z position (displacement); Relative to rest position in StC reference frame +ServoDyn['BStC1_B4_ZQD'] = False # (m/s); Blade StC #1 Blade #4 -- Z velocity; Relative to nacelle in StC reference frame +ServoDyn['BStC1_B4_Fxi'] = False # (kN); Blade StC #1 Blade #4 -- X resulting force; Inertial (global) coordinates +ServoDyn['BStC1_B4_Fyi'] = False # (kN); Blade StC #1 Blade #4 -- Y resulting force; Inertial (global) coordinates +ServoDyn['BStC1_B4_Fzi'] = False # (kN); Blade StC #1 Blade #4 -- Z resulting force; Inertial (global) coordinates +ServoDyn['BStC1_B4_Mxi'] = False # (kN-m); Blade StC #1 Blade #4 -- X resulting moment; Inertial (global) coordinates +ServoDyn['BStC1_B4_Myi'] = False # (kN-m); Blade StC #1 Blade #4 -- Y resulting moment; Inertial (global) coordinates +ServoDyn['BStC1_B4_Mzi'] = False # (kN-m); Blade StC #1 Blade #4 -- Z resulting moment; Inertial (global) coordinates +ServoDyn['BStC1_B4_Fxl'] = False # (kN); Blade StC #1 Blade #4 -- X resulting force; Local StC coordinates +ServoDyn['BStC1_B4_Fyl'] = False # (kN); Blade StC #1 Blade #4 -- Y resulting force; Local StC coordinates +ServoDyn['BStC1_B4_Fzl'] = False # (kN); Blade StC #1 Blade #4 -- Z resulting force; Local StC coordinates +ServoDyn['BStC1_B4_Mxl'] = False # (kN-m); Blade StC #1 Blade #4 -- X resulting moment; Local StC coordinates +ServoDyn['BStC1_B4_Myl'] = False # (kN-m); Blade StC #1 Blade #4 -- Y resulting moment; Local StC coordinates +ServoDyn['BStC1_B4_Mzl'] = False # (kN-m); Blade StC #1 Blade #4 -- Z resulting moment; Local StC coordinates +ServoDyn['BStC2_B4_XQ'] = False # (m); Blade StC #2 Blade #4 -- X position (displacement); Relative to rest position in StC reference frame +ServoDyn['BStC2_B4_XQD'] = False # (m/s); Blade StC #2 Blade #4 -- X velocity; Relative to nacelle in StC reference frame +ServoDyn['BStC2_B4_YQ'] = False # (m); Blade StC #2 Blade #4 -- Y position (displacement); Relative to rest position in StC reference frame +ServoDyn['BStC2_B4_YQD'] = False # (m/s); Blade StC #2 Blade #4 -- Y velocity; Relative to nacelle in StC reference frame +ServoDyn['BStC2_B4_ZQ'] = False # (m); Blade StC #2 Blade #4 -- Z position (displacement); Relative to rest position in StC reference frame +ServoDyn['BStC2_B4_ZQD'] = False # (m/s); Blade StC #2 Blade #4 -- Z velocity; Relative to nacelle in StC reference frame +ServoDyn['BStC2_B4_Fxi'] = False # (kN); Blade StC #2 Blade #4 -- X resulting force; Inertial (global) coordinates +ServoDyn['BStC2_B4_Fyi'] = False # (kN); Blade StC #2 Blade #4 -- Y resulting force; Inertial (global) coordinates +ServoDyn['BStC2_B4_Fzi'] = False # (kN); Blade StC #2 Blade #4 -- Z resulting force; Inertial (global) coordinates +ServoDyn['BStC2_B4_Mxi'] = False # (kN-m); Blade StC #2 Blade #4 -- X resulting moment; Inertial (global) coordinates +ServoDyn['BStC2_B4_Myi'] = False # (kN-m); Blade StC #2 Blade #4 -- Y resulting moment; Inertial (global) coordinates +ServoDyn['BStC2_B4_Mzi'] = False # (kN-m); Blade StC #2 Blade #4 -- Z resulting moment; Inertial (global) coordinates +ServoDyn['BStC2_B4_Fxl'] = False # (kN); Blade StC #2 Blade #4 -- X resulting force; Local StC coordinates +ServoDyn['BStC2_B4_Fyl'] = False # (kN); Blade StC #2 Blade #4 -- Y resulting force; Local StC coordinates +ServoDyn['BStC2_B4_Fzl'] = False # (kN); Blade StC #2 Blade #4 -- Z resulting force; Local StC coordinates +ServoDyn['BStC2_B4_Mxl'] = False # (kN-m); Blade StC #2 Blade #4 -- X resulting moment; Local StC coordinates +ServoDyn['BStC2_B4_Myl'] = False # (kN-m); Blade StC #2 Blade #4 -- Y resulting moment; Local StC coordinates +ServoDyn['BStC2_B4_Mzl'] = False # (kN-m); Blade StC #2 Blade #4 -- Z resulting moment; Local StC coordinates +ServoDyn['BStC3_B4_XQ'] = False # (m); Blade StC #3 Blade #4 -- X position (displacement); Relative to rest position in StC reference frame +ServoDyn['BStC3_B4_XQD'] = False # (m/s); Blade StC #3 Blade #4 -- X velocity; Relative to nacelle in StC reference frame +ServoDyn['BStC3_B4_YQ'] = False # (m); Blade StC #3 Blade #4 -- Y position (displacement); Relative to rest position in StC reference frame +ServoDyn['BStC3_B4_YQD'] = False # (m/s); Blade StC #3 Blade #4 -- Y velocity; Relative to nacelle in StC reference frame +ServoDyn['BStC3_B4_ZQ'] = False # (m); Blade StC #3 Blade #4 -- Z position (displacement); Relative to rest position in StC reference frame +ServoDyn['BStC3_B4_ZQD'] = False # (m/s); Blade StC #3 Blade #4 -- Z velocity; Relative to nacelle in StC reference frame +ServoDyn['BStC3_B4_Fxi'] = False # (kN); Blade StC #3 Blade #4 -- X resulting force; Inertial (global) coordinates +ServoDyn['BStC3_B4_Fyi'] = False # (kN); Blade StC #3 Blade #4 -- Y resulting force; Inertial (global) coordinates +ServoDyn['BStC3_B4_Fzi'] = False # (kN); Blade StC #3 Blade #4 -- Z resulting force; Inertial (global) coordinates +ServoDyn['BStC3_B4_Mxi'] = False # (kN-m); Blade StC #3 Blade #4 -- X resulting moment; Inertial (global) coordinates +ServoDyn['BStC3_B4_Myi'] = False # (kN-m); Blade StC #3 Blade #4 -- Y resulting moment; Inertial (global) coordinates +ServoDyn['BStC3_B4_Mzi'] = False # (kN-m); Blade StC #3 Blade #4 -- Z resulting moment; Inertial (global) coordinates +ServoDyn['BStC3_B4_Fxl'] = False # (kN); Blade StC #3 Blade #4 -- X resulting force; Local StC coordinates +ServoDyn['BStC3_B4_Fyl'] = False # (kN); Blade StC #3 Blade #4 -- Y resulting force; Local StC coordinates +ServoDyn['BStC3_B4_Fzl'] = False # (kN); Blade StC #3 Blade #4 -- Z resulting force; Local StC coordinates +ServoDyn['BStC3_B4_Mxl'] = False # (kN-m); Blade StC #3 Blade #4 -- X resulting moment; Local StC coordinates +ServoDyn['BStC3_B4_Myl'] = False # (kN-m); Blade StC #3 Blade #4 -- Y resulting moment; Local StC coordinates +ServoDyn['BStC3_B4_Mzl'] = False # (kN-m); Blade StC #3 Blade #4 -- Z resulting moment; Local StC coordinates +ServoDyn['BStC4_B4_XQ'] = False # (m); Blade StC #4 Blade #4 -- X position (displacement); Relative to rest position in StC reference frame +ServoDyn['BStC4_B4_XQD'] = False # (m/s); Blade StC #4 Blade #4 -- X velocity; Relative to nacelle in StC reference frame +ServoDyn['BStC4_B4_YQ'] = False # (m); Blade StC #4 Blade #4 -- Y position (displacement); Relative to rest position in StC reference frame +ServoDyn['BStC4_B4_YQD'] = False # (m/s); Blade StC #4 Blade #4 -- Y velocity; Relative to nacelle in StC reference frame +ServoDyn['BStC4_B4_ZQ'] = False # (m); Blade StC #4 Blade #4 -- Z position (displacement); Relative to rest position in StC reference frame +ServoDyn['BStC4_B4_ZQD'] = False # (m/s); Blade StC #4 Blade #4 -- Z velocity; Relative to nacelle in StC reference frame +ServoDyn['BStC4_B4_Fxi'] = False # (kN); Blade StC #4 Blade #4 -- X resulting force; Inertial (global) coordinates +ServoDyn['BStC4_B4_Fyi'] = False # (kN); Blade StC #4 Blade #4 -- Y resulting force; Inertial (global) coordinates +ServoDyn['BStC4_B4_Fzi'] = False # (kN); Blade StC #4 Blade #4 -- Z resulting force; Inertial (global) coordinates +ServoDyn['BStC4_B4_Mxi'] = False # (kN-m); Blade StC #4 Blade #4 -- X resulting moment; Inertial (global) coordinates +ServoDyn['BStC4_B4_Myi'] = False # (kN-m); Blade StC #4 Blade #4 -- Y resulting moment; Inertial (global) coordinates +ServoDyn['BStC4_B4_Mzi'] = False # (kN-m); Blade StC #4 Blade #4 -- Z resulting moment; Inertial (global) coordinates +ServoDyn['BStC4_B4_Fxl'] = False # (kN); Blade StC #4 Blade #4 -- X resulting force; Local StC coordinates +ServoDyn['BStC4_B4_Fyl'] = False # (kN); Blade StC #4 Blade #4 -- Y resulting force; Local StC coordinates +ServoDyn['BStC4_B4_Fzl'] = False # (kN); Blade StC #4 Blade #4 -- Z resulting force; Local StC coordinates +ServoDyn['BStC4_B4_Mxl'] = False # (kN-m); Blade StC #4 Blade #4 -- X resulting moment; Local StC coordinates +ServoDyn['BStC4_B4_Myl'] = False # (kN-m); Blade StC #4 Blade #4 -- Y resulting moment; Local StC coordinates +ServoDyn['BStC4_B4_Mzl'] = False # (kN-m); Blade StC #4 Blade #4 -- Z resulting moment; Local StC coordinates + +# Substructure Structural Control (StC) +ServoDyn['SStC1_XQ'] = False # (m); Substructure StC #1 -- X position (displacement); Relative to rest position in StC reference frame +ServoDyn['SStC1_XQD'] = False # (m/s); Substructure StC #1 -- X velocity; Relative to nacelle in StC reference frame +ServoDyn['SStC1_YQ'] = False # (m); Substructure StC #1 -- Y position (displacement); Relative to rest position in StC reference frame +ServoDyn['SStC1_YQD'] = False # (m/s); Substructure StC #1 -- Y velocity; Relative to nacelle in StC reference frame +ServoDyn['SStC1_ZQ'] = False # (m); Substructure StC #1 -- Z position (displacement); Relative to rest position in StC reference frame +ServoDyn['SStC1_ZQD'] = False # (m/s); Substructure StC #1 -- Z velocity; Relative to nacelle in StC reference frame +ServoDyn['SStC1_Fxi'] = False # (kN); Substructure StC #1 -- X resulting force; Inertial (global) coordinates +ServoDyn['SStC1_Fyi'] = False # (kN); Substructure StC #1 -- Y resulting force; Inertial (global) coordinates +ServoDyn['SStC1_Fzi'] = False # (kN); Substructure StC #1 -- Z resulting force; Inertial (global) coordinates +ServoDyn['SStC1_Mxi'] = False # (kN-m); Substructure StC #1 -- X resulting moment; Inertial (global) coordinates +ServoDyn['SStC1_Myi'] = False # (kN-m); Substructure StC #1 -- Y resulting moment; Inertial (global) coordinates +ServoDyn['SStC1_Mzi'] = False # (kN-m); Substructure StC #1 -- Z resulting moment; Inertial (global) coordinates +ServoDyn['SStC1_Fxl'] = False # (kN); Substructure StC #1 -- X resulting force; Local StC coordinates +ServoDyn['SStC1_Fyl'] = False # (kN); Substructure StC #1 -- Y resulting force; Local StC coordinates +ServoDyn['SStC1_Fzl'] = False # (kN); Substructure StC #1 -- Z resulting force; Local StC coordinates +ServoDyn['SStC1_Mxl'] = False # (kN-m); Substructure StC #1 -- X resulting moment; Local StC coordinates +ServoDyn['SStC1_Myl'] = False # (kN-m); Substructure StC #1 -- Y resulting moment; Local StC coordinates +ServoDyn['SStC1_Mzl'] = False # (kN-m); Substructure StC #1 -- Z resulting moment; Local StC coordinates +ServoDyn['SStC2_XQ'] = False # (m); Substructure StC #2 -- X position (displacement); Relative to rest position in StC reference frame +ServoDyn['SStC2_XQD'] = False # (m/s); Substructure StC #2 -- X velocity; Relative to nacelle in StC reference frame +ServoDyn['SStC2_YQ'] = False # (m); Substructure StC #2 -- Y position (displacement); Relative to rest position in StC reference frame +ServoDyn['SStC2_YQD'] = False # (m/s); Substructure StC #2 -- Y velocity; Relative to nacelle in StC reference frame +ServoDyn['SStC2_ZQ'] = False # (m); Substructure StC #2 -- Z position (displacement); Relative to rest position in StC reference frame +ServoDyn['SStC2_ZQD'] = False # (m/s); Substructure StC #2 -- Z velocity; Relative to nacelle in StC reference frame +ServoDyn['SStC2_Fxi'] = False # (kN); Substructure StC #2 -- X resulting force; Inertial (global) coordinates +ServoDyn['SStC2_Fyi'] = False # (kN); Substructure StC #2 -- Y resulting force; Inertial (global) coordinates +ServoDyn['SStC2_Fzi'] = False # (kN); Substructure StC #2 -- Z resulting force; Inertial (global) coordinates +ServoDyn['SStC2_Mxi'] = False # (kN-m); Substructure StC #2 -- X resulting moment; Inertial (global) coordinates +ServoDyn['SStC2_Myi'] = False # (kN-m); Substructure StC #2 -- Y resulting moment; Inertial (global) coordinates +ServoDyn['SStC2_Mzi'] = False # (kN-m); Substructure StC #2 -- Z resulting moment; Inertial (global) coordinates +ServoDyn['SStC2_Fxl'] = False # (kN); Substructure StC #2 -- X resulting force; Local StC coordinates +ServoDyn['SStC2_Fyl'] = False # (kN); Substructure StC #2 -- Y resulting force; Local StC coordinates +ServoDyn['SStC2_Fzl'] = False # (kN); Substructure StC #2 -- Z resulting force; Local StC coordinates +ServoDyn['SStC2_Mxl'] = False # (kN-m); Substructure StC #2 -- X resulting moment; Local StC coordinates +ServoDyn['SStC2_Myl'] = False # (kN-m); Substructure StC #2 -- Y resulting moment; Local StC coordinates +ServoDyn['SStC2_Mzl'] = False # (kN-m); Substructure StC #2 -- Z resulting moment; Local StC coordinates +ServoDyn['SStC3_XQ'] = False # (m); Substructure StC #3 -- X position (displacement); Relative to rest position in StC reference frame +ServoDyn['SStC3_XQD'] = False # (m/s); Substructure StC #3 -- X velocity; Relative to nacelle in StC reference frame +ServoDyn['SStC3_YQ'] = False # (m); Substructure StC #3 -- Y position (displacement); Relative to rest position in StC reference frame +ServoDyn['SStC3_YQD'] = False # (m/s); Substructure StC #3 -- Y velocity; Relative to nacelle in StC reference frame +ServoDyn['SStC3_ZQ'] = False # (m); Substructure StC #3 -- Z position (displacement); Relative to rest position in StC reference frame +ServoDyn['SStC3_ZQD'] = False # (m/s); Substructure StC #3 -- Z velocity; Relative to nacelle in StC reference frame +ServoDyn['SStC3_Fxi'] = False # (kN); Substructure StC #3 -- X resulting force; Inertial (global) coordinates +ServoDyn['SStC3_Fyi'] = False # (kN); Substructure StC #3 -- Y resulting force; Inertial (global) coordinates +ServoDyn['SStC3_Fzi'] = False # (kN); Substructure StC #3 -- Z resulting force; Inertial (global) coordinates +ServoDyn['SStC3_Mxi'] = False # (kN-m); Substructure StC #3 -- X resulting moment; Inertial (global) coordinates +ServoDyn['SStC3_Myi'] = False # (kN-m); Substructure StC #3 -- Y resulting moment; Inertial (global) coordinates +ServoDyn['SStC3_Mzi'] = False # (kN-m); Substructure StC #3 -- Z resulting moment; Inertial (global) coordinates +ServoDyn['SStC3_Fxl'] = False # (kN); Substructure StC #3 -- X resulting force; Local StC coordinates +ServoDyn['SStC3_Fyl'] = False # (kN); Substructure StC #3 -- Y resulting force; Local StC coordinates +ServoDyn['SStC3_Fzl'] = False # (kN); Substructure StC #3 -- Z resulting force; Local StC coordinates +ServoDyn['SStC3_Mxl'] = False # (kN-m); Substructure StC #3 -- X resulting moment; Local StC coordinates +ServoDyn['SStC3_Myl'] = False # (kN-m); Substructure StC #3 -- Y resulting moment; Local StC coordinates +ServoDyn['SStC3_Mzl'] = False # (kN-m); Substructure StC #3 -- Z resulting moment; Local StC coordinates +ServoDyn['SStC4_XQ'] = False # (m); Substructure StC #4 -- X position (displacement); Relative to rest position in StC reference frame +ServoDyn['SStC4_XQD'] = False # (m/s); Substructure StC #4 -- X velocity; Relative to nacelle in StC reference frame +ServoDyn['SStC4_YQ'] = False # (m); Substructure StC #4 -- Y position (displacement); Relative to rest position in StC reference frame +ServoDyn['SStC4_YQD'] = False # (m/s); Substructure StC #4 -- Y velocity; Relative to nacelle in StC reference frame +ServoDyn['SStC4_ZQ'] = False # (m); Substructure StC #4 -- Z position (displacement); Relative to rest position in StC reference frame +ServoDyn['SStC4_ZQD'] = False # (m/s); Substructure StC #4 -- Z velocity; Relative to nacelle in StC reference frame +ServoDyn['SStC4_Fxi'] = False # (kN); Substructure StC #4 -- X resulting force; Inertial (global) coordinates +ServoDyn['SStC4_Fyi'] = False # (kN); Substructure StC #4 -- Y resulting force; Inertial (global) coordinates +ServoDyn['SStC4_Fzi'] = False # (kN); Substructure StC #4 -- Z resulting force; Inertial (global) coordinates +ServoDyn['SStC4_Mxi'] = False # (kN-m); Substructure StC #4 -- X resulting moment; Inertial (global) coordinates +ServoDyn['SStC4_Myi'] = False # (kN-m); Substructure StC #4 -- Y resulting moment; Inertial (global) coordinates +ServoDyn['SStC4_Mzi'] = False # (kN-m); Substructure StC #4 -- Z resulting moment; Inertial (global) coordinates +ServoDyn['SStC4_Fxl'] = False # (kN); Substructure StC #4 -- X resulting force; Local StC coordinates +ServoDyn['SStC4_Fyl'] = False # (kN); Substructure StC #4 -- Y resulting force; Local StC coordinates +ServoDyn['SStC4_Fzl'] = False # (kN); Substructure StC #4 -- Z resulting force; Local StC coordinates +ServoDyn['SStC4_Mxl'] = False # (kN-m); Substructure StC #4 -- X resulting moment; Local StC coordinates +ServoDyn['SStC4_Myl'] = False # (kN-m); Substructure StC #4 -- Y resulting moment; Local StC coordinates +ServoDyn['SStC4_Mzl'] = False # (kN-m); Substructure StC #4 -- Z resulting moment; Local StC coordinates + -# Tower Tuned Mass Damper (TMD) -ServoDyn['TTMD_XQ'] = False # (m); Tower X TMD position (displacement); Relative to rest position -ServoDyn['TTMD_XQD'] = False # (m/s); Tower X TMD velocity; Relative to tower -ServoDyn['TTMD_YQ'] = False # (m); Tower Y TMD position (displacement); Relative to rest position -ServoDyn['TTMD_YQD'] = False # (m/s); Tower Y TMD velocity; Relative to tower # Flap outputs ServoDyn['BLFLAP1'] = False # (m/s); Tower Y TMD velocity; Relative to tower @@ -1563,6 +2074,60 @@ AeroDyn['B1Pitch'] = False # (deg); Pitch angle of blade 1; AeroDyn['B2Pitch'] = False # (deg); Pitch angle of blade 2; AeroDyn['B3Pitch'] = False # (deg); Pitch angle of blade 3; +AeroDyn['B1AeroFx'] = False # (N); Total blade aerodynamic load for blade 1 (force in x-direction); blade root coordinate system +AeroDyn['B1AeroFy'] = False # (N); Total blade aerodynamic load for blade 1 (force in y-direction); blade root coordinate system +AeroDyn['B1AeroFz'] = False # (N); Total blade aerodynamic load for blade 1 (force in z-direction); blade root coordinate system +AeroDyn['B1AeroMx'] = False # (N-m); Total blade aerodynamic load for blade 1 (moment in x-direction); blade root coordinate system +AeroDyn['B1AeroMy'] = False # (N-m); Total blade aerodynamic load for blade 1 (moment in y-direction); blade root coordinate system +AeroDyn['B1AeroMz'] = False # (N-m); Total blade aerodynamic load for blade 1 (moment in z-direction); blade root coordinate system +AeroDyn['B1AeroPwr'] = False # (W); Total aerodynamic power from blade 1; +AeroDyn['B2AeroFx'] = False # (N); Total blade aerodynamic load for blade 2 (force in x-direction); blade root coordinate system +AeroDyn['B2AeroFy'] = False # (N); Total blade aerodynamic load for blade 2 (force in y-direction); blade root coordinate system +AeroDyn['B2AeroFz'] = False # (N); Total blade aerodynamic load for blade 2 (force in z-direction); blade root coordinate system +AeroDyn['B2AeroMx'] = False # (N-m); Total blade aerodynamic load for blade 2 (moment in x-direction); blade root coordinate system +AeroDyn['B2AeroMy'] = False # (N-m); Total blade aerodynamic load for blade 2 (moment in y-direction); blade root coordinate system +AeroDyn['B2AeroMz'] = False # (N-m); Total blade aerodynamic load for blade 2 (moment in z-direction); blade root coordinate system +AeroDyn['B2AeroPwr'] = False # (W); Total aerodynamic power from blade 2; +AeroDyn['B3AeroFx'] = False # (N); Total blade aerodynamic load for blade 3 (force in x-direction); blade root coordinate system +AeroDyn['B3AeroFy'] = False # (N); Total blade aerodynamic load for blade 3 (force in y-direction); blade root coordinate system +AeroDyn['B3AeroFz'] = False # (N); Total blade aerodynamic load for blade 3 (force in z-direction); blade root coordinate system +AeroDyn['B3AeroMx'] = False # (N-m); Total blade aerodynamic load for blade 3 (moment in x-direction); blade root coordinate system +AeroDyn['B3AeroMy'] = False # (N-m); Total blade aerodynamic load for blade 3 (moment in y-direction); blade root coordinate system +AeroDyn['B3AeroMz'] = False # (N-m); Total blade aerodynamic load for blade 3 (moment in z-direction); blade root coordinate system +AeroDyn['B3AeroPwr'] = False # (W); Total aerodynamic power from blade 3; +AeroDyn['B4AeroFx'] = False # (N); Total blade aerodynamic load for blade 4 (force in x-direction); blade root coordinate system +AeroDyn['B4AeroFy'] = False # (N); Total blade aerodynamic load for blade 4 (force in y-direction); blade root coordinate system +AeroDyn['B4AeroFz'] = False # (N); Total blade aerodynamic load for blade 4 (force in z-direction); blade root coordinate system +AeroDyn['B4AeroMx'] = False # (N-m); Total blade aerodynamic load for blade 4 (moment in x-direction); blade root coordinate system +AeroDyn['B4AeroMy'] = False # (N-m); Total blade aerodynamic load for blade 4 (moment in y-direction); blade root coordinate system +AeroDyn['B4AeroMz'] = False # (N-m); Total blade aerodynamic load for blade 4 (moment in z-direction); blade root coordinate system +AeroDyn['B4AeroPwr'] = False # (W); Total aerodynamic power from blade 4; +AeroDyn['B1AeroFxg'] = False # (N); Total blade aerodynamic load for blade 1 (force in x-direction); global coordinate system +AeroDyn['B1AeroFyg'] = False # (N); Total blade aerodynamic load for blade 1 (force in y-direction); global coordinate system +AeroDyn['B1AeroFzg'] = False # (N); Total blade aerodynamic load for blade 1 (force in z-direction); global coordinate system +AeroDyn['B1AeroMxg'] = False # (N-m); Total blade aerodynamic load for blade 1 (moment in x-direction); global coordinate system +AeroDyn['B1AeroMyg'] = False # (N-m); Total blade aerodynamic load for blade 1 (moment in y-direction); global coordinate system +AeroDyn['B1AeroMzg'] = False # (N-m); Total blade aerodynamic load for blade 1 (moment in z-direction); global coordinate system +AeroDyn['B2AeroFxg'] = False # (N); Total blade aerodynamic load for blade 2 (force in x-direction); global coordinate system +AeroDyn['B2AeroFyg'] = False # (N); Total blade aerodynamic load for blade 2 (force in y-direction); global coordinate system +AeroDyn['B2AeroFzg'] = False # (N); Total blade aerodynamic load for blade 2 (force in z-direction); global coordinate system +AeroDyn['B2AeroMxg'] = False # (N-m); Total blade aerodynamic load for blade 2 (moment in x-direction); global coordinate system +AeroDyn['B2AeroMyg'] = False # (N-m); Total blade aerodynamic load for blade 2 (moment in y-direction); global coordinate system +AeroDyn['B2AeroMzg'] = False # (N-m); Total blade aerodynamic load for blade 2 (moment in z-direction); global coordinate system +AeroDyn['B3AeroFxg'] = False # (N); Total blade aerodynamic load for blade 3 (force in x-direction); global coordinate system +AeroDyn['B3AeroFyg'] = False # (N); Total blade aerodynamic load for blade 3 (force in y-direction); global coordinate system +AeroDyn['B3AeroFzg'] = False # (N); Total blade aerodynamic load for blade 3 (force in z-direction); global coordinate system +AeroDyn['B3AeroMxg'] = False # (N-m); Total blade aerodynamic load for blade 3 (moment in x-direction); global coordinate system +AeroDyn['B3AeroMyg'] = False # (N-m); Total blade aerodynamic load for blade 3 (moment in y-direction); global coordinate system +AeroDyn['B3AeroMzg'] = False # (N-m); Total blade aerodynamic load for blade 3 (moment in z-direction); global coordinate system +AeroDyn['B4AeroFxg'] = False # (N); Total blade aerodynamic load for blade 4 (force in x-direction); global coordinate system +AeroDyn['B4AeroFyg'] = False # (N); Total blade aerodynamic load for blade 4 (force in y-direction); global coordinate system +AeroDyn['B4AeroFzg'] = False # (N); Total blade aerodynamic load for blade 4 (force in z-direction); global coordinate system +AeroDyn['B4AeroMxg'] = False # (N-m); Total blade aerodynamic load for blade 4 (moment in x-direction); global coordinate system +AeroDyn['B4AeroMyg'] = False # (N-m); Total blade aerodynamic load for blade 4 (moment in y-direction); global coordinate system +AeroDyn['B4AeroMzg'] = False # (N-m); Total blade aerodynamic load for blade 4 (moment in z-direction); global coordinate system + +# Blade Nodal outputs AeroDyn['B1N1VUndx'] = False # (m/s); x-component of undisturbed wind velocity at Blade 1, Node 1; local blade coordinate system AeroDyn['B1N2VUndx'] = False # (m/s); x-component of undisturbed wind velocity at Blade 1, Node 2; local blade coordinate system AeroDyn['B1N3VUndx'] = False # (m/s); x-component of undisturbed wind velocity at Blade 1, Node 3; local blade coordinate system @@ -2535,6 +3100,114 @@ AeroDyn['B3N7Clrnc'] = False # (m); Tower clearance at Blade 3, Node 7 (based on the absolute distance to the nearest point in the tower from B3N7 minus the local tower radius, in the deflected configuration); please note that this clearance is only approximate because the calculation assumes that the blade is a line with no volume (however, the calculation does use the local tower radius); when B3N7 is above the tower top (or below the tower base), the absolute distance to the tower top (or base) minus the local tower radius, in the deflected configuration, is output; AeroDyn['B3N8Clrnc'] = False # (m); Tower clearance at Blade 3, Node 8 (based on the absolute distance to the nearest point in the tower from B3N8 minus the local tower radius, in the deflected configuration); please note that this clearance is only approximate because the calculation assumes that the blade is a line with no volume (however, the calculation does use the local tower radius); when B3N8 is above the tower top (or below the tower base), the absolute distance to the tower top (or base) minus the local tower radius, in the deflected configuration, is output; AeroDyn['B3N9Clrnc'] = False # (m); Tower clearance at Blade 3, Node 9 (based on the absolute distance to the nearest point in the tower from B3N9 minus the local tower radius, in the deflected configuration); please note that this clearance is only approximate because the calculation assumes that the blade is a line with no volume (however, the calculation does use the local tower radius); when B3N9 is above the tower top (or below the tower base), the absolute distance to the tower top (or base) minus the local tower radius, in the deflected configuration, is output; +AeroDyn['B1N1Cpmin'] = False # (-); Pressure coefficient blade 1 node 1; +AeroDyn['B1N2Cpmin'] = False # (-); Pressure coefficient blade 1 node 2; +AeroDyn['B1N3Cpmin'] = False # (-); Pressure coefficient blade 1 node 3; +AeroDyn['B1N4Cpmin'] = False # (-); Pressure coefficient blade 1 node 4; +AeroDyn['B1N5Cpmin'] = False # (-); Pressure coefficient blade 1 node 5; +AeroDyn['B1N6Cpmin'] = False # (-); Pressure coefficient blade 1 node 6; +AeroDyn['B1N7Cpmin'] = False # (-); Pressure coefficient blade 1 node 7; +AeroDyn['B1N8Cpmin'] = False # (-); Pressure coefficient blade 1 node 8; +AeroDyn['B1N9Cpmin'] = False # (-); Pressure coefficient blade 1 node 9; +AeroDyn['B2N1Cpmin'] = False # (-); Pressure coefficient blade 2 node 1; +AeroDyn['B2N2Cpmin'] = False # (-); Pressure coefficient blade 2 node 2; +AeroDyn['B2N3Cpmin'] = False # (-); Pressure coefficient blade 2 node 3; +AeroDyn['B2N4Cpmin'] = False # (-); Pressure coefficient blade 2 node 4; +AeroDyn['B2N5Cpmin'] = False # (-); Pressure coefficient blade 2 node 5; +AeroDyn['B2N6Cpmin'] = False # (-); Pressure coefficient blade 2 node 6; +AeroDyn['B2N7Cpmin'] = False # (-); Pressure coefficient blade 2 node 7; +AeroDyn['B2N8Cpmin'] = False # (-); Pressure coefficient blade 2 node 8; +AeroDyn['B2N9Cpmin'] = False # (-); Pressure coefficient blade 2 node 9; +AeroDyn['B3N1Cpmin'] = False # (-); Pressure coefficient blade 3 node 1; +AeroDyn['B3N2Cpmin'] = False # (-); Pressure coefficient blade 3 node 2; +AeroDyn['B3N3Cpmin'] = False # (-); Pressure coefficient blade 3 node 3; +AeroDyn['B3N4Cpmin'] = False # (-); Pressure coefficient blade 3 node 4; +AeroDyn['B3N5Cpmin'] = False # (-); Pressure coefficient blade 3 node 5; +AeroDyn['B3N6Cpmin'] = False # (-); Pressure coefficient blade 3 node 6; +AeroDyn['B3N7Cpmin'] = False # (-); Pressure coefficient blade 3 node 7; +AeroDyn['B3N8Cpmin'] = False # (-); Pressure coefficient blade 3 node 8; +AeroDyn['B3N9Cpmin'] = False # (-); Pressure coefficient blade 3 node 9; +AeroDyn['B1N1SigCr'] = False # (-); Critical cavitation number blade 1 node 1; +AeroDyn['B1N2SigCr'] = False # (-); Critical cavitation number blade 1 node 2; +AeroDyn['B1N3SigCr'] = False # (-); Critical cavitation number blade 1 node 3; +AeroDyn['B1N4SigCr'] = False # (-); Critical cavitation number blade 1 node 4; +AeroDyn['B1N5SigCr'] = False # (-); Critical cavitation number blade 1 node 5; +AeroDyn['B1N6SigCr'] = False # (-); Critical cavitation number blade 1 node 6; +AeroDyn['B1N7SigCr'] = False # (-); Critical cavitation number blade 1 node 7; +AeroDyn['B1N8SigCr'] = False # (-); Critical cavitation number blade 1 node 8; +AeroDyn['B1N9SigCr'] = False # (-); Critical cavitation number blade 1 node 9; +AeroDyn['B2N1SigCr'] = False # (-); Critical cavitation number blade 2 node 1; +AeroDyn['B2N2SigCr'] = False # (-); Critical cavitation number blade 2 node 2; +AeroDyn['B2N3SigCr'] = False # (-); Critical cavitation number blade 2 node 3; +AeroDyn['B2N4SigCr'] = False # (-); Critical cavitation number blade 2 node 4; +AeroDyn['B2N5SigCr'] = False # (-); Critical cavitation number blade 2 node 5; +AeroDyn['B2N6SigCr'] = False # (-); Critical cavitation number blade 2 node 6; +AeroDyn['B2N7SigCr'] = False # (-); Critical cavitation number blade 2 node 7; +AeroDyn['B2N8SigCr'] = False # (-); Critical cavitation number blade 2 node 8; +AeroDyn['B2N9SigCr'] = False # (-); Critical cavitation number blade 2 node 9; +AeroDyn['B3N1SigCr'] = False # (-); Critical cavitation number blade 3 node 1; +AeroDyn['B3N2SigCr'] = False # (-); Critical cavitation number blade 3 node 2; +AeroDyn['B3N3SigCr'] = False # (-); Critical cavitation number blade 3 node 3; +AeroDyn['B3N4SigCr'] = False # (-); Critical cavitation number blade 3 node 4; +AeroDyn['B3N5SigCr'] = False # (-); Critical cavitation number blade 3 node 5; +AeroDyn['B3N6SigCr'] = False # (-); Critical cavitation number blade 3 node 6; +AeroDyn['B3N7SigCr'] = False # (-); Critical cavitation number blade 3 node 7; +AeroDyn['B3N8SigCr'] = False # (-); Critical cavitation number blade 3 node 8; +AeroDyn['B3N9SigCr'] = False # (-); Critical cavitation number blade 3 node 9; +AeroDyn['B1N1SgCav'] = False # (-); Cavitation number blade 1 node 1; +AeroDyn['B1N2SgCav'] = False # (-); Cavitation number blade 1 node 2; +AeroDyn['B1N3SgCav'] = False # (-); Cavitation number blade 1 node 3; +AeroDyn['B1N4SgCav'] = False # (-); Cavitation number blade 1 node 4; +AeroDyn['B1N5SgCav'] = False # (-); Cavitation number blade 1 node 5; +AeroDyn['B1N6SgCav'] = False # (-); Cavitation number blade 1 node 6; +AeroDyn['B1N7SgCav'] = False # (-); Cavitation number blade 1 node 7; +AeroDyn['B1N8SgCav'] = False # (-); Cavitation number blade 1 node 8; +AeroDyn['B1N9SgCav'] = False # (-); Cavitation number blade 1 node 9; +AeroDyn['B2N1SgCav'] = False # (-); Cavitation number blade 2 node 1; +AeroDyn['B2N2SgCav'] = False # (-); Cavitation number blade 2 node 2; +AeroDyn['B2N3SgCav'] = False # (-); Cavitation number blade 2 node 3; +AeroDyn['B2N4SgCav'] = False # (-); Cavitation number blade 2 node 4; +AeroDyn['B2N5SgCav'] = False # (-); Cavitation number blade 2 node 5; +AeroDyn['B2N6SgCav'] = False # (-); Cavitation number blade 2 node 6; +AeroDyn['B2N7SgCav'] = False # (-); Cavitation number blade 2 node 7; +AeroDyn['B2N8SgCav'] = False # (-); Cavitation number blade 2 node 8; +AeroDyn['B2N9SgCav'] = False # (-); Cavitation number blade 2 node 9; +AeroDyn['B3N1SgCav'] = False # (-); Cavitation number blade 3 node 1; +AeroDyn['B3N2SgCav'] = False # (-); Cavitation number blade 3 node 2; +AeroDyn['B3N3SgCav'] = False # (-); Cavitation number blade 3 node 3; +AeroDyn['B3N4SgCav'] = False # (-); Cavitation number blade 3 node 4; +AeroDyn['B3N5SgCav'] = False # (-); Cavitation number blade 3 node 5; +AeroDyn['B3N6SgCav'] = False # (-); Cavitation number blade 3 node 6; +AeroDyn['B3N7SgCav'] = False # (-); Cavitation number blade 3 node 7; +AeroDyn['B3N8SgCav'] = False # (-); Cavitation number blade 3 node 8; +AeroDyn['B3N9SgCav'] = False # (-); Cavitation number blade 3 node 9; +AeroDyn['B1N1Gam'] = False # (m^2/s); Circulation on blade 1 at node 1; +AeroDyn['B1N2Gam'] = False # (m^2/s); Circulation on blade 1 at node 2; +AeroDyn['B1N3Gam'] = False # (m^2/s); Circulation on blade 1 at node 3; +AeroDyn['B1N4Gam'] = False # (m^2/s); Circulation on blade 1 at node 4; +AeroDyn['B1N5Gam'] = False # (m^2/s); Circulation on blade 1 at node 5; +AeroDyn['B1N6Gam'] = False # (m^2/s); Circulation on blade 1 at node 6; +AeroDyn['B1N7Gam'] = False # (m^2/s); Circulation on blade 1 at node 7; +AeroDyn['B1N8Gam'] = False # (m^2/s); Circulation on blade 1 at node 8; +AeroDyn['B1N9Gam'] = False # (m^2/s); Circulation on blade 1 at node 9; +AeroDyn['B2N1Gam'] = False # (m^2/s); Circulation on blade 2 at node 1; +AeroDyn['B2N2Gam'] = False # (m^2/s); Circulation on blade 2 at node 2; +AeroDyn['B2N3Gam'] = False # (m^2/s); Circulation on blade 2 at node 3; +AeroDyn['B2N4Gam'] = False # (m^2/s); Circulation on blade 2 at node 4; +AeroDyn['B2N5Gam'] = False # (m^2/s); Circulation on blade 2 at node 5; +AeroDyn['B2N6Gam'] = False # (m^2/s); Circulation on blade 2 at node 6; +AeroDyn['B2N7Gam'] = False # (m^2/s); Circulation on blade 2 at node 7; +AeroDyn['B2N8Gam'] = False # (m^2/s); Circulation on blade 2 at node 8; +AeroDyn['B2N9Gam'] = False # (m^2/s); Circulation on blade 2 at node 9; +AeroDyn['B3N1Gam'] = False # (m^2/s); Circulation on blade 3 at node 1; +AeroDyn['B3N2Gam'] = False # (m^2/s); Circulation on blade 3 at node 2; +AeroDyn['B3N3Gam'] = False # (m^2/s); Circulation on blade 3 at node 3; +AeroDyn['B3N4Gam'] = False # (m^2/s); Circulation on blade 3 at node 4; +AeroDyn['B3N5Gam'] = False # (m^2/s); Circulation on blade 3 at node 5; +AeroDyn['B3N6Gam'] = False # (m^2/s); Circulation on blade 3 at node 6; +AeroDyn['B3N7Gam'] = False # (m^2/s); Circulation on blade 3 at node 7; +AeroDyn['B3N8Gam'] = False # (m^2/s); Circulation on blade 3 at node 8; +AeroDyn['B3N9Gam'] = False # (m^2/s); Circulation on blade 3 at node 9; # Rotor AeroDyn['RtSpeed'] = False # (rpm); Rotor speed; @@ -2555,6 +3228,267 @@ AeroDyn['RtFldCq'] = False # (-); Rotor aerodynamic torque coefficient; AeroDyn['RtFldCt'] = False # (-); Rotor aerodynamic thrust coefficient; +""" ElastoDyn_Nodes """ +ElastoDyn_Nodes = {} + +# Local Span Motions +ElastoDyn_Nodes['ALx'] = False # (m/s^2); local flapwise acceleration (absolute) of node; Directed along the local xb-axis +ElastoDyn_Nodes['Ax'] = False # (m/s^2); local flapwise acceleration (absolute) of node; Directed along the local xb-axis +ElastoDyn_Nodes['ALy'] = False # (m/s^2); local flapwise acceleration (absolute) of node; Directed along the local yb-axis +ElastoDyn_Nodes['Ay'] = False # (m/s^2); local flapwise acceleration (absolute) of node; Directed along the local yb-axis +ElastoDyn_Nodes['ALz'] = False # (m/s^2); local flapwise acceleration (absolute) of node; Directed along the local zb-axis +ElastoDyn_Nodes['Az'] = False # (m/s^2); local flapwise acceleration (absolute) of node; Directed along the local zb-axis +ElastoDyn_Nodes['TDx'] = False # (m); local flapwise (translational) deflection (relative to the undeflected position) of node; Directed along the xb-axis +ElastoDyn_Nodes['UxB'] = False # (m); local flapwise (translational) deflection (relative to the undeflected position) of node; Directed along the xb-axis +ElastoDyn_Nodes['TDy'] = False # (m); local edgewise (translational) deflection (relative to the undeflected position) of node; Directed along the yb-axis +ElastoDyn_Nodes['UyB'] = False # (m); local edgewise (translational) deflection (relative to the undeflected position) of node; Directed along the yb-axis +ElastoDyn_Nodes['TDz'] = False # (m); local axial (translational) deflection (relative to the undeflected position) of node; Directed along the zb-axis +ElastoDyn_Nodes['UzB'] = False # (m); local axial (translational) deflection (relative to the undeflected position) of node; Directed along the zb-axis +ElastoDyn_Nodes['RDx'] = False # (deg); Local rotational displacement about x-axis (relative to undeflected); About the local xb-axis +ElastoDyn_Nodes['Rx'] = False # (deg); Local rotational displacement about x-axis (relative to undeflected); About the local xb-axis +ElastoDyn_Nodes['RDy'] = False # (deg); Local rotational displacement about y-axis (relative to undeflected); About the local yb-axis +ElastoDyn_Nodes['Ry'] = False # (deg); Local rotational displacement about y-axis (relative to undeflected); About the local yb-axis +ElastoDyn_Nodes['RDz'] = False # (deg); Local rotational displacement about z-axis (relative to undeflected); About the local zb-axis +ElastoDyn_Nodes['Rz'] = False # (deg); Local rotational displacement about z-axis (relative to undeflected); About the local zb-axis + +# Local Span Loads +ElastoDyn_Nodes['MLx'] = False # (kN-m); local edgewise moment at node; About the local xb-axis +ElastoDyn_Nodes['Mx'] = False # (kN-m); local edgewise moment at node; About the local xb-axis +ElastoDyn_Nodes['MLy'] = False # (kN-m); local flapwise moment at node; About the local yb-axis +ElastoDyn_Nodes['My'] = False # (kN-m); local flapwise moment at node; About the local yb-axis +ElastoDyn_Nodes['MLz'] = False # (kN-m); local pitching moment at node; About the local zb-axis +ElastoDyn_Nodes['MLzNT'] = False # (kN-m); local pitching moment at node; About the local zb-axis +ElastoDyn_Nodes['MzL'] = False # (kN-m); local pitching moment at node; About the local zb-axis +ElastoDyn_Nodes['Mz'] = False # (kN-m); local pitching moment at node; About the local zb-axis +ElastoDyn_Nodes['FLx'] = False # (kN); local flapwise shear force at node; Directed along the local xb-axis +ElastoDyn_Nodes['Fx'] = False # (kN); local flapwise shear force at node; Directed along the local xb-axis +ElastoDyn_Nodes['FLy'] = False # (kN); local edgewise shear force at node; Directed along the local yb-axis +ElastoDyn_Nodes['Fy'] = False # (kN); local edgewise shear force at node; Directed along the local yb-axis +ElastoDyn_Nodes['FLz'] = False # (kN); local axial force at node; Directed along the local zb-axis +ElastoDyn_Nodes['FLzNT'] = False # (kN); local axial force at node; Directed along the local zb-axis +ElastoDyn_Nodes['FzL'] = False # (kN); local axial force at node; Directed along the local zb-axis +ElastoDyn_Nodes['Fz'] = False # (kN); local axial force at node; Directed along the local zb-axis +ElastoDyn_Nodes['MLxNT'] = False # (kN-m); Edgewise moment in local coordinate system (initial structural twist removed); About the local xb-axis +ElastoDyn_Nodes['MxL'] = False # (kN-m); Edgewise moment in local coordinate system (initial structural twist removed); About the local xb-axis +ElastoDyn_Nodes['MlyNT'] = False # (kN-m); Flapwise shear moment in local coordinate system (initial structural twist removed); About the local yb-axis +ElastoDyn_Nodes['MyL'] = False # (kN-m); Flapwise shear moment in local coordinate system (initial structural twist removed); About the local yb-axis +ElastoDyn_Nodes['FLxNT'] = False # (kN); Flapwise shear force in local coordinate system (initial structural twist removed); Directed along the local xb-axis +ElastoDyn_Nodes['FxL'] = False # (kN); Flapwise shear force in local coordinate system (initial structural twist removed); Directed along the local xb-axis +ElastoDyn_Nodes['FlyNT'] = False # (kN); Edgewise shear force in local coordinate system (initial structural twist removed); Directed along the local yb-axis +ElastoDyn_Nodes['FyL'] = False # (kN); Edgewise shear force in local coordinate system (initial structural twist removed); Directed along the local yb-axis + + +""" BeamDyn_Nodes """ +BeamDyn_Nodes = {} + +# Sectional Loads +BeamDyn_Nodes['FxL'] = False # (N); Sectional force resultants at each node expressed in l; l: a floating coordinate system local to the deflected beam +BeamDyn_Nodes['FyL'] = False # (N); Sectional force resultants at each node expressed in l; l: a floating coordinate system local to the deflected beam +BeamDyn_Nodes['FzL'] = False # (N); Sectional force resultants at each node expressed in l; l: a floating coordinate system local to the deflected beam +BeamDyn_Nodes['MxL'] = False # (N-m); Sectional moment resultants at each node expressed in l; l: a floating coordinate system local to the deflected beam +BeamDyn_Nodes['MyL'] = False # (N-m); Sectional moment resultants at each node expressed in l; l: a floating coordinate system local to the deflected beam +BeamDyn_Nodes['MzL'] = False # (N-m); Sectional moment resultants at each node expressed in l; l: a floating coordinate system local to the deflected beam +BeamDyn_Nodes['Fxr'] = False # (N); Sectional force resultants at each node expressed in r; r: a floating reference coordinate system fixed to the root of the moving beam; when coupled to FAST for blades, this is equivalent to the IEC blade (b) coordinate system +BeamDyn_Nodes['Fyr'] = False # (N); Sectional force resultants at each node expressed in r; r: a floating reference coordinate system fixed to the root of the moving beam; when coupled to FAST for blades, this is equivalent to the IEC blade (b) coordinate system +BeamDyn_Nodes['Fzr'] = False # (N); Sectional force resultants at each node expressed in r; r: a floating reference coordinate system fixed to the root of the moving beam; when coupled to FAST for blades, this is equivalent to the IEC blade (b) coordinate system +BeamDyn_Nodes['Mxr'] = False # (N-m); Sectional moment resultants at each node expressed in r; r: a floating reference coordinate system fixed to the root of the moving beam; when coupled to FAST for blades, this is equivalent to the IEC blade (b) coordinate system +BeamDyn_Nodes['Myr'] = False # (N-m); Sectional moment resultants at each node expressed in r; r: a floating reference coordinate system fixed to the root of the moving beam; when coupled to FAST for blades, this is equivalent to the IEC blade (b) coordinate system +BeamDyn_Nodes['Mzr'] = False # (N-m); Sectional moment resultants at each node expressed in r; r: a floating reference coordinate system fixed to the root of the moving beam; when coupled to FAST for blades, this is equivalent to the IEC blade (b) coordinate system + +# Sectional Motions +BeamDyn_Nodes['TDxr'] = False # (m); Sectional translational deflection (relative to the undeflected position) at each node expressed in r; r: a floating reference coordinate system fixed to the root of the moving beam; when coupled to FAST for blades, this is equivalent to the IEC blade (b) coordinate system +BeamDyn_Nodes['TDyr'] = False # (m); Sectional translational deflection (relative to the undeflected position) at each node expressed in r; r: a floating reference coordinate system fixed to the root of the moving beam; when coupled to FAST for blades, this is equivalent to the IEC blade (b) coordinate system +BeamDyn_Nodes['TDzr'] = False # (m); Sectional translational deflection (relative to the undeflected position) at each node expressed in r; r: a floating reference coordinate system fixed to the root of the moving beam; when coupled to FAST for blades, this is equivalent to the IEC blade (b) coordinate system +BeamDyn_Nodes['RDxr'] = False # (-); Sectional angular/rotational deflection Wiener-Milenkovic parameter (relative to the undeflected orientation) at each node expressed in r; r: a floating reference coordinate system fixed to the root of the moving beam; when coupled to FAST for blades, this is equivalent to the IEC blade (b) coordinate system +BeamDyn_Nodes['RDyr'] = False # (-); Sectional angular/rotational deflection Wiener-Milenkovic parameter (relative to the undeflected orientation) at each node expressed in r; r: a floating reference coordinate system fixed to the root of the moving beam; when coupled to FAST for blades, this is equivalent to the IEC blade (b) coordinate system +BeamDyn_Nodes['RDzr'] = False # (-); Sectional angular/rotational deflection Wiener-Milenkovic parameter (relative to the undeflected orientation) at each node expressed in r; r: a floating reference coordinate system fixed to the root of the moving beam; when coupled to FAST for blades, this is equivalent to the IEC blade (b) coordinate system +BeamDyn_Nodes['AbsXg'] = False # (m); Node position in X (global coordinate) ; g: the global inertial frame coordinate system; when coupled to FAST, this is equivalent to FAST s global inertial frame (i) coordinate system +BeamDyn_Nodes['AbsYg'] = False # (m); Node position in Y (global coordinate) ; g: the global inertial frame coordinate system; when coupled to FAST, this is equivalent to FAST s global inertial frame (i) coordinate system +BeamDyn_Nodes['AbsZg'] = False # (m); Node position in Z (global coordinate) ; g: the global inertial frame coordinate system; when coupled to FAST, this is equivalent to FAST s global inertial frame (i) coordinate system +BeamDyn_Nodes['AbsXr'] = False # (m); Node position in X (relative to root) ; r: a floating reference coordinate system fixed to the root of the moving beam; when coupled to FAST for blades, this is equivalent to the IEC blade (b) coordinate system +BeamDyn_Nodes['AbsYr'] = False # (m); Node position in Y (relative to root) ; r: a floating reference coordinate system fixed to the root of the moving beam; when coupled to FAST for blades, this is equivalent to the IEC blade (b) coordinate system +BeamDyn_Nodes['AbsZr'] = False # (m); Node position in Z (relative to root) ; r: a floating reference coordinate system fixed to the root of the moving beam; when coupled to FAST for blades, this is equivalent to the IEC blade (b) coordinate system +BeamDyn_Nodes['TVxg'] = False # (m/s); Sectional translational velocities (absolute); g: the global inertial frame coordinate system; when coupled to FAST, this is equivalent to FAST s global inertial frame (i) coordinate system +BeamDyn_Nodes['TVyg'] = False # (m/s); Sectional translational velocities (absolute); g: the global inertial frame coordinate system; when coupled to FAST, this is equivalent to FAST s global inertial frame (i) coordinate system +BeamDyn_Nodes['TVzg'] = False # (m/s); Sectional translational velocities (absolute); g: the global inertial frame coordinate system; when coupled to FAST, this is equivalent to FAST s global inertial frame (i) coordinate system +BeamDyn_Nodes['TVxl'] = False # (m/s); Sectional translational velocities (absolute); l: a floating coordinate system local to the deflected beam +BeamDyn_Nodes['TVyl'] = False # (m/s); Sectional translational velocities (absolute); l: a floating coordinate system local to the deflected beam +BeamDyn_Nodes['TVzl'] = False # (m/s); Sectional translational velocities (absolute); l: a floating coordinate system local to the deflected beam +BeamDyn_Nodes['TVxr'] = False # (m/s); Sectional translational velocities (absolute); r: a floating reference coordinate system fixed to the root of the moving beam; when coupled to FAST for blades, this is equivalent to the IEC blade (b) coordinate system +BeamDyn_Nodes['TVyr'] = False # (m/s); Sectional translational velocities (absolute); r: a floating reference coordinate system fixed to the root of the moving beam; when coupled to FAST for blades, this is equivalent to the IEC blade (b) coordinate system +BeamDyn_Nodes['TVzr'] = False # (m/s); Sectional translational velocities (absolute); r: a floating reference coordinate system fixed to the root of the moving beam; when coupled to FAST for blades, this is equivalent to the IEC blade (b) coordinate system +BeamDyn_Nodes['RVxg'] = False # (deg/s); Sectional angular/rotational velocities (absolute); g: the global inertial frame coordinate system; when coupled to FAST, this is equivalent to FAST s global inertial frame (i) coordinate system +BeamDyn_Nodes['RVyg'] = False # (deg/s); Sectional angular/rotational velocities (absolute); g: the global inertial frame coordinate system; when coupled to FAST, this is equivalent to FAST s global inertial frame (i) coordinate system +BeamDyn_Nodes['RVzg'] = False # (deg/s); Sectional angular/rotational velocities (absolute); g: the global inertial frame coordinate system; when coupled to FAST, this is equivalent to FAST s global inertial frame (i) coordinate system +BeamDyn_Nodes['RVxl'] = False # (deg/s); Sectional angular/rotational velocities (absolute); l: a floating coordinate system local to the deflected beam +BeamDyn_Nodes['RVyl'] = False # (deg/s); Sectional angular/rotational velocities (absolute); l: a floating coordinate system local to the deflected beam +BeamDyn_Nodes['RVzl'] = False # (deg/s); Sectional angular/rotational velocities (absolute); l: a floating coordinate system local to the deflected beam +BeamDyn_Nodes['RVxr'] = False # (deg/s); Sectional angular/rotational velocities (absolute); r: a floating reference coordinate system fixed to the root of the moving beam; when coupled to FAST for blades, this is equivalent to the IEC blade (b) coordinate system +BeamDyn_Nodes['RVyr'] = False # (deg/s); Sectional angular/rotational velocities (absolute); r: a floating reference coordinate system fixed to the root of the moving beam; when coupled to FAST for blades, this is equivalent to the IEC blade (b) coordinate system +BeamDyn_Nodes['RVzr'] = False # (deg/s); Sectional angular/rotational velocities (absolute); r: a floating reference coordinate system fixed to the root of the moving beam; when coupled to FAST for blades, this is equivalent to the IEC blade (b) coordinate system +BeamDyn_Nodes['TAxl'] = False # (m/s^2); Sectional angular/rotational velocities (absolute); l: a floating coordinate system local to the deflected beam +BeamDyn_Nodes['TAyl'] = False # (m/s^2); Sectional angular/rotational velocities (absolute); l: a floating coordinate system local to the deflected beam +BeamDyn_Nodes['TAzl'] = False # (m/s^2); Sectional angular/rotational velocities (absolute); l: a floating coordinate system local to the deflected beam +BeamDyn_Nodes['TAxr'] = False # (m/s^2); Sectional angular/rotational velocities (absolute); r: a floating reference coordinate system fixed to the root of the moving beam; when coupled to FAST for blades, this is equivalent to the IEC blade (b) coordinate system +BeamDyn_Nodes['TAyr'] = False # (m/s^2); Sectional angular/rotational velocities (absolute); r: a floating reference coordinate system fixed to the root of the moving beam; when coupled to FAST for blades, this is equivalent to the IEC blade (b) coordinate system +BeamDyn_Nodes['TAzr'] = False # (m/s^2); Sectional angular/rotational velocities (absolute); r: a floating reference coordinate system fixed to the root of the moving beam; when coupled to FAST for blades, this is equivalent to the IEC blade (b) coordinate system +BeamDyn_Nodes['RAxl'] = False # (deg/s^2); Sectional angular/rotational velocities (absolute); l: a floating coordinate system local to the deflected beam +BeamDyn_Nodes['RAyl'] = False # (deg/s^2); Sectional angular/rotational velocities (absolute); l: a floating coordinate system local to the deflected beam +BeamDyn_Nodes['RAzl'] = False # (deg/s^2); Sectional angular/rotational velocities (absolute); l: a floating coordinate system local to the deflected beam +BeamDyn_Nodes['RAxr'] = False # (deg/s^2); Sectional angular/rotational velocities (absolute); r: a floating reference coordinate system fixed to the root of the moving beam; when coupled to FAST for blades, this is equivalent to the IEC blade (b) coordinate system +BeamDyn_Nodes['RAyr'] = False # (deg/s^2); Sectional angular/rotational velocities (absolute); r: a floating reference coordinate system fixed to the root of the moving beam; when coupled to FAST for blades, this is equivalent to the IEC blade (b) coordinate system +BeamDyn_Nodes['RAzr'] = False # (deg/s^2); Sectional angular/rotational velocities (absolute); r: a floating reference coordinate system fixed to the root of the moving beam; when coupled to FAST for blades, this is equivalent to the IEC blade (b) coordinate system + +# Applied Loads +BeamDyn_Nodes['PFxL'] = False # (N); Applied point forces at each node expressed in l; l: a floating coordinate system local to the deflected beam +BeamDyn_Nodes['PFyL'] = False # (N); Applied point forces at each node expressed in l; l: a floating coordinate system local to the deflected beam +BeamDyn_Nodes['PFzL'] = False # (N); Applied point forces at each node expressed in l; l: a floating coordinate system local to the deflected beam +BeamDyn_Nodes['PMxL'] = False # (N-m); Applied point moments at each node expressed in l; l: a floating coordinate system local to the deflected beam +BeamDyn_Nodes['PMyL'] = False # (N-m); Applied point moments at each node expressed in l; l: a floating coordinate system local to the deflected beam +BeamDyn_Nodes['PMzL'] = False # (N-m); Applied point moments at each node expressed in l; l: a floating coordinate system local to the deflected beam +BeamDyn_Nodes['DFxL'] = False # (N/m); Applied distributed forces at each node expressed in l; l: a floating coordinate system local to the deflected beam +BeamDyn_Nodes['DFyL'] = False # (N/m); Applied distributed forces at each node expressed in l; l: a floating coordinate system local to the deflected beam +BeamDyn_Nodes['DFzL'] = False # (N/m); Applied distributed forces at each node expressed in l; l: a floating coordinate system local to the deflected beam +BeamDyn_Nodes['DMxL'] = False # (N-m/m); Applied distributed moments at each node expressed in l; l: a floating coordinate system local to the deflected beam +BeamDyn_Nodes['DMyL'] = False # (N-m/m); Applied distributed moments at each node expressed in l; l: a floating coordinate system local to the deflected beam +BeamDyn_Nodes['DMzL'] = False # (N-m/m); Applied distributed moments at each node expressed in l; l: a floating coordinate system local to the deflected beam +BeamDyn_Nodes['DFxR'] = False # (N/m); Applied distributed forces at each node expressed in r; r: a floating reference coordinate system fixed to the root of the moving beam; when coupled to FAST for blades, this is equivalent to the IEC blade (b) coordinate system +BeamDyn_Nodes['DFyR'] = False # (N/m); Applied distributed forces at each node expressed in r; r: a floating reference coordinate system fixed to the root of the moving beam; when coupled to FAST for blades, this is equivalent to the IEC blade (b) coordinate system +BeamDyn_Nodes['DFzR'] = False # (N/m); Applied distributed forces at each node expressed in r; r: a floating reference coordinate system fixed to the root of the moving beam; when coupled to FAST for blades, this is equivalent to the IEC blade (b) coordinate system +BeamDyn_Nodes['DMxR'] = False # (N-m/m); Applied distributed forces at each node expressed in r; r: a floating reference coordinate system fixed to the root of the moving beam; when coupled to FAST for blades, this is equivalent to the IEC blade (b) coordinate system +BeamDyn_Nodes['DMyR'] = False # (N-m/m); Applied distributed forces at each node expressed in r; r: a floating reference coordinate system fixed to the root of the moving beam; when coupled to FAST for blades, this is equivalent to the IEC blade (b) coordinate system +BeamDyn_Nodes['DMzR'] = False # (N-m/m); Applied distributed forces at each node expressed in r; r: a floating reference coordinate system fixed to the root of the moving beam; when coupled to FAST for blades, this is equivalent to the IEC blade (b) coordinate system + +# Sectional Partial Loads (debugging) +BeamDyn_Nodes['FFbxl'] = False # (N); Gyroscopic force x ; l: a floating coordinate system local to the deflected beam +BeamDyn_Nodes['FFbyl'] = False # (N); Gyroscopic force y ; l: a floating coordinate system local to the deflected beam +BeamDyn_Nodes['FFbzl'] = False # (N); Gyroscopic force z ; l: a floating coordinate system local to the deflected beam +BeamDyn_Nodes['FFbxr'] = False # (N); Gyroscopic force x ; r: a floating reference coordinate system fixed to the root of the moving beam; when coupled to FAST for blades, this is equivalent to the IEC blade (b) coordinate system +BeamDyn_Nodes['FFbyr'] = False # (N); Gyroscopic force y ; r: a floating reference coordinate system fixed to the root of the moving beam; when coupled to FAST for blades, this is equivalent to the IEC blade (b) coordinate system +BeamDyn_Nodes['FFbzr'] = False # (N); Gyroscopic force z ; r: a floating reference coordinate system fixed to the root of the moving beam; when coupled to FAST for blades, this is equivalent to the IEC blade (b) coordinate system +BeamDyn_Nodes['MFbxl'] = False # (N-m); Gyroscopic moment about x ; l: a floating coordinate system local to the deflected beam +BeamDyn_Nodes['MFbyl'] = False # (N-m); Gyroscopic moment about y ; l: a floating coordinate system local to the deflected beam +BeamDyn_Nodes['MFbzl'] = False # (N-m); Gyroscopic moment about z ; l: a floating coordinate system local to the deflected beam +BeamDyn_Nodes['MFbxr'] = False # (N-m); Gyroscopic moment about x ; r: a floating reference coordinate system fixed to the root of the moving beam; when coupled to FAST for blades, this is equivalent to the IEC blade (b) coordinate system +BeamDyn_Nodes['MFbyr'] = False # (N-m); Gyroscopic moment about y ; r: a floating reference coordinate system fixed to the root of the moving beam; when coupled to FAST for blades, this is equivalent to the IEC blade (b) coordinate system +BeamDyn_Nodes['MFbzr'] = False # (N-m); Gyroscopic moment about z ; r: a floating reference coordinate system fixed to the root of the moving beam; when coupled to FAST for blades, this is equivalent to the IEC blade (b) coordinate system +BeamDyn_Nodes['FFcxl'] = False # (N); Elastic restoring force Fc x ; l: a floating coordinate system local to the deflected beam +BeamDyn_Nodes['FFcyl'] = False # (N); Elastic restoring force Fc y ; l: a floating coordinate system local to the deflected beam +BeamDyn_Nodes['FFczl'] = False # (N); Elastic restoring force Fc z ; l: a floating coordinate system local to the deflected beam +BeamDyn_Nodes['FFcxr'] = False # (N); Elastic restoring force Fc x ; r: a floating reference coordinate system fixed to the root of the moving beam; when coupled to FAST for blades, this is equivalent to the IEC blade (b) coordinate system +BeamDyn_Nodes['FFcyr'] = False # (N); Elastic restoring force Fc y ; r: a floating reference coordinate system fixed to the root of the moving beam; when coupled to FAST for blades, this is equivalent to the IEC blade (b) coordinate system +BeamDyn_Nodes['FFczr'] = False # (N); Elastic restoring force Fc z ; r: a floating reference coordinate system fixed to the root of the moving beam; when coupled to FAST for blades, this is equivalent to the IEC blade (b) coordinate system +BeamDyn_Nodes['MFcxl'] = False # (N-m); Elastic restoring moment Fc about x ; l: a floating coordinate system local to the deflected beam +BeamDyn_Nodes['MFcyl'] = False # (N-m); Elastic restoring moment Fc about y ; l: a floating coordinate system local to the deflected beam +BeamDyn_Nodes['MFczl'] = False # (N-m); Elastic restoring moment Fc about z ; l: a floating coordinate system local to the deflected beam +BeamDyn_Nodes['MFcxr'] = False # (N-m); Elastic restoring moment Fc about x ; r: a floating reference coordinate system fixed to the root of the moving beam; when coupled to FAST for blades, this is equivalent to the IEC blade (b) coordinate system +BeamDyn_Nodes['MFcyr'] = False # (N-m); Elastic restoring moment Fc about y ; r: a floating reference coordinate system fixed to the root of the moving beam; when coupled to FAST for blades, this is equivalent to the IEC blade (b) coordinate system +BeamDyn_Nodes['MFczr'] = False # (N-m); Elastic restoring moment Fc about z ; r: a floating reference coordinate system fixed to the root of the moving beam; when coupled to FAST for blades, this is equivalent to the IEC blade (b) coordinate system +BeamDyn_Nodes['FFdxl'] = False # (N); Elastic restoring force Fd x ; l: a floating coordinate system local to the deflected beam +BeamDyn_Nodes['FFdyl'] = False # (N); Elastic restoring force Fd y ; l: a floating coordinate system local to the deflected beam +BeamDyn_Nodes['FFdzl'] = False # (N); Elastic restoring force Fd z ; l: a floating coordinate system local to the deflected beam +BeamDyn_Nodes['FFdxr'] = False # (N); Elastic restoring force Fd x ; r: a floating reference coordinate system fixed to the root of the moving beam; when coupled to FAST for blades, this is equivalent to the IEC blade (b) coordinate system +BeamDyn_Nodes['FFdyr'] = False # (N); Elastic restoring force Fd y ; r: a floating reference coordinate system fixed to the root of the moving beam; when coupled to FAST for blades, this is equivalent to the IEC blade (b) coordinate system +BeamDyn_Nodes['FFdzr'] = False # (N); Elastic restoring force Fd z ; r: a floating reference coordinate system fixed to the root of the moving beam; when coupled to FAST for blades, this is equivalent to the IEC blade (b) coordinate system +BeamDyn_Nodes['MFdxl'] = False # (N-m); Elastic restoring moment Fd about x ; l: a floating coordinate system local to the deflected beam +BeamDyn_Nodes['MFdyl'] = False # (N-m); Elastic restoring moment Fd about y ; l: a floating coordinate system local to the deflected beam +BeamDyn_Nodes['MFdzl'] = False # (N-m); Elastic restoring moment Fd about z ; l: a floating coordinate system local to the deflected beam +BeamDyn_Nodes['MFdxr'] = False # (N-m); Elastic restoring moment Fd about x ; r: a floating reference coordinate system fixed to the root of the moving beam; when coupled to FAST for blades, this is equivalent to the IEC blade (b) coordinate system +BeamDyn_Nodes['MFdyr'] = False # (N-m); Elastic restoring moment Fd about y ; r: a floating reference coordinate system fixed to the root of the moving beam; when coupled to FAST for blades, this is equivalent to the IEC blade (b) coordinate system +BeamDyn_Nodes['MFdzr'] = False # (N-m); Elastic restoring moment Fd about z ; r: a floating reference coordinate system fixed to the root of the moving beam; when coupled to FAST for blades, this is equivalent to the IEC blade (b) coordinate system +BeamDyn_Nodes['FFgxl'] = False # (N); Gravity force x ; l: a floating coordinate system local to the deflected beam +BeamDyn_Nodes['FFgyl'] = False # (N); Gravity force y ; l: a floating coordinate system local to the deflected beam +BeamDyn_Nodes['FFgzl'] = False # (N); Gravity force z ; l: a floating coordinate system local to the deflected beam +BeamDyn_Nodes['FFgxr'] = False # (N); Gravity force x ; r: a floating reference coordinate system fixed to the root of the moving beam; when coupled to FAST for blades, this is equivalent to the IEC blade (b) coordinate system +BeamDyn_Nodes['FFgyr'] = False # (N); Gravity force y ; r: a floating reference coordinate system fixed to the root of the moving beam; when coupled to FAST for blades, this is equivalent to the IEC blade (b) coordinate system +BeamDyn_Nodes['FFgzr'] = False # (N); Gravity force z ; r: a floating reference coordinate system fixed to the root of the moving beam; when coupled to FAST for blades, this is equivalent to the IEC blade (b) coordinate system +BeamDyn_Nodes['MFgxl'] = False # (N-m); Gravity moment about x ; l: a floating coordinate system local to the deflected beam +BeamDyn_Nodes['MFgyl'] = False # (N-m); Gravity moment about y ; l: a floating coordinate system local to the deflected beam +BeamDyn_Nodes['MFgzl'] = False # (N-m); Gravity moment about z ; l: a floating coordinate system local to the deflected beam +BeamDyn_Nodes['MFgxr'] = False # (N-m); Gravity moment about x ; r: a floating reference coordinate system fixed to the root of the moving beam; when coupled to FAST for blades, this is equivalent to the IEC blade (b) coordinate system +BeamDyn_Nodes['MFgyr'] = False # (N-m); Gravity moment about y ; r: a floating reference coordinate system fixed to the root of the moving beam; when coupled to FAST for blades, this is equivalent to the IEC blade (b) coordinate system +BeamDyn_Nodes['MFgzr'] = False # (N-m); Gravity moment about z ; r: a floating reference coordinate system fixed to the root of the moving beam; when coupled to FAST for blades, this is equivalent to the IEC blade (b) coordinate system +BeamDyn_Nodes['FFixl'] = False # (N); Inertial force x ; l: a floating coordinate system local to the deflected beam +BeamDyn_Nodes['FFiyl'] = False # (N); Inertial force y ; l: a floating coordinate system local to the deflected beam +BeamDyn_Nodes['FFizl'] = False # (N); Inertial force z ; l: a floating coordinate system local to the deflected beam +BeamDyn_Nodes['FFixr'] = False # (N); Inertial force x ; r: a floating reference coordinate system fixed to the root of the moving beam; when coupled to FAST for blades, this is equivalent to the IEC blade (b) coordinate system +BeamDyn_Nodes['FFiyr'] = False # (N); Inertial force y ; r: a floating reference coordinate system fixed to the root of the moving beam; when coupled to FAST for blades, this is equivalent to the IEC blade (b) coordinate system +BeamDyn_Nodes['FFizr'] = False # (N); Inertial force z ; r: a floating reference coordinate system fixed to the root of the moving beam; when coupled to FAST for blades, this is equivalent to the IEC blade (b) coordinate system +BeamDyn_Nodes['MFixl'] = False # (N-m); Inertial moment about x ; l: a floating coordinate system local to the deflected beam +BeamDyn_Nodes['MFiyl'] = False # (N-m); Inertial moment about y ; l: a floating coordinate system local to the deflected beam +BeamDyn_Nodes['MFizl'] = False # (N-m); Inertial moment about z ; l: a floating coordinate system local to the deflected beam +BeamDyn_Nodes['MFixr'] = False # (N-m); Inertial moment about x ; r: a floating reference coordinate system fixed to the root of the moving beam; when coupled to FAST for blades, this is equivalent to the IEC blade (b) coordinate system +BeamDyn_Nodes['MFiyr'] = False # (N-m); Inertial moment about y ; r: a floating reference coordinate system fixed to the root of the moving beam; when coupled to FAST for blades, this is equivalent to the IEC blade (b) coordinate system +BeamDyn_Nodes['MFizr'] = False # (N-m); Inertial moment about z ; r: a floating reference coordinate system fixed to the root of the moving beam; when coupled to FAST for blades, this is equivalent to the IEC blade (b) coordinate system + + +""" AeroDyn_Nodes """ +AeroDyn_Nodes = {} + +# Blade +AeroDyn_Nodes['VUndx'] = False # (m/s); x-component of undisturbed wind velocity at each node; local blade coordinate system +AeroDyn_Nodes['VUndy'] = False # (m/s); y-component of undisturbed wind velocity at each node; local blade coordinate system +AeroDyn_Nodes['VUndz'] = False # (m/s); z-component of undisturbed wind velocity at each node; local blade coordinate system +AeroDyn_Nodes['Vundxi'] = False # (m/s); x-component of undisturbed wind velocity at each node; inertial/global coordinate system +AeroDyn_Nodes['Vundyi'] = False # (m/s); y-component of undisturbed wind velocity at each node; inertial/global coordinate system +AeroDyn_Nodes['Vundzi'] = False # (m/s); z-component of undisturbed wind velocity at each node; inertial/global coordinate system +AeroDyn_Nodes['VDisx'] = False # (m/s); x-component of disturbed wind velocity at each node; local blade coordinate system +AeroDyn_Nodes['VDisy'] = False # (m/s); y-component of disturbed wind velocity at each node; local blade coordinate system +AeroDyn_Nodes['VDisz'] = False # (m/s); z-component of disturbed wind velocity at each node; local blade coordinate system +AeroDyn_Nodes['STVx'] = False # (m/s); x-component of structural translational velocity at each node; local blade coordinate system +AeroDyn_Nodes['STVy'] = False # (m/s); y-component of structural translational velocity at each node; local blade coordinate system +AeroDyn_Nodes['STVz'] = False # (m/s); z-component of structural translational velocity at each node; local blade coordinate system +AeroDyn_Nodes['VRel'] = False # (m/s); Relvative wind speed at each node; +AeroDyn_Nodes['DynP'] = False # (Pa); Dynamic pressure at each node; +AeroDyn_Nodes['Re'] = False # (-); Reynolds number (in millions) at each node; +AeroDyn_Nodes['M'] = False # (-); Mach number at each node; +AeroDyn_Nodes['Vindx'] = False # (m/s); Axial induced wind velocity at each node; +AeroDyn_Nodes['Vindy'] = False # (m/s); Tangential induced wind velocity at each node; +AeroDyn_Nodes['AxInd'] = False # (-); Axial induction factor at each node; +AeroDyn_Nodes['TnInd'] = False # (-); Tangential induction factor at each node; +AeroDyn_Nodes['Alpha'] = False # (deg); Angle of attack at each node; +AeroDyn_Nodes['Theta'] = False # (deg); Pitch+Twist angle at each node; +AeroDyn_Nodes['Phi'] = False # (deg); Inflow angle at each node; +AeroDyn_Nodes['Curve'] = False # (deg); Curvature angle at each node; +AeroDyn_Nodes['Cl'] = False # (-); Lift force coefficient at each node, including unsteady effects; +AeroDyn_Nodes['Cd'] = False # (-); Drag force coefficient at each node, including unsteady effects; +AeroDyn_Nodes['Cm'] = False # (-); Pitching moment coefficient at each node, including unsteady effects; +AeroDyn_Nodes['Cx'] = False # (-); Normal force (to plane) coefficient at each node; +AeroDyn_Nodes['Cy'] = False # (-); Tangential force (to plane) coefficient at each node; +AeroDyn_Nodes['Cn'] = False # (-); Normal force (to chord) coefficient at each node; +AeroDyn_Nodes['Ct'] = False # (-); Tangential force (to chord) coefficient at each node; +AeroDyn_Nodes['Fl'] = False # (N/m); Lift force per unit length at each node; +AeroDyn_Nodes['Fd'] = False # (N/m); Drag force per unit length at each node; +AeroDyn_Nodes['Mm'] = False # (N-m/m); Pitching moment per unit length at each node; +AeroDyn_Nodes['Fx'] = False # (N/m); Normal force (to plane) per unit length at each node; +AeroDyn_Nodes['Fy'] = False # (N/m); Tangential force (to plane) per unit length at each node; +AeroDyn_Nodes['Fn'] = False # (N/m); Normal force (to chord) per unit length at each node; +AeroDyn_Nodes['Ft'] = False # (N/m); Tangential force (to chord) per unit length at each node; +AeroDyn_Nodes['Clrnc'] = False # (m); Tower clearance at each node (based on the absolute distance to the nearest point in the tower from blade node B#N# minus the local tower radius, in the deflected configuration); please note that this clearance is only approximate because the calculation assumes that the blade is a line with no volume (however, the calculation does use the local tower radius); when blade node B#N# is above the tower top (or below the tower base), the absolute distance to the tower top (or base) minus the local tower radius, in the deflected configuration, is output; +AeroDyn_Nodes['Vx'] = False # (m/s); Local axial velocity; +AeroDyn_Nodes['Vy'] = False # (m/s); Local tangential velocity; +AeroDyn_Nodes['GeomPhi'] = False # (1/0); Geometric phi? If phi was solved using normal BEMT equations, GeomPhi = 1; otherwise, if it was solved geometrically, GeomPhi = 0.; +AeroDyn_Nodes['Chi'] = False # (deg); Skew angle (used in skewed wake correction); +AeroDyn_Nodes['UA_Flag'] = False # (-); Flag indicating if UA is turned on for this node.; +AeroDyn_Nodes['UA_x1'] = False # (rad); time-history of wake vorticity contributing to effective angle of attack; +AeroDyn_Nodes['UA_x2'] = False # (rad); time-history of wake vorticity contributing to effective angle of attack; +AeroDyn_Nodes['UA_x3'] = False # (-); dimension of cl (UAMod4) or cn (UAMod5); lagging the fully-attached coefficient; +AeroDyn_Nodes['UA_x4'] = False # (-); UAMod4 and 5 separation factor; +AeroDyn_Nodes['UA_x5'] = False # (-); UAMod5 vortex term; +AeroDyn_Nodes['Debug1'] = False # (-); Placeholders for debugging channels; +AeroDyn_Nodes['Debug2'] = False # (-); Placeholders for debugging channels; +AeroDyn_Nodes['Debug3'] = False # (-); Placeholders for debugging channels; +AeroDyn_Nodes['CpMin'] = False # (-); Pressure coefficient; +AeroDyn_Nodes['SgCav'] = False # (-); Cavitation number; +AeroDyn_Nodes['SigCr'] = False # (-); Critical cavitation number; +AeroDyn_Nodes['Gam'] = False # (m^2/s); Gamma -- circulation on blade; +AeroDyn_Nodes['Cl_Static'] = False # (-); Static portion of lift force coefficient at each node, without unsteady effects; +AeroDyn_Nodes['Cd_Static'] = False # (-); Static portion of drag force coefficient at each node, without unsteady effects; +AeroDyn_Nodes['Cm_Static'] = False # (-); Static portion of pitching moment coefficient at each node, without unsteady effects; +AeroDyn_Nodes['Uin'] = False # (m/s); Axial induced velocity in rotating hub coordinates. Axial aligned with hub axis.; rotor plane polar hub rotating coordinates +AeroDyn_Nodes['Uit'] = False # (m/s); Tangential induced velocity in rotating hub coordinates. Tangential to the rotation plane. Perpendicular to blade aziumth.; rotor plane polar hub rotating coordinates +AeroDyn_Nodes['Uir'] = False # (m/s); Radial induced velocity in rotating hub coordinates. Radial outwards in rotation plane. Aligned with blade azimuth.; rotor plane polar hub rotating coordinates + """ InflowWind """ InflowWind = {} @@ -2588,6 +3522,35 @@ InflowWind['Wind9VelY'] = False # (m/s); Y component of wind at user selected wind point 9; Directed along the yi-axis InflowWind['Wind9VelZ'] = False # (m/s); Z component of wind at user selected wind point 9; Directed along the zi-axis +# Wind Magnitude and Direction +InflowWind['Wind1VelXY'] = False # (m/s); XY (horizontal) wind magnitude at user selected wind point 1; +InflowWind['Wind2VelXY'] = False # (m/s); XY (horizontal) wind magnitude at user selected wind point 2; +InflowWind['Wind3VelXY'] = False # (m/s); XY (horizontal) wind magnitude at user selected wind point 3; +InflowWind['Wind4VelXY'] = False # (m/s); XY (horizontal) wind magnitude at user selected wind point 4; +InflowWind['Wind5VelXY'] = False # (m/s); XY (horizontal) wind magnitude at user selected wind point 5; +InflowWind['Wind6VelXY'] = False # (m/s); XY (horizontal) wind magnitude at user selected wind point 6; +InflowWind['Wind7VelXY'] = False # (m/s); XY (horizontal) wind magnitude at user selected wind point 7; +InflowWind['Wind8VelXY'] = False # (m/s); XY (horizontal) wind magnitude at user selected wind point 8; +InflowWind['Wind9VelXY'] = False # (m/s); XY (horizontal) wind magnitude at user selected wind point 9; +InflowWind['Wind1VelMag'] = False # (m/s); wind magnitude at user selected wind point 1; +InflowWind['Wind2VelMag'] = False # (m/s); wind magnitude at user selected wind point 2; +InflowWind['Wind3VelMag'] = False # (m/s); wind magnitude at user selected wind point 3; +InflowWind['Wind4VelMag'] = False # (m/s); wind magnitude at user selected wind point 4; +InflowWind['Wind5VelMag'] = False # (m/s); wind magnitude at user selected wind point 5; +InflowWind['Wind6VelMag'] = False # (m/s); wind magnitude at user selected wind point 6; +InflowWind['Wind7VelMag'] = False # (m/s); wind magnitude at user selected wind point 7; +InflowWind['Wind8VelMag'] = False # (m/s); wind magnitude at user selected wind point 8; +InflowWind['Wind9VelMag'] = False # (m/s); wind magnitude at user selected wind point 9; +InflowWind['Wind1AngXY'] = False # (deg); Angle between X and Y wind velocity components at user selected wind point 1; +InflowWind['Wind2AngXY'] = False # (deg); Angle between X and Y wind velocity components at user selected wind point 2; +InflowWind['Wind3AngXY'] = False # (deg); Angle between X and Y wind velocity components at user selected wind point 3; +InflowWind['Wind4AngXY'] = False # (deg); Angle between X and Y wind velocity components at user selected wind point 4; +InflowWind['Wind5AngXY'] = False # (deg); Angle between X and Y wind velocity components at user selected wind point 5; +InflowWind['Wind6AngXY'] = False # (deg); Angle between X and Y wind velocity components at user selected wind point 6; +InflowWind['Wind7AngXY'] = False # (deg); Angle between X and Y wind velocity components at user selected wind point 7; +InflowWind['Wind8AngXY'] = False # (deg); Angle between X and Y wind velocity components at user selected wind point 8; +InflowWind['Wind9AngXY'] = False # (deg); Angle between X and Y wind velocity components at user selected wind point 9; + # Wind Sensor Measurements InflowWind['WindMeas1'] = False # (m/s); Wind measurement at sensor 1; Defined by sensor InflowWind['WindMeas2'] = False # (m/s); Wind measurement at sensor 2; Defined by sensor @@ -2641,52 +3604,552 @@ """ HydroDyn """ HydroDyn = {} -# Forces due to additional preload, stiffness, and damping -HydroDyn['AddFxi'] = False # (N); ; -HydroDyn['AddFyi'] = False # (N); ; -HydroDyn['AddFzi'] = False # (N); ; -HydroDyn['AddMxi'] = False # (N m); ; -HydroDyn['AddMyi'] = False # (N m); ; -HydroDyn['AddMzi'] = False # (N m); ; - -# Integrated hydrodynamic loads at the WAMIT reference point -HydroDyn['HydroFxi'] = False # (N); ; -HydroDyn['HydroFyi'] = False # (N); ; -HydroDyn['HydroFzi'] = False # (N); ; -HydroDyn['HydroMxi'] = False # (N m); ; -HydroDyn['HydroMyi'] = False # (N m); ; -HydroDyn['HydroMzi'] = False # (N m); ; +# Integrated Hydrodynamic Loads at (0,0,0) +HydroDyn['HydroFxi'] = False # (N); Total integrated hydrodynamic load along the global x-direction from both potential flow and strip theory at (0,0,0); +HydroDyn['HydroFyi'] = False # (N); Total integrated hydrodynamic load along the global y-direction from both potential flow and strip theory at (0,0,0); +HydroDyn['HydroFzi'] = False # (N); Total integrated hydrodynamic load along the global z-direction from both potential flow and strip theory at (0,0,0); +HydroDyn['HydroMxi'] = False # (N-m); Total integrated hydrodynamic moment about the global x-axis from both potential flow and strip theory at (0,0,0); +HydroDyn['HydroMyi'] = False # (N-m); Total integrated hydrodynamic moment about the global y-axis from both potential flow and strip theory at (0,0,0); +HydroDyn['HydroMzi'] = False # (N-m); Total integrated hydrodynamic moment about the global z-axis from both potential flow and strip theory at (0,0,0); + +# PRP Body Kinematics +HydroDyn['PRPSurge'] = False # (m); Displacement of the PRP (principal reference point) along the global x-axis; +HydroDyn['PRPSway'] = False # (m); Displacement of the PRP (principal reference point) along the global y-axis; +HydroDyn['PRPHeave'] = False # (m); Displacement of the PRP (principal reference point) along the global z-axis; +HydroDyn['PRPRoll'] = False # (rad); Rotation of the PRP (principal reference point) about the global x-axis at the PRP; +HydroDyn['PRPPitch'] = False # (rad); Rotation of the PRP (principal reference point) about the global y-axis at the PRP; +HydroDyn['PRPYaw'] = False # (rad); Rotation of the PRP (principal reference point) about the global z-axis at the PRP; +HydroDyn['PRPTVxi'] = False # (m/s); Translational velocity of the PRP (principal reference point) along the global x-axis; +HydroDyn['PRPTVyi'] = False # (m/s); Translational velocity of the PRP (principal reference point) along the global y-axis; +HydroDyn['PRPTVzi'] = False # (m/s); Translational velocity of the PRP (principal reference point) along the global z-axis; +HydroDyn['PRPRVxi'] = False # (rad/s); Rotation velocity of the PRP (principal reference point) about the global x-axis at the PRP; +HydroDyn['PRPRVyi'] = False # (rad/s); Rotation velocity of the PRP (principal reference point) about the global y-axis at the PRP; +HydroDyn['PRPRVzi'] = False # (rad/s); Rotation velocity of the PRP (principal reference point) about the global z-axis at the PRP; +HydroDyn['PRPTAxi'] = False # (m/s^2); Translational acceleration of the PRP (principal reference point) along the global x-axis; +HydroDyn['PRPTAyi'] = False # (m/s^2); Translational acceleration of the PRP (principal reference point) along the global y-axis; +HydroDyn['PRPTAzi'] = False # (m/s^2); Translational acceleration of the PRP (principal reference point) along the global z-axis; +HydroDyn['PRPRAxi'] = False # (rad/s^2); Rotation acceleration of the PRP (principal reference point) about the global x-axis at the PRP; +HydroDyn['PRPRAyi'] = False # (rad/s^2); Rotation acceleration of the PRP (principal reference point) about the global y-axis at the PRP; +HydroDyn['PRPRAzi'] = False # (rad/s^2); Rotation acceleration of the PRP (principal reference point) about the global z-axis at the PRP; + +# WAMIT Body Kinematics +HydroDyn['B1Surge'] = False # (m); Displacement of the 1st WAMIT body along the global x-axis; +HydroDyn['B1Sway'] = False # (m); Displacement of the 1st WAMIT body along the global y-axis; +HydroDyn['B1Heave'] = False # (m); Displacement of the 1st WAMIT body along the global z-axis; +HydroDyn['B1Roll'] = False # (rad); Rotation of the 1st WAMIT body about the global x-axis at the 1st WAMIT body's reference point; +HydroDyn['B1Pitch'] = False # (rad); Rotation of the 1st WAMIT body about the global y-axis at the 1st WAMIT body's reference point; +HydroDyn['B1Yaw'] = False # (rad); Rotation of the 1st WAMIT body about the global z-axis at the 1st WAMIT body's reference point; +HydroDyn['B1TVxi'] = False # (m/s); Translational velocity of the 1st WAMIT body along the global x-axis; +HydroDyn['B1TVyi'] = False # (m/s); Translational velocity of the 1st WAMIT body along the global y-axis; +HydroDyn['B1TVzi'] = False # (m/s); Translational velocity of the 1st WAMIT body along the global z-axis; +HydroDyn['B1RVxi'] = False # (rad/s); Rotational velocity of the 1st WAMIT body about the global x-axis at the 1st WAMIT body's reference point; +HydroDyn['B1RVyi'] = False # (rad/s); Rotational velocity of the 1st WAMIT body about the global y-axis at the 1st WAMIT body's reference point; +HydroDyn['B1RVzi'] = False # (rad/s); Rotational velocity of the 1st WAMIT body about the global z-axis at the 1st WAMIT body's reference point; +HydroDyn['B1TAxi'] = False # (m/s^2); Translational acceleration of the 1st WAMIT body along the global x-axis; +HydroDyn['B1TAyi'] = False # (m/s^2); Translational acceleration of the 1st WAMIT body along the global y-axis; +HydroDyn['B1TAzi'] = False # (m/s^2); Translational acceleration of the 1st WAMIT body along the global z-axis; +HydroDyn['B1RAxi'] = False # (rad/s^2); Rotational acceleration of the 1st WAMIT body about the global x-axis at the 1st WAMIT body's reference point; +HydroDyn['B1RAyi'] = False # (rad/s^2); Rotational acceleration of the 1st WAMIT body about the global y-axis at the 1st WAMIT body's reference point; +HydroDyn['B1RAzi'] = False # (rad/s^2); Rotational acceleration of the 1st WAMIT body about the global z-axis at the 1st WAMIT body's reference point; +HydroDyn['B2Surge'] = False # (m); Displacement of the 2nd WAMIT body along the global x-axis; +HydroDyn['B2Sway'] = False # (m); Displacement of the 2nd WAMIT body along the global y-axis; +HydroDyn['B2Heave'] = False # (m); Displacement of the 2nd WAMIT body along the global z-axis; +HydroDyn['B2Roll'] = False # (rad); Rotation of the 2nd WAMIT body about the global x-axis at the 2nd WAMIT body's reference point; +HydroDyn['B2Pitch'] = False # (rad); Rotation of the 2nd WAMIT body about the global y-axis at the 2nd WAMIT body's reference point; +HydroDyn['B2Yaw'] = False # (rad); Rotation of the 2nd WAMIT body about the global z-axis at the 2nd WAMIT body's reference point; +HydroDyn['B2TVxi'] = False # (m/s); Translational velocity of the 2nd WAMIT body along the global x-axis; +HydroDyn['B2TVyi'] = False # (m/s); Translational velocity of the 2nd WAMIT body along the global y-axis; +HydroDyn['B2TVzi'] = False # (m/s); Translational velocity of the 2nd WAMIT body along the global z-axis; +HydroDyn['B2RVxi'] = False # (rad/s); Rotational velocity of the 2nd WAMIT body about the global x-axis at the 2nd WAMIT body's reference point; +HydroDyn['B2RVyi'] = False # (rad/s); Rotational velocity of the 2nd WAMIT body about the global y-axis at the 2nd WAMIT body's reference point; +HydroDyn['B2RVzi'] = False # (rad/s); Rotational velocity of the 2nd WAMIT body about the global z-axis at the 2nd WAMIT body's reference point; +HydroDyn['B2TAxi'] = False # (m/s^2); Translational acceleration of the 2nd WAMIT body along the global x-axis; +HydroDyn['B2TAyi'] = False # (m/s^2); Translational acceleration of the 2nd WAMIT body along the global y-axis; +HydroDyn['B2TAzi'] = False # (m/s^2); Translational acceleration of the 2nd WAMIT body along the global z-axis; +HydroDyn['B2RAxi'] = False # (rad/s^2); Rotational acceleration of the 2nd WAMIT body about the global x-axis at the 2nd WAMIT body's reference point; +HydroDyn['B2RAyi'] = False # (rad/s^2); Rotational acceleration of the 2nd WAMIT body about the global y-axis at the 2nd WAMIT body's reference point; +HydroDyn['B2RAzi'] = False # (rad/s^2); Rotational acceleration of the 2nd WAMIT body about the global z-axis at the 2nd WAMIT body's reference point; +HydroDyn['B3Surge'] = False # (m); Displacement of the 3rd WAMIT body along the global x-axis; +HydroDyn['B3Sway'] = False # (m); Displacement of the 3rd WAMIT body along the global y-axis; +HydroDyn['B3Heave'] = False # (m); Displacement of the 3rd WAMIT body along the global z-axis; +HydroDyn['B3Roll'] = False # (rad); Rotation of the 3rd WAMIT body about the global x-axis at the 3rd WAMIT body's reference point; +HydroDyn['B3Pitch'] = False # (rad); Rotation of the 3rd WAMIT body about the global y-axis at the 3rd WAMIT body's reference point; +HydroDyn['B3Yaw'] = False # (rad); Rotation of the 3rd WAMIT body about the global z-axis at the 3rd WAMIT body's reference point; +HydroDyn['B3TVxi'] = False # (m/s); Translational velocity of the 3rd WAMIT body along the global x-axis; +HydroDyn['B3TVyi'] = False # (m/s); Translational velocity of the 3rd WAMIT body along the global y-axis; +HydroDyn['B3TVzi'] = False # (m/s); Translational velocity of the 3rd WAMIT body along the global z-axis; +HydroDyn['B3RVxi'] = False # (rad/s); Rotational velocity of the 3rd WAMIT body about the global x-axis at the 3rd WAMIT body's reference point; +HydroDyn['B3RVyi'] = False # (rad/s); Rotational velocity of the 3rd WAMIT body about the global y-axis at the 3rd WAMIT body's reference point; +HydroDyn['B3RVzi'] = False # (rad/s); Rotational velocity of the 3rd WAMIT body about the global z-axis at the 3rd WAMIT body's reference point; +HydroDyn['B3TAxi'] = False # (m/s^2); Translational acceleration of the 3rd WAMIT body along the global x-axis; +HydroDyn['B3TAyi'] = False # (m/s^2); Translational acceleration of the 3rd WAMIT body along the global y-axis; +HydroDyn['B3TAzi'] = False # (m/s^2); Translational acceleration of the 3rd WAMIT body along the global z-axis; +HydroDyn['B3RAxi'] = False # (rad/s^2); Rotational acceleration of the 3rd WAMIT body about the global x-axis at the 3rd WAMIT body's reference point; +HydroDyn['B3RAyi'] = False # (rad/s^2); Rotational acceleration of the 3rd WAMIT body about the global y-axis at the 3rd WAMIT body's reference point; +HydroDyn['B3RAzi'] = False # (rad/s^2); Rotational acceleration of the 3rd WAMIT body about the global z-axis at the 3rd WAMIT body's reference point; +HydroDyn['B4Surge'] = False # (m); Displacement of the 4th WAMIT body along the global x-axis; +HydroDyn['B4Sway'] = False # (m); Displacement of the 4th WAMIT body along the global y-axis; +HydroDyn['B4Heave'] = False # (m); Displacement of the 4th WAMIT body along the global z-axis; +HydroDyn['B4Roll'] = False # (rad); Rotation of the 4th WAMIT body about the global x-axis at the 4th WAMIT body's reference point; +HydroDyn['B4Pitch'] = False # (rad); Rotation of the 4th WAMIT body about the global y-axis at the 4th WAMIT body's reference point; +HydroDyn['B4Yaw'] = False # (rad); Rotation of the 4th WAMIT body about the global z-axis at the 4th WAMIT body's reference point; +HydroDyn['B4TVxi'] = False # (m/s); Translational velocity of the 4th WAMIT body along the global x-axis; +HydroDyn['B4TVyi'] = False # (m/s); Translational velocity of the 4th WAMIT body along the global y-axis; +HydroDyn['B4TVzi'] = False # (m/s); Translational velocity of the 4th WAMIT body along the global z-axis; +HydroDyn['B4RVxi'] = False # (rad/s); Rotational velocity of the 4th WAMIT body about the global x-axis at the 4th WAMIT body's reference point; +HydroDyn['B4RVyi'] = False # (rad/s); Rotational velocity of the 4th WAMIT body about the global y-axis at the 4th WAMIT body's reference point; +HydroDyn['B4RVzi'] = False # (rad/s); Rotational velocity of the 4th WAMIT body about the global z-axis at the 4th WAMIT body's reference point; +HydroDyn['B4TAxi'] = False # (m/s^2); Translational acceleration of the 4th WAMIT body along the global x-axis; +HydroDyn['B4TAyi'] = False # (m/s^2); Translational acceleration of the 4th WAMIT body along the global y-axis; +HydroDyn['B4TAzi'] = False # (m/s^2); Translational acceleration of the 4th WAMIT body along the global z-axis; +HydroDyn['B4RAxi'] = False # (rad/s^2); Rotational acceleration of the 4th WAMIT body about the global x-axis at the 4th WAMIT body's reference point; +HydroDyn['B4RAyi'] = False # (rad/s^2); Rotational acceleration of the 4th WAMIT body about the global y-axis at the 4th WAMIT body's reference point; +HydroDyn['B4RAzi'] = False # (rad/s^2); Rotational acceleration of the 4th WAMIT body about the global z-axis at the 4th WAMIT body's reference point; +HydroDyn['B5Surge'] = False # (m); Displacement of the 5th WAMIT body along the global x-axis; +HydroDyn['B5Sway'] = False # (m); Displacement of the 5th WAMIT body along the global y-axis; +HydroDyn['B5Heave'] = False # (m); Displacement of the 5th WAMIT body along the global z-axis; +HydroDyn['B5Roll'] = False # (rad); Rotation of the 5th WAMIT body about the global x-axis at the 5th WAMIT body's reference point; +HydroDyn['B5Pitch'] = False # (rad); Rotation of the 5th WAMIT body about the global y-axis at the 5th WAMIT body's reference point; +HydroDyn['B5Yaw'] = False # (rad); Rotation of the 5th WAMIT body about the global z-axis at the 5th WAMIT body's reference point; +HydroDyn['B5TVxi'] = False # (m/s); Translational velocity of the 5th WAMIT body along the global x-axis; +HydroDyn['B5TVyi'] = False # (m/s); Translational velocity of the 5th WAMIT body along the global y-axis; +HydroDyn['B5TVzi'] = False # (m/s); Translational velocity of the 5th WAMIT body along the global z-axis; +HydroDyn['B5RVxi'] = False # (rad/s); Rotational velocity of the 5th WAMIT body about the global x-axis at the 5th WAMIT body's reference point; +HydroDyn['B5RVyi'] = False # (rad/s); Rotational velocity of the 5th WAMIT body about the global y-axis at the 5th WAMIT body's reference point; +HydroDyn['B5RVzi'] = False # (rad/s); Rotational velocity of the 5th WAMIT body about the global z-axis at the 5th WAMIT body's reference point; +HydroDyn['B5TAxi'] = False # (m/s^2); Translational acceleration of the 5th WAMIT body along the global x-axis; +HydroDyn['B5TAyi'] = False # (m/s^2); Translational acceleration of the 5th WAMIT body along the global y-axis; +HydroDyn['B5TAzi'] = False # (m/s^2); Translational acceleration of the 5th WAMIT body along the global z-axis; +HydroDyn['B5RAxi'] = False # (rad/s^2); Rotational acceleration of the 5th WAMIT body about the global x-axis at the 5th WAMIT body's reference point; +HydroDyn['B5RAyi'] = False # (rad/s^2); Rotational acceleration of the 5th WAMIT body about the global y-axis at the 5th WAMIT body's reference point; +HydroDyn['B5RAzi'] = False # (rad/s^2); Rotational acceleration of the 5th WAMIT body about the global z-axis at the 5th WAMIT body's reference point; +HydroDyn['B6Surge'] = False # (m); Displacement of the 6th WAMIT body along the global x-axis; +HydroDyn['B6Sway'] = False # (m); Displacement of the 6th WAMIT body along the global y-axis; +HydroDyn['B6Heave'] = False # (m); Displacement of the 6th WAMIT body along the global z-axis; +HydroDyn['B6Roll'] = False # (rad); Rotation of the 6th WAMIT body about the global x-axis at the 6th WAMIT body's reference point; +HydroDyn['B6Pitch'] = False # (rad); Rotation of the 6th WAMIT body about the global y-axis at the 6th WAMIT body's reference point; +HydroDyn['B6Yaw'] = False # (rad); Rotation of the 6th WAMIT body about the global z-axis at the 6th WAMIT body's reference point; +HydroDyn['B6TVxi'] = False # (m/s); Translational velocity of the 6th WAMIT body along the global x-axis; +HydroDyn['B6TVyi'] = False # (m/s); Translational velocity of the 6th WAMIT body along the global y-axis; +HydroDyn['B6TVzi'] = False # (m/s); Translational velocity of the 6th WAMIT body along the global z-axis; +HydroDyn['B6RVxi'] = False # (rad/s); Rotational velocity of the 6th WAMIT body about the global x-axis at the 6th WAMIT body's reference point; +HydroDyn['B6RVyi'] = False # (rad/s); Rotational velocity of the 6th WAMIT body about the global y-axis at the 6th WAMIT body's reference point; +HydroDyn['B6RVzi'] = False # (rad/s); Rotational velocity of the 6th WAMIT body about the global z-axis at the 6th WAMIT body's reference point; +HydroDyn['B6TAxi'] = False # (m/s^2); Translational acceleration of the 6th WAMIT body along the global x-axis; +HydroDyn['B6TAyi'] = False # (m/s^2); Translational acceleration of the 6th WAMIT body along the global y-axis; +HydroDyn['B6TAzi'] = False # (m/s^2); Translational acceleration of the 6th WAMIT body along the global z-axis; +HydroDyn['B6RAxi'] = False # (rad/s^2); Rotational acceleration of the 6th WAMIT body about the global x-axis at the 6th WAMIT body's reference point; +HydroDyn['B6RAyi'] = False # (rad/s^2); Rotational acceleration of the 6th WAMIT body about the global y-axis at the 6th WAMIT body's reference point; +HydroDyn['B6RAzi'] = False # (rad/s^2); Rotational acceleration of the 6th WAMIT body about the global z-axis at the 6th WAMIT body's reference point; +HydroDyn['B7Surge'] = False # (m); Displacement of the 7th WAMIT body along the global x-axis; +HydroDyn['B7Sway'] = False # (m); Displacement of the 7th WAMIT body along the global y-axis; +HydroDyn['B7Heave'] = False # (m); Displacement of the 7th WAMIT body along the global z-axis; +HydroDyn['B7Roll'] = False # (rad); Rotation of the 7th WAMIT body about the global x-axis at the 7th WAMIT body's reference point; +HydroDyn['B7Pitch'] = False # (rad); Rotation of the 7th WAMIT body about the global y-axis at the 7th WAMIT body's reference point; +HydroDyn['B7Yaw'] = False # (rad); Rotation of the 7th WAMIT body about the global z-axis at the 7th WAMIT body's reference point; +HydroDyn['B7TVxi'] = False # (m/s); Translational velocity of the 7th WAMIT body along the global x-axis; +HydroDyn['B7TVyi'] = False # (m/s); Translational velocity of the 7th WAMIT body along the global y-axis; +HydroDyn['B7TVzi'] = False # (m/s); Translational velocity of the 7th WAMIT body along the global z-axis; +HydroDyn['B7RVxi'] = False # (rad/s); Rotational velocity of the 7th WAMIT body about the global x-axis at the 7th WAMIT body's reference point; +HydroDyn['B7RVyi'] = False # (rad/s); Rotational velocity of the 7th WAMIT body about the global y-axis at the 7th WAMIT body's reference point; +HydroDyn['B7RVzi'] = False # (rad/s); Rotational velocity of the 7th WAMIT body about the global z-axis at the 7th WAMIT body's reference point; +HydroDyn['B7TAxi'] = False # (m/s^2); Translational acceleration of the 7th WAMIT body along the global x-axis; +HydroDyn['B7TAyi'] = False # (m/s^2); Translational acceleration of the 7th WAMIT body along the global y-axis; +HydroDyn['B7TAzi'] = False # (m/s^2); Translational acceleration of the 7th WAMIT body along the global z-axis; +HydroDyn['B7RAxi'] = False # (rad/s^2); Rotational acceleration of the 7th WAMIT body about the global x-axis at the 7th WAMIT body's reference point; +HydroDyn['B7RAyi'] = False # (rad/s^2); Rotational acceleration of the 7th WAMIT body about the global y-axis at the 7th WAMIT body's reference point; +HydroDyn['B7RAzi'] = False # (rad/s^2); Rotational acceleration of the 7th WAMIT body about the global z-axis at the 7th WAMIT body's reference point; +HydroDyn['B8Surge'] = False # (m); Displacement of the 8th WAMIT body along the global x-axis; +HydroDyn['B8Sway'] = False # (m); Displacement of the 8th WAMIT body along the global y-axis; +HydroDyn['B8Heave'] = False # (m); Displacement of the 8th WAMIT body along the global z-axis; +HydroDyn['B8Roll'] = False # (rad); Rotation of the 8th WAMIT body about the global x-axis at the 8th WAMIT body's reference point; +HydroDyn['B8Pitch'] = False # (rad); Rotation of the 8th WAMIT body about the global y-axis at the 8th WAMIT body's reference point; +HydroDyn['B8Yaw'] = False # (rad); Rotation of the 8th WAMIT body about the global z-axis at the 8th WAMIT body's reference point; +HydroDyn['B8TVxi'] = False # (m/s); Translational velocity of the 8th WAMIT body along the global x-axis; +HydroDyn['B8TVyi'] = False # (m/s); Translational velocity of the 8th WAMIT body along the global y-axis; +HydroDyn['B8TVzi'] = False # (m/s); Translational velocity of the 8th WAMIT body along the global z-axis; +HydroDyn['B8RVxi'] = False # (rad/s); Rotational velocity of the 8th WAMIT body about the global x-axis at the 8th WAMIT body's reference point; +HydroDyn['B8RVyi'] = False # (rad/s); Rotational velocity of the 8th WAMIT body about the global y-axis at the 8th WAMIT body's reference point; +HydroDyn['B8RVzi'] = False # (rad/s); Rotational velocity of the 8th WAMIT body about the global z-axis at the 8th WAMIT body's reference point; +HydroDyn['B8TAxi'] = False # (m/s^2); Translational acceleration of the 8th WAMIT body along the global x-axis; +HydroDyn['B8TAyi'] = False # (m/s^2); Translational acceleration of the 8th WAMIT body along the global y-axis; +HydroDyn['B8TAzi'] = False # (m/s^2); Translational acceleration of the 8th WAMIT body along the global z-axis; +HydroDyn['B8RAxi'] = False # (rad/s^2); Rotational acceleration of the 8th WAMIT body about the global x-axis at the 8th WAMIT body's reference point; +HydroDyn['B8RAyi'] = False # (rad/s^2); Rotational acceleration of the 8th WAMIT body about the global y-axis at the 8th WAMIT body's reference point; +HydroDyn['B8RAzi'] = False # (rad/s^2); Rotational acceleration of the 8th WAMIT body about the global z-axis at the 8th WAMIT body's reference point; +HydroDyn['B9Surge'] = False # (m); Displacement of the 9th WAMIT body along the global x-axis; +HydroDyn['B9Sway'] = False # (m); Displacement of the 9th WAMIT body along the global y-axis; +HydroDyn['B9Heave'] = False # (m); Displacement of the 9th WAMIT body along the global z-axis; +HydroDyn['B9Roll'] = False # (rad); Rotation of the 9th WAMIT body about the global x-axis at the 9th WAMIT body's reference point; +HydroDyn['B9Pitch'] = False # (rad); Rotation of the 9th WAMIT body about the global y-axis at the 9th WAMIT body's reference point; +HydroDyn['B9Yaw'] = False # (rad); Rotation of the 9th WAMIT body about the global z-axis at the 9th WAMIT body's reference point; +HydroDyn['B9TVxi'] = False # (m/s); Translational velocity of the 9th WAMIT body along the global x-axis; +HydroDyn['B9TVyi'] = False # (m/s); Translational velocity of the 9th WAMIT body along the global y-axis; +HydroDyn['B9TVzi'] = False # (m/s); Translational velocity of the 9th WAMIT body along the global z-axis; +HydroDyn['B9RVxi'] = False # (rad/s); Rotational velocity of the 9th WAMIT body about the global x-axis at the 9th WAMIT body's reference point; +HydroDyn['B9RVyi'] = False # (rad/s); Rotational velocity of the 9th WAMIT body about the global y-axis at the 9th WAMIT body's reference point; +HydroDyn['B9RVzi'] = False # (rad/s); Rotational velocity of the 9th WAMIT body about the global z-axis at the 9th WAMIT body's reference point; +HydroDyn['B9TAxi'] = False # (m/s^2); Translational acceleration of the 9th WAMIT body along the global x-axis; +HydroDyn['B9TAyi'] = False # (m/s^2); Translational acceleration of the 9th WAMIT body along the global y-axis; +HydroDyn['B9TAzi'] = False # (m/s^2); Translational acceleration of the 9th WAMIT body along the global z-axis; +HydroDyn['B9RAxi'] = False # (rad/s^2); Rotational acceleration of the 9th WAMIT body about the global x-axis at the 9th WAMIT body's reference point; +HydroDyn['B9RAyi'] = False # (rad/s^2); Rotational acceleration of the 9th WAMIT body about the global y-axis at the 9th WAMIT body's reference point; +HydroDyn['B9RAzi'] = False # (rad/s^2); Rotational acceleration of the 9th WAMIT body about the global z-axis at the 9th WAMIT body's reference point; -# Wave Motions -HydroDyn['Wave1Elev'] = False # (m); ; -HydroDyn['Wave2Elev'] = False # (m); ; -HydroDyn['Wave3Elev'] = False # (m); ; -HydroDyn['Wave4Elev'] = False # (m); ; -HydroDyn['Wave5Elev'] = False # (m); ; -HydroDyn['Wave6Elev'] = False # (m); ; -HydroDyn['Wave7Elev'] = False # (m); ; -HydroDyn['Wave8Elev'] = False # (m); ; -HydroDyn['Wave9Elev'] = False # (m); ; - -# WRP Motions -HydroDyn['WRPSurge'] = False # (m); ; -HydroDyn['WRPSway'] = False # (m); ; -HydroDyn['WRPHeave'] = False # (m); ; -HydroDyn['WRPRoll'] = False # (rad); ; -HydroDyn['WRPPitch'] = False # (rad); ; -HydroDyn['WRPYaw'] = False # (rad); ; -HydroDyn['WRPTVxi'] = False # (m/s); ; -HydroDyn['WRPTVyi'] = False # (m/s); ; -HydroDyn['WRPTVzi'] = False # (m/s); ; -HydroDyn['WRPRVxi'] = False # (rad/s); ; -HydroDyn['WRPRVyi'] = False # (rad/s); ; -HydroDyn['WRPRVzi'] = False # (rad/s); ; -HydroDyn['WRPTAxi'] = False # (m/s^2); ; -HydroDyn['WRPTAyi'] = False # (m/s^2); ; -HydroDyn['WRPTAzi'] = False # (m/s^2); ; -HydroDyn['WRPRAxi'] = False # (rad/s^2); ; -HydroDyn['WRPRAyi'] = False # (rad/s^2); ; -HydroDyn['WRPRAzi'] = False # (rad/s^2); ; +# WAMIT Body Forces +HydroDyn['B1AddFxi'] = False # (N); Force along the global x-axis due to additional preload, stiffness, and damping of the 1st WAMIT body ; +HydroDyn['B1AddFyi'] = False # (N); Force along the global y-axis due to additional preload, stiffness, and damping of the 1st WAMIT body ; +HydroDyn['B1AddFzi'] = False # (N); Force along the global z-axis due to additional preload, stiffness, and damping of the 1st WAMIT body ; +HydroDyn['B1AddMxi'] = False # (N-m); Moment about the global x-axis at of the 1st WAMIT body's reference point due to additional preload, stiffness, and damping ; +HydroDyn['B1AddMyi'] = False # (N-m); Moment about the global y-axis at of the 1st WAMIT body's reference point due to additional preload, stiffness, and damping ; +HydroDyn['B1AddMzi'] = False # (N-m); Moment about the global z-axis at of the 1st WAMIT body's reference point due to additional preload, stiffness, and damping ; +HydroDyn['B1WvsF1xi'] = False # (N); First-order wave-excitation force at the 1st WAMIT body from diffraction along the global x-axis; +HydroDyn['B1WvsF1yi'] = False # (N); First-order wave-excitation force at the 1st WAMIT body from diffraction along the global y-axis; +HydroDyn['B1WvsF1zi'] = False # (N); First-order wave-excitation force at the 1st WAMIT body from diffraction along the global z-axis; +HydroDyn['B1WvsM1xi'] = False # (N-m); First-order wave-excitation moment at the 1st WAMIT body reference point from diffraction about the global x-axis; +HydroDyn['B1WvsM1yi'] = False # (N-m); First-order wave-excitation moment at the 1st WAMIT body reference point from diffraction about the global y-axis; +HydroDyn['B1WvsM1zi'] = False # (N-m); First-order wave-excitation moment at the 1st WAMIT body reference point from diffraction about the global z-axis; +HydroDyn['B1WvsFxi'] = False # (N); Total (first-order plus second-order) wave-excitation force at the 1st WAMIT body from diffraction along the global x-axis; +HydroDyn['B1WvsFyi'] = False # (N); Total (first-order plus second-order) wave-excitation force at the 1st WAMIT body from diffraction along the global y-axis; +HydroDyn['B1WvsFzi'] = False # (N); Total (first-order plus second-order) wave-excitation force at the 1st WAMIT body from diffraction along the global z-axis; +HydroDyn['B1WvsMxi'] = False # (N-m); Total (first-order plus second-order) wave-excitation moment at the 1st WAMIT body reference point from diffraction about the global x-axis; +HydroDyn['B1WvsMyi'] = False # (N-m); Total (first-order plus second-order) wave-excitation moment at the 1st WAMIT body reference point from diffraction about the global y-axis; +HydroDyn['B1WvsMzi'] = False # (N-m); Total (first-order plus second-order) wave-excitation moment at the 1st WAMIT body reference point from diffraction about the global z-axis; +HydroDyn['B1HdSFxi'] = False # (N); Hydrostatic force from the 1st WAMIT body along the global x-axis; +HydroDyn['B1HdSFyi'] = False # (N); Hydrostatic force from the 1st WAMIT body along the global y-axis; +HydroDyn['B1HdSFzi'] = False # (N); Hydrostatic force from the 1st WAMIT body along the global z-axis; +HydroDyn['B1HdSMxi'] = False # (N-m); Hydrostatic moment from the 1st WAMIT body about the global x-axis at the 1st WAMT body reference point; +HydroDyn['B1HdSMyi'] = False # (N-m); Hydrostatic moment from the 1st WAMIT body about the global y-axis at the 1st WAMT body reference point; +HydroDyn['B1HdSMzi'] = False # (N-m); Hydrostatic moment from the 1st WAMIT body about the global z-axis at the 1st WAMT body reference point; +HydroDyn['B1RdtFxi'] = False # (N); Wave-radiation force at the 1st WAMIT body along the global x-axis; +HydroDyn['B1RdtFyi'] = False # (N); Wave-radiation force at the 1st WAMIT body along the global y-axis; +HydroDyn['B1RdtFzi'] = False # (N); Wave-radiation force at the 1st WAMIT body along the global z-axis; +HydroDyn['B1RdtMxi'] = False # (N-m); Wave-radiation moment at the 1st WAMIT body about the global x-axis at the 1st WAMIT body's reference point; +HydroDyn['B1RdtMyi'] = False # (N-m); Wave-radiation moment at the 1st WAMIT body about the global y-axis at the 1st WAMIT body's reference point; +HydroDyn['B1RdtMzi'] = False # (N-m); Wave-radiation moment at the 1st WAMIT body about the global z-axis at the 1st WAMIT body's reference point; +HydroDyn['B2AddFxi'] = False # (N); Force along the global x-axis due to additional preload, stiffness, and damping of the 2nd WAMIT body ; +HydroDyn['B2AddFyi'] = False # (N); Force along the global y-axis due to additional preload, stiffness, and damping of the 2nd WAMIT body ; +HydroDyn['B2AddFzi'] = False # (N); Force along the global z-axis due to additional preload, stiffness, and damping of the 2nd WAMIT body ; +HydroDyn['B2AddMxi'] = False # (N-m); Moment about the global x-axis at of the 2nd WAMIT body's reference point due to additional preload, stiffness, and damping ; +HydroDyn['B2AddMyi'] = False # (N-m); Moment about the global y-axis at of the 2nd WAMIT body's reference point due to additional preload, stiffness, and damping ; +HydroDyn['B2AddMzi'] = False # (N-m); Moment about the global z-axis at of the 2nd WAMIT body's reference point due to additional preload, stiffness, and damping ; +HydroDyn['B2WvsF1xi'] = False # (N); First-order wave-excitation force at the 2nd WAMIT body from diffraction along the global x-axis; +HydroDyn['B2WvsF1yi'] = False # (N); First-order wave-excitation force at the 2nd WAMIT body from diffraction along the global y-axis; +HydroDyn['B2WvsF1zi'] = False # (N); First-order wave-excitation force at the 2nd WAMIT body from diffraction along the global z-axis; +HydroDyn['B2WvsM1xi'] = False # (N-m); First-order wave-excitation moment at the 2nd WAMIT body reference point from diffraction about the global x-axis; +HydroDyn['B2WvsM1yi'] = False # (N-m); First-order wave-excitation moment at the 2nd WAMIT body reference point from diffraction about the global y-axis; +HydroDyn['B2WvsM1zi'] = False # (N-m); First-order wave-excitation moment at the 2nd WAMIT body reference point from diffraction about the global z-axis; +HydroDyn['B2WvsFxi'] = False # (N); Total (first-order plus second-order) wave-excitation force at the 2nd WAMIT body from diffraction along the global x-axis; +HydroDyn['B2WvsFyi'] = False # (N); Total (first-order plus second-order) wave-excitation force at the 2nd WAMIT body from diffraction along the global y-axis; +HydroDyn['B2WvsFzi'] = False # (N); Total (first-order plus second-order) wave-excitation force at the 2nd WAMIT body from diffraction along the global z-axis; +HydroDyn['B2WvsMxi'] = False # (N-m); Total (first-order plus second-order) wave-excitation moment at the 2nd WAMIT body reference point from diffraction about the global x-axis; +HydroDyn['B2WvsMyi'] = False # (N-m); Total (first-order plus second-order) wave-excitation moment at the 2nd WAMIT body reference point from diffraction about the global y-axis; +HydroDyn['B2WvsMzi'] = False # (N-m); Total (first-order plus second-order) wave-excitation moment at the 2nd WAMIT body reference point from diffraction about the global z-axis; +HydroDyn['B2HdSFxi'] = False # (N); Hydrostatic force from the 2nd WAMIT body along the global x-axis; +HydroDyn['B2HdSFyi'] = False # (N); Hydrostatic force from the 2nd WAMIT body along the global y-axis; +HydroDyn['B2HdSFzi'] = False # (N); Hydrostatic force from the 2nd WAMIT body along the global z-axis; +HydroDyn['B2HdSMxi'] = False # (N-m); Hydrostatic moment from the 2nd WAMIT body about the global x-axis at the 2nd WAMT body reference point; +HydroDyn['B2HdSMyi'] = False # (N-m); Hydrostatic moment from the 2nd WAMIT body about the global y-axis at the 2nd WAMT body reference point; +HydroDyn['B2HdSMzi'] = False # (N-m); Hydrostatic moment from the 2nd WAMIT body about the global z-axis at the 2nd WAMT body reference point; +HydroDyn['B2RdtFxi'] = False # (N); Wave-radiation force at the 2nd WAMIT body along the global x-axis; +HydroDyn['B2RdtFyi'] = False # (N); Wave-radiation force at the 2nd WAMIT body along the global y-axis; +HydroDyn['B2RdtFzi'] = False # (N); Wave-radiation force at the 2nd WAMIT body along the global z-axis; +HydroDyn['B2RdtMxi'] = False # (N-m); Wave-radiation moment at the 2nd WAMIT body about the global x-axis at the 2nd WAMIT body's reference point; +HydroDyn['B2RdtMyi'] = False # (N-m); Wave-radiation moment at the 2nd WAMIT body about the global y-axis at the 2nd WAMIT body's reference point; +HydroDyn['B2RdtMzi'] = False # (N-m); Wave-radiation moment at the 2nd WAMIT body about the global z-axis at the 2nd WAMIT body's reference point; +HydroDyn['B3AddFxi'] = False # (N); Force along the global x-axis due to additional preload, stiffness, and damping of the 3rd WAMIT body ; +HydroDyn['B3AddFyi'] = False # (N); Force along the global y-axis due to additional preload, stiffness, and damping of the 3rd WAMIT body ; +HydroDyn['B3AddFzi'] = False # (N); Force along the global z-axis due to additional preload, stiffness, and damping of the 3rd WAMIT body ; +HydroDyn['B3AddMxi'] = False # (N-m); Moment about the global x-axis at of the 3rd WAMIT body's reference point due to additional preload, stiffness, and damping ; +HydroDyn['B3AddMyi'] = False # (N-m); Moment about the global y-axis at of the 3rd WAMIT body's reference point due to additional preload, stiffness, and damping ; +HydroDyn['B3AddMzi'] = False # (N-m); Moment about the global z-axis at of the 3rd WAMIT body's reference point due to additional preload, stiffness, and damping ; +HydroDyn['B3WvsF1xi'] = False # (N); First-order wave-excitation force at the 3rd WAMIT body from diffraction along the global x-axis; +HydroDyn['B3WvsF1yi'] = False # (N); First-order wave-excitation force at the 3rd WAMIT body from diffraction along the global y-axis; +HydroDyn['B3WvsF1zi'] = False # (N); First-order wave-excitation force at the 3rd WAMIT body from diffraction along the global z-axis; +HydroDyn['B3WvsM1xi'] = False # (N-m); First-order wave-excitation moment at the 3rd WAMIT body reference point from diffraction about the global x-axis; +HydroDyn['B3WvsM1yi'] = False # (N-m); First-order wave-excitation moment at the 3rd WAMIT body reference point from diffraction about the global y-axis; +HydroDyn['B3WvsM1zi'] = False # (N-m); First-order wave-excitation moment at the 3rd WAMIT body reference point from diffraction about the global z-axis; +HydroDyn['B3WvsFxi'] = False # (N); Total (first-order plus second-order) wave-excitation force at the 3rd WAMIT body from diffraction along the global x-axis; +HydroDyn['B3WvsFyi'] = False # (N); Total (first-order plus second-order) wave-excitation force at the 3rd WAMIT body from diffraction along the global y-axis; +HydroDyn['B3WvsFzi'] = False # (N); Total (first-order plus second-order) wave-excitation force at the 3rd WAMIT body from diffraction along the global z-axis; +HydroDyn['B3WvsMxi'] = False # (N-m); Total (first-order plus second-order) wave-excitation moment at the 3rd WAMIT body reference point from diffraction about the global x-axis; +HydroDyn['B3WvsMyi'] = False # (N-m); Total (first-order plus second-order) wave-excitation moment at the 3rd WAMIT body reference point from diffraction about the global y-axis; +HydroDyn['B3WvsMzi'] = False # (N-m); Total (first-order plus second-order) wave-excitation moment at the 3rd WAMIT body reference point from diffraction about the global z-axis; +HydroDyn['B3HdSFxi'] = False # (N); Hydrostatic force from the 3rd WAMIT body along the global x-axis; +HydroDyn['B3HdSFyi'] = False # (N); Hydrostatic force from the 3rd WAMIT body along the global y-axis; +HydroDyn['B3HdSFzi'] = False # (N); Hydrostatic force from the 3rd WAMIT body along the global z-axis; +HydroDyn['B3HdSMxi'] = False # (N-m); Hydrostatic moment from the 3rd WAMIT body about the global x-axis at the 3rd WAMT body reference point; +HydroDyn['B3HdSMyi'] = False # (N-m); Hydrostatic moment from the 3rd WAMIT body about the global y-axis at the 3rd WAMT body reference point; +HydroDyn['B3HdSMzi'] = False # (N-m); Hydrostatic moment from the 3rd WAMIT body about the global z-axis at the 3rd WAMT body reference point; +HydroDyn['B3RdtFxi'] = False # (N); Wave-radiation force at the 3rd WAMIT body along the global x-axis; +HydroDyn['B3RdtFyi'] = False # (N); Wave-radiation force at the 3rd WAMIT body along the global y-axis; +HydroDyn['B3RdtFzi'] = False # (N); Wave-radiation force at the 3rd WAMIT body along the global z-axis; +HydroDyn['B3RdtMxi'] = False # (N-m); Wave-radiation moment at the 3rd WAMIT body about the global x-axis at the 3rd WAMIT body's reference point; +HydroDyn['B3RdtMyi'] = False # (N-m); Wave-radiation moment at the 3rd WAMIT body about the global y-axis at the 3rd WAMIT body's reference point; +HydroDyn['B3RdtMzi'] = False # (N-m); Wave-radiation moment at the 3rd WAMIT body about the global z-axis at the 3rd WAMIT body's reference point; +HydroDyn['B4AddFxi'] = False # (N); Force along the global x-axis due to additional preload, stiffness, and damping of the 4th WAMIT body ; +HydroDyn['B4AddFyi'] = False # (N); Force along the global y-axis due to additional preload, stiffness, and damping of the 4th WAMIT body ; +HydroDyn['B4AddFzi'] = False # (N); Force along the global z-axis due to additional preload, stiffness, and damping of the 4th WAMIT body ; +HydroDyn['B4AddMxi'] = False # (N-m); Moment about the global x-axis at of the 4th WAMIT body's reference point due to additional preload, stiffness, and damping ; +HydroDyn['B4AddMyi'] = False # (N-m); Moment about the global y-axis at of the 4th WAMIT body's reference point due to additional preload, stiffness, and damping ; +HydroDyn['B4AddMzi'] = False # (N-m); Moment about the global z-axis at of the 4th WAMIT body's reference point due to additional preload, stiffness, and damping ; +HydroDyn['B4WvsF1xi'] = False # (N); First-order wave-excitation force at the 4th WAMIT body from diffraction along the global x-axis; +HydroDyn['B4WvsF1yi'] = False # (N); First-order wave-excitation force at the 4th WAMIT body from diffraction along the global y-axis; +HydroDyn['B4WvsF1zi'] = False # (N); First-order wave-excitation force at the 4th WAMIT body from diffraction along the global z-axis; +HydroDyn['B4WvsM1xi'] = False # (N-m); First-order wave-excitation moment at the 4th WAMIT body reference point from diffraction about the global x-axis; +HydroDyn['B4WvsM1yi'] = False # (N-m); First-order wave-excitation moment at the 4th WAMIT body reference point from diffraction about the global y-axis; +HydroDyn['B4WvsM1zi'] = False # (N-m); First-order wave-excitation moment at the 4th WAMIT body reference point from diffraction about the global z-axis; +HydroDyn['B4WvsFxi'] = False # (N); Total (first-order plus second-order) wave-excitation force at the 4th WAMIT body from diffraction along the global x-axis; +HydroDyn['B4WvsFyi'] = False # (N); Total (first-order plus second-order) wave-excitation force at the 4th WAMIT body from diffraction along the global y-axis; +HydroDyn['B4WvsFzi'] = False # (N); Total (first-order plus second-order) wave-excitation force at the 4th WAMIT body from diffraction along the global z-axis; +HydroDyn['B4WvsMxi'] = False # (N-m); Total (first-order plus second-order) wave-excitation moment at the 4th WAMIT body reference point from diffraction about the global x-axis; +HydroDyn['B4WvsMyi'] = False # (N-m); Total (first-order plus second-order) wave-excitation moment at the 4th WAMIT body reference point from diffraction about the global y-axis; +HydroDyn['B4WvsMzi'] = False # (N-m); Total (first-order plus second-order) wave-excitation moment at the 4th WAMIT body reference point from diffraction about the global z-axis; +HydroDyn['B4HdSFxi'] = False # (N); Hydrostatic force from the 4th WAMIT body along the global x-axis; +HydroDyn['B4HdSFyi'] = False # (N); Hydrostatic force from the 4th WAMIT body along the global y-axis; +HydroDyn['B4HdSFzi'] = False # (N); Hydrostatic force from the 4th WAMIT body along the global z-axis; +HydroDyn['B4HdSMxi'] = False # (N-m); Hydrostatic moment from the 4th WAMIT body about the global x-axis at the 4th WAMT body reference point; +HydroDyn['B4HdSMyi'] = False # (N-m); Hydrostatic moment from the 4th WAMIT body about the global y-axis at the 4th WAMT body reference point; +HydroDyn['B4HdSMzi'] = False # (N-m); Hydrostatic moment from the 4th WAMIT body about the global z-axis at the 4th WAMT body reference point; +HydroDyn['B4RdtFxi'] = False # (N); Wave-radiation force at the 4th WAMIT body along the global x-axis; +HydroDyn['B4RdtFyi'] = False # (N); Wave-radiation force at the 4th WAMIT body along the global y-axis; +HydroDyn['B4RdtFzi'] = False # (N); Wave-radiation force at the 4th WAMIT body along the global z-axis; +HydroDyn['B4RdtMxi'] = False # (N-m); Wave-radiation moment at the 4th WAMIT body about the global x-axis at the 4th WAMIT body's reference point; +HydroDyn['B4RdtMyi'] = False # (N-m); Wave-radiation moment at the 4th WAMIT body about the global y-axis at the 4th WAMIT body's reference point; +HydroDyn['B4RdtMzi'] = False # (N-m); Wave-radiation moment at the 4th WAMIT body about the global z-axis at the 4th WAMIT body's reference point; +HydroDyn['B5AddFxi'] = False # (N); Force along the global x-axis due to additional preload, stiffness, and damping of the 5th WAMIT body ; +HydroDyn['B5AddFyi'] = False # (N); Force along the global y-axis due to additional preload, stiffness, and damping of the 5th WAMIT body ; +HydroDyn['B5AddFzi'] = False # (N); Force along the global z-axis due to additional preload, stiffness, and damping of the 5th WAMIT body ; +HydroDyn['B5AddMxi'] = False # (N-m); Moment about the global x-axis at of the 5th WAMIT body's reference point due to additional preload, stiffness, and damping ; +HydroDyn['B5AddMyi'] = False # (N-m); Moment about the global y-axis at of the 5th WAMIT body's reference point due to additional preload, stiffness, and damping ; +HydroDyn['B5AddMzi'] = False # (N-m); Moment about the global z-axis at of the 5th WAMIT body's reference point due to additional preload, stiffness, and damping ; +HydroDyn['B5WvsF1xi'] = False # (N); First-order wave-excitation force at the 5th WAMIT body from diffraction along the global x-axis; +HydroDyn['B5WvsF1yi'] = False # (N); First-order wave-excitation force at the 5th WAMIT body from diffraction along the global y-axis; +HydroDyn['B5WvsF1zi'] = False # (N); First-order wave-excitation force at the 5th WAMIT body from diffraction along the global z-axis; +HydroDyn['B5WvsM1xi'] = False # (N-m); First-order wave-excitation moment at the 5th WAMIT body reference point from diffraction about the global x-axis; +HydroDyn['B5WvsM1yi'] = False # (N-m); First-order wave-excitation moment at the 5th WAMIT body reference point from diffraction about the global y-axis; +HydroDyn['B5WvsM1zi'] = False # (N-m); First-order wave-excitation moment at the 5th WAMIT body reference point from diffraction about the global z-axis; +HydroDyn['B5WvsFxi'] = False # (N); Total (first-order plus second-order) wave-excitation force at the 5th WAMIT body from diffraction along the global x-axis; +HydroDyn['B5WvsFyi'] = False # (N); Total (first-order plus second-order) wave-excitation force at the 5th WAMIT body from diffraction along the global y-axis; +HydroDyn['B5WvsFzi'] = False # (N); Total (first-order plus second-order) wave-excitation force at the 5th WAMIT body from diffraction along the global z-axis; +HydroDyn['B5WvsMxi'] = False # (N-m); Total (first-order plus second-order) wave-excitation moment at the 5th WAMIT body reference point from diffraction about the global x-axis; +HydroDyn['B5WvsMyi'] = False # (N-m); Total (first-order plus second-order) wave-excitation moment at the 5th WAMIT body reference point from diffraction about the global y-axis; +HydroDyn['B5WvsMzi'] = False # (N-m); Total (first-order plus second-order) wave-excitation moment at the 5th WAMIT body reference point from diffraction about the global z-axis; +HydroDyn['B5HdSFxi'] = False # (N); Hydrostatic force from the 5th WAMIT body along the global x-axis; +HydroDyn['B5HdSFyi'] = False # (N); Hydrostatic force from the 5th WAMIT body along the global y-axis; +HydroDyn['B5HdSFzi'] = False # (N); Hydrostatic force from the 5th WAMIT body along the global z-axis; +HydroDyn['B5HdSMxi'] = False # (N-m); Hydrostatic moment from the 5th WAMIT body about the global x-axis at the 5th WAMT body reference point; +HydroDyn['B5HdSMyi'] = False # (N-m); Hydrostatic moment from the 5th WAMIT body about the global y-axis at the 5th WAMT body reference point; +HydroDyn['B5HdSMzi'] = False # (N-m); Hydrostatic moment from the 5th WAMIT body about the global z-axis at the 5th WAMT body reference point; +HydroDyn['B5RdtFxi'] = False # (N); Wave-radiation force at the 5th WAMIT body along the global x-axis; +HydroDyn['B5RdtFyi'] = False # (N); Wave-radiation force at the 5th WAMIT body along the global y-axis; +HydroDyn['B5RdtFzi'] = False # (N); Wave-radiation force at the 5th WAMIT body along the global z-axis; +HydroDyn['B5RdtMxi'] = False # (N-m); Wave-radiation moment at the 5th WAMIT body about the global x-axis at the 5th WAMIT body's reference point; +HydroDyn['B5RdtMyi'] = False # (N-m); Wave-radiation moment at the 5th WAMIT body about the global y-axis at the 5th WAMIT body's reference point; +HydroDyn['B5RdtMzi'] = False # (N-m); Wave-radiation moment at the 5th WAMIT body about the global z-axis at the 5th WAMIT body's reference point; +HydroDyn['B6AddFxi'] = False # (N); Force along the global x-axis due to additional preload, stiffness, and damping of the 6th WAMIT body ; +HydroDyn['B6AddFyi'] = False # (N); Force along the global y-axis due to additional preload, stiffness, and damping of the 6th WAMIT body ; +HydroDyn['B6AddFzi'] = False # (N); Force along the global z-axis due to additional preload, stiffness, and damping of the 6th WAMIT body ; +HydroDyn['B6AddMxi'] = False # (N-m); Moment about the global x-axis at of the 6th WAMIT body's reference point due to additional preload, stiffness, and damping ; +HydroDyn['B6AddMyi'] = False # (N-m); Moment about the global y-axis at of the 6th WAMIT body's reference point due to additional preload, stiffness, and damping ; +HydroDyn['B6AddMzi'] = False # (N-m); Moment about the global z-axis at of the 6th WAMIT body's reference point due to additional preload, stiffness, and damping ; +HydroDyn['B6WvsF1xi'] = False # (N); First-order wave-excitation force at the 6th WAMIT body from diffraction along the global x-axis; +HydroDyn['B6WvsF1yi'] = False # (N); First-order wave-excitation force at the 6th WAMIT body from diffraction along the global y-axis; +HydroDyn['B6WvsF1zi'] = False # (N); First-order wave-excitation force at the 6th WAMIT body from diffraction along the global z-axis; +HydroDyn['B6WvsM1xi'] = False # (N-m); First-order wave-excitation moment at the 6th WAMIT body reference point from diffraction about the global x-axis; +HydroDyn['B6WvsM1yi'] = False # (N-m); First-order wave-excitation moment at the 6th WAMIT body reference point from diffraction about the global y-axis; +HydroDyn['B6WvsM1zi'] = False # (N-m); First-order wave-excitation moment at the 6th WAMIT body reference point from diffraction about the global z-axis; +HydroDyn['B6WvsFxi'] = False # (N); Total (first-order plus second-order) wave-excitation force at the 6th WAMIT body from diffraction along the global x-axis; +HydroDyn['B6WvsFyi'] = False # (N); Total (first-order plus second-order) wave-excitation force at the 6th WAMIT body from diffraction along the global y-axis; +HydroDyn['B6WvsFzi'] = False # (N); Total (first-order plus second-order) wave-excitation force at the 6th WAMIT body from diffraction along the global z-axis; +HydroDyn['B6WvsMxi'] = False # (N-m); Total (first-order plus second-order) wave-excitation moment at the 6th WAMIT body reference point from diffraction about the global x-axis; +HydroDyn['B6WvsMyi'] = False # (N-m); Total (first-order plus second-order) wave-excitation moment at the 6th WAMIT body reference point from diffraction about the global y-axis; +HydroDyn['B6WvsMzi'] = False # (N-m); Total (first-order plus second-order) wave-excitation moment at the 6th WAMIT body reference point from diffraction about the global z-axis; +HydroDyn['B6HdSFxi'] = False # (N); Hydrostatic force from the 6th WAMIT body along the global x-axis; +HydroDyn['B6HdSFyi'] = False # (N); Hydrostatic force from the 6th WAMIT body along the global y-axis; +HydroDyn['B6HdSFzi'] = False # (N); Hydrostatic force from the 6th WAMIT body along the global z-axis; +HydroDyn['B6HdSMxi'] = False # (N-m); Hydrostatic moment from the 6th WAMIT body about the global x-axis at the 6th WAMT body reference point; +HydroDyn['B6HdSMyi'] = False # (N-m); Hydrostatic moment from the 6th WAMIT body about the global y-axis at the 6th WAMT body reference point; +HydroDyn['B6HdSMzi'] = False # (N-m); Hydrostatic moment from the 6th WAMIT body about the global z-axis at the 6th WAMT body reference point; +HydroDyn['B6RdtFxi'] = False # (N); Wave-radiation force at the 6th WAMIT body along the global x-axis; +HydroDyn['B6RdtFyi'] = False # (N); Wave-radiation force at the 6th WAMIT body along the global y-axis; +HydroDyn['B6RdtFzi'] = False # (N); Wave-radiation force at the 6th WAMIT body along the global z-axis; +HydroDyn['B6RdtMxi'] = False # (N-m); Wave-radiation moment at the 6th WAMIT body about the global x-axis at the 6th WAMIT body's reference point; +HydroDyn['B6RdtMyi'] = False # (N-m); Wave-radiation moment at the 6th WAMIT body about the global y-axis at the 6th WAMIT body's reference point; +HydroDyn['B6RdtMzi'] = False # (N-m); Wave-radiation moment at the 6th WAMIT body about the global z-axis at the 6th WAMIT body's reference point; +HydroDyn['B7AddFxi'] = False # (N); Force along the global x-axis due to additional preload, stiffness, and damping of the 7th WAMIT body ; +HydroDyn['B7AddFyi'] = False # (N); Force along the global y-axis due to additional preload, stiffness, and damping of the 7th WAMIT body ; +HydroDyn['B7AddFzi'] = False # (N); Force along the global z-axis due to additional preload, stiffness, and damping of the 7th WAMIT body ; +HydroDyn['B7AddMxi'] = False # (N-m); Moment about the global x-axis at of the 7th WAMIT body's reference point due to additional preload, stiffness, and damping ; +HydroDyn['B7AddMyi'] = False # (N-m); Moment about the global y-axis at of the 7th WAMIT body's reference point due to additional preload, stiffness, and damping ; +HydroDyn['B7AddMzi'] = False # (N-m); Moment about the global z-axis at of the 7th WAMIT body's reference point due to additional preload, stiffness, and damping ; +HydroDyn['B7WvsF1xi'] = False # (N); First-order wave-excitation force at the 7th WAMIT body from diffraction along the global x-axis; +HydroDyn['B7WvsF1yi'] = False # (N); First-order wave-excitation force at the 7th WAMIT body from diffraction along the global y-axis; +HydroDyn['B7WvsF1zi'] = False # (N); First-order wave-excitation force at the 7th WAMIT body from diffraction along the global z-axis; +HydroDyn['B7WvsM1xi'] = False # (N-m); First-order wave-excitation moment at the 7th WAMIT body reference point from diffraction about the global x-axis; +HydroDyn['B7WvsM1yi'] = False # (N-m); First-order wave-excitation moment at the 7th WAMIT body reference point from diffraction about the global y-axis; +HydroDyn['B7WvsM1zi'] = False # (N-m); First-order wave-excitation moment at the 7th WAMIT body reference point from diffraction about the global z-axis; +HydroDyn['B7WvsFxi'] = False # (N); Total (first-order plus second-order) wave-excitation force at the 7th WAMIT body from diffraction along the global x-axis; +HydroDyn['B7WvsFyi'] = False # (N); Total (first-order plus second-order) wave-excitation force at the 7th WAMIT body from diffraction along the global y-axis; +HydroDyn['B7WvsFzi'] = False # (N); Total (first-order plus second-order) wave-excitation force at the 7th WAMIT body from diffraction along the global z-axis; +HydroDyn['B7WvsMxi'] = False # (N-m); Total (first-order plus second-order) wave-excitation moment at the 7th WAMIT body reference point from diffraction about the global x-axis; +HydroDyn['B7WvsMyi'] = False # (N-m); Total (first-order plus second-order) wave-excitation moment at the 7th WAMIT body reference point from diffraction about the global y-axis; +HydroDyn['B7WvsMzi'] = False # (N-m); Total (first-order plus second-order) wave-excitation moment at the 7th WAMIT body reference point from diffraction about the global z-axis; +HydroDyn['B7HdSFxi'] = False # (N); Hydrostatic force from the 7th WAMIT body along the global x-axis; +HydroDyn['B7HdSFyi'] = False # (N); Hydrostatic force from the 7th WAMIT body along the global y-axis; +HydroDyn['B7HdSFzi'] = False # (N); Hydrostatic force from the 7th WAMIT body along the global z-axis; +HydroDyn['B7HdSMxi'] = False # (N-m); Hydrostatic moment from the 7th WAMIT body about the global x-axis at the 7th WAMT body reference point; +HydroDyn['B7HdSMyi'] = False # (N-m); Hydrostatic moment from the 7th WAMIT body about the global y-axis at the 7th WAMT body reference point; +HydroDyn['B7HdSMzi'] = False # (N-m); Hydrostatic moment from the 7th WAMIT body about the global z-axis at the 7th WAMT body reference point; +HydroDyn['B7RdtFxi'] = False # (N); Wave-radiation force at the 7th WAMIT body along the global x-axis; +HydroDyn['B7RdtFyi'] = False # (N); Wave-radiation force at the 7th WAMIT body along the global y-axis; +HydroDyn['B7RdtFzi'] = False # (N); Wave-radiation force at the 7th WAMIT body along the global z-axis; +HydroDyn['B7RdtMxi'] = False # (N-m); Wave-radiation moment at the 7th WAMIT body about the global x-axis at the 7th WAMIT body's reference point; +HydroDyn['B7RdtMyi'] = False # (N-m); Wave-radiation moment at the 7th WAMIT body about the global y-axis at the 7th WAMIT body's reference point; +HydroDyn['B7RdtMzi'] = False # (N-m); Wave-radiation moment at the 7th WAMIT body about the global z-axis at the 7th WAMIT body's reference point; +HydroDyn['B8AddFxi'] = False # (N); Force along the global x-axis due to additional preload, stiffness, and damping of the 8th WAMIT body ; +HydroDyn['B8AddFyi'] = False # (N); Force along the global y-axis due to additional preload, stiffness, and damping of the 8th WAMIT body ; +HydroDyn['B8AddFzi'] = False # (N); Force along the global z-axis due to additional preload, stiffness, and damping of the 8th WAMIT body ; +HydroDyn['B8AddMxi'] = False # (N-m); Moment about the global x-axis at of the 8th WAMIT body's reference point due to additional preload, stiffness, and damping ; +HydroDyn['B8AddMyi'] = False # (N-m); Moment about the global y-axis at of the 8th WAMIT body's reference point due to additional preload, stiffness, and damping ; +HydroDyn['B8AddMzi'] = False # (N-m); Moment about the global z-axis at of the 8th WAMIT body's reference point due to additional preload, stiffness, and damping ; +HydroDyn['B8WvsF1xi'] = False # (N); First-order wave-excitation force at the 8th WAMIT body from diffraction along the global x-axis; +HydroDyn['B8WvsF1yi'] = False # (N); First-order wave-excitation force at the 8th WAMIT body from diffraction along the global y-axis; +HydroDyn['B8WvsF1zi'] = False # (N); First-order wave-excitation force at the 8th WAMIT body from diffraction along the global z-axis; +HydroDyn['B8WvsM1xi'] = False # (N-m); First-order wave-excitation moment at the 8th WAMIT body reference point from diffraction about the global x-axis; +HydroDyn['B8WvsM1yi'] = False # (N-m); First-order wave-excitation moment at the 8th WAMIT body reference point from diffraction about the global y-axis; +HydroDyn['B8WvsM1zi'] = False # (N-m); First-order wave-excitation moment at the 8th WAMIT body reference point from diffraction about the global z-axis; +HydroDyn['B8WvsFxi'] = False # (N); Total (first-order plus second-order) wave-excitation force at the 8th WAMIT body from diffraction along the global x-axis; +HydroDyn['B8WvsFyi'] = False # (N); Total (first-order plus second-order) wave-excitation force at the 8th WAMIT body from diffraction along the global y-axis; +HydroDyn['B8WvsFzi'] = False # (N); Total (first-order plus second-order) wave-excitation force at the 8th WAMIT body from diffraction along the global z-axis; +HydroDyn['B8WvsMxi'] = False # (N-m); Total (first-order plus second-order) wave-excitation moment at the 8th WAMIT body reference point from diffraction about the global x-axis; +HydroDyn['B8WvsMyi'] = False # (N-m); Total (first-order plus second-order) wave-excitation moment at the 8th WAMIT body reference point from diffraction about the global y-axis; +HydroDyn['B8WvsMzi'] = False # (N-m); Total (first-order plus second-order) wave-excitation moment at the 8th WAMIT body reference point from diffraction about the global z-axis; +HydroDyn['B8HdSFxi'] = False # (N); Hydrostatic force from the 8th WAMIT body along the global x-axis; +HydroDyn['B8HdSFyi'] = False # (N); Hydrostatic force from the 8th WAMIT body along the global y-axis; +HydroDyn['B8HdSFzi'] = False # (N); Hydrostatic force from the 8th WAMIT body along the global z-axis; +HydroDyn['B8HdSMxi'] = False # (N-m); Hydrostatic moment from the 8th WAMIT body about the global x-axis at the 8th WAMT body reference point; +HydroDyn['B8HdSMyi'] = False # (N-m); Hydrostatic moment from the 8th WAMIT body about the global y-axis at the 8th WAMT body reference point; +HydroDyn['B8HdSMzi'] = False # (N-m); Hydrostatic moment from the 8th WAMIT body about the global z-axis at the 8th WAMT body reference point; +HydroDyn['B8RdtFxi'] = False # (N); Wave-radiation force at the 8th WAMIT body along the global x-axis; +HydroDyn['B8RdtFyi'] = False # (N); Wave-radiation force at the 8th WAMIT body along the global y-axis; +HydroDyn['B8RdtFzi'] = False # (N); Wave-radiation force at the 8th WAMIT body along the global z-axis; +HydroDyn['B8RdtMxi'] = False # (N-m); Wave-radiation moment at the 8th WAMIT body about the global x-axis at the 8th WAMIT body's reference point; +HydroDyn['B8RdtMyi'] = False # (N-m); Wave-radiation moment at the 8th WAMIT body about the global y-axis at the 8th WAMIT body's reference point; +HydroDyn['B8RdtMzi'] = False # (N-m); Wave-radiation moment at the 8th WAMIT body about the global z-axis at the 8th WAMIT body's reference point; +HydroDyn['B9AddFxi'] = False # (N); Force along the global x-axis due to additional preload, stiffness, and damping of the 9th WAMIT body ; +HydroDyn['B9AddFyi'] = False # (N); Force along the global y-axis due to additional preload, stiffness, and damping of the 9th WAMIT body ; +HydroDyn['B9AddFzi'] = False # (N); Force along the global z-axis due to additional preload, stiffness, and damping of the 9th WAMIT body ; +HydroDyn['B9AddMxi'] = False # (N-m); Moment about the global x-axis at of the 9th WAMIT body's reference point due to additional preload, stiffness, and damping ; +HydroDyn['B9AddMyi'] = False # (N-m); Moment about the global y-axis at of the 9th WAMIT body's reference point due to additional preload, stiffness, and damping ; +HydroDyn['B9AddMzi'] = False # (N-m); Moment about the global z-axis at of the 9th WAMIT body's reference point due to additional preload, stiffness, and damping ; +HydroDyn['B9WvsF1xi'] = False # (N); First-order wave-excitation force at the 9th WAMIT body from diffraction along the global x-axis; +HydroDyn['B9WvsF1yi'] = False # (N); First-order wave-excitation force at the 9th WAMIT body from diffraction along the global y-axis; +HydroDyn['B9WvsF1zi'] = False # (N); First-order wave-excitation force at the 9th WAMIT body from diffraction along the global z-axis; +HydroDyn['B9WvsM1xi'] = False # (N-m); First-order wave-excitation moment at the 9th WAMIT body reference point from diffraction about the global x-axis; +HydroDyn['B9WvsM1yi'] = False # (N-m); First-order wave-excitation moment at the 9th WAMIT body reference point from diffraction about the global y-axis; +HydroDyn['B9WvsM1zi'] = False # (N-m); First-order wave-excitation moment at the 9th WAMIT body reference point from diffraction about the global z-axis; +HydroDyn['B9WvsFxi'] = False # (N); Total (first-order plus second-order) wave-excitation force at the 9th WAMIT body from diffraction along the global x-axis; +HydroDyn['B9WvsFyi'] = False # (N); Total (first-order plus second-order) wave-excitation force at the 9th WAMIT body from diffraction along the global y-axis; +HydroDyn['B9WvsFzi'] = False # (N); Total (first-order plus second-order) wave-excitation force at the 9th WAMIT body from diffraction along the global z-axis; +HydroDyn['B9WvsMxi'] = False # (N-m); Total (first-order plus second-order) wave-excitation moment at the 9th WAMIT body reference point from diffraction about the global x-axis; +HydroDyn['B9WvsMyi'] = False # (N-m); Total (first-order plus second-order) wave-excitation moment at the 9th WAMIT body reference point from diffraction about the global y-axis; +HydroDyn['B9WvsMzi'] = False # (N-m); Total (first-order plus second-order) wave-excitation moment at the 9th WAMIT body reference point from diffraction about the global z-axis; +HydroDyn['B9HdSFxi'] = False # (N); Hydrostatic force from the 9th WAMIT body along the global x-axis; +HydroDyn['B9HdSFyi'] = False # (N); Hydrostatic force from the 9th WAMIT body along the global y-axis; +HydroDyn['B9HdSFzi'] = False # (N); Hydrostatic force from the 9th WAMIT body along the global z-axis; +HydroDyn['B9HdSMxi'] = False # (N-m); Hydrostatic moment from the 9th WAMIT body about the global x-axis at the 9th WAMT body reference point; +HydroDyn['B9HdSMyi'] = False # (N-m); Hydrostatic moment from the 9th WAMIT body about the global y-axis at the 9th WAMT body reference point; +HydroDyn['B9HdSMzi'] = False # (N-m); Hydrostatic moment from the 9th WAMIT body about the global z-axis at the 9th WAMT body reference point; +HydroDyn['B9RdtFxi'] = False # (N); Wave-radiation force at the 9th WAMIT body along the global x-axis; +HydroDyn['B9RdtFyi'] = False # (N); Wave-radiation force at the 9th WAMIT body along the global y-axis; +HydroDyn['B9RdtFzi'] = False # (N); Wave-radiation force at the 9th WAMIT body along the global z-axis; +HydroDyn['B9RdtMxi'] = False # (N-m); Wave-radiation moment at the 9th WAMIT body about the global x-axis at the 9th WAMIT body's reference point; +HydroDyn['B9RdtMyi'] = False # (N-m); Wave-radiation moment at the 9th WAMIT body about the global y-axis at the 9th WAMIT body's reference point; +HydroDyn['B9RdtMzi'] = False # (N-m); Wave-radiation moment at the 9th WAMIT body about the global z-axis at the 9th WAMIT body's reference point; +HydroDyn['B1WvsF2xi'] = False # (N); Second-order wave-excitation force at the 1st WAMIT body from diffraction along the global x-axis; +HydroDyn['B1WvsF2yi'] = False # (N); Second-order wave-excitation force at the 1st WAMIT body from diffraction along the global y-axis; +HydroDyn['B1WvsF2zi'] = False # (N); Second-order wave-excitation force at the 1st WAMIT body from diffraction along the global z-axis; +HydroDyn['B1WvsM2xi'] = False # (N-m); Second-order wave-excitation moment at the 1st WAMIT body reference point from diffraction about the global x-axis; +HydroDyn['B1WvsM2yi'] = False # (N-m); Second-order wave-excitation moment at the 1st WAMIT body reference point from diffraction about the global y-axis; +HydroDyn['B1WvsM2zi'] = False # (N-m); Second-order wave-excitation moment at the 1st WAMIT body reference point from diffraction about the global z-axis; +HydroDyn['B2WvsF2xi'] = False # (N); Second-order wave-excitation force at the 2nd WAMIT body from diffraction along the global x-axis; +HydroDyn['B2WvsF2yi'] = False # (N); Second-order wave-excitation force at the 2nd WAMIT body from diffraction along the global y-axis; +HydroDyn['B2WvsF2zi'] = False # (N); Second-order wave-excitation force at the 2nd WAMIT body from diffraction along the global z-axis; +HydroDyn['B2WvsM2xi'] = False # (N-m); Second-order wave-excitation moment at the 2nd WAMIT body reference point from diffraction about the global x-axis; +HydroDyn['B2WvsM2yi'] = False # (N-m); Second-order wave-excitation moment at the 2nd WAMIT body reference point from diffraction about the global y-axis; +HydroDyn['B2WvsM2zi'] = False # (N-m); Second-order wave-excitation moment at the 2nd WAMIT body reference point from diffraction about the global z-axis; +HydroDyn['B3WvsF2xi'] = False # (N); Second-order wave-excitation force at the 3rd WAMIT body from diffraction along the global x-axis; +HydroDyn['B3WvsF2yi'] = False # (N); Second-order wave-excitation force at the 3rd WAMIT body from diffraction along the global y-axis; +HydroDyn['B3WvsF2zi'] = False # (N); Second-order wave-excitation force at the 3rd WAMIT body from diffraction along the global z-axis; +HydroDyn['B3WvsM2xi'] = False # (N-m); Second-order wave-excitation moment at the 3rd WAMIT body reference point from diffraction about the global x-axis; +HydroDyn['B3WvsM2yi'] = False # (N-m); Second-order wave-excitation moment at the 3rd WAMIT body reference point from diffraction about the global y-axis; +HydroDyn['B3WvsM2zi'] = False # (N-m); Second-order wave-excitation moment at the 3rd WAMIT body reference point from diffraction about the global z-axis; +HydroDyn['B4WvsF2xi'] = False # (N); Second-order wave-excitation force at the 4th WAMIT body from diffraction along the global x-axis; +HydroDyn['B4WvsF2yi'] = False # (N); Second-order wave-excitation force at the 4th WAMIT body from diffraction along the global y-axis; +HydroDyn['B4WvsF2zi'] = False # (N); Second-order wave-excitation force at the 4th WAMIT body from diffraction along the global z-axis; +HydroDyn['B4WvsM2xi'] = False # (N-m); Second-order wave-excitation moment at the 4th WAMIT body reference point from diffraction about the global x-axis; +HydroDyn['B4WvsM2yi'] = False # (N-m); Second-order wave-excitation moment at the 4th WAMIT body reference point from diffraction about the global y-axis; +HydroDyn['B4WvsM2zi'] = False # (N-m); Second-order wave-excitation moment at the 4th WAMIT body reference point from diffraction about the global z-axis; +HydroDyn['B5WvsF2xi'] = False # (N); Second-order wave-excitation force at the 5th WAMIT body from diffraction along the global x-axis; +HydroDyn['B5WvsF2yi'] = False # (N); Second-order wave-excitation force at the 5th WAMIT body from diffraction along the global y-axis; +HydroDyn['B5WvsF2zi'] = False # (N); Second-order wave-excitation force at the 5th WAMIT body from diffraction along the global z-axis; +HydroDyn['B5WvsM2xi'] = False # (N-m); Second-order wave-excitation moment at the 5th WAMIT body reference point from diffraction about the global x-axis; +HydroDyn['B5WvsM2yi'] = False # (N-m); Second-order wave-excitation moment at the 5th WAMIT body reference point from diffraction about the global y-axis; +HydroDyn['B5WvsM2zi'] = False # (N-m); Second-order wave-excitation moment at the 5th WAMIT body reference point from diffraction about the global z-axis; +HydroDyn['B6WvsF2xi'] = False # (N); Second-order wave-excitation force at the 6th WAMIT body from diffraction along the global x-axis; +HydroDyn['B6WvsF2yi'] = False # (N); Second-order wave-excitation force at the 6th WAMIT body from diffraction along the global y-axis; +HydroDyn['B6WvsF2zi'] = False # (N); Second-order wave-excitation force at the 6th WAMIT body from diffraction along the global z-axis; +HydroDyn['B6WvsM2xi'] = False # (N-m); Second-order wave-excitation moment at the 6th WAMIT body reference point from diffraction about the global x-axis; +HydroDyn['B6WvsM2yi'] = False # (N-m); Second-order wave-excitation moment at the 6th WAMIT body reference point from diffraction about the global y-axis; +HydroDyn['B6WvsM2zi'] = False # (N-m); Second-order wave-excitation moment at the 6th WAMIT body reference point from diffraction about the global z-axis; +HydroDyn['B7WvsF2xi'] = False # (N); Second-order wave-excitation force at the 7th WAMIT body from diffraction along the global x-axis; +HydroDyn['B7WvsF2yi'] = False # (N); Second-order wave-excitation force at the 7th WAMIT body from diffraction along the global y-axis; +HydroDyn['B7WvsF2zi'] = False # (N); Second-order wave-excitation force at the 7th WAMIT body from diffraction along the global z-axis; +HydroDyn['B7WvsM2xi'] = False # (N-m); Second-order wave-excitation moment at the 7th WAMIT body reference point from diffraction about the global x-axis; +HydroDyn['B7WvsM2yi'] = False # (N-m); Second-order wave-excitation moment at the 7th WAMIT body reference point from diffraction about the global y-axis; +HydroDyn['B7WvsM2zi'] = False # (N-m); Second-order wave-excitation moment at the 7th WAMIT body reference point from diffraction about the global z-axis; +HydroDyn['B8WvsF2xi'] = False # (N); Second-order wave-excitation force at the 8th WAMIT body from diffraction along the global x-axis; +HydroDyn['B8WvsF2yi'] = False # (N); Second-order wave-excitation force at the 8th WAMIT body from diffraction along the global y-axis; +HydroDyn['B8WvsF2zi'] = False # (N); Second-order wave-excitation force at the 8th WAMIT body from diffraction along the global z-axis; +HydroDyn['B8WvsM2xi'] = False # (N-m); Second-order wave-excitation moment at the 8th WAMIT body reference point from diffraction about the global x-axis; +HydroDyn['B8WvsM2yi'] = False # (N-m); Second-order wave-excitation moment at the 8th WAMIT body reference point from diffraction about the global y-axis; +HydroDyn['B8WvsM2zi'] = False # (N-m); Second-order wave-excitation moment at the 8th WAMIT body reference point from diffraction about the global z-axis; +HydroDyn['B9WvsF2xi'] = False # (N); Second-order wave-excitation force at the 9th WAMIT body from diffraction along the global x-axis; +HydroDyn['B9WvsF2yi'] = False # (N); Second-order wave-excitation force at the 9th WAMIT body from diffraction along the global y-axis; +HydroDyn['B9WvsF2zi'] = False # (N); Second-order wave-excitation force at the 9th WAMIT body from diffraction along the global z-axis; +HydroDyn['B9WvsM2xi'] = False # (N-m); Second-order wave-excitation moment at the 9th WAMIT body reference point from diffraction about the global x-axis; +HydroDyn['B9WvsM2yi'] = False # (N-m); Second-order wave-excitation moment at the 9th WAMIT body reference point from diffraction about the global y-axis; +HydroDyn['B9WvsM2zi'] = False # (N-m); Second-order wave-excitation moment at the 9th WAMIT body reference point from diffraction about the global z-axis; + +# Wave Elevations +HydroDyn['Wave1Elev'] = False # (m); Total (first-order plus second-order) wave elevation (global Z height) at the 1st user-requested location (location is specified in the global coordinate system); +HydroDyn['Wave2Elev'] = False # (m); Total (first-order plus second-order) wave elevation (global Z height) at the 2nd user-requested location (location is specified in the global coordinate system); +HydroDyn['Wave3Elev'] = False # (m); Total (first-order plus second-order) wave elevation (global Z height) at the 3rd user-requested location (location is specified in the global coordinate system); +HydroDyn['Wave4Elev'] = False # (m); Total (first-order plus second-order) wave elevation (global Z height) at the 4th user-requested location (location is specified in the global coordinate system); +HydroDyn['Wave5Elev'] = False # (m); Total (first-order plus second-order) wave elevation (global Z height) at the 5th user-requested location (location is specified in the global coordinate system); +HydroDyn['Wave6Elev'] = False # (m); Total (first-order plus second-order) wave elevation (global Z height) at the 6th user-requested location (location is specified in the global coordinate system); +HydroDyn['Wave7Elev'] = False # (m); Total (first-order plus second-order) wave elevation (global Z height) at the 7th user-requested location (location is specified in the global coordinate system); +HydroDyn['Wave8Elev'] = False # (m); Total (first-order plus second-order) wave elevation (global Z height) at the 8th user-requested location (location is specified in the global coordinate system); +HydroDyn['Wave9Elev'] = False # (m); Total (first-order plus second-order) wave elevation (global Z height) at the 9th user-requested location (location is specified in the global coordinate system); +HydroDyn['Wave1Elv1'] = False # (m); First-order wave elevation (global Z height) at the 1st user-requested location (location is specified in the global coordinate system); +HydroDyn['Wave2Elv1'] = False # (m); First-order wave elevation (global Z height) at the 2nd user-requested location (location is specified in the global coordinate system); +HydroDyn['Wave3Elv1'] = False # (m); First-order wave elevation (global Z height) at the 3rd user-requested location (location is specified in the global coordinate system); +HydroDyn['Wave4Elv1'] = False # (m); First-order wave elevation (global Z height) at the 4th user-requested location (location is specified in the global coordinate system); +HydroDyn['Wave5Elv1'] = False # (m); First-order wave elevation (global Z height) at the 5th user-requested location (location is specified in the global coordinate system); +HydroDyn['Wave6Elv1'] = False # (m); First-order wave elevation (global Z height) at the 6th user-requested location (location is specified in the global coordinate system); +HydroDyn['Wave7Elv1'] = False # (m); First-order wave elevation (global Z height) at the 7th user-requested location (location is specified in the global coordinate system); +HydroDyn['Wave8Elv1'] = False # (m); First-order wave elevation (global Z height) at the 8th user-requested location (location is specified in the global coordinate system); +HydroDyn['Wave9Elv1'] = False # (m); First-order wave elevation (global Z height) at the 9th user-requested location (location is specified in the global coordinate system); +HydroDyn['Wave1Elv2'] = False # (m); Second-order wave elevation (global Z height) at the 1st user-requested location (location is specified in the global coordinate system); +HydroDyn['Wave2Elv2'] = False # (m); Second-order wave elevation (global Z height) at the 2nd user-requested location (location is specified in the global coordinate system); +HydroDyn['Wave3Elv2'] = False # (m); Second-order wave elevation (global Z height) at the 3rd user-requested location (location is specified in the global coordinate system); +HydroDyn['Wave4Elv2'] = False # (m); Second-order wave elevation (global Z height) at the 4th user-requested location (location is specified in the global coordinate system); +HydroDyn['Wave5Elv2'] = False # (m); Second-order wave elevation (global Z height) at the 5th user-requested location (location is specified in the global coordinate system); +HydroDyn['Wave6Elv2'] = False # (m); Second-order wave elevation (global Z height) at the 6th user-requested location (location is specified in the global coordinate system); +HydroDyn['Wave7Elv2'] = False # (m); Second-order wave elevation (global Z height) at the 7th user-requested location (location is specified in the global coordinate system); +HydroDyn['Wave8Elv2'] = False # (m); Second-order wave elevation (global Z height) at the 8th user-requested location (location is specified in the global coordinate system); +HydroDyn['Wave9Elv2'] = False # (m); Second-order wave elevation (global Z height) at the 9th user-requested location (location is specified in the global coordinate system); """ Morison """ @@ -9421,6 +10884,9 @@ FstOutput['SubDyn'] = SubDyn FstOutput['BeamDyn'] = BeamDyn FstOutput['MoorDyn'] = MoorDyn +FstOutput['AeroDyn_Nodes'] = AeroDyn_Nodes +FstOutput['ElastoDyn_Nodes'] = ElastoDyn_Nodes +FstOutput['BeamDyn_Nodes'] = BeamDyn_Nodes """ Generated from FAST OutListParameters.xlsx files with AeroelasticSE/src/AeroelasticSE/Util/create_output_vars.py """ diff --git a/ROSCO_toolbox/ofTools/fast_io/FAST_writer.py b/ROSCO_toolbox/ofTools/fast_io/FAST_writer.py index 8dd91db3..7fcad436 100644 --- a/ROSCO_toolbox/ofTools/fast_io/FAST_writer.py +++ b/ROSCO_toolbox/ofTools/fast_io/FAST_writer.py @@ -5,7 +5,6 @@ from functools import reduce from ROSCO_toolbox.ofTools.fast_io.FAST_reader import InputReader_OpenFAST -from ROSCO_toolbox.ofTools.fast_io.FAST_vars import FstModel from ROSCO_toolbox.utilities import write_rotor_performance, write_DISCON ROSCO = True @@ -411,6 +410,20 @@ def write_ElastoDyn(self): f.write('"' + channel_list[i] + '"\n') f.write('END of input file (the word "END" must appear in the first 3 columns of this last OutList line)\n') + + # Optional nodal output section + if 'BldNd_BladesOut' in self.fst_vt['ElastoDyn']: + f.write('====== Outputs for all blade stations (same ending as above for B1N1.... =========================== [optional section]\n') + f.write('{:<22d} {:<11} {:}'.format(self.fst_vt['ElastoDyn']['BldNd_BladesOut'], 'BldNd_BladesOut', '- Number of blades to output all node information at. Up to number of blades on turbine. (-)\n')) + f.write('{!s:<22} {:<11} {:}'.format(self.fst_vt['ElastoDyn']['BldNd_BlOutNd'], 'BldNd_BlOutNd', '- Future feature will allow selecting a portion of the nodes to output. Not implemented yet. (-)\n')) + f.write(' OutList - The next line(s) contains a list of output parameters. See OutListParameters.xlsx, ElastoDyn_Nodes tab for a listing of available output channels, (-)\n') + + opt_outlist = self.get_outlist(self.fst_vt['outlist'], ['ElastoDyn_Nodes']) + for opt_channel_list in opt_outlist: + for i in range(len(opt_channel_list)): + f.write('"' + opt_channel_list[i] + '"\n') + f.write('END of input file (the word "END" must appear in the first 3 columns of this last OutList line)\n') + f.write('---------------------------------------------------------------------------------------\n') f.close() @@ -586,7 +599,21 @@ def write_BeamDyn(self): for channel_list in outlist: for i in range(len(channel_list)): f.write('"' + channel_list[i] + '"\n') - f.write('END of input file (the word "END" must appear in the first 3 columns of this last OutList line)') + f.write('END of input file (the word "END" must appear in the first 3 columns of this last OutList line)\n') + + # Optional nodal output section + if 'BldNd_BlOutNd' in self.fst_vt['BeamDyn']: + f.write('====== Outputs for all blade stations (same ending as above for B1N1.... =========================== [optional section]\n') + # f.write('{:<22d} {:<11} {:}'.format(self.fst_vt['BeamDyn']['BldNd_BladesOut'], 'BldNd_BladesOut', '- Number of blades to output all node information at. Up to number of blades on turbine. (-)\n')) + f.write('{!s:<22} {:<11} {:}'.format(self.fst_vt['BeamDyn']['BldNd_BlOutNd'], 'BldNd_BlOutNd', '- Future feature will allow selecting a portion of the nodes to output. Not implemented yet. (-)\n')) + f.write(' OutList - The next line(s) contains a list of output parameters. See OutListParameters.xlsx, BeamDyn_Nodes tab for a listing of available output channels, (-)\n') + + opt_outlist = self.get_outlist(self.fst_vt['outlist'], ['BeamDyn_Nodes']) + for opt_channel_list in opt_outlist: + for i in range(len(opt_channel_list)): + f.write('"' + opt_channel_list[i] + '"\n') + f.write('END of input file (the word "END" must appear in the first 3 columns of this last OutList line)\n') + f.write('---------------------------------------------------------------------------------------') f.close() @@ -639,6 +666,7 @@ def write_InflowWind(self): f.write('{:<22} {:<11} {:}'.format(self.fst_vt['InflowWind']['WindType'], 'WindType', '- switch for wind file type (1=steady; 2=uniform; 3=binary TurbSim FF; 4=binary Bladed-style FF; 5=HAWC format; 6=User defined; 7=native Bladed FF)\n')) f.write('{:<22} {:<11} {:}'.format(self.fst_vt['InflowWind']['PropagationDir'], 'PropagationDir', '- Direction of wind propagation (meteoroligical rotation from aligned with X (positive rotates towards -Y) -- degrees)\n')) f.write('{:<22} {:<11} {:}'.format(self.fst_vt['InflowWind']['VFlowAng'], 'VFlowAng', '- Upflow angle (degrees) (not used for native Bladed format WindType=7)\n')) + f.write('{!s:<22} {:<11} {:}'.format(self.fst_vt['InflowWind']['VelInterpCubic'], 'VelInterpCubic', '- Use cubic interpolation for velocity in time (false=linear, true=cubic) [Used with WindType=2,3,4,5,7]\n')) f.write('{:<22} {:<11} {:}'.format(self.fst_vt['InflowWind']['NWindVel'], 'NWindVel', '- Number of points to output the wind velocity (0 to 9)\n')) f.write('{:<22} {:<11} {:}'.format(self.fst_vt['InflowWind']['WindVxiList'], 'WindVxiList', '- List of coordinates in the inertial X direction (m)\n')) f.write('{:<22} {:<11} {:}'.format(self.fst_vt['InflowWind']['WindVyiList'], 'WindVyiList', '- List of coordinates in the inertial Y direction (m)\n')) @@ -681,6 +709,19 @@ def write_InflowWind(self): f.write('{:<22} {:<11} {:}'.format(self.fst_vt['InflowWind']['PLExp_Hawc'], 'PLExp_Hawc', '- Power law exponent (-) (used for PL wind profile type only)\n')) f.write('{:<22} {:<11} {:}'.format(self.fst_vt['InflowWind']['Z0'], 'Z0', '- Surface roughness length (m) (used for LG wind profile type only)\n')) f.write('{:<22} {:<11} {:}'.format(self.fst_vt['InflowWind']['XOffset'], 'XOffset', '- Initial offset in +x direction (shift of wind box) (-)\n')) + f.write('------------- LIDAR Parameters --------------------------------------------------------------------------\n') + f.write('{:<22} {:<11} {:}'.format(self.fst_vt['InflowWind']['SensorType'], 'SensorType', '- Switch for lidar configuration (0 = None, 1 = Single Point Beam(s), 2 = Continuous, 3 = Pulsed)\n')) + f.write('{:<22} {:<11} {:}'.format(self.fst_vt['InflowWind']['NumPulseGate'], 'NumPulseGate', '- Number of lidar measurement gates (used when SensorType = 3)\n')) + f.write('{:<22} {:<11} {:}'.format(self.fst_vt['InflowWind']['PulseSpacing'], 'PulseSpacing', '- Distance between range gates (m) (used when SensorType = 3)\n')) + f.write('{:<22} {:<11} {:}'.format(self.fst_vt['InflowWind']['NumBeam'], 'NumBeam', '- Number of lidar measurement beams (0-5)(used when SensorType = 1)\n')) + f.write('{:<22} {:<11} {:}'.format(self.fst_vt['InflowWind']['FocalDistanceX'], 'FocalDistanceX', '- Focal distance co-ordinates of the lidar beam in the x direction (relative to hub height) (only first coordinate used for SensorType 2 and 3) (m)\n')) + f.write('{:<22} {:<11} {:}'.format(self.fst_vt['InflowWind']['FocalDistanceY'], 'FocalDistanceY', '- Focal distance co-ordinates of the lidar beam in the y direction (relative to hub height) (only first coordinate used for SensorType 2 and 3) (m)\n')) + f.write('{:<22} {:<11} {:}'.format(self.fst_vt['InflowWind']['FocalDistanceZ'], 'FocalDistanceZ', '- Focal distance co-ordinates of the lidar beam in the z direction (relative to hub height) (only first coordinate used for SensorType 2 and 3) (m)\n')) + f.write('{:<22} {:<11} {:}'.format(', '.join(np.array(self.fst_vt['InflowWind']['RotorApexOffsetPos'], dtype=str)), 'RotorApexOffsetPos', '- Offset of the lidar from hub height (m)\n')) + f.write('{:<22} {:<11} {:}'.format(self.fst_vt['InflowWind']['URefLid'], 'URefLid', '- Reference average wind speed for the lidar[m/s]\n')) + f.write('{:<22} {:<11} {:}'.format(self.fst_vt['InflowWind']['MeasurementInterval'], 'MeasurementInterval', '- Time between each measurement [s]\n')) + f.write('{!s:<22} {:<11} {:}'.format(self.fst_vt['InflowWind']['LidRadialVel'], 'LidRadialVel', '- TRUE => return radial component, FALSE => return x direction estimate\n')) + f.write('{:<22} {:<11} {:}'.format(self.fst_vt['InflowWind']['ConsiderHubMotion'], 'ConsiderHubMotion', '- Flag whether to consider the hub motions impact on Lidar measurements\n')) f.write('====================== OUTPUT ==================================================\n') f.write('{!s:<22} {:<11} {:}'.format(self.fst_vt['InflowWind']['SumPrint'], 'SumPrint', '- Print summary data to .IfW.sum (flag)\n')) f.write('OutList - The next line(s) contains a list of output parameters. See OutListParameters.xlsx for a listing of available output channels, (-)\n') @@ -807,6 +848,20 @@ def write_AeroDyn15(self): for i in range(len(channel_list)): f.write('"' + channel_list[i] + '"\n') f.write('END of input file (the word "END" must appear in the first 3 columns of this last OutList line)\n') + + # Optional nodal output section + if 'BldNd_BladesOut' in self.fst_vt['AeroDyn15']: + f.write('====== Outputs for all blade stations (same ending as above for B1N1.... =========================== [optional section]\n') + f.write('{:<22d} {:<11} {:}'.format(self.fst_vt['AeroDyn15']['BldNd_BladesOut'], 'BldNd_BladesOut', '- Number of blades to output all node information at. Up to number of blades on turbine. (-)\n')) + f.write('{!s:<22} {:<11} {:}'.format(self.fst_vt['AeroDyn15']['BldNd_BlOutNd'], 'BldNd_BlOutNd', '- Future feature will allow selecting a portion of the nodes to output. Not implemented yet. (-)\n')) + f.write(' OutList - The next line(s) contains a list of output parameters. See OutListParameters.xlsx, AeroDyn_Nodes tab for a listing of available output channels, (-)\n') + + opt_outlist = self.get_outlist(self.fst_vt['outlist'], ['AeroDyn_Nodes']) + for opt_channel_list in opt_outlist: + for i in range(len(opt_channel_list)): + f.write('"' + opt_channel_list[i] + '"\n') + f.write('END of input file (the word "END" must appear in the first 3 columns of this last OutList line)\n') + f.write('---------------------------------------------------------------------------------------\n') f.close() @@ -1161,25 +1216,25 @@ def write_OLAF(self): f.write('{:<22d} {:<11} {:}'.format(self.fst_vt['AeroDyn15']['OLAF']['nFWPanelsFree'], 'nFWPanelsFree','- Number of free far-wake panels (-) {default: nFWPanels}\n')) f.write('{!s:<22} {:<11} {:}'.format(self.fst_vt['AeroDyn15']['OLAF']['FWShedVorticity'], 'FWShedVorticity','- Include shed vorticity in the far wake {default: False}\n')) f.write('------------------- WAKE REGULARIZATIONS AND DIFFUSION -----------------------------------------\n') - f.write('{:<22d} {:<11} {:}'.format(self.fst_vt['AeroDyn15']['OLAF']['DiffusionMethod'], 'DiffusionMethod','- Diffusion method to account for viscous effects {0: None, 1: Core Spreading, "default": 0}\n')) - f.write('{:<22d} {:<11} {:}'.format(self.fst_vt['AeroDyn15']['OLAF']['RegDeterMethod'], 'RegDeterMethod','- Method to determine the regularization parameters {0: Manual, 1: Optimized, 2: Chord, 3: Span, default: 0 }\n')) - f.write('{:<22d} {:<11} {:}'.format(self.fst_vt['AeroDyn15']['OLAF']['RegFunction'], 'RegFunction','- Viscous diffusion function {0: None, 1: Rankine, 2: LambOseen, 3: Vatistas, 4: Denominator, "default": 3} (switch)\n')) - f.write('{:<22d} {:<11} {:}'.format(self.fst_vt['AeroDyn15']['OLAF']['WakeRegMethod'], 'WakeRegMethod','- Wake regularization method {1: Constant, 2: Stretching, 3: Age, default: 3} (switch)\n')) + f.write('{:<22} {:<11} {:}'.format(self.fst_vt['AeroDyn15']['OLAF']['DiffusionMethod'], 'DiffusionMethod','- Diffusion method to account for viscous effects {0: None, 1: Core Spreading, "default": 0}\n')) + f.write('{:<22} {:<11} {:}'.format(self.fst_vt['AeroDyn15']['OLAF']['RegDeterMethod'], 'RegDeterMethod','- Method to determine the regularization parameters {0: Manual, 1: Optimized, 2: Chord, 3: Span, default: 0 }\n')) + f.write('{:<22} {:<11} {:}'.format(self.fst_vt['AeroDyn15']['OLAF']['RegFunction'], 'RegFunction','- Viscous diffusion function {0: None, 1: Rankine, 2: LambOseen, 3: Vatistas, 4: Denominator, "default": 3} (switch)\n')) + f.write('{:<22} {:<11} {:}'.format(self.fst_vt['AeroDyn15']['OLAF']['WakeRegMethod'], 'WakeRegMethod','- Wake regularization method {1: Constant, 2: Stretching, 3: Age, default: 3} (switch)\n')) f.write('{:<22} {:<11} {:}'.format(self.fst_vt['AeroDyn15']['OLAF']['WakeRegFactor'], 'WakeRegFactor','- Wake regularization factor (m)\n')) f.write('{:<22} {:<11} {:}'.format(self.fst_vt['AeroDyn15']['OLAF']['WingRegFactor'], 'WingRegFactor','- Wing regularization factor (m)\n')) f.write('{:<22} {:<11} {:}'.format(self.fst_vt['AeroDyn15']['OLAF']['CoreSpreadEddyVisc'], 'CoreSpreadEddyVisc','- Eddy viscosity in core spreading methods, typical values 1-1000\n')) f.write('------------------- WAKE TREATMENT OPTIONS ---------------------------------------------------\n') f.write('{!s:<22} {:<11} {:}'.format(self.fst_vt['AeroDyn15']['OLAF']['TwrShadowOnWake'], 'TwrShadowOnWake','- Include tower flow disturbance effects on wake convection {default:false} [only if TwrPotent or TwrShadow]\n')) - f.write('{:<22d} {:<11} {:}'.format(self.fst_vt['AeroDyn15']['OLAF']['ShearModel'], 'ShearModel','- Shear Model {0: No treatment, 1: Mirrored vorticity, default: 0}\n')) + f.write('{:<22} {:<11} {:}'.format(self.fst_vt['AeroDyn15']['OLAF']['ShearModel'], 'ShearModel','- Shear Model {0: No treatment, 1: Mirrored vorticity, default: 0}\n')) f.write('------------------- SPEEDUP OPTIONS -----------------------------------------------------------\n') f.write('{:<22d} {:<11} {:}'.format(self.fst_vt['AeroDyn15']['OLAF']['VelocityMethod'], 'VelocityMethod','- Method to determine the velocity {1:Segment N^2, 2:Particle tree, 3:Particle N^2, 4:Segment tree, default: 2}\n')) f.write('{:<22} {:<11} {:}'.format(self.fst_vt['AeroDyn15']['OLAF']['TreeBranchFactor'], 'TreeBranchFactor','- Branch radius fraction above which a multipole calculation is used {default: 1.5} [only if VelocityMethod=2,4]\n')) - f.write('{:<22d} {:<11} {:}'.format(self.fst_vt['AeroDyn15']['OLAF']['PartPerSegment'], 'PartPerSegment','- Number of particles per segment {default: 1} [only if VelocityMethod=2,3]\n')) + f.write('{:<22} {:<11} {:}'.format(self.fst_vt['AeroDyn15']['OLAF']['PartPerSegment'], 'PartPerSegment','- Number of particles per segment {default: 1} [only if VelocityMethod=2,3]\n')) f.write('===============================================================================================\n') f.write('--------------------------- OUTPUT OPTIONS ---------------------------------------------------\n') - f.write('{:<22d} {:<11} {:}'.format(self.fst_vt['AeroDyn15']['OLAF']['WrVTk'], 'WrVTk','- Outputs Visualization Toolkit (VTK) (independent of .fst option) {0: NoVTK, 1: Write VTK at VTK_fps, 2: Write VTK at init and final, default: 0} (flag)\n')) - f.write('{:<22d} {:<11} {:}'.format(self.fst_vt['AeroDyn15']['OLAF']['nVTKBlades'], 'nVTKBlades','- Number of blades for which VTK files are exported {0: No VTK per blade, n: VTK for blade 1 to n, default: 0} (-) \n')) - f.write('{:<22d} {:<11} {:}'.format(self.fst_vt['AeroDyn15']['OLAF']['VTKCoord'], 'VTKCoord','- Coordinate system used for VTK export. {1: Global, 2: Hub, 3: Both, default: 1} \n')) + f.write('{:<22} {:<11} {:}'.format(self.fst_vt['AeroDyn15']['OLAF']['WrVTk'], 'WrVTk','- Outputs Visualization Toolkit (VTK) (independent of .fst option) {0: NoVTK, 1: Write VTK at VTK_fps, 2: Write VTK at init and final, default: 0} (flag)\n')) + f.write('{:<22} {:<11} {:}'.format(self.fst_vt['AeroDyn15']['OLAF']['nVTKBlades'], 'nVTKBlades','- Number of blades for which VTK files are exported {0: No VTK per blade, n: VTK for blade 1 to n, default: 0} (-) \n')) + f.write('{:<22} {:<11} {:}'.format(self.fst_vt['AeroDyn15']['OLAF']['VTKCoord'], 'VTKCoord','- Coordinate system used for VTK export. {1: Global, 2: Hub, 3: Both, default: 1} \n')) f.write('{:<22} {:<11} {:}'.format(self.fst_vt['AeroDyn15']['OLAF']['VTK_fps'], 'VTK_fps','- Frame rate for VTK output (frames per second) {"all" for all glue code timesteps, "default" for all OLAF timesteps} [only if WrVTK=1]\n')) f.write('{:<22} {:<11} {:}'.format(self.fst_vt['AeroDyn15']['OLAF']['nGridOut'], 'nGridOut','- Number of grid outputs\n')) f.write('GridName GridType TStart TEnd DTGrid XStart XEnd nX YStart YEnd nY ZStart ZEnd nZ\n') @@ -1450,8 +1505,11 @@ def write_HydroDyn(self): for j in range(6): if type(self.fst_vt['HydroDyn']['AddF0'][j]) == float: ln = '{:14} '.format(self.fst_vt['HydroDyn']['AddF0'][j]) - elif type(self.fst_vt['HydroDyn']['AddF0'][j]) == list: + elif type(self.fst_vt['HydroDyn']['AddF0'][j]) in [list, np.ndarray]: ln = '{:14} '.format(' '.join([f'{val}' for val in self.fst_vt['HydroDyn']['AddF0'][j]])) + else: + raise Exception("Check type of self.fst_vt['HydroDyn']['AddF0']") + if j == 0: ln = ln + 'AddF0 - Additional preload (N, N-m) [If NBodyMod=1, one size 6*NBody x 1 vector; if NBodyMod>1, NBody size 6 x 1 vectors]\n' else: @@ -1939,15 +1997,15 @@ def write_MoorDyn(self): for i in range(len(self.fst_vt['MoorDyn']['Name'])): ln = [] ln.append('{:^11}'.format(self.fst_vt['MoorDyn']['Name'][i])) - ln.append('{:^11}'.format(self.fst_vt['MoorDyn']['Diam'][i])) - ln.append('{:^11}'.format(self.fst_vt['MoorDyn']['MassDen'][i])) - ln.append('{:^11}'.format(self.fst_vt['MoorDyn']['EA'][i])) - ln.append('{:^11}'.format(self.fst_vt['MoorDyn']['BA_zeta'][i])) - ln.append('{:^11}'.format(self.fst_vt['MoorDyn']['EI'][i])) - ln.append('{:^11}'.format(self.fst_vt['MoorDyn']['Cd'][i])) - ln.append('{:^11}'.format(self.fst_vt['MoorDyn']['Ca'][i])) - ln.append('{:^11}'.format(self.fst_vt['MoorDyn']['CdAx'][i])) - ln.append('{:^11}'.format(self.fst_vt['MoorDyn']['CaAx'][i])) + ln.append('{:^11.4f}'.format(self.fst_vt['MoorDyn']['Diam'][i])) + ln.append('{:^11.4f}'.format(self.fst_vt['MoorDyn']['MassDen'][i])) + ln.append('{:^11.4e}'.format(self.fst_vt['MoorDyn']['EA'][i])) + ln.append('{:^11.4f}'.format(self.fst_vt['MoorDyn']['BA_zeta'][i])) + ln.append('{:^11.4e}'.format(self.fst_vt['MoorDyn']['EI'][i])) + ln.append('{:^11.4f}'.format(self.fst_vt['MoorDyn']['Cd'][i])) + ln.append('{:^11.4f}'.format(self.fst_vt['MoorDyn']['Ca'][i])) + ln.append('{:^11.4f}'.format(self.fst_vt['MoorDyn']['CdAx'][i])) + ln.append('{:^11.4f}'.format(self.fst_vt['MoorDyn']['CaAx'][i])) f.write(" ".join(ln) + '\n') f.write('---------------------- POINTS --------------------------------\n') f.write(" ".join(['{:^11s}'.format(i) for i in ['ID', 'Attachment', 'X', 'Y', 'Z', 'M', 'V', 'CdA', 'CA']])+'\n') @@ -1956,13 +2014,13 @@ def write_MoorDyn(self): ln = [] ln.append('{:^11d}'.format(self.fst_vt['MoorDyn']['Point_ID'][i])) ln.append('{:^11}'.format(self.fst_vt['MoorDyn']['Attachment'][i])) - ln.append('{:^11}'.format(self.fst_vt['MoorDyn']['X'][i])) - ln.append('{:^11}'.format(self.fst_vt['MoorDyn']['Y'][i])) - ln.append('{:^11}'.format(self.fst_vt['MoorDyn']['Z'][i])) - ln.append('{:^11}'.format(self.fst_vt['MoorDyn']['M'][i])) - ln.append('{:^11}'.format(self.fst_vt['MoorDyn']['V'][i])) - ln.append('{:^11}'.format(self.fst_vt['MoorDyn']['CdA'][i])) - ln.append('{:^11}'.format(self.fst_vt['MoorDyn']['CA'][i])) + ln.append('{:^11.4f}'.format(self.fst_vt['MoorDyn']['X'][i])) + ln.append('{:^11.4f}'.format(self.fst_vt['MoorDyn']['Y'][i])) + ln.append('{:^11.4f}'.format(self.fst_vt['MoorDyn']['Z'][i])) + ln.append('{:^11.4e}'.format(self.fst_vt['MoorDyn']['M'][i])) + ln.append('{:^11.4e}'.format(self.fst_vt['MoorDyn']['V'][i])) + ln.append('{:^11.4f}'.format(self.fst_vt['MoorDyn']['CdA'][i])) + ln.append('{:^11.4f}'.format(self.fst_vt['MoorDyn']['CA'][i])) f.write(" ".join(ln) + '\n') f.write('---------------------- LINES --------------------------------------\n') f.write(" ".join(['{:^11s}'.format(i) for i in ['Line', 'LineType', 'AttachA', 'AttachB', 'UnstrLen', 'NumSegs', 'Outputs']])+'\n') @@ -1973,7 +2031,7 @@ def write_MoorDyn(self): ln.append('{:^11}'.format(self.fst_vt['MoorDyn']['LineType'][i])) ln.append('{:^11d}'.format(self.fst_vt['MoorDyn']['AttachA'][i])) ln.append('{:^11d}'.format(self.fst_vt['MoorDyn']['AttachB'][i])) - ln.append('{:^11}'.format(self.fst_vt['MoorDyn']['UnstrLen'][i])) + ln.append('{:^11.4f}'.format(self.fst_vt['MoorDyn']['UnstrLen'][i])) ln.append('{:^11d}'.format(self.fst_vt['MoorDyn']['NumSegs'][i])) ln.append('{:^11}'.format(self.fst_vt['MoorDyn']['Outputs'][i])) f.write(" ".join(ln) + '\n') diff --git a/ROSCO_toolbox/utilities.py b/ROSCO_toolbox/utilities.py index cf7f3218..da86cef2 100644 --- a/ROSCO_toolbox/utilities.py +++ b/ROSCO_toolbox/utilities.py @@ -30,6 +30,7 @@ from wisdem.inputs import load_yaml from wisdem.inputs import load_yaml +from ROSCO_toolbox.ofTools.util.FileTools import remove_numpy # Some useful constants now = datetime.datetime.now() @@ -294,7 +295,7 @@ def read_DISCON(DISCON_filename): if (line.split()[1] != '!'): # Array valued entries array_length = line.split().index('!') param = line.split()[array_length+1] - values = np.array( [float(x) for x in line.split()[:array_length]] ) + values = [float(x) for x in line.split()[:array_length]] DISCON_in[param] = values else: # All other entries param = line.split()[2] @@ -581,6 +582,8 @@ def DISCON_dict(turbine, controller, txt_filename=None): for param, value in controller.controller_params['DISCON'].items(): DISCON_dict[param] = value + # Make all lists, not numpy + DISCON_dict = remove_numpy(DISCON_dict) return DISCON_dict diff --git a/Test_Cases/BAR_10/BAR_10_InflowFile.dat b/Test_Cases/BAR_10/BAR_10_InflowFile.dat index 3cd7c48f..0cb641ac 100644 --- a/Test_Cases/BAR_10/BAR_10_InflowFile.dat +++ b/Test_Cases/BAR_10/BAR_10_InflowFile.dat @@ -5,6 +5,7 @@ False Echo - Echo input data to .ech (flag) 1 WindType - switch for wind file type (1=steady; 2=uniform; 3=binary TurbSim FF; 4=binary Bladed-style FF; 5=HAWC format; 6=User defined) 0.0 PropagationDir - Direction of wind propagation (meteoroligical rotation from aligned with X (positive rotates towards -Y) -- degrees) 0 VFlowAng - Upflow angle (degrees) (not used for native Bladed format WindType=7) +False VelInterpCubic - Use cubic interpolation for velocity in time (false=linear, true=cubic) [Used with WindType=2,3,4,5,7] 1 NWindVel - Number of points to output the wind velocity (0 to 9) 0.0 WindVxiList - List of coordinates in the inertial X direction (m) 0.0 WindVyiList - List of coordinates in the inertial Y direction (m) @@ -47,6 +48,19 @@ False TowerFile - Have tower file (.twr) (flag) 0.2 PLExp_Hawc - Power law exponent (-) (used for PL wind profile type only) 0.03 Z0 - Surface roughness length (m) (used for LG wind profile type only) 0 XOffset - Initial offset in +x direction (shift of wind box) +================== LIDAR Parameters =========================================================================== +0 SensorType - Switch for lidar configuration (0 = None, 1 = Single Point Beam(s), 2 = Continuous, 3 = Pulsed) +0 NumPulseGate - Number of lidar measurement gates (used when SensorType = 3) +30 PulseSpacing - Distance between range gates (m) (used when SensorType = 3) +0 NumBeam - Number of lidar measurement beams (0-5)(used when SensorType = 1) +-200 FocalDistanceX - Focal distance co-ordinates of the lidar beam in the x direction (relative to hub height) (only first coordinate used for SensorType 2 and 3) (m) +0 FocalDistanceY - Focal distance co-ordinates of the lidar beam in the y direction (relative to hub height) (only first coordinate used for SensorType 2 and 3) (m) +0 FocalDistanceZ - Focal distance co-ordinates of the lidar beam in the z direction (relative to hub height) (only first coordinate used for SensorType 2 and 3) (m) +0.0 0.0 0.0 RotorApexOffsetPos - Offset of the lidar from hub height (m) +17 URefLid - Reference average wind speed for the lidar[m/s] +0.25 MeasurementInterval - Time between each measurement [s] +False LidRadialVel - TRUE => return radial component, FALSE => return 'x' direction estimate +1 ConsiderHubMotion - Flag whether to consider the hub motion's impact on Lidar measurements ====================== OUTPUT ================================================== False SumPrint - Print summary data to .IfW.sum (flag) OutList - The next line(s) contains a list of output parameters. See OutListParameters.xlsx for a listing of available output channels, (-) diff --git a/Test_Cases/IEA-15-240-RWT-UMaineSemi/IEA-15-240-RWT_InflowFile.dat b/Test_Cases/IEA-15-240-RWT-UMaineSemi/IEA-15-240-RWT_InflowFile.dat index f7e3ccc8..bc188532 100644 --- a/Test_Cases/IEA-15-240-RWT-UMaineSemi/IEA-15-240-RWT_InflowFile.dat +++ b/Test_Cases/IEA-15-240-RWT-UMaineSemi/IEA-15-240-RWT_InflowFile.dat @@ -5,6 +5,7 @@ False Echo - Echo input data to .ech (flag) 1 WindType - switch for wind file type (1=steady; 2=uniform; 3=binary TurbSim FF; 4=binary Bladed-style FF; 5=HAWC format; 6=User defined; 7=native Bladed FF) 0.0 PropagationDir - Direction of wind propagation (meteoroligical rotation from aligned with X (positive rotates towards -Y) -- degrees) 0 VFlowAng - Upflow angle (degrees) (not used for native Bladed format WindType=7) +False VelInterpCubic - Use cubic interpolation for velocity in time (false=linear, true=cubic) [Used with WindType=2,3,4,5,7] 1 NWindVel - Number of points to output the wind velocity (0 to 9) 0.0 WindVxiList - List of coordinates in the inertial X direction (m) 0.0 WindVyiList - List of coordinates in the inertial Y direction (m) @@ -47,6 +48,19 @@ False TowerFile - Have tower file (.twr) (flag) 0.2 PLExp_Hawc - Power law exponent (-) (used for PL wind profile type only) 0.03 Z0 - Surface roughness length (m) (used for LG wind profile type only) 0 XOffset - Initial offset in +x direction (shift of wind box) +================== LIDAR Parameters =========================================================================== +0 SensorType - Switch for lidar configuration (0 = None, 1 = Single Point Beam(s), 2 = Continuous, 3 = Pulsed) +0 NumPulseGate - Number of lidar measurement gates (used when SensorType = 3) +30 PulseSpacing - Distance between range gates (m) (used when SensorType = 3) +0 NumBeam - Number of lidar measurement beams (0-5)(used when SensorType = 1) +-200 FocalDistanceX - Focal distance co-ordinates of the lidar beam in the x direction (relative to hub height) (only first coordinate used for SensorType 2 and 3) (m) +0 FocalDistanceY - Focal distance co-ordinates of the lidar beam in the y direction (relative to hub height) (only first coordinate used for SensorType 2 and 3) (m) +0 FocalDistanceZ - Focal distance co-ordinates of the lidar beam in the z direction (relative to hub height) (only first coordinate used for SensorType 2 and 3) (m) +0.0 0.0 0.0 RotorApexOffsetPos - Offset of the lidar from hub height (m) +17 URefLid - Reference average wind speed for the lidar[m/s] +0.25 MeasurementInterval - Time between each measurement [s] +False LidRadialVel - TRUE => return radial component, FALSE => return 'x' direction estimate +1 ConsiderHubMotion - Flag whether to consider the hub motion's impact on Lidar measurements ====================== OUTPUT ================================================== False SumPrint - Print summary data to .IfW.sum (flag) OutList - The next line(s) contains a list of output parameters. See OutListParameters.xlsx for a listing of available output channels, (-) diff --git a/Test_Cases/IEA-15-240-RWT-UMaineSemi/StC-Force-Col1.dat b/Test_Cases/IEA-15-240-RWT-UMaineSemi/StC-Force-Col1.dat index 5709eb5f..c35e51c9 100644 --- a/Test_Cases/IEA-15-240-RWT-UMaineSemi/StC-Force-Col1.dat +++ b/Test_Cases/IEA-15-240-RWT-UMaineSemi/StC-Force-Col1.dat @@ -3,7 +3,7 @@ Input file for tuned mass damper, module by Matt Lackner, Meghan Glade, and Semy ---------------------- SIMULATION CONTROL -------------------------------------- True Echo - Echo input data to .ech (flag) ---------------------- StC DEGREES OF FREEDOM ---------------------------------- - 5 StC_DOF_MODE - DOF mode (switch) {0: No StC or TLCD DOF; 1: StC_X_DOF, StC_Y_DOF, and/or StC_Z_DOF (three independent StC DOFs); 2: StC_XY_DOF (Omni-Directional StC); 3: TLCD; 4: Prescribed force/moment time series} + 5 StC_DOF_MODE - DOF mode (switch) {0: No StC or TLCD DOF; 1: StC_X_DOF, StC_Y_DOF, and/or StC_Z_DOF (three independent StC DOFs); 2: StC_XY_DOF (Omni-Directional StC); 3: TLCD; 4: Prescribed force/moment time series; 5: Force determined by external DLL} false StC_X_DOF - DOF on or off for StC X (flag) [Used only when StC_DOF_MODE=1] false StC_Y_DOF - DOF on or off for StC Y (flag) [Used only when StC_DOF_MODE=1] false StC_Z_DOF - DOF on or off for StC Z (flag) [Used only when StC_DOF_MODE=1] @@ -92,4 +92,4 @@ False Use_F_TBL - Use spring force from user-defined table (flag) ---------------------- PRESCRIBED TIME SERIES --------------------------------- [used only when StC_DOF_MODE=4] 1 PrescribedForcesCoord- Prescribed forces are in global or local coordinates (switch) {1: global; 2: local} "Bld-TimeForceSeries.dat" PrescribedForcesFile - Time series force and moment (7 columns of time, FX, FY, FZ, MX, MY, MZ) -------------------------------------------------------------------------------- \ No newline at end of file +------------------------------------------------------------------------------- diff --git a/Test_Cases/IEA-15-240-RWT-UMaineSemi/StC-Force-Col2.dat b/Test_Cases/IEA-15-240-RWT-UMaineSemi/StC-Force-Col2.dat index 83e86cf8..768c74a8 100644 --- a/Test_Cases/IEA-15-240-RWT-UMaineSemi/StC-Force-Col2.dat +++ b/Test_Cases/IEA-15-240-RWT-UMaineSemi/StC-Force-Col2.dat @@ -3,7 +3,7 @@ Input file for tuned mass damper, module by Matt Lackner, Meghan Glade, and Semy ---------------------- SIMULATION CONTROL -------------------------------------- True Echo - Echo input data to .ech (flag) ---------------------- StC DEGREES OF FREEDOM ---------------------------------- - 5 StC_DOF_MODE - DOF mode (switch) {0: No StC or TLCD DOF; 1: StC_X_DOF, StC_Y_DOF, and/or StC_Z_DOF (three independent StC DOFs); 2: StC_XY_DOF (Omni-Directional StC); 3: TLCD; 4: Prescribed force/moment time series} + 5 StC_DOF_MODE - DOF mode (switch) {0: No StC or TLCD DOF; 1: StC_X_DOF, StC_Y_DOF, and/or StC_Z_DOF (three independent StC DOFs); 2: StC_XY_DOF (Omni-Directional StC); 3: TLCD; 4: Prescribed force/moment time series; 5: Force determined by external DLL} false StC_X_DOF - DOF on or off for StC X (flag) [Used only when StC_DOF_MODE=1] false StC_Y_DOF - DOF on or off for StC Y (flag) [Used only when StC_DOF_MODE=1] false StC_Z_DOF - DOF on or off for StC Z (flag) [Used only when StC_DOF_MODE=1] @@ -92,4 +92,4 @@ False Use_F_TBL - Use spring force from user-defined table (flag) ---------------------- PRESCRIBED TIME SERIES --------------------------------- [used only when StC_DOF_MODE=4] 1 PrescribedForcesCoord- Prescribed forces are in global or local coordinates (switch) {1: global; 2: local} "Bld-TimeForceSeries.dat" PrescribedForcesFile - Time series force and moment (7 columns of time, FX, FY, FZ, MX, MY, MZ) -------------------------------------------------------------------------------- \ No newline at end of file +------------------------------------------------------------------------------- diff --git a/Test_Cases/IEA-15-240-RWT-UMaineSemi/StC-Force-Col3.dat b/Test_Cases/IEA-15-240-RWT-UMaineSemi/StC-Force-Col3.dat index 0488dc80..c9c5bc66 100644 --- a/Test_Cases/IEA-15-240-RWT-UMaineSemi/StC-Force-Col3.dat +++ b/Test_Cases/IEA-15-240-RWT-UMaineSemi/StC-Force-Col3.dat @@ -3,7 +3,7 @@ Input file for tuned mass damper, module by Matt Lackner, Meghan Glade, and Semy ---------------------- SIMULATION CONTROL -------------------------------------- True Echo - Echo input data to .ech (flag) ---------------------- StC DEGREES OF FREEDOM ---------------------------------- - 5 StC_DOF_MODE - DOF mode (switch) {0: No StC or TLCD DOF; 1: StC_X_DOF, StC_Y_DOF, and/or StC_Z_DOF (three independent StC DOFs); 2: StC_XY_DOF (Omni-Directional StC); 3: TLCD; 4: Prescribed force/moment time series} + 5 StC_DOF_MODE - DOF mode (switch) {0: No StC or TLCD DOF; 1: StC_X_DOF, StC_Y_DOF, and/or StC_Z_DOF (three independent StC DOFs); 2: StC_XY_DOF (Omni-Directional StC); 3: TLCD; 4: Prescribed force/moment time series; 5: Force determined by external DLL} false StC_X_DOF - DOF on or off for StC X (flag) [Used only when StC_DOF_MODE=1] false StC_Y_DOF - DOF on or off for StC Y (flag) [Used only when StC_DOF_MODE=1] false StC_Z_DOF - DOF on or off for StC Z (flag) [Used only when StC_DOF_MODE=1] @@ -92,4 +92,4 @@ False Use_F_TBL - Use spring force from user-defined table (flag) ---------------------- PRESCRIBED TIME SERIES --------------------------------- [used only when StC_DOF_MODE=4] 1 PrescribedForcesCoord- Prescribed forces are in global or local coordinates (switch) {1: global; 2: local} "Bld-TimeForceSeries.dat" PrescribedForcesFile - Time series force and moment (7 columns of time, FX, FY, FZ, MX, MY, MZ) -------------------------------------------------------------------------------- \ No newline at end of file +------------------------------------------------------------------------------- diff --git a/Test_Cases/NREL-5MW/NRELOffshrBsline5MW_InflowWind.dat b/Test_Cases/NREL-5MW/NRELOffshrBsline5MW_InflowWind.dat index 3fd8bc13..13a784f1 100644 --- a/Test_Cases/NREL-5MW/NRELOffshrBsline5MW_InflowWind.dat +++ b/Test_Cases/NREL-5MW/NRELOffshrBsline5MW_InflowWind.dat @@ -5,6 +5,7 @@ False Echo - Echo input data to .ech (flag) 1 WindType - switch for wind file type (1=steady; 2=uniform; 3=binary TurbSim FF; 4=binary Bladed-style FF; 5=HAWC format; 6=User defined) 0 PropagationDir - Direction of wind propagation (meteoroligical rotation from aligned with X (positive rotates towards -Y) -- degrees) 0 VFlowAng - Upflow angle (degrees) (not used for native Bladed format WindType=7) +False VelInterpCubic - Use cubic interpolation for velocity in time (false=linear, true=cubic) [Used with WindType=2,3,4,5,7] 1 NWindVel - Number of points to output the wind velocity (0 to 9) 0 WindVxiList - List of coordinates in the inertial X direction (m) 0 WindVyiList - List of coordinates in the inertial Y direction (m) @@ -47,6 +48,19 @@ False TowerFile - Have tower file (.twr) (flag) ignored when WindTy 0.2 PLExp_Hawc - Power law exponent (-) (used for PL wind profile type only) 0.03 Z0 - Surface roughness length (m) (used for LG wind profile type only) 0 XOffset - Initial offset in +x direction (shift of wind box) +================== LIDAR Parameters =========================================================================== +0 SensorType - Switch for lidar configuration (0 = None, 1 = Single Point Beam(s), 2 = Continuous, 3 = Pulsed) +0 NumPulseGate - Number of lidar measurement gates (used when SensorType = 3) +30 PulseSpacing - Distance between range gates (m) (used when SensorType = 3) +0 NumBeam - Number of lidar measurement beams (0-5)(used when SensorType = 1) +-200 FocalDistanceX - Focal distance co-ordinates of the lidar beam in the x direction (relative to hub height) (only first coordinate used for SensorType 2 and 3) (m) +0 FocalDistanceY - Focal distance co-ordinates of the lidar beam in the y direction (relative to hub height) (only first coordinate used for SensorType 2 and 3) (m) +0 FocalDistanceZ - Focal distance co-ordinates of the lidar beam in the z direction (relative to hub height) (only first coordinate used for SensorType 2 and 3) (m) +0.0 0.0 0.0 RotorApexOffsetPos - Offset of the lidar from hub height (m) +17 URefLid - Reference average wind speed for the lidar[m/s] +0.25 MeasurementInterval - Time between each measurement [s] +False LidRadialVel - TRUE => return radial component, FALSE => return 'x' direction estimate +1 ConsiderHubMotion - Flag whether to consider the hub motion's impact on Lidar measurements ====================== OUTPUT ================================================== False SumPrint - Print summary data to .IfW.sum (flag) OutList - The next line(s) contains a list of output parameters. See OutListParameters.xlsx for a listing of available output channels, (-) diff --git a/Test_Cases/NREL_2p8_127/NREL-2p8-127_InflowFile.dat b/Test_Cases/NREL_2p8_127/NREL-2p8-127_InflowFile.dat index 401fd0a0..f1e0f032 100644 --- a/Test_Cases/NREL_2p8_127/NREL-2p8-127_InflowFile.dat +++ b/Test_Cases/NREL_2p8_127/NREL-2p8-127_InflowFile.dat @@ -5,6 +5,7 @@ False Echo - Echo input data to .ech (flag) 1 WindType - switch for wind file type (1=steady; 2=uniform; 3=binary TurbSim FF; 4=binary Bladed-style FF; 5=HAWC format; 6=User defined; 7=native Bladed FF) 0.0 PropagationDir - Direction of wind propagation (meteoroligical rotation from aligned with X (positive rotates towards -Y) -- degrees) 0.0 VFlowAng - Upflow angle (degrees) (not used for native Bladed format WindType=7) +False VelInterpCubic - Use cubic interpolation for velocity in time (false=linear, true=cubic) [Used with WindType=2,3,4,5,7] 1 NWindVel - Number of points to output the wind velocity (0 to 9) 0.0 WindVxiList - List of coordinates in the inertial X direction (m) 0.0 WindVyiList - List of coordinates in the inertial Y direction (m) @@ -47,6 +48,19 @@ False TowerFile - Have tower file (.twr) (flag) 0.0 PLExp_Hawc - Power law exponent (-) (used for PL wind profile type only) 0.0 Z0 - Surface roughness length (m) (used for LG wind profile type only) 0 XOffset - Initial offset in +x direction (shift of wind box) (-) +================== LIDAR Parameters =========================================================================== +0 SensorType - Switch for lidar configuration (0 = None, 1 = Single Point Beam(s), 2 = Continuous, 3 = Pulsed) +0 NumPulseGate - Number of lidar measurement gates (used when SensorType = 3) +30 PulseSpacing - Distance between range gates (m) (used when SensorType = 3) +0 NumBeam - Number of lidar measurement beams (0-5)(used when SensorType = 1) +-200 FocalDistanceX - Focal distance co-ordinates of the lidar beam in the x direction (relative to hub height) (only first coordinate used for SensorType 2 and 3) (m) +0 FocalDistanceY - Focal distance co-ordinates of the lidar beam in the y direction (relative to hub height) (only first coordinate used for SensorType 2 and 3) (m) +0 FocalDistanceZ - Focal distance co-ordinates of the lidar beam in the z direction (relative to hub height) (only first coordinate used for SensorType 2 and 3) (m) +0.0 0.0 0.0 RotorApexOffsetPos - Offset of the lidar from hub height (m) +17 URefLid - Reference average wind speed for the lidar[m/s] +0.25 MeasurementInterval - Time between each measurement [s] +False LidRadialVel - TRUE => return radial component, FALSE => return 'x' direction estimate +1 ConsiderHubMotion - Flag whether to consider the hub motion's impact on Lidar measurements ====================== OUTPUT ================================================== False SumPrint - Print summary data to .IfW.sum (flag) OutList - The next line(s) contains a list of output parameters. See OutListParameters.xlsx for a listing of available output channels, (-) From 2f069daec96e690249083fbc2ce53b7107304f57 Mon Sep 17 00:00:00 2001 From: alandwright <56039708+alandwright@users.noreply.github.com> Date: Thu, 20 Jul 2023 11:17:46 -0600 Subject: [PATCH 106/224] Floating Feedback Gain Scheduling (#241) * Add back open loop yaw rate control * Check OL outputs in example * Update CI to use mamba, first attempt * Install extras when environment first set up * Remove potential libpython typo * Remove more potential typos * Use mamba in compile, too * Use environment.yml file * Remove conda installs from rosco-compile * Clean up CI scripts * added yaml file in folder tune_cases * additional yaml files added to tune_cases * additional yaml * additional yaml * further additions * various changes to add KPfloat gain scheduling * updating ROSCO toolbox files and ROSCO source code for KPfloat gain scheduling * Update BAR_10_InflowFile.dat added VelInterpCubic and LiDAR Parameters to the InflowFile * Update IEA-15-240-RWT_InflowFile.dat added VelInterpCubic and LiDAR Parameters to the InflowFile * Update NRELOffshrBsline5MW_InflowWind.dat added VelInterpCubic and LiDAR Parameters to the InflowFile * Update BAR_10_InflowFile.dat added VelInterpCubic and LiDAR Parameters to the InflowFile * Update NREL-2p8-127_InflowFile.dat added VelInterpCubic and LiDAR Parameters to the InflowFile * Remove CCT9 at rated model * Remove CCT above rated model * Remove extra tuning yamls * Update NREL-2p8-127_InflowFile.dat added VelInterpCubic and LiDAR Parameters to the InflowFile * Update IEA-15-240-RWT_InflowFile.dat added VelInterpCubic and LiDAR Parameters to the InflowFile * Update NRELOffshrBsline5MW_InflowWind.dat added VelInterpCubic and LiDAR Parameters to the InflowFile * Update NREL-2p8-127_InflowFile.dat added VelInterpCubic and LiDAR Parameters to the InflowFile * Update StC-Force-Col1.dat adjusted comment on StC_DOF_MODE * Update StC-Force-Col2.dat adjusted comment on StC_DOF_MODE * Update StC-Force-Col3.dat adjusted comment on StC_DOF_MODE * Update FAST_reader.py added parsing of cubic interpolation for velocity and LIDAR parameters in read_InflowWind method for the InflowWind data file * Update FAST_writer.py added writing of cubic interpolation for velocity and LIDAR parameters in write_InflowWind method for the InflowWind data file * Update mamba install in CI * Remove petsc and mpi * Revert CI back to conda * Give Fl_Kp own gain scheduling, separate from pitch control * Remove duplicate AWC entries in registry * Sync FAST_reader/writer with WEIS versions * Set default Kp_float and U_Fl for non-floating cases * Increment openfast version in CI * Add nodes to FAST_vars_out * Add nodes to vartree * Remove duplicated F_NotchType check * Sync FAST_vars_out more * Update DISCONs with new Fl_* inputs * Make Fl_n an int when writing DISCON * Add MoorDyn outlist params to FstOutput * Add floating feedback example * Fix schema for Kp_float * Update run_FAST to work in weis environment * Pull some FAST_reader improvements in Beam/SubDyn * Simplify example 05, most moved to 24_floating_feedback * Make rotor_performance_filename relative to tuning yaml * Update paths with new Cp location * Add api change and update toolbox input for docs * Update installation docs with wisdem note * Update documentation regarding pyFAST in 11_robust_tuning.py * Update DISCON schema with new inputs --------- Co-authored-by: dzalkind Co-authored-by: Wright, Alan Co-authored-by: Rudy <107142607+Yuksel-Rudy@users.noreply.github.com> Co-authored-by: dzalkind <65573423+dzalkind@users.noreply.github.com> --- Examples/01_turbine_model.py | 2 +- Examples/03_tune_controller.py | 2 +- Examples/04_simple_sim.py | 2 +- Examples/05_openfast_sim.py | 34 +--- Examples/06_peak_shaving.py | 2 +- Examples/10_linear_params.py | 2 +- Examples/11_robust_tuning.py | 8 +- Examples/14_open_loop_control.py | 2 +- Examples/24_floating_feedback.py | 165 ++++++++++++++++++ Examples/ROSCO_walkthrough.ipynb | 29 ++- Examples/test_examples.py | 1 + ROSCO/rosco_registry/rosco_types.yaml | 35 ++-- ROSCO/src/Controllers.f90 | 17 +- ROSCO/src/ROSCO_IO.f90 | 117 +++++++------ ROSCO/src/ROSCO_Types.f90 | 7 +- ROSCO/src/ReadSetParameters.f90 | 5 +- ROSCO_toolbox/controller.py | 39 ++++- ROSCO_toolbox/inputs/toolbox_schema.yaml | 30 +++- ROSCO_toolbox/ofTools/case_gen/CaseLibrary.py | 27 +-- ROSCO_toolbox/ofTools/case_gen/run_FAST.py | 25 ++- ROSCO_toolbox/ofTools/fast_io/FAST_reader.py | 13 +- ROSCO_toolbox/tune.py | 2 +- ROSCO_toolbox/utilities.py | 10 +- Test_Cases/BAR_10/BAR_10_DISCON.IN | 6 +- .../DISCON-UMaineSemi.IN | 6 +- Test_Cases/NREL-5MW/DISCON.IN | 6 +- .../NREL_2p8_127/NREL-2p8-127_DISCON.IN | 6 +- Tune_Cases/BAR.yaml | 2 +- Tune_Cases/IEA15MW.yaml | 2 +- Tune_Cases/IEA15MW_ExtInterface.yaml | 2 +- Tune_Cases/IEA15MW_FOCAL.yaml | 2 +- Tune_Cases/IEA15MW_MultiOmega.yaml | 2 +- Tune_Cases/IEA15MW_OL.yaml | 2 +- Tune_Cases/IEA15MW_ballast.yaml | 2 +- Tune_Cases/IEA15MW_cable.yaml | 2 +- Tune_Cases/IEA15MW_robust.yaml | 2 +- Tune_Cases/NREL2p8.yaml | 2 +- Tune_Cases/NREL5MW.yaml | 2 +- Tune_Cases/NREL5MW_PassThrough.yaml | 2 +- docs/source/api_change.rst | 16 ++ docs/source/install.rst | 2 +- docs/source/toolbox_input.rst | 94 ++++++++-- 42 files changed, 524 insertions(+), 212 deletions(-) create mode 100644 Examples/24_floating_feedback.py diff --git a/Examples/01_turbine_model.py b/Examples/01_turbine_model.py index 95a69bac..dbf181b9 100644 --- a/Examples/01_turbine_model.py +++ b/Examples/01_turbine_model.py @@ -34,7 +34,7 @@ turbine.load_from_fast( path_params['FAST_InputFile'], os.path.join(tune_dir,path_params['FAST_directory']), - rot_source='txt',txt_filename=os.path.join(tune_dir,path_params['FAST_directory'],path_params['rotor_performance_filename']) + rot_source='txt',txt_filename=os.path.join(tune_dir,path_params['rotor_performance_filename']) ) # Print some basic turbine info diff --git a/Examples/03_tune_controller.py b/Examples/03_tune_controller.py index 4aa19369..74e77415 100644 --- a/Examples/03_tune_controller.py +++ b/Examples/03_tune_controller.py @@ -34,7 +34,7 @@ controller = ROSCO_controller.Controller(controller_params) # Load turbine data from OpenFAST and rotor performance text file -cp_filename = os.path.join(tune_dir,path_params['FAST_directory'],path_params['rotor_performance_filename']) +cp_filename = os.path.join(tune_dir,path_params['rotor_performance_filename']) turbine.load_from_fast( path_params['FAST_InputFile'], os.path.join(tune_dir,path_params['FAST_directory']), diff --git a/Examples/04_simple_sim.py b/Examples/04_simple_sim.py index aba7e468..097af355 100644 --- a/Examples/04_simple_sim.py +++ b/Examples/04_simple_sim.py @@ -55,7 +55,7 @@ # controller = ROSCO_controller.Controller(controller_params) # Load turbine data from OpenFAST and rotor performance text file -cp_filename = os.path.join(tune_dir,path_params['FAST_directory'],path_params['rotor_performance_filename']) +cp_filename = os.path.join(tune_dir,path_params['rotor_performance_filename']) turbine.load_from_fast( path_params['FAST_InputFile'], os.path.join(tune_dir,path_params['FAST_directory']), diff --git a/Examples/05_openfast_sim.py b/Examples/05_openfast_sim.py index 7dd33085..553d355f 100644 --- a/Examples/05_openfast_sim.py +++ b/Examples/05_openfast_sim.py @@ -41,48 +41,16 @@ path_params['FAST_InputFile'], os.path.join(this_dir,path_params['FAST_directory']), rot_source='txt', - txt_filename=os.path.join(this_dir,path_params['FAST_directory'],path_params['rotor_performance_filename']) + txt_filename=os.path.join(this_dir,path_params['rotor_performance_filename']) ) # Tune controller controller.tune_controller(turbine) -# Now double Kp_float and check that it's passed through -Kp_float = -18 -controller_params['Kp_float'] = Kp_float -controller_params['tune_Fl'] = False -controller = ROSCO_controller.Controller(controller_params) -controller.tune_controller(turbine) -np.testing.assert_almost_equal(Kp_float,controller.Kp_float) - # Write parameter input file param_file = os.path.join(this_dir,'DISCON.IN') # This must be named DISCON.IN to be seen by the compiled controller binary. write_DISCON(turbine,controller,param_file=param_file, txt_filename=path_params['rotor_performance_filename']) -# Plot gain schedule -fig, ax = plt.subplots(2,2,constrained_layout=True,sharex=True) -ax = ax.flatten() -ax[0].plot(controller.v[len(controller.v_below_rated)+1:], controller.omega_pc_U) -ax[0].set_ylabel('omega_pc') - -ax[1].plot(controller.v[len(controller.v_below_rated)+1:], controller.zeta_pc_U) -ax[1].set_ylabel('zeta_pc') - -ax[2].plot(controller.v[len(controller.v_below_rated)+1:], controller.pc_gain_schedule.Kp) -ax[2].set_xlabel('Wind Speed') -ax[2].set_ylabel('Proportional Gain') - -ax[3].plot(controller.v[len(controller.v_below_rated)+1:], controller.pc_gain_schedule.Ki) -ax[3].set_xlabel('Wind Speed') -ax[3].set_ylabel('Integral Gain') - -plt.suptitle('Pitch Controller Gains') - -if False: - plt.show() -else: - plt.savefig(os.path.join(example_out_dir,'05_GainSched.png')) - # Run OpenFAST # --- May need to change fastcall if you use a non-standard command to call openfast fastcall = 'openfast' diff --git a/Examples/06_peak_shaving.py b/Examples/06_peak_shaving.py index 525e4fc0..ca3e90cd 100644 --- a/Examples/06_peak_shaving.py +++ b/Examples/06_peak_shaving.py @@ -44,7 +44,7 @@ turbine.load_from_fast( path_params['FAST_InputFile'], os.path.join(tune_dir,path_params['FAST_directory']), - rot_source='txt',txt_filename=os.path.join(tune_dir,path_params['FAST_directory'],path_params['rotor_performance_filename']) + rot_source='txt',txt_filename=os.path.join(tune_dir,path_params['rotor_performance_filename']) ) # Tune controller controller.tune_controller(turbine) diff --git a/Examples/10_linear_params.py b/Examples/10_linear_params.py index 69aa3094..36e995a3 100644 --- a/Examples/10_linear_params.py +++ b/Examples/10_linear_params.py @@ -45,7 +45,7 @@ path_params['FAST_InputFile'], os.path.join(this_dir,path_params['FAST_directory']), rot_source='txt', - txt_filename=os.path.join(tune_dir,path_params['FAST_directory'],path_params['rotor_performance_filename']) + txt_filename=os.path.join(tune_dir,path_params['rotor_performance_filename']) ) # Tune controller diff --git a/Examples/11_robust_tuning.py b/Examples/11_robust_tuning.py index aa4d7df6..30693419 100644 --- a/Examples/11_robust_tuning.py +++ b/Examples/11_robust_tuning.py @@ -3,6 +3,8 @@ Controller tuning to satisfy a robustness criteria ------------------------------------- NOTE: This example necessitates the mbc3 through either pyFAST or WEIS +pyFAST is the easiest to install by cloning https://github.com/OpenFAST/python-toolbox and +running `python setup.py develop` from your conda environment In this example: - setup ROSCO's robust tuning methods for the IEA15MW on the UMaine Semi-sub @@ -53,12 +55,12 @@ def run_example(): controller = ROSCO_controller.Controller(controller_params) turbine.load_from_fast( path_params['FAST_InputFile'], - os.path.join(this_dir, path_params['FAST_directory']), - rot_source='txt', txt_filename=os.path.join(this_dir,path_params['FAST_directory'],path_params['rotor_performance_filename']) + os.path.join(tune_dir, path_params['FAST_directory']), + rot_source='txt', txt_filename=os.path.join(tune_dir,path_params['rotor_performance_filename']) ) # Fix path params for robust setup - path_params['FAST_directory'] = os.path.join(this_dir, path_params['FAST_directory']) + path_params['FAST_directory'] = os.path.join(tune_dir, path_params['FAST_directory']) controller.tune_controller(turbine) k_float = controller.Kp_float diff --git a/Examples/14_open_loop_control.py b/Examples/14_open_loop_control.py index cbc20f5d..50626d84 100644 --- a/Examples/14_open_loop_control.py +++ b/Examples/14_open_loop_control.py @@ -77,7 +77,7 @@ turbine.load_from_fast(path_params['FAST_InputFile'], \ os.path.join(this_dir,path_params['FAST_directory']), \ rot_source='txt',\ - txt_filename=os.path.join(this_dir,path_params['FAST_directory'],path_params['rotor_performance_filename'])) + txt_filename=os.path.join(this_dir,path_params['rotor_performance_filename'])) # Tune controller controller.tune_controller(turbine) diff --git a/Examples/24_floating_feedback.py b/Examples/24_floating_feedback.py new file mode 100644 index 00000000..d46378ce --- /dev/null +++ b/Examples/24_floating_feedback.py @@ -0,0 +1,165 @@ +''' +----------- 23_structural_control ------------------------ +Run openfast with ROSCO and all the floating feedback methods +----------------------------------------------- + +Floating feedback methods available in ROSCO/ROSCO_Toolbox + +1. Automated tuning, constant for all wind speeds +2. Automated tuning, varies with wind speed +3. Direct tuning, constant for all wind speeds +4. Direct tuning, varies with wind speeds + +''' + +import os, platform +from ROSCO_toolbox.ofTools.case_gen.run_FAST import run_FAST_ROSCO +from ROSCO_toolbox.ofTools.case_gen import CaseLibrary as cl +import numpy as np +from ROSCO_toolbox.ofTools.fast_io.FAST_reader import InputReader_OpenFAST +from ROSCO_toolbox.inputs.validation import load_rosco_yaml +from ROSCO_toolbox.controller import OpenLoopControl +from ROSCO_toolbox.tune import yaml_to_objs +from ROSCO_toolbox.utilities import write_DISCON, read_DISCON +from ROSCO_toolbox import controller as ROSCO_controller +from ROSCO_toolbox.ofTools.fast_io import output_processing +import matplotlib.pyplot as plt + + + +#directories +this_dir = os.path.dirname(os.path.abspath(__file__)) +rosco_dir = os.path.dirname(this_dir) +example_out_dir = os.path.join(this_dir,'examples_out') +os.makedirs(example_out_dir,exist_ok=True) + +if platform.system() == 'Windows': + lib_name = os.path.realpath(os.path.join(this_dir, '../ROSCO/build/libdiscon.dll')) +elif platform.system() == 'Darwin': + lib_name = os.path.realpath(os.path.join(this_dir, '../ROSCO/build/libdiscon.dylib')) +else: + lib_name = os.path.realpath(os.path.join(this_dir, '../ROSCO/build/libdiscon.so')) + + +def main(): + + # Input yaml and output directory + parameter_filename = os.path.join(rosco_dir,'Tune_Cases/IEA15MW.yaml') + run_dir = os.path.join(example_out_dir,'24_floating_feedback') + os.makedirs(run_dir,exist_ok=True) + + controller, turbine, path_params = yaml_to_objs(parameter_filename) + + # First, let's write the DISCONs for each method + param_files = [] + + # Method 1: Automated tuning, constant for all wind speeds + controller_params_1 = controller.controller_params # numbers correspond to methods above + param_file = os.path.join(run_dir,'DISCON_Fl_1.IN') + param_files.append(param_file) + write_DISCON(turbine,controller, + param_file=param_file, + txt_filename=path_params['rotor_performance_filename']) + + + # Method 2: Automated tuning, all wind speeds + controller_params_2 = controller_params_1.copy() + controller_params_2['U_Fl'] = 'all' + controller_params_2['tune_Fl'] = True + controller = ROSCO_controller.Controller(controller_params_2) + controller.tune_controller(turbine) + param_file = os.path.join(run_dir,'DISCON_Fl_2.IN') + param_files.append(param_file) + write_DISCON(turbine,controller, + param_file=param_file, + txt_filename=path_params['rotor_performance_filename']) + + # Method 3: Direct tuning, constant for all wind speeds + controller_params_3 = controller_params_1.copy() + Kp_float = -18 + controller_params_3['Kp_float'] = Kp_float + controller_params_3['tune_Fl'] = False + controller = ROSCO_controller.Controller(controller_params_3) + controller.tune_controller(turbine) + np.testing.assert_almost_equal(Kp_float,controller.Kp_float) # Check that it's passed through correctly + param_file = os.path.join(run_dir,'DISCON_Fl_3.IN') + param_files.append(param_file) + write_DISCON(turbine,controller, + param_file=param_file, + txt_filename=path_params['rotor_performance_filename']) + + # Method 4: Direct tuning, varies with wind speeds + controller_params_4 = controller_params_1.copy() + controller_params_4['U_Fl'] = [12,16,25] + controller_params_4['Kp_float'] = [-12,-6,-3] + controller_params_4['tune_Fl'] = False + controller = ROSCO_controller.Controller(controller_params_4) + controller.tune_controller(turbine) + param_file = os.path.join(run_dir,'DISCON_Fl_4.IN') + param_files.append(param_file) + write_DISCON(turbine,controller, + param_file=os.path.join(run_dir,'DISCON_Fl_4.IN'), + txt_filename=path_params['rotor_performance_filename']) + + # Read all DISCONs and make into case_inputs + case_inputs = {} + discon_lists = {} + for discon in param_files: + discon_vt = read_DISCON(discon) + for discon_input in discon_vt: + if discon_input not in discon_lists: # initialize + discon_lists[discon_input] = [] + discon_lists[discon_input].append(discon_vt[discon_input]) + + for discon_input, input in discon_lists.items(): + case_inputs[('DISCON_in',discon_input)] = {'vals': input, 'group': 2} + + + # simulation set up + r = run_FAST_ROSCO() + r.tuning_yaml = parameter_filename + r.wind_case_fcn = cl.simp_step # single step wind input + r.wind_case_opts = { + 'U_start': [13], + 'U_end': [16], + 'TMax': 100, + 'TStep': 50, + } + r.case_inputs = case_inputs + r.save_dir = run_dir + r.rosco_dir = rosco_dir + r.n_cores = 4 + r.run_FAST() + + op = output_processing.output_processing() + op_dbg = output_processing.output_processing() + op_dbg2 = output_processing.output_processing() + + out_files = [os.path.join(run_dir,f'IEA15MW/simp_step/base/IEA15MW_{i_case}.outb') for i_case in range(4)] + dbg_files = [os.path.join(run_dir,f'IEA15MW/simp_step/base/IEA15MW_{i_case}.RO.dbg') for i_case in range(4)] + dbg2_files = [os.path.join(run_dir,f'IEA15MW/simp_step/base/IEA15MW_{i_case}.RO.dbg2') for i_case in range(4)] + + fst_out = op.load_fast_out(out_files, tmin=0) + debug_vars = op_dbg.load_fast_out(dbg_files, tmin=0) + local_vars = op_dbg2.load_fast_out(dbg2_files, tmin=0) + + comb_out = [None] * len(fst_out) + for i, (r_out, f_out) in enumerate(zip(debug_vars,fst_out)): + r_out.update(f_out) + comb_out[i] = r_out + for i, (r_out2, f_out) in enumerate(zip(local_vars,comb_out)): + r_out2.update(f_out) + comb_out[i] = r_out2 + + cases = {} + cases['Fl Sigs.'] = ['Wind1VelX','Kp_Float', 'Fl_PitCom', 'BldPitch1','PtfmPitch']#,'PtfmPitch','PtfmYaw','NacYaw'] + fig, ax = op.plot_fast_out(comb_out,cases, showplot=True) + + if False: + plt.show() + else: + plt.savefig(os.path.join(run_dir,'24_floating_feedback.png')) + + +if __name__=="__main__": + main() \ No newline at end of file diff --git a/Examples/ROSCO_walkthrough.ipynb b/Examples/ROSCO_walkthrough.ipynb index d3f912b7..9a129e20 100644 --- a/Examples/ROSCO_walkthrough.ipynb +++ b/Examples/ROSCO_walkthrough.ipynb @@ -1,6 +1,7 @@ { "cells": [ { + "attachments": {}, "cell_type": "markdown", "metadata": { "slideshow": { @@ -60,6 +61,7 @@ ] }, { + "attachments": {}, "cell_type": "markdown", "metadata": { "slideshow": { @@ -131,6 +133,7 @@ ] }, { + "attachments": {}, "cell_type": "markdown", "metadata": { "slideshow": { @@ -151,6 +154,7 @@ ] }, { + "attachments": {}, "cell_type": "markdown", "metadata": { "slideshow": { @@ -190,11 +194,12 @@ "turbine.load_from_fast(\n", " path_params['FAST_InputFile'],\n", " os.path.join('../Tune_Cases/',path_params['FAST_directory']),\n", - " rot_source='txt',txt_filename=os.path.join('../Tune_Cases/',path_params['FAST_directory'],path_params['rotor_performance_filename'])\n", + " rot_source='txt',txt_filename=os.path.join('../Tune_Cases/',path_params['rotor_performance_filename'])\n", " )\n" ] }, { + "attachments": {}, "cell_type": "markdown", "metadata": { "slideshow": { @@ -231,7 +236,7 @@ }, { "data": { - "image/png": "iVBORw0KGgoAAAANSUhEUgAAAjUAAAG2CAYAAACH2XdzAAAAOXRFWHRTb2Z0d2FyZQBNYXRwbG90bGliIHZlcnNpb24zLjYuMiwgaHR0cHM6Ly9tYXRwbG90bGliLm9yZy8o6BhiAAAACXBIWXMAAA9hAAAPYQGoP6dpAACEh0lEQVR4nO3deVwU9f8H8NeyCyxyC4iigIgHHnlBKZqppZCapXbYZZpHonaQqUlaIl9Lu/xqhwdmmZpGamaHZlQeeFRK0s+iyxO+hCKIXHLuzu8P2nXvnZmd2Z1Z3s/HYx/B7OwcrLEv3p/3fEbBMAwDQgghhBCZ83D1ARBCCCGECIFCDSGEEELcAoUaQgghhLgFCjWEEEIIcQsUagghhBDiFijUEEIIIcQtUKghhBBCiFtQufoApECr1eKff/6Bv78/FAqFqw+HEEKIRDEMg6qqKkRERMDDQ7y6QF1dHRoaGgTZlpeXF9RqtSDbkjoKNQD++ecfREZGuvowCCGEyERhYSE6dOggyrbr6urQMdoXl0u0gmyvbdu2OH/+fIsINhRqAPj7+wNo/kcaEBAAABjf9gmr63u0DjZbxgT5my1rDDL/B9QY4Gn0fUOA0vh7f/NKUYOfyTZ8LR+XJsDy/wAaX43lFxjw9HX8L4LGGi+rzylrlObLKm/8leNZc2O5V7XB11XNE157VTafg2dlY/N/r9VBca0KAKC9Wg4A2H0pk9+BE0IIS5WVlYiMjNR/boihoaEBl0u0+PVEW/j7O1YNqqrSotfNl9DQ0EChpqXQDTkFBAToQ41KYfkD2iOktcXljNLbfJnK+B9QY6Cn2Q9c42X8Ya/0Mg81ppvWWvl3yajNQ43GTwMPeFpY25hHK8fLqN6tgMZqyz83xgdQVpuca8ONfSqbDJcbfO3VHGpUns2hRqVq3oZKyQAh3lCUV0H773ule+8IIURszmhV8Pf3QICDoaaloZ+WBcm+j3Fanwm2UKUJ9rH7uvpA8+qFqQaWfww0WanSsOHpJ8y4rT0aP+sVo0aDahTbc9axFjQJIYS0LBRqJMTS0JOpRj+7q+jZChE6QgcaLttjE8R0PxM2AZBrGCWEEOJeKNRw4EhFoDHQ/hCQKbGrNGJVaGxtl03QskX3c2RTCSOEENKyUKgxIaWhJ0fYCw/OGnLigs8QlO7nT0NQhBBCKNSwJHaVhu/QE58qjTMCDdt9ONILRAghhBiiUOMAKTQIW+LoEI9QrAUbrsfHJvDpUF8NIYS0XBRqDNiam0ZM7lalcYStIShdGKS+GkIIIZZILtRUVVVhwYIFSEpKQlhYGBQKBdLT022+hmEY3HbbbVAoFHjyyScFPyapNghz5YpAw2afjg5BUV8NIYQQQIKhpqysDJmZmaivr8e4ceNYvebdd9/FmTNnxD0wE65uELYWBKwN7XAJNIH+tZwftljat1SGyAghhLgPyYWa6OholJeX49ChQ1i+fLnd9S9cuIC0tDS8++67ohyP2H/9Cz03jaPsBRRCCCFEqiQXahQKBafpp5944gmMHDkS48ePF/Go+HH20JOjVRpHAg2fao0hw8qTpb4a00n4bPXVULMwIYS0TLK+99N7772Hn376Cfn5+ZxeV19fj/r6ev33lZWVnF4v1aEnRwhRoQn0r0VFlfWfg6dfg9G9oTR+GrP7QfHFBPtDUV4lyLYIIYTIk+QqNWwVFRVh3rx5eO211xAREcHptcuXL0dgYKD+ERkZaXE9OQ09CdFL4w6oWZgQQlou2YaalJQU9OnTBzNmzOD82rS0NFRUVOgfhYWFDh2LpSqNWENPUq3SsN0W25DlzD4iQgghN6xZswYxMTFQq9WIj49HTk4Oq9cdPXoUKpUKffv2tbrOxx9/DIVCYXYh0OHDhzF27FhERERAoVDgs88+43Xssgw1O3fuxNdff43XXnsNFRUVuHbtGq5duwYAaGhowLVr19DY2Gj19d7e3ggICDB6mLL2F7+loSc2TIeepFKlEaMxmO82rQU2tn01hu8N9dUQQgh3WVlZSE1NxaJFi3Dq1CkMGTIEo0aNQkFBgc3XVVRU4LHHHsMdd9xhdZ2LFy9i3rx5GDJkiNlzNTU16NOnD9555x2Hjl+WoebXX39FU1MTBg4ciODgYP0DADZs2IDg4GB89dVXLjs+Kc1NY4sUrnSiS7sJIUQ6Vq5ciWnTpmH69Ono3r07Vq1ahcjISKxdu9bm62bOnImHH34YiYmJFp/XaDR45JFHsHTpUnTq1Mns+VGjRmHZsmWYMGGCQ8cvy1AzZcoUHDhwwOwBAOPGjcOBAwdw6623OuVYXN0gzLdKI3agsbV9sYegqK+GEEKMVVZWGj0ML5bRaWhoQG5uLpKSkoyWJyUl4dixY1a3/cEHH+Ds2bNYsmSJ1XUyMjIQFhaGadOm8T8JFiR59dO+fftQU1ODqqrmq1ny8/Oxc+dOAMDo0aPRsWNHdOzY0eJr27dvj2HDhjm0f6GHnkxJbW4aKWkK0EJVKcusTQghgjrbpIRfk2O/D6ubmj9vTC+IWbJkidls/aWlpdBoNAgPDzdaHh4ejkuXLlnc/t9//42FCxciJycHKpXlSHH06FFs3LgReXl5/E6CA0mGmlmzZuHixYv673fs2IEdO3YAAM6fP2810EiBMxuEpVqlMdyPrUu8dfhc2l0fqIR3hQaNgZ7wrGhEY7APPMuNzyvZ9zHsr9nMabuEEOKOCgsLjfpHvb29ra5rOlccwzAW54/TaDR4+OGHsXTpUnTt2tXitqqqqvDoo49iw4YNCA0N5Xn07Eky1Fy4cIHX6xiGEfZADLftxLlpxKzSOLuPxlqwMZ2zxppGP8Czujn4eVU1V7m8qqy/zzRfDSGEmLN2UYyh0NBQKJVKs6pMSUmJWfUGaA4sJ0+exKlTp/T3XdRqtWAYBiqVCt988w1at26NCxcuYOzYsfrXabXNf6SrVCr8+eefiI2NdfT09CQZalxJCnPTsMGnSiOFxmA2aAiKEEKcz8vLC/Hx8cjOzjaapT87Oxv33HOP2foBAQE4ffq00bI1a9bg+++/x86dOxETEwOlUmm2zuLFi1FVVYXVq1dbnSeOLwo1LLDtpZHy3DRCB5o2vtX6r0tqbJeW2AxDCTm7MNAcTrVlVwXbHiGEtARz587FpEmTkJCQgMTERGRmZqKgoAApKSkAmud5KyoqwubNm+Hh4YFevXoZvb5NmzZQq9VGy03XCQoKMlteXV1tdGPq8+fPIy8vD61bt0ZUVBTr46dQY8CjdTDrdeU49MSWYWBhu74QwYYrNn01hBBC2Js4cSLKysqQkZGB4uJi9OrVC3v37kV0dDQAoLi42O6cNXycPHkSw4cP138/d+5cAMDkyZOxadMm1ttRMGI2oshEZWUlAgMDMaJ9ClQe5s1TbPppLFVp2Ey4Z1qpsRRqTCs1XIeeuFRpuAYaQ/aCjaVQY9hXY1qp0Q1BeRockleV7r/N/2y9K5p/Fp4VzZMtepbX6ntqdJUaahYmhAhF93lRUVFht0fF0X18/2sk/PwdvPqpSovbexWKerxSQo0Ldgh1GbclfAKNmBwJNGzYC1fWwhrX6pWY7xkhhBDpolDDA5+hJ6EahK1xtEojRKBhsw1nNivTJHyEENKyUKixQYoNwlK/rQDXcGTrai02VSrT+0ARQghpuSjUcCTFBmEpVGmEwja0Wat8WXp/6OaWhBDSMlCocQKx56ZxhBiBxt42HRmCYnvjT+qrIYSQlodCjRVSHHqyhO3NIS0Rs0LDZdtshqCkcKk7IYQQaaNQw4EUh56skcvswUKw1VdDzcKEENJyUKhxAJsqDZ+hJ7YNwlKt0ji6D+qrIYQQwgeFGgvEvHkl254QR9ir0jizMdjavqivhhBCiNAo1IiITZWGzdCTkFUaKV3pZIjN+VBfDSGEEFso1JiQS4OwNVLspeETpAyDnKPz1VBfDSGEtAwUaliQU4OwLVKr0ggRwKivhhBCiA7dpVskYs5Nw2eyPaECTWSraxaXF14Psvk6Nnfy9vRrMLrBpS0N/jdubkkIIe7oQkMoWjVw/4PZ0PUGDYBCYQ5IBijUGGCC2DUIS3XoyRqugcZacBHiOOwFG0MaP43Znbsb/Yzv2m0PE+yvv2s3IYQQ90bDTwKQwtCTUL00fAONWEGIC1vvA/XVEEKI+6NQYwPfKo1U56axx9Fgwub1plUj0zBm7fxsVbFMf9623iPqqyGEEPdFocZBUpmbxhqpNQdzZWsiPns/VzYN3oQQQtwHhRqBuWJuGiGGnoQaPpLCMJQpmoSPEEJaBgo1VrSkBmFnBxG+Q1A6tkIhm74aGoIihBD3RKHGAe7UICwksUKSUH01hBBC3BOFGguc2SBsiRANwq6u0jir+kN9NYQQQnQo1PAkVIOwI0NPjlZpXNn/wmUIiu1du23R9dXQpd2EEOK+KNSwIFSVxlk3r2RTpXFGoBFzH44O41FfDSGEuB8KNSaEGq6QepXGWZxZDdIFS1s3tySEEOK+KNTwIIUGYUdI8bJrtiwFQeqrIYQQAlCoMdIYpDZf5mYNwq4INNb26eil3VxRXw0hhLg3CjUcyblB2JUVGkf3bSnwUV8NIYQQQxRqbHBmg7AQ5H5LBCGY9tUQQghpOSjUCIzvfZ7YDj1JqUoT7VOGaJ8yh46BzxAUl74aXTDV9dXQLRMIIcS2NWvWICYmBmq1GvHx8cjJybG67pEjRzB48GCEhITAx8cHcXFx+O9//2u0TmNjIzIyMhAbGwu1Wo0+ffrg66+/Nlpn+fLluPnmm+Hv7482bdpg3Lhx+PPPPzkfu4rzK1oIS1Uaof76F+O2CLaqNI4GGnvBJdqnDBdrQxzah7N5hLSGtuyqqw+DEEIkJSsrC6mpqVizZg0GDx6M9evXY9SoUcjPz0dUVJTZ+r6+vnjyySfRu3dv+Pr64siRI5g5cyZ8fX3xxBNPAAAWL16MrVu3YsOGDYiLi8P+/fsxfvx4HDt2DP369QMAHDp0CHPmzMHNN9+MpqYmLFq0CElJScjPz4evry/r41cwDMMI86OQr8rKSgQGBuK2wS9CpWpuFmYTaiwNPZlWDCwNPZmGGiFuXilkqOFSfTHENtgUXg8y+r6kxviHVFFlfLVSY7WX/mtldfN7oKq8UWT0/PfUvap0/23+J+1d0fxz9axobP5vefPPTlHevKIu1Oyv2czquAkhRPd5UVFRgYCAAFH38f7P/dDK37E/pq9XaTC1/ykUFhYaHa+3tze8vb3N1h8wYAD69++PtWvX6pd1794d48aNw/Lly1ntc8KECfD19cWWLVsAABEREVi0aBHmzJmjX2fcuHHw8/PD1q1bLW7jypUraNOmDQ4dOoTbbruN1X4BqtSwJuUGYSF7afgGGiEF+teaBRtCCGlpzjWEQV3v2HxbdQ3Nf9RFRkYaLV+yZAnS09ONljU0NCA3NxcLFy40Wp6UlIRjx46x2t+pU6dw7NgxLFu2TL+svr4earXx1cU+Pj44cuSI1e1UVFQAAFq35na1KoUaC+TWIGwLlyqNo4GG7zBUG99qs2qNPU0BWqNqDdAcKr2qmt8bryoG9YFKeFdo0BjoCc+KRjQG+8CzvBZMsL++WkMIIS2BpUqNqdLSUmg0GoSHhxstDw8Px6VLl2xuv0OHDrhy5QqampqQnp6O6dOn659LTk7GypUrcdtttyE2Nhbfffcd9uzZA43G8i1wGIbB3Llzceutt6JXr15cTpMahdkQqkpjiaNz00jtiic2wYjrcJjQ89Xo0Hw1hJCWIiAgwOhhKdToKBTGf7QzDGO2zFROTg5OnjyJdevWYdWqVdi+fbv+udWrV6NLly6Ii4uDl5cXnnzySTz++ONQKi1/tj755JP4v//7P6NtsEWhxoSYU+s7e24aZ1ZphMblfGm+GkIIcVxoaCiUSqVZVaakpMSsemMqJiYGN910E2bMmIFnn33WaGgrLCwMn332GWpqanDx4kX88ccf8PPzQ0xMjNl2nnrqKXz++ec4cOAAOnTowPkcKNTwIJWbVwpVpRE60PDZHttzEeKO3YQQQsx5eXkhPj4e2dnZRsuzs7MxaNAg1tthGAb19fVmy9VqNdq3b4+mpibs2rUL99xzj9FrnnzySXz66af4/vvvLQYeNqinxkBjgKfZD0TKDcK2SP3+TpGtrpldBcUV9dUQQoiw5s6di0mTJiEhIQGJiYnIzMxEQUEBUlJSAABpaWkoKirC5s3NV42+++67iIqKQlxcHIDmeWveeOMNPPXUU/pt/vjjjygqKkLfvn1RVFSE9PR0aLVaLFiwQL/OnDlzsG3bNuzZswf+/v76alFgYCB8fNhfOEKhhiO5NAizJdawk1zmrqH5aggh5IaJEyeirKwMGRkZKC4uRq9evbB3715ER0cDAIqLi1FQUKBfX6vVIi0tDefPn4dKpUJsbCxWrFiBmTNn6tepq6vD4sWLce7cOfj5+WH06NHYsmULgoKC9OvoLiEfNmyY0fF88MEHmDJlCuvjp3lqcGNOgMRRGVB53rjszFKVxjTUWKrSOGNuGiHmpXFGH42tYGNvvhrAeM4a3Xw1urlqAJqvhhDiXM6cp2bxD0lQ+zl4SXd1I5YN/EbU45US6qnhgO/duF1x80p7pNYYDDivr0Z3ywRCCCHuhUKNFXxvicB36EmoBmGp9dLYCk9CHKutwGh6c0vTK9voPlCEEOJeKNQ4gG+DMNtKQ0uq0giJ65xBNF8NIYS4B8mFmqqqKixYsABJSUkICwuDQqEwm8pZo9Fg5cqVuPPOO9GhQwe0atUK3bt3x8KFC3Ht2jWHj4FNL40lcmgQdkWg4bJPe3fttoXmqyGEkJZNcqGmrKwMmZmZqK+vx7hx4yyuU1tbi/T0dERHR2PVqlXYu3cvZsyYgczMTAwePBi1teJUOAxJcQZhqQ09GRIiTBn+nPj21eiGoKivhhBC3I/kLumOjo5GeXk5FAoFSktL8d5775mt4+Pjg/PnzyMk5MaVNcOGDUNUVBTuv/9+7Nq1C48++iiv/QtZpZFag7AUh53Emq/GlG6+GlM0Xw0hhLgPyVVqFAqF3XtMKJVKo0Cjc8sttwBovnGXmPhWaRzlSJVGCoHGmcege4/YXrGm66uhIShCCJEvyVVqHPH9998DAHr27Glzvfr6eqMpnCsrK62uK+Rl3GyHnsRqEJYLPnft1mn0uzFfDSGEkJZFcpUavoqKirBw4UIkJCTgrrvusrnu8uXLERgYqH9ERkYCABoCnHsZt1BcUaXp7H3Z6MEWn2MxDHlC3LGb+moIIcQ9uUWouXr1KkaPHg2GYZCVlQUPD9unlZaWhoqKCv3D2nCVpSqNkJdxu+LmlXyYBhguIYYNvg3Ohj9TNv1L1uYe0s1XQ5d2E0KIvMl++Km8vBwjR45EUVERvv/+e3Tq1Mnua7y9veHt7S3I/oWu0nAdehKjSsMntHT2vowz9bZvTc+FI0NQpnQ3t2Qr2fcxumUCIYTIkKwrNeXl5RgxYgTOnz+P7Oxs9O7dW7Bt863SsCXVKo3QVRhLnNUw7KqGbkIIIa4h20qNLtCcO3cO2dnZ6Nevn9OPge1l3GLNICy1K54cqdbYu7Q70L9Wf3NLT78G/c0tLWHTLNwY6AnPikY0BvvAs7yWLu0mhEhOYW1reCmt/65jo6HW8T5EOZFkqNm3bx9qampQVdX8IZOfn4+dO3cCAEaPHg2FQoHk5GScOnUKq1atQlNTE3744Qf968PCwhAbG8t7/2JXaaTKGVUaLtgMQWn8NPq7djsyX42OR0hraMuu0hAUIYTIkCRDzaxZs3Dx4kX99zt27MCOHTsAAOfPnwcAnDhxAgDwzDPPmL1+8uTJ2LRpk/gHasKZDcJCzx4sVKARurdGKFz7agghhMiPJEPNhQsX7K7DMOJ8QLGt0ri6QdgeV062xybYRPuU4WKt+QSKQmvwB7xoVIkQQloEWTcKS4mcL+OWyrCTkNUnW6FTd2m36Xw1dGk3IYTIG4UaA3Kp0gjZICxWoBFju9Ym4eN7c0t76JYJhBAiLxRqiKRxrVbZmoSP7y0vCCGEyAOFGhvYVmmkNPQkhSoN2+1bOlahG6CBlnHlGiGEEAo1Lif00BNbUumjcRW2fTU0BEUIIfJBocYKd6/SOIuY4cleX42l94uGoAghxH1RqHEhqtJwx+ZnxubmloQQQtwPhRoLhK7SSIkrAo2tfbLpqxHi0nYufTU0BEUIIfJEocYJWurQk9RZ66shhBAiTxRqTDirSuOKoSdXDjuJtW/qqyGEEKJDoUZkUqnSSKGPRqhjEPqWEoQQQtwDhRoDDRb+qhd69mDAdQ3CUiXGfDWWKmls+mro0m5CCJEvCjU8yO0ybilUaXT4HotY98Ey7ashhJCWbs2aNYiJiYFarUZ8fDxycnKsrnvkyBEMHjwYISEh8PHxQVxcHP773/9aXf/jjz+GQqHAuHHjjJavXbsWvXv3RkBAAAICApCYmIh9+/ZxPnZJ3qVbKqhKIw+efg1orPYC0BwuldVKo+cb/QBPk0zU4K+AV5U4d3onhBC5ysrKQmpqKtasWYPBgwdj/fr1GDVqFPLz8xEVFWW2vq+vL5588kn07t0bvr6+OHLkCGbOnAlfX1888cQTRutevHgR8+bNw5AhQ8y206FDB6xYsQKdO3cGAHz44Ye45557cOrUKfTs2ZP18VOlhiMxqjR8ya1Kw5WrAx0NQRFC3EVlZaXRo76+3uJ6K1euxLRp0zB9+nR0794dq1atQmRkJNauXWtx/X79+uGhhx5Cz5490bFjRzz66KNITk42q+5oNBo88sgjWLp0KTp16mS2nbFjx2L06NHo2rUrunbtipdffhl+fn744YcfOJ0nVWqscGaVRqyhFbF08rpituxcQ5hD24z2KcPF2hDW6wf616KiyvYl2E0BWqgqjXN7gz/gVWV5/cZAT3hWNKIx2Aee5dSMTAhxraLaQKg8vB3aRlNtc3iJjIw0Wr5kyRKkp6cbLWtoaEBubi4WLlxotDwpKQnHjh1jtb9Tp07h2LFjWLZsmdHyjIwMhIWFYdq0aTaHs4DmALRjxw7U1NQgMTGR1X51KNRw4OzJ9mxVKpxVpbEUYBzV2fsyztSHc35dG99qlNQInzbrA5XwrpD2pImEEOKIwsJCBAQE6L/39jYPS6WlpdBoNAgPN/79HB4ejkuXLtncfocOHXDlyhU0NTUhPT0d06dP1z939OhRbNy4EXl5eTa3cfr0aSQmJqKurg5+fn7YvXs3evToweLsbqDhJwscrdI4o0FYTJ28rugfXF7jSvZ+5nznq6EhKEKIO9A14OoelkKNjkJh/LuRYRizZaZycnJw8uRJrFu3DqtWrcL27dsBAFVVVXj00UexYcMGhIaG2txGt27dkJeXhx9++AGzZs3C5MmTkZ+fz/IMm1GlhiUpTbYn5uzBrg4nQrDULGzI1hCUDg1BEUJamtDQUCiVSrOqTElJiVn1xlRMTAwA4KabbsLly5eRnp6Ohx56CGfPnsWFCxcwduxY/bpabfPnqUqlwp9//onY2FgAgJeXl75ROCEhASdOnMDq1auxfv161udAlRoTzqzSiInP0JOjgcbR13Odr0aMSfjo0m5CSEvl5eWF+Ph4ZGdnGy3Pzs7GoEGDWG+HYRh9I3JcXBxOnz6NvLw8/ePuu+/G8OHDkZeXZ9brY207bFGlhgWxqjRSHHpyN5aahS2hvhpCCAHmzp2LSZMmISEhAYmJicjMzERBQQFSUlIAAGlpaSgqKsLmzZsBAO+++y6ioqIQFxcHoHnemjfeeANPPfUUAECtVqNXr15G+wgKCgIAo+UvvPACRo0ahcjISFRVVeHjjz/GwYMH8fXXX3M6fgo1Bhp9AeuDFvYJVaVxRYOwUMNOnbyusLoSSoxmYcP5aizhO18NE+wPRXkVPEJaQ1t2Fcm+j2F/zWbOx04IIVI3ceJElJWVISMjA8XFxejVqxf27t2L6OhoAEBxcTEKCgr062u1WqSlpeH8+fNQqVSIjY3FihUrMHPmTE77vXz5MiZNmoTi4mIEBgaid+/e+PrrrzFy5EhO26FQYwdVadwT9dUQQohls2fPxuzZsy0+t2nTJqPvn3rqKX1Vhi3TbQDAxo0bOW3DGuqpscFSoLGGqjTCbI9rE7S10OjIpfbUV0MIIfJEoYYjd6vSyOFqJzFubmmJ7j5QltCl3YQQIn0UaqyQWpWGDbndEsEVx8t1vhrdXbsJIYRIH4UaDsScPdgeMeamEbNKI+a2bVW6uATMBn/rz9EQFCGEyA+FGguEqNI4e+iJa9VDysNOQgU4PiGUhqAIIUS+KNSwJHaVxlUzCIvJWcGJzSR89oIqDUERQoj8UagxQVUa98d21mgagiKEEHmhUGNAYyXQuLJKIzRnBxp7+2MbyMT6Gdnqq7GFhqAIIUR6KNTw5Kwqjb2hJ7ld8cSWvfMWqlnYEjZ9NYQQQqSHQo0dVKWRBzaT8BkOLdKl3YQQ4n4o1PAglSoNF64MNHIOU7b6amgIihBCpIVCjQ2unJeGDXcdenI2S301NARFCCHyQze0tMJaoBGySuOsy7ilUCmxdfdua3fsjvYpw8XaEP33ka2uofB6kFiHaBfd4JIQ4kxXrvtBCW+HtqG53rKu4qRKjUxRlcY8MBoGS8Pw6WhfDZtLu2kIihBCXI9CjQWurtIISQpVGndkOrswIYQQ16NQI0Huehm3lAMW274augqKEEKki0KNCXeq0hB+uA5B0VVQhBAiDRRqDGh8uQUaMQhZpZFyZcQU35mF2V4uz6Wvhi26CooQQqSFQo0DqErDHdegxfUqMGvNwnzREBQhhMgHhRo7pFSl4UJOVRqpsHcfKBqCIoQQaaNQw5MrqjRybRCWI1u3TDBEQ1CEECIdFGps4Noc7Aiq0oiPb18N1yEoqtYQQohrUKixgs+wE1VpHCNGszDX99HeEJQtNGcNIYS4luRCTVVVFRYsWICkpCSEhYVBoVAgPT3d4ro///wzRowYAT8/PwQFBWHChAk4d+6cqMfXEqo0XVQaTg9XHKMtQr1HbC/tpiEoQgiRBsmFmrKyMmRmZqK+vh7jxo2zut4ff/yBYcOGoaGhAZ988gnef/99/PXXXxgyZAiuXHHsQ1NqVRpn4hNS+LyGCyFDn7PQEBQhhDif5G5oGR0djfLycigUCpSWluK9996zuN5LL70Eb29vfPnllwgICAAAxMfHo0uXLnjjjTfw6quvCn5sYlRp2HDW0JPY4UQKNH4aKKube2SaArRQVTbn+kY/wNPGlDf1gUp4Vxj/fCzd4NIjpDW0ZVeFPWhCCCGsSK5So1AooFDYvvKkqakJX375Je699159oAGaA9Hw4cOxe/du3vt3dpVGakNPrsY3wLGdhI8NPpd20xAUIYS4nuRCDRtnz55FbW0tevfubfZc7969cebMGdTV1Vl9fX19PSorK40eAODpaz3QUJVG3NeLyZG5hthe2m0JDUERQohzyTLUlJU1Vzdatza/2qR169ZgGAbl5eVWX798+XIEBgbqH5GRkTb3ZyvQuEOVRsqBxBp7P1sxQijbS7vpKihCiJytWbMGMTExUKvViI+PR05OjtV1P/30U4wcORJhYWEICAhAYmIi9u/fb7ROY2MjMjIyEBsbC7VajT59+uDrr7+2us3ly5dDoVAgNTWV87HLMtTo2BqmsvVcWloaKioq9I/CwkIxDs9h7nwZtyuHyoS4DxQNQRFC3FFWVhZSU1OxaNEinDp1CkOGDMGoUaNQUFBgcf3Dhw9j5MiR2Lt3L3JzczF8+HCMHTsWp06d0q+zePFirF+/Hm+//Tby8/ORkpKC8ePHG62jc+LECWRmZlociWFDlqEmJCQEwI2KjaGrV69CoVAgKCjI6uu9vb0REBBg9LCGqjSu2ZYpZ18BZdhXQ0NQhBC5M225qK+vt7jeypUrMW3aNEyfPh3du3fHqlWrEBkZibVr11pcf9WqVViwYAFuvvlmdOnSBa+88gq6dOmCL774Qr/Oli1b8MILL2D06NHo1KkTZs2aheTkZLz55ptG26qursYjjzyCDRs2IDg4mNd5yjLUxMbGwsfHB6dPnzZ77vTp0+jcuTPUarXD+3FVHw3g3lUasQg5CZ81NARFCHGWyio1Kqp8HHpUVjV/FkZGRhq1XSxfvtxsfw0NDcjNzUVSUpLR8qSkJBw7dozVMWu1WlRVVRm1h9TX15t9Jvv4+ODIkSNGy+bMmYMxY8ZgxIgRrPZliSxDjUqlwtixY/Hpp5+iqqpKv7ygoAAHDhzAhAkTRD8GqtKIRy6Bju0QFFVrCCGuVlhYaNR2kZaWZrZOaWkpNBoNwsPDjZaHh4fj0qVLrPbz5ptvoqamBg888IB+WXJyMlauXIm///4bWq0W2dnZ2LNnD4qLi/XrfPzxx/j5558thi0uJBlq9u3bh507d+rLV/n5+di5cyd27tyJ69evAwCWLl2K69ev46677sK+ffuwe/dujBkzBqGhoXjuueccPga+w05CcMaHulQDDReONAuz6avhMgRF1RpCiJSZtlx4e3tbXde0J5VhGLtTrQDA9u3bkZ6ejqysLLRp00a/fPXq1ejSpQvi4uLg5eWFJ598Eo8//jiUyubKd2FhIZ555hls3brV4VEWSYaaWbNm4f7778fUqVMBADt27MD999+P+++/HyUlJQCAuLg4HDx4EJ6enrjvvvswZcoUdO7cGYcPH0ZYWJhD+3dk2EkuVRqxuENYssfSEBQhhMhdaGgolEqlWVWmpKTErHpjKisrC9OmTcMnn3xiNnwUFhaGzz77DDU1Nbh48SL++OMP+Pn5ISYmBgCQm5uLkpISxMfHQ6VSQaVS4dChQ3jrrbegUqmg0bD/XJHcjMIAcOHCBVbrxcfH49tvvxX3YEyIPexEVRrxePo1oLHaS9BtNgZ6wrOi0WgZE+wPRXmV0bJk38ewv2azoPsmhBAheXl5IT4+HtnZ2Rg/frx+eXZ2Nu655x6rr9u+fTumTp2K7du3Y8yYMVbXU6vVaN++PRobG7Fr1y79ENUdd9xh1iP7+OOPIy4uDs8//7y+osOGJEONK7myOZgLvlUaKQWaTl5XcK6BfVUt2qcMF2tDbK7TxrcaJTUcrs22wPCWCQ3+gFeV7fX1r6PbJhBCZG7u3LmYNGkSEhISkJiYiMzMTBQUFCAlJQVA85QoRUVF2Ly5+Y+07du347HHHsPq1asxcOBAfZXHx8cHgYGBAIAff/wRRUVF6Nu3L4qKipCeng6tVosFCxYAAPz9/dGrVy+j4/D19UVISIjZcnskOfzkKgH+1mchBtyjSiMXzvhZWOurscawr4bPEBQ1DBNCpG7ixIlYtWoVMjIy0LdvXxw+fBh79+5FdHQ0AKC4uNhozpr169ejqakJc+bMQbt27fSPZ555Rr9OXV0dFi9ejB49emD8+PFo3749jhw5YnPqFb6oUsOS2M3BXEi9StNFpcHfTc7pO4lsdQ2F14OsPh/oX4uKKvMmXiGxHYIihBA5mD17NmbPnm3xuU2bNhl9f/DgQbvbGzp0KPLz8zkdA5vtWkKVGgHIoUojpWEnVxJqvhpr6CooQghxHQo1LLhDlYZww/fSbkM0Zw0hhDgXhRo77AUaZ17CzRdVadhh01djyLCvxtJEfIQQQpyLQo0EuGODsCuDFJfKmmGzsFBoCIoQQlyDQo0NUqvS8Bl6knqVxtY5WQp7ln6mXGcW5tNXQ0NQhBAifRRqrHA00LDljlUaObN2ywRruAxBUbWGEELExeqS7sOHDwuys9tuu02Q7YhNiMZgoa94cscqjTuzNBGfIZphmBBChMcq1AwbNozVzaxsUSgUaGpqcmgbUiGH5mDCnsZPA2W1/Xl1DGcXbvBXwKuKYbV9wzlraIZhQggRD6fhJ4Zh90vc9DW6hxxIcdiJLuPmzvR95Hv7C0eGoCw1DBNCCBEP554aw5DC5iEnYa2cM+zkDDT0ZJutZmGul3azQQ3DhBAiPk6h5o033oBWq+X0eP3118U6dqejKg03YgUrPldAiY3LvaCoYZgQQsRBVz+xxOZDk6o08mVrvhquswtzGYKiag0hhAiHVaPw3XffDYVCgS5dunDeQZcuXXDPPfdwfp3csA00LaVKI5TO3pdxpj7c1YchCGoYJoRw0VjjBQ+tl0Pb0NYKP5wuZaxCzWeffcZ7B3fffTfuvvtu3q+XAlcPbXAhxypNJ68rONcQJvp+TO/Y7enXgMZqy78wmgK0UFVyK2TWByrhXcH950+XdxNCiDBo+MkOIYedqErjXGLdiNSRIShLDcOEEEKEIUioefPNN6FUKqFSsSr8yIacKjSAPKs0QnL0/WLbVyMUahgmhBBhCVapkeMl3EKgKo374nNpN987d1PDMCGEOI6Gn6xw1bATX1Kt0jjzsm42hLi5JcD9BpfWhqCoWkMIIcKhUGOBK4edqEojXWIMQRmiag0hhDiGQo0JtoGGqjTywLVZ2FZfDVtsbptADcOEECI8CjU8iDXJHlVppMdWXw3XIShrDIegqFpDCCH8CRJqnnvuOWi1Wmg08q4YtPepEHR7zmgObglVGmdUuwghhMgfVWo4ktKwEzHHZvjQXrOwEJd2cx2ComoNIYQ4jtXEMlOnTgUAPPjgg0hKSuK0g/379yMrKwsKhQIbN27kfoQSIrVhp5ZQpZECW7MLN/gDXlW6rxXwqmp50xoQQohUsKrUbNq0CR9++CF+/fVXzjv49ddfsWnTJmzatInza6WES6ChKo1zsH1PxJpZmAuq1hBCiPho+ElgXAMNVWmayalJ2tYQlGHDsOEQFCGEEPFxCjXz58+HUqnk9FiwYIFYx+40Yg07EddxpK/GVAOPq7MNqzWGaDI+Qgjhj1Oo0d0KgctD7sQcdqIqjXzwuWUCwO62CdbmrKEhKEII4YZ1qOEbUOQcbKQYaIh9zpgRmu0QFCGEyM2aNWsQExMDtVqN+Ph45OTkWF33008/xciRIxEWFoaAgAAkJiZi//79Vtf/+OOPoVAoMG7cOKPl6enpUCgURo+2bdtyPnZWVz8dOHCA84blTqpDTlSlkSbDq6BsaQz0hGdFY/PXwT7wLG8eBmOC/aEob96AR0hraMuuAmiu1uyv2SzOQRNCiImsrCykpqZizZo1GDx4MNavX49Ro0YhPz8fUVFRZusfPnwYI0eOxCuvvIKgoCB88MEHGDt2LH788Uf069fPaN2LFy9i3rx5GDJkiMV99+zZE99++63+e6WSe18iq1AzdOhQzhuWM66Bhqo00tfGtxolNbYnmfH0a0BjtZf+e42fBsrqG/9T2bq025b6QCW8KyiMEkJcp7Ky0uh7b29veHt7m623cuVKTJs2DdOnTwcArFq1Cvv378fatWuxfPlys/VXrVpl9P0rr7yCPXv24IsvvjAKNRqNBo888giWLl2KnJwcXLt2zWxbKpWKV3XGEF395CBnXr5NVRphmTYLcyXEEBRd3k0IsUZZo4Sy2sFHTfMfZpGRkQgMDNQ/LAWUhoYG5Obmms1Hl5SUhGPHjrE6Zq1Wi6qqKrRubXzRQ0ZGBsLCwjBt2jSrr/37778RERGBmJgYPPjggzh37hyrfRpiValpScQedqIqjbCifcpwsTbE1YcBgN8QFCGEOENhYSECAgL031uq0pSWlkKj0SA8PNxoeXh4OC5dusRqP2+++SZqamrwwAMP6JcdPXoUGzduRF5entXXDRgwAJs3b0bXrl1x+fJlLFu2DIMGDcJvv/2GkBD2v+OpUmMg0ucqp/WpSuM8cp/QkO2cNVStIYSIISAgwOhhKdToKBTGlWaGYcyWWbJ9+3akp6cjKysLbdq0AQBUVVXh0UcfxYYNGxAaGmr1taNGjcK9996Lm266CSNGjMBXX30FAPjwww/ZnJ4eVWp44vMhS5dwy48jfTW2bptgrWGYEEJcJTQ0FEql0qwqU1JSYla9MZWVlYVp06Zhx44dGDFihH752bNnceHCBYwdO1a/TKttniJDpVLhzz//RGxsrNn2fH19cdNNN+Hvv//mdA5UqeHBmYGG8GPpsm42t0swnYTPHtO+GlsT8VG1hhAiZV5eXoiPj0d2drbR8uzsbAwaNMjq67Zv344pU6Zg27ZtGDNmjNFzcXFxOH36NPLy8vSPu+++G8OHD0deXh4iIyMtbrO+vh6///472rVrx+kcqFIjcVSlEVegfy0qqizP7isEtje5pGoNIUQK5s6di0mTJiEhIQGJiYnIzMxEQUEBUlJSAABpaWkoKirC5s3NU01s374djz32GFavXo2BAwfqqzw+Pj4IDAyEWq1Gr169jPYRFBQEAEbL582bh7FjxyIqKgolJSVYtmwZKisrMXnyZE7HT5UajqhK0/KY3jKB7+zCpqzNMGyKqjWEEGeZOHEiVq1ahYyMDPTt2xeHDx/G3r17ER0dDQAoLi5GQUGBfv3169ejqakJc+bMQbt27fSPZ555htN+//e//+Ghhx5Ct27dMGHCBHh5eeGHH37Q75ct0So1J0+exLJly/DZZ5+JtQunc3agoSqNPDT6AZ4GI1u2roKyNWeNtcn4CCHEmWbPno3Zs2dbfG7Tpk1G3x88eJDz9k23ATTPNCwEXpWakpISNDZaviQ1JycHd955JwYMGIAvvvjCoYOTEmdffUOBxnW49tXYY2vOGqrWEEKIcDiFmo0bNyI8PBzt2rVDq1atcN999+lnBfzrr7+QlJSEYcOGITs7W9b3fDLFN9DQsJNzcJlbiE2zsNhsNQxbm4yPEEKIfaxDzcGDBzFjxgxcuXIFDMNAo9Fg9+7deOSRR/Dzzz8jISEB3333nVuFGcA1gYaqNM7FZmZhe301XK6C4ouqNYQQYhvrULNu3ToAxpPyMAyDr7/+Gg899BCqq2/8BaxQKHDfffchNzdXwEN1PqrQEKHwHYKiag0hhLDHOtScOHECQHNgmThxIubOnYvIyEgwDIMzZ87on5s8eTLy8/PxySefoG/fvqIctM6pU6cwbtw4REREoFWrVoiLi0NGRgauX7/u8LZdFWioSiMcS3PVsCV0X40ptkNQpqhaQwgh1rG++unSpUtQKBR44IEHsG3bNgDAQw89hJtvvhkAEBgYiK+++srmBD1Cys/Px6BBg9CtWzesWrUKoaGhOHz4MDIyMpCbm4s9e/bw3rarpuSnQCMvprMLc7kKypSt+0HRlVCEEMIO61BTW1sLhUKB3r1765f16dNH//WUKVOcFmgAYNu2bairq8OuXbv0UyzffvvtKC4uRmZmJsrLyxEcHMx5u44EGhp2cm+mt0zgynQiPraXd5vyCGkNbVnzfcqSfR/D/prNvI+JEELcCedLur28vPRfq1Q3MpG1qY7F4unZ3IcQGBhotDwoKAgeHh5Gx8mWI6GEhp3kw9IVUGyahcVGvTWEEOIYzpPvrV27Fl9++SWr5QqFAt999x3/o7Nh8uTJWLVqFWbNmoVXX30VYWFhOHToENavX485c+bA19fX6mvr6+tRX1+v/76ystKhY6EKjXvy9GtAY7XtcMx1CIrtbRMAqtYQQghXnEPNuXPncO7cOf33uquhTJezvVU5Xx07dsTx48cxfvx4ozt8Pv3001i1apXN1y5fvhxLly4V5DiECDRUpXEAw2DImr8xZ8f/0KqqAed7hmLbggEojg1i9fKkQ79h+at7cHBgV0x/dpLRc+FXKzHvw28x7PSfUDc24lx4KBZMuQ+/h96Ytjv20mUs/HQvbrlwFgqGwZk24Zg3djKKA9gNfZoOQVFvDSGE8CfbG1rqbmUeHh6OnTt3IiwsDD/++COWLVuG6upqbNy40epr09LSMHfuXP33lZWVTh8+03H3QPN3E/8eFDYS3z+HAZvP4/2XBuNyVADGvH8azz6ZjRd3jkO9r+3ZetterkDqe9/j557m731AdS2yXtqAY11jMTl1KsoCfBFdchWVrW5cmRRVWopPVr+Lnf0H4K3bk1Gt9kHslcuoVwr3vxVVawghhD3Wv32joqJErbxwtXDhQlRWViIvL08/1HTbbbchNDQUU6dOxWOPPYahQ4dafK23tze8vb0dPga59tH43VcCTZwn4KGA584awFOBuvkBaJjQCj6LrsHrq1poQz1QuywITbf/+yGuYeCzoByqo/XwuKKBNkKF+sm+aJj+b69HHQP/UZfRdLM3al9rrlJ4FDShX1IRChcFo/QhEXpCGAa3bDmPo090xqnbm6snH6QPxhvJn2DA/vM4PKErIltdQ+H1ILOXemi0ePn1PVj/6BD0+60Q/tX1Rs/P/DwHxSGBmD/1Af2y/4U2X06t/Hd46bkvv8bBHnF4PXmsfp3C1iEAuA1B2WoYNjtlG9UaCjaEkJaOdai5cOGCiIfBXV5eHnr06GHWO6O7xPzXX3+1GmqEIPc+Gq8d11E3yx/VX7aB5+e18Em7Bs/9dWi8U42qp/zhvaEarZ4uR+UJb8DHA9ACTDslrq8LAdPaA8qTDWi1oBxMGyUa724FqBW4/nZr+I0tQdPtajSOVKPV01dRlai2GWi6PHYZ/ieaA0VfFFpc59Nf+ltcHvS/WviV1uPcoFBE+5ThYm0ImryU+Kt/ODr9XwkOT+hqdb+pO79HeWAr7Enui36/Ne830L8WFVXNIe6Ok38gp09nrMvcjJvzL+ByUCA2Dx+Ij4cOAAAotFoMz/8dmXcMw3sfrUPPwn/wv+DWWD/kDnzb4yb7b4ANpkNQbKs1hBD3oqz0gLKB1y0a9TR1jr1ebmQ7/BQREYFff/0V1dXV8PO7MUf98ePHAQAdOnQQbd/u0Eej6eGJ+tQAAED9Uyqo360CE+yBhkeaf5Z1zwbAe3MNlPmN0MR7N1dz5t240kwbpULDyXp4flHbHGoAaHp5oW5BIHzml0M1rhU8LjbhQmYbm8dx4bUQeNQ1Vy0KG1vbXNeUb2kdAKAmxLjqVtnaByGXrN/jqcfpf5C89zdMfGuG1XUiS8rxcPYJvD9mEN5OvgN9zhdi6fbP0eCpwqeD4hH+Tw386uuR8u33WDl6FN68fSyG/P0H3vl4EyY9Pgt5YZ2NtkfVGkIIEZ9sQ01qairGjRuHkSNH4tlnn0VoaCh++OEHLF++HD169MCoUaNE2a87BBoA0HQ36DdRKsAEexgtY8Ka072i7MY9jrw2V8Nrew08/qeBoo4BGhloehr3rdTP9IPn/lp4v1+N6q2haGptu6emse2Nf4LVDWp+J2MyKqpgGDCmC//lc70B85d9g9Xz7sC1wFbWN6ll8GtsBN58aCQaq73wW3R7dP3nMiYd+AGfDoqHx7/3OPu2Vy+8P/w2qCo98Hu79uhXcAEPnTiOEw90NhqC4oqqNYQQwp0goeaLL77AqlWrcObMGQQFBWHUqFFYuHAhgoKChNi8RXfffTe+++47rFixAs888wwqKioQGRmJmTNnIi0tjdc8Nfa4S6ABAKhMkwCM/zX82z+l+DfTeH5+HT5Lr6H2xSBoErzA+HrAe20VVKeMbyegKNXC42wTGCXgcb4JGGL7MBwZfqoJbQ5BvqX1qA67EYj8y+tQGWI5ILUrqkDbS5VIf+ELLGG+AAB9QPnxruVI+m8qCtq2xpVgP5xpb1xlOtOuDUbl/goAKPf1RaOHB/5uGw7gxqXdZ8PaIL7gvO2TFgBVawghxBzrUPPOO+9g7ty5UCgU2Lt3L+644w4AwIcffoipU6cCaL6Mu7CwEL/++iu++uor/PTTT/DxsX4fG0cNHz4cw4cPF237htwq0PCg+qkeTfHeaJhyY6jP42KT2XqtniuHppsnGh7xhc9z5VAP9EFdV+sB05Hhp2sdfFAd6o2Y46W43L15aEzZqEHXny/j06fiLb6mMCoYKR88AgC4Wtv8b3P25sNoVVuPN2aORHFg85BcbrcoxBSXArgxX03M5VIUhQQBABpVKvxfVCQ6lZQYbT+m7Ar+CWxulOY6Zw2Xy7tNUbWGEEI4zCj8888/o6mpCcHBwfpAo9VqsWjRIjCM8WRiDMMgPz8fa9asEfZoXUTuTcFC0HRUQfV/DVAdrIPH2UaoX6uA6hfjKo3Xpmooc+txfXUwGse3wtXRrdDpmVIoGqxPNtfYVoX6jp74PSIC1dFqiw+rFAr8NCkGgzecQbdvLyHiTDmmLD2KBrUKPybH6Fd77uVvMCXzaPP+vFW42CkEFzuF4GzHNjjbsQ2q/Lxx3ccbZzu2Qavg5hDxwehB6Pt3IWbtPoToS2W454dTePjQj9h8e/OtQDR+Gmy4fRjGnPoFE4/9gOgrpXj0hxwM/zMf2wYM5vtjtsn0RpemswzTzS4JIS0d61Dzf//3f1AoFLj11lv1y44ePYp//vlHf6l3//79MXjwjV/on332mXBH6iJCBRo5V2kAoGGSHxpG+cB3Vhn8xpZAUa5F/WSDqs2ZRvj8pwK1rwSDad9cALz4n9ZQVWrR/s1roh3X8amd8NOjMbhz2a9YNPkrBJfUYtXbI4zmqGlTUoXWZdzu3H66cwfMfu5h3HX0/7B33jt4+svvsPTBsfhsYD/9Ot/0uQkvPnAvZn53EPtefQP35f2Ipx6cgtzoTla32+Bv+r3xMKDp3btt3TrBHgo2hJCWhvXw0+XLzTd67Nixo35ZTk6O/utOnTrhp59+goeHB4YOHYqcnBz8/vvvwh2pC7hFoNEwUP1YD0WJFkwbDzQN8Eb1TvMrkip/bGe27FqRwRVk3grU/rc1av9rvE5dWvOwj7azJyrOtjd6Tuvvgf87Kt5VaAAAhQI5c7oiZ05XXKwNsbjK86vvtbi8jW81Smr8kD53rMXnD8R3w4H4bgBg9XYJOwbegh0Db9F/b3jLBMB8CMpRpg3Dpr01NAxFCGnJWFdqysrKAAChoaH6Zbm5ufqvJ0yYAA+P5s3dfvvtAICqKvlO6e4OgcZzby0CBlyC3/2l8J1zFX73lyJgwCV47nX9zRudKbLVNYe34enXYLZM4yfOe2uvWmM6DGULVWsIIS0J51l5iouL9V8fO3ZM//WgQYP0X+vuoG04f4ycuEMPjefeWrR6ogyKYuMPXsUlDVo9USZ6sBH79ghS1RSgtbuOvSEormz11hBCSEvCOtRERESAYRh88sknOHr0KFavXq0fkgKMQ01hYfOluW3a2J54TYqEDDQuq9JoGPi8dA1gzKZwgeLfnl2fJdcADbu7Rbc0gf7CBr5GHtmeqjWEEMId61Cju+VASUkJbrvtNv0NIRUKBfr164ewsDD9useOHYNCoUBUVJTAhyuujl6lgm3LlcNOqh/r4VGssTL9XHOw8fhHA9WP9VbWIM4mdrWGgg0hpCVgHWqee+45/bCS6SXc8+fP13/9119/4fTp0wAg6r2XpMzVVzopSuwPgXBZjzRj21fDZwiKDXvVGtNgQwghLQ3rUNOjRw98+umnaNu2LYDmYKNWq/Hqq69i4sSJ+vXeffdd/fO6huGWxNWBBgCYNuzeVrbrEcexGYKyd3k3V1StIYS0NJw+1caMGYPCwkL88ssvyM3NRWlpKebNm2e0zsKFC3H+/HmcP38eAwYMEPRgpU4KgQYAmgZ4Q9tOCcbKiAajALQRSjQN8La8goPk1CTcxlfA6605cka1hoINIaQlYR1qDh8+jMOHD6O4uBg33XQT+vXrh1atzG8I2K5dO0RHRyM6Olo/KR9xMqUCtRlBAGAWbHTf1y4NApTSeH/ONYTZX8nJuDQL8x2CskToag0hhHC1Zs0axMTEQK1WIz4+3mhOOlPFxcV4+OGH0a1bN3h4eCA1NdVsncbGRmRkZCA2NhZqtRp9+vTB119/bbZeUVERHn30UYSEhKBVq1bo27ev0dQxbLAONcOGDcPw4cORlZXFaQcthVSqNDqNo31wPTMETFvjD0WmnRLXM0PQOFq8e3K5M0t9NWzxuQrK4naoWkMIEUlWVhZSU1OxaNEinDp1CkOGDMGoUaNQUFBgcf36+nqEhYVh0aJF6NOnj8V1Fi9ejPXr1+Ptt99Gfn4+UlJSMH78eJw6dUq/Tnl5OQYPHgxPT0/s27cP+fn5ePPNNznfGFuQu3S3dFILNDqNo33QmKw2m1FYzAqNnIaepMD0JpeWmN7okg+aaZgQwsbKlSsxbdo0TJ8+HQCwatUq7N+/H2vXrsXy5cvN1u/YsSNWr14NAHj//fctbnPLli1YtGgRRo8eDQCYNWsW9u/fjzfffBNbt24FALz66quIjIzEBx98YLRtrqhT1EFSDTR6SgWaBqnROK4VmgapJTPk1BJYGoLi0zBsiaNXQlG1hpCWpbKy0uhRX28+pUdDQwNyc3ORlJRktDwpKclosl2u6uvroVYb35zYx8cHR44c0X//+eefIyEhAffffz/atGmDfv36YcOGDZz3RaHGAZIPNMRpHLllApuGYTa9NfYm5KNhKELkxbOm+d5xDj1qmrcVGRmJwMBA/cNS1aW0tBQajQbh4eFGy8PDw3Hp0iXe55GcnIyVK1fi77//hlarRXZ2Nvbs2WN0h4Jz585h7dq16NKlC/bv34+UlBQ8/fTT2Lx5M6d9cR5++uabb1Bdzf6KkZdeeonrLohM8Rl6kmKTsE6gfy0qqlzTe9Tgr4BXle0ZnxsDPeFZ0Wj1edObXRJCWq7CwkIEBATov/f2tn71q+lFPgzDOHThz+rVqzFjxgzExcVBoVAgNjYWjz/+uNFQk1arRUJCAl555RUAQL9+/fDbb79h7dq1eOwx9n+AcQ412dnZyM7OZr2+u4YaqtI415n6cPsr2RDZ6hoKrwcJciyefg1W79ptqilAK9idu9n01nC9i3ey72PYX8PtLyFCiPwEBAQYhRpLQkNDoVQqzaoyJSUlZtUbLsLCwvDZZ5+hrq4OZWVliIiIwMKFCxETE6Nfp127dujRo4fR67p3745du3Zx2pdow0+msw67Ewo07kWouWqEHoLi01vDBg1DEUIs8fLyQnx8vFnhIjs72+j+jnyp1Wq0b98eTU1N2LVrF+655x79c4MHD8aff/5ptP5ff/2F6OhoTvvgXKlx57DCBgUa4kpCVGsIIcSauXPnYtKkSUhISEBiYiIyMzNRUFCAlJQUAEBaWhqKioqMel3y8vIAANXV1bhy5Qry8vLg5eWlr7z8+OOPKCoqQt++fVFUVIT09HRotVosWLBAv41nn30WgwYNwiuvvIIHHngAP/30EzIzM5GZmcnp+DmHmkWLFukv9SJEhy7lto7tEJSly7uF6K0BaBiKEMLOxIkTUVZWhoyMDBQXF6NXr17Yu3evvmJSXFxsNmdNv3799F/n5uZi27ZtiI6OxoULFwAAdXV1WLx4Mc6dOwc/Pz+MHj0aW7ZsMZqD5uabb8bu3buRlpaGjIwMxMTEYNWqVXjkkUc4HT/nUBMcHMy5HOQuqErT8lhrFubSVyM0PtUaNijYEEIAYPbs2Zg9e7bF5zZt2mS2zN4IztChQ5Gfn293v3fddRfuuusuVsdoDV3SzRIFGuFJ+convrj01Vias4bP/aAAdr019mYaJoQQuaNQQxxGQ0/28b0XFGC5YViIeWsAahomhLgX1qEmKioKUVFRCAwMFPN4JIs+uInUWarWcJ1pGKBgQwiRL9Y9NbqGH0IM8Q177jD0ZK2vRuOngbKa3c/FkYZhvveEstc0DFB/DSFEnmj4ifDmrOqVoxPvSYUjQ1BssanWWEL9NYQQd0ChhgMagmqZAv25XUUkBLaT8VnqraFhKEJIS0WhhvDibgFPqFmF+WBz524xsLkaioINIUROKNQQzhwNNGL001ysDRF8m46wdmk3lyEosas1llCwIYTIGYUajtytQkEc4+nXIMh2HK3WsLnE2xJLw1DUX0MIkSsKNYQTZ4c6d2kS5ovvjS4B9tUa6q8hhLgLCjWENSECjTtcyu0osa6CYlutoWEoQoi7olDDAw1BETa43DIB4DYE5Ui1xhIahiKEuAMKNYSVll6lsXVZt1B9NdZwuR+UI03DNAxFCJE7znfpJi2PqypT7txP0xSgharS/G8KSzMMW2NplmGh0WzDhLiOVzWgdPBvJo24f3NJDlVqeKIhKG7kXKVxBNchKGtcWa2h/hpCiFxQqCE2UXiTNra9NQAFG0KI+6NQ4wB3/8AX6vzErtJIbeI9tqxdBWWtYdjRag0hhLg7CjUGLjSEcn7N301Ktww3rj4nufXTiN0sbAtVawghpBmFGhN8qwquDgFCEvJcWmovjSE+fTXOrtZQsCGEuAMKNRacawjj9WHsDlUbKQQaMao0hdeDBN+mEISaiM/Rao01FGwIIXJCocYGR6o2cgs3cjxmwLn9NLbmqpEqa9Uavje8tIWCDSHE1SjU2OHI8IlcgoIYxyilKo1ccR2CslatcdYwFCGEuBqFGhb4DkfpSDXciHVcLbWPxlazsK2+GrHuBWUPDUMRQtwNhRoOHP2wllK4Ees4HPkZca3SyPVSbi7ErtZwGYaiYEMIkToKNRwJUYVwZbiRUrAi4uDSNGwNl/4aCjaEEKmQfag5cuQIRo8ejeDgYPj4+KBLly74z3/+w2tbbAOLo8NROs4OGGLvy5lVGjkSegiKy+XdALdqDcDtppcUbAghUiDrULNt2zYMHToUgYGB2Lx5M/bu3Yvnn38eDMP/Jn9cPlyF6h0RK9zotuuM8NRS+2icwdoQlC1CNA1bw+Zu3joUbAghziTbu3QXFRXhiSeewMyZM7FmzRr98uHDhzu87TP14ejsfZnVuucawtDJ64rD+wSsV1K6qNhN3taShpW49NNIdY4aITT4A15Vjm+nMdATnhWN5suDfeBZbn4pOxPsD0W58Y4t3dGbEEKcSbaVmvfeew81NTV4/vnnRdk+14qNmJUK04qLtYerOHru7jT05MjtEmwNQTmjWsNlGMoaGoYiRP7WrFmDmJgYqNVqxMfHIycnx+q6xcXFePjhh9GtWzd4eHggNTXV5rY//vhjKBQKjBs3zmh5x44doVAozB5z5szhdOyyDTWHDx9G69at8ccff6Bv375QqVRo06YNUlJSUFlZafO19fX1qKysNHpYcqY+3CXDUXLSEs/ZEXxumWAP194aWxy9zBugYEOInGVlZSE1NRWLFi3CqVOnMGTIEIwaNQoFBQUW16+vr0dYWBgWLVqEPn362Nz2xYsXMW/ePAwZMsTsuRMnTqC4uFj/yM7OBgDcf//9nI5ftqGmqKgI169fx/3334+JEyfi22+/xfz587F582aMHj3aZl/N8uXLERgYqH9ERkba3BcFG8uEOFd3qtKIzZW9NVwu8wYo2BAiVytXrsS0adMwffp0dO/eHatWrUJkZCTWrl1rcf2OHTti9erVeOyxxxAYGGh1uxqNBo888giWLl2KTp06mT0fFhaGtm3b6h9ffvklYmNjMXToUE7HL9tQo9VqUVdXhxdeeAFpaWkYNmwY5s+fj+XLl+Po0aP47rvvrL42LS0NFRUV+kdhYaHd/UlpOMrVhDo/voHGneen4TsRH59qjVDDUBRsCJE+09GJ+vp6s3UaGhqQm5uLpKQko+VJSUk4duyYQ/vPyMhAWFgYpk2bZnfdhoYGbN26FVOnToVCwW2KCtmGmpCQ5g+25ORko+WjRo0CAPz8889WX+vt7Y2AgACjBwAU1tqe+p3PcJS7BRy5nYs7NwmzxWfeGqGCjSUUbAhhx6uKEeQBAJGRkUYjFMuXLzfbX2lpKTQaDcLDjT/nwsPDcenSJd7ncfToUWzcuBEbNmxgtf5nn32Ga9euYcqUKZz3JdtQ07t3b4vLdcNOHh78To1NFYBruAHkX70R+vhbcpXGkb4aW0NQtqo1Yl7ibYu1e0RRsCHEuQoLC41GKNLS0qyua1odYRiGc8VEp6qqCo8++ig2bNiA0NBQVq/ZuHEjRo0ahYiICM77k22ouffeewEA+/btM1q+d+9eAMDAgQN5b/tibYjo4UYuAUeMY23JgYYNV90LypSYw1AABRtCnMl0dMLb29tsndDQUCiVSrOqTElJiVn1hq2zZ8/iwoULGDt2LFQqFVQqFTZv3ozPP/8cKpUKZ8+eNVr/4sWL+PbbbzF9+nRe+5PtPDVJSUkYO3YsMjIyoNVqMXDgQJw8eRJLly7FXXfdhVtvvdXhfVysDUG0T5nd9XQf0mznttExDAtCzXUjFLFClzMbg7kMPZXU8OjCtcLTrwGN1V6Cbc9Uox/gWW35OVvz1jT4K/SlaEP1gUp4V1iuHgkxfw1gfQ6bZN/HsL9ms+UDJoQ4lZeXF+Lj45GdnY3x48frl2dnZ+Oee+7htc24uDicPn3aaNnixYtRVVWF1atXm12o88EHH6BNmzYYM2YMr/3JNtQAzZeeLV26FJmZmVi6dCkiIiLw7LPPYsmSJYLtQ1cdEDPcAJZDhLODjtjVI0cCTUup0rgKBRtCCADMnTsXkyZNQkJCAhITE5GZmYmCggKkpKQAaL7QpqioCJs33/h/Ni8vDwBQXV2NK1euIC8vD15eXujRowfUajV69epltI+goCAAMFuu1WrxwQcfYPLkyVCp+MUTWYcaHx8frFixAitWrBB9X2yrNoBj4caQacgQOuQ4cwiMLt02pvHTQFltvZ+lKUALVSW/0WE+1Rq+KNgQ4l4mTpyIsrIyZGRkoLi4GL169cLevXsRHR0NoHmyPdM5a/r166f/Ojc3F9u2bUN0dDQuXLjAad/ffvstCgoKMHXqVN7Hr2AcuVGSm6isrERgYCBG7J2JmDDzX9Cm2IYbHUfDjaN0YcgVfTxChBk+VRquVz2xHX6qqGI3uy6b4SdboQaA3VBjbQgKsH3rBFuhxlq1BoDFag0Ai6FGx1KwAWD1dgoUbIjU6T4vKioq9FfOirWP+IkvQ+mldmhbmoY65GYtEvV4pUS2jcJiYfNhyLaRWIdPQ7GQXNWYTNUZ1+FzJRRg+2ooIW6joEPNw4QQMVCosaDwepCo4aYlfNgLdY4tuZfG3lVQfGYY1uEzd40tfOavoWBDCBEahRobxAo3gOurN2JydaARa+hJbvjeE4pPtQagYEMIcT0KNSyw/ZB0JNy4Q8Bxl/NwFjFubsmF0MNQAAUbQohrUahhiW3VBuAXbgB5Bxyhj7klDzsZcnQIypE7eFOwIYTIDYUaA1eu2x+GcEa4AeQTcMQ4RkcCjVTu9eTp1+DqQ2BF6N4aeyjYEELERKHGREmNH6seCy4fno6EG0CaAUes46EKDXeOVmucOQwFULAhhIiHQo0VbIONM8MNYBxwnBlynLFfR382fKo0cmgSdvW9oCjYEELkQtYzCotN94HXxtfGLGe48WEa2eoaq+0afnhzncjPlL2AwXbiP1dWgYSozkhl2IkrezMLs2XrflCA7VmGm5/nP9OwtdsoANZnHAaszzoM0MzDhBB+KNSwwDXcAK4JOJZIacjKElcGGjlUaaTC1r2hAAo2hBBpoOEnDrh8CHIdmgJuDE+1hL4Soc7TmRUatrdIANjdJsHZHOmtAWwPQ9lDQ1GEEGegUGOgssr+PTbYNhLr8Ak3gHHAcaeQI+T5yHXIiQ82fTVsZhh2NNjY3L+N/hp7+AYbCjeEEEM0/GRC99d4oL/tG1saBht7w1IAv6EpQ2IPU4lJjFDmaKChoSd+xBqGAvgNRQE0HEXcl1elBipPxybpbGp07SSfzkaVGisqqnxYDzc4q3qjY1rFkWIlR8xjo0BjnTOqNfaGofheEWWPtYoNQMNRhJBmVKmxg23lBmDfUKzjaPXGkKXw4OyKjjPClauGnLj007gDR66GAsRpHAaoYkMIsY1CDUsVVT6sgg3APdwAwgYcHTYhg0vwcXVFSIhAI+cqTVOAFqpKYYqr9i7xtsfeMJQ99oINABqKIoRwRqGGAy5VG4BfuAHECTjWuDqosOXOgUaouWp07M1Zw5a9ao0j/TWAuD02ACjcENICUU+NgcYadpfh6vptuPbc8PlQ1fXftKQrfUy15HMXkyM3u9RxpL8GsN9jw+eqKB3qsyGk5aFQY6Kx2ovTHCNcwg0gXMBpCR/0Qp6nI1UaKfXTsL1lApuGYTbYXOJNwYYQIhUUaqwQO9wA3K+aMuWuIUfo85HqsJMUsKnWCHEnb7GDDV0ZRQgBqKfGLl2w8fRrYLU+174bgPucN9aYBgGx+3GE5k7BTAqE6q1hg03jsJg9NgD12RBCqFLDGt/KDd/qjRDVBblUcsQ8Pkd/jlIaehKLUNUaNrdRELNiA9BwFCEtHVVqOOJauQH4VW8A4So4OraCg7OqOs4KV0KEwpYQaLhgM3eN1Cs2AF32TYg7o1BjQFmjBMPyc8yRcAO4PuCYknIlhytXBxqxb2bJZb4atkNQjs5bIzRnBBuAhqMIcTc0/GRCWa3kNGeIbliK6wcZn6EpHcMhKmqCvUGon4eUA42rOWsYChBmKIqGowhpWSjUWME13ADc+24A/r03hlpyyBH6vFvykJMQ89boSCXYANRnQ0hLQqHGDmeFG0CYgAO4f8gR69wc/bnzrdIIOZuwJULNWaPD9hJvZwYbaiAmhADUU8Oa7oNH48f+fjd8+m50HOm/MWXtw1+M3hyxiB3OWnKFxhDb3hpHb3hpyF7jMGC/xwagPhtCCFVqOHOkcsP3L3mhKjimTCs6UqvqOOu4hPi5unsvDV9sqjWAMBUbwPFLvgGq2hCyZs0axMTEQK1WIz4+Hjk5OTbXP3ToEOLj46FWq9GpUyesW7fO6PnGxkZkZGQgNjYWarUaffr0wddff220TlNTExYvXoyYmBj4+PigU6dOyMjIgFbLbhZ1HarU8MSncgMYf/i5uoJjCdsAIUSVRwohiio05oSu1rC9o7czKzYA6LJvQizIyspCamoq1qxZg8GDB2P9+vUYNWoU8vPzERUVZbb++fPnMXr0aMyYMQNbt27F0aNHMXv2bISFheHee+8FACxevBhbt27Fhg0bEBcXh/3792P8+PE4duwY+vXrBwB49dVXsW7dOnz44Yfo2bMnTp48iccffxyBgYF45plnWB+/gmEYYWrIMlZZWYnAwEB0WvQKlGo16/vrmOIacHT4hBtLxAg57kyoQONolYZPTw3bS7oNcZldmMvl3WyHodgEG3uhRr+enWADwGaw0bEVbHQo3BBDus+LiooKBAQEiLqPxFEZUHmqHdpWU2Mdju97ifXxDhgwAP3798fatWv1y7p3745x48Zh+fLlZus///zz+Pzzz/H777/rl6WkpOCXX37B8ePHAQARERFYtGgR5syZo19n3Lhx8PPzw9atWwEAd911F8LDw7Fx40b9Ovfeey9atWqFLVu2sD5fGn6yQFXpwetDg8/QFOD48JSO4TAVVSCsE/Ln467DTlyuhHJ24zDAfiiKLvsmpFllZaXRo76+3mydhoYG5ObmIikpyWh5UlISjh07ZnG7x48fN1s/OTkZJ0+eRGNj8x8p9fX1UKuNw5mPjw+OHDmi//7WW2/Fd999h7/++gsA8Msvv+DIkSMYPXo0p/Ok4ScbdMGGa+WG79AU4PjwlCFLH9wttZrjbiGPywR8UsJ2xmHAftWGzVAUYH84CqAmYiJNnpWNUKkcuzpS0dT8/1FkZKTR8iVLliA9Pd1oWWlpKTQaDcLDw42Wh4eH49KlSxa3f+nSJYvrNzU1obS0FO3atUNycjJWrlyJ2267DbGxsfjuu++wZ88eaDQ3fhc8//zzqKioQFxcHJRKJTQaDV5++WU89NBDnM6XQg0LjoYbwPGAAwgzTNXSgo6YYUaIKo3Yl3Mb4nqDSy6zDHO5GsrZPTaAMMEGoF4bIl+FhYVGw0/e3t5W11UojKuvDMOYLbO3vuHy1atXY8aMGYiLi4NCoUBsbCwef/xxfPDBB/rXZGVlYevWrdi2bRt69uyJvLw8pKamIiIiApMnT2Z9nhRqODD8y9jZAQcQtopjyB2DjrtVZuRAyMu8ddgGG8B+nw3bYAPYbyIGqGpD5CUgIMBuT01oaCiUSqVZVaakpMSsGqPTtm1bi+urVCqEhIQAAMLCwvDZZ5+hrq4OZWVliIiIwMKFCxETE6N/zfz587Fw4UI8+OCDAICbbroJFy9exPLlyzmFGvnVryWCb98NcKP3xpG/0g37cMTo6zDtz5FDr44zj9Fde2lMCTnLsCG2l3oDzu+zAdhf+k39NsSdeHl5IT4+HtnZ2UbLs7OzMWjQIIuvSUxMNFv/m2++QUJCAjw9jf/fVavVaN++PZqamrBr1y7cc889+ueuX78ODw/jz1SlUkmXdDvCswbQcmw05zs0peNI/40hMYaqrGETGsSs9Lg6WLWUQMOHGMNQALuKDSD8cBRg/wopGpIi7mTu3LmYNGkSEhISkJiYiMzMTBQUFCAlJQUAkJaWhqKiImze3PxvPiUlBe+88w7mzp2LGTNm4Pjx49i4cSO2b9+u3+aPP/6IoqIi9O3bF0VFRUhPT4dWq8WCBQv064wdOxYvv/wyoqKi0LNnT5w6dQorV67E1KlTOR0/hRoTup4DrlPLOzI0BQgzPGXImSHHElcHDzEIGWYc7aXhWyXk2lcDcL+DtzsFG4B9rw1AQ1JE/iZOnIiysjJkZGSguLgYvXr1wt69exEdHQ0AKC4uRkFBgX79mJgY7N27F88++yzeffddRERE4K233tLPUQMAdXV1WLx4Mc6dOwc/Pz+MHj0aW7ZsQVBQkH6dt99+Gy+++CJmz56NkpISREREYObMmXjppZc4HT/NU4MbcwJ0S30FSm/jUo0j983hW70xJUTIMeXskCNnQldmhGgOduTKJ66hBuAWaprX5/ZrhW2wAYSdywZgN58NwG5OG4CCjbtz5jw1tw1+ESqVg/PUNNXh8NH/iHq8UkKVGjv4Vm4Ax6s3OkJXcQDLH9QUdG4Qa4jJmVc7uZIYTcNccanYAPbDDZfhKIDCDSGuQI3CLHlW8/sLV0fXWOzo3CJCNBlbY9p83NJ6R8Q+b6HeM1fMTyNWw7COGI3DALvmYR02DcQAuyZigCbtI8QVqFLDkWGw4Ts05WhzsY7ph6QYw1TWPuDdoarjzNDWUio0hrhWa8TorwHYV2wAbn02AFVtCJEaqtQ4QCrVGx3DKo7YH6KWqjpSrfC48hid8V44i9jVGkBeFRuAqjaESA1Vagx4VQPKBu6/vIWs3gDCNRiL0YvDliOhwVYVSGqByRYxwozcbo0gdm8N14oNwK6BmG2fDcDu6iiAqjaEOAOFGgt0V3rw+cvUkcZiHdMPLiFCjqUPWGcHHbbkFFyscZfqjBDEHIYC2N8rSr++C4ejAAo3hIhJXn/22fHee+9BoVDAz8+BRGHAq4r7paw6uqEpR4andIQeptIxHa6iD2LHiflzlEKVxhlDUAC3YSgdMYejuDQR05AUIa7j+t+SAikqKsK8efMQEREh+LYdCTeAPAKODgUd7uhnZV+Dv/Wb4VnjjGAjZq8N3WqBEOdzm1CTkpKC2267DSNHjhRtH7pwI8WAI+Zf8ZaCDn2AO7cJWApVGkdJMdgA4lVtAG6NxBRuCHGc/H9TAti6dSsOHTqENWvWOG2fjoYbQNiAAzgv5OhYCzvuHHpccX5SCzSODEFJOdi4umoDULghxFGybxQuKSlBamoqVqxYgQ4dOjh9/4bBxpFf9kJcQWVKjIZjLux98Eu1UVnHXYOZHHFtHga4XRmlfw3HJmKA/W0WqJmYEPHJPtTMnj0b3bp1w6xZs1i/pr6+HvX19frvKysrATTfr0bpxfD6a7L59c3/dbSZUoyAA1j+i9/ZQccQ39AgVBiSQ2iRWpVGh+tNLo1fy+8yb77BBmB/ZRTALdgA/MIN2/tIUbghhBtZh5pdu3bhiy++wKlTp6BQsA8iy5cvx9KlS60+r/uF62i4ad4Gr03omQ5NCRlyAOkFHTbkEEYcJdUwo+Po0CtffIINH1yDDcD+8m+AW9UGoHDTUnleq4NK6dg8TwpNvf2V3Ii0f3PaUF1djTlz5uCpp55CREQErl27hmvXrqGhoXnitmvXrqGmpsbia9PS0lBRUaF/FBYWWlzPq4rRP/gSornYkNB9OJaY9uZI/QPWnYj98xbz3w0XfP9gAJzTYwNw77MBuPXaANz6bQDquSHEHtl+WpWWluLy5ct48803ERwcrH9s374dNTU1CA4OxiOPPGLxtd7e3ggICDB62ONouGnehngBR+wPKwo64nHWz1QqgcZV+AQbgNvVUQD3K6QA9ldJ6VCwIcQy2Q4/tW3bFgcOHDBbvmLFChw6dAj79u1DaGio4Pt1dGjqxnZufC3UhGZiD1WZsvUhLPUhLFdzdiiUYqBx5BYKfIeh+PTYAOIPRwE0JEWIEGQbatRqNYYNG2a2fNOmTVAqlRafE5LhL2MpBhzA+SHHkLUP7ZYYdlxd1ZJioBGCI/01fK+MAtjdO0qHaxMxwK2RGKBwQ4gh2YYaKZFDwAFcG3J02HzAyzn4uDrAmBIj0AjZJCz2DS9t4RNsAGlWbQAKN4QAbhhqNm3ahE2bNvF6rVelBipPDa9GRP02BBqeat7Wja/FuOeOpQ88VwQdU3yCgdhBSGphxR53rc6YcvRqKGcHG4B71QagcEMIW24XaoSg+yUpRLgBhA84zdt0eJMWSTXo2CO30CGWlhJmDMkp2ADcqzYAhRtC2KJQY4MQ4QYQPuA0b9P4ezHvnizXoNOSOCvMiDE/jRBDUK4MNgC3PhuAX9UGoHBDiD0Ualgw/GUpxYDTvF3j78UMOYD1D1EKO87VEisz1rgq2ACOVW0A54YbgAIOcV8UajgSqnoDiBdwmrd942uxA44hCjvO4W5hRqiGYSGCDcD9km+Af9UGcG64Aah6Q9wXhRqehKzeADD7hS5mFad5+4JtnhV7H8IUeuxzdZBx1a0RuBLiVgqOVm0ACjeEuAKFGgEIHXAAcas4zds3/t7ZIccUhZ4bXB1eXEXIy7tdHWwA/kNSgOvCDUABh8gbhRoDnpWNYELUDm1D7IADOCfkNO9H8N3wxvWDXi4hqKUGGGcQKtgA/IajAMeqNoDj4Qag6g1pWSjUmND98uJ7nxhDYgQcQPwqzo39mC+TUtCxhcICEZIrqzYAv8vAdah6Q1oSCjVWGP4Ck0vAAcQNOc37s7xcLmGHcOesXhoxZhYWolqjI0SwAZxftdHhG24Aqt4Q+aAZy1jwrGh06JeZKe8Kjf4hNN3dxIW4qzi3/Zo/iHw5+3101a0SuBLiDxyud/02xecu4Ia43hHcULLvY3SH8BZgzZo1iImJgVqtRnx8PHJycmyuf+jQIcTHx0OtVqNTp05Yt26d1XU//vhjKBQKjBs3zmh5VVUVUlNTER0dDR8fHwwaNAgnTpzgfOwUajjQhRu5BBzAdSGned/WH0SaXPH+yCXQCMnRYAPA4WBD4YZYkpWVhdTUVCxatAinTp3CkCFDMGrUKBQUFFhc//z58xg9ejSGDBmCU6dO4YUXXsDTTz+NXbt2ma178eJFzJs3D0OGDDF7bvr06cjOzsaWLVtw+vRpJCUlYcSIESgqKuJ0/AqGYVrebxQTlZWVCAwMxG2DX4RKxa1RWIi/3CwRcojKFrGHq/igoSzncXXAdFagEfqPBiH/sHGk10aH75CUDp8hKUMtaVhK93lRUVGBgIAAUfdxR8/5UCm9HdpWk6Ye3/32OuvjHTBgAPr374+1a9fql3Xv3h3jxo3D8uXLzdZ//vnn8fnnn+P333/XL0tJScEvv/yC48eP65dpNBoMHToUjz/+OHJycnDt2jV89tlnAIDa2lr4+/tjz549GDNmjP41ffv2xV133YVly5axPl/qqXGQ0L03Oqa/hMUKOZY+VFwddOx90FLo4cfVAcaUnCs0jvbXGG3LwSZiwLFGYsCxq6UAaiqWg8rKSqPvvb294e1tHJgaGhqQm5uLhQsXGi1PSkrCsWPHLG73+PHjSEpKMlqWnJyMjRs3orGxEZ6ezZ+LGRkZCAsLw7Rp08yGs5qamqDRaKBWGxcVfHx8cOTIEfYnCQo1ghIr4ADiNRpb4uzmY67YfDi39OAjtQBjSs6BRkfoYAM4VrVxtJFYx5GGYoCaioWkuFYFhUeDY9vQ1gMAIiMjjZYvWbIE6enpRstKS0uh0WgQHh5utDw8PByXLl2yuP1Lly5ZXL+pqQmlpaVo164djh49io0bNyIvL8/iNvz9/ZGYmIj//Oc/6N69O8LDw7F9+3b8+OOP6NKlC4ezpVAjGmcFHMD5IQeQXtAxxfVDXW4hSOqhxRZXBBohr4IyJGSwAYSr2gDSCTcABRwpKCwsNBp+Mq3SGFIojH+/Mwxjtsze+rrlVVVVePTRR7FhwwaEhoZa3caWLVswdepUtG/fHkqlEv3798fDDz+Mn3/+2eZ5maJQY8DzWh1UyuY3Q4hGPv12RQw4gPNDDmD9g0nqYccaOYcEOXGHCo0pMYIN4HivjVTCDUABRwoCAgLs9tSEhoZCqVSaVWVKSkrMqjE6bdu2tbi+SqVCSEgIfvvtN1y4cAFjx47VP6/VagEAKpUKf/75J2JjYxEbG4tDhw6hpqYGlZWVaNeuHSZOnIiYmBhO50mhxgrdLxQhww0gfsABXBNydORY1SHO4Y6BRkfoYAMIU7UBjK+ScmXfjQ4NT0mXl5cX4uPjkZ2djfHjx+uXZ2dn45577rH4msTERHzxxRdGy7755hskJCTA09MTcXFxOH36tNHzixcvRlVVFVavXm02LObr6wtfX1+Ul5dj//79eO211zidA4UaOwx/qcgx4ACuDTmA7Q8zCjwtgzsHGh1Hb6lgcZsCVW10qHpD7Jk7dy4mTZqEhIQEJCYmIjMzEwUFBUhJSQEApKWloaioCJs3N79nKSkpeOeddzB37lzMmDEDx48fx8aNG7F9+3YAgFqtRq9evYz2ERQUBABGy/fv3w+GYdCtWzecOXMG8+fPR7du3fD4449zOn4KNRw4K+AAzg05gPODjo67DWMRc1IJNGL11ZgSq2oDSDfcABRw3MXEiRNRVlaGjIwMFBcXo1evXti7dy+io6MBAMXFxUZz1sTExGDv3r149tln8e677yIiIgJvvfUW7r33Xk77raioQFpaGv73v/+hdevWuPfee/Hyyy/rr55ii+apgeNzAggdcCzuQ8SQY4mrQg5bFHqkTSpBxpQzQo0hocONfrsChRsdR8ONKUfnvdGRYsBx5jw1I9qnQOXh4Dw12np8W7RO1OOVEqrUCEDMCo5+H04aqtKRUjXHEnsfmhR6nEuqIcaUs6o1OmJUbQDxKjeAMAFHjAoOIM2QQ6SFQo3AnB1wAOdVcaQedAyx+ZCl4OMYuQQZU+4SbADhww0g3NCUjlABB6BhKmIfhRoROSPgAK4LOYD1cr5Uw44hLh/KLT0AyTXASIWYwQYQ7kopQ0KHG0CYBmMdCjjEEgo1TuKsgAO4NuToyKmqw4YQH+pSCUYtOaA4u6fGmcQINoD0ww1Al4mTGyjUGDCcktqRO+Da48yAA0gj5ADyruoIoSWHCVdz5zBjSIzhKB05hRuAAk5LRaHGCt3/uGKGG8D5AQeQTsjRaelhh4inpYQZU2JVbQBxww1AAYc4hkKNHc4KN4BrAg5g+bJTVwcdgMIO4a+lhhlDYgYbQJxwAwhfvQEo4LQkFGpYcma4AczLx84MOYD0qjmGbH1gUeBpuaQeZMRuFra4TxGHo3TEDjcABRzCHoUajgz/x3VWwAFcV8XR71+i1RxT9j7YKPS4H6mHGSkQu2oDiBduAHGqNwAFHHdEocYBUgg4gGtCDiCfoGOIzQcgBR9poxDDjzOCDeCccANQwCGWUagRiKsCDiCdkANYnxZe6mHHENsPTQo/4qMAIyxnDEfpiBluAOcFHIBCjpxQqBGBKwMOIK2QoyPHqo49XD9wKQRZRsHF+ZxVtQGEvwWDJWIGHMA45DQxDYJvnwiHQo3ITP8nlkLIAaQbdAD5hx1rHP3wllsoorAibc6s2ug4O+AA4oQcZ9FeLYdW4eXYNlpYCKNQ42RSCDmAdIMOYPvOxu4aeNigkEDE4IpwA4g/PKUjdhWHSAuFGhdz9VCVISkHHR0KPETOXHFZN1uG/6+7W/VGx52qOMQyCjUSIpUqjiE5BB0dCjyECMPV1RsdCjmEKwo1BgzHL03/sbuCpf+hKejwY++vYwo9hJhzVbjRcWYVB6CQ4w4o1Fhh+I9ZCgFHR4rVHMD6Lz2phx0dCj2ESBsT7O+UYGNIrEn/iHgo1LCg+wctpXCjI6WeHEvkWNWxhEIP4UOq/TNy5azmYlNGv/tLLzl134QbCjUcSDncANKt4phyl6BjiM2HFwUf90chxjlcFW4AwKN1MFDk9N0SlijU8CD1cKMj9SqOIXcMOqa4fOBRAJI+CjCu58pwQ6SJQo0D5BJuAPlUcQzJvU/HEXw+MCkICY+CizxQuCE6FGoEINWmYlvkGHJ0WnLYsUWID+CWEIwoqLgvVzQTE2mhUCMwOVVvDEn18nEubF122tIDD1v0gU/kjqo2LRuFGpHIsXpjyh2Cjg4FHkL4cdUcNY5y9hw3RBoo1DiB6RwHcg05gHsFHR17v7Qp9BAibxRwWg4KNS7gDlUcQ+4YdAxR6CHEfVDAcW+yDTXff/89tm7dimPHjqGwsBBBQUFISEjASy+9hPj4eFcfHmvuVMUxZO2XhTuFHR025XkKPoRIDwUc9+Ph6gPga+3atbhw4QKeeeYZ7N27F6tXr0ZJSQkGDhyI77//3tWHx5u27KrRw90oyqusPtyZZ3ktqwchxDWYYH/9o6Vbs2YNYmJioFarER8fj5ycHJvrHzp0CPHx8VCr1ejUqRPWrVtnts6uXbvQo0cPeHt7o0ePHti9e7fD+7VEtpWad999F23atDFaduedd6Jz58545ZVXcPvtt7voyIRlKdi4SzXHVEuq7ljDNthQ5YcQ8Tj7buFSkpWVhdTUVKxZswaDBw/G+vXrMWrUKOTn5yMqKsps/fPnz2P06NGYMWMGtm7diqNHj2L27NkICwvDvffeCwA4fvw4Jk6ciP/85z8YP348du/ejQceeABHjhzBgAEDeO3XGgXDMIwwPwppuP3221FUVIQ///yT9WsqKysRGBiI230mQvXvXbrlxl2DDhstKfTwQQGIOIIqiMaaNPX47rfXUVFRgYCAAFH2IeRnUhPTgO9rs1gf74ABA9C/f3+sXbtWv6x79+4YN24cli9fbrb+888/j88//xy///67fllKSgp++eUXHD9+HAAwceJEVFZWYt++ffp17rzzTgQHB2P79u289muNbCs1llRUVODnn3+2W6Wpr69HfX290esAoImR8RwdFm6y5tE62AUH4gJl9VafYoIo8ChKrf98TDUGqUU8EiJHCg37fz8tQdO/Pw9n1AOE+EzSbaOystJoube3N7y9vY2WNTQ0IDc3FwsXLjRanpSUhGPHjlnc/vHjx5GUlGS0LDk5GRs3bkRjYyM8PT1x/PhxPPvss2brrFq1ivd+rXGrUDNnzhzU1NRg0aJFNtdbvnw5li5darb8cN2nYh2aa9BN1+hnQAgRRVlZGQIDA0XZtpeXF9q2bYvDl4T5TPLz80NkZKTRsiVLliA9Pd1oWWlpKTQaDcLDw42Wh4eH49Ily3cnv3TpksX1m5qaUFpainbt2lldR7dNPvu1xm1CzYsvvoiPPvoIb7/9tt2rn9LS0jB37lz999euXUN0dDQKCgpE+0fqSpWVlYiMjERhYaFo5VJXo3OUP3c/P4DO0R1UVFQgKioKrVuLN+SvVqtx/vx5NDQ0CLI9hmGgUCiMlplWaQyZrmvp9fbWN13OZptc92uJW4SapUuXYtmyZXj55Zfx5JNP2l3fUtkNAAIDA93yf0KdgIAAtz4/gM7RHbj7+QF0ju7Aw0Pci4fVajXUaucOB4eGhkKpVJpVR0pKSsyqKDpt27a1uL5KpUJISIjNdXTb5LNfa2R7SbfO0qVLkZ6ejvT0dLzwwguuPhxCCCFElry8vBAfH4/s7Gyj5dnZ2Rg0aJDF1yQmJpqt/8033yAhIQGenp4219Ftk89+rWJkLCMjgwHALF682KHtVFRUMACYiooKgY5MWtz9/BiGztEduPv5MQydoztw9/P7+OOPGU9PT2bjxo1Mfn4+k5qayvj6+jIXLlxgGIZhFi5cyEyaNEm//rlz55hWrVoxzz77LJOfn89s3LiR8fT0ZHbu3Klf5+jRo4xSqWRWrFjB/P7778yKFSsYlUrF/PDDD6z3y5ZsQ80bb7zBAGDuvPNO5vjx42YPLurq6pglS5YwdXV1Ih2ta7n7+TEMnaM7cPfzYxg6R3fg7ufHMAzz7rvvMtHR0YyXlxfTv39/5tChQ/rnJk+ezAwdOtRo/YMHDzL9+vVjvLy8mI4dOzJr16412+aOHTuYbt26MZ6enkxcXByza9cuTvtlS7bz1AwbNgyHDh2y+rxMT4sQQgghPMk21BBCCCGEGJJ9ozAhhBBCCEChhhBCCCFugkKNiYMHD0KhUFh8/PDDD64+PE6qq6uRmpqKiIgIqNVq9O3bFx9//LGrD0sw7vReAUBVVRUWLFiApKQkhIWFQaFQmM34qfPzzz9jxIgR8PPzQ1BQECZMmIBz584594B5YHuOU6ZMsfi+xsXFOf+gOfj+++8xdepUxMXFwdfXF+3bt8c999yD3Nxcs3Xl+B6yPT+5vn8AkJeXhzFjxiAqKgo+Pj5o3bo1EhMTsXXrVrN15fgeuju3mHxPDK+88gqGDx9utKxXr14uOhp+JkyYgBMnTmDFihXo2rUrtm3bhoceegharRYPP/ywqw9PMO7wXgHN065nZmaiT58+GDduHN577z2L6/3xxx8YNmwY+vbti08++QR1dXV46aWXMGTIEOTl5SEsLMzJR84e23MEAB8fH3z//fdmy6Rs7dq1KCsrwzPPPIMePXrgypUrePPNNzFw4EDs379ff186ub6HbM8PkOf7BzTPMB8ZGYmHHnoI7du3R01NDT766CNMmjQJFy5cwOLFiwHI9z10e5yvl3JzBw4cYAAwO3bscPWhOOSrr75iADDbtm0zWj5y5EgmIiKCaWpqctGRCcdd3isdrVbLaLVahmEY5sqVKwwAZsmSJWbr3X///UxoaKjRPBkXLlxgPD09mQULFjjrcHlhe46TJ09mfH19nXx0jrt8+bLZsqqqKiY8PJy544479Mvk+h6yPT+5vn+2DBgwgImMjNR/L9f30N3R8JOb2r17N/z8/HD//fcbLX/88cfxzz//4Mcff3TRkRFrdCV6W5qamvDll1/i3nvvNZqCPjo6GsOHD8fu3bvFPkyHsDlHOWvTpo3ZMj8/P/To0QOFhYUA5P0esjk/dxUaGgqVqnlwQ87vobujUGPFnDlzoFKpEBAQgOTkZBw5csTVh8TJr7/+iu7du+v/J9Tp3bu3/nl3Iff3iouzZ8+itrZW/z4a6t27N86cOYO6ujoXHJnwamtr0bZtWyiVSnTo0AFPPvkkrl696urD4qyiogI///wzevbsCcD93kPT89OR+/un1WrR1NSEK1euYM2aNdi/fz+ef/55AO73HroT6qkxERgYiGeeeQbDhg1DSEgIzpw5g9dffx3Dhg3DV199heTkZFcfIitlZWXo1KmT2XLdnWXLysqcfUiCc5f3igvd+2bpDsGtW7cGwzAoLy9Hu3btnH1ogurTpw/69Omj7406dOgQ/vvf/+K7777DiRMn4Ofn5+IjZG/OnDmoqanBokWLALjfe2h6foB7vH+zZ8/G+vXrATTfm+itt97CzJkzAbjfe+hO3DrUHDx40KyB1JpTp06hb9++6NevH/r166dfPmTIEIwfPx433XQTFixYIKsPSi63ipcjd3qvuHL39/bZZ581+n7kyJHo168f7rvvPmzYsMHseal68cUX8dFHH+Htt99GfHy80XPu8B5aOz93eP9eeOEFTJ8+HSUlJfjiiy/w5JNPoqamBvPmzdOv4w7vobtx61DTrVs3bNiwgdW6UVFRVp8LCgrCXXfdhXXr1qG2tlYWHfwhISEWqzG68q+lvzDcgRzfKy5CQkIAWK60Xb16FQqFAkFBQU4+KucYP348fH19ZXO5/tKlS7Fs2TK8/PLLePLJJ/XL3eU9tHZ+1sjt/YuKitJ/LowePRoAkJaWhsmTJ7vNe+iO3DrUtGvXDtOnTxdkW8y/d5OQS/q+6aabsH37djQ1NRn11Zw+fRqAPC95Zktu7xUXsbGx8PHx0b+Phk6fPo3OnTtDrVa74Micg2EYeHhIvxVw6dKlSE9PR3p6Ol544QWj59zhPbR1frbI5f2z5JZbbsG6detw7tw5xMfHy/49dFfy/NflZOXl5fjyyy/Rt29f2fxDHT9+PKqrq7Fr1y6j5R9++CEiIiIwYMAAFx2ZuOT4XnGhUqkwduxYfPrpp6iqqtIvLygowIEDBzBhwgQXHp24du7cievXr2PgwIGuPhSb/vOf/yA9PR2LFy/GkiVLzJ6X+3to7/yskcv7Z82BAwfg4eGBTp06yf49dGduXanh4+GHH0ZUVBQSEhIQGhqKv//+G2+++SYuX76MTZs2ufrwWBs1ahRGjhyJWbNmobKyEp07d8b27dvx9ddfY+vWrVAqla4+RIe5y3tlaN++faipqdH/oszPz8fOnTsBNJfAW7VqhaVLl+Lmm2/GXXfdhYULF+on/QoNDcVzzz3nysNnxd45XrlyBQ8//DAefPBBdO7cGQqFAocOHcKqVavQs2dPwaqvYnjzzTfx0ksv4c4778SYMWPMhlp0H+hyfQ/ZnN/Fixdl+/4BwBNPPIGAgADccsstCA8PR2lpKXbs2IGsrCzMnz9fP6meXN9Dt+fCOXIkafny5Uzfvn2ZwMBARqlUMmFhYcz48eOZn376ydWHxllVVRXz9NNPM23btmW8vLyY3r17M9u3b3f1YQnGnd4rnejoaAaAxcf58+f16508eZK54447mFatWjEBAQHMuHHjmDNnzrjuwDmwd45Xr15lxo8fz3Ts2JHx8fFhvLy8mC5dujALFixgrl275urDt2no0KFWz830160c30M25yfn949hGOb9999nhgwZwoSGhjIqlYoJCgpihg4dymzZssVsXTm+h+5OwTD/NiAQQgghhMgY9dQQQgghxC1QqCGEEEKIW6BQQwghhBC3QKGGEEIIIW6BQg0hhBBC3AKFGkIIIYS4BQo1hBBCCHELFGoIIYQQ4hYo1BC3dvDgQSgUCv3jwoULou5v2LBh+n1NmTJF1H1JzZQpU/TnPmzYMFH3Zfie6h4dO3Zk/fqOHTvqX5eeni7acdqyatUqi+fhquMhxB1QqCGyYBpODB9+fn7o0aMHnnrqKZw7d473NsUOPEJITk42OmZfX1+jG+oRQkhLRje0JLJXU1OD33//Hb///jvef/997NmzByNGjAAAxMbG4vXXX9ev27p1a1cdpsOKiorw7bffGi27fv06PvnkE0ybNs1FR+V6KSkpiI2NRWBgoKsPhZPbbrtN/29z7dq1nAI5IcQyCjVEliZOnIiEhAQ0NDTg+PHj+PLLLwE0f8hPmjQJFy5cgLe3NyIjIzFv3jwXH60wNm/eDK1Wa7Z806ZNLTrUTJw4UfThLjH0798f/fv3BwB8+eWXFGoIEQANPxFZuvPOOzFv3jy88MIL+OKLL/DII4/on7t06RKOHj0KwPoQk0KhwPDhw422GRMTY7UfJj8/H7NmzUJcXBx8fX3RqlUrdO7cGZMmTcJvv/1m9TjPnTuHhx56CCEhIfDx8UFiYiIOHjzI65w//PBD/dddu3bVf33kyBGcOXPGbH3Tcz979izeeust9OrVC97e3oiIiEBqairq6urMXltWVoZZs2ahbdu28PHxQXx8PLZv3+7QkF1xcTEWLlyI3r17w9/fH2q1Gl27dsXcuXNx6dIlbj8MljZs2ICbbroJarUaHTp0wHPPPcdquO7UqVN4/PHH0alTJ6jVavj7++Pmm2/GypUrLf68AOCzzz7DLbfcAh8fH7Rp0wZTp07F5cuXW3SfFSFO5+rbhBPCxoEDBxgA+scHH3xg9Pw777xj9PxHH31k8XXnz59nGIYxWmbpMXnyZP22169fz3h6elpd1/BYhg4dql+ekJDABAcHm63v5eXF/Prrr5zO/9ixY0bb2L9/P9O6dWv994sXL7b7Mxs8eLDF43/44YeNXldeXs7ExcVZXHfs2LEWf54MwzCTJ0/WLx86dKjRNo8cOWJ0vKaPNm3aMKdOnWL98zB87YEDByyus3DhQov7SkhIYMLDw/XfL1myxOh1b7/9NqNUKq0e680338xcu3bN6DXr1q2zuG5MTAzTs2dPi/+uDBn+uzE9HkIIezT8RNzC8ePHjb5v27atzfVff/11nD17FuvWrdMve+GFFxAcHAwA6NWrFwDg2LFjmDVrln7Yx9PTEw888AC6du2KwsJC/bCXJSdPnkRoaCjmzZuHy5cvY8uWLQCAhoYGvPXWW1i/fj3r89u0aZP+63bt2mHEiBGYMGEC3nvvPQDNQ1MZGRlQKBRWt3H06FEkJyfj5ptvxrZt2/TDHdu3b8drr72G9u3bAwAWL16MP/74Q/+6W2+9FcOHD0dOTg6++OIL1sesU1FRgfHjx+Pq1asAgE6dOuGBBx6Ap6cnPvnkE/z5558oKSnBhAkT8Pvvv8Pb25vzPkydOHECr776qv77tm3b4rHHHkN1dTU2btyI+vp6i687evQonn76aTAMA6D53EeMGIFr167hww8/RHl5OU6cOIFZs2Zh27ZtAID//e9/SE1N1W/D19cX06dPh4eHBzZu3Ijz5887fD6EEJZcnaoIYcO06jBx4kTm9ddfZ15++WWz6kF4eDhTW1tr8XWGlQVbz+mMHz9e/7xSqWSOHDli9HxtbS3zzz//6L83/Ivbw8OD+eWXX/TPjRs3Tv9c//79WZ97bW0tExQUpH/tM888wzAMw2RnZxsd/7fffmvzZ3bffffpn8vLyzN67vPPP2cYhmEaGhoYPz8//fJBgwYxTU1NDMMwjEajYYYPH865UrN69WqjioxhlaO8vJxRq9VmFTZ7DI/BUqVm5syZRu/bn3/+qX/uo48+Mnq9YWXE8P1OTk5mtFqt/rmvv/5a/5xCoWAKCwsZhmGYV155xWh7+/bts/oeUKWGEHFRTw2RpaysLMyfPx+LFi0yqh6o1Wp8+OGHUKvVguxH15sDNF9OPXjwYKPn1Wo12rVrZ/G1iYmJ6N27t/77bt266b8uLy9nfQy7d+/GtWvX9N8/+OCDAIDhw4cjPDxcv9ywmmPJzJkzLR6L4fH8+eefqK6u1i9/5JFHoFQqAQAeHh6YPHky6+PWMfwZlpSUICgoSN9jEhwcbNSjcuzYMc7bt+TkyZP6rxMSEox6kCZOnAhPT0+7x7p//354eHjoj/XOO+/UP8cwDH744QcAQG5urn55WFiY0XrDhg3jNH8OIcQxFGqI7Pn4+CAuLg6zZ8/G6dOnkZycLNi2dUMmADh/OEVHRxt9bzisYukqJmsMw0rHjh0xcOBAAIBSqcR9992nf+7TTz+12QRreDymQzy64zEMT4D5MJ69YT1LDH+G9ly5coXz9i0xPI82bdoYPadUKhESEmLxdXyO1XBfln4+fH5mhBB+qKeGyNIHH3zglCtJWrdujZKSEgDgPDmfaTXAVr+LNaZz01y4cMHqduzNWWN4PNa2ERQUZPS97tx1+FylpOtTAoCoqCg89dRTVtc1rSDxZXgepueg0WhQVlZm8XXBwcH6sDJ8+HCMHj3a6j4SExPt7gvg9zMjhPBDoYa0WKah4/r162brDB48GLt37wbQPBzxww8/6CslQHPTb1lZmdUhKEdZm5vGGkfnrImLi4O/v7++4pOVlYWZM2dCoVCAYRijy8rZGjRoEHbs2AEAuHz5MsaMGYPu3bsbrdPU1IQvv/wSt956K+9jN5SQkKAfFjp58iT++usv/RBUVlYWGhsbrR7rnj17ADSHkVmzZsHX19doncrKSuzbtw99+/YFANx8883YtWuX/vwOHjyonzfn0KFDspipmhB3QaGGtFi6q310Zs+ejTvvvBMqlQp33303unbtinnz5mHPnj3QarXQaDQYOnQoJk6ciC5duuCff/7B3r17sXTpUtGqRoYhIjw83OIkc2fOnNF/gOvmrOncuTOv/alUKkyZMgVvv/02gOa5bu644w4MGTIEhw8f5jXHzpQpU7Bs2TKUlZWhvr4eAwcOxAMPPICYmBjU1tYiPz8fBw8exNWrV3H+/Hmjyg5fU6dORWZmJhiG0b9vkydPRlVVFTZu3Gj1dc899xw+//xzMAyD33//Hb169cKECRMQGhqKq1evIi8vDzk5OWjbti0mTpwIAHj00UeRnp6u7w0aN24cpk6dCgA290UIEYFr+5QJYcfePDVsX2d6hVP//v0tzi+yY8cO/Tp856kxvdJlyZIl+ueio6PtHrvp3DQrVqywuN5vv/1mtJ5uzhp7527tHGzNUzNq1Cij7y9evKh/na15anJycmzOU2PtGK0xfI21eWrmz59vcR89e/ZkQkNDrV5t9NZbb9mcp8bS+7d27Vqr63Xv3l3//eOPP27xWOnqJ0KEQY3CpEXbtWsXxo8fj9atW1vtM3niiSdw6tQpzJw5E127doWPjw/UajWio6Px4IMPIiEhQZRjM6zSKJVKPPbYYxbX69GjB2655Rb991yHrEwFBQUhJycHM2fORJs2beDt7Y0+ffpg8+bNZsdg2oNjza233orffvsNaWlp6NevH/z9/eHl5YWoqCgMHjwYL774InJzcwW9Uui1117DunXr0KNHD3h5eaFdu3aYM2cOcnJyzIaUDD311FM4efIkpk2bhs6dO0OtVsPX1xddunTBnXfeidWrV+Pw4cNGr0lJScGnn36KhIQEeHt7IzQ0FJMmTcLx48eN3gu2Py9CCD8Khvl3lilCCPlXbW0tfHx8zJbfd999+v6RLl264K+//nL2oQEwbnQ2vKHljBkzXHI81n5eeXl5SEhIgEajAQB89NFHePjhhwEAP//8M77//nsAxje0XLJkCdLT051z4IS4GeqpIYSY6datG5KTk3HLLbcgIiICJSUl2LFjB/bt26df5+mnn3bhEd6gmxU6OjraZaEmMzMTW7ZswX333YfY2FgolUqcPn0a77zzjj7QdOjQAePHj9e/5vDhw5g/f75LjpcQd0WhhhBiprKyEu+9957+NgymZsyYgTlz5jj5qKSLYRjk5uYaTcRnKDw8HHv27LFYzSGECIeGnwghZl599VV8/fXX+OOPP3D16lV4eHigXbt2GDhwIKZNm4Y77rjD1YcoKXl5eVi9ejWOHTuGy5cvo7q6GgEBAYiLi8OYMWMwa9YstG7d2tWHSYjbo1BDCCGEELdAVz8RQgghxC1QqCGEEEKIW6BQQwghhBC3QKGGEEIIIW6BQg0hhBBC3AKFGkIIIYS4BQo1hBBCCHELFGoIIYQQ4hb+H6N3PUfHqyYQAAAAAElFTkSuQmCC\n", + "image/png": "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", "text/plain": [ "
" ] @@ -248,6 +253,7 @@ ] }, { + "attachments": {}, "cell_type": "markdown", "metadata": { "slideshow": { @@ -285,6 +291,7 @@ ] }, { + "attachments": {}, "cell_type": "markdown", "metadata": { "slideshow": { @@ -308,7 +315,7 @@ "outputs": [ { "data": { - "image/png": "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\n", + "image/png": "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", "text/plain": [ "
" ] @@ -355,11 +362,12 @@ "ROSCO_utilities.write_DISCON(\n", " turbine,controller,\n", " param_file=param_file, \n", - " txt_filename=os.path.join('../Tune_Cases/',path_params['FAST_directory'],path_params['rotor_performance_filename'])\n", + " txt_filename=os.path.join('../Tune_Cases/',path_params['rotor_performance_filename'])\n", ")" ] }, { + "attachments": {}, "cell_type": "markdown", "metadata": { "slideshow": { @@ -394,7 +402,7 @@ }, { "data": { - "image/png": "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\n", + "image/png": "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", "text/plain": [ "
" ] @@ -421,6 +429,7 @@ ] }, { + "attachments": {}, "cell_type": "markdown", "metadata": { "slideshow": { @@ -557,7 +566,7 @@ }, { "data": { - "image/png": "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\n", + "image/png": "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", "text/plain": [ "
" ] @@ -598,6 +607,7 @@ ] }, { + "attachments": {}, "cell_type": "markdown", "metadata": { "slideshow": { @@ -609,6 +619,7 @@ ] }, { + "attachments": {}, "cell_type": "markdown", "metadata": { "slideshow": { @@ -636,7 +647,7 @@ "outputs": [ { "data": { - "image/png": "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\n", + "image/png": "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", "text/plain": [ "
" ] @@ -646,7 +657,7 @@ }, { "data": { - "image/png": "iVBORw0KGgoAAAANSUhEUgAAAosAAAHrCAYAAACn9tfQAAAAOXRFWHRTb2Z0d2FyZQBNYXRwbG90bGliIHZlcnNpb24zLjYuMiwgaHR0cHM6Ly9tYXRwbG90bGliLm9yZy8o6BhiAAAACXBIWXMAAA9hAAAPYQGoP6dpAACmmklEQVR4nOzdd5yT9eEH8M+TPS7J7b3ZeykKLhyg4KJKrXWhrdVKa0V/SgUrgtbdKtbWWqs4alHrrANlqYgFlI2yx93B7X3Z+/n98SSB4wbJkdzl7j7v1yte8uTJk2/u6x2f+05BFEURRERERETtkPV0AYiIiIgofjEsEhEREVGHGBaJiIiIqEMMi0RERETUIYZFIiIiIuoQwyIRERERdYhhkYiIiIg6xLBIRERERB1iWCQiIiKiDjEsElGPeO211yAIQuimUCiQlZWFa6+9FgcOHOjSNdevX49Fixahubk5uoXtxKJFi1p9DpVKhaKiItx1111RL0djYyOuvfZapKenQxAEzJw5M6rXJyJqj6KnC0BE/durr76KoUOHwul04n//+x8effRRfPXVV9i7dy+SkpIiutb69euxePFi3HzzzUhMTIxNgTvwxRdfwGQywWKxYPny5Xjuuefw/fffY/369RAEISrv8cgjj+DDDz/E0qVLMWDAACQnJ0flukREnWFYJKIeNXLkSJx22mkAgClTpsDn8+Ghhx7CRx99hFtuuaWHSyex2+3Q6XSdnjNhwgSkpqYCAKZOnYqGhgb861//wvr163HWWWed0vs7HA5otVr8+OOPGDBgAK6//vpTul6QKIpwOp3QarVRuR4R9U3shiaiuBIMjjU1Na2Of/zxx5g0aRJ0Oh0MBgOmTp2KDRs2hJ5ftGgR7rvvPgBAUVFRqFv466+/BgD4/X489dRTGDp0KNRqNdLT03HTTTehvLy81ftMmTIFI0eOxDfffIPJkydDp9PhF7/4RcSf48wzzwQAlJWVAQDcbjf++Mc/ht4/LS0Nt9xyC+rq6lq9rrCwEJdddhk++OADjBs3DhqNBrfccgsEQcDq1auxZ8+eNp+tsbERc+bMQU5ODlQqFYqLi/HAAw/A5XK1urYgCPjtb3+LF198EcOGDYNarcbrr78eGhLw5Zdf4le/+hVSUlJgNBpx0003wWazobq6Gtdccw0SExORlZWFe++9Fx6Pp9W1Fy9ejDPOOAPJyckwGo0YP348XnnlFYii2O7n++KLLzB+/HhotVoMHToUS5cubfM9rKiowG233Ya8vDyoVCpkZ2dj1qxZrf7fMJvNuPfee1FUVASVSoWcnBzMnTsXNpst4jojovaxZZGI4kpJSQkAYPDgwaFjy5Ytw/XXX49p06bhrbfegsvlwlNPPYUpU6ZgzZo1OPvss3HrrbeisbERzz//PD744ANkZWUBAIYPHw4AuOOOO/DSSy/ht7/9LS677DKUlpbiwQcfxNdff42tW7eGWgUBoKqqCjfccAPmzZuHxx57DDJZ5H9XHzx4EACQlpYGv9+PK6+8EuvWrcO8efMwefJklJWV4aGHHsKUKVOwefPmVq17W7duxZ49e/CHP/wBRUVF0Gq1mDt3LubMmYOWlhb8+9//Dn02p9OJ888/H4cOHcLixYsxevRorFu3Do8//ji2b9+Ozz77rFW5PvroI6xbtw4LFy5EZmYm0tPTsWnTJgDArbfeiquuugpvv/02tm3bhgULFsDr9WLfvn246qqrcNttt2H16tV48sknkZ2djXvuuSd03dLSUtx+++3Iz88HAGzcuBF33nknKioqsHDhwlZl2LFjB/7v//4P999/PzIyMvDyyy/jl7/8JQYOHIhzzz0XgBQUTz/9dHg8HixYsACjR49GQ0MDVqxYgaamJmRkZMBut+O8885DeXl56Jxdu3Zh4cKF+OGHH7B69eqoDQEg6tdEIqIe8Oqrr4oAxI0bN4oej0e0WCziF198IWZmZornnnuu6PF4RFEURZ/PJ2ZnZ4ujRo0SfT5f6PUWi0VMT08XJ0+eHDr29NNPiwDEkpKSVu+1Z88eEYA4Z86cVse/++47EYC4YMGC0LHzzjtPBCCuWbMmrM/x0EMPiQDE6upq0ePxiE1NTeKbb74parVaMS8vT3Q4HOJbb70lAhDff//9Vq/dtGmTCEB84YUXQscKCgpEuVwu7tu3r817nXfeeeKIESNaHXvxxRdFAOJ//vOfVseffPJJEYC4cuXK0DEAoslkEhsbG1udG6yLO++8s9XxmTNnigDEZ555ptXxsWPHiuPHj+/we+Lz+USPxyM+/PDDYkpKiuj3+1t9Po1GI5aVlYWOORwOMTk5Wbz99ttDx37xi1+ISqVS3L17d4fv8/jjj4symUzctGlTq+PvvfeeCEBcvnx5h68lovCxG5qIetSZZ54JpVIJg8GASy65BElJSfjvf/8LhULq+Ni3bx8qKytx4403tmrhS0hIwNVXX42NGzfCbrd3+h5fffUVAODmm29udXzixIkYNmwY1qxZ0+p4UlISLrjggog+R2ZmJpRKJZKSknDDDTdg/Pjx+OKLL6DRaPDpp58iMTERl19+Obxeb+g2duxYZGZmhrqTg0aPHt2qZbUzX375JfR6PWbNmtXqePCznvjZLrjggg4nDl122WWtHg8bNgwAcOmll7Y5HuxeP74cF110EUwmE+RyOZRKJRYuXIiGhgbU1ta2Onfs2LGhFkgA0Gg0GDx4cKtrfv755zj//PNDZWjPp59+ipEjR2Ls2LGtvq8XX3xxq256Ijo17IYmoh71xhtvYNiwYbBYLHjnnXfwj3/8Az//+c/x+eefAwAaGhoAINStfLzs7Gz4/X40NTV1OgHlZNc4Mfi0d97JrF69GiaTCUqlErm5uUhJSQk9V1NTg+bmZqhUqnZfW19f3+X3b2hoQGZmZpvu1vT0dCgUitBnD+faJ86uDpa3veNOpzP0+Pvvv8e0adMwZcoU/POf/0Rubi5UKhU++ugjPProo3A4HK1ef/z3JkitVrc6r66uDrm5uR2WFZC+rwcPHoRSqWz3+RO/r0TUNQyLRNSjhg0bFprUcv7558Pn8+Hll1/Ge++9h1mzZoWCRVVVVZvXVlZWQiaTnXSJneOvcWIAqaysbDVeEUCXxrmNGTOmzXWCUlNTkZKSgi+++KLd5w0GQ5ffPyUlBd999x1EUWz1utraWni93qh8tpN5++23oVQq8emnn0Kj0YSOf/TRR12+ZlpaWpvJRydKTU2FVqttd3JM8HkiOnXshiaiuPLUU08hKSkJCxcuhN/vx5AhQ5CTk4Nly5a1mllrs9nw/vvvh2ZIA1LrFIA2LVnBLuU333yz1fFNmzZhz549uPDCC2P5kXDZZZehoaEBPp8Pp512WpvbkCFDunztCy+8EFartU0we+ONN0LPx1pwUXW5XB465nA48K9//avL15w+fTq++uor7Nu3r8NzLrvsMhw6dAgpKSntfl8LCwu7/P5EdAzDIhHFlaSkJMyfPx979uzBsmXLIJPJ8NRTT2H79u247LLL8PHHH+Pdd9/F+eefj+bmZjzxxBOh144aNQoA8Nxzz2HDhg3YvHkzLBYLhgwZgttuuw3PP/887r77bqxcuRIvvfQSLrvsMuTl5eHuu++O6We69tprMX36dMyYMQMPP/wwvvjiC6xZswavv/46br75Znz44YddvvZNN92E0aNHY/bs2Xj22WexevVqLFq0CAsWLMCMGTNw0UUXRfGTtO/SSy+F1WrFddddh1WrVuHtt9/GOeecEwrvXfHwww8jNTUV5557Lp577jl8+eWX+OCDD3Dbbbdh7969AIC5c+diyJAhOPfcc/HMM89g9erVWLlyJV5++WVcc801+O6776L1EYn6NXZDE1HcufPOO/HXv/4VDz/8MH7+85/juuuug16vx+OPP46f/exnkMvlOPPMM/HVV19h8uTJoddNmTIF8+fPx+uvv45//vOf8Pv9+OqrrzBlyhT8/e9/x4ABA/DKK6/gb3/7G0wmEy655BI8/vjj7Y6hiya5XI6PP/4Yzz33HP71r3/h8ccfh0KhQG5uLs4777xQyO0KjUaDr776Cg888ACefvpp1NXVIScnB/feey8eeuihKH6Kjl1wwQVYunQpnnzySVx++eXIycnBr371K6Snp+OXv/xll66Zk5OD77//Hg899BCeeOIJNDQ0IC0tDWeffXZoDKVer8e6devwxBNP4KWXXkJJSQm0Wi3y8/Nx0UUXsWWRKEoEUTxhxVQiIiIiogB2QxMRERFRhxgWiYiIiKhDDItERERE1CGGRSIiIiLqEMMiEREREXWoX4bFb775Bpdffjmys7MhCEKbxWxFUcSiRYuQnZ0NrVaLKVOmYNeuXT1TWCIiIqIe1C/XWbTZbBgzZgxuueUWXH311W2ef+qpp/DMM8/gtddew+DBg/HHP/4RU6dOxb59+9psy9Uev9+PyspKGAyGmGytRURERHSqRFGExWJBdnY2ZLJO2g/Ffg6A+OGHH4Ye+/1+MTMzU3ziiSdCx5xOp2gymcQXX3wxrGsePXpUBMAbb7zxxhtvvPEW97ejR492mmv6ZctiZ0pKSlBdXY1p06aFjqnVapx33nlYv349br/99javcblccLlcocdiYJ3zkpKSsFoiu8rj8eCrr77C+eefD6VSGbP3ofCxTuIP6yT+sE7iC+sj/nRXnVgsFhQVFZ00qzAsnqC6uhoAkJGR0ep4RkYGysrK2n3N448/jsWLF7c5vmHDBuh0uugX8jg6nY77n8YZ1kn8YZ3EH9ZJfGF9xJ/uqBO73Q4AJx0yx7DYgRO/caIodvjNnD9/Pu65557QY7PZjLy8PEybNg1GozFmZfR4PFi1ahWmTp3KvwbjBOsk/rBO4g/rJL6wPuJPd9WJ2WwO6zyGxRNkZmYCkFoYs7KyQsdra2vbtDYGqdVqqNXqNseVSmXMKnn9oXr89csDUNllmBHD96HIuDw+NLuA0kYXNGo/NEo5knQqaFXyni5avxfLn0fqGtZJfGF9xJ9Y10m412ZYPEFRUREyMzOxatUqjBs3DgDgdruxdu1aPPnkkz1cumPMDg/WH2pEkYGzrXuKx+fHjqPN+N/BBuwsb8b+WguONjoAKICt61udm2XSoDhNjzG5iTi9KBkTCpJg1PCXMhERxb9+GRatVisOHjwYelxSUoLt27cjOTkZ+fn5mDt3Lh577DEMGjQIgwYNwmOPPQadTofrrruuB0vdWoJaChpObw8XJAp2V5qxcnc19tdYIBME5CbpMCQzASOzTShOS4BcFh+B2O8XsbfagvWH6rH+UAO+O9wAm9vX5jyZIMKkVcHrE+Hw+OD1i6hqcaKqxYn/HWwAvj4EQQDG5CbigqHpuGBoOkZkG7nMEhERxaV+GRY3b96M888/P/Q4ON5w9uzZeO211zBv3jw4HA7MmTMHTU1NOOOMM7By5cqYzmyOlEEjVZ2jbVbpNapaHHjgwx/x5d7aDs/RqeQYkW3EyBwThmYakJOoQ06SFtmJGqgVse3adXv92F9jwXcljfjucAO+K2lEi8PT6pwknRKTB6RiYlEyBmcYUJSsxsa1a3DppcdmsDXZ3Dhcb8OBGgs2lzVhc2kjShvs2H60GduPNuOZVfuRYVTjgqHpmDIkHWcNTEWCul/+aBIRURzql/8iTZkyJbS8TXsEQcCiRYuwaNGi7itUhIJh0dlLw+Lm0kbc+sZmNNs9kMsETB2WgdMKkyAIAkrrbdhbbcauSjPsbh82lTZhU2lTm2ukJqiQadIg06hFlkmDrESN9NWkRU6iFhlGDVSKk29S5PX5UdnsREmDDXurzNhbbcGeKjMO1lrh9bf+/0SvkuP0omScNSAVkwemYFimEbLjWj49Hg9ObCBM0qswQa/ChIIkXDsxHwBQ3eLE1/tq8eXeWnx7sB41Zhfe+v4o3vr+KJRyAacVJGPKkDRMGZKOwRkJbHUkIqIe0y/DYl9gCIx3c/mk7tHeZEtZI25a+j3sbh9G5Ziw5NqxGJCW0OY8n1/E4Torfqhowc7yFpTU21DR7EB5kx1Ojx/1VjfqrW78WNH+bC5BANINamQnapFt0iJBrYBCLsAvSmM+m+xuVDQ7UNHkaBMKg4waBcYXJOHM4hScWZyCkdlGKOSnvktmpkmDayfm49qJ+XB6fPiupBFf7a3F1/tqUdpgx4bDDdhwuAGPf74XqQkqjMtPwvj8JIzPT8TwbGOo/omIiGKNYbGXCrYsihBgc/vQzmTsuFTZ7MBtb2yB3e3D2QNT8fLs06BRtt+dLJcJGJRhwKAMA64anxs6LooimuweVLU4UB0YCxj8WtXiQFWLExXNDri9ftSYXagxu7ANzZ2WS6WQIT9Zh8EZCRiWacSwLCOGZRuRbdLEvFVPo5TjvMFpOG9wGoARKKm34et9tfh6Xx02Hm5AvdWNVbtrsGp3Teg1OYlaDM00YEjgNizLiKJUPZRRCLJERETHY1jspdQKGZRyAR6fCKvLi+T4GU7ZIa/Pj98s24oGmxvDs4z4500dB8XOCIKAZL0KyXoVRmSb2j1HFEU02NyobHYEbk5psolPhAgRiVolEnVSN3ZBig4ZBk2r7uSeVJSqR1FqEW45qwhOjw+7KluwtawZW8qasP1oM6rNUhiuaHZgzXHjPVUKWeuwm2XE8CwjTDq2QhIRUdcxLPZSgiAgQa1Ak90Di9Nz8hfEgX+uK8G2I80waBT4x40TYrr2oCAISE1QIzVBjdG5iTF7n1jTKOWYUJCMCQXJ+FXgWJPNjX01FuyrtmBvtQX7qs3YV22Bze3DjxXmNt3y2SYNhmUZMSLbiHH5SRiXn4hEnar7P0w3E0URZqcXNc02lFqATaVN8EMGnyhCo5BBq5JDp1IgzaCGUaPguFAiog4wLPZiBk0wLMb/+jml9TY8u2o/AOChy0cgLzm22yD2ZUl6VWgMZZDfL+Jokx17qszYXSVN0NlTZUZ5kwOVLU5UtjhbtUIWp+kxPhAcx+UlYXBGQlTGYsaa0+NDvdWFBqsbDTYX6q1uNNrcaAgcqz/ufoPNBY8vOBZVAfy4qcPrapVyZBjVKEjRozhNjwFpCShO02NQugFphl4yxoOIKEYYFnux4LhFiyv+w+IfP9sDt8+Pcwen4erxOT1dnD5HJhNQkKJHQYoel4w8tvOQ2enB3ioLdle2YGdFC7YdaUZJvQ2H66Tbe1vKAUhhaXSuCWMD4XFsXiIyjOqotLY5PT5YnF5YnJ7A12P3zU4PzIHHdpcPdo8PdpcXdrd03+GW7jvcPtjcXjg9/ojfX6+WQyV6kWjQQ62UQxAEuLzSNa0uqTwOjw+lDXaUNtixdn9dq9enGdQYnmXE8Gxj6Gthij5u1v8kIoo1hsVezBBYi88a5y2L6w7UYfWeGihkAhZeNpzdfd3IqFFiYlEyJhYlh4412tzYfrQJW8uaQ2s9Wl1eaT3JksbQeXqVHHnJOuQn65CkU0GvViBBLYUtn1+ETxTh9flhc/tgc3lhdXphdUk3W+Cr2emF2xt5wOuMSi5DSoJKuunVSElQITVBjWS99DUlQYXUwPFkvQpy+LF8+XLMmHF2u1tbOdw+1FqcqGx2orTBhsN1Vhyqs+FQnRVHGu2os7iw1lLXKkRqlXIMzTJgeJYRo3NNGJWTiEEZCZxgRER9EsNiLxZcPqUljsOizy/ikU93AwBunFSAgeltl8ih7pWsV+GCoRm4YKi017nfL+JQnRXbjjRj29FmbDvShP010hjIvYFxkdFgUCtg0Chg0Chh0Chg1CoDj6VjCWoFtEo5dCp5aDzhsfty6JQKJOqVMKgjG1/oOUlrpFYlD7XKThqQ0uo5u9uLvdUW7K40Y3ega39vlQUOj0/6fh1pxr+/k85VKWTHhUcTRucmYkCavld07xMRdYZhsRczaaWwaHbE7wSXj3dUYH+NFSatEnMvHNzTxaF2yI5bouia0/MAAC6vD+VNDhxpsONokx1mhwdWl9SCKEKEQiaDTBCgkAvQqeRIUCukm0YBvVoBgzrw9bgg2Bu7bXUqRWB9y6TQMZ9fRGmDDbsrzfixogU/BG4WpzfUUhukVR7bgWh0rgnj85NQkKJj6zoR9SoMi72YSStV34lb0MULr8+Pv6yR9uC+7dxiLuHSi6gVcgxIS2h3sfT+Ti4TQt+by8dkA5BaZ4802rGzogU/lDdjZ3kLfqxogc3tk7Z4LDu2A1GaQY3TC5NwWkEyTi9MxvBsY68M0kTUfzAs9mLBlsUWR3x2Q/93eyVK6m1I0ikxe3JhTxeHKGZkMgGFqXoUpupxxXEB8nC9DT9USOFxZ3kLfihvQZ3FheU/VGP5D9UAgESdEucNTsOUIWk4d1AaUhI4+5qI4gvDYi92LCzGX8uizy/ir18FWxUHIEHN/9Wof5HJBAxMT8DA9AT8ZJy0A5HT48PO8hZsKm3E5tJGbC5rQrPdg/9ur8R/t1dCEIAxuYm4aFg6LhiagWFZBnZZE1GP47/gvVhiICw2x2FY/HJvLUrqbTBplbhpUkFPF4coLmiU8laz070+P7YdbcbX+2rx1d467K4yh8Y9/mnlfuQkanHB0HRcOCwdZxandGnHo3glikCDzY1GuwPNDjfMjsBSSg5pOSWX1we31w+Pzw+PV4TH54fXL0IuEyCXCVAEvirlMujVciSoj02YMmqVSEtQI92gRkqCmt38RKeIYbEXC44BjMcJLku/LQEA/HxiPvRsVSRql0Iuw+mF0tjF+y4eihqzE1/urcWaPTX49mA9Kpod+NfGMvxrYxl0KjnOGZSKC4dm4Pyh6XG7WHhw55x6qwt1FulWY5b2b682O1FjdqKq2YGqFjl8G7+OeXlkApASCI7pBjWyErXIT9YhL0mHvGQt8pJ0SNQp2YJL1An+K96LmTTx2bK4u9KMDYcbIJcJbFUkikCGUYOfT8zHzyfmw+nxYf2heqzeI4XHGrMLK3bVYMWuGgBAYYoOw7KMGJiegDSDtLWlUi6DAMAninB7/XB5/XB5fXB5jrvv9QceS/fdgeMAAq12MsgFqRs92HonlwmQC4HnZNJzLo+/9ZqaDg/qrW7UWV1hrq0phbPUBBWSdCoYtUoYNQqYtEoYNEpoVXIo5VLLoVIug0oug1wmwC+K8PpF+PwivD6pxTG4uLrF6YHV5UWLw4M6iwv1Vhf8IkKhdVcHJUlQK5CbpJUmLqUnYFBg+EBRqr5PteYSdRXDYi9m0sXnbOhX/ye1Kk4fmYnsRG0Pl4aod9Io5aH1MMWZI7Gr0ozVe2qwZk8tfqhoCe04E68MakUoxGaYNMg0qpFh1CDTpEGaXondW9bjmssvgV4buxZSn19Eg82FWvOxFs6KZgeONtpxpNGOo00O1FlcsLq87a4pKhOAghRp+8dhgUXYh2cbkZekg4xd29SPMCz2YsExi06PH06PLy7+Ara6vPhkZyUA4JazCnu2MER9hCAIGJljwsgcE+ZeNBiNNndgofAWHGm0o95ybC9sEVKbnUYpg1ohh1ohg1oZ+KoIHFMed18hg0ohgyBI4arVTRTh8wW+nnBMrZQFdvVRQK+SxgmmJqhCAbGz30cejwfVP0oLmceSXCYg3aBBukHT4TlOjw/lTVJ4PFxnw4EaKw7UWnCg1gqL04uSehtK6m1Yvacm9JoEtaJVeByeZcKgjIS4+B1MFAsMi72YXqWAABEiBJgdnrj4RfX5D1VwevwoTtO3WsiYiKInWa/C2YNScfag1J4uSq+nUcoxMN2AgekGXDD02HFRFFFnceFArRX7ayzSHutVZuyrtsDq8mJTaRM2lR5bP1MuEzAwLaHVHuLDs4xI0qt64FMRRRfDYi8mkwnQKQCbVxq3mG7s+K/n7vLB1goAwFXjcjhgnIh6LUEQkG7UIN2owVkDj4Vyj8+Pw3U27K5qCW0DuavSjGa7B/tqLNhXY8GH2ypC52caNRiSacCQTAMGZxgwJMOAgekJ0Kp6/o97onAxLPZyobBo7/lxizVmJzYcbgAAzByX08OlISKKPqVcFgp/PxknHRNFEdVmpxQeAwFyd5UZZQ12VJulWeBr99eFriEIQGFgLGRhig4FKTrkp+hRmKJDdqIWSu4nTnGGYbGXC8xxiYtJLsExPWPzEpGbpOvh0hARdQ9BEJBl0iLLpMWFwzJCxy1OD/ZVW7C/RurK3lcttTw22tyhsZAnkssE5CRqpQCZrENOkhY5iVrkJmmRk6hDmiF+1o0UA2NZAUAmCBAEsEepj2JY7OV0Cmk4e7Pd3dNFwardUlicOjzjJGcSEfV9Bo0SpxUm47TC5NAxURRRb3VjX7UFh+utKGuwo6zBjiONNpQ12OHy+nEkMFu7PUq5gEyTBjmJUnjMSdQEAqUULLNMmi6PXxdFEbUWJw7X2VBab0Npgx1lDTbUWVxosrvRZPfA4fZJyxb5/QjkxHYJgjTRKhQiIR1ofUwKlwIQeg7BY4EHwXPkMgF6lRw6lQJ6deuvSTolEnUqJOulZZiSdErpvl6FRK0SCrbUnjKGxV4uXloWbS4v1h+UuqCnMSwSEbVLEASkGdRIM6jbTFDy+0XUWlwoa7ChrNGOo412VDQ5UN7sQEWTA9VmJzw+EUcbHTja6ADQ2O57pCaokZOkRW6iFjlJWmSbNMhJ0iHLpIFCLsDvB2xuL+osLlS1OHGgxozv98rx0Pavo7ZurygCIgC/GEyUnSTLMNWd/JR2GTUKJOulMJmSoEZKu/dVSNGrkaxXxXyWfm/EsNjL6QJ/QPZ0WFx3oB5unx8FKToMTE/o0bIQEfVGMpnUaphp0uCM4pQ2z/v8YmityIomh/T1+PtNDjg8PtRbpQXJdxxtjuDdBQAeCAKQl6RDYao0hrIwRY9Mk0ZqsdMroVcpoJAHt1yUIdgjLopSMBQRDIpSWgwGxmB4FIP3A+ccfxxA6PWBq4bue3wiHB4vbC4f7G4vrIGvFqe0CHuTzY0muxuNNjea7R402t1ocXggioDZ6YXZ6Q17XVKDRtFBoOy/4bJLYXH//v34+uuvUVtbC7+/9Ur9CxcujErBKDzBlsWenuCyMTCx5dxBaRyzQkQUA3KZgOxELbITtTi9sO3zoiii2e5BRbMD5U0OVJ4QJqvNToii1EWsVcqlLRCNahQkaWGtPIhZ087CkKzEuFiGLRp8fhEtDg8aA0GyweqS9iO3utFgk26NNhcarMH7bvj8YmA3oMjDZaJOBb1aDq0y2EV+7L5WJYdOKYdScWxHIml3IkE6Jjt2XwDg8XpRYgGqzU7kpShj+40KQ8Rh8Z///CfuuOMOpKamIjMzs1UwEASBYbGb6ZTSn11NPTxmMRgWJw1o+9cwERHFniAISAqM1RuZYwr7dR6PB8uXH8DwLCOUfSQoAlK4DnY/h8PvF2F2eqQgaZWCZL1VCpGNNjfqra7j7ksB9PhwiajvqKSAIqsKv73QEOXrdqUkEfrjH/+IRx99FL///e9jUR6KkD4Oxiw22dyhbbImFiWf5GwiIqL4I5MJSNRJLYQD0k5+vj/QchlslWyyu+Fw+2B3S13kdrcPNrc3dMzh9sHt88Pj88PrE1vd9/j8ocfBrnen3Q6DJj5GC0ZciqamJvz0pz+NRVmoC4Ld0I22nmtZ/K5EGmQ9OCMBqQmx2+eViIgoXshkx1pyo01q7V2OGRPzon7troh4VOZPf/pTrFy5MhZloS7QK6Q/QXpyzOJ3JVIX9BlF7IImIiLqa8JqWfzLX/4Suj9w4EA8+OCD2LhxI0aNGgWlsvXAy9/97nfRLSF1KiHw7e/JMYvbAzPuTivkXtBERER9TVhh8dlnn231OCEhAWvXrsXatWtbHRcEgWGxmwW7oe1uH5weX7fPYvP4/NhdaQYAjM5N7Nb3JiIiotgLKyyWlJTEuhzURVq5NOPL55eWTMg0dW9Y3F9jgcvrh0GjQEEyt/gjIiLqayIes+hwODp8rqqq6pQKQ5ETBCBRK/VF90RX9A/lLQCA0bkmyOJkv1IiIiKKnojD4rhx47B169Y2x9977z2MHj06KoWiyCTqAmGxB2ZE7wiExVE5id3+3kRERBR7EYfFqVOnYvLkyXjiiScgiiKsVituvvlmzJ49mwty95CkYFjsgRnRP1Q0A5BaFomIiKjviXidxeeffx6XXnopbrnlFnz22WeorKyE0WjEpk2bMHz48LCvc/ToUZSWlsJutyMtLQ0jRoyAWs01+rqip7qhvT4/9tdYAQAjso3d+t5ERETUPbq0+/W0adNw1VVX4X//+x+OHj2KJ554IqygWFZWhvnz56OwsBCFhYU477zzMH36dJx22mkwmUyYOnUq3n333Tb7TXc3r9eLP/zhDygqKoJWq0VxcTEefvjhHi9XR4ILgnZ3N/TRJgfcXj80Shlykzi5hYiIqC+KOCweOnQIkyZNwqeffooVK1Zg3rx5uPLKKzFv3jx4PB13g951110YNWoUDhw4gIcffhi7du1CS0sL3G43qqursXz5cpx99tl48MEHMXr0aGzatOmUPtipePLJJ/Hiiy/ir3/9K/bs2YOnnnoKTz/9NJ5//vkeK1NnjrUsdm839IEaaYu/AWkJkHNyCxERUZ8UcTf02LFjcemll2LFihVITEzE1KlTMWPGDNx0001YtWoVtm3b1u7rVCoVDh06hLS0thsupqen44ILLsAFF1yAhx56CMuXL0dZWRlOP/30yD9RFGzYsAFXXnklLr30UgBAYWEh3nrrLWzevLlHynMywQkuzd3cDX2gVuqCHpzR85ucExERUWxEHBZfeOEF3Hjjja2OTZ48Gdu2bcPcuXM7fN3TTz8d9nvMmDEj0mJF1dlnn40XX3wR+/fvx+DBg7Fjxw58++23WLJkSbvnu1wuuFyu0GOzWVqk2uPxdNraeqqC1zaqpbUVG6yumL7fifZVSZ+zOEXbre8bz4LfB34/4gfrJP6wTuIL6yP+dFedhHt9QRRFMaYlaYfD4YAoitDppHFuZWVl+PDDDzFs2DBcfPHF3V2cNkRRxIIFC/Dkk09CLpfD5/Ph0Ucfxfz589s9f9GiRVi8eHGb48uWLQt9xlj6oVHAy/vkKEgQcc8oX8zfL+jpnXKU2wTcOsSHUcnd/r8RERERnQK73Y7rrrsOLS0tMBo7nqgacVj8+OOP27+QIECj0WDgwIEoKirq9BrBCTK//vWv0dzcjKFDh0KpVKK+vh7PPPMM7rjjjkiKFHVvv/027rvvPjz99NMYMWIEtm/fjrlz5+KZZ57B7Nmz25zfXstiXl4e6uvrO/3mnyqPx4NVq1YhecjpuPG1bchP1mLN3efE7P2O5/OLGPPIGri8fqyaexYKU/Td8r7xLlgnU6dObbNvOvUM1kn8YZ3EF9ZH/OmuOjGbzUhNTT1pWIy4G3rmzJkQBAEnZszgMUEQcPbZZ+Ojjz5CUlJSu9fYunVraL/p9957DxkZGdi2bRvef/99LFy4sMfD4n333Yf7778f1157LQBg1KhRKCsrw+OPP95uWFSr1e0u+6NUKrvlBy/dKLVeNto83faDXtVgh8vrh0ohQ1GaEQp5lybW91ndVfcUPtZJ/GGdxBfWR/yJdZ2Ee+2I/4VftWoVTj/9dKxatQotLS1oaWnBqlWrMHHiRHz66af45ptv0NDQgHvvvbfDa9jtdhgM0qSIlStX4qqrroJMJsOZZ56JsrKySIsUdXa7HTJZ62+NXC6P26VzUhOkpXOsLi+cnu7phj5QK82ELk7VMygSERH1YRG3LN5111146aWXMHny5NCxCy+8EBqNBrfddht27dqFJUuW4Be/+EWH1xg4cCA++ugj/OQnP8GKFStw9913AwBqa2tj2m0brssvvxyPPvoo8vPzMWLECGzbtg3PPPNMp5+pJxk0CqgUMri9ftRZXMhLjv04yeBM6EGcCU1ERNSndWmdxfYCndFoxOHDhwEAgwYNQn19fYfXWLhwIe69914UFhbijDPOwKRJkwBIrYzjxo2LtEhR9/zzz2PWrFmYM2cOhg0bhnvvvRe33347HnnkkZ4uWrsEQUBagtQNXmd1neTs6DgQ2LllUHpCt7wfERER9YyIWxYnTJiA++67D2+88UZozcS6ujrMmzcvtC7igQMHkJub2+E1Zs2ahbPPPhtVVVUYM2ZM6PiFF16In/zkJ5EWKeoMBgOWLFnS4VI58SjVoEZFswP1lu4JiwcD3dCDMxgWiYiI+rKIw+Irr7yCK6+8Erm5ucjLy4MgCDhy5AiKi4vx3//+FwBgtVrx4IMPtnltdnY2rrzySlxxxRW48MILkZmZ2er5iRMndvFjUFpg3GJ3tCz6/WKoG3pgOruhiYiI+rKIw+KQIUOwZ88erFixAvv374coihg6dCimTp0amhQyc+bMdl+7bNkyfPLJJ/jd736HmpoaXHzxxbjiiitw6aWXIjk5+ZQ+SH+XZpC6oestsd/FpbLFAbvbB6VcQEEK94QmIiLqyyIOi6WlpSgsLMQll1yCSy65JKLXTpkyBVOmTMGf//xn7Nq1Cx9//DH+9re/4dZbb8WkSZNCrY4DBgyItFj9XmpozKIz5u8VbFUsStVDyZnQREREfVrE/9IXFxfj7LPPxj/+8Q80NjZ2+Y1HjBiB+fPnY+PGjSgrK8P111+PL7/8EqNGjcLIkSPx2Wefdfna/VEwLHZHy+LB0OQWdkETERH1dRGHxc2bN2PSpEn44x//GBqD+O6777bawSRSmZmZ+NWvfoVPPvkE9fX1eOSRR9pd5Jo6FuqG7oYxi8E1FgdyJjQREVGfF3E39Pjx4zF+/Hg89dRT+Prrr7Fs2TLcfvvtuPXWW3H11Vdj6dKlYV+rtrYWtbW1bRa7jocZ0b1NajcunXNsjUWGRSIior4u4rAYJAgCzj//fJx//vm444478Mtf/hKvv/56WGFxy5YtmD17Nvbs2dPutoE+X/fsQtKXHJvgEtuwKIoiu6GJiIj6kS6HxaNHj+Ktt97CsmXL8MMPP2DSpEn461//GtZrb7nlFgwePBivvPIKMjIyIAhCV4tBAcEt/2xuH+xuL3SqLldtp2rMLlhcXshlAopS9TF5DyIiIoofESeKl156Cf/+97/xv//9D0OGDMH111+Pjz76CIWFhWFfo6SkBB988AEGDhwY6dtTBxLUCmiUMjg90pZ/BSmxCYvB8YqFKTqoFJwJTURE1NdF/K/9I488gokTJ2Lz5s3YtWsXFixYEAqKdXV1YV3jwgsvxI4dOyJ9a+qEIAjIMGoAANUtsVs+5wC7oImIiPqViJufjhw50qrbWBRFfP7553j55Zfx2WefhTUr+uWXX8bs2bPx448/YuTIkVAqla2ev+KKKyItFgHINGpQ1mBHtTmGYTHQssjJLURERP1DxGExGBQPHz6MpUuX4vXXX4fVasWll16Kt99+O6xrrF+/Ht9++y0+//zzdq/PCS5dk52oBQBUNscuLO6vCW7zx7BIRETUH0TUDe10OvHmm29iypQpGD58OHbs2IGqqiqsW7cOb775ZthL3vzud7/DjTfeiKqqKvj9/lY3BsWuyzJJ3dBVLY6YXF8UReyvlloWh2SyG5qIiKg/CDsszpkzB9nZ2fjb3/6Gn/70p6ioqMAnn3wCQRBCe0KHq6GhAXfffTcyMjIiLjB1LCvGLYtVLU5YXF4oZAKKU9mySERE1B+E3Q390ksv4fe//z3uv/9+GAyn1qp01VVX4auvvuIe0FGWHeOWxf01UqtiUaqeM6GJiIj6ibDD4htvvIFXX30VWVlZuPTSS3HjjTfikksu6dKbDh48GPPnz8e3336LUaNGtZng8rvf/a5L1+3vskxSy2JVjGZDB8PiYHZBExER9Rthh8XrrrsO1113HUpLS/Hqq6/iN7/5Dex2O/x+P3bv3o3hw4eH/aYvv/wyEhISsHbtWqxdu7bVc4IgMCx2UXai1LLYaHPD6fFBo5RH9fr7qqXJLUMyGBaJiIj6i4j7EgsLC7F48WKUlpbiX//6F66++mrccMMNyM3NDTvklZSUdHg7fPhwxB+CJCatEtpAQIzFWouhlkWGRSIion4j7LC4ZMkSNDQ0hB4LgoBLLrkE//nPf1BZWYl77723TSshdS9BEJAVaF2sjPK4RZ9fDK2xyJnQRERE/UfYYXHx4sXIycnBNddcg5UrV0IUxdBzycnJmDt3bqe7sjzxxBOw2+1hvdd3332Hzz77LNyi0XGyg+MWozwj+mijHU6PH2qFDPnJuqhem4iIiOJX2GGxuroar7zyChobGzF9+nQUFBTgoYceQklJSViv3717N/Lz83HHHXfg888/b7U1oNfrxc6dO/HCCy9g8uTJuPbaa2E0GiP/NBQat1jeFN2WxX2BLuiB6QmQy4STnE1ERER9RdhhUa1W4/rrr8fq1atx6NAh3HLLLXjjjTcwaNAgXHTRRXjrrbc63ervjTfewJdffgm/34/rr78emZmZUKlUMBgMUKvVGDduHJYuXYqbb74Ze/fuxTnnnBOVD9jfFKToAQBljbaoXvdAICxycgsREVH/0qXF8oKTXEpKSvDFF18gIyMDt956K7Kzszt93ejRo/GPf/wDDQ0N2Lp1K959913885//xIoVK1BTU4PNmzfjtttug1qt7tKHIYS6iI80hNflH659gW3+uGwOERFR/xLx3tAnkslkEAQBoijC7/eH9RpBEDBmzBiMGTPmVN+eTlCQIoXFssbohsXQNn9sWSQiIupXutSyWFZWhsWLF6OoqAjTpk1DZWUl/vnPf6Kqqira5aMIFSRL3dB1Fhfsbm9Urun2+nGoji2LRERE/VHYLYtOpxPvv/8+li5dirVr1yIrKwuzZ8/GL37xCxQXF8eyjBQBk04Jk1aJFocHRxrtGJp56hOFSupt8PpFJKgVoS0FiYiIqH8IOyxmZmbC6XTisssuwyeffIKLL74YMhn3B45HBSk67CxvQVlDdMLiniozAGBopgGCwJnQRERE/UnYYXHhwoW46aabkJqaGsvyUBTkJ0thMVqTXHYHwuLwbC5nRERE1N+E3TR4zz33IDU1FcXFxa12cglqbm5md3ScODbJJTrL5+yqbAEADM9iWCQiIupvIu5HLi0thc/na3Pc5XKhoqIiKoWiUxNca7Gk/tTDoiiK2F0ptSyOyDad8vWIiIiodwm7G/rjjz8O3V+xYgVMpmPBwefzYc2aNSgsLIxq4ahrBqYnAAAO1lpP+VrVZiea7B7IZQIGZSSc8vWIiIiodwk7LM6cOROAtEbi7NmzWz2nVCpRWFiIP//5z1EtHHVNMCzWmF0wOz0wapRdvtauCqlVcWBaAjRKeVTKR0RERL1H2GExuOB2UVERNm3axIkuccyoUSLDqEaN2YWDtVaMz0/q8rU4uYWIiKh/i3jMYklJSYdBkWMW48egdGnx7FPtij42XpFhkYiIqD+KykKJ1dXVuPPOOzFw4MBoXI6iIFrjFndVcSY0ERFRfxZ2WGxubsb111+PtLQ0ZGdn4y9/+Qv8fj8WLlyI4uJibNy4EUuXLo1lWSkCwbB4oMbS5Wu0ODw42ugAwG5oIiKi/irssLhgwQJ88803mD17NpKTk3H33Xfjsssuw7fffovPP/8cmzZtws9//vNYlrVbVVRU4IYbbkBKSgp0Oh3Gjh2LLVu29HSxwjYoGBZPoWXxxwqpVTEnUYtEnSoq5SIiIqLeJewJLp999hleffVVXHTRRZgzZw4GDhyIwYMHY8mSJTEsXs9oamrCWWedhfPPPx+ff/450tPTcejQISQmJvZ00cI2OEMas1je5IDF6YGhCzOid5Q3AwDG5iVGsWRERETUm4QdFisrKzF8+HAAQHFxMTQaDW699daYFawnPfnkk8jLy8Orr74aOtbZGpIulwsulyv02GyWJoV4PB54PJ6YlTN47fbeI0ElIMukQVWLEz8cbcLphZHPiN5W1gQAGJGdENPP0Zd0VifUM1gn8Yd1El9YH/Gnu+ok3OsLoiiK4Zwol8tRXV2NtLQ0AIDBYMDOnTtRVFTU9VLGqeHDh+Piiy9GeXk51q5di5ycHMyZMwe/+tWv2j1/0aJFWLx4cZvjy5Ytg06ni3VxO/TPvTL82CTDVYU+nJcVVjW38tAWOZrdAu4c7sVAbt5CRETUp9jtdlx33XVoaWmB0djx3ISww6JMJsP06dOhVqsBAJ988gkuuOAC6PX6Vud98MEHp1Ds+KDRaABI+2H/9Kc/xffff4+5c+fiH//4B2666aY257fXspiXl4f6+vpOv/mnyuPxYNWqVZg6dSqUyrbdzH/58iCe/+owfjIuG09dNTKia9dZXJj81FoIArD1gQuQoA67EbpfO1mdUPdjncQf1kl8YX3En+6qE7PZjNTU1JOGxbATwIm7ttxwww1dL12c8/v9OO200/DYY48BAMaNG4ddu3bh73//e7thUa1Wh0L08ZRKZbf84HX0PqNypa7nPVWWiMuxu7oRgLRzS1KC9tQL2c90V91T+Fgn8Yd1El9YH/En1nUS7rXDDovHj9/r67KyskLjM4OGDRuG999/v4dK1DUjcqS+44O1Vri8PqgV4W/XtzMwuWV0bmIMSkZERES9RVQW5e5rzjrrLOzbt6/Vsf3796OgoKCHStQ12SYNknRKeP0i9lVHtt7i9nJp2ZyxeRysSERE1J8xLLbj7rvvxsaNG/HYY4/h4MGDWLZsGV566SX85je/6emiRUQQhFDL4LYjzWG/ThRF/MCWRSIiIgLDYrtOP/10fPjhh3jrrbcwcuRIPPLII1iyZAmuv/76ni5axCYUSOMWtwSWwQnHoTobmuweqBUyDM0yxKpoRERE1AtwimsHLrvsMlx22WU9XYxT1pWwuLlUmtwyJi8xonGORERE1PewZbGPG5OXCJkAVDQ7UGN2hvWaTaVSsJxYmBzLohEREVEvwLDYxyWoFRiSKa2dtDXM1sVNgZbF07qw6wsRERH1LQyL/cBpga7ojYcbTnpujdmJI412yIRjXdhERETUfzEs9gNnDUwBAKw7WH/SczcckgLl0EwjDBouzkpERNTfMSz2A5MGpEImAIfrbKhsdnR67jf76wAA5wxO7Y6iERERUZxjWOwHTFplaL3Ebw903Lro94v4JvD8eYPSuqNoREREFOcYFvuJcwZJLYXfHKjr8Jw91WbUW13QKuWYwMktREREBIbFfmPKkHQAwNf76uD0+No95+t9UpCcNCCF6ysSERERAIbFfmNcXiKyTBpYXV6s3d9+6+InOyoBAFOHZ3Rn0YiIiCiOMSz2EzKZgEtHZQEAPttZ1eb5PVVm7K22QCWXYcbIrO4uHhEREcUphsV+5NLRUghcvacGFqen1XMfba8AAEwZkgaTjkvmEBERkYRhsR8Zm5eIAWl62N0+vLelPHTc6fHhvc3S45+My+mp4hEREVEcYljsRwRBwM1nFQEAXlx7CA63NNHlXxvK0GBzIydRy/GKRERE1ArDYj9zzWm5yE3Sosbswh8++hGbSxvx7Or9AIC7LhwEhZz/SxAREdExTAb9jFohx+NXjYIgAO9vLcesFzfA7vbhrIEpmDUht6eLR0RERHGGYbEfOmdQGp67dhxS9CoAwMUjMvDCdRMgkwk9XDIiIiKKN4qeLgD1jCvGZOPSUVnw+PzQKLkANxEREbWPYbEfk8sEyGUMikRERNQxdkMTERERUYcYFomIiIioQ+yGjgFRFAEAZrM5pu/j8Xhgt9thNpuhVHLXlXjAOok/rJP4wzqJL6yP+NNddRLMKcHc0hGGxRiwWCwAgLy8vB4uCREREVHnLBYLTCZTh88L4sniJEXM7/ejsrISBoMBghC75WjMZjPy8vJw9OhRGI3GmL0PhY91En9YJ/GHdRJfWB/xp7vqRBRFWCwWZGdnQybreGQiWxZjQCaTITe3+xa4NhqN/AGPM6yT+MM6iT+sk/jC+og/3VEnnbUoBnGCCxERERF1iGGRiIiIiDrEsNiLqdVqPPTQQ1Cr1T1dFApgncQf1kn8YZ3EF9ZH/Im3OuEEFyIiIiLqEFsWiYiIiKhDDItERERE1CGGRSIiIiLqEMMiEREREXWIYZGIiIiIOsQdXGKgu7b7IyIiIuoqbvfXgyorK5GXl9fTxSAiIiI6qaNHj3a6TTHDYgwYDAYAiPkG4B6PBytXrsS0adOgVCpj9j4UPtZJ/GGdxB/WSXxhfcSf7qoTs9mMvLy8UG7pCMNiDAS7nmO9AbjH44FOp4PRaOQPeJxgncQf1kn8YZ3EF9ZH/OnuOjnZkDlOcCEiIiKiDjEs9mMtDg9eXncY3+yv6+miEBERUZxiN3Q/5fT4MOvv63Gg1goAeGTmSNx4ZkEPl4qIiIjiDVsW+6lXvi0JBUUAeOyzPWi2u3uwRERERBSPGBb7Ib9fxFvfHwEAPDVrNIZmGuDw+PDelvIeLhkRERHFG4bFfmjrkSaUNzlg0ChwxZhsXH9GPgDgkx2VPVwyIiIiijcMi/3QV/tqAQBThqRDo5Tj4hGZAIAd5S2oNTt7smhEREQUZxgW+6F1B+oBAFMGpwEA0o0ajMoxAQD+d6i+x8pFRERE8adfhsVvvvkGl19+ObKzsyEIAj766KPQcx6PB7///e8xatQo6PV6ZGdn46abbkJlZd/oonV6fNhdaQYAnFGcHDo+sUi6v7WsuSeKRURERHGqX4ZFm82GMWPG4K9//Wub5+x2O7Zu3YoHH3wQW7duxQcffID9+/fjiiuu6IGSRt+uSjO8fhGpCWrkJGpDx8fnJwGQxjMSERERBfXLdRanT5+O6dOnt/ucyWTCqlWrWh17/vnnMXHiRBw5cgT5+fndUcSY2X60GQAwNs/Uanuf8QWJAIC91RbY3V7oVP3yfw0iIiI6ARNBGFpaWiAIAhITE9t93uVyweVyhR6bzVI3r8fjgcfjiVm5gteO5D22lTUCAEZmG1u9LlWnQKZRjWqzC1tLG3BGUXJHl6BOdKVOKLZYJ/GHdRJfWB/xp7vqJNzrC6IoijEtSZwTBAEffvghZs6c2e7zTqcTZ599NoYOHYo333yz3XMWLVqExYsXtzm+bNky6HS6aBb3lD2yVY56l4A7hvkwNLF11b+6X4btDTJclu/D1Jx+/b8FERFRn2e323HdddehpaUFRqOxw/PYstgJj8eDa6+9Fn6/Hy+88EKH582fPx/33HNP6LHZbEZeXh6mTZvW6Tc/GuVbtWoVpk6dCqVSedLzm+0e1G/4CgDwy59cBJO29WsqjaXYvmI/vIZszJgxJiZl7usirROKPdZJ/GGdxBfWR/zprjoJ9oSeDMNiBzweD6655hqUlJTgyy+/7DT0qdVqqNXqNseVSmW3/OCF+z6HG6T/KXIStUg1tm3xHJ6TCADYX2vlL4xT1F11T+FjncQf1kl8YX3En1jXSbjX7pezoU8mGBQPHDiA1atXIyUlpaeLFBX7A3tBD85IaPf5oZkGAEBpvQ1Oj6/bykVERETxq1+2LFqtVhw8eDD0uKSkBNu3b0dycjKys7Mxa9YsbN26FZ9++il8Ph+qq6sBAMnJyVCpVD1V7FN2oMYCABgcCIUnSjeokahTotnuwcFaK0YGFuomIiKi/qtftixu3rwZ48aNw7hx4wAA99xzD8aNG4eFCxeivLwcH3/8McrLyzF27FhkZWWFbuvXr+/hkp+afdWBsJjeflgUBAFDMqTn9gbOJSIiov6tX7YsTpkyBZ1NAu+LE8RFUcT+YMtiRvthEZC6or8racS+6vAGvRIREVHf1i9bFvujeqsbTXYPBAEYmN7+mEUAGJIpTeRhyyIREREBDIv9RnC8Yn6yDlqVvMPzhmQmBM63dku5iIiIKL4xLPYTh+qk8Deok1ZFAChOlZ6vNjthc3ljXi4iIiKKbwyL/cThehsAoDit87CYpFchWS/N+C4JvIaIiIj6L4bFfiIY/IpS9Sc9tzhwTrA1koiIiPovhsV+IqKwmCadc7iOLYtERET9HcNiP+D2+nG00Q7gWKthZwYEuqoPsxuaiIio32NY7AeONNrhFwG9So40Q9s9rE8UHNd4qJbd0ERERP0dw2I/EOqCTtNDEISTnh/shi6pt8Hv73sLlBMREVH4GBb7gZJ6qYWwKLXzmdBB+ck6KGQCHB4fqs3OWBaNiIiI4hzDYj8QyeQWAFDKZchP1gHgJBciIqL+jmGxHwgGvnAmtwSFxi1y+RwiIqJ+jWGxH4i0ZREABoSWz2FYJCIi6s8UPV0Aii2ry4taiwsAUBhRy2IgLHL5HCIiog65vD6YHV7YXF7Y3F7Y3T7p5vLC5vbB7vbC5vLB4fbC7RPh9fnh8flb3ff4xMBXP7x+ERBFNNTLIORX44pxeT39ERkW+7rSQNhL0atg0irDfl2wG5pjFomIqL8QRRHNdg9qLE7Uml2oMTtRa3GhyeZGi8ODZocHLQ4PzA4Pmu3SfYfHF6PSyHCk0RGja0eGYbGPK22Qwl4krYrAsS7ryhYHnB4fNEp51MtGRETUHURRRIvDgxqzC7UWJ2oCQbDOIn2Vbi7UWVxw+/xdeg+9Sg6dWiF9VSmgV7f+qlXKoVLIoJTLoJQLga+t7yvkAhQyAV6vD9t27MC5g1Kj/J3oGobFPq6sQdq5pSAwuzlcKXoVjBoFzE4vShtsGJppjEXxiIgoxjw+P+osrlCLmAhAKRegVsiRblTDpOqd0xdEUYTd7UOzw4Mmmxt1FikISl9dqA0Ew9rAY7c3/BCYpFMiw6hBmkGNdIMGKQlS71zwlqg77r5WBYNGAZns5OsYh8vj8UBdtR3DsgxRu+apYFjs44Lb/OVFGBYFQUBRWgJ2HG1GSR3DIhFRPBNFEdVmJ/bXWHGgxoKSehuONNpR1mBHRbMDvk42WFDKBRgUcrxZtQl5yTrkJumQm6hFbpIWuUk6JOmV0KkUkLcThvx+ES6vH06PDw6P77ivfriOux98znnCOW6vH16/H16fCJ9fhNcvtnrs8YvwnfDY4jzWDeyNcOOIRJ0SGQYN0o1SCMwwqpFuUCPDqEG6UYN0gxppBjV7007AsNjHhVoWUyILi4C01M6Oo82c5EJEFCdEUUStxYX9NZZQMNxfY8GBWissTm+Hr1PKBZi0Shg1SshkAjw+P2wuHxpsLnh8Ihp9AhpLm7CptKnDa2iVcshlAnx+ET5RCm+dhdDuIn02VaAVMHALhMHj7zMEdh3DYh93pPHUwiLASS5ERN1NFEXUWV04UGNtEwzNHYRCuUxAYYoOg9INGJCuR0GyHgUpOhSk6JFuULfbTerx+VHVZMMHX3yJ/GHjUGV2o6LZgfImB8qb7ChvcoS6b082kUMll0GtlEGjlEOrlEOjlEGrlEN9wmPNcTeVQgalTIBcLkApk0EuE6CQC5DLWj9WBO/LBOjVilA3cKJOCa1SHtZWttR1DIt9mMvrQ2WLNJMqPzmyCS6AtJc0cGy7QCIiij6314+DtVbsrjJjd6UZuypbsK/Ggma7p93zZQJQmKLHoIwEDM4wYFCGAYMzElCUqodaEVnLmVIuQ5ZJgyIDMGN0FpTK1qtmiKLUzWxzScu/+EQRCpkAWSC4yWVCKAC2101NfQPDYh9W3uSAKAI6lRypCaqIXx+cEV3Cbmgioqhwenz4saIFP1S0BIKhGQdqLfD42nbnygSgIEWPQekJx4JhugHFafpu604VBCHUCpiS0C1vSXGIYbEPOxIYr5ifrOtSE30wLDbZpZlmSfrIAycRUX/WaHNjS1kTNpc2YnNZE34ob2l3aRaDRoHhWUaMyDZheLYRQzMNGJiewDF2FBeiFha3bt2KhQsX4tNPP43WJekUBccr5kc4EzpIp1Igy6RBVYsTh+ttmMCwSETUIVEUUdpgl4JhaRM2lzXiUDtjvlMT1BibZ8LwbBNGZBsxPMuI3CQtx91R3IooLK5atQorV66EUqnErbfeiuLiYuzduxf3338/PvnkE0ydOjVW5aQuOJWZ0EFFqXpUtThRUm/DhIKkaBWNiKjXc3v92FXZgi1lTdhU2ogtZU2ot7rbnDcwPQGnFyZhQkEyTi9M6nJvD1FPCTssvv7667jllluQnJyMxsZGvPzyy3jmmWcwZ84cXH311dixYwdGjhwZy7JShI40Sn/R5qdEPrklqDhNj/WHGnC4jpNciKh/a3F4sPVIE7aUSuFwR3kznJ7WXcoquQyjc004rTAZpxUkYUJBEofwUK8Xdlh89tln8dhjj+H+++/Hf/7zH1x77bV49tlnsW3bNgwYMCCWZYy6b775Bk8//TS2bNmCqqoqfPjhh5g5c2boeVEUsXjxYrz00ktoamrCGWecgb/97W8YMWJEzxW6C7q6e8vxilKlEc2c5EJE/Ykoijja6MCWI1KX8payJuyrsUA8YR5Kok6J0wqSQuFwZI6J4wypzwk7LB46dAg/+9nPAACzZs2CXC7HM8880+uCIgDYbDaMGTMGt9xyC66++uo2zz/11FN45pln8Nprr2Hw4MH44x//iKlTp2Lfvn0wGOJj652T8fvFU1pjMaiYM6KJqB8IzlLeUiYFw61H2u9SLkzRhbqTTytMQnFqQlS3eSOKR2GHRZvNBr1eCg4ymQwajQZ5eXkxK1gsTZ8+HdOnT2/3OVEUsWTJEjzwwAO46qqrAEhd8BkZGVi2bBluv/327ixql9VaXHB5/ZDLBGQnart8neK0Y2HR7xf5S5GIej2PT1rX8IeKFuyqaMHOihb8WNHSZvkapVzAyBwTxucn4fTCJIwvSEK6QdNDpSbqORFNcFmxYgVMJhMAwO/3Y82aNfjxxx9bnXPFFVdEr3Q9oKSkBNXV1Zg2bVromFqtxnnnnYf169e3GxZdLhdcLlfosdlsBiBtBO7xtL+oajQEr93eexyulcqQbdIAfh88/s5X3u9Iul4BpVyAy+vHkQYLck4hePYHndUJ9QzWSfzpzjppcXhwqM6G/TXSote7Ks3YW2MN7UpyvBS9CuPzEzE+PxHj8kwYmW2E+oQu5b74/xF/RuJPd9VJuNcXRPHEERjtk8lkJ7+YIMDn61oo6SmCILQas7h+/XqcddZZqKioQHZ2dui82267DWVlZVixYkWbayxatAiLFy9uc3zZsmXQ6breBXwqvqsVsOyQHINNfvxmeNtfipF4bLscNQ4BdwzzYWhiz+8DSkR0PJcPaHIBDS4BjS6g1iGg2gFU2wWYPe33hmjkInL1InL1QJ5eRKFBRIoa4CRl6k/sdjuuu+46tLS0wGg0dnhe2C2Lfv+pBY7e5sRlDURR7HCpg/nz5+Oee+4JPTabzcjLy8O0adM6/eafKo/Hg1WrVmHq1Klttmjat/ogcOgwxg/Ox4wZw0/pfT5p2oaavXVIKx6BGWfmn9K1+rrO6oR6Busk/oRTJz6/CKvLiwarG/U2FxqsbjTY3Ki3SrdGmxs1ZifKmx1otHXeOpJpVGNgegKGZRowItuIkdlG5CVpOawmgD8j8ae76iTYE3oy3MHlBJmZmQCA6upqZGVlhY7X1tYiIyOj3deo1Wqo1eo2x5VKZbf84LX3PuXNTgDSbOZTLcOAdANW763DkSYnf5GEqbvqnsLHOjl1fr8Iq9uLFrsHZqcHZocXZqcHTo8PLq8fHp8fHq8fHp8It88Pd+CY1y9Kz/n88PpEuLw+HDkqw+fm3fCJ0nqFFqcHFqc3cPPA5o6sl8qgUSAvSYfcJC0KU4Nb5BkwIE0Pg4b1Hg7+jMSfWNdJuNcOOywePHgQLS0tmDBhQujYmjVr8Mc//hE2mw0zZ87EggULTnqdffv24a233sK6detQWloKu92OtLQ0jBs3DhdffDGuvvrqdoNXdykqKkJmZiZWrVqFcePGAQDcbjfWrl2LJ598ssfKFalT3b3leMFt/w5zRjRRnyaKIuqtbhxtsqO8yYGjjdLX8sDjiiZHu1vVdY0MqK856VkGtQKpBjVS9CqkJqiRkiB9TTWokZagRl6yFrlJOpi0DDlEsRJ2WLzvvvswcuTIUFgsKSnB5ZdfjnPOOQejR4/G448/Dp1Oh7lz57b7+m3btmHevHlYt24dJk+ejIkTJ2LmzJnQarVobGzEjz/+iAceeAB33nkn5s2bh7lz58YsNFqtVhw8eDD0uKSkBNu3b0dycjLy8/Mxd+5cPPbYYxg0aBAGDRqExx57DDqdDtddd11MyhMLFc0OAEBu0qmHxeI0aa1FLsxN1LuJoogmuycU/oJhMBgOy5vsbRaZbo9aIYNRq4RJq4RBo4BeJU2EU8plUCpkUMtlgfsCFDIZVAoZFLLA83IBAkQc2LcXo0eOgEalhFIuwKBRwqhRwKCRrmkI3FcpTj5enohiK+ywuHnzZsybNy/0+N///jcGDx4cmvAxevRoPP/88x2GxZkzZ+K+++7DO++8g+Tk5A7fZ8OGDXj22Wfx5z//OayWyq7YvHkzzj///NDj4HjD2bNn47XXXsO8efPgcDgwZ86c0KLcK1eu7DVrLDo9PtRZpNnZOUmnPns52LJY0eyA0+PjgrNEcczs9OBoox1HG4+1CJY3HXt8su5dQQCyjBrkJumQG2i1y0uSvuYmaZFmUJ/y7wCPx4Pllj2YcWY+uz2JeoGww2J9fT1yc3NDj7/66itcfvnlocdTpkzB//3f/3X4+gMHDkClOvmWR5MmTcKkSZPgdrddDDVapkyZgs4mgQuCgEWLFmHRokUxK0MsVbdI4xU1ShmSdKf+izg1QQWDWgGLy4sjjXYMzugdoZmor2u0ufHd4QZsPdKEvdUW7K+xoMbsOunr0g1q5CZpkZcsBUBprJ8OeclaZJm0bM0jolbCDovJycmoqqpCXl4e/H4/Nm/ejLvvvjv0vNvt7jSAdRQUy8vLkZ2d3WZpnnCCJbUv2AWdk6iNymb1giCgOE2PHeUtOFxnZVgk6iGiKGJneQs+/7EaX++rxd5qS7vnpehVyE3SIrdVGJTCYU6ilr0DRBSRsMPieeedh0ceeQQvvPAC3n33Xfj9/lZdubt370ZhYWHEBRg+fDi2b9+O4uLiiF9L7atoCoTFKIxXDCpKDYRFTnIh6laiKOKHihb8d3slvvixOvTHYNCg9AScUZyM4VkmDMk0YFBGAoyc/UtEURR2WPzjH/+IadOmobCwEDKZDH/5y19C2/8BwL/+9S9ccMEFERcgzDXBKQLlx7UsRktRqjTJpaSOYZGoO9SanfhwWwXe31qO/TXHJpfpVHKcPzQd04ZnYPKAVKQZem71CCLqH8IOi8XFxdizZw92796NtLS0VrubAMDixYtbjWmknhNsWcyNwuSWoOAe0WxZJIodp8eH1Xtq8N6Wcnyzvw7+wN/SaoUMU4dn4PIx2ThvcBq7kYmoW0UUFjdt2oQxY8a0+3xHx09mwYIFnc6OpshVNEtrLEa3ZVEKiyUMi0RRJYoith9txntbyvHJjkqYnd7Qc+PzEzFrQh4uHZ3FdQSJqMeEHRZLS0tjsu/z/Pnzo37N/q4ysHtLdgzCYqPNjWa7G4k6TkAiOhXVLU58sK0c720px+HjhndkmTS4anwOrh6fG1rjlIioJ3Xbdn9PPPEEfve730GnO/mki++++w719fW49NJLu6FkfYvfL6KqJTjBJXphUa9WINOoQbXZicP1NozPZ1gkipTD7cPK3dV4b0s5vj1Yj+CQbY1Shukjs3D1+FxMGpACOfcsJqI4ElFY3L17N6qrqzs9Z/To0R2+Nj8/Hz/96U9xxRVX4LTTTkNaWhoAwOv1Yvfu3fj222/x5ptvoqqqCm+88UYkRaOAWosLHp8IuUxARpQHvhel6lFtdqKkzobx+UlRvTZRXyWKIraUNeH9reX4dEcVLK5j3cwTC5Mxa0Iupo/K5P7FRBS3IgqLF154YbuzlwVBgCiKEAShw67qN954Azt37sTf/vY3XH/99WhpaYFcLodarYbdLo2xGzduHG677TbMnj27R/eH7s2C4xUzjRoo5NFdWLc4TY8Nhxs4bpEoDBXNDny4tRzvb61o9TOTm6TFVeNzcfX4HBSk6Du5AhFRfIgoLH733Xeh1sCuGD16NP7xj3/gxRdfxM6dO1FaWgqHw4HU1FSMHTsWqampXb42Scqbot8FHRQct3i4nntEE7XH7vbi8x+q8f7Wcmw43BDqZtap5Jg+MguzJuTijKJkyNjNTES9SERhMT8/H+np6af8poIgYMyYMV2eQU0dCy7YmxvFyS1BweVzDtWyZZEoyO8X8V1JI97bUo7Pf6yC/bi9l88sTsasCXmYPjITenW3DREnIooq/vbqYyoDYTGaM6GDBqVL2/yV1Nvg9fmj3s1N1Fv4/SK2HW3Gil3V+GxnVatdVQpSdLh6fC5+Mi4HecnR20WJiKinRLTdH/drjn8VMeyGlvaUlcHp8eNIo53LelC/4vb6sam0EV/8WI0Vu6pRa3GFnjOoFbhsjDSbeUJBUlT2ZCciihdhh8WvvvoKwLHFuVNSUlo939zcjPHjx+Pw4cPRLSFFpCIGW/0FyWQCBqYn4McKMw7WWhkWqU8TRRGH6qxYd6Ae6w7UY+PhhlZdzAa1AhcMS8clIzJx/tB07qpCRH1WxN3QHS3O7XK5UFFREZVCUdeIohjTlkVA6or+scKMA7VWTBsRk7cg6hE2lxc/VrRgR3kzdpS3YGtZE6panK3OSU1Q4aJhGbh4ZCYmD0iBWsGASER9X9hh8eOPPw7dX7FiBUwmU+ixz+fDmjVrUFhYGNXCUWRaHB7YAi0fsWhZBICB6VJr4sFazoim3svt9WNftUUKhkebsbO8BQdqLaG9mIPUChkmFiXjnEGpOHtgGoZmGjiTmYj6nbDD4syZMwFIM5lnz57d6jmlUonCwkL8+c9/jmrhKDLBZXNS9KqYdYkNCoTFA7WWmFyfKNr8fhE1DuCj7ZXYVWXF9qPN2F1lhtvrb3NutkmD0bmJGJOXiDF5JozPT2L3MhH1e2GHRb9f+sVaVFSETZs2cU3EOBScCR2rLmigdcui3y+ylYXiiiiKqDY7seOo1J28s7wZO462wOpSANt/bHWuSauUQmGuCWNyEzE6z4R0g6aHSk5EFL8iHrNYUlLS4XMVFRXIyck5pQJR18VycktQfrIOKrk0I7qi2cGlQajHBIPhrgozdlWa8UNFC3aWN7eapRyklIkYnZuEMXlJGJNnwti8ROQn6zhrmYgoDFFZZ7G6uhqPPvooXn75ZTgcjpO/gGIiNLklhmFRIZehOE2PvdUWHKi1MCxSzImiiDqrC6X1dpTW23Co3ordlWbsrjSjweZuc75cJmBwhgFj80wYnZuIEZkJOLh1HS6/dCKUSu6/TEQUqbDDYnNzM37zm99g5cqVUCqVuP/++/Hb3/4WixYtwp/+9CeMGDECS5cujWVZ6SQquqEbGpC6ovdWW3Cw1ooLhmbE9L2ob3N5fai3utFgdaHW7EKNxYlaswu1FidqzC5UtzhR1mALTdw6kVwmYGBaAkZkGzE824ixeYkYkW2CVnVsnKHH40EJGxCJiLos7LC4YMECfPPNN5g9eza++OIL3H333fjiiy/gdDrx+eef47zzzotlOSkM3dENDQR3cqnCgRrOiKbO2Vxe7K22oKzBhtIGO8oabKhsdqDe6ka91QWL0xvWdWSC9EdQYYoeRal6DMk0YGS2CUMyDZyAQkQUY2GHxc8++wyvvvoqLrroIsyZMwcDBw7E4MGDsWTJkhgWjyIRy63+jjcoIzgjmmGRWmuxe/DlvhqsP9iAHeXN0kQosfPXKOUCUvRqpBvVSDeokW7UIMOgQYZROpafrEdespZrGhIR9ZCww2JlZSWGDx8OQNrFRaPR4NZbb41ZwSgyTo/UnQcAuTHuhh503IxoURQ5SaCfq2h2YNWuaqzcXYPvShrhOyEdZhjVKE5NQGGqDgUpeuQmaZGWoEZKghppCWoYtQr+P0REFMciWjrn+MHhcrkcer0+JoWiyAW7oPUqOUza2A7iL0jRQyETYHV5UW12IssU23BK8UUUReypsmDl7mqs2l2DXZXmVs8PyTDggmHpGJ+fhDG5JqQbuRwNEVFvFnZYFEURN998M9RqNQDA6XTi17/+dZvA+MEHH0S3hD3A6/Vi0aJF+Pe//43q6mpkZWXh5ptvxh/+8AfIZLKeLl67jt/mL9atNCqFDAUpOhyqs2F/jZVhsR/w+vz4vrQRq3bXYOWumtAfJ4A0nvC0wmRMG56BqcMzUJDCPyKJiPqSsMPiibu23HDDDVEvTLx48skn8eKLL+L111/HiBEjsHnzZtxyyy0wmUy46667erp47equyS1BQ7OMOFRnw54qM84bnNYt70ndy+724pv9dVi5qwZf7qtFs90Tek6jlOGcQWmYNjwDFw7LQLJe1YMlJSKiWAo7LL766quxLEdc2bBhA6688kpceumlAIDCwkK89dZb2Lx5cw+XrGPBlsVYT24JGp5lxGc7q7D7hC5I6t2ONtrx7cF6rN5dg3UH61ttiZesV+HCoemYOjwD5wxKa7U8DRER9V1RWZS7rzn77LPx4osvYv/+/Rg8eDB27NiBb7/9tsOZ3y6XCy7XsV0jzGYpQHk8Hng8nnZfEw3Ba3s8HpQ32gAAWUZ1TN8zaGiG1NW4q7KlW96vtzi+TnoDs8ODjSWN+N+hBvzvYCPKGu2tns9L0mLqsHRcNCwd4/MTIQ9t7+iHx9N2b+V41NvqpD9gncQX1kf86a46Cff6giiKJ1nYov8RRRELFizAk08+CblcDp/Ph0cffRTz589v9/xFixZh8eLFbY4vW7YMOl337HDylx/lOGQRcNMgHyakxr5KzW7gwS0KCBDx1EQf2MjUO/j8QKkV2Ncsw74WAWVWQMSxMa4yiCgwAMMS/RiVLCJLC3CiMhFR32S323HdddehpaUFRqOxw/MYFtvx9ttv47777sPTTz+NESNGYPv27Zg7dy6eeeaZNmM3gfZbFvPy8lBfX9/pN/9UeTwerFq1ClOnTsXUv2xARbMT7/xqIsbnJ8bsPY836cmvUW91493bJmJsXve8Z7w7vk7iZWu5I412rN1fj3UH6/F9SVOb3VCKU3U4a0AKzhqQgolFyTBo+laHQzzWSX/HOokvrI/40111YjabkZqaetKw2Lf+VYiS++67D/fffz+uvfZaAMCoUaNQVlaGxx9/vN2wqFarQ7PEj6dUKrvlB0+QyVFtlsJqQaqh237YR2SbsHZ/HfbV2nF6MSe5HK+76r4je6vN+HBbBVbvrsGhOlur55L1Kpw1MBXnDEzFWYNSu21SVE/r6Tqhtlgn8YX1EX9iXSfhXpthsR12u73NEjlyuRx+f3yO0aq1uODzi1DKBaQb2obWWBmRbcTa/XX4obyl296TOtbi8ODdzUfx/tYK7Kk6NvFILhNwWkESpgxJxzmDUjE8ywiZjH3LREQUHobFdlx++eV49NFHkZ+fjxEjRmDbtm145pln8Itf/KKni9auimYnACDTpOnWEDAuPwkAsOVIU7e9J7V1tNGOpf8rwX82HQ11MSvlAi4Ymo7Lx2TjnEFpMV+onYiI+i6GxXY8//zzePDBBzFnzhzU1tYiOzsbt99+OxYuXNjTRWtXZYsUFru7O3FCgRQWD9Za0Wx3I1HHtfa60+E6K55dfQCf7awM7b88OCMBN04qxOWjs1gfREQUFQyL7TAYDFiyZEmHS+XEm8rQgtzdM/M6KFmvQnGqHofrbdh6pAkXDM3o1vfvr6paHHhu9QG8u6U8tA/zOYNSces5xTh3UCr3WSYioqhiWOwDgt3QOUndP1FhQkESDtfbsKWMYTHWmmxuvPD1Qby+oSy0WPYFQ9Pxf9MGY0S2qYdLR0REfRXDYh8QbFnM7YFZrRMKkvDulnJsKuW4xVixubx45dsSvPTNYVhdXgDAxMJkzLtkCE4rTO7h0hERUV/HsNgH9GTL4hnFKQCAbUeaYHV5kaDm/1LR4vT48ObGMrzw9SE02twApG0W77tkCKYMTmN3MxERdQv+y97LiSJQ2dK9+0IfryhVj4IUHcoa7Fh/sB7TRmR2exn6GrfXj/9sPoq/fnkQ1WbpD4HCFB3umTYEl43K4rI3RETUrRgWezmbF3AG9ujNMml6pAxTBqfh9Q1l+Hp/HcPiKWixe7Ds+yN4fX1pKCRmmzS466JBuGp8LpRy2UmuQEREFH0Mi71cU2CXwTSDGhplz2zQPGVIuhQW99ZCFEV2j0bA7xexuawJH24rx0fbKuHwSOskphnU+M2UAfj5GflQK7jxNhER9RyGxV6u0SUFs57csu3M4hSoFTJUtjjxQ0ULRucm9lhZegOz04NNJY1Yu78Oa/bUoiIwQQkAhmYacOs5xbh8TBZDIhERxQWGxV6uMdCy2BOTW4K0KjmmDs/Apzur8OG2in4fFkURaLS50WB3oMbsRLXZieoWJw7WWrGrsgWlDfZW5yeoFZg+MhNXjc/FmcXJbJklIqK4wrDYyzXFQcsiAFw1Pgef7qzCJzsq8cCMYVD08fF1Xp8fh+ps2Fttxv4aCyqbnahodqCq2YGqZjm8G7/u9PX5yTqcOzgV5w5KwzmD0qBVsRWRiIjiE8NiLxdqWezhsHjOoDSk6FWot7rx9b46XDS87y3QfaTBjhW7qrH+UD2+L2kM7cPclhTgU/QqZBg1yDCqkWnSoCBFjxHZRozINiFZz634iIiod2BY7OWa3PHRsqiUy3D1hFy89M1hvPJtSZ8Ji7VmJz7dWYWPd1Ri+9HmVs8lqBUYmmnAkEwD8pJ1yDJpkJ6gxJ4tG3DNFZcgQavumUITERFFEcNiL9cUB2MWg26eXIil35Zgw+EG/FDeglG5vXMLuiabGyt2VeOTnZXYcKgBge2XIROASQNScP6QdEwakIJhmcY2ax56PB7U7gLUir7dDU9ERP0Hw2IvZnd7YfMGWhbjICxmJ2px+ZhsfLitAs+tOYCXZ5/W00UKiyiKOFRnw4bDDVizpwbfHqiHN5gQAYzPT8QVY7IxY3QW0g09s5YlERFRT2FY7MWC2/wZNAoYNcoeLo3kN+cPwMc7KrF6Tw02Hm7AmYHtAKPN5xdxuM6KQ3VWlDc5YHV5YXF6IYqAUi5AIRegkMkC92VQyAQoZALkMgEOjw8Wpxd1FhcO19twqNaKhsB2ekHDsoy4bHQWrhiTjbxkXUw+AxERUW/AsNiLVQbW58vuoZ1b2jMw3YCfT8zDmxuP4OFPduO/vz0rajuPuLw+rNlTi092VGL9oQa0ODxRuS4AqBQyTMhPwlkDUzB9VBYGpCVE7dpERES9GcNiLxZsWcxOjJ+wCABzLxqMT3ZUYXeVGX//+hB+d+GgU7qe1eXF6+tL8cq3JWg8rgVQp5JjUHoC8pJ1MGmVSFArIJMJ8Hj98PpFeHx+eH0ivH4RXr90zOcToVXJYdAokKRToThNj8IUPYZkGnpsBxwiIqJ4xrDYi1W1SGGxp2dCnyg1QY2HrxyBu97ejr+sOYBJA1JwemFyxNcRRREfbK3Ao8v3hEJiplGDqyfk4KJhGRiVY+rz6zkSERH1NIbFXiy4TVy8tSwCwBVjsrFqdw0+3VmFO97cio9+Mxm5SeGP/TvaaMeCD3/AugP1AICiVD3uunAQLh+TDbmMO5wQERF1F4bFXqwy0A2dY4qvlkUAEAQBT80ajYO1VuyttuD6l7/D27ediayTlNXnF/Ha+lL8acU+ODw+qBQyzL1oEH51TnHUxj4SERFR+Pivby8Wzy2LAKBTKfDqLacjP1mHsgY7rvzr/7ClrLHD87ceacLMv/0Pj3y6Gw6PDxOLkvHFXedgzpSBDIpEREQ9hC2LvZTH50etRVqROzvOxiweL8ukxVu3nYmbl36PA7VWzHpxA64al4trTsvF4AwDnF4fth9pxvtby7F6Ty0AaSmg+dOH4drT89osek1ERETdi2Gxl6puccIvAnJBRGqc7zOck6jFh785Cwv/+yM+2FqB97eW4/2t5e2eO2tCLn5/yVCkGbhVHhERUTxgWOylgl3QSWr0ita3BLUCz1wzFjecWYB/bzyCtfvrUG91QS4TUJSqx5TBafj5Gflc35CIiCjOMCz2UhVNUlhMVosnOTO+jM9Pwvj8JACA0+ODSi7rFWGXiIiov+KsgV7q3MFpeOWm8ZiW07vC4vE0SjmDIhERUZxjy2IvlWZQ49xBqbAe6L1hkYiIiOIfWxaJiIiIqEMMi0RERETUIXZDx4AoSl3DZrM5pu/j8Xhgt9thNpuhVCpj+l4UHtZJ/GGdxB/WSXxhfcSf7qqTYE4J5paOMCzGgMViAQDk5eX1cEmIiIiIOmexWGAymTp8XhBPFicpYn6/H5WVlTAYDBCE2M32NZvNyMvLw9GjR2E0GmP2PhQ+1kn8YZ3EH9ZJfGF9xJ/uqhNRFGGxWJCdnQ2ZrOORiWxZjAGZTIbc3Nxuez+j0cgf8DjDOok/rJP4wzqJL6yP+NMdddJZi2IQJ7gQERERUYcYFomIiIioQwyLvZharcZDDz0EtVrd00WhANZJ/GGdxB/WSXxhfcSfeKsTTnAhIiIiog6xZZGIiIiIOsSwSEREREQdYlgkIiIiog4xLBIRERFRhxgWiYiIiKhD3MElBrpruz8iIiKiruJ2fz2osrISeXl5PV0MIiIiopM6evRop9sUMyzGgMFgAICYbwDu8XiwcuVKTJs2DUqlMmbvQ+FjncQf1kn8YZ3EF9ZH/OmuOjGbzcjLywvllo4wLMZAsOs51huAezwe6HQ6GI1G/oDHCdZJ/GGdxB/WSXxhfcSf7q6Tkw2Z4wQXIiIiIuoQw2I/4/X5sfFwA8xOT08XhYiIiHoBdkP3I06PDz//50ZsO9KMJJ0S790xGQPSEnq6WERERBTH2LLYj7zw1UFsO9IMAGiye7Do4109WyAiIiKKewyL/YTN5cWr60sBAPdPHwpBANYdqMfRRnvPFoyIiIjiWq8Oi9988w0uv/xyZGdnQxAEfPTRRyd9zdq1azFhwgRoNBoUFxfjxRdfbHPO+++/j+HDh0OtVmP48OH48MMPY1D67vX5j9WwOL0oSNHhtnOKMXlACgDgk52VPVwyIiIiime9OizabDaMGTMGf/3rX8M6v6SkBDNmzMA555yDbdu2YcGCBfjd736H999/P3TOhg0b8LOf/Qw33ngjduzYgRtvvBHXXHMNvvvuu1h9jG6xYlc1AGDm2BzIZAIuHpEJANhwqKEni0VERERxrldPcJk+fTqmT58e9vkvvvgi8vPzsWTJEgDAsGHDsHnzZvzpT3/C1VdfDQBYsmQJpk6divnz5wMA5s+fj7Vr12LJkiV46623ov4ZuoPd7cU3++sAIBQSzyiSWhY3lzbB4/NDKe/VfzcQERFRjPTqsBipDRs2YNq0aa2OXXzxxXjllVfg8XigVCqxYcMG3H333W3OCQbM9rhcLrhcrtBjs9kMQFpU0+OJ3RI1wWuf7D2+2lMDl9eP3CQtBqZq4PF4UJikRpJOiSa7BzuPNGJ0rilm5exPwq0T6j6sk/jDOokvrI/40111Eu71+1VYrK6uRkZGRqtjGRkZ8Hq9qK+vR1ZWVofnVFdXd3jdxx9/HIsXL25zfOXKldDpdNEpfCdWrVrV6fPLDsoAyDBAY8Pnn38eOp6hlKEJMvxn1XqUZ4gxLmX/crI6oe7HOok/rJP4wvqIP7GuE7s9vEmu/SosAm23tBFFsc3x9s7pbCuc+fPn45577gk9Du61OG3atJhv97dq1SpMnTq10+2A/vTMOgAO3HjRBJw3OC10fLfiAPauK4GQUoAZM4bHrJz9Sbh1Qt2HdRJ/WCfxhfURf7qrToI9oSfTr8JiZmZmmxbC2tpaKBQKpKSkdHrOia2Nx1Or1VCr1W2OK5XKbvnB6+x9qlocONrkgEwAzhiQ1uq80XlJAEqwp9rKXxBR1l11T+FjncQf1kl8YX3En1jXSbjX7lezGiZNmtSmSXflypU47bTTQt+wjs6ZPHlyt5Uzmr4vaQQAjMg2waBp/T/FoAxp95bDddZQCysRERHR8Xp1WLRardi+fTu2b98OQFoaZ/v27Thy5AgAqXv4pptuCp3/61//GmVlZbjnnnuwZ88eLF26FK+88gruvffe0Dl33XUXVq5ciSeffBJ79+7Fk08+idWrV2Pu3Lnd+dGi5rtAWDyjKLnNc/nJOggCYHF6UW91d3fRiIiIqBfo1WFx8+bNGDduHMaNGwcAuOeeezBu3DgsXLgQAFBVVRUKjgBQVFSE5cuX4+uvv8bYsWPxyCOP4C9/+Uto2RwAmDx5Mt5++228+uqrGD16NF577TW88847OOOMM7r3w0VJsGVxYjthUaOUIzdJC0BqXSQiIiI6Ua8eszhlypROu09fe+21NsfOO+88bN26tdPrzpo1C7NmzTrV4vU4q8uLQ4EQOC4/qd1zilMTcLTRgcP1NpxRnNKdxSMiIqJeoFe3LFLndlW0QBSBLJMGaYa2E3AAoChVDwAoqbd1Z9GIiIiol2BY7MN+qGgBAIzK6XjB7QFpUlhkNzQRERG1h2GxDwsnLBalBmdEs2WRiIiI2mJY7MN+KA+ExU628isOtCweabTD4/N3S7mIiIio92BY7KMsTg8OB8YhdtaymGnUQKWQwesXUd3i7K7iERERUS/BsNhH7a+RxiBmGNVISWh/cgsAyGQCsk0aAEB5k6NbykZERES9B8NiH3Ww1gIAGJxhOOm5OYG1FiuaGRaJiIioNYbFPupAoGVxUHoYYTExEBbZskhEREQnYFjsow7UBsJiYP/nzuQk6gAAFc32mJaJiIiIeh+GxT7qYDAspocRFgPd0JXNnOBCRERErTEs9kFWlzc0/nBgOGExkWMWiYiIqH0Mi33QoUCrYppBjUSd6qTn5x43wcXv73ivbSIiIup/GBb7oOB4xYFpJ29VBIBMkwYyAXB7/ai3uWJZNCIiIuplGBb7oLIGaTHu4O4sJ6OUy5BhlNZa5IxoIiIiOh7DYh9U2iDNai5I0YX9muC4RU5yISIiouMxLPZBwZbFgpTwWhYBICOwi0uNmWGRiIiIjmFY7IPKAi2LhZGERQPDIhEREbXFsNjHNNvdaHF4AAD5yeF3Q2eapP2jqxkWiYiI6DgMi31McLxihlENrUoe9uuCE1zYskhERETHY1jsY0LjFZPD74IGjg+LXDqHiIiIjlF05UX79u3D888/jz179kAQBAwdOhR33nknhgwZEu3yUYTKujATGgAyA2GxusUJURQhCELUy0ZERES9T8Qti++99x5GjhyJLVu2YMyYMRg9ejS2bt2KkSNH4t13341FGSkCXQ2LwZZFh8cHi8sb9XIRERFR7xRxy+K8efMwf/58PPzww62OP/TQQ/j973+Pn/70p1ErHEWuolkKi7lJkYVFrUoOo0YBs9OLmhYnjBplLIpHREREvUzELYvV1dW46aab2hy/4YYbUF1dHZVCReqFF15AUVERNBoNJkyYgHXr1nV47s033wxBENrcRowYETrntddea/ccpzP+J39UtUhlzA4ssh2JzMBai5wRTUREREERh8UpU6a0G8a+/fZbnHPOOVEpVCTeeecdzJ07Fw888AC2bduGc845B9OnT8eRI0faPf+5555DVVVV6Hb06FEkJye3aRE1Go2tzquqqoJGo+mOj9Rlfr+IqsAOLFmmyMvKSS5ERER0ooi7oa+44gr8/ve/x5YtW3DmmWcCADZu3Ih3330Xixcvxscff9zq3Fh75pln8Mtf/hK33norAGDJkiVYsWIF/v73v+Pxxx9vc77JZILJZAo9/uijj9DU1IRbbrml1XmCICAzMzO2hY+yBpsbbp8fgnCslTASmVw+h4iIiE4QcVicM2cOAKnr94UXXmj3OUAKWz6f7xSL1zm3240tW7bg/vvvb3V82rRpWL9+fVjXeOWVV3DRRRehoKCg1XGr1YqCggL4fD6MHTsWjzzyCMaNG9fuNVwuF1yuY61xZrMZAODxeODxeCL5SBEJXjv49Ui9BQCQblADfh88/si+/6kJ0jjFyiZ7TMvdl51YJ9TzWCfxh3USX1gf8ae76iTc60ccFv1+f8SFiZX6+nr4fD5kZGS0Op6RkRHW+Mmqqip8/vnnWLZsWavjQ4cOxWuvvYZRo0bBbDbjueeew1lnnYUdO3Zg0KBBba7z+OOPY/HixW2Or1y5EjpdZBNNumLVqlUAgB0NAgA5tH4nli9fHvF16qul1+88UIbly0uiW8h+JlgnFD9YJ/GHdRJfWB/xJ9Z1YrfbwzqvS+ssxpsT1wQMd53A1157DYmJiZg5c2ar42eeeWaoix0AzjrrLIwfPx7PP/88/vKXv7S5zvz583HPPfeEHpvNZuTl5WHatGkwGo0RfprweTwerFq1ClOnToVSqUTN+jJg/z4ML8zEjBljIr6eek8t3i3ZDkGXiBkzzjz5C6iNE+uEeh7rJP6wTuIL6yP+dFedBHtCTybssPjll1/it7/9LTZu3NgmALW0tGDy5Mn4+9//jnPPPTeykp6C1NRUyOXyNq2ItbW1bVobTySKIpYuXYobb7wRKpWq03NlMhlOP/10HDhwoN3n1Wo11Gp1m+NKpbJbfvCC71NrcQMAcpJ0XXrf7MCuLzUWF39hnKLuqnsKH+sk/rBO4gvrI/7Euk7CvXbYs6GXLFmCX/3qV+22lJlMJtx+++149tlnwy9hFKhUKkyYMKFNM+2qVaswefLkTl+7du1aHDx4EL/85S9P+j6iKGL79u3Iyso6pfLGWmWLA0DXls0Bjk1wqbO44POLUSsXERER9V5hh8UdO3bgkksu6fD5adOmYcuWLVEpVCTuuecevPzyy1i6dCn27NmDu+++G0eOHMGvf/1rAFIXcXvrQr7yyis444wzMHLkyDbPLV68GCtWrMDhw4exfft2/PKXv8T27dtD14xXlaFlc7oWFlMS1JDLBPhFoN7K5XOIiIgogm7ompqaTpsrFQoF6urqolKoSPzsZz9DQ0MDHn74YVRVVWHkyJFYvnx5aHZzVVVVmzUXW1pa8P777+O5555r95rNzc247bbbUF1dDZPJhHHjxuGbb77BxIkTY/55TkVVqGWxa+tBymUC0hLUqDY7Ud3iDK27SERERP1X2GExJycHP/zwAwYOHNju8zt37uyxbto5c+a0WrbneK+99lqbYyaTqdMZQM8++2y3d6mfKp9fRL1VGrOYeQohL8OkQbXZybUWiYiICEAE3dAzZszAwoUL293yzuFw4KGHHsJll10W1cJR+Jrsbvj8IgQBSNZ3PmGnM5lGaaIOwyIREREBEbQs/uEPf8AHH3yAwYMH47e//S2GDBkCQRCwZ88e/O1vf4PP58MDDzwQy7JSJ2oDW/Sl6FVQyCPexTGEW/4RERHR8cIOixkZGVi/fj3uuOMOzJ8/H6IozZYVBAEXX3wxXnjhhZMuVwMA+/btw1tvvYV169ahtLQUdrsdaWlpGDduHC6++GJcffXV7S5DQ52rC0xISU04te9dMCxWs2WRiIiIEOGi3AUFBVi+fDmamppw8OBBiKKIQYMGISkp6aSv3bZtG+bNm4d169Zh8uTJmDhxImbOnAmtVovGxkb8+OOPeOCBB3DnnXdi3rx5mDt3LkNjBOosUlhMP8VJKRncH5qIiIiO06UdXJKSknD66adH9JqZM2fivvvuwzvvvIPk5OQOz9uwYQOeffZZ/PnPf8aCBQu6Urx+KRgW006xZTGTYZGIiIiOE1ZYvOqqq8K+4AcffNDu8QMHDpx0pxQAmDRpEiZNmgS32x32exJQa5HCXZrhVLuhpddXtzAsEhERUZizoU0mU+hmNBqxZs0abN68OfT8li1bsGbNGphMpg6v0VFQLC8vh9/vD/t8al+oZfFUw6JJalk0O71wuH2nXC4iIiLq3cJqWXz11VdD93//+9/jmmuuwYsvvgi5XA4A8Pl8mDNnTrtbAZ7M8OHDsX37dhQXF0f8WjomNGbxFMOiQa2AVimHw+NDjdmJwlR9NIpHREREvVTEa6wsXboU9957bygoAoBcLsc999yDpUuXRlyA4KxqOjXB2dCn2rIoCAIyTRy3SERERJKIw6LX68WePXvaHN+zZ0+73cnUPerM0QmLwLHWSS6fQ0RERBHPhr7lllvwi1/8AgcPHsSZZ54JANi4cSOeeOIJ3HLLLREXYMGCBZ3OjqaTc7h9sLi8AKITFrl8DhEREQVFHBb/9Kc/ITMzE88++yyqqqoAAFlZWZg3bx7+7//+L+ICzJ8/P+LXUGv1NqlVUaOUwaDu0mpIrRzrhuYuLkRERP1dxN3QMpkM8+bNQ0VFBZqbm9Hc3IyKigrMmzev1TjGEz3xxBOw2+1hvcd3332Hzz77LNKi9Vv1VmmZoRS9GoIgnPL12A1NREREQV3fRBiA0WgMewb07t27kZ+fjzvuuAOff/456urqQs95vV7s3LkTL7zwAiZPnoxrr722SzOr+6smuwcAkJIQneWGgi2LtQyLRERE/V5YfZbjxo0Lu8Vq69at7R5/4403sHPnTvztb3/D9ddfj5aWFsjlcqjV6lCL47hx43Dbbbdh9uzZ3OovAo02qWUxSRedsMj9oYmIiCgorLA4c+bMqLzZ6NGj8Y9//AMvvvgidu7cidLSUjgcDqSmpmLs2LFITU2Nyvv0N032YDd0lFoWjcfGLIqiGJWubSIiIuqdwgqLDz30UFTfVBAEjBkzBmPGjInqdfurRpvUDZ0cpbAYnFHt9vrRbPcgKUrXJSIiot4n7DGLS5cuhcvF2bHxKNQNHaVQp1HKQ62UlS2OqFyTiIiIeqeww+KvfvUrtLS0hB5nZ2ejtLQ0FmWiCEW7GxoAshO1AIDKZo5bJCIi6s/CDosnbstnsVi4Y0ucCHZDR7O7ODtRGrdY2cyWRSIiov7slJbOofgQ25ZFhkUiIqL+LOywKAhCq1mxJz6mnhOLlsWcYFhsYTc0ERFRfxb23nCiKGLw4MGhgGi1WjFu3DjIZK3zZmNjY3RLSJ3y+gFrYF9otiwSERFRtIUdFl999dVYluOUvPDCC3j66adRVVWFESNGYMmSJTjnnHPaPffrr7/G+eef3+b4nj17MHTo0NDj999/Hw8++CAOHTqEAQMG4NFHH8VPfvKTmH2GrrJJORFymQCjRhm16zIsEhERERBBWJw9e3Ysy9Fl77zzDubOnYsXXngBZ511Fv7xj39g+vTpoe0FO7Jv375WWwqmpaWF7m/YsAE/+9nP8Mgjj+AnP/kJPvzwQ1xzzTX49ttvccYZZ8T080TKKvVAI0mnhEwWvWEBwQkuNWYnPD4/lHIObyUiIuqPwg6LQcXFxdi0aRNSUlJaHW9ubsb48eNx+PDhqBUuHM888wx++ctf4tZbbwUALFmyBCtWrMDf//53PP744x2+Lj09HYmJie0+t2TJEkydOhXz588HAMyfPx9r167FkiVL8NZbb0X9M5wKq1cKiNFakDsoVa+GSi6D2+dHjdmJ3CRdVK9PRMeIogiz04t6qwsNVjfqrS5YnB64vH64vX64vH7IZQJ0KnloHdTcJB1yk7TQqyP+NU5EFJGIf8uUlpbC5/O1Oe5yuVBeXh6VQoXL7XZjy5YtuP/++1sdnzZtGtavX9/pa8eNGwen04nhw4fjD3/4Q6uu6Q0bNuDuu+9udf7FF1+MJUuWtHstl8vVasFys9kMAPB4PPB4PJF8pIh4PB4E5rYgUauM+ntlmtQ40ujAkXorMhKi18XdlwXrIJb1TpHp6Tpxe/2osThR2SzdKpodqGpxotbiQoPNjXqrGw02N9zeri1FlqJXYWC6HgPTEjAoXY+B6QkYmKZHsl4Vt5MQe7pOqDXWR/zprjoJ9/phh8WPP/44dH/FihUwmUyhxz6fD2vWrEFRUVEERTx19fX18Pl8yMjIaHU8IyMD1dXV7b4mKysLL730EiZMmACXy4V//etfuPDCC/H111/j3HPPBQBUV1dHdM3HH38cixcvbnN85cqV0Oli2yJn9Uj/GLjNDVi+fHlUr632ygDIsHztRtTtFk96Ph2zatWqni4CnSAWdSKKgN0LNLmBJpeA5sDXJhfQ6BLQ5AbMbkBEeKFNLRdhUAIGJaCVi1DJAEXg5hcBtw9w+QGLR0CjE7D7BDTY3GgoceO7kqZW19IrRGRqgVSNCJ0C0MhFqOWAUnbsJheO3VfIROlr4JhBCajkUf+WtRJPPyeiCDh8Un06vNL31hG47/ABDq8gPRc6R4DHD/hEaaKhV5RuvsAxEYAQuEE4dl8QAJUMUMuDX0Vo5MeOqeWAOnA8+Dj4nEYuQiUHNHJAG3guiqOP4qo+SBLrOrHb7WGdF3ZYnDlzJgBpyZwTxy8qlUoUFhbiz3/+c/gljKIT/3oWRbHDv6iHDBmCIUOGhB5PmjQJR48exZ/+9KdQWIz0mvPnz8c999wTemw2m5GXl4dp06a1GhcZbR6PB8uXrgEADB+Yjxkzhkf1+utcu3BgawWS8wdjxvkDonrtvsrj8WDVqlWYOnUqlEq2xsaDrtaJ3e3FkUYHai0u1FlcqLe6UWd1od4ifa2zuFBtdsLhOXmLoEohQ7ZJg+xEDbJNWmQnapBhUCMlQYXUBDVSE1RI0augUUaWzixOD0ob7DhYa8PBOisO1tpwoNaK8mYHbF4BhyzAIUvX04RRo0CmUYMMoxoZRg2yTRpkJWqQk6hBdqIWWUYNVIrIxzPH+ufE5xfR7PCg0eZGk92NJpsHTXYPmu1uNDuC9z1odkjHmuwemJ1e+Pzd80dx63+eTy3t6dVyJKgVSFArYNAEvqoVSNarkG5QI92oRoZBjYIUHXIStZC3ky75eyv+dFedBHtCTybssBjcraWoqAibNm1Campq10oWRampqZDL5W1a/Gpra9u0DHbmzDPPxJtvvhl6nJmZGdE11Wo11Gp1m+NKpTLmP3jBCS6pCZqov1dRWgIAoLzJyV8gEeqOuqfItFcndrcXpfV2lDbYpFu9DaUNdpTW21BrcXVwpbZSE1TICoTALJMWOYla5CRpkZ0o3U9NiE2XcLJSiWSDDuMLW/8+drh9OFRnxcFaK4402mF1eWFxemFzeeHy+lqNhXR5fXB5/HD7/HB5pMd2t3SO2emF2WnF/lpru+8vCEC6QR36nDlJWuQmapGSoEaiTokknQpJOhUSdcp2g3B7dSKKIlxeP6wuqbxWlxdWpxc2txdWl0865vS2er7R5pZudjeabFIgFLuY+zRKGUxaJUxaJYyawNfQYwWMgcdGjQJalQJKuQC1QgalXAZV8OtxEwJFEfCLIsTAZ/OLIhxuP2xuL+xuL2yBz2Rz+2APfJUee2F3+WBzS5/T7pbuBz+7xyd9QOn1PtTg5P+/qhUyFKclYFB6AoZkGjA4w4DBGQnIDAwz6s2/t4L/3zjcPtg9Pjjc0vfM7vZJx9w+2N1eODy+4457Wz/vaX3M5fVDJgNkggC5IEAQpPsyQYBMJkAhE6CUC63qPvRYHnisOOFx4Firx3LhuNdLj2Xwo9QCNDn9yNHFrk7Cre+IxyyWlJR0+FxFRQVycnIivWSXqVQqTJgwAatWrWq1rM2qVatw5ZVXhn2dbdu2ISsrK/R40qRJWLVqVatxiytXrsTkyZOjU/AoCi6dE+0JLgBQkCJ1oZc1htdMTT3L6/OjqsWJo412HDnudrTRDrPTC5fHFwoEPlGEKAIixNA/qmLgP4Ig/aOiUcqhVsqgUUhftUo5tCoFdEo5dCo5tKrgVwV0wftKOXSBf0CVchkUga9KuQCF7Nhj6ZfsscfB10Y7UHl9flSbnSizAqt21+JosxOlDTaU1NtQWm9HtbnzRedNWiWyE7VIM6iRlqCWvgZvCWpkmTTINGkibhGMNa1KjpE5JozMMZ385HaIogiLy4uaFieqWpyoNjtR3eJEZbMDFcFbkwMurx81ZhdqzC5sO9Lc6TVVChnUCukfTYVcgNclx1N7voHXL8LjE+Hx+QM3MWotfCatEil6FZL0KiTplEjUHf/1uPt6KdiatO2H2njk9PhCfwRYnV5YXJ5j950eNNjcqDE7UWN2obrFiZIGG1xeP/ZUmbGnygzsOHYtrVKGFJUc/23chnSjBglqBeQyKRAJALx+EV6fCJ/fD49fhM8nwuP3wxc47g3cDwZYZejnPhiiT3gcfF5x7LFCLoPXF/wDxg+Xx3fsvtd3QvALBDpP62Pd1DDcjRTwp5fj7mlDT35qzEsSBdXV1Xj00Ufx8ssvw+Ho3nX57rnnHtx444047bTTMGnSJLz00ks4cuQIfv3rXwOQuogrKirwxhtvAJBmOhcWFmLEiBFwu91488038f777+P9998PXfOuu+7CueeeiyeffBJXXnkl/vvf/2L16tX49ttvu/WzhSO0dE4swmKyHgBQ1sCwGA88gZnp1YF/wCuaHaEweKTRjoomB7xR+m0ZbFXqToIA6FUK6NVy6APdasc/Dh5TyAT4RBF+vwifH/D6j7VC2Vy+0P0muwcNNlcgDCuAH7a3+75JOiUKU/UoStGjIEWPwlQdClP0KEjRIVEX/Z+r3kAQpHVbjRolBmUY2j1HFEU02NxSgGySAmR5kwOVzY5Q929LoMvX5xfhDrRmHvcugKvzsK5XHff/gloR6HJVIuG4/0cS1Aok6VVIPu4WDIKKPrzkl0YpzYxPTWjbq9Uen1/E0UY7DtZasb/WggM1VuyvseBArRUOjx/lHgHl++piXOruoZLLjvtjVvqqUyraHlMpAn/gtv7DV6uSQ6eUQ62Uh1qD/SLg9we+itIfND6/CHfojxw/PN4THvuk/+9bPfb54fGe8Lid17s8PjSZrUhJiI/fQWGHxebmZvzmN7/BypUroVQqcf/99+O3v/0tFi1ahD/96U8YMWIEli5dGsuytutnP/sZGhoa8PDDD6OqqgojR47E8uXLUVBQAACoqqrCkSNHQue73W7ce++9qKiogFarxYgRI/DZZ59hxowZoXMmT56Mt99+G3/4wx/w4IMPYsCAAXjnnXfibo1FALAFJrik6MP7hRGJ/EDLYr3VBZvLyyU6uoHD7cPBWiv21VhwoMaCknobqs1SOKy3uk7ataaSy5CbrEV+sg4FyTrkBW4pelWgZUcOlUIW6lIBpJAWbNETIP0idHn9cAb+snd6pG7KY3/FH9e94znur/zj/vJ3+/zw+v3wBlqMgi0Twfsenz/UIhFsjRBFaTciaUei8LuAT0YuE5Cg8KMgzYSC1AQUpehQlKZHYYoeRan6fhsIT5UgCIHxlmqMzk3s8LxgK2WL3RP6B9LhcuPrdd/irMmToVWrWnffKaSWZr1KEdW1Y/s7uUxAYaoehal6XDT82JAqr8+Pw7Vm/OeLb1AwZBSaHFIXePCPMRFiqDdAIRMgD/QQKGRSa6D09dhzwWt6/OJxocgPd7D12HvC4+DzXhEqhQC1Qg51oBVarZRDJZfua4/vzVAe15sRCH3Hh7y+8EeCx+PB8uXLMeP0vJ4uCoAIwuKCBQvwzTffYPbs2fjiiy9w991344svvoDT6cTnn3+O8847L5bl7NScOXMwZ86cdp977bXXWj2eN28e5s2bd9Jrzpo1C7NmzYpG8WLKGsNuaJNWiSSdEk12D8oa7BieHbvJOv2N0+PD4Tob9tdYAjfpr/yjTfZOA6FKLkNmoOsz26RBfiAM5ifrkJ+iQ4ZB0+v+gfX7RTi9wRbBwHgtV+sxasFWQ5vbC69PhDwwjkgmE6CUCdCFWh6lkJGgVsCkUyLdoIFBJWDFF59jxowze+14rN7s+FbKII/HgzIDMDYvkXXSwxRyGYpS9RiVLGLG6bmsD2pX2GHxs88+w6uvvoqLLroIc+bMwcCBAzF48OAO1x6k2PP7xdA6i7EIiwCQn6JHk70ZRxptDItd4PL6UNZglwJh9bFQWNpg63B8TYpehUEZCRiSYcCA9ARkmbTIMmmQZdLE9dp5XSWTCYGWAQXQfo/nKeHacUREpybssFhZWYnhw6WlWYqLi6HRaEK7plDPMDu98AeWXUjSx+avwcIUHXYcbea4xZPw+UWU1Nuw82gjPi2T4cN/bUVJgzSesKNQaNIqMTgjAYMyDBiSYcCgjAQMzjCEPQaJiIioO0S0dM7xzdNyuRx6vT4mhaLw1AWW9jBpFVArYjODryBZGrdY2mCLyfV7I5fXhwM1VuyqbMGuSjN2VUqzC+3u4M5GMgD1ofMT1AopCKZLgTC4ZEW6Qd3nWgmJiKjvCTssiqKIm2++ObSeoNPpxK9//es2gfGDDz6IbgmpQ7VWKSymG2LXEjUgXVpr8VBt/IVFn19EeZMdh+ttKKu3oSEwA9Ph9ofGtKkUMiTpVEhJkGZJpuilRWrTDWokqBWdhjVRFFHV4sSBWmm9ur1VUjA8UGsJTco4nlYpx9DMBOjdTZg6cQQGZ5owIE2PNIZCIiLqxcIOiyfu2nLDDTdEvTAUmVqzFBbTYhgWBwbC4v5aS6e72HQHn1/Ed4cbsO5gPb4vacQP5S1w+7q2ny4ghbtgcAyO+fT5AbPTg3qrCzUtTtjcbfdBB6Qu5BHZRozMMWFEthEjso0oSk2A3+eVZrBNzONAcSIi6hPCDouvvvpqLMtBXRDcYSIjli2LaQkQBKDZLi3y2hPj6cxOD5Z+W4J3Nh1FVUvrddnUCmkmX0GKDmkGNZJ1KmhVCmnHBFGE0+NHo92NRqu0w0O91YVaiwtWl7SSf1mDvdPxmIrAchOD0qVdD0YEwmFOorbd4OxvP1sSERH1Wlw4r5dyenz406oDAGLbsqhRypGfrENZgx0HaqzdHhY/3VmJhf/dhUabG4DUonfRsAycWZyM0wuTkZ+s69JSMXa3F7VmF2rMTtRaXGi2uyEIgrQmn1qB1ASpuzo/WQdlH1izi4iIqKsYFnupFbuO7V0dy7AIAIPSE6SwWGvBpAEpMX2vII/Pj0Uf78K/v5MWVB+QpsddFw3GxSMyojKZR6dSoDBVgcJUTtIiIiLqDMNiL5WXrMO04enYU1aDi49bjT8WBqYbsHpPLQ7UWGP6PkEWpwdz/r0V6w7UQxCAO88fiDsvHMQWvv9v797joqrW/4F/BhgGUC4hwoAKDScUhBQQL4gKmGDqsfwdUyE1DMVM05BT3o/XhKOVoWIahpp5yetJPVJKCiihhgSmUJqGYQrhnZtym/37g8N8nYZRVGDPyOf9es0frL32Ws+eJe6Htfdem4iISARMFvWUt+NzWBPqicTERNhbmjRpXy7/e8jl16KSJu0HqJ1RrEsUzYwNsTLEC0FNnAwTERGRdkwW6ZE62tW+VuN8YdM+ES0IAubsPatKFLdF9IJnB6sm6YuIiIgahtf16JFc7FrDyECC2+VVuHrnXpP1s/roRezK/AMGEmDN695MFImIiHQAk0V6JBOpoWp28dzVu03Sx94f/8CKpAsAgMWveiDQ1bZJ+iEiIqLHw2SRGuTFdpYAgHNXixu97fSLNzBzz08AgLf8nTGml1Oj90FERERPhskiNYhH+9pk8Wwjzyxe+LMEb23JRFWNgL93scfMga6N2j4RERE9HSaL1CAeDhYAai9DC4Lme5GfRFHxfby5MQMl96vR/fnn8NGIrk+0wDYRERE1HSaL1CBu9hYwNJDgZlklrv3llXtPoqyiGuFfZODqnXtwtmmF+LE+MJE+/WLbRERE1LiYLFKDmEgN4f6/2cXTl289VVvVNUpM3Z6Fc1eL0aaVMTa+2R3PtTJujDCJiIiokTFZpAbr8bw1AOBU3pMni4Ig4F/7cnD0lyLIjAywPswHTm34yj0iIiJdxWSRGqyHojZZ/OEpksWPDp/H9h/yYSABVoZ4wdvxucYKj4iIiJoAk0VqsLpk8WJRKW6UVjz2/p8f/w1rki8BAJb+vxfxsoe8UeMjIiKixsdkkRrMyswYrvLaxbkfd3Zxd+Yf+ODgzwCAGS93QmgPx0aPj4iIiBofk0V6LL5/awMASDlf1OB9vsv9U7XodkRfBd72/1uTxEZERESNj8kiPZaXXO0AAEd/uQ6l8tHrLWb+fgtTtv2IGqWA4d7tMWewGyQSrqVIRESkL56JZPHTTz+FQqGAiYkJunXrhuPHj2utu3fvXgQFBaFt27awsLCAr68vDh06pFZn06ZNkEgkGp/7959+fUF910NhDXOZEW6UVuDMH3ceWvdiUQnGf3EaFdVKBHZqi38Pf5GJIhERkZ7R+2Rxx44diIyMxNy5c5GVlYW+ffti0KBByM/Pr7f+sWPHEBQUhMTERGRmZiIwMBBDhw5FVlaWWj0LCwsUFBSofUxMTJrjkHSasZEB+nVsCwA48rP2S9E3SysQtiEDd8qr0LWDFdaM9obUUO//uREREbU4en/2XrFiBcaPH48JEybAzc0NsbGx6NChA9auXVtv/djYWMyYMQPdu3eHi4sLoqOj4eLiggMHDqjVk0gkkMvlah+qFexeeyn6P1lXUVPPpejKaiXe3vojrt65B6c2ZtgQ5gMzY6PmDpOIiIgagV6fwSsrK5GZmYlZs2aplQcHByM9Pb1BbSiVSpSUlMDa2lqtvLS0FE5OTqipqYGnpyeWLFkCLy+vetuoqKhARcX/LSVTXFwMAKiqqkJVVdXjHNJjqWu7Kfuoz0sd28DKVIqrd+7hu9wC9O/UVm37/P25+CHvFlrJDLHudU9YyAyaPUaxiDUmpB3HRPdwTHQLx0P3NNeYNLR9vU4Wb9y4gZqaGtjZ2amV29nZobCwsEFtfPzxxygrK8PIkSNVZa6urti0aRNefPFFFBcXY+XKlfDz88OZM2fg4uKi0UZMTAwWLVqkUX748GGYmZk95lE9vqSkpCbv46+8rAyQfM8Asf/NxP1LSlV5WqEEu/IMIYGA0YpKXDh9DBeaPTrxiTEm9HAcE93DMdEtHA/d09RjUl5e3qB6ep0s1vnrQxOCIDToQYrt27dj4cKF2LdvH2xtbVXlvXr1Qq9evVQ/+/n5wdvbG6tXr8aqVas02pk9ezaioqJUPxcXF6NDhw4IDg6GhYXFkxxSg1RVVSEpKQlBQUGQSqVN1k993G+WI3VlGn6+YwBzFx/0dbHBvuxr2HsqB4CAfwZ1xFv9FM0aky4Qc0yofhwT3cMx0S0cD93TXGNSdyX0UfQ6WbSxsYGhoaHGLGJRUZHGbONf7dixA+PHj8euXbswYMCAh9Y1MDBA9+7d8euvv9a7XSaTQSaTaZRLpdJm+cVrrn4e9ILcEmN7OeGLE79j2o6f0FNhjaPniyAIwCifDpjS36VFP/ksxpjQw3FMdA/HRLdwPHRPU49JQ9vW6wdcjI2N0a1bN41p2qSkJPTu3Vvrftu3b8e4ceOwbds2DBky5JH9CIKA7Oxs2NvbP3XMz5LZg93QQ2GN0opqHPmlNlF80+95xPyDS+QQERE9K/R6ZhEAoqKiMHbsWPj4+MDX1xfx8fHIz8/HpEmTANReIr569So2b94MoDZRfOONN7By5Ur06tVLNStpamoKS0tLAMCiRYvQq1cvuLi4oLi4GKtWrUJ2djbWrFkjzkHqKBOpIbZN6ImDZwvwx+176P23NvByfE7ssIiIiKgR6X2yOGrUKNy8eROLFy9GQUEBPDw8kJiYCCcnJwBAQUGB2pqLn332GaqrqzFlyhRMmTJFVR4WFoZNmzYBAO7cuYOJEyeisLAQlpaW8PLywrFjx9CjR49mPTZ9YGRogFc924kdBhERETURvU8WAWDy5MmYPHlyvdvqEsA6KSkpj2zvk08+wSeffNIIkRERERHpN72+Z5GIiIiImtYzMbOoawSh9q0mDX0k/UlVVVWhvLwcxcXFfIJNR3BMdA/HRPdwTHQLx0P3NNeY1OUpdXmLNkwWm0BJSQkAoEOHDiJHQkRERPRwJSUlqod86yMRHpVO0mNTKpW4du0azM3Nm3QJmbrFv69cudKki39Tw3FMdA/HRPdwTHQLx0P3NNeYCIKAkpISODg4wMBA+52JnFlsAgYGBmjfvn2z9WdhYcFfcB3DMdE9HBPdwzHRLRwP3dMcY/KwGcU6fMCFiIiIiLRiskhEREREWjFZ1GMymQwLFiyo973UJA6Oie7hmOgejolu4XjoHl0bEz7gQkRERERacWaRiIiIiLRiskhEREREWjFZJCIiIiKtmCwSERERkVZMFvXUp59+CoVCARMTE3Tr1g3Hjx8XO6QWKyYmBt27d4e5uTlsbW0xbNgwnD9/Xuyw6AExMTGQSCSIjIwUO5QW7erVqxgzZgzatGkDMzMzeHp6IjMzU+ywWqzq6mrMmzcPCoUCpqamcHZ2xuLFi6FUKsUOrcU4duwYhg4dCgcHB0gkEnz99ddq2wVBwMKFC+Hg4ABTU1MEBAQgJyen2eNksqiHduzYgcjISMydOxdZWVno27cvBg0ahPz8fLFDa5FSU1MxZcoUnDx5EklJSaiurkZwcDDKysrEDo0AZGRkID4+Hl26dBE7lBbt9u3b8PPzg1QqxTfffIPc3Fx8/PHHsLKyEju0FmvZsmVYt24d4uLi8PPPP2P58uX48MMPsXr1arFDazHKysrQtWtXxMXF1bt9+fLlWLFiBeLi4pCRkQG5XI6goCCUlJQ0a5xcOkcP9ezZE97e3li7dq2qzM3NDcOGDUNMTIyIkREAXL9+Hba2tkhNTUW/fv3EDqdFKy0thbe3Nz799FN88MEH8PT0RGxsrNhhtUizZs3C999/z6sgOuTvf/877OzskJCQoCobPnw4zMzM8OWXX4oYWcskkUjwn//8B8OGDQNQO6vo4OCAyMhIzJw5EwBQUVEBOzs7LFu2DG+99VazxcaZRT1TWVmJzMxMBAcHq5UHBwcjPT1dpKjoQXfv3gUAWFtbixwJTZkyBUOGDMGAAQPEDqXF279/P3x8fDBixAjY2trCy8sL69evFzusFq1Pnz44cuQILly4AAA4c+YM0tLSMHjwYJEjIwDIy8tDYWGh2vleJpPB39+/2c/3Rs3aGz21GzduoKamBnZ2dmrldnZ2KCwsFCkqqiMIAqKiotCnTx94eHiIHU6L9tVXX+HHH39ERkaG2KEQgN9++w1r165FVFQU5syZgx9++AHTpk2DTCbDG2+8IXZ4LdLMmTNx9+5duLq6wtDQEDU1NVi6dClCQ0PFDo0A1Tm9vvP977//3qyxMFnUUxKJRO1nQRA0yqj5vfPOO/jpp5+QlpYmdigt2pUrV/Duu+/i8OHDMDExETscAqBUKuHj44Po6GgAgJeXF3JycrB27VomiyLZsWMHtmzZgm3btsHd3R3Z2dmIjIyEg4MDwsLCxA6P/kcXzvdMFvWMjY0NDA0NNWYRi4qKNP76oOY1depU7N+/H8eOHUP79u3FDqdFy8zMRFFREbp166Yqq6mpwbFjxxAXF4eKigoYGhqKGGHLY29vj86dO6uVubm5Yc+ePSJFRO+//z5mzZqFkJAQAMCLL76I33//HTExMUwWdYBcLgdQO8Nob2+vKhfjfM97FvWMsbExunXrhqSkJLXypKQk9O7dW6SoWjZBEPDOO+9g7969OHr0KBQKhdghtXgvvfQSzp49i+zsbNXHx8cHo0ePRnZ2NhNFEfj5+WksKXXhwgU4OTmJFBGVl5fDwEA9DTA0NOTSOTpCoVBALperne8rKyuRmpra7Od7zizqoaioKIwdOxY+Pj7w9fVFfHw88vPzMWnSJLFDa5GmTJmCbdu2Yd++fTA3N1fN+lpaWsLU1FTk6Fomc3NzjXtGW7VqhTZt2vBeUpFMnz4dvXv3RnR0NEaOHIkffvgB8fHxiI+PFzu0Fmvo0KFYunQpHB0d4e7ujqysLKxYsQLh4eFih9ZilJaW4uLFi6qf8/LykJ2dDWtrazg6OiIyMhLR0dFwcXGBi4sLoqOjYWZmhtdff715AxVIL61Zs0ZwcnISjI2NBW9vbyE1NVXskFosAPV+Nm7cKHZo9AB/f3/h3XffFTuMFu3AgQOCh4eHIJPJBFdXVyE+Pl7skFq04uJi4d133xUcHR0FExMTwdnZWZg7d65QUVEhdmgtRnJycr3nj7CwMEEQBEGpVAoLFiwQ5HK5IJPJhH79+glnz55t9ji5ziIRERERacV7FomIiIhIKyaLRERERKQVk0UiIiIi0orJIhERERFpxWSRiIiIiLTiOotEekqpVKKyslLsMIioCUmlUi4iT6JjskikhyorK5GXl8c3LRC1AFZWVpDL5c3+PmCiOkwWifSMIAgoKCiAoaEhOnTooPG6LiJ6NgiCgPLychQVFQGA2vuBiZoTk0UiPVNdXY3y8nI4ODjAzMxM7HCIqAnVvTK0qKgItra2vCRNouCUBJGeqampAQAYGxuLHAkRNYe6PwqrqqpEjoRaKiaLRHqK9y8RtQz8XSexMVkkIiIiIq2YLBIRkd4YN24chg0bJnYYjSYgIACRkZFih0H0UEwWiahZPHiSHzduHCQSicbn5Zdf1tgvOjoahoaG+Pe//92gfvbu3YuBAwfCxsYGEokE2dnZGnUCAgI0+g4JCXlou2fOnEFoaCg6dOgAU1NTuLm5YeXKlVrrX7x4Eebm5rCystLYlpqaim7dusHExATOzs5Yt27dI4/rwe/MyMgIjo6OePvtt3H79m0AwC+//AKJRIJTp06p7dezZ0/IZDKUl5eryiorK2FmZob4+Ph6x+HBz7hx4zRiWbhwITw9PTXK79y5A4lEgpSUFADA5cuXVfFevXpVrW5BQQGMjIwgkUhw+fLlRx5/nZUrV2LTpk0Nrt8QNTU1iImJgaurK0xNTWFtbY1evXph48aNjdpPffbu3YslS5Y0eT9ET4PJIhGJ4uWXX0ZBQYHaZ/v27Rr1Nm7ciBkzZmDDhg0NaresrAx+fn6PTC4jIiLU+v7ss88eWj8zMxNt27bFli1bkJOTg7lz52L27NmIi4vTqFtVVYXQ0FD07dtXY1teXh4GDx6Mvn37IisrC3PmzMG0adOwZ8+eRx5b3Xd2+fJlfP755zhw4AAmT54MAHB1dYW9vT2Sk5NV9UtLS5GVlQVbW1ukp6eryk+dOoV79+4hMDBQ7TuIjY2FhYWFWtnDEuKGcnBwwObNm9XKvvjiC7Rr1+6x27K0tKw3AX8aCxcuRGxsLJYsWYLc3FwkJycjIiJClYg3JWtra5ibmzd5P0RPg8kiEYlCJpNBLperfZ577jm1Oqmpqbh37x4WL16MsrIyHDt27JHtjh07FvPnz8eAAQMeWs/MzEytb0tLy4fWDw8Px6pVq+Dv7w9nZ2eMGTMGb775Jvbu3atRd968eXB1dcXIkSM1tq1btw6Ojo6IjY2Fm5sbJkyYgPDwcHz00UePPLa676x9+/YIDg7GqFGjcPjwYdX2gIAA1aweABw/fhwdO3bEK6+8olaekpKCdu3awcXFReM7kEgkj/W9NERYWJjGLN2mTZsQFhamVlZTU4Px48dDoVDA1NQUnTp10khW/3oZOiAgANOmTcOMGTNgbW0NuVyOhQsXqu1z9+5dTJw4Eba2trCwsED//v1x5swZ1fa6pHvEiBFQKBTo2rUrxo8fj6ioKFUdQRCwfPlyODs7w9TUFF27dsXu3btV21NSUiCRSHDo0CF4eXnB1NQU/fv3R1FREb755hu4ubnBwsICoaGharO8vAxN+oDJIpGeEwQB5ZXVonwEQWjSY0tISEBoaCikUilCQ0ORkJDQaG1v3boVNjY2cHd3x3vvvYeSkpLHbuPu3buwtrZWKzt69Ch27dqFNWvW1LvPiRMnEBwcrFY2cOBAnD59+rGWRvntt9/w7bffQiqVqsoCAwORlpaG6upqAEBycjICAgLg7++vNuOYnJyMwMDABvf1tF555RXcvn0baWlpAIC0tDTcunULQ4cOVaunVCrRvn177Ny5E7m5uZg/fz7mzJmDnTt3PrT9L774Aq1atcKpU6ewfPlyLF68GElJSQBqfz+GDBmCwsJCJCYmIjMzE97e3njppZdw69YtAIBcLsfRo0dx/fp1rX3MmzcPGzduxNq1a5GTk4Pp06djzJgxSE1NVau3cOFCxMXFIT09HVeuXMHIkSMRGxuLbdu24eDBg0hKSsLq1asf+zskEhMX5SbSc/eqatB5/iFR+s5dPBBmxk/238h///tftG7dWq1s5syZ+Ne//gUAKC4uxp49e1SXT8eMGQM/Pz+sXr0aFhYWTxX36NGjoVAoIJfLce7cOcyePRtnzpxRJRgNceLECezcuRMHDx5Uld28eRPjxo3Dli1btMZYWFgIOzs7tTI7OztUV1fjxo0bD31LR913VlNTg/v37wMAVqxYodoeEBCAsrIyZGRkwNfXFykpKXj//ffRr18/jB07FuXl5TAyMsLJkyfrvXzeVKRSKcaMGYMNGzagT58+2LBhA8aMGaOW6NbVW7RokepnhUKB9PR07Ny5s95Z2jpdunTBggULAAAuLi6Ii4vDkSNHEBQUhOTkZJw9exZFRUWQyWQAgI8++ghff/01du/ejYkTJ2LFihV47bXXIJfL4e7ujt69e+PVV1/FoEGDANTe2rBixQocPXoUvr6+AABnZ2ekpaXhs88+g7+/vyqWDz74AH5+fgCA8ePHY/bs2bh06RKcnZ0BAK+99hqSk5Mxc+bMp/1aiZoNZxaJSBSBgYHIzs5W+0yZMkW1fdu2bXB2dkbXrl0BAJ6ennB2dsZXX30FoHZmsHXr1qrP8ePHG9x3REQEBgwYAA8PD4SEhGD37t347rvv8OOPPwIABg0apGrX3d1dY/+cnBy8+uqrmD9/PoKCgtTaff3119GvX7+H9v/XdfPqZmglEgmOHz+udlxbt27V+M5OnTqFqVOnYuDAgZg6dapqu4uLC9q3b4+UlBQUFxcjKysL/v7+sLOzg0KhwPfff4+TJ0/i3r176N+/f4O+qwdjmTRpUoP2qc/48eOxa9cuFBYWYteuXQgPD6+33rp16+Dj44O2bduidevWWL9+PfLz8x/adpcuXdR+tre3V70iLzMzE6WlpWjTpo3aseTl5eHSpUsAgM6dO+PcuXM4efIk3nzzTfz5558YOnQoJkyYAADIzc3F/fv3ERQUpNbG5s2bVW3UF4udnR3MzMxUiWJdWV1sRPqCM4tEes5UaojcxQNF6/tJtWrVCi+88ILW7Rs2bEBOTg6MjP7vvymlUomEhARMnDgRr7zyCnr27Kna9iQPS9Tx9vaGVCrFr7/+Cm9vb3z++ee4d+8eAGjMfuXm5qJ///6IiIjAvHnz1LYdPXoU+/fvV91/KAgClEoljIyMEB8fj/DwcMjlchQWFqrtV1RUBCMjI7Rp0waWlpZqT3A/OAv54He2atUqBAYGYtGiRWpP0wYEBCA5ORldunSBi4sLbG1tAUB1KVomk8HJyQnPP/98g76bB2Opmy21sLDA3bt3NereuXMHAOq9z9HDwwOurq4IDQ2Fm5sbPDw8NJ5U37lzJ6ZPn46PP/4Yvr6+MDc3x4cffqjxhPdf/XWMJBIJlEolgNp/M/b29mr3bNZ58EEZAwMDdO/eHd27d8f06dOxZcsWjB07FnPnzlW1dfDgQY1/Z3WzlfXFIpFIHhobkb5gskik5yQSyRNfCtZVZ8+exenTp5GSkqJ2T+CdO3fQr18/nDt3Dh4eHo32FGlOTg6qqqpUl4C1JZ45OTno378/wsLCsHTpUo3tJ06cUL2OEQD27duHZcuWIT09XdWmr68vDhw4oLbf4cOH4ePjA6lUCqlU+tAk+kELFizAoEGD8Pbbb8PBwQFA7ezjtGnT0LlzZwQEBKjq+vv7Iy4uDjKZrMGzigDqjcXV1RV//PEHCgsLIZfLVeUZGRkwMDDQGn94eDgmT56MtWvX1rv9+PHj6N27t+oJbwAaM3ePy9vbG4WFhTAyMmpwggzUzjYCtZegO3fuDJlMhvz8fLVLzkQtxbN1hiEivVFRUaExw2ZkZAQbGxskJCSgR48e9V7O9fX1RUJCAj755JN627116xby8/Nx7do1AMD58+cBQPV076VLl7B161YMHjwYNjY2yM3NxT//+U94eXmp7jWrT05ODgIDAxEcHIyoqChV7IaGhmjbti0AwM3NTW2f06dPw8DAAB4eHqqySZMmIS4uDlFRUYiIiMCJEyeQkJBQ77JBjxIQEAB3d3dER0er7kEMDAxEWVkZNmzYgPXr16vq+vv7Y9y4cTA0NNR6CbihgoOD4ebmhpCQECxduhQODg746aef8N5772HSpElak/iIiAiMGDFC69I3L7zwAjZv3oxDhw5BoVDgyy+/REZGBhQKxRPHOmDAAPj6+mLYsGFYtmwZOnXqhGvXriExMRHDhg2Dj48PXnvtNfj5+aF3796Qy+XIy8vD7Nmz0bFjR7i6usLIyAjvvfcepk+fDqVSiT59+qC4uBjp6elo3bq1xlPdRM8a3rNIRKL49ttvYW9vr/bp06cPKisrsWXLFgwfPrze/YYPH44tW7agsrKy3u379++Hl5cXhgwZAgAICQmBl5eXauFrY2NjHDlyBAMHDkSnTp0wbdo0BAcH47vvvoOhofbL6rt27cL169exdetWtZi7d+/+WMetUCiQmJiIlJQUeHp6YsmSJVi1apXW432UqKgorF+/HleuXFG17+TkhJKSErVZsHbt2sHR0RH3799/6iehjYyMcPjwYTg7O2P06NFwd3fHrFmzMGHCBLUHburbz8bGRu3WggdNmjQJ//jHPzBq1Cj07NkTN2/eVJtlfBISiQSJiYno168fwsPD0bFjR4SEhODy5cuqS/wDBw7EgQMHMHToUHTs2BFhYWFwdXXF4cOHVbEuWbIE8+fPR0xMDNzc3FT7PE0iS6QvJEJTr31BRI3q/v37yMvLg0KhgImJidjhEFET4+88iY0zi0RERESkFZNFIiIiItKKySIRERERacVkkYiIiIi0YrJIpKf4bBpRy8DfdRIbk0UiPVO3vIu2pWOI6NlSXl4OQPNNNUTNhYtyE+kZIyMjmJmZ4fr165BKpTAw4N98RM8iQRBQXl6OoqIiWFlZPXQdUKKmxHUWifRQZWUl8vLy+I5ZohbAysoKcrkcEolE7FCohWKySKSnlEolL0UTPeOkUilnFEl0TBaJiIiISCve7EREREREWjFZJCIiIiKtmCwSERERkVZMFomIiIhIKyaLRERERKQVk0UiIiIi0orJIhERERFp9f8Buc1bnbTL7OMAAAAASUVORK5CYII=\n", + "image/png": "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", "text/plain": [ "
" ] @@ -691,6 +702,7 @@ ] }, { + "attachments": {}, "cell_type": "markdown", "metadata": { "slideshow": { @@ -729,6 +741,7 @@ ] }, { + "attachments": {}, "cell_type": "markdown", "metadata": { "slideshow": { diff --git a/Examples/test_examples.py b/Examples/test_examples.py index c23b0804..5f45ec06 100644 --- a/Examples/test_examples.py +++ b/Examples/test_examples.py @@ -26,6 +26,7 @@ '21_optional_inputs', '22_cable_control', '23_structural_control', + '24_floating_feedback', 'update_rosco_discons', ] diff --git a/ROSCO/rosco_registry/rosco_types.yaml b/ROSCO/rosco_registry/rosco_types.yaml index 759c9d0a..0c4bfdeb 100644 --- a/ROSCO/rosco_registry/rosco_types.yaml +++ b/ROSCO/rosco_registry/rosco_types.yaml @@ -376,9 +376,17 @@ ControlParameters: Fl_Mode: <<: *integer description: Floating specific feedback mode {0 - no nacelle velocity feedback, 1 - nacelle velocity feedback} + Fl_n: + <<: *integer + description: Number of Fl_Kp for gain scheduling Fl_Kp: <<: *real description: Nacelle velocity proportional feedback gain [s] + allocatable: True + Fl_U: + <<: *real + description: Wind speeds for scheduling Fl_Kp [m/s] + allocatable: True # Trailing edge flaps Flp_Mode: @@ -494,30 +502,6 @@ ControlParameters: allocatable: True description: AWC clocking angle [deg] - # Active wake control - AWC_Mode: - <<: *integer - description: Active wake control mode [0 - unused, 1 - SNL method, 2 - NREL method] - AWC_NumModes: - <<: *integer - description: AWC- Number of modes to include [-] - AWC_n: - <<: *integer - allocatable: True - description: AWC azimuthal mode [-] - AWC_freq: - <<: *real - allocatable: True - description: AWC frequency [Hz] - AWC_amp: - <<: *real - allocatable: True - description: AWC amplitude [deg] - AWC_clockangle: - <<: *real - allocatable: True - description: AWC clocking angle [deg] - # Pitch actuator error PF_Mode: <<: *integer @@ -1017,6 +1001,9 @@ LocalVariables: TestType: <<: *real description: Test variable, no use + Kp_Float: + <<: *real + description: Local, instantaneous Kp_Float, scheduled on wind speed, if desired VS_MaxTq: <<: *real description: Maximum allowable generator torque [Nm]. diff --git a/ROSCO/src/Controllers.f90 b/ROSCO/src/Controllers.f90 index dde72431..28676dc4 100644 --- a/ROSCO/src/Controllers.f90 +++ b/ROSCO/src/Controllers.f90 @@ -84,7 +84,7 @@ SUBROUTINE PitchControl(avrSWAP, CntrPar, LocalVar, objInst, DebugVar, ErrVar) ! FloatingFeedback IF (CntrPar%Fl_Mode > 0) THEN - LocalVar%Fl_PitCom = FloatingFeedback(LocalVar, CntrPar, objInst) + LocalVar%Fl_PitCom = FloatingFeedback(LocalVar, CntrPar, objInst, ErrVar) DebugVar%FL_PitCom = LocalVar%Fl_PitCom LocalVar%PC_PitComT = LocalVar%PC_PitComT + LocalVar%Fl_PitCom ENDIF @@ -509,28 +509,33 @@ SUBROUTINE ForeAftDamping(CntrPar, LocalVar, objInst) END SUBROUTINE ForeAftDamping !------------------------------------------------------------------------------------------------------------------------------- - REAL(DbKi) FUNCTION FloatingFeedback(LocalVar, CntrPar, objInst) + REAL(DbKi) FUNCTION FloatingFeedback(LocalVar, CntrPar, objInst, ErrVar) ! FloatingFeedback defines a minimum blade pitch angle based on a lookup table provided by DISON.IN ! Fl_Mode = 0, No feedback ! Fl_Mode = 1, Proportional feedback of nacelle velocity (translational) ! Fl_Mode = 2, Proportional feedback of nacelle velocity (rotational) - USE ROSCO_Types, ONLY : LocalVariables, ControlParameters, ObjectInstances + USE ROSCO_Types, ONLY : LocalVariables, ControlParameters, ObjectInstances, ErrorVariables IMPLICIT NONE ! Inputs TYPE(ControlParameters), INTENT(IN) :: CntrPar TYPE(LocalVariables), INTENT(INOUT) :: LocalVar TYPE(ObjectInstances), INTENT(INOUT) :: objInst + TYPE(ErrorVariables), INTENT(INOUT) :: ErrVar ! Allocate Variables REAL(DbKi) :: FA_vel ! Tower fore-aft velocity [m/s] REAL(DbKi) :: NacIMU_FA_vel ! Tower fore-aft pitching velocity [rad/s] + + ! Gain scheduling + LocalVar%Kp_Float = interp1d(CntrPar%Fl_U,CntrPar%Fl_Kp,LocalVar%WE_Vw_F,ErrVar) ! Schedule based on WSE ! Calculate floating contribution to pitch command FA_vel = PIController(LocalVar%FA_AccF, 0.0_DbKi, 1.0_DbKi, -100.0_DbKi , 100.0_DbKi ,LocalVar%DT, 0.0_DbKi, LocalVar%piP, LocalVar%restart, objInst%instPI) ! NJA: should never reach saturation limits.... - NacIMU_FA_vel = PIController(LocalVar%NacIMU_FA_AccF, 0.0_DbKi, 1.0_DbKi, -100.0_DbKi , 100.0_DbKi ,LocalVar%DT, 0.0_DbKi, LocalVar%piP, LocalVar%restart, objInst%instPI) ! NJA: should never reach saturation limits.... + NacIMU_FA_vel = PIController(LocalVar%NacIMU_FA_AccF, 0.0_DbKi, 1.0_DbKi, -100.0_DbKi , 100.0_DbKi ,LocalVar%DT, 0.0_DbKi, LocalVar%piP, LocalVar%restart, objInst%instPI) ! NJA: should never reach saturation limits.... +! Mod made by A. Wright: use the gain scheduled value of KPfloat in the floating fb equ's below (instead of the old value of CntrPar%Fl_Kp), for either value of CntrPar%Fl_Mode... if (CntrPar%Fl_Mode == 1) THEN - FloatingFeedback = (0.0_DbKi - FA_vel) * CntrPar%Fl_Kp !* LocalVar%PC_KP/maxval(CntrPar%PC_GS_KP) + FloatingFeedback = (0.0_DbKi - FA_vel) * LocalVar%Kp_Float ! Mod made by A. Wright: use the gain scheduled value of KPfloat in the floating fb equ's below (instead of the old value of CntrPar%Fl_Kp), for either value of CntrPar%Fl_Mode... ELSEIF (CntrPar%Fl_Mode == 2) THEN - FloatingFeedback = (0.0_DbKi - NacIMU_FA_vel) * CntrPar%Fl_Kp !* LocalVar%PC_KP/maxval(CntrPar%PC_GS_KP) + FloatingFeedback = (0.0_DbKi - NacIMU_FA_vel) *LocalVar%Kp_Float ! Mod made by A. Wright: use the gain scheduled value of KPfloat in the floating fb equ's below (instead of the old value of CntrPar%Fl_Kp), for either value of CntrPar%Fl_Mode... END IF END FUNCTION FloatingFeedback diff --git a/ROSCO/src/ROSCO_IO.f90 b/ROSCO/src/ROSCO_IO.f90 index fc05e7b1..0d7a492e 100644 --- a/ROSCO/src/ROSCO_IO.f90 +++ b/ROSCO/src/ROSCO_IO.f90 @@ -110,6 +110,7 @@ SUBROUTINE WriteRestartFile(LocalVar, CntrPar, ErrVar, objInst, RootName, size_a WRITE( Un, IOSTAT=ErrStat) LocalVar%PitComAct(3) WRITE( Un, IOSTAT=ErrStat) LocalVar%SS_DelOmegaF WRITE( Un, IOSTAT=ErrStat) LocalVar%TestType + WRITE( Un, IOSTAT=ErrStat) LocalVar%Kp_Float WRITE( Un, IOSTAT=ErrStat) LocalVar%VS_MaxTq WRITE( Un, IOSTAT=ErrStat) LocalVar%VS_LastGenTrq WRITE( Un, IOSTAT=ErrStat) LocalVar%VS_LastGenPwr @@ -379,6 +380,7 @@ SUBROUTINE ReadRestartFile(avrSWAP, LocalVar, CntrPar, objInst, PerfData, RootNa READ( Un, IOSTAT=ErrStat) LocalVar%PitComAct(3) READ( Un, IOSTAT=ErrStat) LocalVar%SS_DelOmegaF READ( Un, IOSTAT=ErrStat) LocalVar%TestType + READ( Un, IOSTAT=ErrStat) LocalVar%Kp_Float READ( Un, IOSTAT=ErrStat) LocalVar%VS_MaxTq READ( Un, IOSTAT=ErrStat) LocalVar%VS_LastGenTrq READ( Un, IOSTAT=ErrStat) LocalVar%VS_LastGenPwr @@ -621,7 +623,7 @@ SUBROUTINE Debug(LocalVar, CntrPar, DebugVar, ErrVar, avrSWAP, RootName, size_av '[rad/s]', '[rad/s]', '[m/s]', '[rad]', '[rad]', & '[N/A]', '[N/A]', '[N/A]', '[N/A]', '[rad/s]', & '[deg]', '[deg]', '[deg]', '[N/A]'] - nLocalVars = 100 + nLocalVars = 101 Allocate(LocalVarOutData(nLocalVars)) Allocate(LocalVarOutStrings(nLocalVars)) LocalVarOutData(1) = LocalVar%iStatus @@ -681,49 +683,50 @@ SUBROUTINE Debug(LocalVar, CntrPar, DebugVar, ErrVar, avrSWAP, RootName, size_av LocalVarOutData(55) = LocalVar%PitComAct(1) LocalVarOutData(56) = LocalVar%SS_DelOmegaF LocalVarOutData(57) = LocalVar%TestType - LocalVarOutData(58) = LocalVar%VS_MaxTq - LocalVarOutData(59) = LocalVar%VS_LastGenTrq - LocalVarOutData(60) = LocalVar%VS_LastGenPwr - LocalVarOutData(61) = LocalVar%VS_MechGenPwr - LocalVarOutData(62) = LocalVar%VS_SpdErrAr - LocalVarOutData(63) = LocalVar%VS_SpdErrBr - LocalVarOutData(64) = LocalVar%VS_SpdErr - LocalVarOutData(65) = LocalVar%VS_State - LocalVarOutData(66) = LocalVar%VS_Rgn3Pitch - LocalVarOutData(67) = LocalVar%WE_Vw - LocalVarOutData(68) = LocalVar%WE_Vw_F - LocalVarOutData(69) = LocalVar%WE_VwI - LocalVarOutData(70) = LocalVar%WE_VwIdot - LocalVarOutData(71) = LocalVar%VS_LastGenTrqF - LocalVarOutData(72) = LocalVar%Fl_PitCom - LocalVarOutData(73) = LocalVar%NACIMU_FA_AccF - LocalVarOutData(74) = LocalVar%FA_AccF - LocalVarOutData(75) = LocalVar%PtfmTDX - LocalVarOutData(76) = LocalVar%PtfmTDY - LocalVarOutData(77) = LocalVar%PtfmTDZ - LocalVarOutData(78) = LocalVar%PtfmRDX - LocalVarOutData(79) = LocalVar%PtfmRDY - LocalVarOutData(80) = LocalVar%PtfmRDZ - LocalVarOutData(81) = LocalVar%PtfmTVX - LocalVarOutData(82) = LocalVar%PtfmTVY - LocalVarOutData(83) = LocalVar%PtfmTVZ - LocalVarOutData(84) = LocalVar%PtfmRVX - LocalVarOutData(85) = LocalVar%PtfmRVY - LocalVarOutData(86) = LocalVar%PtfmRVZ - LocalVarOutData(87) = LocalVar%PtfmTAX - LocalVarOutData(88) = LocalVar%PtfmTAY - LocalVarOutData(89) = LocalVar%PtfmTAZ - LocalVarOutData(90) = LocalVar%PtfmRAX - LocalVarOutData(91) = LocalVar%PtfmRAY - LocalVarOutData(92) = LocalVar%PtfmRAZ - LocalVarOutData(93) = LocalVar%CC_DesiredL(1) - LocalVarOutData(94) = LocalVar%CC_ActuatedL(1) - LocalVarOutData(95) = LocalVar%CC_ActuatedDL(1) - LocalVarOutData(96) = LocalVar%StC_Input(1) - LocalVarOutData(97) = LocalVar%Flp_Angle(1) - LocalVarOutData(98) = LocalVar%RootMyb_Last(1) - LocalVarOutData(99) = LocalVar%ACC_INFILE_SIZE - LocalVarOutData(100) = LocalVar%AWC_complexangle(1) + LocalVarOutData(58) = LocalVar%Kp_Float + LocalVarOutData(59) = LocalVar%VS_MaxTq + LocalVarOutData(60) = LocalVar%VS_LastGenTrq + LocalVarOutData(61) = LocalVar%VS_LastGenPwr + LocalVarOutData(62) = LocalVar%VS_MechGenPwr + LocalVarOutData(63) = LocalVar%VS_SpdErrAr + LocalVarOutData(64) = LocalVar%VS_SpdErrBr + LocalVarOutData(65) = LocalVar%VS_SpdErr + LocalVarOutData(66) = LocalVar%VS_State + LocalVarOutData(67) = LocalVar%VS_Rgn3Pitch + LocalVarOutData(68) = LocalVar%WE_Vw + LocalVarOutData(69) = LocalVar%WE_Vw_F + LocalVarOutData(70) = LocalVar%WE_VwI + LocalVarOutData(71) = LocalVar%WE_VwIdot + LocalVarOutData(72) = LocalVar%VS_LastGenTrqF + LocalVarOutData(73) = LocalVar%Fl_PitCom + LocalVarOutData(74) = LocalVar%NACIMU_FA_AccF + LocalVarOutData(75) = LocalVar%FA_AccF + LocalVarOutData(76) = LocalVar%PtfmTDX + LocalVarOutData(77) = LocalVar%PtfmTDY + LocalVarOutData(78) = LocalVar%PtfmTDZ + LocalVarOutData(79) = LocalVar%PtfmRDX + LocalVarOutData(80) = LocalVar%PtfmRDY + LocalVarOutData(81) = LocalVar%PtfmRDZ + LocalVarOutData(82) = LocalVar%PtfmTVX + LocalVarOutData(83) = LocalVar%PtfmTVY + LocalVarOutData(84) = LocalVar%PtfmTVZ + LocalVarOutData(85) = LocalVar%PtfmRVX + LocalVarOutData(86) = LocalVar%PtfmRVY + LocalVarOutData(87) = LocalVar%PtfmRVZ + LocalVarOutData(88) = LocalVar%PtfmTAX + LocalVarOutData(89) = LocalVar%PtfmTAY + LocalVarOutData(90) = LocalVar%PtfmTAZ + LocalVarOutData(91) = LocalVar%PtfmRAX + LocalVarOutData(92) = LocalVar%PtfmRAY + LocalVarOutData(93) = LocalVar%PtfmRAZ + LocalVarOutData(94) = LocalVar%CC_DesiredL(1) + LocalVarOutData(95) = LocalVar%CC_ActuatedL(1) + LocalVarOutData(96) = LocalVar%CC_ActuatedDL(1) + LocalVarOutData(97) = LocalVar%StC_Input(1) + LocalVarOutData(98) = LocalVar%Flp_Angle(1) + LocalVarOutData(99) = LocalVar%RootMyb_Last(1) + LocalVarOutData(100) = LocalVar%ACC_INFILE_SIZE + LocalVarOutData(101) = LocalVar%AWC_complexangle(1) LocalVarOutStrings = [CHARACTER(15) :: 'iStatus', 'Time', 'DT', 'VS_GenPwr', 'GenSpeed', & 'RotSpeed', 'NacHeading', 'NacVane', 'HorWindV', 'rootMOOP', & 'rootMOOPF', 'BlPitch', 'BlPitchCMeas', 'Azimuth', 'NumBl', & @@ -735,16 +738,16 @@ SUBROUTINE Debug(LocalVar, CntrPar, DebugVar, ErrVar, avrSWAP, RootName, size_av 'IPC_AxisYaw_1P', 'IPC_AxisTilt_2P', 'IPC_AxisYaw_2P', 'axisTilt_1P', 'axisYaw_1P', & 'axisYawF_1P', 'axisTilt_2P', 'axisYaw_2P', 'axisYawF_2P', 'IPC_KI', & 'IPC_KP', 'IPC_IntSat', 'PC_State', 'PitCom', 'PitComAct', & - 'SS_DelOmegaF', 'TestType', 'VS_MaxTq', 'VS_LastGenTrq', 'VS_LastGenPwr', & - 'VS_MechGenPwr', 'VS_SpdErrAr', 'VS_SpdErrBr', 'VS_SpdErr', 'VS_State', & - 'VS_Rgn3Pitch', 'WE_Vw', 'WE_Vw_F', 'WE_VwI', 'WE_VwIdot', & - 'VS_LastGenTrqF', 'Fl_PitCom', 'NACIMU_FA_AccF', 'FA_AccF', 'PtfmTDX', & - 'PtfmTDY', 'PtfmTDZ', 'PtfmRDX', 'PtfmRDY', 'PtfmRDZ', & - 'PtfmTVX', 'PtfmTVY', 'PtfmTVZ', 'PtfmRVX', 'PtfmRVY', & - 'PtfmRVZ', 'PtfmTAX', 'PtfmTAY', 'PtfmTAZ', 'PtfmRAX', & - 'PtfmRAY', 'PtfmRAZ', 'CC_DesiredL', 'CC_ActuatedL', 'CC_ActuatedDL', & - 'StC_Input', 'Flp_Angle', 'RootMyb_Last', 'ACC_INFILE_SIZE', 'AWC_complexangle' & - ] + 'SS_DelOmegaF', 'TestType', 'Kp_Float', 'VS_MaxTq', 'VS_LastGenTrq', & + 'VS_LastGenPwr', 'VS_MechGenPwr', 'VS_SpdErrAr', 'VS_SpdErrBr', 'VS_SpdErr', & + 'VS_State', 'VS_Rgn3Pitch', 'WE_Vw', 'WE_Vw_F', 'WE_VwI', & + 'WE_VwIdot', 'VS_LastGenTrqF', 'Fl_PitCom', 'NACIMU_FA_AccF', 'FA_AccF', & + 'PtfmTDX', 'PtfmTDY', 'PtfmTDZ', 'PtfmRDX', 'PtfmRDY', & + 'PtfmRDZ', 'PtfmTVX', 'PtfmTVY', 'PtfmTVZ', 'PtfmRVX', & + 'PtfmRVY', 'PtfmRVZ', 'PtfmTAX', 'PtfmTAY', 'PtfmTAZ', & + 'PtfmRAX', 'PtfmRAY', 'PtfmRAZ', 'CC_DesiredL', 'CC_ActuatedL', & + 'CC_ActuatedDL', 'StC_Input', 'Flp_Angle', 'RootMyb_Last', 'ACC_INFILE_SIZE', & + 'AWC_complexangle'] ! Initialize debug file IF ((LocalVar%iStatus == 0) .OR. (LocalVar%iStatus == -9)) THEN ! .TRUE. if we're on the first call to the DLL IF (CntrPar%LoggingLevel > 0) THEN @@ -759,8 +762,8 @@ SUBROUTINE Debug(LocalVar, CntrPar, DebugVar, ErrVar, avrSWAP, RootName, size_av CALL GetNewUnit(UnDb2, ErrVar) OPEN(unit=UnDb2, FILE=TRIM(RootName)//'.RO.dbg2') WRITE(UnDb2, *) 'Generated on '//CurDate()//' at '//CurTime()//' using ROSCO-'//TRIM(rosco_version) - WRITE(UnDb2, '(101(a20,TR5:))') 'Time', LocalVarOutStrings - WRITE(UnDb2, '(101(a20,TR5:))') + WRITE(UnDb2, '(102(a20,TR5:))') 'Time', LocalVarOutStrings + WRITE(UnDb2, '(102(a20,TR5:))') END IF IF (CntrPar%LoggingLevel > 2) THEN @@ -817,7 +820,7 @@ SUBROUTINE Debug(LocalVar, CntrPar, DebugVar, ErrVar, avrSWAP, RootName, size_av END DO ! Write debug files - FmtDat = "(F20.5,TR5,100(ES20.5E2,TR5:))" ! The format of the debugging data + FmtDat = "(F20.5,TR5,101(ES20.5E2,TR5:))" ! The format of the debugging data IF(CntrPar%LoggingLevel > 0) THEN WRITE (UnDb, TRIM(FmtDat)) LocalVar%Time, DebugOutData END IF diff --git a/ROSCO/src/ROSCO_Types.f90 b/ROSCO/src/ROSCO_Types.f90 index ec19d6b8..76631c19 100644 --- a/ROSCO/src/ROSCO_Types.f90 +++ b/ROSCO/src/ROSCO_Types.f90 @@ -95,7 +95,9 @@ MODULE ROSCO_Types REAL(DbKi) :: SD_MaxPit ! Maximum blade pitch angle to initiate shutdown, [rad] REAL(DbKi) :: SD_CornerFreq ! Cutoff Frequency for first order low-pass filter for blade pitch angle, [rad/s] INTEGER(IntKi) :: Fl_Mode ! Floating specific feedback mode {0 - no nacelle velocity feedback, 1 - nacelle velocity feedback} - REAL(DbKi) :: Fl_Kp ! Nacelle velocity proportional feedback gain [s] + INTEGER(IntKi) :: Fl_n ! Number of Fl_Kp for gain scheduling + REAL(DbKi), DIMENSION(:), ALLOCATABLE :: Fl_Kp ! Nacelle velocity proportional feedback gain [s] + REAL(DbKi), DIMENSION(:), ALLOCATABLE :: Fl_U ! Wind speeds for scheduling Fl_Kp [m/s] INTEGER(IntKi) :: Flp_Mode ! Flap actuator mode {0 - off, 1 - fixed flap position, 2 - PI flap control} REAL(DbKi) :: Flp_Angle ! Fixed flap angle (degrees) REAL(DbKi) :: Flp_Kp ! PI flap control proportional gain @@ -119,7 +121,7 @@ MODULE ROSCO_Types INTEGER(IntKi) :: PA_Mode ! Pitch actuator mode {0 - not used, 1 - first order filter, 2 - second order filter} REAL(DbKi) :: PA_CornerFreq ! Pitch actuator bandwidth/cut-off frequency [rad/s] REAL(DbKi) :: PA_Damping ! Pitch actuator damping ratio [-, unused if PA_Mode = 1] - INTEGER(IntKi) :: AWC_Mode ! Active wake control mode [0 - unused, 1 - SNL method, 2 - NREL method] + INTEGER(IntKi) :: AWC_Mode ! Active wake control mode [0 - unused, 1 - complex number method, 2 - Coleman transform method] INTEGER(IntKi) :: AWC_NumModes ! AWC- Number of modes to include [-] INTEGER(IntKi), DIMENSION(:), ALLOCATABLE :: AWC_n ! AWC azimuthal mode [-] INTEGER(IntKi), DIMENSION(:), ALLOCATABLE :: AWC_harmonic ! AWC AWC Coleman transform harmonic [-] @@ -275,6 +277,7 @@ MODULE ROSCO_Types REAL(DbKi) :: PitComAct(3) ! Actuated pitch command of each blade [rad]. REAL(DbKi) :: SS_DelOmegaF ! Filtered setpoint shifting term defined in setpoint smoother [rad/s]. REAL(DbKi) :: TestType ! Test variable, no use + REAL(DbKi) :: Kp_Float ! Local, instantaneous Kp_Float, scheduled on wind speed, if desired REAL(DbKi) :: VS_MaxTq ! Maximum allowable generator torque [Nm]. REAL(DbKi) :: VS_LastGenTrq ! Commanded electrical generator torque the last time the controller was called [Nm]. REAL(DbKi) :: VS_LastGenPwr ! Commanded electrical generator torque the last time the controller was called [Nm]. diff --git a/ROSCO/src/ReadSetParameters.f90 b/ROSCO/src/ReadSetParameters.f90 index 1b29ab0e..7343eb04 100644 --- a/ROSCO/src/ReadSetParameters.f90 +++ b/ROSCO/src/ReadSetParameters.f90 @@ -526,7 +526,10 @@ SUBROUTINE ReadControlParameterFileSub(CntrPar, zmqVar, accINFILE, accINFILE_siz IF (ErrVar%aviFAIL < 0) RETURN !------------ FLOATING ------------ - CALL ParseInput(FileLines, 'Fl_Kp', CntrPar%Fl_Kp, accINFILE(1), ErrVar, CntrPar%FL_Mode == 0, UnEc) + CALL ParseInput(FileLines, 'Fl_n', CntrPar%Fl_n, accINFILE(1), ErrVar, .TRUE., UnEc) + IF (CntrPar%Fl_n == 0) CntrPar%Fl_n = 1 ! Default is 1 + CALL ParseAry(FileLines, 'Fl_Kp', CntrPar%Fl_Kp, CntrPar%Fl_n, accINFILE(1), ErrVar, CntrPar%FL_Mode == 0, UnEc) + CALL ParseAry(FileLines, 'Fl_U', CntrPar%Fl_U, CntrPar%Fl_n, accINFILE(1), ErrVar, CntrPar%Fl_n == 1, UnEc) ! Allow default if only one Fl_Kp IF (ErrVar%aviFAIL < 0) RETURN !------------ Flaps ------------ diff --git a/ROSCO_toolbox/controller.py b/ROSCO_toolbox/controller.py index c5896517..4051cea5 100644 --- a/ROSCO_toolbox/controller.py +++ b/ROSCO_toolbox/controller.py @@ -116,7 +116,7 @@ def __init__(self, controller_params): if 'Kp_float' in controller_params: self.Kp_float = controller_params['Kp_float'] else: - self.Kp_float = 0 + self.Kp_float = np.array([0]) self.tune_Fl = controller_params['tune_Fl'] @@ -344,6 +344,9 @@ def tune_controller(self, turbine): self.v = v # Wind speed (m/s) self.v_above_rated = v_above_rated self.v_below_rated = v_below_rated + # Mod by A. Wright + self.v_for_gs = v[-len(v_above_rated)+1:] + # end self.pitch_op = pitch_op self.pitch_op_pc = pitch_op[-len(v_above_rated)+1:] self.TSR_op = TSR_op @@ -372,14 +375,41 @@ def tune_controller(self, turbine): self.ps.min_pitch_saturation(self,turbine) # --- Floating feedback term --- + if self.Fl_Mode >= 1: # Floating feedback - # If we haven't set Kp_float as a control parameter + + # Wind speed gain scheduling + self.U_Fl = self.controller_params['U_Fl'] + if self.U_Fl: # default is [], only have one Fl_Kp + if type(self.U_Fl) == str: + if self.U_Fl == 'all': + # Mod by A. Wright: get the array of Kp_float values at the values of v-above rated (see self.v_for_gs calculated around line 344). + self.U_Fl = self.v_for_gs + else: + raise Exception("Invalid entry in controller_params for U_Fl, please see schema") + else: + self.U_Fl = np.array([turbine.v_rated * (1.05)]) + + + # If we haven't set Kp_float as a control parameter, we tune it automatically here if self.tune_Fl: Kp_float = (dtau_dv/dtau_dbeta) * Ng if self.Fl_Mode == 2: Kp_float *= turbine.TowerHt f_kp = interpolate.interp1d(v,Kp_float) - self.Kp_float = f_kp(turbine.v_rated * (1.05)) # get Kp at v_rated + 0.5 m/s + self.Kp_float = f_kp(self.U_Fl) # get Kp at v_rated + 0.5 m/s + + # Make arrays if not + if not np.shape(self.Kp_float): + self.Kp_float = np.array([self.Kp_float]) + if not np.shape(self.U_Fl): + self.U_Fl = np.array([self.U_Fl]) + + # Check size of Kp_float and U_Fl + if len(self.Kp_float) != len(self.U_Fl): + raise Exception('The sizes of Kp_float and U_Fl are not equal, please check your controller_params') + + # Turn on the notch filter if floating self.F_NotchType = 2 @@ -389,7 +419,8 @@ def tune_controller(self, turbine): print('WARNING: twr_freq and ptfm_freq should be defined for floating turbine control!!') else: - self.Kp_float = 0.0 + self.Kp_float = np.array([0.0]) + self.U_Fl = np.array([0.0]) # Flap actuation if self.Flp_Mode >= 1: diff --git a/ROSCO_toolbox/inputs/toolbox_schema.yaml b/ROSCO_toolbox/inputs/toolbox_schema.yaml index 80a5486d..24d4d5ef 100644 --- a/ROSCO_toolbox/inputs/toolbox_schema.yaml +++ b/ROSCO_toolbox/inputs/toolbox_schema.yaml @@ -18,11 +18,11 @@ properties: # default: IEA-15-240-RWT-UMaineSemi.fst FAST_directory: type: string - description: Main OpenFAST model directory, where the `*.fst` lives, relative to ROSCO dir (if applicable) + description: Main OpenFAST model directory, where the `*.fst` lives, relative to directory of this yaml (if applicable) # default: Test_Cases/IEA-15-240-RWT-UMaineSemi rotor_performance_filename: type: string - description: Filename for rotor performance text file (if it has been generated by ccblade already) + description: Filename for rotor performance text file (if it has been generated by ccblade already), relative to directory of this yaml # default: Cp_Ct_Cq.IEA15MW.txt turbine_params: @@ -331,13 +331,21 @@ properties: minimum: 0 default: 30 Kp_float: - type: number - description: Gain of floating feedback control + type: [number, array] + description: Gain(s) of floating feedback control unit: s + items: + type: number tune_Fl: type: boolean description: Whether to automatically tune Kp_float default: True + U_Fl: + type: [array, string, number] + description: List of wind speeds for tuning floating feedback, or "all" for all above-rated wind speeds + default: [] + items: + type: number zeta_flp: type: number minimum: 0 @@ -834,10 +842,22 @@ properties: type: number description: Cutoff Frequency for first order low-pass filter for blade pitch angle units: rad/s - Fl_Kp: + Fl_n: type: number + description: Number of Fl_Kp gains in gain scheduling, optional with default of 1 + units: s + Fl_Kp: + type: array description: Nacelle velocity proportional feedback gain units: s + items: + type: number + Fl_U: + type: array + description: Wind speeds for scheduling Fl_Kp, optional if Fl_Kp is single value [m/s] + units: s + items: + type: number Flp_Angle: type: number description: Initial or steady state flap angle diff --git a/ROSCO_toolbox/ofTools/case_gen/CaseLibrary.py b/ROSCO_toolbox/ofTools/case_gen/CaseLibrary.py index e6aef0bf..001844f4 100644 --- a/ROSCO_toolbox/ofTools/case_gen/CaseLibrary.py +++ b/ROSCO_toolbox/ofTools/case_gen/CaseLibrary.py @@ -155,25 +155,10 @@ def simp_step(**wind_case_opts): # Set up cases for FIW-JIP project # 3.x in controller tuning register - if 'T_Max' in wind_case_opts: - T_max = wind_case_opts['T_Max'] - else: #default - T_max = 300. - - if 'U_start' in wind_case_opts: - U_start = wind_case_opts['U_start'] - else: #default - U_start = [16] - - if 'U_end' in wind_case_opts: - U_end = wind_case_opts['U_end'] - else: #default - U_end = [17] - - if 'T_step' in wind_case_opts: - T_step = wind_case_opts['T_step'] - else: #default - T_step = 150 + TMax = wind_case_opts.get('TMax',300.) + T_step = wind_case_opts.get('TStep',150.) + U_start = wind_case_opts.get('U_start',[16.]) + U_end = wind_case_opts.get('U_end',[17.]) # Wind directory, default is run_dir wind_case_opts['wind_dir'] = wind_case_opts.get('wind_dir',wind_case_opts['run_dir']) @@ -182,7 +167,7 @@ def simp_step(**wind_case_opts): # Make Default step wind object hh_step = HH_StepFile() - hh_step.t_max = T_max + hh_step.t_max = TMax hh_step.t_step = T_step hh_step.wind_directory = wind_case_opts['wind_dir'] @@ -200,7 +185,7 @@ def simp_step(**wind_case_opts): case_inputs = base_op_case() # simulation settings - case_inputs[("Fst","TMax")] = {'vals':[T_max], 'group':0} + case_inputs[("Fst","TMax")] = {'vals':[TMax], 'group':0} # case_inputs[("Fst","DT")] = {'vals':[1/80], 'group':0} # wind inflow diff --git a/ROSCO_toolbox/ofTools/case_gen/run_FAST.py b/ROSCO_toolbox/ofTools/case_gen/run_FAST.py index acff382f..abec4c25 100644 --- a/ROSCO_toolbox/ofTools/case_gen/run_FAST.py +++ b/ROSCO_toolbox/ofTools/case_gen/run_FAST.py @@ -7,7 +7,10 @@ """ -from ROSCO_toolbox.ofTools.case_gen.runFAST_pywrapper import runFAST_pywrapper_batch +try: + from weis.aeroelasticse.runFAST_pywrapper import runFAST_pywrapper_batch +except: + from ROSCO_toolbox.ofTools.case_gen.runFAST_pywrapper import runFAST_pywrapper_batch from ROSCO_toolbox.ofTools.case_gen.CaseGen_IEC import CaseGen_IEC from ROSCO_toolbox.ofTools.case_gen.CaseGen_General import CaseGen_General from ROSCO_toolbox.ofTools.case_gen import CaseLibrary as cl @@ -92,7 +95,6 @@ def run_FAST(self): tune_yaml_dir = os.path.split(self.tuning_yaml)[0] cp_filename = os.path.join( tune_yaml_dir, - path_params['FAST_directory'], path_params['rotor_performance_filename'] ) turbine.load_from_fast( @@ -174,6 +176,7 @@ def run_FAST(self): fastBatch.case_name_list = case_name_list fastBatch.fst_vt = self.fst_vt fastBatch.FAST_exe = self.openfast_exe + fastBatch.use_exe = True if MPI: fastBatch.run_mpi(comm_map_down) @@ -198,7 +201,7 @@ def run_FAST(self): if __name__ == "__main__": # Simulation config - sim_config = 1 + sim_config = 3 r = run_FAST_ROSCO() @@ -210,6 +213,22 @@ def run_FAST(self): r.wind_case_fcn = cl.simp_step r.sweep_mode = None r.save_dir = '/Users/dzalkind/Tools/ROSCO/outputs' + + elif sim_config == 3: + # IEA-22 fixed bottom + r.tuning_yaml = '/Users/dzalkind/Projects/IEA-22MW/IEA-22-280-RWT/OpenFAST/IEA-22-280-RWT-Monopile/IEA-22-280-RWT-Monopile.yaml' + r.wind_case_fcn = cl.power_curve + r.sweep_mode = None + r.wind_case_opts = { + 'U': [6,9,12,15], + 'TMax': 100, + } + r.save_dir = '/Users/dzalkind/Projects/IEA-22MW/MonopileControl/outputs/1_const_power' + r.openfast_exe = '/Users/dzalkind/opt/anaconda3/envs/rosco-new/bin/openfast' + # rosco_dll = '/Users/dzalkind/Tools/ROSCO1/ROSCO/build/libdiscon.dylib' + r.case_inputs = {} + # r.case_inputs[('ServoDyn','DLL_FileName')] = {'vals': [rosco_dll], 'group': 0} + r.n_cores = 4 elif sim_config == 6: diff --git a/ROSCO_toolbox/ofTools/fast_io/FAST_reader.py b/ROSCO_toolbox/ofTools/fast_io/FAST_reader.py index 7b9130f6..8974110b 100644 --- a/ROSCO_toolbox/ofTools/fast_io/FAST_reader.py +++ b/ROSCO_toolbox/ofTools/fast_io/FAST_reader.py @@ -652,12 +652,12 @@ def read_BeamDyn(self, bd_file): f.close() - self.read_BeamDynBlade() + beamdyn_blade_file = os.path.join(os.path.dirname(bd_file), self.fst_vt['BeamDyn']['BldFile']) + self.read_BeamDynBlade(beamdyn_blade_file) - def read_BeamDynBlade(self): + def read_BeamDynBlade(self, beamdyn_blade_file): # BeamDyn Blade - beamdyn_blade_file = os.path.join(self.FAST_directory, self.fst_vt['BeamDyn']['BldFile']) f = open(beamdyn_blade_file) f.readline() @@ -2061,7 +2061,7 @@ def read_SubDyn(self, sd_file): self.fst_vt['SubDyn']['NDiv'] = int_read(f.readline().split()[0]) self.fst_vt['SubDyn']['CBMod'] = bool_read(f.readline().split()[0]) self.fst_vt['SubDyn']['Nmodes'] = int_read(f.readline().split()[0]) - self.fst_vt['SubDyn']['JDampings'] = int_read(f.readline().split()[0]) + self.fst_vt['SubDyn']['JDampings'] = float_read(f.readline().split()[0]) self.fst_vt['SubDyn']['GuyanDampMod'] = int_read(f.readline().split()[0]) self.fst_vt['SubDyn']['RayleighDamp'] = [float(m.replace(',','')) for m in f.readline().split()[:2]] self.fst_vt['SubDyn']['GuyanDampSize'] = int_read(f.readline().split()[0]) @@ -2113,7 +2113,10 @@ def read_SubDyn(self, sd_file): self.fst_vt['SubDyn']['RctRDXss'][i] = int(ln[4]) self.fst_vt['SubDyn']['RctRDYss'][i] = int(ln[5]) self.fst_vt['SubDyn']['RctRDZss'][i] = int(ln[6]) - self.fst_vt['SubDyn']['Rct_SoilFile'][i] = ln[7] + if len(ln) == 8: + self.fst_vt['SubDyn']['Rct_SoilFile'][i] = ln[7] + else: + self.fst_vt['SubDyn']['Rct_SoilFile'][i] = 'None' f.readline() # INTERFACE JOINTS self.fst_vt['SubDyn']['NInterf'] = int_read(f.readline().split()[0]) diff --git a/ROSCO_toolbox/tune.py b/ROSCO_toolbox/tune.py index e4d5392c..9a10bda1 100644 --- a/ROSCO_toolbox/tune.py +++ b/ROSCO_toolbox/tune.py @@ -36,7 +36,7 @@ def yaml_to_objs(tuning_yaml): path_params['FAST_InputFile'], os.path.join(yaml_dir,path_params['FAST_directory']), rot_source='txt', - txt_filename=os.path.join(yaml_dir,path_params['FAST_directory'],path_params['rotor_performance_filename']) + txt_filename=os.path.join(yaml_dir,path_params['rotor_performance_filename']) ) # Tune controller diff --git a/ROSCO_toolbox/utilities.py b/ROSCO_toolbox/utilities.py index da86cef2..44b8e03f 100644 --- a/ROSCO_toolbox/utilities.py +++ b/ROSCO_toolbox/utilities.py @@ -132,7 +132,7 @@ def write_DISCON(turbine, controller, param_file='DISCON.IN', txt_filename='Cp_C file.write('{:<11d} ! PC_GS_n - Amount of gain-scheduling table entries\n'.format(int(rosco_vt['PC_GS_n']))) file.write('{} ! PC_GS_angles - Gain-schedule table: pitch angles [rad].\n'.format(''.join('{:<4.6f} '.format(rosco_vt['PC_GS_angles'][i]) for i in range(len(rosco_vt['PC_GS_angles']))))) file.write('{} ! PC_GS_KP - Gain-schedule table: pitch controller kp gains [s].\n'.format(''.join('{:<4.6f} '.format(rosco_vt['PC_GS_KP'][i]) for i in range(len(rosco_vt['PC_GS_KP']))))) - file.write('{} ! PC_GS_KI - Gain-schedule table: pitch controller ki gains [-].\n'.format(''.join('{:<4.6f} '.format(rosco_vt['PC_GS_KI'][i]) for i in range(len(rosco_vt['PC_GS_KI']))))) + file.write('{} ! PC_GS_KI - Gain-schedule table: pitch controller ki gains [-].\n'.format(''.join('{:<4.6f} '.format(rosco_vt['PC_GS_KI'][i]) for i in range(len(rosco_vt['PC_GS_KI'])))))# file.write('{} ! PC_GS_KD - Gain-schedule table: pitch controller kd gains\n'.format(''.join('{:<4.6f} '.format(rosco_vt['PC_GS_KD'][i]) for i in range(len(rosco_vt['PC_GS_KD']))))) file.write('{} ! PC_GS_TF - Gain-schedule table: pitch controller tf gains (derivative filter)\n'.format(''.join('{:<4.6f} '.format(rosco_vt['PC_GS_TF'][i]) for i in range(len(rosco_vt['PC_GS_TF']))))) file.write('{:<014.5f} ! PC_MaxPit - Maximum physical pitch limit, [rad].\n'.format(rosco_vt['PC_MaxPit'])) @@ -214,7 +214,9 @@ def write_DISCON(turbine, controller, param_file='DISCON.IN', txt_filename='Cp_C floatstr = 'pitching' else: floatstr = 'velocity' - file.write('{:<014.5f} ! Fl_Kp - Nacelle {} proportional feedback gain [s]\n'.format(rosco_vt['Fl_Kp'], floatstr)) + file.write('{:<11d} ! Fl_n - Number of Fl_Kp gains in gain scheduling, optional with default of 1\n'.format(int(rosco_vt['Fl_n']))) + file.write('{} ! Fl_Kp - Nacelle {} proportional feedback gain [s]\n'.format(write_array(rosco_vt['Fl_Kp'],'<6.4f'), floatstr)) + file.write('{} ! Fl_U - Wind speeds for scheduling Fl_Kp, optional if Fl_Kp is single value [m/s]\n'.format(write_array(rosco_vt['Fl_U'],'<6.4f'))) file.write('\n') file.write('!------- FLAP ACTUATION -----------------------------------------------------\n') file.write('{:<014.5f} ! Flp_Angle - Initial or steady state flap angle [rad]\n'.format(rosco_vt['Flp_Angle'])) @@ -488,6 +490,8 @@ def DISCON_dict(turbine, controller, txt_filename=None): DISCON_dict['PC_GS_KI'] = controller.pc_gain_schedule.Ki DISCON_dict['PC_GS_KD'] = [0.0 for i in range(len(controller.pc_gain_schedule.Ki))] DISCON_dict['PC_GS_TF'] = [0.0 for i in range(len(controller.pc_gain_schedule.Ki))] + + # DISCON_dict['PC_MaxPit'] = controller.max_pitch DISCON_dict['PC_MinPit'] = controller.min_pitch DISCON_dict['PC_MaxRat'] = turbine.max_pitch_rate @@ -554,7 +558,9 @@ def DISCON_dict(turbine, controller, txt_filename=None): DISCON_dict['SD_MaxPit'] = controller.sd_maxpit DISCON_dict['SD_CornerFreq'] = controller.f_sd_cornerfreq # ------- Floating ------- + DISCON_dict['Fl_n'] = len(controller.Kp_float) DISCON_dict['Fl_Kp'] = controller.Kp_float + DISCON_dict['Fl_U'] = controller.U_Fl # ------- FLAP ACTUATION ------- DISCON_dict['Flp_Angle'] = controller.flp_angle DISCON_dict['Flp_Kp'] = controller.Kp_flap[-1] diff --git a/Test_Cases/BAR_10/BAR_10_DISCON.IN b/Test_Cases/BAR_10/BAR_10_DISCON.IN index f750015d..b3636e42 100644 --- a/Test_Cases/BAR_10/BAR_10_DISCON.IN +++ b/Test_Cases/BAR_10/BAR_10_DISCON.IN @@ -1,5 +1,5 @@ ! Controller parameter input file for the BAR_10 wind turbine -! - File written using ROSCO version 2.8.0 controller tuning logic on 04/10/23 +! - File written using ROSCO version 2.8.0 controller tuning logic on 06/13/23 !------- DEBUG ------------------------------------------------------------ 1 ! LoggingLevel - (0: write no debug files, 1: write standard output .dbg-file, 2: LoggingLevel 1 + ROSCO LocalVars (.dbg2) 3: LoggingLevel 2 + complete avrSWAP-array (.dbg3)) @@ -122,7 +122,9 @@ 0.418880000000 ! SD_CornerFreq - Cutoff Frequency for first order low-pass filter for blade pitch angle, [rad/s] !------- Floating ----------------------------------------------------------- -0.000000000000 ! Fl_Kp - Nacelle velocity proportional feedback gain [s] +1 ! Fl_n - Number of Fl_Kp gains in gain scheduling, optional with default of 1 +0.0000 ! Fl_Kp - Nacelle velocity proportional feedback gain [s] +0.0000 ! Fl_U - Wind speeds for scheduling Fl_Kp, optional if Fl_Kp is single value [m/s] !------- FLAP ACTUATION ----------------------------------------------------- 0.000000000000 ! Flp_Angle - Initial or steady state flap angle [rad] diff --git a/Test_Cases/IEA-15-240-RWT-UMaineSemi/DISCON-UMaineSemi.IN b/Test_Cases/IEA-15-240-RWT-UMaineSemi/DISCON-UMaineSemi.IN index 17c96a1e..be780b4c 100644 --- a/Test_Cases/IEA-15-240-RWT-UMaineSemi/DISCON-UMaineSemi.IN +++ b/Test_Cases/IEA-15-240-RWT-UMaineSemi/DISCON-UMaineSemi.IN @@ -1,5 +1,5 @@ ! Controller parameter input file for the IEA-15-240-RWT-UMaineSemi wind turbine -! - File written using ROSCO version 2.8.0 controller tuning logic on 04/10/23 +! - File written using ROSCO version 2.8.0 controller tuning logic on 06/13/23 !------- DEBUG ------------------------------------------------------------ 2 ! LoggingLevel - (0: write no debug files, 1: write standard output .dbg-file, 2: LoggingLevel 1 + ROSCO LocalVars (.dbg2) 3: LoggingLevel 2 + complete avrSWAP-array (.dbg3)) @@ -122,7 +122,9 @@ 0.418880000000 ! SD_CornerFreq - Cutoff Frequency for first order low-pass filter for blade pitch angle, [rad/s] !------- Floating ----------------------------------------------------------- --9.34645000000 ! Fl_Kp - Nacelle pitching proportional feedback gain [s] +1 ! Fl_n - Number of Fl_Kp gains in gain scheduling, optional with default of 1 +-9.3465 ! Fl_Kp - Nacelle pitching proportional feedback gain [s] +11.2770 ! Fl_U - Wind speeds for scheduling Fl_Kp, optional if Fl_Kp is single value [m/s] !------- FLAP ACTUATION ----------------------------------------------------- 0.000000000000 ! Flp_Angle - Initial or steady state flap angle [rad] diff --git a/Test_Cases/NREL-5MW/DISCON.IN b/Test_Cases/NREL-5MW/DISCON.IN index 0ddb6aa4..22d049d4 100644 --- a/Test_Cases/NREL-5MW/DISCON.IN +++ b/Test_Cases/NREL-5MW/DISCON.IN @@ -1,5 +1,5 @@ ! Controller parameter input file for the NREL-5MW wind turbine -! - File written using ROSCO version 2.8.0 controller tuning logic on 04/10/23 +! - File written using ROSCO version 2.8.0 controller tuning logic on 06/13/23 !------- DEBUG ------------------------------------------------------------ 1 ! LoggingLevel - (0: write no debug files, 1: write standard output .dbg-file, 2: LoggingLevel 1 + ROSCO LocalVars (.dbg2) 3: LoggingLevel 2 + complete avrSWAP-array (.dbg3)) @@ -122,7 +122,9 @@ 0.418880000000 ! SD_CornerFreq - Cutoff Frequency for first order low-pass filter for blade pitch angle, [rad/s] !------- Floating ----------------------------------------------------------- -0.000000000000 ! Fl_Kp - Nacelle velocity proportional feedback gain [s] +1 ! Fl_n - Number of Fl_Kp gains in gain scheduling, optional with default of 1 +0.0000 ! Fl_Kp - Nacelle velocity proportional feedback gain [s] +0.0000 ! Fl_U - Wind speeds for scheduling Fl_Kp, optional if Fl_Kp is single value [m/s] !------- FLAP ACTUATION ----------------------------------------------------- 0.000000000000 ! Flp_Angle - Initial or steady state flap angle [rad] diff --git a/Test_Cases/NREL_2p8_127/NREL-2p8-127_DISCON.IN b/Test_Cases/NREL_2p8_127/NREL-2p8-127_DISCON.IN index ec720eb5..4366ff44 100644 --- a/Test_Cases/NREL_2p8_127/NREL-2p8-127_DISCON.IN +++ b/Test_Cases/NREL_2p8_127/NREL-2p8-127_DISCON.IN @@ -1,5 +1,5 @@ ! Controller parameter input file for the NREL-2p8-127 wind turbine -! - File written using ROSCO version 2.8.0 controller tuning logic on 04/10/23 +! - File written using ROSCO version 2.8.0 controller tuning logic on 06/13/23 !------- DEBUG ------------------------------------------------------------ 2 ! LoggingLevel - (0: write no debug files, 1: write standard output .dbg-file, 2: LoggingLevel 1 + ROSCO LocalVars (.dbg2) 3: LoggingLevel 2 + complete avrSWAP-array (.dbg3)) @@ -122,7 +122,9 @@ 0.418880000000 ! SD_CornerFreq - Cutoff Frequency for first order low-pass filter for blade pitch angle, [rad/s] !------- Floating ----------------------------------------------------------- -0.000000000000 ! Fl_Kp - Nacelle velocity proportional feedback gain [s] +1 ! Fl_n - Number of Fl_Kp gains in gain scheduling, optional with default of 1 +0.0000 ! Fl_Kp - Nacelle velocity proportional feedback gain [s] +0.0000 ! Fl_U - Wind speeds for scheduling Fl_Kp, optional if Fl_Kp is single value [m/s] !------- FLAP ACTUATION ----------------------------------------------------- 0.000000000000 ! Flp_Angle - Initial or steady state flap angle [rad] diff --git a/Tune_Cases/BAR.yaml b/Tune_Cases/BAR.yaml index e1d7c463..bb21281d 100644 --- a/Tune_Cases/BAR.yaml +++ b/Tune_Cases/BAR.yaml @@ -6,7 +6,7 @@ path_params: FAST_InputFile: 'BAR_10.fst' # Name of *.fst file FAST_directory: '../Test_Cases/BAR_10' # Main OpenFAST model directory, where the *.fst lives # Optional (but suggested...) - rotor_performance_filename: 'Cp_Ct_Cq.BAR_10.txt' # Filename for rotor performance text file (if it has been generated by ccblade already) + rotor_performance_filename: '../Test_Cases/BAR_10/Cp_Ct_Cq.BAR_10.txt' # Filename for rotor performance text file (if it has been generated by ccblade already) # -------------------------------- TURBINE PARAMETERS ----------------------------------- turbine_params: diff --git a/Tune_Cases/IEA15MW.yaml b/Tune_Cases/IEA15MW.yaml index fa2aeb57..b654cf9a 100644 --- a/Tune_Cases/IEA15MW.yaml +++ b/Tune_Cases/IEA15MW.yaml @@ -6,7 +6,7 @@ path_params: FAST_InputFile: 'IEA-15-240-RWT-UMaineSemi.fst' # Name of *.fst file FAST_directory: '../Test_Cases/IEA-15-240-RWT-UMaineSemi' # Main OpenFAST model directory, where the *.fst lives # Optional (but suggested...) - rotor_performance_filename: 'Cp_Ct_Cq.IEA15MW.txt' # Filename for rotor performance text file (if it has been generated by ccblade already) + rotor_performance_filename: '../Test_Cases/IEA-15-240-RWT-UMaineSemi/Cp_Ct_Cq.IEA15MW.txt' # -------------------------------- TURBINE PARAMETERS ----------------------------------- turbine_params: diff --git a/Tune_Cases/IEA15MW_ExtInterface.yaml b/Tune_Cases/IEA15MW_ExtInterface.yaml index 7abe10da..0f65812d 100644 --- a/Tune_Cases/IEA15MW_ExtInterface.yaml +++ b/Tune_Cases/IEA15MW_ExtInterface.yaml @@ -6,7 +6,7 @@ path_params: FAST_InputFile: 'IEA-15-240-RWT-UMaineSemi.fst' # Name of *.fst file FAST_directory: '../Test_Cases/IEA-15-240-RWT-UMaineSemi' # Main OpenFAST model directory, where the *.fst lives # Optional (but suggested...) - rotor_performance_filename: 'Cp_Ct_Cq.IEA15MW.txt' # Filename for rotor performance text file (if it has been generated by ccblade already) + rotor_performance_filename: '../Test_Cases/IEA-15-240-RWT-UMaineSemi/Cp_Ct_Cq.IEA15MW.txt' # -------------------------------- TURBINE PARAMETERS ----------------------------------- turbine_params: diff --git a/Tune_Cases/IEA15MW_FOCAL.yaml b/Tune_Cases/IEA15MW_FOCAL.yaml index 06a36cf8..4f28825a 100644 --- a/Tune_Cases/IEA15MW_FOCAL.yaml +++ b/Tune_Cases/IEA15MW_FOCAL.yaml @@ -6,7 +6,7 @@ path_params: FAST_InputFile: 'IEA-15-240-RWT-UMaineSemi.fst' # Name of *.fst file FAST_directory: '../Test_Cases/IEA-15-240-RWT-UMaineSemi' # Main OpenFAST model directory, where the *.fst lives # Optional (but suggested...) - rotor_performance_filename: 'Cp_Ct_Cq.IEA15MW.txt' # Filename for rotor performance text file (if it has been generated by ccblade already) + rotor_performance_filename: '../Test_Cases/IEA-15-240-RWT-UMaineSemi/Cp_Ct_Cq.IEA15MW.txt' # -------------------------------- TURBINE PARAMETERS ----------------------------------- turbine_params: diff --git a/Tune_Cases/IEA15MW_MultiOmega.yaml b/Tune_Cases/IEA15MW_MultiOmega.yaml index 20278253..bee656b5 100644 --- a/Tune_Cases/IEA15MW_MultiOmega.yaml +++ b/Tune_Cases/IEA15MW_MultiOmega.yaml @@ -6,7 +6,7 @@ path_params: FAST_InputFile: 'IEA-15-240-RWT-UMaineSemi.fst' # Name of *.fst file FAST_directory: '../Test_Cases/IEA-15-240-RWT-UMaineSemi' # Main OpenFAST model directory, where the *.fst lives # Optional (but suggested...) - rotor_performance_filename: 'Cp_Ct_Cq.IEA15MW.txt' # Filename for rotor performance text file (if it has been generated by ccblade already) + rotor_performance_filename: '../Test_Cases/IEA-15-240-RWT-UMaineSemi/Cp_Ct_Cq.IEA15MW.txt' # -------------------------------- TURBINE PARAMETERS ----------------------------------- turbine_params: diff --git a/Tune_Cases/IEA15MW_OL.yaml b/Tune_Cases/IEA15MW_OL.yaml index faaa6943..50e7bc81 100644 --- a/Tune_Cases/IEA15MW_OL.yaml +++ b/Tune_Cases/IEA15MW_OL.yaml @@ -6,7 +6,7 @@ path_params: FAST_InputFile: 'IEA-15-240-RWT-UMaineSemi.fst' # Name of *.fst file FAST_directory: '../Test_Cases/IEA-15-240-RWT-UMaineSemi' # Main OpenFAST model directory, where the *.fst lives # Optional (but suggested...) - rotor_performance_filename: 'Cp_Ct_Cq.IEA15MW.txt' # Filename for rotor performance text file (if it has been generated by ccblade already) + rotor_performance_filename: '../Test_Cases/IEA-15-240-RWT-UMaineSemi/Cp_Ct_Cq.IEA15MW.txt' # -------------------------------- TURBINE PARAMETERS ----------------------------------- turbine_params: diff --git a/Tune_Cases/IEA15MW_ballast.yaml b/Tune_Cases/IEA15MW_ballast.yaml index 6bf34418..ab5fc90f 100644 --- a/Tune_Cases/IEA15MW_ballast.yaml +++ b/Tune_Cases/IEA15MW_ballast.yaml @@ -6,7 +6,7 @@ path_params: FAST_InputFile: 'IEA-15-240-RWT-UMaineSemi.fst' # Name of *.fst file FAST_directory: '../Test_Cases/IEA-15-240-RWT-UMaineSemi' # Main OpenFAST model directory, where the *.fst lives # Optional (but suggested...) - rotor_performance_filename: 'Cp_Ct_Cq.IEA15MW.txt' # Filename for rotor performance text file (if it has been generated by ccblade already) + rotor_performance_filename: '../Test_Cases/IEA-15-240-RWT-UMaineSemi/Cp_Ct_Cq.IEA15MW.txt' # Filename for rotor performance text file (if it has been generated by ccblade already) # -------------------------------- TURBINE PARAMETERS ----------------------------------- turbine_params: diff --git a/Tune_Cases/IEA15MW_cable.yaml b/Tune_Cases/IEA15MW_cable.yaml index c17b006b..be81e6ec 100644 --- a/Tune_Cases/IEA15MW_cable.yaml +++ b/Tune_Cases/IEA15MW_cable.yaml @@ -6,7 +6,7 @@ path_params: FAST_InputFile: 'IEA-15-240-RWT-UMaineSemi.fst' # Name of *.fst file FAST_directory: '../Test_Cases/IEA-15-240-RWT-UMaineSemi' # Main OpenFAST model directory, where the *.fst lives # Optional (but suggested...) - rotor_performance_filename: 'Cp_Ct_Cq.IEA15MW.txt' # Filename for rotor performance text file (if it has been generated by ccblade already) + rotor_performance_filename: '../Test_Cases/IEA-15-240-RWT-UMaineSemi/Cp_Ct_Cq.IEA15MW.txt' # -------------------------------- TURBINE PARAMETERS ----------------------------------- turbine_params: diff --git a/Tune_Cases/IEA15MW_robust.yaml b/Tune_Cases/IEA15MW_robust.yaml index cb7e611d..984ec52b 100644 --- a/Tune_Cases/IEA15MW_robust.yaml +++ b/Tune_Cases/IEA15MW_robust.yaml @@ -6,7 +6,7 @@ path_params: FAST_InputFile: 'IEA-15-240-RWT-UMaineSemi.fst' # Name of *.fst file FAST_directory: '../Test_Cases/IEA-15-240-RWT-UMaineSemi' # Main OpenFAST model directory, where the *.fst lives # Optional (but suggested...) - rotor_performance_filename: 'Cp_Ct_Cq.IEA15MW.txt' # Filename for rotor performance text file (if it has been generated by ccblade already) + rotor_performance_filename: '../Test_Cases/IEA-15-240-RWT-UMaineSemi/Cp_Ct_Cq.IEA15MW.txt' # -------------------------------- TURBINE PARAMETERS ----------------------------------- turbine_params: diff --git a/Tune_Cases/NREL2p8.yaml b/Tune_Cases/NREL2p8.yaml index bbba19a2..be0f4387 100644 --- a/Tune_Cases/NREL2p8.yaml +++ b/Tune_Cases/NREL2p8.yaml @@ -1,4 +1,4 @@ -path_params: {FAST_InputFile: NREL-2p8-127.fst, FAST_directory: ../Test_Cases/NREL_2p8_127, rotor_performance_filename: NREL-2p8-127_Cp_Ct_Cq.txt} +path_params: {FAST_InputFile: NREL-2p8-127.fst, FAST_directory: ../Test_Cases/NREL_2p8_127, rotor_performance_filename: ../Test_Cases/NREL_2p8_127/NREL-2p8-127_Cp_Ct_Cq.txt} controller_params: LoggingLevel: 2 F_LPFType: 1 diff --git a/Tune_Cases/NREL5MW.yaml b/Tune_Cases/NREL5MW.yaml index 9ad252dc..21f5acab 100644 --- a/Tune_Cases/NREL5MW.yaml +++ b/Tune_Cases/NREL5MW.yaml @@ -6,7 +6,7 @@ path_params: FAST_InputFile: 'NREL-5MW.fst' # Name of *.fst file FAST_directory: '../Test_Cases/NREL-5MW' # Main OpenFAST model directory, where the *.fst lives # Optional - rotor_performance_filename: 'Cp_Ct_Cq.NREL5MW.txt' # Filename for rotor performance text file (if it has been generated by ccblade already) + rotor_performance_filename: '../Test_Cases/NREL-5MW/Cp_Ct_Cq.NREL5MW.txt' # Filename for rotor performance text file (if it has been generated by ccblade already) # -------------------------------- TURBINE PARAMETERS ----------------------------------- turbine_params: diff --git a/Tune_Cases/NREL5MW_PassThrough.yaml b/Tune_Cases/NREL5MW_PassThrough.yaml index 2ad3be80..7f126785 100644 --- a/Tune_Cases/NREL5MW_PassThrough.yaml +++ b/Tune_Cases/NREL5MW_PassThrough.yaml @@ -6,7 +6,7 @@ path_params: FAST_InputFile: 'NREL-5MW.fst' # Name of *.fst file FAST_directory: '../Test_Cases/NREL-5MW' # Main OpenFAST model directory, where the *.fst lives # Optional - rotor_performance_filename: 'Cp_Ct_Cq.NREL5MW.txt' # Filename for rotor performance text file (if it has been generated by ccblade already) + rotor_performance_filename: '../Test_Cases/NREL-5MW/Cp_Ct_Cq.NREL5MW.txt' # Filename for rotor performance text file (if it has been generated by ccblade already) # -------------------------------- TURBINE PARAMETERS ----------------------------------- turbine_params: diff --git a/docs/source/api_change.rst b/docs/source/api_change.rst index 4fecc5a6..0598c0c8 100644 --- a/docs/source/api_change.rst +++ b/docs/source/api_change.rst @@ -9,6 +9,22 @@ The changes are tabulated according to the line number, and flag name. The line number corresponds to the resulting line number after all changes are implemented. Thus, be sure to implement each in order so that subsequent line numbers are correct. +2.8.0 to develop +------------------------------- +Gain scheduling of floating feedback +- The floating feedback gain can be scheduled on the low pass filtered wind speed signal. Note that Fl_Kp can now be an array. + +====== ================= ====================================================================================================================================================================================================== +New in ROSCO develop +---------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- +Line Input Name Example Value +====== ================= ====================================================================================================================================================================================================== +125 Fl_n 1 ! Fl_n - Number of Fl_Kp gains in gain scheduling, optional with default of 1 +126 Fl_Kp 0.0000 ! Fl_Kp - Nacelle velocity proportional feedback gain [s] +127 Fl_U 0.0000 ! Fl_U - Wind speeds for scheduling Fl_Kp, optional if Fl_Kp is single value [m/s] +====== ================= ====================================================================================================================================================================================================== + + 2.7.0 to 2.8.0 ------------------------------- Optional Inputs diff --git a/docs/source/install.rst b/docs/source/install.rst index ecd12be2..4e310e49 100644 --- a/docs/source/install.rst +++ b/docs/source/install.rst @@ -201,7 +201,7 @@ Please follow the following steps to install the ROSCO tool-chain. You should do conda install compilers # (Mac/Linux only) conda install m2w64-toolchain libpython # (Windows only) conda env config vars set FC=gfortran # Sometimes needed for Windows - conda install -y wisdem=3.5.0 + conda install -y wisdem>3.7 python setup.py install --compile-rosco 3. Clone and Install the ROSCO toolbox without ROSCO controller diff --git a/docs/source/toolbox_input.rst b/docs/source/toolbox_input.rst index 5b205c70..6e15f0e2 100644 --- a/docs/source/toolbox_input.rst +++ b/docs/source/toolbox_input.rst @@ -22,11 +22,11 @@ path_params :code:`FAST_directory` : String Main OpenFAST model directory, where the `*.fst` lives, relative - to ROSCO dir (if applicable) + to directory of this yaml (if applicable) :code:`rotor_performance_filename` : String Filename for rotor performance text file (if it has been generated - by ccblade already) + by ccblade already), relative to directory of this yaml @@ -265,6 +265,15 @@ controller_params *Minimum* = 0 *Maximum* = 1 +:code:`AWC_Mode` : Float + Active wake control mode {0 - not used, 1 - SNL method, 2 - NREL + method} + + *Default* = 0 + + *Minimum* = 0 *Maximum* = 2 + + :code:`Ext_Mode` : Float External control mode [0 - not used, 1 - call external dynamic library] @@ -275,20 +284,21 @@ controller_params :code:`CC_Mode` : Float - Cable control mode [0- unused, 1- User defined, 2- Position - control (not yet implemented)] + Cable control mode [0- unused, 1- User defined, 2- Open loop + control] *Default* = 0 - *Minimum* = 0 *Maximum* = 1 + *Minimum* = 0 *Maximum* = 2 :code:`StC_Mode` : Float - Structural control mode [0- unused, 1- User defined] + Structural control mode [0- unused, 1- User defined, 2- Open loop + control] *Default* = 0 - *Minimum* = 0 *Maximum* = 1 + *Minimum* = 0 *Maximum* = 2 :code:`U_pc` : Array of Floats @@ -396,14 +406,20 @@ controller_params *Minimum* = 0 -:code:`Kp_float` : Float, s - Gain of floating feedback control +:code:`Kp_float` : Float, s or Array of Floats + Gain(s) of floating feedback control :code:`tune_Fl` : Boolean Whether to automatically tune Kp_float *Default* = True +:code:`U_Fl` : Array of Floats or String or Float + List of wind speeds for tuning floating feedback, or "all" for all + above-rated wind speeds + + *Default* = [] + :code:`zeta_flp` : Float Flap controller desired damping ratio [-] @@ -895,9 +911,17 @@ These are pass-through parameters for the DISCON.IN file. Use with caution. Cutoff Frequency for first order low-pass filter for blade pitch angle -:code:`Fl_Kp` : Float, s +:code:`Fl_n` : Float, s + Number of Fl_Kp gains in gain scheduling, optional with default of + 1 + +:code:`Fl_Kp` : Array of Floats Nacelle velocity proportional feedback gain +:code:`Fl_U` : Array of Floats + Wind speeds for scheduling Fl_Kp, optional if Fl_Kp is single + value [m/s] + :code:`Flp_Angle` : Float, rad Initial or steady state flap angle @@ -928,6 +952,14 @@ These are pass-through parameters for the DISCON.IN file. Use with caution. :code:`Ind_YawRate` : Float The column in OL_Filename that contains the generator torque in Nm +:code:`Ind_CableControl` : Array of Floats + The column in OL_Filename that contains the cable control inputs + in m + +:code:`Ind_StructControl` : Array of Floats + The column in OL_Filename that contains the structural control + inputs in various units + :code:`DLL_FileName` : String Name/location of the dynamic library {.dll [Windows] or .so [Linux]} in the Bladed-DLL format @@ -947,6 +979,8 @@ These are pass-through parameters for the DISCON.IN file. Use with caution. :code:`PF_Offsets` : Array of Floats Pitch angle offsets for each blade (array with length of 3) + *Default* = [0, 0, 0] + :code:`CC_Group_N` : Float Number of cable control groups @@ -973,6 +1007,46 @@ These are pass-through parameters for the DISCON.IN file. Use with caution. *Default* = [0] +:code:`AWC_Mode` : Float + Active wake control mode {0 - not used, 1 - complex number method, + 2 - Coleman transformation method} + + *Default* = 0 + + *Minimum* = 0 *Maximum* = 2 + + +:code:`AWC_NumModes` : Float, rad + Number of AWC modes + + *Default* = 1 + +:code:`AWC_n` : Array of Floats + AWC azimuthal number (only used in complex number method) + + *Default* = [1] + +:code:`AWC_harmonic` : Array of Integers + AWC Coleman transform harmonic (only used in Coleman transform + method) + + *Default* = [1] + +:code:`AWC_freq` : Array of Floats + AWC frequency [Hz] + + *Default* = [0.05] + +:code:`AWC_amp` : Array of Floats + AWC amplitude [deg] + + *Default* = [1.0] + +:code:`AWC_clockangle` : Array of Floats + AWC clock angle [deg] + + *Default* = [0] + linmodel_tuning From d9547ddcdc0466a6d830b35243142c3607dbfe03 Mon Sep 17 00:00:00 2001 From: dzalkind Date: Mon, 24 Jul 2023 14:28:48 -0600 Subject: [PATCH 107/224] Fix relative Cp filepaths --- ROSCO_toolbox/ofTools/fast_io/update_discons.py | 8 +++++++- 1 file changed, 7 insertions(+), 1 deletion(-) diff --git a/ROSCO_toolbox/ofTools/fast_io/update_discons.py b/ROSCO_toolbox/ofTools/fast_io/update_discons.py index 6c8b6271..72abb605 100644 --- a/ROSCO_toolbox/ofTools/fast_io/update_discons.py +++ b/ROSCO_toolbox/ofTools/fast_io/update_discons.py @@ -15,10 +15,16 @@ def update_discons(tune_to_test_map): if not isinstance(tune_to_test_map[tuning_yaml],list): tune_to_test_map[tuning_yaml] = [tune_to_test_map[tuning_yaml]] + # Handle relative directory to Cp file + yaml_dir = os.path.dirname(tuning_yaml) + cp_filename = os.path.relpath( + os.path.join(yaml_dir,path_params['rotor_performance_filename']), + os.path.join(yaml_dir,path_params['FAST_directory'])) + discon_in_files = [f for f in tune_to_test_map[tuning_yaml]] for discon in discon_in_files: write_DISCON( turbine,controller, param_file=discon, - txt_filename=path_params['rotor_performance_filename'] + txt_filename=cp_filename ) From 178217bb1d30ca37b01f8ed9af78e7f965ba3bae Mon Sep 17 00:00:00 2001 From: dzalkind Date: Mon, 24 Jul 2023 15:11:21 -0600 Subject: [PATCH 108/224] Regenerate registry, inputs --- ROSCO/src/ROSCO_IO.f90 | 208 +++++++++--------- Test_Cases/BAR_10/BAR_10_DISCON.IN | 12 +- .../DISCON-UMaineSemi.IN | 12 +- Test_Cases/NREL-5MW/DISCON.IN | 12 +- .../NREL_2p8_127/NREL-2p8-127_DISCON.IN | 12 +- 5 files changed, 143 insertions(+), 113 deletions(-) diff --git a/ROSCO/src/ROSCO_IO.f90 b/ROSCO/src/ROSCO_IO.f90 index 0d7a492e..84742b77 100644 --- a/ROSCO/src/ROSCO_IO.f90 +++ b/ROSCO/src/ROSCO_IO.f90 @@ -64,6 +64,8 @@ SUBROUTINE WriteRestartFile(LocalVar, CntrPar, ErrVar, objInst, RootName, size_a WRITE( Un, IOSTAT=ErrStat) LocalVar%FA_PitCom(2) WRITE( Un, IOSTAT=ErrStat) LocalVar%FA_PitCom(3) WRITE( Un, IOSTAT=ErrStat) LocalVar%RotSpeedF + WRITE( Un, IOSTAT=ErrStat) LocalVar%VS_RefSpd + WRITE( Un, IOSTAT=ErrStat) LocalVar%PC_RefSpd WRITE( Un, IOSTAT=ErrStat) LocalVar%GenSpeedF WRITE( Un, IOSTAT=ErrStat) LocalVar%GenTq WRITE( Un, IOSTAT=ErrStat) LocalVar%GenTqMeas @@ -334,6 +336,8 @@ SUBROUTINE ReadRestartFile(avrSWAP, LocalVar, CntrPar, objInst, PerfData, RootNa READ( Un, IOSTAT=ErrStat) LocalVar%FA_PitCom(2) READ( Un, IOSTAT=ErrStat) LocalVar%FA_PitCom(3) READ( Un, IOSTAT=ErrStat) LocalVar%RotSpeedF + READ( Un, IOSTAT=ErrStat) LocalVar%VS_RefSpd + READ( Un, IOSTAT=ErrStat) LocalVar%PC_RefSpd READ( Un, IOSTAT=ErrStat) LocalVar%GenSpeedF READ( Un, IOSTAT=ErrStat) LocalVar%GenTq READ( Un, IOSTAT=ErrStat) LocalVar%GenTqMeas @@ -623,7 +627,7 @@ SUBROUTINE Debug(LocalVar, CntrPar, DebugVar, ErrVar, avrSWAP, RootName, size_av '[rad/s]', '[rad/s]', '[m/s]', '[rad]', '[rad]', & '[N/A]', '[N/A]', '[N/A]', '[N/A]', '[rad/s]', & '[deg]', '[deg]', '[deg]', '[N/A]'] - nLocalVars = 101 + nLocalVars = 103 Allocate(LocalVarOutData(nLocalVars)) Allocate(LocalVarOutStrings(nLocalVars)) LocalVarOutData(1) = LocalVar%iStatus @@ -647,107 +651,109 @@ SUBROUTINE Debug(LocalVar, CntrPar, DebugVar, ErrVar, avrSWAP, RootName, size_av LocalVarOutData(19) = LocalVar%FA_AccHPFI LocalVarOutData(20) = LocalVar%FA_PitCom(1) LocalVarOutData(21) = LocalVar%RotSpeedF - LocalVarOutData(22) = LocalVar%GenSpeedF - LocalVarOutData(23) = LocalVar%GenTq - LocalVarOutData(24) = LocalVar%GenTqMeas - LocalVarOutData(25) = LocalVar%GenArTq - LocalVarOutData(26) = LocalVar%GenBrTq - LocalVarOutData(27) = LocalVar%IPC_PitComF(1) - LocalVarOutData(28) = LocalVar%PC_KP - LocalVarOutData(29) = LocalVar%PC_KI - LocalVarOutData(30) = LocalVar%PC_KD - LocalVarOutData(31) = LocalVar%PC_TF - LocalVarOutData(32) = LocalVar%PC_MaxPit - LocalVarOutData(33) = LocalVar%PC_MinPit - LocalVarOutData(34) = LocalVar%PC_PitComT - LocalVarOutData(35) = LocalVar%PC_PitComT_Last - LocalVarOutData(36) = LocalVar%PC_PitComTF - LocalVarOutData(37) = LocalVar%PC_PitComT_IPC(1) - LocalVarOutData(38) = LocalVar%PC_PwrErr - LocalVarOutData(39) = LocalVar%PC_SpdErr - LocalVarOutData(40) = LocalVar%IPC_AxisTilt_1P - LocalVarOutData(41) = LocalVar%IPC_AxisYaw_1P - LocalVarOutData(42) = LocalVar%IPC_AxisTilt_2P - LocalVarOutData(43) = LocalVar%IPC_AxisYaw_2P - LocalVarOutData(44) = LocalVar%axisTilt_1P - LocalVarOutData(45) = LocalVar%axisYaw_1P - LocalVarOutData(46) = LocalVar%axisYawF_1P - LocalVarOutData(47) = LocalVar%axisTilt_2P - LocalVarOutData(48) = LocalVar%axisYaw_2P - LocalVarOutData(49) = LocalVar%axisYawF_2P - LocalVarOutData(50) = LocalVar%IPC_KI(1) - LocalVarOutData(51) = LocalVar%IPC_KP(1) - LocalVarOutData(52) = LocalVar%IPC_IntSat - LocalVarOutData(53) = LocalVar%PC_State - LocalVarOutData(54) = LocalVar%PitCom(1) - LocalVarOutData(55) = LocalVar%PitComAct(1) - LocalVarOutData(56) = LocalVar%SS_DelOmegaF - LocalVarOutData(57) = LocalVar%TestType - LocalVarOutData(58) = LocalVar%Kp_Float - LocalVarOutData(59) = LocalVar%VS_MaxTq - LocalVarOutData(60) = LocalVar%VS_LastGenTrq - LocalVarOutData(61) = LocalVar%VS_LastGenPwr - LocalVarOutData(62) = LocalVar%VS_MechGenPwr - LocalVarOutData(63) = LocalVar%VS_SpdErrAr - LocalVarOutData(64) = LocalVar%VS_SpdErrBr - LocalVarOutData(65) = LocalVar%VS_SpdErr - LocalVarOutData(66) = LocalVar%VS_State - LocalVarOutData(67) = LocalVar%VS_Rgn3Pitch - LocalVarOutData(68) = LocalVar%WE_Vw - LocalVarOutData(69) = LocalVar%WE_Vw_F - LocalVarOutData(70) = LocalVar%WE_VwI - LocalVarOutData(71) = LocalVar%WE_VwIdot - LocalVarOutData(72) = LocalVar%VS_LastGenTrqF - LocalVarOutData(73) = LocalVar%Fl_PitCom - LocalVarOutData(74) = LocalVar%NACIMU_FA_AccF - LocalVarOutData(75) = LocalVar%FA_AccF - LocalVarOutData(76) = LocalVar%PtfmTDX - LocalVarOutData(77) = LocalVar%PtfmTDY - LocalVarOutData(78) = LocalVar%PtfmTDZ - LocalVarOutData(79) = LocalVar%PtfmRDX - LocalVarOutData(80) = LocalVar%PtfmRDY - LocalVarOutData(81) = LocalVar%PtfmRDZ - LocalVarOutData(82) = LocalVar%PtfmTVX - LocalVarOutData(83) = LocalVar%PtfmTVY - LocalVarOutData(84) = LocalVar%PtfmTVZ - LocalVarOutData(85) = LocalVar%PtfmRVX - LocalVarOutData(86) = LocalVar%PtfmRVY - LocalVarOutData(87) = LocalVar%PtfmRVZ - LocalVarOutData(88) = LocalVar%PtfmTAX - LocalVarOutData(89) = LocalVar%PtfmTAY - LocalVarOutData(90) = LocalVar%PtfmTAZ - LocalVarOutData(91) = LocalVar%PtfmRAX - LocalVarOutData(92) = LocalVar%PtfmRAY - LocalVarOutData(93) = LocalVar%PtfmRAZ - LocalVarOutData(94) = LocalVar%CC_DesiredL(1) - LocalVarOutData(95) = LocalVar%CC_ActuatedL(1) - LocalVarOutData(96) = LocalVar%CC_ActuatedDL(1) - LocalVarOutData(97) = LocalVar%StC_Input(1) - LocalVarOutData(98) = LocalVar%Flp_Angle(1) - LocalVarOutData(99) = LocalVar%RootMyb_Last(1) - LocalVarOutData(100) = LocalVar%ACC_INFILE_SIZE - LocalVarOutData(101) = LocalVar%AWC_complexangle(1) + LocalVarOutData(22) = LocalVar%VS_RefSpd + LocalVarOutData(23) = LocalVar%PC_RefSpd + LocalVarOutData(24) = LocalVar%GenSpeedF + LocalVarOutData(25) = LocalVar%GenTq + LocalVarOutData(26) = LocalVar%GenTqMeas + LocalVarOutData(27) = LocalVar%GenArTq + LocalVarOutData(28) = LocalVar%GenBrTq + LocalVarOutData(29) = LocalVar%IPC_PitComF(1) + LocalVarOutData(30) = LocalVar%PC_KP + LocalVarOutData(31) = LocalVar%PC_KI + LocalVarOutData(32) = LocalVar%PC_KD + LocalVarOutData(33) = LocalVar%PC_TF + LocalVarOutData(34) = LocalVar%PC_MaxPit + LocalVarOutData(35) = LocalVar%PC_MinPit + LocalVarOutData(36) = LocalVar%PC_PitComT + LocalVarOutData(37) = LocalVar%PC_PitComT_Last + LocalVarOutData(38) = LocalVar%PC_PitComTF + LocalVarOutData(39) = LocalVar%PC_PitComT_IPC(1) + LocalVarOutData(40) = LocalVar%PC_PwrErr + LocalVarOutData(41) = LocalVar%PC_SpdErr + LocalVarOutData(42) = LocalVar%IPC_AxisTilt_1P + LocalVarOutData(43) = LocalVar%IPC_AxisYaw_1P + LocalVarOutData(44) = LocalVar%IPC_AxisTilt_2P + LocalVarOutData(45) = LocalVar%IPC_AxisYaw_2P + LocalVarOutData(46) = LocalVar%axisTilt_1P + LocalVarOutData(47) = LocalVar%axisYaw_1P + LocalVarOutData(48) = LocalVar%axisYawF_1P + LocalVarOutData(49) = LocalVar%axisTilt_2P + LocalVarOutData(50) = LocalVar%axisYaw_2P + LocalVarOutData(51) = LocalVar%axisYawF_2P + LocalVarOutData(52) = LocalVar%IPC_KI(1) + LocalVarOutData(53) = LocalVar%IPC_KP(1) + LocalVarOutData(54) = LocalVar%IPC_IntSat + LocalVarOutData(55) = LocalVar%PC_State + LocalVarOutData(56) = LocalVar%PitCom(1) + LocalVarOutData(57) = LocalVar%PitComAct(1) + LocalVarOutData(58) = LocalVar%SS_DelOmegaF + LocalVarOutData(59) = LocalVar%TestType + LocalVarOutData(60) = LocalVar%Kp_Float + LocalVarOutData(61) = LocalVar%VS_MaxTq + LocalVarOutData(62) = LocalVar%VS_LastGenTrq + LocalVarOutData(63) = LocalVar%VS_LastGenPwr + LocalVarOutData(64) = LocalVar%VS_MechGenPwr + LocalVarOutData(65) = LocalVar%VS_SpdErrAr + LocalVarOutData(66) = LocalVar%VS_SpdErrBr + LocalVarOutData(67) = LocalVar%VS_SpdErr + LocalVarOutData(68) = LocalVar%VS_State + LocalVarOutData(69) = LocalVar%VS_Rgn3Pitch + LocalVarOutData(70) = LocalVar%WE_Vw + LocalVarOutData(71) = LocalVar%WE_Vw_F + LocalVarOutData(72) = LocalVar%WE_VwI + LocalVarOutData(73) = LocalVar%WE_VwIdot + LocalVarOutData(74) = LocalVar%VS_LastGenTrqF + LocalVarOutData(75) = LocalVar%Fl_PitCom + LocalVarOutData(76) = LocalVar%NACIMU_FA_AccF + LocalVarOutData(77) = LocalVar%FA_AccF + LocalVarOutData(78) = LocalVar%PtfmTDX + LocalVarOutData(79) = LocalVar%PtfmTDY + LocalVarOutData(80) = LocalVar%PtfmTDZ + LocalVarOutData(81) = LocalVar%PtfmRDX + LocalVarOutData(82) = LocalVar%PtfmRDY + LocalVarOutData(83) = LocalVar%PtfmRDZ + LocalVarOutData(84) = LocalVar%PtfmTVX + LocalVarOutData(85) = LocalVar%PtfmTVY + LocalVarOutData(86) = LocalVar%PtfmTVZ + LocalVarOutData(87) = LocalVar%PtfmRVX + LocalVarOutData(88) = LocalVar%PtfmRVY + LocalVarOutData(89) = LocalVar%PtfmRVZ + LocalVarOutData(90) = LocalVar%PtfmTAX + LocalVarOutData(91) = LocalVar%PtfmTAY + LocalVarOutData(92) = LocalVar%PtfmTAZ + LocalVarOutData(93) = LocalVar%PtfmRAX + LocalVarOutData(94) = LocalVar%PtfmRAY + LocalVarOutData(95) = LocalVar%PtfmRAZ + LocalVarOutData(96) = LocalVar%CC_DesiredL(1) + LocalVarOutData(97) = LocalVar%CC_ActuatedL(1) + LocalVarOutData(98) = LocalVar%CC_ActuatedDL(1) + LocalVarOutData(99) = LocalVar%StC_Input(1) + LocalVarOutData(100) = LocalVar%Flp_Angle(1) + LocalVarOutData(101) = LocalVar%RootMyb_Last(1) + LocalVarOutData(102) = LocalVar%ACC_INFILE_SIZE + LocalVarOutData(103) = LocalVar%AWC_complexangle(1) LocalVarOutStrings = [CHARACTER(15) :: 'iStatus', 'Time', 'DT', 'VS_GenPwr', 'GenSpeed', & 'RotSpeed', 'NacHeading', 'NacVane', 'HorWindV', 'rootMOOP', & 'rootMOOPF', 'BlPitch', 'BlPitchCMeas', 'Azimuth', 'NumBl', & 'FA_Acc', 'NacIMU_FA_Acc', 'FA_AccHPF', 'FA_AccHPFI', 'FA_PitCom', & - 'RotSpeedF', 'GenSpeedF', 'GenTq', 'GenTqMeas', 'GenArTq', & - 'GenBrTq', 'IPC_PitComF', 'PC_KP', 'PC_KI', 'PC_KD', & - 'PC_TF', 'PC_MaxPit', 'PC_MinPit', 'PC_PitComT', 'PC_PitComT_Last', & - 'PC_PitComTF', 'PC_PitComT_IPC', 'PC_PwrErr', 'PC_SpdErr', 'IPC_AxisTilt_1P', & - 'IPC_AxisYaw_1P', 'IPC_AxisTilt_2P', 'IPC_AxisYaw_2P', 'axisTilt_1P', 'axisYaw_1P', & - 'axisYawF_1P', 'axisTilt_2P', 'axisYaw_2P', 'axisYawF_2P', 'IPC_KI', & - 'IPC_KP', 'IPC_IntSat', 'PC_State', 'PitCom', 'PitComAct', & - 'SS_DelOmegaF', 'TestType', 'Kp_Float', 'VS_MaxTq', 'VS_LastGenTrq', & - 'VS_LastGenPwr', 'VS_MechGenPwr', 'VS_SpdErrAr', 'VS_SpdErrBr', 'VS_SpdErr', & - 'VS_State', 'VS_Rgn3Pitch', 'WE_Vw', 'WE_Vw_F', 'WE_VwI', & - 'WE_VwIdot', 'VS_LastGenTrqF', 'Fl_PitCom', 'NACIMU_FA_AccF', 'FA_AccF', & - 'PtfmTDX', 'PtfmTDY', 'PtfmTDZ', 'PtfmRDX', 'PtfmRDY', & - 'PtfmRDZ', 'PtfmTVX', 'PtfmTVY', 'PtfmTVZ', 'PtfmRVX', & - 'PtfmRVY', 'PtfmRVZ', 'PtfmTAX', 'PtfmTAY', 'PtfmTAZ', & - 'PtfmRAX', 'PtfmRAY', 'PtfmRAZ', 'CC_DesiredL', 'CC_ActuatedL', & - 'CC_ActuatedDL', 'StC_Input', 'Flp_Angle', 'RootMyb_Last', 'ACC_INFILE_SIZE', & - 'AWC_complexangle'] + 'RotSpeedF', 'VS_RefSpd', 'PC_RefSpd', 'GenSpeedF', 'GenTq', & + 'GenTqMeas', 'GenArTq', 'GenBrTq', 'IPC_PitComF', 'PC_KP', & + 'PC_KI', 'PC_KD', 'PC_TF', 'PC_MaxPit', 'PC_MinPit', & + 'PC_PitComT', 'PC_PitComT_Last', 'PC_PitComTF', 'PC_PitComT_IPC', 'PC_PwrErr', & + 'PC_SpdErr', 'IPC_AxisTilt_1P', 'IPC_AxisYaw_1P', 'IPC_AxisTilt_2P', 'IPC_AxisYaw_2P', & + 'axisTilt_1P', 'axisYaw_1P', 'axisYawF_1P', 'axisTilt_2P', 'axisYaw_2P', & + 'axisYawF_2P', 'IPC_KI', 'IPC_KP', 'IPC_IntSat', 'PC_State', & + 'PitCom', 'PitComAct', 'SS_DelOmegaF', 'TestType', 'Kp_Float', & + 'VS_MaxTq', 'VS_LastGenTrq', 'VS_LastGenPwr', 'VS_MechGenPwr', 'VS_SpdErrAr', & + 'VS_SpdErrBr', 'VS_SpdErr', 'VS_State', 'VS_Rgn3Pitch', 'WE_Vw', & + 'WE_Vw_F', 'WE_VwI', 'WE_VwIdot', 'VS_LastGenTrqF', 'Fl_PitCom', & + 'NACIMU_FA_AccF', 'FA_AccF', 'PtfmTDX', 'PtfmTDY', 'PtfmTDZ', & + 'PtfmRDX', 'PtfmRDY', 'PtfmRDZ', 'PtfmTVX', 'PtfmTVY', & + 'PtfmTVZ', 'PtfmRVX', 'PtfmRVY', 'PtfmRVZ', 'PtfmTAX', & + 'PtfmTAY', 'PtfmTAZ', 'PtfmRAX', 'PtfmRAY', 'PtfmRAZ', & + 'CC_DesiredL', 'CC_ActuatedL', 'CC_ActuatedDL', 'StC_Input', 'Flp_Angle', & + 'RootMyb_Last', 'ACC_INFILE_SIZE', 'AWC_complexangle'] ! Initialize debug file IF ((LocalVar%iStatus == 0) .OR. (LocalVar%iStatus == -9)) THEN ! .TRUE. if we're on the first call to the DLL IF (CntrPar%LoggingLevel > 0) THEN @@ -762,8 +768,8 @@ SUBROUTINE Debug(LocalVar, CntrPar, DebugVar, ErrVar, avrSWAP, RootName, size_av CALL GetNewUnit(UnDb2, ErrVar) OPEN(unit=UnDb2, FILE=TRIM(RootName)//'.RO.dbg2') WRITE(UnDb2, *) 'Generated on '//CurDate()//' at '//CurTime()//' using ROSCO-'//TRIM(rosco_version) - WRITE(UnDb2, '(102(a20,TR5:))') 'Time', LocalVarOutStrings - WRITE(UnDb2, '(102(a20,TR5:))') + WRITE(UnDb2, '(104(a20,TR5:))') 'Time', LocalVarOutStrings + WRITE(UnDb2, '(104(a20,TR5:))') END IF IF (CntrPar%LoggingLevel > 2) THEN @@ -820,7 +826,7 @@ SUBROUTINE Debug(LocalVar, CntrPar, DebugVar, ErrVar, avrSWAP, RootName, size_av END DO ! Write debug files - FmtDat = "(F20.5,TR5,101(ES20.5E2,TR5:))" ! The format of the debugging data + FmtDat = "(F20.5,TR5,103(ES20.5E2,TR5:))" ! The format of the debugging data IF(CntrPar%LoggingLevel > 0) THEN WRITE (UnDb, TRIM(FmtDat)) LocalVar%Time, DebugOutData END IF diff --git a/Test_Cases/BAR_10/BAR_10_DISCON.IN b/Test_Cases/BAR_10/BAR_10_DISCON.IN index b3636e42..0d859e4c 100644 --- a/Test_Cases/BAR_10/BAR_10_DISCON.IN +++ b/Test_Cases/BAR_10/BAR_10_DISCON.IN @@ -1,5 +1,5 @@ ! Controller parameter input file for the BAR_10 wind turbine -! - File written using ROSCO version 2.8.0 controller tuning logic on 06/13/23 +! - File written using ROSCO version 2.8.0 controller tuning logic on 07/24/23 !------- DEBUG ------------------------------------------------------------ 1 ! LoggingLevel - (0: write no debug files, 1: write standard output .dbg-file, 2: LoggingLevel 1 + ROSCO LocalVars (.dbg2) 3: LoggingLevel 2 + complete avrSWAP-array (.dbg3)) @@ -13,6 +13,7 @@ 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} +0 ! PRC_Mode - Power reference tracking mode{0: use standard rotor speed set points, 1: use PRC rotor speed setpoints} 2 ! WE_Mode - Wind speed estimator mode {0: One-second low pass filtered hub height wind speed, 1: Immersion and Invariance Estimator, 2: Extended Kalman Filter} 1 ! PS_Mode - Pitch saturation mode {0: no pitch saturation, 1: implement pitch saturation} 0 ! SD_Mode - Shutdown mode {0: no shutdown procedure, 1: pitch to max pitch at shutdown} @@ -84,6 +85,11 @@ 1.00000 ! SS_VSGain - Variable speed torque controller setpoint smoother gain, [-]. 0.00100 ! SS_PCGain - Collective pitch controller setpoint smoother gain, [-]. +!------- POWER REFERENCE TRACKING -------------------------------------- +2 ! PRC_n - Number of elements in PRC_WindSpeeds and PRC_RotorSpeeds array +3.000 25.000 ! PRC_WindSpeeds - Array of wind speeds used in rotor speed vs. wind speed lookup table [m/s]. +0.792 0.792 ! PRC_RotorSpeeds - Array of rotor speeds corresponding to PRC_WindSpeeds [rad/s]. + !------- WIND SPEED ESTIMATOR --------------------------------------------- 102.996 ! WE_BladeRadius - Blade length (distance from hub center to blade tip), [m] 1 ! WE_CP_n - Amount of parameters in the Cp array @@ -114,8 +120,8 @@ !------- MINIMUM PITCH SATURATION ------------------------------------------- 60 ! PS_BldPitchMin_N - Number of values in minimum blade pitch lookup table (should equal number of values in PS_WindSpeeds and PS_BldPitchMin) -3.0000 3.1818 3.3637 3.5455 3.7274 3.9092 4.0911 4.2729 4.4548 4.6366 4.8185 5.0003 5.1822 5.3640 5.5459 5.7277 5.9096 6.0914 6.2732 6.4551 6.6369 6.8188 7.0006 7.1825 7.3643 7.5462 7.7280 7.9099 8.0917 8.2736 8.8311 9.3887 9.9462 10.5038 11.0613 11.6188 12.1764 12.7339 13.2915 13.8490 14.4066 14.9641 15.5217 16.0792 16.6368 17.1943 17.7519 18.3094 18.8670 19.4245 19.9821 20.5396 21.0972 21.6547 22.2123 22.7698 23.3274 23.8849 24.4425 25.0000 ! PS_WindSpeeds - Wind speeds corresponding to minimum blade pitch angles [m/s] --0.01505486 -0.01505486 -0.01505486 -0.01505486 -0.01505486 -0.01505486 -0.01505486 -0.01505486 -0.01505486 -0.01505486 -0.01505486 -0.01505486 -0.01505486 -0.01505486 -0.01505486 -0.01505486 -0.01505486 -0.01505486 -0.01505486 -0.01505486 -0.01505486 -0.01505486 -0.01505486 -0.01505486 -0.01247538 0.00009416 0.01064594 0.02025612 0.02875892 0.04130468 0.05575026 0.06941162 0.08245994 0.09516301 0.10759186 0.11974680 0.13166674 0.14343508 0.15503135 0.16644975 0.17776272 0.18893241 0.19997037 0.21092550 0.22173526 0.23245676 0.24309225 0.25359679 0.26404201 0.27436979 0.28461736 0.29478565 0.30484212 0.31485020 0.32473305 0.33456481 0.34429551 0.35395031 0.36352600 0.37300643 ! PS_BldPitchMin - Minimum blade pitch angles [rad] +3.000 3.182 3.364 3.546 3.727 3.909 4.091 4.273 4.455 4.637 4.818 5.000 5.182 5.364 5.546 5.728 5.910 6.091 6.273 6.455 6.637 6.819 7.001 7.182 7.364 7.546 7.728 7.910 8.092 8.274 8.831 9.389 9.946 10.504 11.061 11.619 12.176 12.734 13.291 13.849 14.407 14.964 15.522 16.079 16.637 17.194 17.752 18.309 18.867 19.425 19.982 20.540 21.097 21.655 22.212 22.770 23.327 23.885 24.442 25.000 ! PS_WindSpeeds - Wind speeds corresponding to minimum blade pitch angles [m/s] +-0.015 -0.015 -0.015 -0.015 -0.015 -0.015 -0.015 -0.015 -0.015 -0.015 -0.015 -0.015 -0.015 -0.015 -0.015 -0.015 -0.015 -0.015 -0.015 -0.015 -0.015 -0.015 -0.015 -0.015 -0.012 0.000 0.011 0.020 0.029 0.041 0.056 0.069 0.082 0.095 0.108 0.120 0.132 0.143 0.155 0.166 0.178 0.189 0.200 0.211 0.222 0.232 0.243 0.254 0.264 0.274 0.285 0.295 0.305 0.315 0.325 0.335 0.344 0.354 0.364 0.373 ! PS_BldPitchMin - Minimum blade pitch angles [rad] !------- SHUTDOWN ----------------------------------------------------------- 0.698100000000 ! SD_MaxPit - Maximum blade pitch angle to initiate shutdown, [rad] diff --git a/Test_Cases/IEA-15-240-RWT-UMaineSemi/DISCON-UMaineSemi.IN b/Test_Cases/IEA-15-240-RWT-UMaineSemi/DISCON-UMaineSemi.IN index be780b4c..5394d5d0 100644 --- a/Test_Cases/IEA-15-240-RWT-UMaineSemi/DISCON-UMaineSemi.IN +++ b/Test_Cases/IEA-15-240-RWT-UMaineSemi/DISCON-UMaineSemi.IN @@ -1,5 +1,5 @@ ! Controller parameter input file for the IEA-15-240-RWT-UMaineSemi wind turbine -! - File written using ROSCO version 2.8.0 controller tuning logic on 06/13/23 +! - File written using ROSCO version 2.8.0 controller tuning logic on 07/24/23 !------- DEBUG ------------------------------------------------------------ 2 ! LoggingLevel - (0: write no debug files, 1: write standard output .dbg-file, 2: LoggingLevel 1 + ROSCO LocalVars (.dbg2) 3: LoggingLevel 2 + complete avrSWAP-array (.dbg3)) @@ -13,6 +13,7 @@ 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} +0 ! PRC_Mode - Power reference tracking mode{0: use standard rotor speed set points, 1: use PRC rotor speed setpoints} 2 ! WE_Mode - Wind speed estimator mode {0: One-second low pass filtered hub height wind speed, 1: Immersion and Invariance Estimator, 2: Extended Kalman Filter} 1 ! PS_Mode - Pitch saturation mode {0: no pitch saturation, 1: implement pitch saturation} 0 ! SD_Mode - Shutdown mode {0: no shutdown procedure, 1: pitch to max pitch at shutdown} @@ -84,6 +85,11 @@ 1.00000 ! SS_VSGain - Variable speed torque controller setpoint smoother gain, [-]. 0.00100 ! SS_PCGain - Collective pitch controller setpoint smoother gain, [-]. +!------- POWER REFERENCE TRACKING -------------------------------------- +2 ! PRC_n - Number of elements in PRC_WindSpeeds and PRC_RotorSpeeds array +3.000 25.000 ! PRC_WindSpeeds - Array of wind speeds used in rotor speed vs. wind speed lookup table [m/s]. +0.792 0.792 ! PRC_RotorSpeeds - Array of rotor speeds corresponding to PRC_WindSpeeds [rad/s]. + !------- WIND SPEED ESTIMATOR --------------------------------------------- 120.000 ! WE_BladeRadius - Blade length (distance from hub center to blade tip), [m] 1 ! WE_CP_n - Amount of parameters in the Cp array @@ -114,8 +120,8 @@ !------- MINIMUM PITCH SATURATION ------------------------------------------- 60 ! PS_BldPitchMin_N - Number of values in minimum blade pitch lookup table (should equal number of values in PS_WindSpeeds and PS_BldPitchMin) -3.0000 3.2669 3.5338 3.8007 4.0676 4.3345 4.6014 4.8683 5.1352 5.4021 5.6690 5.9359 6.2028 6.4697 6.7366 7.0034 7.2703 7.5372 7.8041 8.0710 8.3379 8.6048 8.8717 9.1386 9.4055 9.6724 9.9393 10.2062 10.4731 10.7400 11.2153 11.6907 12.1660 12.6413 13.1167 13.5920 14.0673 14.5427 15.0180 15.4933 15.9687 16.4440 16.9193 17.3947 17.8700 18.3453 18.8207 19.2960 19.7713 20.2467 20.7220 21.1973 21.6727 22.1480 22.6233 23.0987 23.5740 24.0493 24.5247 25.0000 ! PS_WindSpeeds - Wind speeds corresponding to minimum blade pitch angles [m/s] -0.05997374 0.05997374 0.05997374 0.05997374 0.05997374 0.05995230 0.05568017 0.05139305 0.04630957 0.04053154 0.03444871 0.02774193 0.02083682 0.01377992 0.00660717 0.00000000 0.00000000 0.00000000 0.00000000 0.00000000 0.00000000 0.00000000 0.00000000 0.00000000 0.00000000 0.00798358 0.02222567 0.03475505 0.04563791 0.05328450 0.06405592 0.07436594 0.08427713 0.09385932 0.10323575 0.11234777 0.12134295 0.13011531 0.13881511 0.14732690 0.15578898 0.16409463 0.17235500 0.18049466 0.18858365 0.19658691 0.20452181 0.21241204 0.22021131 0.22800500 0.23567545 0.24336643 0.25094186 0.25851588 0.26602564 0.27348266 0.28093357 0.28828297 0.29566389 0.30293290 ! PS_BldPitchMin - Minimum blade pitch angles [rad] +3.000 3.267 3.534 3.801 4.068 4.334 4.601 4.868 5.135 5.402 5.669 5.936 6.203 6.470 6.737 7.003 7.270 7.537 7.804 8.071 8.338 8.605 8.872 9.139 9.406 9.672 9.939 10.206 10.473 10.740 11.215 11.691 12.166 12.641 13.117 13.592 14.067 14.543 15.018 15.493 15.969 16.444 16.919 17.395 17.870 18.345 18.821 19.296 19.771 20.247 20.722 21.197 21.673 22.148 22.623 23.099 23.574 24.049 24.525 25.000 ! PS_WindSpeeds - Wind speeds corresponding to minimum blade pitch angles [m/s] +0.060 0.060 0.060 0.060 0.060 0.060 0.056 0.051 0.046 0.041 0.034 0.028 0.021 0.014 0.007 0.000 0.000 0.000 0.000 0.000 0.000 0.000 0.000 0.000 0.000 0.008 0.022 0.035 0.046 0.053 0.064 0.074 0.084 0.094 0.103 0.112 0.121 0.130 0.139 0.147 0.156 0.164 0.172 0.180 0.189 0.197 0.205 0.212 0.220 0.228 0.236 0.243 0.251 0.259 0.266 0.273 0.281 0.288 0.296 0.303 ! PS_BldPitchMin - Minimum blade pitch angles [rad] !------- SHUTDOWN ----------------------------------------------------------- 0.698100000000 ! SD_MaxPit - Maximum blade pitch angle to initiate shutdown, [rad] diff --git a/Test_Cases/NREL-5MW/DISCON.IN b/Test_Cases/NREL-5MW/DISCON.IN index 22d049d4..dca8baff 100644 --- a/Test_Cases/NREL-5MW/DISCON.IN +++ b/Test_Cases/NREL-5MW/DISCON.IN @@ -1,5 +1,5 @@ ! Controller parameter input file for the NREL-5MW wind turbine -! - File written using ROSCO version 2.8.0 controller tuning logic on 06/13/23 +! - File written using ROSCO version 2.8.0 controller tuning logic on 07/24/23 !------- DEBUG ------------------------------------------------------------ 1 ! LoggingLevel - (0: write no debug files, 1: write standard output .dbg-file, 2: LoggingLevel 1 + ROSCO LocalVars (.dbg2) 3: LoggingLevel 2 + complete avrSWAP-array (.dbg3)) @@ -13,6 +13,7 @@ 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} +0 ! PRC_Mode - Power reference tracking mode{0: use standard rotor speed set points, 1: use PRC rotor speed setpoints} 2 ! WE_Mode - Wind speed estimator mode {0: One-second low pass filtered hub height wind speed, 1: Immersion and Invariance Estimator, 2: Extended Kalman Filter} 1 ! PS_Mode - Pitch saturation mode {0: no pitch saturation, 1: implement pitch saturation} 0 ! SD_Mode - Shutdown mode {0: no shutdown procedure, 1: pitch to max pitch at shutdown} @@ -84,6 +85,11 @@ 1.00000 ! SS_VSGain - Variable speed torque controller setpoint smoother gain, [-]. 0.00100 ! SS_PCGain - Collective pitch controller setpoint smoother gain, [-]. +!------- POWER REFERENCE TRACKING -------------------------------------- +2 ! PRC_n - Number of elements in PRC_WindSpeeds and PRC_RotorSpeeds array +3.000 25.000 ! PRC_WindSpeeds - Array of wind speeds used in rotor speed vs. wind speed lookup table [m/s]. +0.792 0.792 ! PRC_RotorSpeeds - Array of rotor speeds corresponding to PRC_WindSpeeds [rad/s]. + !------- WIND SPEED ESTIMATOR --------------------------------------------- 63.000 ! WE_BladeRadius - Blade length (distance from hub center to blade tip), [m] 1 ! WE_CP_n - Amount of parameters in the Cp array @@ -114,8 +120,8 @@ !------- MINIMUM PITCH SATURATION ------------------------------------------- 60 ! PS_BldPitchMin_N - Number of values in minimum blade pitch lookup table (should equal number of values in PS_WindSpeeds and PS_BldPitchMin) -3.0000 3.2897 3.5793 3.8690 4.1586 4.4483 4.7379 5.0276 5.3172 5.6069 5.8966 6.1862 6.4759 6.7655 7.0552 7.3448 7.6345 7.9241 8.2138 8.5034 8.7931 9.0828 9.3724 9.6621 9.9517 10.2414 10.5310 10.8207 11.1103 11.4000 11.8533 12.3067 12.7600 13.2133 13.6667 14.1200 14.5733 15.0267 15.4800 15.9333 16.3867 16.8400 17.2933 17.7467 18.2000 18.6533 19.1067 19.5600 20.0133 20.4667 20.9200 21.3733 21.8267 22.2800 22.7333 23.1867 23.6400 24.0933 24.5467 25.0000 ! PS_WindSpeeds - Wind speeds corresponding to minimum blade pitch angles [m/s] -0.00088027 0.00088027 0.00088027 0.00088027 0.00088027 0.00088027 0.00088027 0.00088027 0.00088027 0.00088027 0.00088027 0.00088027 0.00088027 0.00088027 0.00088027 0.00088027 0.00088027 0.00088027 0.00088027 0.00088027 0.00088027 0.00088027 0.00088027 0.00088027 0.00088027 0.01116187 0.02310060 0.03164156 0.03968639 0.04741131 0.05899071 0.07019329 0.08090119 0.09141661 0.10169361 0.11174124 0.12170066 0.13137494 0.14103377 0.15048120 0.15989580 0.16913227 0.17831010 0.18739638 0.19643591 0.20537011 0.21419674 0.22293719 0.23161365 0.24025975 0.24885012 0.25735704 0.26578040 0.27407178 0.28233051 0.29047594 0.29867838 0.30674517 0.31490089 0.32284411 ! PS_BldPitchMin - Minimum blade pitch angles [rad] +3.000 3.290 3.579 3.869 4.159 4.448 4.738 5.028 5.317 5.607 5.897 6.186 6.476 6.766 7.055 7.345 7.634 7.924 8.214 8.503 8.793 9.083 9.372 9.662 9.952 10.241 10.531 10.821 11.110 11.400 11.853 12.307 12.760 13.213 13.667 14.120 14.573 15.027 15.480 15.933 16.387 16.840 17.293 17.747 18.200 18.653 19.107 19.560 20.013 20.467 20.920 21.373 21.827 22.280 22.733 23.187 23.640 24.093 24.547 25.000 ! PS_WindSpeeds - Wind speeds corresponding to minimum blade pitch angles [m/s] +0.001 0.001 0.001 0.001 0.001 0.001 0.001 0.001 0.001 0.001 0.001 0.001 0.001 0.001 0.001 0.001 0.001 0.001 0.001 0.001 0.001 0.001 0.001 0.001 0.001 0.011 0.023 0.032 0.040 0.047 0.059 0.070 0.081 0.091 0.102 0.112 0.122 0.131 0.141 0.150 0.160 0.169 0.178 0.187 0.196 0.205 0.214 0.223 0.232 0.240 0.249 0.257 0.266 0.274 0.282 0.290 0.299 0.307 0.315 0.323 ! PS_BldPitchMin - Minimum blade pitch angles [rad] !------- SHUTDOWN ----------------------------------------------------------- 0.436300000000 ! SD_MaxPit - Maximum blade pitch angle to initiate shutdown, [rad] diff --git a/Test_Cases/NREL_2p8_127/NREL-2p8-127_DISCON.IN b/Test_Cases/NREL_2p8_127/NREL-2p8-127_DISCON.IN index 4366ff44..ed8df9a2 100644 --- a/Test_Cases/NREL_2p8_127/NREL-2p8-127_DISCON.IN +++ b/Test_Cases/NREL_2p8_127/NREL-2p8-127_DISCON.IN @@ -1,5 +1,5 @@ ! Controller parameter input file for the NREL-2p8-127 wind turbine -! - File written using ROSCO version 2.8.0 controller tuning logic on 06/13/23 +! - File written using ROSCO version 2.8.0 controller tuning logic on 07/24/23 !------- DEBUG ------------------------------------------------------------ 2 ! LoggingLevel - (0: write no debug files, 1: write standard output .dbg-file, 2: LoggingLevel 1 + ROSCO LocalVars (.dbg2) 3: LoggingLevel 2 + complete avrSWAP-array (.dbg3)) @@ -13,6 +13,7 @@ 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} +0 ! PRC_Mode - Power reference tracking mode{0: use standard rotor speed set points, 1: use PRC rotor speed setpoints} 2 ! WE_Mode - Wind speed estimator mode {0: One-second low pass filtered hub height wind speed, 1: Immersion and Invariance Estimator, 2: Extended Kalman Filter} 1 ! PS_Mode - Pitch saturation mode {0: no pitch saturation, 1: implement pitch saturation} 0 ! SD_Mode - Shutdown mode {0: no shutdown procedure, 1: pitch to max pitch at shutdown} @@ -84,6 +85,11 @@ 1.00000 ! SS_VSGain - Variable speed torque controller setpoint smoother gain, [-]. 0.00100 ! SS_PCGain - Collective pitch controller setpoint smoother gain, [-]. +!------- POWER REFERENCE TRACKING -------------------------------------- +2 ! PRC_n - Number of elements in PRC_WindSpeeds and PRC_RotorSpeeds array +3.000 25.000 ! PRC_WindSpeeds - Array of wind speeds used in rotor speed vs. wind speed lookup table [m/s]. +0.792 0.792 ! PRC_RotorSpeeds - Array of rotor speeds corresponding to PRC_WindSpeeds [rad/s]. + !------- WIND SPEED ESTIMATOR --------------------------------------------- 63.457 ! WE_BladeRadius - Blade length (distance from hub center to blade tip), [m] 1 ! WE_CP_n - Amount of parameters in the Cp array @@ -114,8 +120,8 @@ !------- MINIMUM PITCH SATURATION ------------------------------------------- 60 ! PS_BldPitchMin_N - Number of values in minimum blade pitch lookup table (should equal number of values in PS_WindSpeeds and PS_BldPitchMin) -3.0000 3.2897 3.5793 3.8690 4.1586 4.4483 4.7379 5.0276 5.3172 5.6069 5.8966 6.1862 6.4759 6.7655 7.0552 7.3448 7.6345 7.9241 8.2138 8.5034 8.7931 9.0828 9.3724 9.6621 9.9517 10.2414 10.5310 10.8207 11.1103 11.4000 11.8533 12.3067 12.7600 13.2133 13.6667 14.1200 14.5733 15.0267 15.4800 15.9333 16.3867 16.8400 17.2933 17.7467 18.2000 18.6533 19.1067 19.5600 20.0133 20.4667 20.9200 21.3733 21.8267 22.2800 22.7333 23.1867 23.6400 24.0933 24.5467 25.0000 ! PS_WindSpeeds - Wind speeds corresponding to minimum blade pitch angles [m/s] -0.00000000 0.00000000 0.00000000 0.00000000 0.00000000 0.00000000 0.00000000 0.00000000 0.00000000 0.00000000 0.00000000 0.00000000 0.00000000 0.00000000 0.00000000 0.00000000 0.00000000 0.00000000 0.00000000 0.00000000 0.00000000 0.00000000 0.00000000 0.01902632 0.03121162 0.04101621 0.04957537 0.05812141 0.06604528 0.07366393 0.08564088 0.09644430 0.10731742 0.11740081 0.12723365 0.13691718 0.14655371 0.15552079 0.16457871 0.17358206 0.18261499 0.19163393 0.20072294 0.20968649 0.21849678 0.22748802 0.23597095 0.24444734 0.25312967 0.26178025 0.27046099 0.27863869 0.28691931 0.29527580 0.30349928 0.31191439 0.32017189 0.32834804 0.33653924 0.34452172 ! PS_BldPitchMin - Minimum blade pitch angles [rad] +3.000 3.290 3.579 3.869 4.159 4.448 4.738 5.028 5.317 5.607 5.897 6.186 6.476 6.766 7.055 7.345 7.634 7.924 8.214 8.503 8.793 9.083 9.372 9.662 9.952 10.241 10.531 10.821 11.110 11.400 11.853 12.307 12.760 13.213 13.667 14.120 14.573 15.027 15.480 15.933 16.387 16.840 17.293 17.747 18.200 18.653 19.107 19.560 20.013 20.467 20.920 21.373 21.827 22.280 22.733 23.187 23.640 24.093 24.547 25.000 ! PS_WindSpeeds - Wind speeds corresponding to minimum blade pitch angles [m/s] +0.000 0.000 0.000 0.000 0.000 0.000 0.000 0.000 0.000 0.000 0.000 0.000 0.000 0.000 0.000 0.000 0.000 0.000 0.000 0.000 0.000 0.000 0.000 0.019 0.031 0.041 0.050 0.058 0.066 0.074 0.086 0.096 0.107 0.117 0.127 0.137 0.147 0.156 0.165 0.174 0.183 0.192 0.201 0.210 0.218 0.227 0.236 0.244 0.253 0.262 0.270 0.279 0.287 0.295 0.303 0.312 0.320 0.328 0.337 0.345 ! PS_BldPitchMin - Minimum blade pitch angles [rad] !------- SHUTDOWN ----------------------------------------------------------- 0.436300000000 ! SD_MaxPit - Maximum blade pitch angle to initiate shutdown, [rad] From c641b54a649cf60b2343a45a9683ee887cab0f7a Mon Sep 17 00:00:00 2001 From: dzalkind <65573423+dzalkind@users.noreply.github.com> Date: Fri, 4 Aug 2023 09:32:23 -0600 Subject: [PATCH 109/224] Rotor Position Control (#255) * testing flag cleanup * Use lv_strings to generate debug output * Revert "testing flag cleanup" This reverts commit 6f295563832413e96347acd82716f9aadac6d46c. * Revert "specify gfortran-10" This reverts commit 4c3154491523bcd542133ca2bce5803cdc94523f. * minor cleanup * Use kind from constants * Add some comments for clarity * put debug in if statements * separate reg tests from oother tests * Fl_Mode>0 * Remove hard coded values * Add filtered signals and WE_Vw to debug varrs * cd for regtest * Check logging level before calling debug * add fl_pitcom and pc_minpit to debugvars * Turn runFAST into a class * Refactor/simplify CaseLibrary * Restart & registry (#99) * Convert WE saved variables to WE type * Put restart flag in localvars * Use saved filter params from LocalVar * save pitcomt last * Move IPC saved variables to localvars * Saved pi controller variables to localvar * Save RootMyb_Last to localvar * ROSCO_IO - initial commit. Include restart and debug functions * Use ROSCO IO and call restart functions * Remove debug from function.f90 * Save ACC Infile info * update for restart capabilities * add rosco_io with restart and debug functions * cleanup debug call * use registry generate types and IO * delete DFController * fix timestep mismatch * remove unnecessaray istatus check * close files * add reg test for restart * add restart option to run_openfast * add testing to CI, ignore generate files * fix fastcall * remove extra commas * specify gfortran-10 * testing flag cleanup * Use lv_strings to generate debug output * Revert "testing flag cleanup" This reverts commit 6f295563832413e96347acd82716f9aadac6d46c. * Revert "specify gfortran-10" This reverts commit 4c3154491523bcd542133ca2bce5803cdc94523f. * minor cleanup * Use kind from constants * Add some comments for clarity * put debug in if statements * separate reg tests from oother tests * Fl_Mode>0 * Remove hard coded values * Add filtered signals and WE_Vw to debug varrs * cd for regtest * Check logging level before calling debug * add fl_pitcom and pc_minpit to debugvars Co-authored-by: dzalkind * Implement initial pitch actuator * Set up steps case * Break up if statement in open loop pitch (#100) * Break up if statement in open loop pitch * Make torque and yaw consistent with pitch: can start after some time * add bld edgewise freq to robust dict_inputs * Add actuator variable * Print first time step in debug outs * Fix FOCAL yaml * Set actuator to 0.25 Hz bandwidth * Fix ccrotor inputs (#104) * remove interpolation of blade chord and twist * rename aerodynblade inputs * Update surface and DISCON.INs * Fix performance table paths * Allow default inputs (#110) * Allow defaults for AeroDyn inputs * Allow AeroDyn inputs to be floats, too * ipc (#105) * remove interpolation of blade chord and twist * rename aerodynblade inputs * Update surface and DISCON.INs * Fix performance table paths * Add proportional control and cleanup IPC * Add IPC and filtered RootMyc to registry * Better logic for filtering RootMOOP and fix notch filter slopes bug * Add cyclic flap conrol * Fix comments in ColemanTransformInverse * Addd IPC_KP to DISCON.IN * Error checking foro flp or ipc * add mutichannel plotting with tuples * add CMakeFiles to gitignore * Add IPC_KP to api changes * numerical qualifiers for error handling * add IPC gains to schema for pass-through ability * fix variable names * fix ipc gain printing bug * make sure IPC_KP is positive * Update Polars to point to coord files * ignore dbg2 files * Add IEA15MW_OL.yaml * update coord reader/writer * expand pitch_initial to 30 degrees * Add example 13 for IPC * Update cp surfaces and DISCONS * add examples to readme * cleanup and streaamline run_examples * Add IPC tuning vars * Allow IPC to command pitch value below peak shaving saturation limit * shorten simulation time * Fix Material parameter path * Update DISCONs again * Fix OL_Input reading * Set wind speed, rotor speed IC in example 14 * Debug OL reading * Add more debugging lines * Add more debugging lines 2 * Clean up, hone in on debug call * Disable logging level * Update discons - resolve conflict * Print when finished with ROSCO * add control packageg * Use PriPath and RootName to name dbg files * Print AvrSWAP * Revert "Use PriPath and RootName to name dbg files" This reverts commit 062fcaa55b3bf42d44f8a3f163aa883ab9552412. * Disable other examples * Print OL inputs * Allow logging level 3 * Print OL inputs * Make example shorter * Print more stuf * Print shape * Revert "Print OL inputs" This reverts commit 8e2a642bb35e46850f579ca4e69ca6d6fc93f4cc. * Update ROSCO Simulink model with IPC example * refactor flap tuning for normalization methods * improved flap controller filtering * delete extra F_FlpCornerFrerq * Update inputs, reader, and writer for OF 3.1.0 * Make sigma default interp type for multi_sigma * Use openfast 3.1.0 in CI * Fix leak...maybe * Use OF 3.1.0 in testing * Use gfotran for compile * Clean up print statements * Re-enable all examples * Update NREL-5MW AD file * Only check airfoil controls if more than one table * Update BAR models * Revert "Use gfotran for compile" This reverts commit 5a6e2b7e30287a09a09781e2ba12f9b578132e1f. * Install pyFAST for CI * Fix some paths in ex12 * Disable example 12 * Fix example 12 linear path, re-enable * Skip compilers install for mac * Try gfortran-9, no compilers * Try gfortran-10, no compilers * Skip windows compile in pytools * Re-enable windows, use gfortran as FC * Unset FC in windows * Set environment for windows when dependencies installed * Try setting environment in installation * Put conditional env setting in correct place * Try in setup again * Break up tasks: Windows vs. not * Update DISCONs * Update docs with new variables * Add example documentation * Update ROSCO Simulink model for 3.1.0 * Make IEA model float again * Reduce IEA timestep * Match DT to checkpoint time Co-authored-by: dzalkind * Increment version number * Bladed docs (#116) * Added image of Bladed control screen setup * Delete Bladed control screen.png * Adding image of Bladed control screen * Add files via upload * Minor edit 1 * Minor change 2 * Minor change 3 * Minor change 4 * Change 6 * Change 7 * Change 8 * Minor change 9 Co-authored-by: nikhar-abbas <40865984+nikhar-abbas@users.noreply.github.com> Co-authored-by: WillC-DNV <100850534+WillC-DNV@users.noreply.github.com> * Update version in API change docs * Bladed readthedocs (#117) * Added image of Bladed control screen setup * Delete Bladed control screen.png * Adding image of Bladed control screen * Add files via upload * Minor edit 1 * Minor change 2 * Minor change 3 * Minor change 4 * Change 6 * Change 7 * Change 8 * Minor change 9 * Tinker with characters in bladed instructions * Add bladed instructions to index * Change bladed toctree label * Do underline stuff * Make toctree label same as file * Remove colons from headers Co-authored-by: nikhar-abbas <40865984+nikhar-abbas@users.noreply.github.com> Co-authored-by: WillC-DNV <100850534+WillC-DNV@users.noreply.github.com> * Update docs to reflect CI process * Regenerate types, IO with registry * Update registry so first timestep is printed * Update inverted notch to move frequency properly * Saturate inv notch corner frequency at 0 * Add tower damper mode flag * Add Azimuth tracking controller in Simulink * Always enable GenDOF, add options for simp_step * Add sweep for IPC gains and FA damper * Fix NumCoords in FAST_writer * sigma + ipc (#125) * cleanup api change table * Update inverted notch to move frequency properly * Saturate inv notch corner frequency at 0 * add sigma function * Use IPC_Vramp for IPC cut-in * Add IPC_Vramp DISCON inputs * update registry * Update DISCONs * Update docs for API change * Fix IPC_Vramp data type * update comments Co-authored-by: dzalkind * Add turbulent case to runFAST/CaseLibrary * Add peak shaving sweep function * Increase default IPC_IntSat, make input parameter in future * Flip Ct and Cq table allocation * Flip Ct and Cq table allocation (#130) * Regen types * Remove print statements used for debugging * Update input files: IEA model has pitch actuator * Add back flap control (no idea when it was deleted) * Update discons, docs with API change * Add user-defined hh case * Fix AddF0 and RayleighDamp in FAST_reader * Pitch Actuator and IPC updates (#123) * Convert WE saved variables to WE type * Put restart flag in localvars * Use saved filter params from LocalVar * save pitcomt last * Move IPC saved variables to localvars * Saved pi controller variables to localvar * Save RootMyb_Last to localvar * ROSCO_IO - initial commit. Include restart and debug functions * Use ROSCO IO and call restart functions * Remove debug from function.f90 * Save ACC Infile info * update for restart capabilities * add rosco_io with restart and debug functions * cleanup debug call * use registry generate types and IO * delete DFController * fix timestep mismatch * remove unnecessaray istatus check * close files * add reg test for restart * add restart option to run_openfast * add testing to CI, ignore generate files * fix fastcall * remove extra commas * specify gfortran-10 * testing flag cleanup * Use lv_strings to generate debug output * Revert "testing flag cleanup" This reverts commit 6f295563832413e96347acd82716f9aadac6d46c. * Revert "specify gfortran-10" This reverts commit 4c3154491523bcd542133ca2bce5803cdc94523f. * minor cleanup * Use kind from constants * Add some comments for clarity * put debug in if statements * separate reg tests from oother tests * Fl_Mode>0 * Remove hard coded values * Add filtered signals and WE_Vw to debug varrs * cd for regtest * Check logging level before calling debug * add fl_pitcom and pc_minpit to debugvars * Turn runFAST into a class * Refactor/simplify CaseLibrary * Implement initial pitch actuator * Set up steps case * Add actuator variable * Print first time step in debug outs * Fix FOCAL yaml * Set actuator to 0.25 Hz bandwidth * ROSCO 2.5.0 (#115) * FOCAL Updates (#64) * Update headers * fix bullets * make uppercase * Update turbine.py (#56) * Update turbine.py This add several lines for fixing the problem of repeated maximum values in the performance tables. This will cause the error (' the length of x and y is different.') of 'interpolate.interp1d.' * Add comments and catch when there are multiple optimal pitch angles Co-authored-by: dzalkind * increment version * Update for OpenFAST v3.0.0 * Update for OpenFAST v3.0.0 * Install OF3.0.0 for tests * update for OF v3.0.0 * add publish to pypi on release * Update to ROSCO v2.3.0 * Update Testing (#58) * Update scripts to run on eagle * Update IEA-15MW semi example: use peak shaving w/ ps_percen=0.8 * Add comparison plots to testing scripts * Update submit script for testing * Update for latest eagle runs * Add future to install dependencies * add TMax to self, define tmin in print_results * run tests in CI * generic ROSCO path * default to overwrite * fix path * import platform * separate run_testing * cleanup, specify lite test * don't run testing in after examples, oops. Co-authored-by: nikhar-abbas <40865984+nikhar-abbas@users.noreply.github.com> Co-authored-by: Nikhar Abbas * increment version * Update for OpenFAST v3.0.0 * Install OF3.0.0 for tests * update for OF v3.0.0 * add publish to pypi on release * Update to ROSCO v2.3.0 * Increment Version, OF3.0 (#57) * increment version * Update for OpenFAST v3.0.0 * Install OF3.0.0 for tests * update for OF v3.0.0 * add publish to pypi on release * Update to ROSCO v2.3.0 * increment version * Update for OpenFAST v3.0.0 * Install OF3.0.0 for tests * update for OF v3.0.0 * add publish to pypi on release * Update to ROSCO v2.3.0 * add ROSCO without submodule * move ROSCO source to ROSCO folder * Move cmake-related files to ROSCO * Add back pesky ErrVar * Remove parameters_files * Merge ROSCO and _toolbox gitignore * Fix .gitignore * Remove Examples/DISCON.IN from git * Fix and point example_01 to Tune_Cases/ * Update verbiage around using ofTools vs. weis * Fix and point example_04 to Tune_Cases/ * Clean up example_06 * Clean up example_07 * Only check FlpCornerFreq if using Flp control, fixes example 05 * Make example_04 consistent with others * Let example_05 run independently from 04 * Clean up example_05, wind files * Add schema and update empty tuning yaml inputs, not connected yet * Integrate schema into turbine, controller, and examples * Only check Fl filter parameters if Fl_Mode > 0, fix example_05 * bump version to 2.3 * Compile ROSCO from ROSCO dir * Rename to CI_rosco * Add omega vs. windspeed functionality * Fix tests: 5MW U_pc and 06 example dir * Make _Toolbox vs_minspeed in rotor frame to match ROSCO * Revert ServoDyn change * change rotor speed constraint to be epsilon * rename for clarity * docs major refresh * fix FA_AccF units in debug file * docs that build locally * Deallocate arrays in ROSCO, check in example_05 * Clean up comments * remove gitmodules * furo theme * furo in requirements * move readthedocs config file, remove furo import in conf.py * add docs requirements file * typo * move index out of source folder * trying to get furo to work * import date * fix versions and titles, cleanup readthedocs requirements * typo fix, remove extras * more cleanup * bump version * no furo extension, "hack" to load RT version * proper toctree paths * specify method * add mock modules * fix typos * update python install requirements * running locally * move index to main docs dir again * update to build locally * error during warnings * automated version * cleanup * remove old docs * re-add docs * simplify * fix figure path * try alabaster * remove archived docs * Add omega vs. windspeed functionality * Fix tests: 5MW U_pc and 06 example dir * more detailed sp.optimize settings * run MBC3 in parallel * restructure driver, run initialization doe for tuning * Try new dlclose function * Update example_05 to run simple simulation twice and check result * Revert deallocation stuff * Close discon library after every sim run * Test examples on macOS and windows * Run examples instead of testing on other platforms * Skip examples in windows for now * update paths and yaml load funciton * Skip mac testing of examples * provide default U_pc for single omega/zeta case * allow for float or list-like pc tuning inputs * Change name in setup.py * WE_Vw unit fix * Pass through kp_float, if desired * Minor fixes: schema error and InputReader defaults * cleeanup for improved stability * check for doe_logs as string in load_DOE * major restructure for rsched_driver class * cleanup verbosity * run serial by default * load_parallel as linturb_option * specific IEA15MW yaml for multi omega * remove unused module imports * fix error message types * lin_file as input * add comments on inputs to LinearTurbineModel init method * remove relative file paths * provide OpenFAST linearizations for IEA15MW UMaineSemi * put plotting in specific function * fix WE_lambda units * add self in on a few necessary variables * creaete example 12 for robust scheduling * try a few mbc3 locations for import * allow list-like or numpy arrays for omega_pc and zeta_pc schedules * create and use recorder setup function * Pass Through Kp_float (#57) * Pass through kp_float, if desired * Minor fixes: schema error and InputReader defaults * fix setup_recorder to work for optimization driver too * Allow pass through of Kp_float = 0 * cleanup om problems, update om0 calc * doe levels as input * negative k_float to account for OF conventions * cleanup print statements * variable name cleanup, use calculated k_float * Add defaults to omega_,zeta_ pc and vs, allow to be numbers * use standard tuning k_float as IC * formatting update * update problem setup methods * cleanup add_dv, enable adding design variables after problem is setup * change optimization step size * more setup restructure * update verbosity * use sphinx-rtd-theme * master doc and sphinx rtd theme * index back to root folder * only ignore install folders * remove hidden toctree * furo theme * update paths * convert rt version to string * update sphinx settings * move conf * furo theme * Mostly a docs update (#61) * rename for clarity * docs major refresh * fix FA_AccF units in debug file * docs that build locally * remove gitmodules * furo theme * furo in requirements * move readthedocs config file, remove furo import in conf.py * add docs requirements file * typo * move index out of source folder * trying to get furo to work * import date * fix versions and titles, cleanup readthedocs requirements * typo fix, remove extras * more cleanup * bump version * no furo extension, "hack" to load RT version * proper toctree paths * specify method * add mock modules * fix typos * update python install requirements * running locally * move index to main docs dir again * update to build locally * error during warnings * automated version * cleanup * remove old docs * re-add docs * simplify * fix figure path * try alabaster * remove archived docs * use sphinx-rtd-theme * master doc and sphinx rtd theme * index back to root folder * only ignore install folders * remove hidden toctree * furo theme * update paths * convert rt version to string * update sphinx settings * move conf * furo theme * Pass through Kp_float = 0 (#59) * Pass through kp_float, if desired * Minor fixes: schema error and InputReader defaults * Allow pass through of Kp_float = 0 * Add flp parameters to schema * Change Fl_Mode default to 0 * Add defaults to omega_,zeta_ pc and vs, allow to be numbers * Allow single pitch tuning values in code, default U_pc to 0 * use nac acceleration for floating feedback * Fix TSR saturation for region 2.5operation * Modify system for constant power operation * Only modify pole for constant power above-rated * Remove GenEff from K calc * Update tuning, use constant power * use load_rosco_yaml * constant power * Fix broken tests * Include Fl_Mode=2 for nacelle pitching feedback * Add FOCAL inputs - hpf on floating feedback - lpf on wind speed estimator - associated schema updates * Set notch and check frequencies when Fl_Mode = 1 (fixes bug) * Skip filter step if there's an error * Update IEA-15MW test case DISCON with focal inputs * Allow Fl_Mode = 2 in ROSCO * Pass through lpf frequency * Add FOCAL tuning yaml * Set Cp contour number of levels * Add FOCAL params to various writers * Update/tune focal yaml * Add scripts for running FAST, tuning various parameters and cases * Add notebook for FAST plotting * Set up step case for testing * Change doubles to C_doubles * Define real and integer kinds, assign to all of ROSCO * Add ADJUSTL to DISCON error message * Fix Fl_Mode == 2 * Fix Fl_Mode == 2 again * Call yaw, flap, and debug only if enabled in DISOCN.IN * Make avrSWAP a ReKi and set constant kinds * Add DISCONs for testing - revert this later * Fix DISCON comparison, before DISCON's were overwritten by model * Rename DEBUG2.dbg to RootName.dbg2 * Update TestCase DISCONs to new input file * Add API change page in docs * Add link to API change on main page * Fix table headers * Fix title underlines * Fix tables again * Fix tables again * Fix version numbering in docs * Simplify FAST_directory in run_FAST * Versioning (#65) * use sphinx-rtd-theme * master doc and sphinx rtd theme * index back to root folder * only ignore install folders * remove hidden toctree * furo theme * update paths * convert rt version to string * update sphinx settings * move conf * furo theme * remove git versioning from cmake * use hard coded rosco_version * update intro write method * set nowrap for intel compilers * Add transfer of error message and clear message after each call * update install instructions * Catch nans in ROSCO at end of WSE * fix conda install typo * cleanup docs * Rename DEBUG2.dbg to RootName.dbg2 * Fix Fl_Mode == 2 * Fix Fl_Mode == 2 again * Allow Fl_Mode = 2 in ROSCO * Set notch and check frequencies when Fl_Mode = 1 (fixes bug) * Update FOCAL tuning yaml * Update TSR * Clean up and doc fix * Remove publish to pypi * Define all constant inputs to functions with kind typing * Generate Test_Case/ inputs automatically * Fix IEA15 DISCON path * Fix example 11 paths * Auto-generate tuning input yaml using schema * Add toolbox_input to doc index * Add toctree * Re-name title of toolbox_input Co-authored-by: Nikhar Abbas Co-authored-by: Xianping Du <38188001+Seager1989@users.noreply.github.com> Co-authored-by: nikhar-abbas <40865984+nikhar-abbas@users.noreply.github.com> * update listcheck method for numpy arrays * Open Loop Control (#98) * create rosco types yaml * Add more descriptions, add integer_c default, cleanup * updates for allocatability and shapes * python scripts to write ROSCO_types.f90 * reemove superfulous modules * use types from ROSCO registry * create rosco types yaml * Add more descriptions, add integer_c default, cleanup * updates for allocatability and shapes * python scripts to write ROSCO_types.f90 * reemove superfulous modules * use types from ROSCO registry * Saturate inputs to WSE. Needs some TLC, but seems to work * Reduce saturation limits on speed, torque * Re-organize, set saturation limits. Working at 3 m/s * Initial add of OL control to ROSCO: builds * Update DISCONs with open loop inputs * Fix file reading for OL_Filename * Add open loop control generation and file writing * Use DISCON_dict for more manageable DISCON file writing * Add open loop example, fix constant timeseries * Make open loop example generate power * Handle relative paths and calling from outside the run directory: - Some helper functions borrowed from OpenFAST, f/ext_control - Updated file writing * Clean up: versions, print statements * Fix SysFiles paths in CMakeLists * Tidy up Ext_DLL names * More Ext_DLL name tidying * Test write_registry.py * Update for OL Control * Move preprocessor lines * add zenodo DOI * Regenerated Types * fix shape * revert filepath change * give all types a size, ProcAddr size = 3 * update types * test registry in compile step * specify default shell * update write_registry path * remove default shell * Document API changes, provide OL input example * Fix example 14 (yaw input) * Add error catching to yaw control * Tidy up OL_Input Reading: error catching, generalize * More yaw control fixes, to model * Checkout develop CMakeLists for ROSCO * Update DISCON.INs for TestCases/ * Revert "Checkout develop CMakeLists for ROSCO" This reverts commit 87a491359d73806e3aaa59b4cfdc00f2838875df. * Revert windows cmake stuff to develop * Fix CMake again * Revert "Revert windows cmake stuff to develop" This reverts commit 39df122449b0e2055f2e12e3ce38a0c010c7bd91. * Make last cmake fix - hopefully Co-authored-by: Nikhar Abbas * Restart & registry (#99) * Convert WE saved variables to WE type * Put restart flag in localvars * Use saved filter params from LocalVar * save pitcomt last * Move IPC saved variables to localvars * Saved pi controller variables to localvar * Save RootMyb_Last to localvar * ROSCO_IO - initial commit. Include restart and debug functions * Use ROSCO IO and call restart functions * Remove debug from function.f90 * Save ACC Infile info * update for restart capabilities * add rosco_io with restart and debug functions * cleanup debug call * use registry generate types and IO * delete DFController * fix timestep mismatch * remove unnecessaray istatus check * close files * add reg test for restart * add restart option to run_openfast * add testing to CI, ignore generate files * fix fastcall * remove extra commas * specify gfortran-10 * testing flag cleanup * Use lv_strings to generate debug output * Revert "testing flag cleanup" This reverts commit 6f295563832413e96347acd82716f9aadac6d46c. * Revert "specify gfortran-10" This reverts commit 4c3154491523bcd542133ca2bce5803cdc94523f. * minor cleanup * Use kind from constants * Add some comments for clarity * put debug in if statements * separate reg tests from oother tests * Fl_Mode>0 * Remove hard coded values * Add filtered signals and WE_Vw to debug varrs * cd for regtest * Check logging level before calling debug * add fl_pitcom and pc_minpit to debugvars Co-authored-by: dzalkind * Break up if statement in open loop pitch (#100) * Break up if statement in open loop pitch * Make torque and yaw consistent with pitch: can start after some time * add bld edgewise freq to robust dict_inputs * Fix ccrotor inputs (#104) * remove interpolation of blade chord and twist * rename aerodynblade inputs * Update surface and DISCON.INs * Fix performance table paths * Allow default inputs (#110) * Allow defaults for AeroDyn inputs * Allow AeroDyn inputs to be floats, too * ipc (#105) * remove interpolation of blade chord and twist * rename aerodynblade inputs * Update surface and DISCON.INs * Fix performance table paths * Add proportional control and cleanup IPC * Add IPC and filtered RootMyc to registry * Better logic for filtering RootMOOP and fix notch filter slopes bug * Add cyclic flap conrol * Fix comments in ColemanTransformInverse * Addd IPC_KP to DISCON.IN * Error checking foro flp or ipc * add mutichannel plotting with tuples * add CMakeFiles to gitignore * Add IPC_KP to api changes * numerical qualifiers for error handling * add IPC gains to schema for pass-through ability * fix variable names * fix ipc gain printing bug * make sure IPC_KP is positive * Update Polars to point to coord files * ignore dbg2 files * Add IEA15MW_OL.yaml * update coord reader/writer * expand pitch_initial to 30 degrees * Add example 13 for IPC * Update cp surfaces and DISCONS * add examples to readme * cleanup and streaamline run_examples * Add IPC tuning vars * Allow IPC to command pitch value below peak shaving saturation limit * shorten simulation time * Fix Material parameter path * Update DISCONs again * Fix OL_Input reading * Set wind speed, rotor speed IC in example 14 * Debug OL reading * Add more debugging lines * Add more debugging lines 2 * Clean up, hone in on debug call * Disable logging level * Update discons - resolve conflict * Print when finished with ROSCO * add control packageg * Use PriPath and RootName to name dbg files * Print AvrSWAP * Revert "Use PriPath and RootName to name dbg files" This reverts commit 062fcaa55b3bf42d44f8a3f163aa883ab9552412. * Disable other examples * Print OL inputs * Allow logging level 3 * Print OL inputs * Make example shorter * Print more stuf * Print shape * Revert "Print OL inputs" This reverts commit 8e2a642bb35e46850f579ca4e69ca6d6fc93f4cc. * Update ROSCO Simulink model with IPC example * refactor flap tuning for normalization methods * improved flap controller filtering * delete extra F_FlpCornerFrerq * Update inputs, reader, and writer for OF 3.1.0 * Make sigma default interp type for multi_sigma * Use openfast 3.1.0 in CI * Fix leak...maybe * Use OF 3.1.0 in testing * Use gfotran for compile * Clean up print statements * Re-enable all examples * Update NREL-5MW AD file * Only check airfoil controls if more than one table * Update BAR models * Revert "Use gfotran for compile" This reverts commit 5a6e2b7e30287a09a09781e2ba12f9b578132e1f. * Install pyFAST for CI * Fix some paths in ex12 * Disable example 12 * Fix example 12 linear path, re-enable * Skip compilers install for mac * Try gfortran-9, no compilers * Try gfortran-10, no compilers * Skip windows compile in pytools * Re-enable windows, use gfortran as FC * Unset FC in windows * Set environment for windows when dependencies installed * Try setting environment in installation * Put conditional env setting in correct place * Try in setup again * Break up tasks: Windows vs. not * Update DISCONs * Update docs with new variables * Add example documentation * Update ROSCO Simulink model for 3.1.0 * Make IEA model float again * Reduce IEA timestep * Match DT to checkpoint time Co-authored-by: dzalkind * Increment version number * Bladed docs (#116) * Added image of Bladed control screen setup * Delete Bladed control screen.png * Adding image of Bladed control screen * Add files via upload * Minor edit 1 * Minor change 2 * Minor change 3 * Minor change 4 * Change 6 * Change 7 * Change 8 * Minor change 9 Co-authored-by: nikhar-abbas <40865984+nikhar-abbas@users.noreply.github.com> Co-authored-by: WillC-DNV <100850534+WillC-DNV@users.noreply.github.com> * Update version in API change docs * Bladed readthedocs (#117) * Added image of Bladed control screen setup * Delete Bladed control screen.png * Adding image of Bladed control screen * Add files via upload * Minor edit 1 * Minor change 2 * Minor change 3 * Minor change 4 * Change 6 * Change 7 * Change 8 * Minor change 9 * Tinker with characters in bladed instructions * Add bladed instructions to index * Change bladed toctree label * Do underline stuff * Make toctree label same as file * Remove colons from headers Co-authored-by: nikhar-abbas <40865984+nikhar-abbas@users.noreply.github.com> Co-authored-by: WillC-DNV <100850534+WillC-DNV@users.noreply.github.com> * Update docs to reflect CI process Co-authored-by: Nikhar Abbas Co-authored-by: Xianping Du <38188001+Seager1989@users.noreply.github.com> Co-authored-by: nikhar-abbas <40865984+nikhar-abbas@users.noreply.github.com> Co-authored-by: WillC-DNV <100850534+WillC-DNV@users.noreply.github.com> * Fixed wrong formatting of list items (#122) extra newline required between list elements * Regenerate types, IO with registry * Update registry so first timestep is printed * Update inverted notch to move frequency properly * Saturate inv notch corner frequency at 0 * Add tower damper mode flag * Flip Ct and Cq table allocation * Regen types * Remove print statements used for debugging * Update input files: IEA model has pitch actuator * Add back flap control (no idea when it was deleted) * Update discons, docs with API change Co-authored-by: nikhar-abbas <40865984+nikhar-abbas@users.noreply.github.com> Co-authored-by: Nikhar Abbas Co-authored-by: Xianping Du <38188001+Seager1989@users.noreply.github.com> Co-authored-by: WillC-DNV <100850534+WillC-DNV@users.noreply.github.com> Co-authored-by: Gustavo Hylander <74593034+ghylander@users.noreply.github.com> * Add max_torque_factor for constant power control, flexible upper limit * Make update discons relative to tuning yaml * Update AddF0 and NumCoords in FAST_reader/writer * Remove matlab/rotor position control stuff * Add OpenFAST channels that Simulink reads (#135) * RAAW Updates (#133) * Convert WE saved variables to WE type * Put restart flag in localvars * Use saved filter params from LocalVar * save pitcomt last * Move IPC saved variables to localvars * Saved pi controller variables to localvar * Save RootMyb_Last to localvar * ROSCO_IO - initial commit. Include restart and debug functions * Use ROSCO IO and call restart functions * Remove debug from function.f90 * Save ACC Infile info * update for restart capabilities * add rosco_io with restart and debug functions * cleanup debug call * use registry generate types and IO * delete DFController * fix timestep mismatch * remove unnecessaray istatus check * close files * add reg test for restart * add restart option to run_openfast * add testing to CI, ignore generate files * fix fastcall * remove extra commas * specify gfortran-10 * testing flag cleanup * Use lv_strings to generate debug output * Revert "testing flag cleanup" This reverts commit 6f295563832413e96347acd82716f9aadac6d46c. * Revert "specify gfortran-10" This reverts commit 4c3154491523bcd542133ca2bce5803cdc94523f. * minor cleanup * Use kind from constants * Add some comments for clarity * put debug in if statements * separate reg tests from oother tests * Fl_Mode>0 * Remove hard coded values * Add filtered signals and WE_Vw to debug varrs * cd for regtest * Check logging level before calling debug * add fl_pitcom and pc_minpit to debugvars * Turn runFAST into a class * Refactor/simplify CaseLibrary * Implement initial pitch actuator * Set up steps case * Add actuator variable * Print first time step in debug outs * Fix FOCAL yaml * Set actuator to 0.25 Hz bandwidth * ROSCO 2.5.0 (#115) * FOCAL Updates (#64) * Update headers * fix bullets * make uppercase * Update turbine.py (#56) * Update turbine.py This add several lines for fixing the problem of repeated maximum values in the performance tables. This will cause the error (' the length of x and y is different.') of 'interpolate.interp1d.' * Add comments and catch when there are multiple optimal pitch angles Co-authored-by: dzalkind * increment version * Update for OpenFAST v3.0.0 * Update for OpenFAST v3.0.0 * Install OF3.0.0 for tests * update for OF v3.0.0 * add publish to pypi on release * Update to ROSCO v2.3.0 * Update Testing (#58) * Update scripts to run on eagle * Update IEA-15MW semi example: use peak shaving w/ ps_percen=0.8 * Add comparison plots to testing scripts * Update submit script for testing * Update for latest eagle runs * Add future to install dependencies * add TMax to self, define tmin in print_results * run tests in CI * generic ROSCO path * default to overwrite * fix path * import platform * separate run_testing * cleanup, specify lite test * don't run testing in after examples, oops. Co-authored-by: nikhar-abbas <40865984+nikhar-abbas@users.noreply.github.com> Co-authored-by: Nikhar Abbas * increment version * Update for OpenFAST v3.0.0 * Install OF3.0.0 for tests * update for OF v3.0.0 * add publish to pypi on release * Update to ROSCO v2.3.0 * Increment Version, OF3.0 (#57) * increment version * Update for OpenFAST v3.0.0 * Install OF3.0.0 for tests * update for OF v3.0.0 * add publish to pypi on release * Update to ROSCO v2.3.0 * increment version * Update for OpenFAST v3.0.0 * Install OF3.0.0 for tests * update for OF v3.0.0 * add publish to pypi on release * Update to ROSCO v2.3.0 * add ROSCO without submodule * move ROSCO source to ROSCO folder * Move cmake-related files to ROSCO * Add back pesky ErrVar * Remove parameters_files * Merge ROSCO and _toolbox gitignore * Fix .gitignore * Remove Examples/DISCON.IN from git * Fix and point example_01 to Tune_Cases/ * Update verbiage around using ofTools vs. weis * Fix and point example_04 to Tune_Cases/ * Clean up example_06 * Clean up example_07 * Only check FlpCornerFreq if using Flp control, fixes example 05 * Make example_04 consistent with others * Let example_05 run independently from 04 * Clean up example_05, wind files * Add schema and update empty tuning yaml inputs, not connected yet * Integrate schema into turbine, controller, and examples * Only check Fl filter parameters if Fl_Mode > 0, fix example_05 * bump version to 2.3 * Compile ROSCO from ROSCO dir * Rename to CI_rosco * Add omega vs. windspeed functionality * Fix tests: 5MW U_pc and 06 example dir * Make _Toolbox vs_minspeed in rotor frame to match ROSCO * Revert ServoDyn change * change rotor speed constraint to be epsilon * rename for clarity * docs major refresh * fix FA_AccF units in debug file * docs that build locally * Deallocate arrays in ROSCO, check in example_05 * Clean up comments * remove gitmodules * furo theme * furo in requirements * move readthedocs config file, remove furo import in conf.py * add docs requirements file * typo * move index out of source folder * trying to get furo to work * import date * fix versions and titles, cleanup readthedocs requirements * typo fix, remove extras * more cleanup * bump version * no furo extension, "hack" to load RT version * proper toctree paths * specify method * add mock modules * fix typos * update python install requirements * running locally * move index to main docs dir again * update to build locally * error during warnings * automated version * cleanup * remove old docs * re-add docs * simplify * fix figure path * try alabaster * remove archived docs * Add omega vs. windspeed functionality * Fix tests: 5MW U_pc and 06 example dir * more detailed sp.optimize settings * run MBC3 in parallel * restructure driver, run initialization doe for tuning * Try new dlclose function * Update example_05 to run simple simulation twice and check result * Revert deallocation stuff * Close discon library after every sim run * Test examples on macOS and windows * Run examples instead of testing on other platforms * Skip examples in windows for now * update paths and yaml load funciton * Skip mac testing of examples * provide default U_pc for single omega/zeta case * allow for float or list-like pc tuning inputs * Change name in setup.py * WE_Vw unit fix * Pass through kp_float, if desired * Minor fixes: schema error and InputReader defaults * cleeanup for improved stability * check for doe_logs as string in load_DOE * major restructure for rsched_driver class * cleanup verbosity * run serial by default * load_parallel as linturb_option * specific IEA15MW yaml for multi omega * remove unused module imports * fix error message types * lin_file as input * add comments on inputs to LinearTurbineModel init method * remove relative file paths * provide OpenFAST linearizations for IEA15MW UMaineSemi * put plotting in specific function * fix WE_lambda units * add self in on a few necessary variables * creaete example 12 for robust scheduling * try a few mbc3 locations for import * allow list-like or numpy arrays for omega_pc and zeta_pc schedules * create and use recorder setup function * Pass Through Kp_float (#57) * Pass through kp_float, if desired * Minor fixes: schema error and InputReader defaults * fix setup_recorder to work for optimization driver too * Allow pass through of Kp_float = 0 * cleanup om problems, update om0 calc * doe levels as input * negative k_float to account for OF conventions * cleanup print statements * variable name cleanup, use calculated k_float * Add defaults to omega_,zeta_ pc and vs, allow to be numbers * use standard tuning k_float as IC * formatting update * update problem setup methods * cleanup add_dv, enable adding design variables after problem is setup * change optimization step size * more setup restructure * update verbosity * use sphinx-rtd-theme * master doc and sphinx rtd theme * index back to root folder * only ignore install folders * remove hidden toctree * furo theme * update paths * convert rt version to string * update sphinx settings * move conf * furo theme * Mostly a docs update (#61) * rename for clarity * docs major refresh * fix FA_AccF units in debug file * docs that build locally * remove gitmodules * furo theme * furo in requirements * move readthedocs config file, remove furo import in conf.py * add docs requirements file * typo * move index out of source folder * trying to get furo to work * import date * fix versions and titles, cleanup readthedocs requirements * typo fix, remove extras * more cleanup * bump version * no furo extension, "hack" to load RT version * proper toctree paths * specify method * add mock modules * fix typos * update python install requirements * running locally * move index to main docs dir again * update to build locally * error during warnings * automated version * cleanup * remove old docs * re-add docs * simplify * fix figure path * try alabaster * remove archived docs * use sphinx-rtd-theme * master doc and sphinx rtd theme * index back to root folder * only ignore install folders * remove hidden toctree * furo theme * update paths * convert rt version to string * update sphinx settings * move conf * furo theme * Pass through Kp_float = 0 (#59) * Pass through kp_float, if desired * Minor fixes: schema error and InputReader defaults * Allow pass through of Kp_float = 0 * Add flp parameters to schema * Change Fl_Mode default to 0 * Add defaults to omega_,zeta_ pc and vs, allow to be numbers * Allow single pitch tuning values in code, default U_pc to 0 * use nac acceleration for floating feedback * Fix TSR saturation for region 2.5operation * Modify system for constant power operation * Only modify pole for constant power above-rated * Remove GenEff from K calc * Update tuning, use constant power * use load_rosco_yaml * constant power * Fix broken tests * Include Fl_Mode=2 for nacelle pitching feedback * Add FOCAL inputs - hpf on floating feedback - lpf on wind speed estimator - associated schema updates * Set notch and check frequencies when Fl_Mode = 1 (fixes bug) * Skip filter step if there's an error * Update IEA-15MW test case DISCON with focal inputs * Allow Fl_Mode = 2 in ROSCO * Pass through lpf frequency * Add FOCAL tuning yaml * Set Cp contour number of levels * Add FOCAL params to various writers * Update/tune focal yaml * Add scripts for running FAST, tuning various parameters and cases * Add notebook for FAST plotting * Set up step case for testing * Change doubles to C_doubles * Define real and integer kinds, assign to all of ROSCO * Add ADJUSTL to DISCON error message * Fix Fl_Mode == 2 * Fix Fl_Mode == 2 again * Call yaw, flap, and debug only if enabled in DISOCN.IN * Make avrSWAP a ReKi and set constant kinds * Add DISCONs for testing - revert this later * Fix DISCON comparison, before DISCON's were overwritten by model * Rename DEBUG2.dbg to RootName.dbg2 * Update TestCase DISCONs to new input file * Add API change page in docs * Add link to API change on main page * Fix table headers * Fix title underlines * Fix tables again * Fix tables again * Fix version numbering in docs * Simplify FAST_directory in run_FAST * Versioning (#65) * use sphinx-rtd-theme * master doc and sphinx rtd theme * index back to root folder * only ignore install folders * remove hidden toctree * furo theme * update paths * convert rt version to string * update sphinx settings * move conf * furo theme * remove git versioning from cmake * use hard coded rosco_version * update intro write method * set nowrap for intel compilers * Add transfer of error message and clear message after each call * update install instructions * Catch nans in ROSCO at end of WSE * fix conda install typo * cleanup docs * Rename DEBUG2.dbg to RootName.dbg2 * Fix Fl_Mode == 2 * Fix Fl_Mode == 2 again * Allow Fl_Mode = 2 in ROSCO * Set notch and check frequencies when Fl_Mode = 1 (fixes bug) * Update FOCAL tuning yaml * Update TSR * Clean up and doc fix * Remove publish to pypi * Define all constant inputs to functions with kind typing * Generate Test_Case/ inputs automatically * Fix IEA15 DISCON path * Fix example 11 paths * Auto-generate tuning input yaml using schema * Add toolbox_input to doc index * Add toctree * Re-name title of toolbox_input Co-authored-by: Nikhar Abbas Co-authored-by: Xianping Du <38188001+Seager1989@users.noreply.github.com> Co-authored-by: nikhar-abbas <40865984+nikhar-abbas@users.noreply.github.com> * update listcheck method for numpy arrays * Open Loop Control (#98) * create rosco types yaml * Add more descriptions, add integer_c default, cleanup * updates for allocatability and shapes * python scripts to write ROSCO_types.f90 * reemove superfulous modules * use types from ROSCO registry * create rosco types yaml * Add more descriptions, add integer_c default, cleanup * updates for allocatability and shapes * python scripts to write ROSCO_types.f90 * reemove superfulous modules * use types from ROSCO registry * Saturate inputs to WSE. Needs some TLC, but seems to work * Reduce saturation limits on speed, torque * Re-organize, set saturation limits. Working at 3 m/s * Initial add of OL control to ROSCO: builds * Update DISCONs with open loop inputs * Fix file reading for OL_Filename * Add open loop control generation and file writing * Use DISCON_dict for more manageable DISCON file writing * Add open loop example, fix constant timeseries * Make open loop example generate power * Handle relative paths and calling from outside the run directory: - Some helper functions borrowed from OpenFAST, f/ext_control - Updated file writing * Clean up: versions, print statements * Fix SysFiles paths in CMakeLists * Tidy up Ext_DLL names * More Ext_DLL name tidying * Test write_registry.py * Update for OL Control * Move preprocessor lines * add zenodo DOI * Regenerated Types * fix shape * revert filepath change * give all types a size, ProcAddr size = 3 * update types * test registry in compile step * specify default shell * update write_registry path * remove default shell * Document API changes, provide OL input example * Fix example 14 (yaw input) * Add error catching to yaw control * Tidy up OL_Input Reading: error catching, generalize * More yaw control fixes, to model * Checkout develop CMakeLists for ROSCO * Update DISCON.INs for TestCases/ * Revert "Checkout develop CMakeLists for ROSCO" This reverts commit 87a491359d73806e3aaa59b4cfdc00f2838875df. * Revert windows cmake stuff to develop * Fix CMake again * Revert "Revert windows cmake stuff to develop" This reverts commit 39df122449b0e2055f2e12e3ce38a0c010c7bd91. * Make last cmake fix - hopefully Co-authored-by: Nikhar Abbas * Restart & registry (#99) * Convert WE saved variables to WE type * Put restart flag in localvars * Use saved filter params from LocalVar * save pitcomt last * Move IPC saved variables to localvars * Saved pi controller variables to localvar * Save RootMyb_Last to localvar * ROSCO_IO - initial commit. Include restart and debug functions * Use ROSCO IO and call restart functions * Remove debug from function.f90 * Save ACC Infile info * update for restart capabilities * add rosco_io with restart and debug functions * cleanup debug call * use registry generate types and IO * delete DFController * fix timestep mismatch * remove unnecessaray istatus check * close files * add reg test for restart * add restart option to run_openfast * add testing to CI, ignore generate files * fix fastcall * remove extra commas * specify gfortran-10 * testing flag cleanup * Use lv_strings to generate debug output * Revert "testing flag cleanup" This reverts commit 6f295563832413e96347acd82716f9aadac6d46c. * Revert "specify gfortran-10" This reverts commit 4c3154491523bcd542133ca2bce5803cdc94523f. * minor cleanup * Use kind from constants * Add some comments for clarity * put debug in if statements * separate reg tests from oother tests * Fl_Mode>0 * Remove hard coded values * Add filtered signals and WE_Vw to debug varrs * cd for regtest * Check logging level before calling debug * add fl_pitcom and pc_minpit to debugvars Co-authored-by: dzalkind * Break up if statement in open loop pitch (#100) * Break up if statement in open loop pitch * Make torque and yaw consistent with pitch: can start after some time * add bld edgewise freq to robust dict_inputs * Fix ccrotor inputs (#104) * remove interpolation of blade chord and twist * rename aerodynblade inputs * Update surface and DISCON.INs * Fix performance table paths * Allow default inputs (#110) * Allow defaults for AeroDyn inputs * Allow AeroDyn inputs to be floats, too * ipc (#105) * remove interpolation of blade chord and twist * rename aerodynblade inputs * Update surface and DISCON.INs * Fix performance table paths * Add proportional control and cleanup IPC * Add IPC and filtered RootMyc to registry * Better logic for filtering RootMOOP and fix notch filter slopes bug * Add cyclic flap conrol * Fix comments in ColemanTransformInverse * Addd IPC_KP to DISCON.IN * Error checking foro flp or ipc * add mutichannel plotting with tuples * add CMakeFiles to gitignore * Add IPC_KP to api changes * numerical qualifiers for error handling * add IPC gains to schema for pass-through ability * fix variable names * fix ipc gain printing bug * make sure IPC_KP is positive * Update Polars to point to coord files * ignore dbg2 files * Add IEA15MW_OL.yaml * update coord reader/writer * expand pitch_initial to 30 degrees * Add example 13 for IPC * Update cp surfaces and DISCONS * add examples to readme * cleanup and streaamline run_examples * Add IPC tuning vars * Allow IPC to command pitch value below peak shaving saturation limit * shorten simulation time * Fix Material parameter path * Update DISCONs again * Fix OL_Input reading * Set wind speed, rotor speed IC in example 14 * Debug OL reading * Add more debugging lines * Add more debugging lines 2 * Clean up, hone in on debug call * Disable logging level * Update discons - resolve conflict * Print when finished with ROSCO * add control packageg * Use PriPath and RootName to name dbg files * Print AvrSWAP * Revert "Use PriPath and RootName to name dbg files" This reverts commit 062fcaa55b3bf42d44f8a3f163aa883ab9552412. * Disable other examples * Print OL inputs * Allow logging level 3 * Print OL inputs * Make example shorter * Print more stuf * Print shape * Revert "Print OL inputs" This reverts commit 8e2a642bb35e46850f579ca4e69ca6d6fc93f4cc. * Update ROSCO Simulink model with IPC example * refactor flap tuning for normalization methods * improved flap controller filtering * delete extra F_FlpCornerFrerq * Update inputs, reader, and writer for OF 3.1.0 * Make sigma default interp type for multi_sigma * Use openfast 3.1.0 in CI * Fix leak...maybe * Use OF 3.1.0 in testing * Use gfotran for compile * Clean up print statements * Re-enable all examples * Update NREL-5MW AD file * Only check airfoil controls if more than one table * Update BAR models * Revert "Use gfotran for compile" This reverts commit 5a6e2b7e30287a09a09781e2ba12f9b578132e1f. * Install pyFAST for CI * Fix some paths in ex12 * Disable example 12 * Fix example 12 linear path, re-enable * Skip compilers install for mac * Try gfortran-9, no compilers * Try gfortran-10, no compilers * Skip windows compile in pytools * Re-enable windows, use gfortran as FC * Unset FC in windows * Set environment for windows when dependencies installed * Try setting environment in installation * Put conditional env setting in correct place * Try in setup again * Break up tasks: Windows vs. not * Update DISCONs * Update docs with new variables * Add example documentation * Update ROSCO Simulink model for 3.1.0 * Make IEA model float again * Reduce IEA timestep * Match DT to checkpoint time Co-authored-by: dzalkind * Increment version number * Bladed docs (#116) * Added image of Bladed control screen setup * Delete Bladed control screen.png * Adding image of Bladed control screen * Add files via upload * Minor edit 1 * Minor change 2 * Minor change 3 * Minor change 4 * Change 6 * Change 7 * Change 8 * Minor change 9 Co-authored-by: nikhar-abbas <40865984+nikhar-abbas@users.noreply.github.com> Co-authored-by: WillC-DNV <100850534+WillC-DNV@users.noreply.github.com> * Update version in API change docs * Bladed readthedocs (#117) * Added image of Bladed control screen setup * Delete Bladed control screen.png * Adding image of Bladed control screen * Add files via upload * Minor edit 1 * Minor change 2 * Minor change 3 * Minor change 4 * Change 6 * Change 7 * Change 8 * Minor change 9 * Tinker with characters in bladed instructions * Add bladed instructions to index * Change bladed toctree label * Do underline stuff * Make toctree label same as file * Remove colons from headers Co-authored-by: nikhar-abbas <40865984+nikhar-abbas@users.noreply.github.com> Co-authored-by: WillC-DNV <100850534+WillC-DNV@users.noreply.github.com> * Update docs to reflect CI process Co-authored-by: Nikhar Abbas Co-authored-by: Xianping Du <38188001+Seager1989@users.noreply.github.com> Co-authored-by: nikhar-abbas <40865984+nikhar-abbas@users.noreply.github.com> Co-authored-by: WillC-DNV <100850534+WillC-DNV@users.noreply.github.com> * Fixed wrong formatting of list items (#122) extra newline required between list elements * Regenerate types, IO with registry * Update registry so first timestep is printed * Update inverted notch to move frequency properly * Saturate inv notch corner frequency at 0 * Add tower damper mode flag * Add Azimuth tracking controller in Simulink * Always enable GenDOF, add options for simp_step * Add sweep for IPC gains and FA damper * Fix NumCoords in FAST_writer * Add turbulent case to runFAST/CaseLibrary * Add peak shaving sweep function * Increase default IPC_IntSat, make input parameter in future * Flip Ct and Cq table allocation (#129) * Flip Ct and Cq table allocation * Regen types * Remove print statements used for debugging * Update input files: IEA model has pitch actuator * Add back flap control (no idea when it was deleted) * Update discons, docs with API change * Add user-defined hh case * Fix AddF0 and RayleighDamp in FAST_reader * Add max_torque_factor for constant power control, flexible upper limit * Make update discons relative to tuning yaml * Update AddF0 and NumCoords in FAST_reader/writer * Remove matlab/rotor position control stuff Co-authored-by: nikhar-abbas <40865984+nikhar-abbas@users.noreply.github.com> Co-authored-by: Nikhar Abbas Co-authored-by: Xianping Du <38188001+Seager1989@users.noreply.github.com> Co-authored-by: WillC-DNV <100850534+WillC-DNV@users.noreply.github.com> Co-authored-by: Gustavo Hylander <74593034+ghylander@users.noreply.github.com> * Pass through (#136) * Convert WE saved variables to WE type * Put restart flag in localvars * Use saved filter params from LocalVar * save pitcomt last * Move IPC saved variables to localvars * Saved pi controller variables to localvar * Save RootMyb_Last to localvar * ROSCO_IO - initial commit. Include restart and debug functions * Use ROSCO IO and call restart functions * Remove debug from function.f90 * Save ACC Infile info * update for restart capabilities * add rosco_io with restart and debug functions * cleanup debug call * use registry generate types and IO * delete DFController * fix timestep mismatch * remove unnecessaray istatus check * close files * add reg test for restart * add restart option to run_openfast * add testing to CI, ignore generate files * fix fastcall * remove extra commas * specify gfortran-10 * testing flag cleanup * Use lv_strings to generate debug output * Revert "testing flag cleanup" This reverts commit 6f295563832413e96347acd82716f9aadac6d46c. * Revert "specify gfortran-10" This reverts commit 4c3154491523bcd542133ca2bce5803cdc94523f. * minor cleanup * Use kind from constants * Add some comments for clarity * put debug in if statements * separate reg tests from oother tests * Fl_Mode>0 * Remove hard coded values * Add filtered signals and WE_Vw to debug varrs * cd for regtest * Check logging level before calling debug * add fl_pitcom and pc_minpit to debugvars * Turn runFAST into a class * Refactor/simplify CaseLibrary * Implement initial pitch actuator * Set up steps case * Add actuator variable * Print first time step in debug outs * Fix FOCAL yaml * Set actuator to 0.25 Hz bandwidth * ROSCO 2.5.0 (#115) * FOCAL Updates (#64) * Update headers * fix bullets * make uppercase * Update turbine.py (#56) * Update turbine.py This add several lines for fixing the problem of repeated maximum values in the performance tables. This will cause the error (' the length of x and y is different.') of 'interpolate.interp1d.' * Add comments and catch when there are multiple optimal pitch angles Co-authored-by: dzalkind * increment version * Update for OpenFAST v3.0.0 * Update for OpenFAST v3.0.0 * Install OF3.0.0 for tests * update for OF v3.0.0 * add publish to pypi on release * Update to ROSCO v2.3.0 * Update Testing (#58) * Update scripts to run on eagle * Update IEA-15MW semi example: use peak shaving w/ ps_percen=0.8 * Add comparison plots to testing scripts * Update submit script for testing * Update for latest eagle runs * Add future to install dependencies * add TMax to self, define tmin in print_results * run tests in CI * generic ROSCO path * default to overwrite * fix path * import platform * separate run_testing * cleanup, specify lite test * don't run testing in after examples, oops. Co-authored-by: nikhar-abbas <40865984+nikhar-abbas@users.noreply.github.com> Co-authored-by: Nikhar Abbas * increment version * Update for OpenFAST v3.0.0 * Install OF3.0.0 for tests * update for OF v3.0.0 * add publish to pypi on release * Update to ROSCO v2.3.0 * Increment Version, OF3.0 (#57) * increment version * Update for OpenFAST v3.0.0 * Install OF3.0.0 for tests * update for OF v3.0.0 * add publish to pypi on release * Update to ROSCO v2.3.0 * increment version * Update for OpenFAST v3.0.0 * Install OF3.0.0 for tests * update for OF v3.0.0 * add publish to pypi on release * Update to ROSCO v2.3.0 * add ROSCO without submodule * move ROSCO source to ROSCO folder * Move cmake-related files to ROSCO * Add back pesky ErrVar * Remove parameters_files * Merge ROSCO and _toolbox gitignore * Fix .gitignore * Remove Examples/DISCON.IN from git * Fix and point example_01 to Tune_Cases/ * Update verbiage around using ofTools vs. weis * Fix and point example_04 to Tune_Cases/ * Clean up example_06 * Clean up example_07 * Only check FlpCornerFreq if using Flp control, fixes example 05 * Make example_04 consistent with others * Let example_05 run independently from 04 * Clean up example_05, wind files * Add schema and update empty tuning yaml inputs, not connected yet * Integrate schema into turbine, controller, and examples * Only check Fl filter parameters if Fl_Mode > 0, fix example_05 * bump version to 2.3 * Compile ROSCO from ROSCO dir * Rename to CI_rosco * Add omega vs. windspeed functionality * Fix tests: 5MW U_pc and 06 example dir * Make _Toolbox vs_minspeed in rotor frame to match ROSCO * Revert ServoDyn change * change rotor speed constraint to be epsilon * rename for clarity * docs major refresh * fix FA_AccF units in debug file * docs that build locally * Deallocate arrays in ROSCO, check in example_05 * Clean up comments * remove gitmodules * furo theme * furo in requirements * move readthedocs config file, remove furo import in conf.py * add docs requirements file * typo * move index out of source folder * trying to get furo to work * import date * fix versions and titles, cleanup readthedocs requirements * typo fix, remove extras * more cleanup * bump version * no furo extension, "hack" to load RT version * proper toctree paths * specify method * add mock modules * fix typos * update python install requirements * running locally * move index to main docs dir again * update to build locally * error during warnings * automated version * cleanup * remove old docs * re-add docs * simplify * fix figure path * try alabaster * remove archived docs * Add omega vs. windspeed functionality * Fix tests: 5MW U_pc and 06 example dir * more detailed sp.optimize settings * run MBC3 in parallel * restructure driver, run initialization doe for tuning * Try new dlclose function * Update example_05 to run simple simulation twice and check result * Revert deallocation stuff * Close discon library after every sim run * Test examples on macOS and windows * Run examples instead of testing on other platforms * Skip examples in windows for now * update paths and yaml load funciton * Skip mac testing of examples * provide default U_pc for single omega/zeta case * allow for float or list-like pc tuning inputs * Change name in setup.py * WE_Vw unit fix * Pass through kp_float, if desired * Minor fixes: schema error and InputReader defaults * cleeanup for improved stability * check for doe_logs as string in load_DOE * major restructure for rsched_driver class * cleanup verbosity * run serial by default * load_parallel as linturb_option * specific IEA15MW yaml for multi omega * remove unused module imports * fix error message types * lin_file as input * add comments on inputs to LinearTurbineModel init method * remove relative file paths * provide OpenFAST linearizations for IEA15MW UMaineSemi * put plotting in specific function * fix WE_lambda units * add self in on a few necessary variables * creaete example 12 for robust scheduling * try a few mbc3 locations for import * allow list-like or numpy arrays for omega_pc and zeta_pc schedules * create and use recorder setup function * Pass Through Kp_float (#57) * Pass through kp_float, if desired * Minor fixes: schema error and InputReader defaults * fix setup_recorder to work for optimization driver too * Allow pass through of Kp_float = 0 * cleanup om problems, update om0 calc * doe levels as input * negative k_float to account for OF conventions * cleanup print statements * variable name cleanup, use calculated k_float * Add defaults to omega_,zeta_ pc and vs, allow to be numbers * use standard tuning k_float as IC * formatting update * update problem setup methods * cleanup add_dv, enable adding design variables after problem is setup * change optimization step size * more setup restructure * update verbosity * use sphinx-rtd-theme * master doc and sphinx rtd theme * index back to root folder * only ignore install folders * remove hidden toctree * furo theme * update paths * convert rt version to string * update sphinx settings * move conf * furo theme * Mostly a docs update (#61) * rename for clarity * docs major refresh * fix FA_AccF units in debug file * docs that build locally * remove gitmodules * furo theme * furo in requirements * move readthedocs config file, remove furo import in conf.py * add docs requirements file * typo * move index out of source folder * trying to get furo to work * import date * fix versions and titles, cleanup readthedocs requirements * typo fix, remove extras * more cleanup * bump version * no furo extension, "hack" to load RT version * proper toctree paths * specify method * add mock modules * fix typos * update python install requirements * running locally * move index to main docs dir again * update to build locally * error during warnings * automated version * cleanup * remove old docs * re-add docs * simplify * fix figure path * try alabaster * remove archived docs * use sphinx-rtd-theme * master doc and sphinx rtd theme * index back to root folder * only ignore install folders * remove hidden toctree * furo theme * update paths * convert rt version to string * update sphinx settings * move conf * furo theme * Pass through Kp_float = 0 (#59) * Pass through kp_float, if desired * Minor fixes: schema error and InputReader defaults * Allow pass through of Kp_float = 0 * Add flp parameters to schema * Change Fl_Mode default to 0 * Add defaults to omega_,zeta_ pc and vs, allow to be numbers * Allow single pitch tuning values in code, default U_pc to 0 * use nac acceleration for floating feedback * Fix TSR saturation for region 2.5operation * Modify system for constant power operation * Only modify pole for constant power above-rated * Remove GenEff from K calc * Update tuning, use constant power * use load_rosco_yaml * constant power * Fix broken tests * Include Fl_Mode=2 for nacelle pitching feedback * Add FOCAL inputs - hpf on floating feedback - lpf on wind speed estimator - associated schema updates * Set notch and check frequencies when Fl_Mode = 1 (fixes bug) * Skip filter step if there's an error * Update IEA-15MW test case DISCON with focal inputs * Allow Fl_Mode = 2 in ROSCO * Pass through lpf frequency * Add FOCAL tuning yaml * Set Cp contour number of levels * Add FOCAL params to various writers * Update/tune focal yaml * Add scripts for running FAST, tuning various parameters and cases * Add notebook for FAST plotting * Set up step case for testing * Change doubles to C_doubles * Define real and integer kinds, assign to all of ROSCO * Add ADJUSTL to DISCON error message * Fix Fl_Mode == 2 * Fix Fl_Mode == 2 again * Call yaw, flap, and debug only if enabled in DISOCN.IN * Make avrSWAP a ReKi and set constant kinds * Add DISCONs for testing - revert this later * Fix DISCON comparison, before DISCON's were overwritten by model * Rename DEBUG2.dbg to RootName.dbg2 * Update TestCase DISCONs to new input file * Add API change page in docs * Add link to API change on main page * Fix table headers * Fix title underlines * Fix tables again * Fix tables again * Fix version numbering in docs * Simplify FAST_directory in run_FAST * Versioning (#65) * use sphinx-rtd-theme * master doc and sphinx rtd theme * index back to root folder * only ignore install folders * remove hidden toctree * furo theme * update paths * convert rt version to string * update sphinx settings * move conf * furo theme * remove git versioning from cmake * use hard coded rosco_version * update intro write method * set nowrap for intel compilers * Add transfer of error message and clear message after each call * update install instructions * Catch nans in ROSCO at end of WSE * fix conda install typo * cleanup docs * Rename DEBUG2.dbg to RootName.dbg2 * Fix Fl_Mode == 2 * Fix Fl_Mode == 2 again * Allow Fl_Mode = 2 in ROSCO * Set notch and check frequencies when Fl_Mode = 1 (fixes bug) * Update FOCAL tuning yaml * Update TSR * Clean up and doc fix * Remove publish to pypi * Define all constant inputs to functions with kind typing * Generate Test_Case/ inputs automatically * Fix IEA15 DISCON path * Fix example 11 paths * Auto-generate tuning input yaml using schema * Add toolbox_input to doc index * Add toctree * Re-name title of toolbox_input Co-authored-by: Nikhar Abbas Co-authored-by: Xianping Du <38188001+Seager1989@users.noreply.github.com> Co-authored-by: nikhar-abbas <40865984+nikhar-abbas@users.noreply.github.com> * update listcheck method for numpy arrays * Open Loop Control (#98) * create rosco types yaml * Add more descriptions, add integer_c default, cleanup * updates for allocatability and shapes * python scripts to write ROSCO_types.f90 * reemove superfulous modules * use types from ROSCO registry * create rosco types yaml * Add more descriptions, add integer_c default, cleanup * updates for allocatability and shapes * python scripts to write ROSCO_types.f90 * reemove superfulous modules * use types from ROSCO registry * Saturate inputs to WSE. Needs some TLC, but seems to work * Reduce saturation limits on speed, torque * Re-organize, set saturation limits. Working at 3 m/s * Initial add of OL control to ROSCO: builds * Update DISCONs with open loop inputs * Fix file reading for OL_Filename * Add open loop control generation and file writing * Use DISCON_dict for more manageable DISCON file writing * Add open loop example, fix constant timeseries * Make open loop example generate power * Handle relative paths and calling from outside the run directory: - Some helper functions borrowed from OpenFAST, f/ext_control - Updated file writing * Clean up: versions, print statements * Fix SysFiles paths in CMakeLists * Tidy up Ext_DLL names * More Ext_DLL name tidying * Test write_registry.py * Update for OL Control * Move preprocessor lines * add zenodo DOI * Regenerated Types * fix shape * revert filepath change * give all types a size, ProcAddr size = 3 * update types * test registry in compile step * specify default shell * update write_registry path * remove default shell * Document API changes, provide OL input example * Fix example 14 (yaw input) * Add error catching to yaw control * Tidy up OL_Input Reading: error catching, generalize * More yaw control fixes, to model * Checkout develop CMakeLists for ROSCO * Update DISCON.INs for TestCases/ * Revert "Checkout develop CMakeLists for ROSCO" This reverts commit 87a491359d73806e3aaa59b4cfdc00f2838875df. * Revert windows cmake stuff to develop * Fix CMake again * Revert "Revert windows cmake stuff to develop" This reverts commit 39df122449b0e2055f2e12e3ce38a0c010c7bd91. * Make last cmake fix - hopefully Co-authored-by: Nikhar Abbas * Restart & registry (#99) * Convert WE saved variables to WE type * Put restart flag in localvars * Use saved filter params from LocalVar * save pitcomt last * Move IPC saved variables to localvars * Saved pi controller variables to localvar * Save RootMyb_Last to localvar * ROSCO_IO - initial commit. Include restart and debug functions * Use ROSCO IO and call restart functions * Remove debug from function.f90 * Save ACC Infile info * update for restart capabilities * add rosco_io with restart and debug functions * cleanup debug call * use registry generate types and IO * delete DFController * fix timestep mismatch * remove unnecessaray istatus check * close files * add reg test for restart * add restart option to run_openfast * add testing to CI, ignore generate files * fix fastcall * remove extra commas * specify gfortran-10 * testing flag cleanup * Use lv_strings to generate debug output * Revert "testing flag cleanup" This reverts commit 6f295563832413e96347acd82716f9aadac6d46c. * Revert "specify gfortran-10" This reverts commit 4c3154491523bcd542133ca2bce5803cdc94523f. * minor cleanup * Use kind from constants * Add some comments for clarity * put debug in if statements * separate reg tests from oother tests * Fl_Mode>0 * Remove hard coded values * Add filtered signals and WE_Vw to debug varrs * cd for regtest * Check logging level before calling debug * add fl_pitcom and pc_minpit to debugvars Co-authored-by: dzalkind * Break up if statement in open loop pitch (#100) * Break up if statement in open loop pitch * Make torque and yaw consistent with pitch: can start after some time * add bld edgewise freq to robust dict_inputs * Fix ccrotor inputs (#104) * remove interpolation of blade chord and twist * rename aerodynblade inputs * Update surface and DISCON.INs * Fix performance table paths * Allow default inputs (#110) * Allow defaults for AeroDyn inputs * Allow AeroDyn inputs to be floats, too * ipc (#105) * remove interpolation of blade chord and twist * rename aerodynblade inputs * Update surface and DISCON.INs * Fix performance table paths * Add proportional control and cleanup IPC * Add IPC and filtered RootMyc to registry * Better logic for filtering RootMOOP and fix notch filter slopes bug * Add cyclic flap conrol * Fix comments in ColemanTransformInverse * Addd IPC_KP to DISCON.IN * Error checking foro flp or ipc * add mutichannel plotting with tuples * add CMakeFiles to gitignore * Add IPC_KP to api changes * numerical qualifiers for error handling * add IPC gains to schema for pass-through ability * fix variable names * fix ipc gain printing bug * make sure IPC_KP is positive * Update Polars to point to coord files * ignore dbg2 files * Add IEA15MW_OL.yaml * update coord reader/writer * expand pitch_initial to 30 degrees * Add example 13 for IPC * Update cp surfaces and DISCONS * add examples to readme * cleanup and streaamline run_examples * Add IPC tuning vars * Allow IPC to command pitch value below peak shaving saturation limit * shorten simulation time * Fix Material parameter path * Update DISCONs again * Fix OL_Input reading * Set wind speed, rotor speed IC in example 14 * Debug OL reading * Add more debugging lines * Add more debugging lines 2 * Clean up, hone in on debug call * Disable logging level * Update discons - resolve conflict * Print when finished with ROSCO * add control packageg * Use PriPath and RootName to name dbg files * Print AvrSWAP * Revert "Use PriPath and RootName to name dbg files" This reverts commit 062fcaa55b3bf42d44f8a3f163aa883ab9552412. * Disable other examples * Print OL inputs * Allow logging level 3 * Print OL inputs * Make example shorter * Print more stuf * Print shape * Revert "Print OL inputs" This reverts commit 8e2a642bb35e46850f579ca4e69ca6d6fc93f4cc. * Update ROSCO Simulink model with IPC example * refactor flap tuning for normalization methods * improved flap controller filtering * delete extra F_FlpCornerFrerq * Update inputs, reader, and writer for OF 3.1.0 * Make sigma default interp type for multi_sigma * Use openfast 3.1.0 in CI * Fix leak...maybe * Use OF 3.1.0 in testing * Use gfotran for compile * Clean up print statements * Re-enable all examples * Update NREL-5MW AD file * Only check airfoil controls if more than one table * Update BAR models * Revert "Use gfotran for compile" This reverts commit 5a6e2b7e30287a09a09781e2ba12f9b578132e1f. * Install pyFAST for CI * Fix some paths in ex12 * Disable example 12 * Fix example 12 linear path, re-enable * Skip compilers install for mac * Try gfortran-9, no compilers * Try gfortran-10, no compilers * Skip windows compile in pytools * Re-enable windows, use gfortran as FC * Unset FC in windows * Set environment for windows when dependencies installed * Try setting environment in installation * Put conditional env setting in correct place * Try in setup again * Break up tasks: Windows vs. not * Update DISCONs * Update docs with new variables * Add example documentation * Update ROSCO Simulink model for 3.1.0 * Make IEA model float again * Reduce IEA timestep * Match DT to checkpoint time Co-authored-by: dzalkind * Increment version number * Bladed docs (#116) * Added image of Bladed control screen setup * Delete Bladed control screen.png * Adding image of Bladed control screen * Add files via upload * Minor edit 1 * Minor change 2 * Minor change 3 * Minor change 4 * Change 6 * Change 7 * Change 8 * Minor change 9 Co-authored-by: nikhar-abbas <40865984+nikhar-abbas@users.noreply.github.com> Co-authored-by: WillC-DNV <100850534+WillC-DNV@users.noreply.github.com> * Update version in API change docs * Bladed readthedocs (#117) * Added image of Bladed control screen setup * Delete Bladed control screen.png * Adding image of Bladed control screen * Add files via upload * Minor edit 1 * Minor change 2 * Minor change 3 * Minor change 4 * Change 6 * Change 7 * Change 8 * Minor change 9 * Tinker with characters in bladed instructions * Add bladed instructions to index * Change bladed toctree label * Do underline stuff * Make toctree label same as file * Remove colons from headers Co-authored-by: nikhar-abbas <40865984+nikhar-abbas@users.noreply.github.com> Co-authored-by: WillC-DNV <100850534+WillC-DNV@users.noreply.github.com> * Update docs to reflect CI process Co-authored-by: Nikhar Abbas Co-authored-by: Xianping Du <38188001+Seager1989@users.noreply.github.com> Co-authored-by: nikhar-abbas <40865984+nikhar-abbas@users.noreply.github.com> Co-authored-by: WillC-DNV <100850534+WillC-DNV@users.noreply.github.com> * Fixed wrong formatting of list items (#122) extra newline required between list elements * Regenerate types, IO with registry * Update registry so first timestep is printed * Update inverted notch to move frequency properly * Saturate inv notch corner frequency at 0 * Add tower damper mode flag * Add Azimuth tracking controller in Simulink * Always enable GenDOF, add options for simp_step * Add sweep for IPC gains and FA damper * Fix NumCoords in FAST_writer * Add turbulent case to runFAST/CaseLibrary * Add peak shaving sweep function * Increase default IPC_IntSat, make input parameter in future * Flip Ct and Cq table allocation (#129) * Flip Ct and Cq table allocation * Regen types * Remove print statements used for debugging * Update input files: IEA model has pitch actuator * Add back flap control (no idea when it was deleted) * Update discons, docs with API change * Add user-defined hh case * Fix AddF0 and RayleighDamp in FAST_reader * Add max_torque_factor for constant power control, flexible upper limit * Make update discons relative to tuning yaml * Update AddF0 and NumCoords in FAST_reader/writer * Remove matlab/rotor position control stuff * Add initial DISCON pass through schema * Add TODO items for pull requests * Add initial pass through capability, example * Add PassThrough example yaml * Make cp filename relative to FAST_directory throughout * Remove brackets, regen input docs * Add to PassThrough example yaml * Add example 15 to testing, fix yaml * Tidy comments in CaseLibrary Co-authored-by: nikhar-abbas <40865984+nikhar-abbas@users.noreply.github.com> Co-authored-by: Nikhar Abbas Co-authored-by: Xianping Du <38188001+Seager1989@users.noreply.github.com> Co-authored-by: WillC-DNV <100850534+WillC-DNV@users.noreply.github.com> Co-authored-by: Gustavo Hylander <74593034+ghylander@users.noreply.github.com> * Add ExtControl manually from f/ext_control, compiling * Fix c_float type in registry, building * Update DISCON writer, fix reader * Add example for running Ext control, running * Max example actually call extdll, update inputs, running * Add ExtControl module! * Add ROSCO_Helpers, GetNewUnit, shorten ReadSetParameters, Functions * Update write_registry with GetNewUnit * Add open loop IPC * Robust control updates (#139) * change default interp type * improve nested MPI handling * fix cl bug, sm calc more robust, allow single plant for interp * add load from pickle capabilites * add re-try logic * save v_above_rated to controller object * fix BAR cp_ct_cq surface path * update discons * remove rogue DISCON * Pass case_inputs and rosco_dll to runFAST object * Set default T_max in power_curve case * Add rotor position control example * Add inputs for Azimuth index and rotor pos gains * Set up OL IPC example, working, refactor OL setup in RT * External Control Interface (#141) * Add ExtControl manually from f/ext_control, compiling * Fix Cp plots * Update multiple discons * Make FAST_Directory relative to yaml * Set control to ROSCO, sweep max torque * Fix c_float type in registry, building * Update DISCON writer, fix reader * Add example for running Ext control, running * Max example actually call extdll, update inputs, running * Add ExtControl module! * Add ROSCO_Helpers, GetNewUnit, shorten ReadSetParameters, Functions * Update write_registry with GetNewUnit * Tidy up RootName: remove hard-coded index * Close Cp file, fixes checkpoint test * Clean up examples, add 16 to CI testing * Change regtest name in CI * Update DISCONs * Add API change documentation * Add summary of API changes, finish external interface * Tidy code, point to location for using ExtDLL * F/zmq (#145) * cleanup api change table * zeromq client and f90 files - initia lcommit * add zmq install reqs * remove yaw-by-ipc * typo fix * add zeroMQ interface to registry and source - enable zeroMQ for yaw control * cleanup to compile, move ZMQ_Mode to flags, write DISCONS * only set ZMQ_Client if flag is enabled * fix bug in discons * minor updates and add sim with wind direction * change to dict inputs for control interface * add zmq example * Revert "remove yaw-by-ipc" This reverts commit 2ca2859884313aa6d8fdd217a7fede73802a5fcf. * Enable Yaw-by-ipc again * update and execute zeromq example * add zmq to dependencies * sudo for apt-get * libzmq3-dev typo * setup cmake * rename example 16 to 17 * read empty line * update types, regen discons * fix build path * remove non-ubuntu examples, type in cmake command * Set ROSCO=True * typo fix and update DISCONs * document API changes * newlines and in-text code * updated removed inputs, fix intext code syntax * run example 17 * Add description to example 17 * zeromq -> pyzmq, cleanup * better table for new/modified/removed * fix real(8) * cleanup zmqVar conventions and uses. Call zmq using a time period * Update DISCONS * run all examples * Fix Y_uSwitch description * update comm address example * execute with runpy instead of importlib * move zmq interface classes to control_interface * Properly shutdown ZMQ interface * add IEA15MW_ExtInterface.yaml * Incorporate runFAST stuff from WEIS, clean up * Remove specific rosco_dll * Publish artifacts from examples * Clean up examples following runFAST business * move archive artifacts * Fix build dir in example 17 * Switch install/develop in pytools CI * archive even if exampless fail * add zmq build instructions * cleanup and rename sim * Remove BITS_IN_ADDR stuff * Pass case_inputs and rosco_dll to runFAST object * Pass correct DLL_FileName for external control * Tidy example 15 commenting Co-authored-by: dzalkind * Tidy up OL_Mode * Add unwrap function, working on OL target * Set azimuth ol_timeseries in radians * Move example number * Add default Ind_Azimuth, regen DISCONs * Tidy merge, building * Calculate azimuth error * Make PID control, building * Add collective blade pitch signal for WSE, shutdown * Clean up merge: two sigma functions, finish adding collective BP * Use IPC always in IEA-15MW case * Add IPC_SatMode input * Force IPC_SatMode to be an int in writer * Fix IPC_SatMode cherry pick * Fix IPC_SatMode/IntSat description, update DISCONs * Add new IPC_SatModes * Fix ******s in dbg files * Move example 18 to 19 (rotor position control) * Tidy up types, regen Types, IO, DISCONs * Make openfast_exe an attribute * Update and run example_19 * Set up PID control for GenTqAz, working in steady * Set up turbulence example * Rate limit blade pitch on first time step * Initialize AzBuffer * Fix open loop IPC * Add SCADA to example_19, needs tuning * Fix PID, tune gains for RAAW, working * Sync OF tools with WEIS * Add DT_Out to ROSCO to downsample debug files * Update user defined controller parameters deep in control_param dict * AWC First Version, collected changes * Add AWC parameters to registry, regenerate types * Apply DbKi to COMPLEX * Re-organize AWC pitch contribution, before actuator * Separate contribution to PitCom from mode calculation * Make AWC_complexangle a LocalVar for logging * Start DISCON_dict with schema defaults * Allow DEFAULT in read_DISCON * Removed duplicate pitch assignment and removed MinPitch mods for AWC * Fixes to readsetparams and awc location * Adding NREL 2.8 127 for AWC testing * Add case generation updates * Add initial AWC example, needs OF3.4 * Add AWC_Mode and move AWC into subroutine * Update example to point to correct inputs * Remove LocalVar%PC_MinPit = CntrPar%PC_MinPit, breaking setpoint smoother * Set min pitch for AWC * Tidy up input additions * Update other DISCONs * Add AWC to toolbox schema * Tidy example * Update AWC example with instructions/theory * Formatting fixes * Prep for more modes * Set up baseline cases in example_19 * Set up sweep cases in run_FAST * Fix bug in FAST_writer * Update 20_active_wake_control.py * Fix units in schema * Test all AWC cases in example 20 * Tidy up DISCON file writing * Revert setup directory * Update 20_active_wake_control.py Documentation update: -added type of input, either integer or float -added suggested ranges for input variables (only one of these ranges is a hard rule that might break something if not followed, which is that AWC_NumModes>=0) -added more description of what the azimuthal mode number is Note to Dan: I didn't follow exactly if the units in the code changed between rad and deg - can you check that the units in rows 14-16 are correct? Also, let's have Lawrence review these additions. * Update NREL-2p8-127_DISCON.IN Updating units. * Update Controllers.f90 Update units. * Update ROSCO_Types.f90 Update units. * Update ReadSetParameters.f90 Update units. * Update 20_active_wake_control.py Update units and documentation. * Update toolbox_schema.yaml Update units. * Update utilities.py Update AWC descriptions and units. * Update rosco_types.yaml Update AWC units. * Added NREL-developed AWC-implementation * Undo unintentional changes to wrie_registry.py * Fix file writing in AWC section * Update all DISCONs * Add 20_awc to test_examples * Add 2.8 to update_discons, regenerate DISCON Should match closely to original DISCON * Update AWC_Mode descriptions * Updated Coleman Transformation based AWC * Tidy print statements, file writing * Remove duplicate PF_Offsets input read * Rename methods in readme * Tidy input writing, remove `future` references * Force AWC_n into int * Force AWC_n into int better * Make AWC_n a list, too * Fix input file writing, force into int in write_array * Run ROSCO_testing from anywhere * Dylib -> so in Test_Cases * Rename example * Complete merge, building * Get openfast read/write from 3.4 * Fix error message in dbl read * Update example number for output file * Change default DT_Out to 0 * Remove raaw example parts * Update discons * Give new model, relative path for example * Regen registry * Tidy up indices, example running * Remove old update_discons * Clean up print statements * Clean up rpc example * Change name of rpc example * Tidy up paths in RPC example * Fix original open loop set up * Fix OL file writing for Cable/StC * Fix OL indices again * Remove duplicate PF_Mode * Regen registry files, discons * Clean up cable control example * Add RPC example to CI * Remove duplicate AWC inputs from registry * Clean up open loop yaw control * Clean up AWC implementation again * Regen registry * Revert AWC controller * Allow defaults for DT_Out, LoggingLevel * Clean up run_FAST * Update input writer, inputs * Document API changes * Fix relative Cp filepaths * Move all CntrPar%* assignments to ReadControlParameterFileSub Otherwise, they are lost in restarts * Write dbg3 only at DT_Out * Tidy up examples * Pass fst_vt from runFAST properly * Change AFAeroMod only in DLC 1.4 sims * Saturate lower limit of WSE initialization * Give max() proper inputs * Do a light clean up * Revert moordyn * Remove duplicate import * Clean up types * Saturate values too large for fortran write format * Fix example 25 output folder * Update docs to use python 3.9 * Add Tf for derivative term of RPC --------- Co-authored-by: Nikhar Abbas Co-authored-by: Nikhar J. Abbas <40865984+nikhar-abbas@users.noreply.github.com> Co-authored-by: WillC-DNV <100850534+WillC-DNV@users.noreply.github.com> Co-authored-by: Xianping Du <38188001+Seager1989@users.noreply.github.com> Co-authored-by: Gustavo Hylander <74593034+ghylander@users.noreply.github.com> Co-authored-by: Nathaniel deVelder Co-authored-by: kbrown1snl <66843135+kbrown1snl@users.noreply.github.com> Co-authored-by: jfrederik-nrel --- Examples/16_external_dll.py | 3 +- Examples/22_cable_control.py | 1 - Examples/25_rotor_position_control.py | 120 +++++++ Examples/test_examples.py | 1 + ROSCO/rosco_registry/rosco_types.yaml | 75 +++- ROSCO/rosco_registry/write_registry.py | 32 +- ROSCO/src/ControllerBlocks.f90 | 4 +- ROSCO/src/Controllers.f90 | 51 ++- ROSCO/src/DISCON.F90 | 1 - ROSCO/src/Functions.f90 | 108 +++++- ROSCO/src/ROSCO_Helpers.f90 | 10 +- ROSCO/src/ROSCO_IO.f90 | 304 +++++++++-------- ROSCO/src/ROSCO_Types.f90 | 24 +- ROSCO/src/ReadSetParameters.f90 | 321 ++++++++++++------ ROSCO_toolbox/control_interface.py | 1 + ROSCO_toolbox/controller.py | 116 +++++-- ROSCO_toolbox/inputs/toolbox_schema.yaml | 62 +++- .../ofTools/case_gen/CaseGen_General.py | 2 +- ROSCO_toolbox/ofTools/case_gen/CaseGen_IEC.py | 3 - ROSCO_toolbox/ofTools/case_gen/CaseLibrary.py | 29 +- ROSCO_toolbox/ofTools/case_gen/run_FAST.py | 74 +--- .../ofTools/fast_io/update_discons.py | 8 +- ROSCO_toolbox/utilities.py | 20 +- Test_Cases/BAR_10/BAR_10_DISCON.IN | 15 +- .../DISCON-UMaineSemi.IN | 15 +- Test_Cases/NREL-5MW/DISCON.IN | 15 +- .../NREL_2p8_127/NREL-2p8-127_DISCON.IN | 15 +- Tune_Cases/IEA15MW_OL.yaml | 3 +- Tune_Cases/IEA15MW_ballast.yaml | 3 +- Tune_Cases/IEA15MW_cable.yaml | 3 +- docs/source/api_change.rst | 58 ++-- docs/source/install.rst | 2 +- docs/source/toolbox_input.rst | 54 ++- 33 files changed, 1081 insertions(+), 472 deletions(-) create mode 100644 Examples/25_rotor_position_control.py diff --git a/Examples/16_external_dll.py b/Examples/16_external_dll.py index afb629ec..e876b2c3 100644 --- a/Examples/16_external_dll.py +++ b/Examples/16_external_dll.py @@ -43,7 +43,6 @@ def main(): # Set DLL file and DISCON input dynamically (hard-coded in yaml) controller_params = {} controller_params['DISCON'] = {} - controller_params['OL_Mode'] = 2 controller_params['DISCON']['DLL_FileName'] = copy_lib controller_params['DISCON']['DLL_InFile'] = os.path.join(rosco_dir,'Test_Cases/NREL-5MW/DISCON.IN') controller_params['DISCON']['DLL_ProcName'] = 'DISCON' @@ -65,4 +64,4 @@ def main(): if __name__=="__main__": - main() \ No newline at end of file + main() diff --git a/Examples/22_cable_control.py b/Examples/22_cable_control.py index 467ed629..7956d44a 100644 --- a/Examples/22_cable_control.py +++ b/Examples/22_cable_control.py @@ -120,7 +120,6 @@ def main(): r.controller_params = controller_params r.save_dir = run_dir r.rosco_dir = rosco_dir - r.run_FAST() diff --git a/Examples/25_rotor_position_control.py b/Examples/25_rotor_position_control.py new file mode 100644 index 00000000..2bbf494b --- /dev/null +++ b/Examples/25_rotor_position_control.py @@ -0,0 +1,120 @@ +''' +----------- 25_rotor_position_control -------------- +Run ROSCO with rotor position control +------------------------------------- + +Run a steady simulation, use the azimuth output as an input to the next steady simulation, with different ICs + +''' + +import os, platform +from ROSCO_toolbox.ofTools.case_gen.run_FAST import run_FAST_ROSCO +from ROSCO_toolbox.ofTools.case_gen import CaseLibrary as cl +from ROSCO_toolbox.ofTools.fast_io import output_processing +from ROSCO_toolbox.controller import OpenLoopControl +import numpy as np +import pandas as pd +import matplotlib.pyplot as plt + +#directories +this_dir = os.path.dirname(os.path.abspath(__file__)) +rosco_dir = os.path.dirname(this_dir) +example_out_dir = os.path.join(this_dir,'examples_out') +os.makedirs(example_out_dir,exist_ok=True) + +if platform.system() == 'Windows': + lib_name = os.path.realpath(os.path.join(this_dir, '../ROSCO/build/libdiscon.dll')) +elif platform.system() == 'Darwin': + lib_name = os.path.realpath(os.path.join(this_dir, '../ROSCO/build/libdiscon.dylib')) +else: + lib_name = os.path.realpath(os.path.join(this_dir, '../ROSCO/build/libdiscon.so')) + +def main(): + + + # Set up paths + parameter_filename = os.path.join(rosco_dir,'Tune_Cases/NREL2p8.yaml') + run_dir = os.path.join(example_out_dir,'25_rotor_position_control') + os.makedirs(run_dir,exist_ok=True) + + # Steady simualtion with initial RotSpeed of 5 rpm + r = run_FAST_ROSCO() + r.wind_case_fcn = cl.power_curve + r.tuning_yaml = parameter_filename + r.wind_case_opts = { + 'U': [14], + 'TMax': 100, + } + r.save_dir = run_dir + r.run_FAST() + + # Gather azimuth, blade pitch, generator torque output, apply as open loop inputs to ROSCO + op = output_processing.output_processing() + fast_out = op.load_fast_out(os.path.join(run_dir,'NREL2p8/power_curve/base/NREL2p8_0.outb'), tmin=0) + + olc = OpenLoopControl() + olc.ol_timeseries['time'] = fast_out[0]['Time'] + olc.ol_timeseries['blade_pitch1'] = np.radians(fast_out[0]['BldPitch1']) + olc.ol_timeseries['blade_pitch2'] = np.radians(fast_out[0]['BldPitch2']) + olc.ol_timeseries['blade_pitch3'] = np.radians(fast_out[0]['BldPitch3']) + olc.ol_timeseries['generator_torque'] = fast_out[0]['GenTq'] * 1000 + olc.ol_timeseries['azimuth'] = np.radians(fast_out[0]['Azimuth']) + + # Save initial RotSpeed, Azimuth for later + RotSpeed_0 = fast_out[0]['RotSpeed'][0] + Azimuth_0 = fast_out[0]['Azimuth'][0] + + # set up control_params for next run + open_loop = olc.write_input(os.path.join(run_dir,'ol_input.dat')) + controller_params = {} + controller_params['open_loop'] = open_loop + controller_params['OL_Mode'] = 2 # Azimuth tracking open loop + controller_params['PA_Mode'] = 0 # No pitch actuator + controller_params['DISCON'] = {} + + gains = -1800 * np.array([12,1.2,120]) # PID gains of rotor position control + controller_params['DISCON']['RP_Gains'] = np.r_[gains, 2] # Add Tf + controller_params['DISCON']['PC_MinPit'] = np.radians(-20) # Remove lower limit of pitch so it doesn't interfere with open loop input + + + # run again with different IC and rotor position control + r.base_name = 'rpc' + r.tuning_yaml = parameter_filename + # Set initial conditions + r.case_inputs = {} + r.case_inputs[("ElastoDyn","RotSpeed")] = {'vals':[RotSpeed_0 + 1], 'group':0} + r.case_inputs[("ElastoDyn","Azimuth")] = {'vals':[Azimuth_0 + 30], 'group':0} + r.case_inputs[("ServoDyn","Ptch_Cntrl")] = {'vals':[1], 'group':0} + + r.controller_params = controller_params + r.run_FAST() + + # Plot relevant outputs + op = output_processing.output_processing() + op_dbg2 = output_processing.output_processing() + + out_files = [os.path.join(run_dir,f'NREL2p8/power_curve/base/NREL2p8_0.out'), + os.path.join(run_dir,f'rpc/power_curve/base/rpc_0.out')] + dbg2_files = [out.split('.out')[0] + '.RO.dbg2' for out in out_files] + + fst_out = op.load_fast_out(out_files, tmin=0) + local_vars = op_dbg2.load_fast_out(dbg2_files, tmin=0) + + comb_out = [None] * len(fst_out) + for i, (r_out2, f_out) in enumerate(zip(local_vars,fst_out)): + r_out2.update(f_out) + comb_out[i] = r_out2 + + cases = {} + cases['Fl Sigs.'] = ['BldPitch1','GenTq','GenSpeed', 'Azimuth', 'AzError','GenTqAz'] + fig, ax = op.plot_fast_out(comb_out,cases, showplot=True) + + if False: + plt.show() + else: + plt.savefig(os.path.join(run_dir,'25_rotor_position_control.png')) + + + +if __name__=="__main__": + main() \ No newline at end of file diff --git a/Examples/test_examples.py b/Examples/test_examples.py index 5f45ec06..244c288a 100644 --- a/Examples/test_examples.py +++ b/Examples/test_examples.py @@ -27,6 +27,7 @@ '22_cable_control', '23_structural_control', '24_floating_feedback', + '25_rotor_position_control', 'update_rosco_discons', ] diff --git a/ROSCO/rosco_registry/rosco_types.yaml b/ROSCO/rosco_registry/rosco_types.yaml index 0c4bfdeb..91d1b90b 100644 --- a/ROSCO/rosco_registry/rosco_types.yaml +++ b/ROSCO/rosco_registry/rosco_types.yaml @@ -1,7 +1,8 @@ default_types: integer: &integer type: integer - description: + description: + dimension: allocatable: False equals: size: 0 @@ -79,6 +80,15 @@ ControlParameters: Echo: <<: *integer description: 0 - no Echo, 1 - Echo input data to .echo + + DT_Out: + <<: *real + description: Output time step + + n_DT_Out: + <<: *integer + description: output every this many steps + # Filters F_LPFType: <<: *integer @@ -418,13 +428,21 @@ ControlParameters: description: The column in OL_Filename that contains the breakpoint (time if OL_Mode = 1) Ind_BldPitch: <<: *integer - description: The column in OL_Filename that contains the blade pitch input in rad + description: The columns in OL_Filename that contains the blade pitch inputs (1,2,3) in rad + allocatable: True Ind_GenTq: <<: *integer description: The column in OL_Filename that contains the generator torque in Nm Ind_YawRate: <<: *integer description: The column in OL_Filename that contains the generator torque in Nm + Ind_Azimuth: + <<: *integer + description: The column in OL_Filename that contains the desired azimuth position in rad (used if OL_Mode = 2) + RP_Gains: + <<: *real + description: PID gains and Tf on derivative term for rotor position control (used if OL_Mode = 2) + allocatable: True Ind_CableControl: <<: *integer allocatable: True @@ -437,10 +455,18 @@ ControlParameters: <<: *real allocatable: True description: Open loop breakpoints in timeseries - OL_BldPitch: + OL_BldPitch1: + <<: *real + allocatable: True + description: Open loop blade pitch 1 timeseries + OL_BldPitch2: <<: *real allocatable: True - description: Open blade pitch timeseries + description: Open loop blade pitch 2 timeseries + OL_BldPitch3: + <<: *real + allocatable: True + description: Open loop blade pitch 3 timeseries OL_CableControl: <<: *real allocatable: True @@ -452,11 +478,15 @@ ControlParameters: OL_GenTq: <<: *real allocatable: True - description: Open generator torque timeseries + description: Open loop generator torque timeseries OL_YawRate: <<: *real allocatable: True - description: Open yaw rate timeseries + description: Open loop yaw rate timeseries + OL_Azimuth: + <<: *real + allocatable: True + description: Open loop azimuth timeseries OL_Channels: <<: *real allocatable: True @@ -501,7 +531,7 @@ ControlParameters: <<: *real allocatable: True description: AWC clocking angle [deg] - + # Pitch actuator error PF_Mode: <<: *integer @@ -511,6 +541,7 @@ ControlParameters: description: Pitch actuator fault offsets for blade 1-3 [rad/s] allocatable: True + # External Control Ext_Mode: <<: *integer @@ -818,6 +849,10 @@ piParams: <<: *real dimension: (99) description: Previous integrator term - second integrator + ELast: + <<: *real + dimension: (99) + description: Previous error term for derivative LocalVariables: iStatus: @@ -829,6 +864,15 @@ LocalVariables: DT: <<: *real description: Time step [s] + WriteThisStep: + <<: *logical + description: Write an output line this time step + n_DT: + <<: *integer + description: number of timesteps since start + Time_Last: + <<: *real + description: Last time [s] VS_GenPwr: <<: *real description: Generator power [W] @@ -865,6 +909,22 @@ LocalVariables: Azimuth: <<: *real description: Rotor aziumuth angle [rad] + OL_Azimuth: + <<: *real + description: Rotor aziumuth angle [rad] + AzUnwrapped: + <<: *real + description: Rotor aziumuth angle [rad] + AzError: + <<: *real + description: Azimuth error angle [rad] + GenTqAz: + <<: *real + description: Gen torque command due to azimuth error + AzBuffer: + <<: *real + size: 2 + description: Current and last rotor aziumuth angles [rad] NumBl: <<: *integer description: Number of blades [-] @@ -1271,7 +1331,6 @@ DebugVariables: axisYaw_2P: <<: *real description: Yaw component of coleman transformation, 2P - YawRateCom: <<: *real description: Commanded yaw rate [rad/s]. diff --git a/ROSCO/rosco_registry/write_registry.py b/ROSCO/rosco_registry/write_registry.py index 2f31b400..db9d7ad7 100644 --- a/ROSCO/rosco_registry/write_registry.py +++ b/ROSCO/rosco_registry/write_registry.py @@ -163,7 +163,7 @@ def write_roscoio(yfile): file.write(' Close ( Un )\n') file.write(' ENDIF\n') file.write(' ! Read Parameter files\n') - file.write(' CALL ReadControlParameterFileSub(CntrPar, zmqVar, LocalVar%ACC_INFILE, LocalVar%ACC_INFILE_SIZE, RootName, ErrVar)\n') + file.write(' CALL ReadControlParameterFileSub(CntrPar, LocalVar, zmqVar, LocalVar%ACC_INFILE, LocalVar%ACC_INFILE_SIZE, RootName, ErrVar)\n') file.write(' IF (CntrPar%WE_Mode > 0) THEN\n') file.write(' CALL READCpFile(CntrPar, PerfData, ErrVar)\n') file.write(' ENDIF\n') @@ -337,29 +337,37 @@ def write_roscoio(yfile): file.write(" ! Process DebugOutData, LocalVarOutData\n") file.write(" ! Remove very small numbers that cause ******** outputs\n") file.write(" DO I = 1,SIZE(DebugOutData)\n") - file.write(" IF (ABS(DebugOutData(I)) < 1E-10) THEN\n") + file.write(" IF (ABS(DebugOutData(I)) < 1E-99) THEN\n") file.write(" DebugOutData(I) = 0\n") file.write(" END IF\n") + file.write(" IF (ABS(DebugOutData(I)) > 1E+99) THEN\n") + file.write(" DebugOutData(I) = 1E+99\n") + file.write(" END IF\n") file.write(" END DO\n") file.write(" \n") file.write(" DO I = 1,SIZE(LocalVarOutData)\n") - file.write(" IF (ABS(LocalVarOutData(I)) < 1E-10) THEN\n") + file.write(" IF (ABS(LocalVarOutData(I)) < 1E-99) THEN\n") file.write(" LocalVarOutData(I) = 0\n") file.write(" END IF\n") + file.write(" IF (ABS(LocalVarOutData(I)) > 1E+99) THEN\n") + file.write(" LocalVarOutData(I) = 1E+99\n") + file.write(" END IF\n") file.write(" END DO\n") file.write(" \n") file.write(" ! Write debug files\n") file.write(f' FmtDat = "(F20.5,TR5,{n_lv_outputs}(ES20.5E2,TR5:))" ! The format of the debugging data\n') - file.write(" IF(CntrPar%LoggingLevel > 0) THEN\n") - file.write(" WRITE (UnDb, TRIM(FmtDat)) LocalVar%Time, DebugOutData\n") - file.write(" END IF\n") + file.write(" IF ( MOD(LocalVar%n_DT, CntrPar%n_DT_Out) == 0) THEN\n") + file.write(" IF(CntrPar%LoggingLevel > 0) THEN\n") + file.write(" WRITE (UnDb, FmtDat) LocalVar%Time, DebugOutData\n") + file.write(" END IF\n") file.write("\n") - file.write(" IF(CntrPar%LoggingLevel > 1) THEN\n") - file.write(" WRITE (UnDb2, TRIM(FmtDat)) LocalVar%Time, LocalVarOutData\n") - file.write(" END IF\n") + file.write(" IF(CntrPar%LoggingLevel > 1) THEN\n") + file.write(" WRITE (UnDb2, FmtDat) LocalVar%Time, LocalVarOutData\n") + file.write(" END IF\n") file.write("\n") - file.write(" IF(CntrPar%LoggingLevel > 2) THEN\n") - file.write(" WRITE (UnDb3, TRIM(FmtDat)) LocalVar%Time, avrSWAP(avrIndices)\n") + file.write(" IF(CntrPar%LoggingLevel > 2) THEN\n") + file.write(" WRITE (UnDb3, TRIM(FmtDat)) LocalVar%Time, avrSWAP(avrIndices)\n") + file.write(" END IF\n") file.write(" END IF\n") file.write("\n") file.write("END SUBROUTINE Debug\n") @@ -383,6 +391,8 @@ def read_type(param): f90type = 'INTEGER(IntKi)' if param['allocatable']: f90type += ', DIMENSION(:), ALLOCATABLE' + elif param['dimension']: + f90type += ', DIMENSION{}'.format(param['dimension']) elif param['type'] == 'real': f90type = 'REAL(DbKi)' if param['allocatable']: diff --git a/ROSCO/src/ControllerBlocks.f90 b/ROSCO/src/ControllerBlocks.f90 index 390be8d0..a9ad8af0 100644 --- a/ROSCO/src/ControllerBlocks.f90 +++ b/ROSCO/src/ControllerBlocks.f90 @@ -248,8 +248,8 @@ SUBROUTINE WindSpeedEstimator(LocalVar, CntrPar, objInst, PerfData, DebugVar, Er ! Initialize recurring values LocalVar%WE%om_r = WE_Inp_Speed LocalVar%WE%v_t = 0.0 - LocalVar%WE%v_m = LocalVar%HorWindV - LocalVar%WE%v_h = LocalVar%HorWindV + LocalVar%WE%v_m = max(LocalVar%HorWindV, 3.0_DbKi) ! avoid divide by 0 below if HorWindV is 0, which some AMRWind setups create + LocalVar%WE%v_h = max(LocalVar%HorWindV, 3.0_DbKi) ! avoid divide by 0 below if HorWindV is 0, which some AMRWind setups create lambda = WE_Inp_Speed * CntrPar%WE_BladeRadius/LocalVar%WE%v_h LocalVar%WE%xh = RESHAPE((/LocalVar%WE%om_r, LocalVar%WE%v_t, LocalVar%WE%v_m/),(/3,1/)) LocalVar%WE%P = RESHAPE((/0.01, 0.0, 0.0, 0.0, 0.01, 0.0, 0.0, 0.0, 1.0/),(/3,3/)) diff --git a/ROSCO/src/Controllers.f90 b/ROSCO/src/Controllers.f90 index 28676dc4..15bd2223 100644 --- a/ROSCO/src/Controllers.f90 +++ b/ROSCO/src/Controllers.f90 @@ -116,11 +116,19 @@ SUBROUTINE PitchControl(avrSWAP, CntrPar, LocalVar, objInst, DebugVar, ErrVar) ! Open Loop control, use if ! Open loop mode active Using OL blade pitch control - IF ((CntrPar%OL_Mode == 1) .AND. (CntrPar%Ind_BldPitch > 0)) THEN + IF (CntrPar%OL_Mode > 0) THEN IF (LocalVar%Time >= CntrPar%OL_Breakpoints(1)) THEN ! Time > first open loop breakpoint - DO K = 1,LocalVar%NumBl ! Loop through all blades - LocalVar%PitCom(K) = interp1d(CntrPar%OL_Breakpoints,CntrPar%OL_BldPitch,LocalVar%Time, ErrVar) - END DO + IF (CntrPar%Ind_BldPitch(1) > 0) THEN + LocalVar%PitCom(1) = interp1d(CntrPar%OL_Breakpoints,CntrPar%OL_BldPitch1,LocalVar%Time, ErrVar) + ENDIF + + IF (CntrPar%Ind_BldPitch(2) > 0) THEN + LocalVar%PitCom(2) = interp1d(CntrPar%OL_Breakpoints,CntrPar%OL_BldPitch2,LocalVar%Time, ErrVar) + ENDIF + + IF (CntrPar%Ind_BldPitch(3) > 0) THEN + LocalVar%PitCom(3) = interp1d(CntrPar%OL_Breakpoints,CntrPar%OL_BldPitch3,LocalVar%Time, ErrVar) + ENDIF ENDIF ENDIF @@ -201,7 +209,7 @@ SUBROUTINE VariableSpeedControl(avrSWAP, CntrPar, LocalVar, objInst, ErrVar) ! VS_MaxTq = CntrPar%VS_MaxTq ! NJA: May want to boost max torque LocalVar%VS_MaxTq = CntrPar%VS_RtTq ENDIF - + ! Optimal Tip-Speed-Ratio tracking controller IF ((CntrPar%VS_ControlMode == 2) .OR. (CntrPar%VS_ControlMode == 3)) THEN ! Constant Power, update VS_MaxTq @@ -244,10 +252,35 @@ SUBROUTINE VariableSpeedControl(avrSWAP, CntrPar, LocalVar, objInst, ErrVar) LocalVar%GenTq = ratelimit(LocalVar%GenTq, -CntrPar%VS_MaxRat, CntrPar%VS_MaxRat, LocalVar%DT, LocalVar%restart, LocalVar%rlP,objInst%instRL) ! Saturate the command using the torque rate limit ! Open loop torque control - IF ((CntrPar%OL_Mode == 1) .AND. (CntrPar%Ind_GenTq > 0)) THEN + IF ((CntrPar%OL_Mode > 0) .AND. (CntrPar%Ind_GenTq > 0)) THEN + ! Get current OL GenTq, applies for OL_Mode 1 and 2 IF (LocalVar%Time >= CntrPar%OL_Breakpoints(1)) THEN LocalVar%GenTq = interp1d(CntrPar%OL_Breakpoints,CntrPar%OL_GenTq,LocalVar%Time,ErrVar) ENDIF + + ! Azimuth tracking control + IF (CntrPar%OL_Mode == 2) THEN + + ! Push, pop and unwrap azimuth buffer + ! Initialize + IF (LocalVar%iStatus == 0) THEN + LocalVar%AzBuffer(1) = LocalVar%Azimuth + LocalVar%AzBuffer(2) = LocalVar%Azimuth + ENDIF + LocalVar%AzBuffer(1) = LocalVar%AzBuffer(2) + LocalVar%AzBuffer(2) = LocalVar%Azimuth + LocalVar%AzBuffer = UNWRAP(LocalVar%AzBuffer, ErrVar) + LocalVar%AzUnwrapped = LocalVar%AzBuffer(2) + + ! Current desired Azimuth, error + LocalVar%OL_Azimuth = interp1d(CntrPar%OL_Breakpoints,CntrPar%OL_Azimuth,LocalVar%Time,ErrVar) + LocalVar%AzError = LocalVar%OL_Azimuth - LocalVar%AzUnwrapped + + LocalVar%GenTqAz = PIDController(LocalVar%AzError, CntrPar%RP_Gains(1), CntrPar%RP_Gains(2), CntrPar%RP_Gains(3), CntrPar%RP_Gains(4), -LocalVar%VS_MaxTq * 2, LocalVar%VS_MaxTq * 2, LocalVar%DT, 0.0_DbKi, LocalVar%piP, LocalVar%restart, objInst, LocalVar) + LocalVar%GenTq = LocalVar%GenTq + LocalVar%GenTqAz + + ENDIF + ENDIF ! Reset the value of LocalVar%VS_LastGenTrq to the current values: @@ -372,7 +405,7 @@ SUBROUTINE YawRateControl(avrSWAP, CntrPar, LocalVar, objInst, zmqVar, DebugVar, avrSWAP(48) = YawRateCom * D2R ! If using open loop yaw rate control, overwrite controlled output - ! Open loop torque control + ! Open loop yaw rate control - control input in rad/s IF ((CntrPar%OL_Mode == 1) .AND. (CntrPar%Ind_YawRate > 0)) THEN IF (LocalVar%Time >= CntrPar%OL_Breakpoints(1)) THEN avrSWAP(48) = interp1d(CntrPar%OL_Breakpoints,CntrPar%OL_YawRate,LocalVar%Time, ErrVar) @@ -570,7 +603,7 @@ SUBROUTINE FlapControl(avrSWAP, CntrPar, LocalVar, objInst) LocalVar%Flp_Angle(3) = CntrPar%Flp_Angle ! Initialize controller IF (CntrPar%Flp_Mode == 2) THEN - LocalVar%Flp_Angle(K) = PIIController(RootMyb_VelErr(K), 0 - LocalVar%Flp_Angle(K), CntrPar%Flp_Kp, CntrPar%Flp_Ki, 0.05, -CntrPar%Flp_MaxPit , CntrPar%Flp_MaxPit , LocalVar%DT, 0.0, LocalVar%piP, LocalVar%restart, objInst%instPI) + LocalVar%Flp_Angle(K) = PIIController(RootMyb_VelErr(K), 0 - LocalVar%Flp_Angle(K), CntrPar%Flp_Kp, CntrPar%Flp_Ki, 0.05_DbKi, -CntrPar%Flp_MaxPit , CntrPar%Flp_MaxPit , LocalVar%DT, 0.0_DbKi, LocalVar%piP, LocalVar%restart, objInst%instPI) ENDIF ! Steady flap angle @@ -583,7 +616,7 @@ SUBROUTINE FlapControl(avrSWAP, CntrPar, LocalVar, objInst) ELSEIF (CntrPar%Flp_Mode == 2) THEN DO K = 1,LocalVar%NumBl ! Find flap angle command - includes an integral term to encourage zero flap angle - LocalVar%Flp_Angle(K) = PIIController(-LocalVar%rootMOOPF(K), 0 - LocalVar%Flp_Angle(K), CntrPar%Flp_Kp, CntrPar%Flp_Ki, REAL(0.05,DbKi), -CntrPar%Flp_MaxPit , CntrPar%Flp_MaxPit , LocalVar%DT, 0.0, LocalVar%piP, LocalVar%restart, objInst%instPI) + LocalVar%Flp_Angle(K) = PIIController(-LocalVar%rootMOOPF(K), 0 - LocalVar%Flp_Angle(K), CntrPar%Flp_Kp, CntrPar%Flp_Ki, 0.05_DbKi, -CntrPar%Flp_MaxPit , CntrPar%Flp_MaxPit , LocalVar%DT, 0.0_DbKi, LocalVar%piP, LocalVar%restart, objInst%instPI) ! Saturation Limits LocalVar%Flp_Angle(K) = saturate(LocalVar%Flp_Angle(K), -CntrPar%Flp_MaxPit, CntrPar%Flp_MaxPit) * R2D END DO diff --git a/ROSCO/src/DISCON.F90 b/ROSCO/src/DISCON.F90 index 577cd530..5d62d61c 100644 --- a/ROSCO/src/DISCON.F90 +++ b/ROSCO/src/DISCON.F90 @@ -90,7 +90,6 @@ SUBROUTINE DISCON(avrSWAP, aviFAIL, accINFILE, avcOUTNAME, avcMSG) BIND (C, NAME ! Data from external dll is in ExtDLL%avrSWAP, it's unused in the following code END IF - ! Filter signals CALL PreFilterMeasuredSignals(CntrPar, LocalVar, DebugVar, objInst, ErrVar) diff --git a/ROSCO/src/Functions.f90 b/ROSCO/src/Functions.f90 index 4f4a936e..7fac0bc9 100644 --- a/ROSCO/src/Functions.f90 +++ b/ROSCO/src/Functions.f90 @@ -22,13 +22,14 @@ ! interp1d: 1-d interpolation ! interp2d: 2-d interpolation ! matinv3: 3x3 matrix inverse -! PIController: implement a PI controller +! PIDController: implement a PID controller ! ratelimit: Rate limit signal ! saturate: Saturate signal MODULE Functions USE Constants +USE Filters IMPLICIT NONE @@ -90,7 +91,7 @@ REAL(DbKi) FUNCTION ratelimit(inputSignal, minRate, maxRate, DT, reset, rlP, ins END FUNCTION ratelimit -!------------------------------------------------------------------------------------------------------------------------------- + !------------------------------------------------------------------------------------------------------------------------------- REAL(DbKi) FUNCTION PIController(error, kp, ki, minValue, maxValue, DT, I0, piP, reset, inst) USE ROSCO_Types, ONLY : piParams @@ -130,6 +131,66 @@ REAL(DbKi) FUNCTION PIController(error, kp, ki, minValue, maxValue, DT, I0, piP, END FUNCTION PIController + +!------------------------------------------------------------------------------------------------------------------------------- + REAL(DbKi) FUNCTION PIDController(error, kp, ki, kd, tf, minValue, maxValue, DT, I0, piP, reset, objInst, LocalVar) + USE ROSCO_Types, ONLY : piParams, LocalVariables, ObjectInstances + + ! PI controller, with output saturation + + IMPLICIT NONE + ! Allocate Inputs + REAL(DbKi), INTENT(IN) :: error + REAL(DbKi), INTENT(IN) :: kp + REAL(DbKi), INTENT(IN) :: ki + REAL(DbKi), INTENT(IN) :: kd + REAL(DbKi), INTENT(IN) :: tf + REAL(DbKi), INTENT(IN) :: minValue + REAL(DbKi), INTENT(IN) :: maxValue + REAL(DbKi), INTENT(IN) :: DT + TYPE(ObjectInstances), INTENT(INOUT) :: objInst ! all object instances (PI, filters used here) + TYPE(LocalVariables), INTENT(INOUT) :: LocalVar + + REAL(DbKi), INTENT(IN) :: I0 + TYPE(piParams), INTENT(INOUT) :: piP + LOGICAL, INTENT(IN) :: reset + + ! Allocate local variables + INTEGER(IntKi) :: i ! Counter for making arrays + REAL(DbKi) :: PTerm, DTerm ! Proportional, deriv. terms + REAL(DbKi) :: EFilt ! Filtered error for derivative + + ! Always filter error + EFilt = LPFilter(error, DT, tf, LocalVar%FP, LocalVar%iStatus, reset, objInst%instLPF) + + ! Initialize persistent variables/arrays, and set inital condition for integrator term + IF (reset) THEN + piP%ITerm(objInst%instPI) = I0 + piP%ITermLast(objInst%instPI) = I0 + piP%ELast(objInst%instPI) = 0.0_DbKi + PIDController = I0 + ELSE + ! Proportional + PTerm = kp*error + + ! Integrate and saturate + piP%ITerm(objInst%instPI) = piP%ITerm(objInst%instPI) + DT*ki*error + piP%ITerm(objInst%instPI) = saturate(piP%ITerm(objInst%instPI), minValue, maxValue) + + ! Derivative (filtered) + DTerm = kd * (EFilt - piP%ELast(objInst%instPI)) / DT + + ! Saturate all + PIDController = saturate(PTerm + piP%ITerm(objInst%instPI) + DTerm, minValue, maxValue) + + ! Save lasts + piP%ITermLast(objInst%instPI) = piP%ITerm(objInst%instPI) + piP%ELast(objInst%instPI) = EFilt + END IF + objInst%instPI = objInst%instPI + 1 + + END FUNCTION PIDController + !------------------------------------------------------------------------------------------------------------------------------- REAL(DbKi) FUNCTION PIIController(error, error2, kp, ki, ki2, minValue, maxValue, DT, I0, piP, reset, inst) ! PI controller, with output saturation. @@ -599,5 +660,48 @@ REAL(DbKi) FUNCTION sigma(x, x0, x1, y0, y1, ErrVar) END FUNCTION sigma +!------------------------------------------------------------------------------------------------------------------------------- + FUNCTION unwrap(x, ErrVar) result(y) + ! Unwrap function + ! If difference between signal elements is < -pi, add 2 pi to reset of signal, and the opposite + ! Someday, generalize period and check difference is less than period/2 + USE ROSCO_Types, ONLY : ErrorVariables + IMPLICIT NONE + + ! Inputs + TYPE(ErrorVariables), INTENT(INOUT) :: ErrVar + REAL(DbKi), DIMENSION(:), Intent(IN) :: x + + ! Output + REAL(DbKi), DIMENSION(SIZE(x)) :: y + + ! Local + INTEGER(IntKi) :: i + + CHARACTER(*), PARAMETER :: RoutineName = 'unwrap' + y = x ! set initial + DO i = 2, SIZE(x) + DO while (y(i) - y(i-1) .LE. -PI) + y(i:SIZE(x)) = y(i:SIZE(x)) + 2 * PI + END DO + + DO while (y(i) - y(i-1) .GE. PI) + y(i:SIZE(x)) = y(i:SIZE(x)) - 2 * PI + END DO + END DO + + ! Add RoutineName to error message + IF (ErrVar%aviFAIL < 0) THEN + ErrVar%ErrMsg = RoutineName//':'//TRIM(ErrVar%ErrMsg) + ENDIF + + ! Debug + ! write(400,*) x + ! write(401,*) y + + END FUNCTION unwrap + + +!------------------------------------------------------------------------------------------------------------------------------- END MODULE Functions diff --git a/ROSCO/src/ROSCO_Helpers.f90 b/ROSCO/src/ROSCO_Helpers.f90 index 13f9d2d6..7bca4c93 100644 --- a/ROSCO/src/ROSCO_Helpers.f90 +++ b/ROSCO/src/ROSCO_Helpers.f90 @@ -34,7 +34,7 @@ MODULE ROSCO_Helpers ! MODULE PROCEDURE ParseInput_Log ! Parses an LOGICAL from a string. END INTERFACE - INTERFACE ParseAry ! Parse an array of numbers from a string. + INTERFACE ParseAry ! Parse an array of numbers from a string. MODULE PROCEDURE ParseDbAry ! Parse an array of double-precision REAL values. MODULE PROCEDURE ParseInAry ! Parse an array of whole numbers. MODULE PROCEDURE ParseInAry_Opt ! Parse an array of whole numbers. Optional inputs. @@ -258,7 +258,7 @@ subroutine ParseInput_Dbl_Opt(FileLines, VarName, Variable, FileName, ErrVar, Al ErrVar%aviFAIL = -1 ErrVar%ErrMsg = NewLine//' >> A fatal error occurred when parsing data from "' & //TRIM( FileName )//'".'//NewLine// & - ' >> The variable "'//TRIM( Words(2) )//'" was not assigned valid INTEGER value on line #' & + ' >> The variable "'//TRIM( Words(2) )//'" was not assigned valid REAL value on line #' & //TRIM( Int2LStr( CurLine ) )//'.'//NewLine//& ' >> The text being parsed was :'//NewLine//' "'//TRIM( Line )//'"' ENDIF @@ -697,7 +697,7 @@ SUBROUTINE ParseInAry ( Un, LineNum, ParamName, Ary, AryLen, FileName, ErrVar, C ErrVar%aviFAIL = -1 ErrVar%ErrMsg = RoutineName//':A fatal error occurred when parsing data from "' & //TRIM( FileName )//'".'//NewLine// & - ' >> The "'//TRIM( ParamName )//'" array was not assigned valid REAL values on line #' & + ' >> The "'//TRIM( ParamName )//'" array was not assigned valid INTEGER values on line #' & //TRIM( Int2LStr( LineNum ) )//'.'//NewLine//' >> The text being parsed was :'//NewLine & //' "'//TRIM( Line )//'"' RETURN @@ -1014,6 +1014,8 @@ END SUBROUTINE Cleanup END SUBROUTINE ParseDbAry_Opt + + !======================================================================= !> This subroutine checks the data to be parsed to make sure it finds @@ -1716,4 +1718,4 @@ FUNCTION CurDate( ) END FUNCTION CurDate -END MODULE ROSCO_Helpers \ No newline at end of file +END MODULE ROSCO_Helpers diff --git a/ROSCO/src/ROSCO_IO.f90 b/ROSCO/src/ROSCO_IO.f90 index 0d7a492e..b598f08f 100644 --- a/ROSCO/src/ROSCO_IO.f90 +++ b/ROSCO/src/ROSCO_IO.f90 @@ -38,6 +38,9 @@ SUBROUTINE WriteRestartFile(LocalVar, CntrPar, ErrVar, objInst, RootName, size_a WRITE( Un, IOSTAT=ErrStat) LocalVar%iStatus WRITE( Un, IOSTAT=ErrStat) LocalVar%Time WRITE( Un, IOSTAT=ErrStat) LocalVar%DT + WRITE( Un, IOSTAT=ErrStat) LocalVar%WriteThisStep + WRITE( Un, IOSTAT=ErrStat) LocalVar%n_DT + WRITE( Un, IOSTAT=ErrStat) LocalVar%Time_Last WRITE( Un, IOSTAT=ErrStat) LocalVar%VS_GenPwr WRITE( Un, IOSTAT=ErrStat) LocalVar%GenSpeed WRITE( Un, IOSTAT=ErrStat) LocalVar%RotSpeed @@ -55,6 +58,12 @@ SUBROUTINE WriteRestartFile(LocalVar, CntrPar, ErrVar, objInst, RootName, size_a WRITE( Un, IOSTAT=ErrStat) LocalVar%BlPitch(3) WRITE( Un, IOSTAT=ErrStat) LocalVar%BlPitchCMeas WRITE( Un, IOSTAT=ErrStat) LocalVar%Azimuth + WRITE( Un, IOSTAT=ErrStat) LocalVar%OL_Azimuth + WRITE( Un, IOSTAT=ErrStat) LocalVar%AzUnwrapped + WRITE( Un, IOSTAT=ErrStat) LocalVar%AzError + WRITE( Un, IOSTAT=ErrStat) LocalVar%GenTqAz + WRITE( Un, IOSTAT=ErrStat) LocalVar%AzBuffer(1) + WRITE( Un, IOSTAT=ErrStat) LocalVar%AzBuffer(2) WRITE( Un, IOSTAT=ErrStat) LocalVar%NumBl WRITE( Un, IOSTAT=ErrStat) LocalVar%FA_Acc WRITE( Un, IOSTAT=ErrStat) LocalVar%NacIMU_FA_Acc @@ -264,6 +273,7 @@ SUBROUTINE WriteRestartFile(LocalVar, CntrPar, ErrVar, objInst, RootName, size_a WRITE( Un, IOSTAT=ErrStat) LocalVar%piP%ITermLast WRITE( Un, IOSTAT=ErrStat) LocalVar%piP%ITerm2 WRITE( Un, IOSTAT=ErrStat) LocalVar%piP%ITermLast2 + WRITE( Un, IOSTAT=ErrStat) LocalVar%piP%ELast WRITE( Un, IOSTAT=ErrStat) LocalVar%rlP%LastSignal WRITE( Un, IOSTAT=ErrStat) objInst%instLPF WRITE( Un, IOSTAT=ErrStat) objInst%instSecLPF @@ -308,6 +318,9 @@ SUBROUTINE ReadRestartFile(avrSWAP, LocalVar, CntrPar, objInst, PerfData, RootNa READ( Un, IOSTAT=ErrStat) LocalVar%iStatus READ( Un, IOSTAT=ErrStat) LocalVar%Time READ( Un, IOSTAT=ErrStat) LocalVar%DT + READ( Un, IOSTAT=ErrStat) LocalVar%WriteThisStep + READ( Un, IOSTAT=ErrStat) LocalVar%n_DT + READ( Un, IOSTAT=ErrStat) LocalVar%Time_Last READ( Un, IOSTAT=ErrStat) LocalVar%VS_GenPwr READ( Un, IOSTAT=ErrStat) LocalVar%GenSpeed READ( Un, IOSTAT=ErrStat) LocalVar%RotSpeed @@ -325,6 +338,12 @@ SUBROUTINE ReadRestartFile(avrSWAP, LocalVar, CntrPar, objInst, PerfData, RootNa READ( Un, IOSTAT=ErrStat) LocalVar%BlPitch(3) READ( Un, IOSTAT=ErrStat) LocalVar%BlPitchCMeas READ( Un, IOSTAT=ErrStat) LocalVar%Azimuth + READ( Un, IOSTAT=ErrStat) LocalVar%OL_Azimuth + READ( Un, IOSTAT=ErrStat) LocalVar%AzUnwrapped + READ( Un, IOSTAT=ErrStat) LocalVar%AzError + READ( Un, IOSTAT=ErrStat) LocalVar%GenTqAz + READ( Un, IOSTAT=ErrStat) LocalVar%AzBuffer(1) + READ( Un, IOSTAT=ErrStat) LocalVar%AzBuffer(2) READ( Un, IOSTAT=ErrStat) LocalVar%NumBl READ( Un, IOSTAT=ErrStat) LocalVar%FA_Acc READ( Un, IOSTAT=ErrStat) LocalVar%NacIMU_FA_Acc @@ -535,6 +554,7 @@ SUBROUTINE ReadRestartFile(avrSWAP, LocalVar, CntrPar, objInst, PerfData, RootNa READ( Un, IOSTAT=ErrStat) LocalVar%piP%ITermLast READ( Un, IOSTAT=ErrStat) LocalVar%piP%ITerm2 READ( Un, IOSTAT=ErrStat) LocalVar%piP%ITermLast2 + READ( Un, IOSTAT=ErrStat) LocalVar%piP%ELast READ( Un, IOSTAT=ErrStat) LocalVar%rlP%LastSignal READ( Un, IOSTAT=ErrStat) objInst%instLPF READ( Un, IOSTAT=ErrStat) objInst%instSecLPF @@ -547,7 +567,7 @@ SUBROUTINE ReadRestartFile(avrSWAP, LocalVar, CntrPar, objInst, PerfData, RootNa Close ( Un ) ENDIF ! Read Parameter files - CALL ReadControlParameterFileSub(CntrPar, zmqVar, LocalVar%ACC_INFILE, LocalVar%ACC_INFILE_SIZE, RootName, ErrVar) + CALL ReadControlParameterFileSub(CntrPar, LocalVar, zmqVar, LocalVar%ACC_INFILE, LocalVar%ACC_INFILE_SIZE, RootName, ErrVar) IF (CntrPar%WE_Mode > 0) THEN CALL READCpFile(CntrPar, PerfData, ErrVar) ENDIF @@ -623,131 +643,139 @@ SUBROUTINE Debug(LocalVar, CntrPar, DebugVar, ErrVar, avrSWAP, RootName, size_av '[rad/s]', '[rad/s]', '[m/s]', '[rad]', '[rad]', & '[N/A]', '[N/A]', '[N/A]', '[N/A]', '[rad/s]', & '[deg]', '[deg]', '[deg]', '[N/A]'] - nLocalVars = 101 + nLocalVars = 108 Allocate(LocalVarOutData(nLocalVars)) Allocate(LocalVarOutStrings(nLocalVars)) LocalVarOutData(1) = LocalVar%iStatus LocalVarOutData(2) = LocalVar%Time LocalVarOutData(3) = LocalVar%DT - LocalVarOutData(4) = LocalVar%VS_GenPwr - LocalVarOutData(5) = LocalVar%GenSpeed - LocalVarOutData(6) = LocalVar%RotSpeed - LocalVarOutData(7) = LocalVar%NacHeading - LocalVarOutData(8) = LocalVar%NacVane - LocalVarOutData(9) = LocalVar%HorWindV - LocalVarOutData(10) = LocalVar%rootMOOP(1) - LocalVarOutData(11) = LocalVar%rootMOOPF(1) - LocalVarOutData(12) = LocalVar%BlPitch(1) - LocalVarOutData(13) = LocalVar%BlPitchCMeas - LocalVarOutData(14) = LocalVar%Azimuth - LocalVarOutData(15) = LocalVar%NumBl - LocalVarOutData(16) = LocalVar%FA_Acc - LocalVarOutData(17) = LocalVar%NacIMU_FA_Acc - LocalVarOutData(18) = LocalVar%FA_AccHPF - LocalVarOutData(19) = LocalVar%FA_AccHPFI - LocalVarOutData(20) = LocalVar%FA_PitCom(1) - LocalVarOutData(21) = LocalVar%RotSpeedF - LocalVarOutData(22) = LocalVar%GenSpeedF - LocalVarOutData(23) = LocalVar%GenTq - LocalVarOutData(24) = LocalVar%GenTqMeas - LocalVarOutData(25) = LocalVar%GenArTq - LocalVarOutData(26) = LocalVar%GenBrTq - LocalVarOutData(27) = LocalVar%IPC_PitComF(1) - LocalVarOutData(28) = LocalVar%PC_KP - LocalVarOutData(29) = LocalVar%PC_KI - LocalVarOutData(30) = LocalVar%PC_KD - LocalVarOutData(31) = LocalVar%PC_TF - LocalVarOutData(32) = LocalVar%PC_MaxPit - LocalVarOutData(33) = LocalVar%PC_MinPit - LocalVarOutData(34) = LocalVar%PC_PitComT - LocalVarOutData(35) = LocalVar%PC_PitComT_Last - LocalVarOutData(36) = LocalVar%PC_PitComTF - LocalVarOutData(37) = LocalVar%PC_PitComT_IPC(1) - LocalVarOutData(38) = LocalVar%PC_PwrErr - LocalVarOutData(39) = LocalVar%PC_SpdErr - LocalVarOutData(40) = LocalVar%IPC_AxisTilt_1P - LocalVarOutData(41) = LocalVar%IPC_AxisYaw_1P - LocalVarOutData(42) = LocalVar%IPC_AxisTilt_2P - LocalVarOutData(43) = LocalVar%IPC_AxisYaw_2P - LocalVarOutData(44) = LocalVar%axisTilt_1P - LocalVarOutData(45) = LocalVar%axisYaw_1P - LocalVarOutData(46) = LocalVar%axisYawF_1P - LocalVarOutData(47) = LocalVar%axisTilt_2P - LocalVarOutData(48) = LocalVar%axisYaw_2P - LocalVarOutData(49) = LocalVar%axisYawF_2P - LocalVarOutData(50) = LocalVar%IPC_KI(1) - LocalVarOutData(51) = LocalVar%IPC_KP(1) - LocalVarOutData(52) = LocalVar%IPC_IntSat - LocalVarOutData(53) = LocalVar%PC_State - LocalVarOutData(54) = LocalVar%PitCom(1) - LocalVarOutData(55) = LocalVar%PitComAct(1) - LocalVarOutData(56) = LocalVar%SS_DelOmegaF - LocalVarOutData(57) = LocalVar%TestType - LocalVarOutData(58) = LocalVar%Kp_Float - LocalVarOutData(59) = LocalVar%VS_MaxTq - LocalVarOutData(60) = LocalVar%VS_LastGenTrq - LocalVarOutData(61) = LocalVar%VS_LastGenPwr - LocalVarOutData(62) = LocalVar%VS_MechGenPwr - LocalVarOutData(63) = LocalVar%VS_SpdErrAr - LocalVarOutData(64) = LocalVar%VS_SpdErrBr - LocalVarOutData(65) = LocalVar%VS_SpdErr - LocalVarOutData(66) = LocalVar%VS_State - LocalVarOutData(67) = LocalVar%VS_Rgn3Pitch - LocalVarOutData(68) = LocalVar%WE_Vw - LocalVarOutData(69) = LocalVar%WE_Vw_F - LocalVarOutData(70) = LocalVar%WE_VwI - LocalVarOutData(71) = LocalVar%WE_VwIdot - LocalVarOutData(72) = LocalVar%VS_LastGenTrqF - LocalVarOutData(73) = LocalVar%Fl_PitCom - LocalVarOutData(74) = LocalVar%NACIMU_FA_AccF - LocalVarOutData(75) = LocalVar%FA_AccF - LocalVarOutData(76) = LocalVar%PtfmTDX - LocalVarOutData(77) = LocalVar%PtfmTDY - LocalVarOutData(78) = LocalVar%PtfmTDZ - LocalVarOutData(79) = LocalVar%PtfmRDX - LocalVarOutData(80) = LocalVar%PtfmRDY - LocalVarOutData(81) = LocalVar%PtfmRDZ - LocalVarOutData(82) = LocalVar%PtfmTVX - LocalVarOutData(83) = LocalVar%PtfmTVY - LocalVarOutData(84) = LocalVar%PtfmTVZ - LocalVarOutData(85) = LocalVar%PtfmRVX - LocalVarOutData(86) = LocalVar%PtfmRVY - LocalVarOutData(87) = LocalVar%PtfmRVZ - LocalVarOutData(88) = LocalVar%PtfmTAX - LocalVarOutData(89) = LocalVar%PtfmTAY - LocalVarOutData(90) = LocalVar%PtfmTAZ - LocalVarOutData(91) = LocalVar%PtfmRAX - LocalVarOutData(92) = LocalVar%PtfmRAY - LocalVarOutData(93) = LocalVar%PtfmRAZ - LocalVarOutData(94) = LocalVar%CC_DesiredL(1) - LocalVarOutData(95) = LocalVar%CC_ActuatedL(1) - LocalVarOutData(96) = LocalVar%CC_ActuatedDL(1) - LocalVarOutData(97) = LocalVar%StC_Input(1) - LocalVarOutData(98) = LocalVar%Flp_Angle(1) - LocalVarOutData(99) = LocalVar%RootMyb_Last(1) - LocalVarOutData(100) = LocalVar%ACC_INFILE_SIZE - LocalVarOutData(101) = LocalVar%AWC_complexangle(1) - LocalVarOutStrings = [CHARACTER(15) :: 'iStatus', 'Time', 'DT', 'VS_GenPwr', 'GenSpeed', & - 'RotSpeed', 'NacHeading', 'NacVane', 'HorWindV', 'rootMOOP', & - 'rootMOOPF', 'BlPitch', 'BlPitchCMeas', 'Azimuth', 'NumBl', & - 'FA_Acc', 'NacIMU_FA_Acc', 'FA_AccHPF', 'FA_AccHPFI', 'FA_PitCom', & - 'RotSpeedF', 'GenSpeedF', 'GenTq', 'GenTqMeas', 'GenArTq', & - 'GenBrTq', 'IPC_PitComF', 'PC_KP', 'PC_KI', 'PC_KD', & - 'PC_TF', 'PC_MaxPit', 'PC_MinPit', 'PC_PitComT', 'PC_PitComT_Last', & - 'PC_PitComTF', 'PC_PitComT_IPC', 'PC_PwrErr', 'PC_SpdErr', 'IPC_AxisTilt_1P', & - 'IPC_AxisYaw_1P', 'IPC_AxisTilt_2P', 'IPC_AxisYaw_2P', 'axisTilt_1P', 'axisYaw_1P', & - 'axisYawF_1P', 'axisTilt_2P', 'axisYaw_2P', 'axisYawF_2P', 'IPC_KI', & - 'IPC_KP', 'IPC_IntSat', 'PC_State', 'PitCom', 'PitComAct', & - 'SS_DelOmegaF', 'TestType', 'Kp_Float', 'VS_MaxTq', 'VS_LastGenTrq', & - 'VS_LastGenPwr', 'VS_MechGenPwr', 'VS_SpdErrAr', 'VS_SpdErrBr', 'VS_SpdErr', & - 'VS_State', 'VS_Rgn3Pitch', 'WE_Vw', 'WE_Vw_F', 'WE_VwI', & - 'WE_VwIdot', 'VS_LastGenTrqF', 'Fl_PitCom', 'NACIMU_FA_AccF', 'FA_AccF', & - 'PtfmTDX', 'PtfmTDY', 'PtfmTDZ', 'PtfmRDX', 'PtfmRDY', & - 'PtfmRDZ', 'PtfmTVX', 'PtfmTVY', 'PtfmTVZ', 'PtfmRVX', & - 'PtfmRVY', 'PtfmRVZ', 'PtfmTAX', 'PtfmTAY', 'PtfmTAZ', & - 'PtfmRAX', 'PtfmRAY', 'PtfmRAZ', 'CC_DesiredL', 'CC_ActuatedL', & - 'CC_ActuatedDL', 'StC_Input', 'Flp_Angle', 'RootMyb_Last', 'ACC_INFILE_SIZE', & - 'AWC_complexangle'] + LocalVarOutData(4) = LocalVar%n_DT + LocalVarOutData(5) = LocalVar%Time_Last + LocalVarOutData(6) = LocalVar%VS_GenPwr + LocalVarOutData(7) = LocalVar%GenSpeed + LocalVarOutData(8) = LocalVar%RotSpeed + LocalVarOutData(9) = LocalVar%NacHeading + LocalVarOutData(10) = LocalVar%NacVane + LocalVarOutData(11) = LocalVar%HorWindV + LocalVarOutData(12) = LocalVar%rootMOOP(1) + LocalVarOutData(13) = LocalVar%rootMOOPF(1) + LocalVarOutData(14) = LocalVar%BlPitch(1) + LocalVarOutData(15) = LocalVar%BlPitchCMeas + LocalVarOutData(16) = LocalVar%Azimuth + LocalVarOutData(17) = LocalVar%OL_Azimuth + LocalVarOutData(18) = LocalVar%AzUnwrapped + LocalVarOutData(19) = LocalVar%AzError + LocalVarOutData(20) = LocalVar%GenTqAz + LocalVarOutData(21) = LocalVar%AzBuffer(1) + LocalVarOutData(22) = LocalVar%NumBl + LocalVarOutData(23) = LocalVar%FA_Acc + LocalVarOutData(24) = LocalVar%NacIMU_FA_Acc + LocalVarOutData(25) = LocalVar%FA_AccHPF + LocalVarOutData(26) = LocalVar%FA_AccHPFI + LocalVarOutData(27) = LocalVar%FA_PitCom(1) + LocalVarOutData(28) = LocalVar%RotSpeedF + LocalVarOutData(29) = LocalVar%GenSpeedF + LocalVarOutData(30) = LocalVar%GenTq + LocalVarOutData(31) = LocalVar%GenTqMeas + LocalVarOutData(32) = LocalVar%GenArTq + LocalVarOutData(33) = LocalVar%GenBrTq + LocalVarOutData(34) = LocalVar%IPC_PitComF(1) + LocalVarOutData(35) = LocalVar%PC_KP + LocalVarOutData(36) = LocalVar%PC_KI + LocalVarOutData(37) = LocalVar%PC_KD + LocalVarOutData(38) = LocalVar%PC_TF + LocalVarOutData(39) = LocalVar%PC_MaxPit + LocalVarOutData(40) = LocalVar%PC_MinPit + LocalVarOutData(41) = LocalVar%PC_PitComT + LocalVarOutData(42) = LocalVar%PC_PitComT_Last + LocalVarOutData(43) = LocalVar%PC_PitComTF + LocalVarOutData(44) = LocalVar%PC_PitComT_IPC(1) + LocalVarOutData(45) = LocalVar%PC_PwrErr + LocalVarOutData(46) = LocalVar%PC_SpdErr + LocalVarOutData(47) = LocalVar%IPC_AxisTilt_1P + LocalVarOutData(48) = LocalVar%IPC_AxisYaw_1P + LocalVarOutData(49) = LocalVar%IPC_AxisTilt_2P + LocalVarOutData(50) = LocalVar%IPC_AxisYaw_2P + LocalVarOutData(51) = LocalVar%axisTilt_1P + LocalVarOutData(52) = LocalVar%axisYaw_1P + LocalVarOutData(53) = LocalVar%axisYawF_1P + LocalVarOutData(54) = LocalVar%axisTilt_2P + LocalVarOutData(55) = LocalVar%axisYaw_2P + LocalVarOutData(56) = LocalVar%axisYawF_2P + LocalVarOutData(57) = LocalVar%IPC_KI(1) + LocalVarOutData(58) = LocalVar%IPC_KP(1) + LocalVarOutData(59) = LocalVar%IPC_IntSat + LocalVarOutData(60) = LocalVar%PC_State + LocalVarOutData(61) = LocalVar%PitCom(1) + LocalVarOutData(62) = LocalVar%PitComAct(1) + LocalVarOutData(63) = LocalVar%SS_DelOmegaF + LocalVarOutData(64) = LocalVar%TestType + LocalVarOutData(65) = LocalVar%Kp_Float + LocalVarOutData(66) = LocalVar%VS_MaxTq + LocalVarOutData(67) = LocalVar%VS_LastGenTrq + LocalVarOutData(68) = LocalVar%VS_LastGenPwr + LocalVarOutData(69) = LocalVar%VS_MechGenPwr + LocalVarOutData(70) = LocalVar%VS_SpdErrAr + LocalVarOutData(71) = LocalVar%VS_SpdErrBr + LocalVarOutData(72) = LocalVar%VS_SpdErr + LocalVarOutData(73) = LocalVar%VS_State + LocalVarOutData(74) = LocalVar%VS_Rgn3Pitch + LocalVarOutData(75) = LocalVar%WE_Vw + LocalVarOutData(76) = LocalVar%WE_Vw_F + LocalVarOutData(77) = LocalVar%WE_VwI + LocalVarOutData(78) = LocalVar%WE_VwIdot + LocalVarOutData(79) = LocalVar%VS_LastGenTrqF + LocalVarOutData(80) = LocalVar%Fl_PitCom + LocalVarOutData(81) = LocalVar%NACIMU_FA_AccF + LocalVarOutData(82) = LocalVar%FA_AccF + LocalVarOutData(83) = LocalVar%PtfmTDX + LocalVarOutData(84) = LocalVar%PtfmTDY + LocalVarOutData(85) = LocalVar%PtfmTDZ + LocalVarOutData(86) = LocalVar%PtfmRDX + LocalVarOutData(87) = LocalVar%PtfmRDY + LocalVarOutData(88) = LocalVar%PtfmRDZ + LocalVarOutData(89) = LocalVar%PtfmTVX + LocalVarOutData(90) = LocalVar%PtfmTVY + LocalVarOutData(91) = LocalVar%PtfmTVZ + LocalVarOutData(92) = LocalVar%PtfmRVX + LocalVarOutData(93) = LocalVar%PtfmRVY + LocalVarOutData(94) = LocalVar%PtfmRVZ + LocalVarOutData(95) = LocalVar%PtfmTAX + LocalVarOutData(96) = LocalVar%PtfmTAY + LocalVarOutData(97) = LocalVar%PtfmTAZ + LocalVarOutData(98) = LocalVar%PtfmRAX + LocalVarOutData(99) = LocalVar%PtfmRAY + LocalVarOutData(100) = LocalVar%PtfmRAZ + LocalVarOutData(101) = LocalVar%CC_DesiredL(1) + LocalVarOutData(102) = LocalVar%CC_ActuatedL(1) + LocalVarOutData(103) = LocalVar%CC_ActuatedDL(1) + LocalVarOutData(104) = LocalVar%StC_Input(1) + LocalVarOutData(105) = LocalVar%Flp_Angle(1) + LocalVarOutData(106) = LocalVar%RootMyb_Last(1) + LocalVarOutData(107) = LocalVar%ACC_INFILE_SIZE + LocalVarOutData(108) = LocalVar%AWC_complexangle(1) + LocalVarOutStrings = [CHARACTER(15) :: 'iStatus', 'Time', 'DT', 'n_DT', 'Time_Last', & + 'VS_GenPwr', 'GenSpeed', 'RotSpeed', 'NacHeading', 'NacVane', & + 'HorWindV', 'rootMOOP', 'rootMOOPF', 'BlPitch', 'BlPitchCMeas', & + 'Azimuth', 'OL_Azimuth', 'AzUnwrapped', 'AzError', 'GenTqAz', & + 'AzBuffer', 'NumBl', 'FA_Acc', 'NacIMU_FA_Acc', 'FA_AccHPF', & + 'FA_AccHPFI', 'FA_PitCom', 'RotSpeedF', 'GenSpeedF', 'GenTq', & + 'GenTqMeas', 'GenArTq', 'GenBrTq', 'IPC_PitComF', 'PC_KP', & + 'PC_KI', 'PC_KD', 'PC_TF', 'PC_MaxPit', 'PC_MinPit', & + 'PC_PitComT', 'PC_PitComT_Last', 'PC_PitComTF', 'PC_PitComT_IPC', 'PC_PwrErr', & + 'PC_SpdErr', 'IPC_AxisTilt_1P', 'IPC_AxisYaw_1P', 'IPC_AxisTilt_2P', 'IPC_AxisYaw_2P', & + 'axisTilt_1P', 'axisYaw_1P', 'axisYawF_1P', 'axisTilt_2P', 'axisYaw_2P', & + 'axisYawF_2P', 'IPC_KI', 'IPC_KP', 'IPC_IntSat', 'PC_State', & + 'PitCom', 'PitComAct', 'SS_DelOmegaF', 'TestType', 'Kp_Float', & + 'VS_MaxTq', 'VS_LastGenTrq', 'VS_LastGenPwr', 'VS_MechGenPwr', 'VS_SpdErrAr', & + 'VS_SpdErrBr', 'VS_SpdErr', 'VS_State', 'VS_Rgn3Pitch', 'WE_Vw', & + 'WE_Vw_F', 'WE_VwI', 'WE_VwIdot', 'VS_LastGenTrqF', 'Fl_PitCom', & + 'NACIMU_FA_AccF', 'FA_AccF', 'PtfmTDX', 'PtfmTDY', 'PtfmTDZ', & + 'PtfmRDX', 'PtfmRDY', 'PtfmRDZ', 'PtfmTVX', 'PtfmTVY', & + 'PtfmTVZ', 'PtfmRVX', 'PtfmRVY', 'PtfmRVZ', 'PtfmTAX', & + 'PtfmTAY', 'PtfmTAZ', 'PtfmRAX', 'PtfmRAY', 'PtfmRAZ', & + 'CC_DesiredL', 'CC_ActuatedL', 'CC_ActuatedDL', 'StC_Input', 'Flp_Angle', & + 'RootMyb_Last', 'ACC_INFILE_SIZE', 'AWC_complexangle'] ! Initialize debug file IF ((LocalVar%iStatus == 0) .OR. (LocalVar%iStatus == -9)) THEN ! .TRUE. if we're on the first call to the DLL IF (CntrPar%LoggingLevel > 0) THEN @@ -762,8 +790,8 @@ SUBROUTINE Debug(LocalVar, CntrPar, DebugVar, ErrVar, avrSWAP, RootName, size_av CALL GetNewUnit(UnDb2, ErrVar) OPEN(unit=UnDb2, FILE=TRIM(RootName)//'.RO.dbg2') WRITE(UnDb2, *) 'Generated on '//CurDate()//' at '//CurTime()//' using ROSCO-'//TRIM(rosco_version) - WRITE(UnDb2, '(102(a20,TR5:))') 'Time', LocalVarOutStrings - WRITE(UnDb2, '(102(a20,TR5:))') + WRITE(UnDb2, '(109(a20,TR5:))') 'Time', LocalVarOutStrings + WRITE(UnDb2, '(109(a20,TR5:))') END IF IF (CntrPar%LoggingLevel > 2) THEN @@ -808,29 +836,37 @@ SUBROUTINE Debug(LocalVar, CntrPar, DebugVar, ErrVar, avrSWAP, RootName, size_av ! Process DebugOutData, LocalVarOutData ! Remove very small numbers that cause ******** outputs DO I = 1,SIZE(DebugOutData) - IF (ABS(DebugOutData(I)) < 1E-10) THEN + IF (ABS(DebugOutData(I)) < 1E-99) THEN DebugOutData(I) = 0 END IF + IF (ABS(DebugOutData(I)) > 1E+99) THEN + DebugOutData(I) = 1E+99 + END IF END DO DO I = 1,SIZE(LocalVarOutData) - IF (ABS(LocalVarOutData(I)) < 1E-10) THEN + IF (ABS(LocalVarOutData(I)) < 1E-99) THEN LocalVarOutData(I) = 0 END IF + IF (ABS(LocalVarOutData(I)) > 1E+99) THEN + LocalVarOutData(I) = 1E+99 + END IF END DO ! Write debug files - FmtDat = "(F20.5,TR5,101(ES20.5E2,TR5:))" ! The format of the debugging data - IF(CntrPar%LoggingLevel > 0) THEN - WRITE (UnDb, TRIM(FmtDat)) LocalVar%Time, DebugOutData - END IF + FmtDat = "(F20.5,TR5,108(ES20.5E2,TR5:))" ! The format of the debugging data + IF ( MOD(LocalVar%n_DT, CntrPar%n_DT_Out) == 0) THEN + IF(CntrPar%LoggingLevel > 0) THEN + WRITE (UnDb, FmtDat) LocalVar%Time, DebugOutData + END IF - IF(CntrPar%LoggingLevel > 1) THEN - WRITE (UnDb2, TRIM(FmtDat)) LocalVar%Time, LocalVarOutData - END IF + IF(CntrPar%LoggingLevel > 1) THEN + WRITE (UnDb2, FmtDat) LocalVar%Time, LocalVarOutData + END IF - IF(CntrPar%LoggingLevel > 2) THEN - WRITE (UnDb3, TRIM(FmtDat)) LocalVar%Time, avrSWAP(avrIndices) + IF(CntrPar%LoggingLevel > 2) THEN + WRITE (UnDb3, TRIM(FmtDat)) LocalVar%Time, avrSWAP(avrIndices) + END IF END IF END SUBROUTINE Debug diff --git a/ROSCO/src/ROSCO_Types.f90 b/ROSCO/src/ROSCO_Types.f90 index 76631c19..ce22b2da 100644 --- a/ROSCO/src/ROSCO_Types.f90 +++ b/ROSCO/src/ROSCO_Types.f90 @@ -10,6 +10,8 @@ MODULE ROSCO_Types TYPE, PUBLIC :: ControlParameters INTEGER(IntKi) :: LoggingLevel ! 0 - write no debug files, 1 - write standard output .dbg-file, 2 - write standard output .dbg-file and complete avrSWAP-array .dbg2-file INTEGER(IntKi) :: Echo ! 0 - no Echo, 1 - Echo input data to .echo + REAL(DbKi) :: DT_Out ! Output time step + INTEGER(IntKi) :: n_DT_Out ! output every this many steps INTEGER(IntKi) :: F_LPFType ! Low pass filter on the rotor and generator speed {1 - first-order low-pass filter, 2 - second-order low-pass filter}, [rad/s] INTEGER(IntKi) :: F_NotchType ! Notch on the measured generator speed {0 - disable, 1 - enable} REAL(DbKi) :: F_LPFCornerFreq ! Corner frequency (-3dB point) in the first-order low-pass filter, [rad/s] @@ -106,17 +108,22 @@ MODULE ROSCO_Types CHARACTER(1024) :: OL_Filename ! Input file with open loop timeseries INTEGER(IntKi) :: OL_Mode ! Open loop control mode {0 - no open loop control, 1 - open loop control vs. time, 2 - open loop control vs. wind speed} INTEGER(IntKi) :: Ind_Breakpoint ! The column in OL_Filename that contains the breakpoint (time if OL_Mode = 1) - INTEGER(IntKi) :: Ind_BldPitch ! The column in OL_Filename that contains the blade pitch input in rad + INTEGER(IntKi), DIMENSION(:), ALLOCATABLE :: Ind_BldPitch ! The columns in OL_Filename that contains the blade pitch inputs (1,2,3) in rad INTEGER(IntKi) :: Ind_GenTq ! The column in OL_Filename that contains the generator torque in Nm INTEGER(IntKi) :: Ind_YawRate ! The column in OL_Filename that contains the generator torque in Nm + INTEGER(IntKi) :: Ind_Azimuth ! The column in OL_Filename that contains the desired azimuth position in rad (used if OL_Mode = 2) + REAL(DbKi), DIMENSION(:), ALLOCATABLE :: RP_Gains ! PID gains for rotor position control (used if OL_Mode = 2) INTEGER(IntKi), DIMENSION(:), ALLOCATABLE :: Ind_CableControl ! The column in OL_Filename that contains the cable control inputs in m INTEGER(IntKi), DIMENSION(:), ALLOCATABLE :: Ind_StructControl ! The column in OL_Filename that contains the structural control inputs in various units REAL(DbKi), DIMENSION(:), ALLOCATABLE :: OL_Breakpoints ! Open loop breakpoints in timeseries - REAL(DbKi), DIMENSION(:), ALLOCATABLE :: OL_BldPitch ! Open blade pitch timeseries + REAL(DbKi), DIMENSION(:), ALLOCATABLE :: OL_BldPitch1 ! Open loop blade pitch 1 timeseries + REAL(DbKi), DIMENSION(:), ALLOCATABLE :: OL_BldPitch2 ! Open loop blade pitch 2 timeseries + REAL(DbKi), DIMENSION(:), ALLOCATABLE :: OL_BldPitch3 ! Open loop blade pitch 3 timeseries REAL(DbKi), DIMENSION(:,:), ALLOCATABLE :: OL_CableControl ! None REAL(DbKi), DIMENSION(:,:), ALLOCATABLE :: OL_StructControl ! None - REAL(DbKi), DIMENSION(:), ALLOCATABLE :: OL_GenTq ! Open generator torque timeseries - REAL(DbKi), DIMENSION(:), ALLOCATABLE :: OL_YawRate ! Open yaw rate timeseries + REAL(DbKi), DIMENSION(:), ALLOCATABLE :: OL_GenTq ! Open loop generator torque timeseries + REAL(DbKi), DIMENSION(:), ALLOCATABLE :: OL_YawRate ! Open loop yaw rate timeseries + REAL(DbKi), DIMENSION(:), ALLOCATABLE :: OL_Azimuth ! Open loop azimuth timeseries REAL(DbKi), DIMENSION(:,:), ALLOCATABLE :: OL_Channels ! Open loop channels in timeseries INTEGER(IntKi) :: PA_Mode ! Pitch actuator mode {0 - not used, 1 - first order filter, 2 - second order filter} REAL(DbKi) :: PA_CornerFreq ! Pitch actuator bandwidth/cut-off frequency [rad/s] @@ -217,12 +224,16 @@ MODULE ROSCO_Types REAL(DbKi), DIMENSION(99) :: ITermLast ! Previous integrator term REAL(DbKi), DIMENSION(99) :: ITerm2 ! Integrator term - second integrator REAL(DbKi), DIMENSION(99) :: ITermLast2 ! Previous integrator term - second integrator + REAL(DbKi), DIMENSION(99) :: ELast ! Previous error term for derivative END TYPE piParams TYPE, PUBLIC :: LocalVariables INTEGER(IntKi) :: iStatus ! Initialization status REAL(DbKi) :: Time ! Time [s] REAL(DbKi) :: DT ! Time step [s] + LOGICAL :: WriteThisStep ! Write an output line this time step + INTEGER(IntKi) :: n_DT ! number of timesteps since start + REAL(DbKi) :: Time_Last ! Last time [s] REAL(DbKi) :: VS_GenPwr ! Generator power [W] REAL(DbKi) :: GenSpeed ! Generator speed (HSS) [rad/s] REAL(DbKi) :: RotSpeed ! Rotor speed (LSS) [rad/s] @@ -234,6 +245,11 @@ MODULE ROSCO_Types REAL(DbKi) :: BlPitch(3) ! Blade pitch [rad] REAL(DbKi) :: BlPitchCMeas ! Mean (collective) blade pitch [rad] REAL(DbKi) :: Azimuth ! Rotor aziumuth angle [rad] + REAL(DbKi) :: OL_Azimuth ! Rotor aziumuth angle [rad] + REAL(DbKi) :: AzUnwrapped ! Rotor aziumuth angle [rad] + REAL(DbKi) :: AzError ! Azimuth error angle [rad] + REAL(DbKi) :: GenTqAz ! Gen torque command due to azimuth error + REAL(DbKi) :: AzBuffer(2) ! Current and last rotor aziumuth angles [rad] INTEGER(IntKi) :: NumBl ! Number of blades [-] REAL(DbKi) :: FA_Acc ! Tower fore-aft acceleration [m/s^2] REAL(DbKi) :: NacIMU_FA_Acc ! Tower fore-aft acceleration [rad/s^2] diff --git a/ROSCO/src/ReadSetParameters.f90 b/ROSCO/src/ReadSetParameters.f90 index 7343eb04..ee03cff0 100644 --- a/ROSCO/src/ReadSetParameters.f90 +++ b/ROSCO/src/ReadSetParameters.f90 @@ -110,6 +110,13 @@ SUBROUTINE ReadAvrSWAP(avrSWAP, LocalVar, CntrPar) LocalVar%restart = .False. ENDIF + ! Increment timestep counter + IF (LocalVar%iStatus == 0 .AND. LocalVar%Time == 0) THEN + LocalVar%n_DT = 0 + ELSE + LocalVar%n_DT = LocalVar%n_DT + 1 + ENDIF + END SUBROUTINE ReadAvrSWAP ! ----------------------------------------------------------------------------------- ! Define parameters for control actions @@ -133,7 +140,7 @@ SUBROUTINE SetParameters(avrSWAP, accINFILE, size_avcMSG, CntrPar, LocalVar, obj INTEGER(IntKi) :: K, I, I_OL ! Index used for looping through blades. CHARACTER(1024) :: OL_String ! Open description loop string INTEGER(IntKi) :: OL_Count ! Number of open loop channels - + INTEGER(IntKi) :: UnOpenLoop ! Open Loop file unit INTEGER(IntKi) :: N_OL_Cables INTEGER(IntKi) :: N_OL_StCs @@ -189,7 +196,7 @@ SUBROUTINE SetParameters(avrSWAP, accINFILE, size_avcMSG, CntrPar, LocalVar, obj LocalVar%ACC_INFILE = accINFILE ! Read Control Parameter File - CALL ReadControlParameterFileSub(CntrPar, zmqVar, accINFILE, NINT(avrSWAP(50)), RootName, ErrVar) + CALL ReadControlParameterFileSub(CntrPar, LocalVar, zmqVar, accINFILE, NINT(avrSWAP(50)), RootName, ErrVar) ! If there's been an file reading error, don't continue ! Add RoutineName to error message IF (ErrVar%aviFAIL < 0) THEN @@ -201,7 +208,7 @@ SUBROUTINE SetParameters(avrSWAP, accINFILE, size_avcMSG, CntrPar, LocalVar, obj CALL READCpFile(CntrPar,PerfData,ErrVar) ENDIF - ! Initialize the SAVED variables: + ! Initialize the Local variables: LocalVar%PitCom = LocalVar%BlPitch ! This will ensure that the variable speed controller picks the correct control region and the pitch controller picks the correct gain on the first call ! Wind speed estimator initialization @@ -220,99 +227,14 @@ SUBROUTINE SetParameters(avrSWAP, accINFILE, size_avcMSG, CntrPar, LocalVar, obj LocalVar%VS_LastGenTrq = LocalVar%GenTq LocalVar%VS_MaxTq = CntrPar%VS_MaxTq - ! Check validity of input parameters: - CALL CheckInputs(LocalVar, CntrPar, avrSWAP, ErrVar, size_avcMSG) - ! Initialize variables LocalVar%CC_DesiredL = 0 LocalVar%CC_ActuatedL = 0 LocalVar%CC_ActuatedDL = 0 LocalVar%StC_Input = 0 - ! Initialize open loop control - ! Read open loop input, if desired - IF (CntrPar%OL_Mode == 1) THEN - OL_String = '' ! Display string - OL_Count = 1 - IF (CntrPar%Ind_BldPitch > 0) THEN - OL_String = TRIM(OL_String)//' BldPitch ' - OL_Count = OL_Count + 1 - ENDIF - - IF (CntrPar%Ind_GenTq > 0) THEN - OL_String = TRIM(OL_String)//' GenTq ' - OL_Count = OL_Count + 1 - ENDIF - - IF (CntrPar%Ind_YawRate > 0) THEN - OL_String = TRIM(OL_String)//' YawRate ' - OL_Count = OL_Count + 1 - ENDIF - - N_OL_Cables = 0 - IF (ANY(CntrPar%Ind_CableControl > 0)) THEN - DO I = 1,SIZE(CntrPar%Ind_CableControl) - IF (CntrPar%Ind_CableControl(I) > 0) THEN - OL_String = TRIM(OL_String)//' Cable'//TRIM(Int2LStr(I))//' ' - OL_Count = OL_Count + 1 - N_OL_Cables = N_OL_Cables + 1 - ENDIF - ENDDO - ENDIF - - N_OL_StCs = 0 - IF (ANY(CntrPar%Ind_StructControl > 0)) THEN - DO I = 1,SIZE(CntrPar%Ind_StructControl) - IF (CntrPar%Ind_StructControl(I) > 0) THEN - OL_String = TRIM(OL_String)//' StC'//TRIM(Int2LStr(I))//' ' - OL_Count = OL_Count + 1 - N_OL_StCs = N_OL_StCs + 1 - ENDIF - ENDDO - ENDIF - - - PRINT *, 'ROSCO: Implementing open loop control for'//TRIM(OL_String) - CALL Read_OL_Input(CntrPar%OL_Filename,110_IntKi,OL_Count,CntrPar%OL_Channels, ErrVar) - - CntrPar%OL_Breakpoints = CntrPar%OL_Channels(:,CntrPar%Ind_Breakpoint) - - IF (CntrPar%Ind_BldPitch > 0) THEN - CntrPar%OL_BldPitch = CntrPar%OL_Channels(:,CntrPar%Ind_BldPitch) - ENDIF - - IF (CntrPar%Ind_GenTq > 0) THEN - CntrPar%OL_GenTq = CntrPar%OL_Channels(:,CntrPar%Ind_GenTq) - ENDIF - - IF (CntrPar%Ind_YawRate > 0) THEN - CntrPar%OL_YawRate = CntrPar%OL_Channels(:,CntrPar%Ind_YawRate) - ENDIF - - IF (ANY(CntrPar%Ind_CableControl > 0)) THEN - ALLOCATE(CntrPar%OL_CableControl(N_OL_Cables,SIZE(CntrPar%OL_Channels,DIM=1))) - I_OL = 1 - DO I = 1,SIZE(CntrPar%Ind_CableControl) - IF (CntrPar%Ind_CableControl(I) > 0) THEN - CntrPar%OL_CableControl(I_OL,:) = CntrPar%OL_Channels(:,CntrPar%Ind_CableControl(I)) - I_OL = I_OL + 1 - ENDIF - ENDDO - ENDIF - - IF (ANY(CntrPar%Ind_StructControl > 0)) THEN - ALLOCATE(CntrPar%OL_StructControl(N_OL_StCs,SIZE(CntrPar%OL_Channels,DIM=1))) - I_OL = 1 - DO I = 1,SIZE(CntrPar%Ind_StructControl) - IF (CntrPar%Ind_StructControl(I) > 0) THEN - CntrPar%OL_StructControl(I_OL,:) = CntrPar%OL_Channels(:,CntrPar%Ind_StructControl(I)) - I_OL = I_OL + 1 - ENDIF - ENDDO - ENDIF - - END IF - + ! Check validity of input parameters: + CALL CheckInputs(LocalVar, CntrPar, avrSWAP, ErrVar, size_avcMSG) ! Add RoutineName to error message IF (ErrVar%aviFAIL < 0) THEN @@ -327,15 +249,18 @@ SUBROUTINE SetParameters(avrSWAP, accINFILE, size_avcMSG, CntrPar, LocalVar, obj ENDIF END SUBROUTINE SetParameters + ! ----------------------------------------------------------------------------------- ! Read all constant control parameters from DISCON.IN parameter file - SUBROUTINE ReadControlParameterFileSub(CntrPar, zmqVar, accINFILE, accINFILE_size, RootName, ErrVar)!, accINFILE_size) + ! Also, all computed CntrPar%* parameters should be computed in this subroutine + SUBROUTINE ReadControlParameterFileSub(CntrPar, LocalVar, zmqVar, accINFILE, accINFILE_size, RootName, ErrVar)!, accINFILE_size) USE, INTRINSIC :: ISO_C_Binding - USE ROSCO_Types, ONLY : ControlParameters, ErrorVariables, ZMQ_Variables + USE ROSCO_Types, ONLY : ControlParameters, ErrorVariables, ZMQ_Variables, LocalVariables INTEGER(IntKi) :: accINFILE_size ! size of DISCON input filename CHARACTER(accINFILE_size), INTENT(IN ) :: accINFILE(accINFILE_size) ! DISCON input filename TYPE(ControlParameters), INTENT(INOUT) :: CntrPar ! Control parameter type + TYPE(LocalVariables), INTENT(INOUT) :: LocalVar ! Control parameter type TYPE(ErrorVariables), INTENT(INOUT) :: ErrVar ! Control parameter type TYPE(ZMQ_Variables), INTENT(INOUT) :: zmqVar ! Control parameter type CHARACTER(accINFILE_size), INTENT(IN) :: RootName @@ -350,6 +275,13 @@ SUBROUTINE ReadControlParameterFileSub(CntrPar, zmqVar, accINFILE, accINFILE_siz INTEGER(IntKi) :: UnEc CHARACTER(128) :: EchoFilename ! Input checkpoint file CHARACTER(MaxLineLength), DIMENSION(:), ALLOCATABLE :: FileLines + + INTEGER(IntKi) :: I, I_OL ! Index used for looping through blades. + CHARACTER(1024) :: OL_String ! Open description loop string + INTEGER(IntKi) :: OL_Count ! Number of open loop channels + INTEGER(IntKi) :: UnOpenLoop ! Open Loop file unit + INTEGER(IntKi) :: N_OL_Cables + INTEGER(IntKi) :: N_OL_StCs CHARACTER(*), PARAMETER :: RoutineName = 'ReadControlParameterFileSub' @@ -373,8 +305,10 @@ SUBROUTINE ReadControlParameterFileSub(CntrPar, zmqVar, accINFILE, accINFILE_siz READ(UnControllerParameters,'(A)',IOSTAT=IOS) FileLines(I_LINE) END DO - !----------------------- DEBUG -------------------------- - CALL ParseInput(FileLines,'LoggingLevel', CntrPar%LoggingLevel, accINFILE(1), ErrVar) + ! Close Input File + CLOSE(UnControllerParameters) + + ! Read Echo first, so file can be set up, if desired CALL ParseInput(FileLines,'Echo', CntrPar%Echo, accINFILE(1), ErrVar) IF (ErrVar%aviFAIL < 0) RETURN @@ -396,6 +330,11 @@ SUBROUTINE ReadControlParameterFileSub(CntrPar, zmqVar, accINFILE, accINFILE_siz ENDIF ENDIF + !----------------------- Simulation Control -------------------------- + CALL ParseInput(FileLines,'LoggingLevel', CntrPar%LoggingLevel, accINFILE(1), ErrVar, .TRUE., UnEc=UnEc) + CALL ParseInput(FileLines,'DT_Out', CntrPar%DT_Out, accINFILE(1), ErrVar, .TRUE., UnEc=UnEc) + IF (ErrVar%aviFAIL < 0) RETURN + !----------------- CONTROLLER FLAGS --------------------- CALL ParseInput(FileLines,'F_LPFType', CntrPar%F_LPFType, accINFILE(1), ErrVar, UnEc=UnEc) CALL ParseInput(FileLines,'F_NotchType', CntrPar%F_NotchType, accINFILE(1), ErrVar, UnEc=UnEc) @@ -541,13 +480,14 @@ SUBROUTINE ReadControlParameterFileSub(CntrPar, zmqVar, accINFILE, accINFILE_siz !------------ Open loop input ------------ ! Indices can be left 0 by default, checked later - CALL ParseInput(FileLines, 'OL_Filename', CntrPar%OL_Filename, accINFILE(1), ErrVar, CntrPar%OL_Mode == 0, UnEc) - CALL ParseInput(FileLines, 'Ind_Breakpoint', CntrPar%Ind_Breakpoint, accINFILE(1), ErrVar, UnEc=UnEc) - CALL ParseInput(FileLines, 'Ind_BldPitch', CntrPar%Ind_BldPitch, accINFILE(1), ErrVar, UnEc=UnEc) - CALL ParseInput(FileLines, 'Ind_GenTq', CntrPar%Ind_GenTq, accINFILE(1), ErrVar, UnEc=UnEc) - CALL ParseInput(FileLines, 'Ind_YawRate', CntrPar%Ind_YawRate, accINFILE(1), ErrVar, UnEc=UnEc) + CALL ParseInput(FileLines, 'OL_Filename', CntrPar%OL_Filename, accINFILE(1), ErrVar, CntrPar%OL_Mode == 0, UnEc) + CALL ParseInput(FileLines, 'Ind_Breakpoint', CntrPar%Ind_Breakpoint, accINFILE(1), ErrVar, UnEc=UnEc) + CALL ParseAry( FileLines, 'Ind_BldPitch', CntrPar%Ind_BldPitch, 3, accINFILE(1), ErrVar, UnEc=UnEc) + CALL ParseInput(FileLines, 'Ind_GenTq', CntrPar%Ind_GenTq, accINFILE(1), ErrVar, UnEc=UnEc) + CALL ParseInput(FileLines, 'Ind_YawRate', CntrPar%Ind_YawRate, accINFILE(1), ErrVar, UnEc=UnEc) + CALL ParseInput(FileLines, 'Ind_Azimuth', CntrPar%Ind_Azimuth, accINFILE(1), ErrVar, CntrPar%OL_Mode .NE. 2, UnEc=UnEc) + CALL ParseAry( FileLines, 'RP_Gains', CntrPar%RP_Gains, 4, accINFILE(1), ErrVar, CntrPar%OL_Mode .NE. 2, UnEc=UnEc) IF (ErrVar%aviFAIL < 0) RETURN - !------------ Pitch Actuator Inputs ------------ CALL ParseInput(FileLines, 'PA_CornerFreq', CntrPar%PA_CornerFreq, accINFILE(1), ErrVar, CntrPar%PA_Mode == 0, UnEc) @@ -596,7 +536,18 @@ SUBROUTINE ReadControlParameterFileSub(CntrPar, zmqVar, accINFILE, accINFILE_siz IF (UnEc > 0) CLOSE(UnEc) ! Close echo file - !!!!!!!!!!!!!!!!!!!!!!!!!!!!!!! + !------------------- + !------------------- CALCULATED CONSTANTS ----------------------- + !---------------------------------------------------------------- + + ! Fix defaults manually for now + IF (CntrPar%DT_Out == 0) THEN + CntrPar%DT_Out = LocalVar%DT + ENDIF + + ! DT_Out + CntrPar%n_DT_Out = NINT(CntrPar%DT_Out / LocalVar%DT) + ! Fix Paths (add relative paths if called from another dir, UnEc) IF (PathIsRelative(CntrPar%PerfFileName)) CntrPar%PerfFileName = TRIM(PriPath)//TRIM(CntrPar%PerfFileName) @@ -604,17 +555,138 @@ SUBROUTINE ReadControlParameterFileSub(CntrPar, zmqVar, accINFILE, accINFILE_siz ! Convert yaw rate to deg/s CntrPar%Y_Rate = CntrPar%Y_Rate * R2D - - ! END OF INPUT FILE - - ! Close Input File - CLOSE(UnControllerParameters) - - !------------------- CALCULATED CONSTANTS ----------------------- + CntrPar%PC_RtTq99 = CntrPar%VS_RtTq*0.99 CntrPar%VS_MinOMTq = CntrPar%VS_Rgn2K*CntrPar%VS_MinOMSpd**2 CntrPar%VS_MaxOMTq = CntrPar%VS_Rgn2K*CntrPar%VS_RefSpd**2 + + ! Read open loop input, if desired + IF (CntrPar%OL_Mode > 0) THEN + OL_String = '' ! Display string + OL_Count = 1 + IF (CntrPar%Ind_BldPitch(1) > 0) THEN + OL_String = TRIM(OL_String)//' BldPitch1 ' + OL_Count = OL_Count + 1 + ENDIF + + IF (CntrPar%Ind_BldPitch(2) > 0) THEN + OL_String = TRIM(OL_String)//' BldPitch2 ' + ! If there are duplicate indices, don't increment OL_Count + IF (.NOT. ((CntrPar%Ind_BldPitch(2) == CntrPar%Ind_BldPitch(1)) .OR. & + (CntrPar%Ind_BldPitch(2) == CntrPar%Ind_BldPitch(3)))) THEN + OL_Count = OL_Count + 1 + ENDIF + ENDIF + + IF (CntrPar%Ind_BldPitch(3) > 0) THEN + OL_String = TRIM(OL_String)//' BldPitch3 ' + ! If there are duplicate indices, don't increment OL_Count + IF (.NOT. ((CntrPar%Ind_BldPitch(3) == CntrPar%Ind_BldPitch(1)) .OR. & + (CntrPar%Ind_BldPitch(3) == CntrPar%Ind_BldPitch(2)))) THEN + OL_Count = OL_Count + 1 + ENDIF + ENDIF + + IF (CntrPar%Ind_GenTq > 0) THEN + OL_String = TRIM(OL_String)//' GenTq ' + OL_Count = OL_Count + 1 ! Read channel still, so we don't have issues + ENDIF + + IF (CntrPar%Ind_YawRate > 0) THEN + OL_String = TRIM(OL_String)//' YawRate ' + OL_Count = OL_Count + 1 + ENDIF + + IF (CntrPar%Ind_Azimuth > 0) THEN + IF (CntrPar%OL_Mode == 2) THEN + OL_String = TRIM(OL_String)//' Azimuth ' + OL_Count = OL_Count + 1 + END IF + ENDIF + + N_OL_Cables = 0 + IF (ANY(CntrPar%Ind_CableControl > 0)) THEN + DO I = 1,SIZE(CntrPar%Ind_CableControl) + IF (CntrPar%Ind_CableControl(I) > 0) THEN + OL_String = TRIM(OL_String)//' Cable'//TRIM(Int2LStr(I))//' ' + OL_Count = OL_Count + 1 + N_OL_Cables = N_OL_Cables + 1 + ENDIF + ENDDO + ENDIF + + N_OL_StCs = 0 + IF (ANY(CntrPar%Ind_StructControl > 0)) THEN + DO I = 1,SIZE(CntrPar%Ind_StructControl) + IF (CntrPar%Ind_StructControl(I) > 0) THEN + OL_String = TRIM(OL_String)//' StC'//TRIM(Int2LStr(I))//' ' + OL_Count = OL_Count + 1 + N_OL_StCs = N_OL_StCs + 1 + ENDIF + ENDDO + ENDIF + + + PRINT *, 'ROSCO: Implementing open loop control for'//TRIM(OL_String) + IF (CntrPar%OL_Mode == 2) THEN + PRINT *, 'ROSCO: OL_Mode = 2 will change generator torque control for Azimuth tracking' + ENDIF + + CALL GetNewUnit(UnOpenLoop, ErrVar) + CALL Read_OL_Input(CntrPar%OL_Filename,UnOpenLoop,OL_Count,CntrPar%OL_Channels, ErrVar) + + CntrPar%OL_Breakpoints = CntrPar%OL_Channels(:,CntrPar%Ind_Breakpoint) + + ! Set OL Inputs based on indices + IF (CntrPar%Ind_BldPitch(1) > 0) THEN + CntrPar%OL_BldPitch1 = CntrPar%OL_Channels(:,CntrPar%Ind_BldPitch(1)) + ENDIF + + IF (CntrPar%Ind_BldPitch(2) > 0) THEN + CntrPar%OL_BldPitch2 = CntrPar%OL_Channels(:,CntrPar%Ind_BldPitch(2)) + ENDIF + + IF (CntrPar%Ind_BldPitch(3) > 0) THEN + CntrPar%OL_BldPitch3 = CntrPar%OL_Channels(:,CntrPar%Ind_BldPitch(3)) + ENDIF + + IF (CntrPar%Ind_GenTq > 0) THEN + CntrPar%OL_GenTq = CntrPar%OL_Channels(:,CntrPar%Ind_GenTq) + ENDIF + + IF (CntrPar%Ind_YawRate > 0) THEN + CntrPar%OL_YawRate = CntrPar%OL_Channels(:,CntrPar%Ind_YawRate) + ENDIF + + IF (CntrPar%Ind_Azimuth > 0) THEN + CntrPar%OL_Azimuth = Unwrap(CntrPar%OL_Channels(:,CntrPar%Ind_Azimuth),ErrVar) + ENDIF + + IF (ANY(CntrPar%Ind_CableControl > 0)) THEN + ALLOCATE(CntrPar%OL_CableControl(N_OL_Cables,SIZE(CntrPar%OL_Channels,DIM=1))) + I_OL = 1 + DO I = 1,SIZE(CntrPar%Ind_CableControl) + IF (CntrPar%Ind_CableControl(I) > 0) THEN + CntrPar%OL_CableControl(I_OL,:) = CntrPar%OL_Channels(:,CntrPar%Ind_CableControl(I)) + I_OL = I_OL + 1 + ENDIF + ENDDO + ENDIF + + IF (ANY(CntrPar%Ind_StructControl > 0)) THEN + ALLOCATE(CntrPar%OL_StructControl(N_OL_StCs,SIZE(CntrPar%OL_Channels,DIM=1))) + I_OL = 1 + DO I = 1,SIZE(CntrPar%Ind_StructControl) + IF (CntrPar%Ind_StructControl(I) > 0) THEN + CntrPar%OL_StructControl(I_OL,:) = CntrPar%OL_Channels(:,CntrPar%Ind_StructControl(I)) + I_OL = I_OL + 1 + ENDIF + ENDDO + ENDIF + + END IF + !------------------- HOUSEKEEPING ----------------------- CntrPar%PerfFileName = TRIM(CntrPar%PerfFileName) @@ -702,8 +774,8 @@ SUBROUTINE CheckInputs(LocalVar, CntrPar, avrSWAP, ErrVar, size_avcMSG) IMPLICIT NONE ! Inputs - TYPE(ControlParameters), INTENT(IN ) :: CntrPar - TYPE(LocalVariables), INTENT(IN ) :: LocalVar + TYPE(ControlParameters), INTENT(INOUT) :: CntrPar + TYPE(LocalVariables), INTENT(INOUT) :: LocalVar TYPE(ErrorVariables), INTENT(INOUT) :: ErrVar INTEGER(IntKi), INTENT(IN ) :: size_avcMSG INTEGER(IntKi) :: Imode ! Index used for looping through AWC modes @@ -727,6 +799,20 @@ SUBROUTINE CheckInputs(LocalVar, CntrPar, avrSWAP, ErrVar, size_avcMSG) ErrVar%ErrMsg = 'LoggingLevel must be 0 - 3.' ENDIF + IF (CntrPar%DT_Out .le. 0) THEN + ErrVar%aviFAIL = -1 + ErrVar%ErrMsg = 'DT_Out must be greater than 0' + ENDIF + + IF (CntrPar%DT_Out < LocalVar%DT) THEN + ErrVar%aviFAIL = -1 + ErrVar%ErrMsg = 'DT_Out must be greater than or equal to DT in OpenFAST' + ENDIF + + IF (ABS(CntrPar%DT_out - Localvar%DT * CntrPar%n_DT_Out) > 0.001_DbKi) THEN + ErrVar%aviFAIL = -1 + ErrVar%ErrMsg = 'DT_Out must be a factor of DT in OpenFAST' + ENDIF !------- CONTROLLER FLAGS ------------------------------------------------- ! F_LPFType @@ -1121,7 +1207,7 @@ SUBROUTINE CheckInputs(LocalVar, CntrPar, avrSWAP, ErrVar, size_avcMSG) ! --- Open loop control --- IF (CntrPar%OL_Mode > 0) THEN ! Get all open loop indices - ALLOCATE(All_OL_Indices(3)) ! Will need to increase to 5 when IPC + ALLOCATE(All_OL_Indices(5)) ! Will need to increase to 5 when IPC All_OL_Indices = (/CntrPar%Ind_BldPitch, & CntrPar%Ind_GenTq, & CntrPar%Ind_YawRate/) @@ -1149,6 +1235,17 @@ SUBROUTINE CheckInputs(LocalVar, CntrPar, avrSWAP, ErrVar, size_avcMSG) ErrVar%ErrMsg = 'At least one open loop input channel must be non-zero' ENDIF + IF (CntrPar%OL_Mode == 2) THEN + IF ((CntrPar%Ind_BldPitch(1) == 0) .OR. & + (CntrPar%Ind_BldPitch(2) == 0) .OR. & + (CntrPar%Ind_BldPitch(3) == 0) .OR. & + (CntrPar%Ind_GenTq == 0) .OR. & + (CntrPar%Ind_Azimuth == 0)) THEN + ErrVar%aviFAIL = -1 + ErrVar%ErrMsg = 'If OL_Mode = 2, Ind_BldPitch, Ind_GenTq, and Ind_Azimuth must be greater than zero' + ENDIF + ENDIF + IF (ANY(CntrPar%Ind_CableControl > 0) .AND. CntrPar%CC_Mode .NE. 2) THEN ErrVar%aviFAIL = -1 ErrVar%ErrMsg = 'CC_Mode must be 2 if using open loop cable control via Ind_CableControl' @@ -1167,6 +1264,8 @@ SUBROUTINE CheckInputs(LocalVar, CntrPar, avrSWAP, ErrVar, size_avcMSG) PRINT *, "ROSCO WARNING: Individual pitch control and active wake control are both enabled. Performance may be compromised." ENDIF + + ! --- Pitch Actuator --- IF (CntrPar%PA_Mode > 0) THEN IF ((CntrPar%PA_Mode < 0) .OR. (CntrPar%PA_Mode > 2)) THEN diff --git a/ROSCO_toolbox/control_interface.py b/ROSCO_toolbox/control_interface.py index 4d17dba2..84a3f369 100644 --- a/ROSCO_toolbox/control_interface.py +++ b/ROSCO_toolbox/control_interface.py @@ -315,6 +315,7 @@ def get_measurements(self): def send_setpoints(self, genTorques=None, nacelleHeadings=None, bladePitchAngles=None): + ''' Send setpoints to DLL via zmq server for farm level controls diff --git a/ROSCO_toolbox/controller.py b/ROSCO_toolbox/controller.py index 4051cea5..4f59e968 100644 --- a/ROSCO_toolbox/controller.py +++ b/ROSCO_toolbox/controller.py @@ -139,9 +139,10 @@ def __init__(self, controller_params): self.f_sd_cornerfreq = controller_params['filter_params']['f_sd_cornerfreq'] # Open loop parameters: set up and error catching - self.OL_Mode = int(controller_params['open_loop']['flag']) + self.OL_Mode = controller_params['OL_Mode'] self.OL_Filename = controller_params['open_loop']['filename'] - self.OL_Ind_Breakpoint = self.OL_Ind_BldPitch = self.OL_Ind_GenTq = self.OL_Ind_YawRate = 0 + self.OL_Ind_Breakpoint = self.OL_Ind_GenTq = self.OL_Ind_YawRate = self.OL_Ind_Azimuth = 0 + self.OL_Ind_BldPitch = [0,0,0] self.OL_Ind_CableControl = [0] self.OL_Ind_StructControl = [0] @@ -151,11 +152,12 @@ def __init__(self, controller_params): self.OL_Ind_BldPitch = ol_params['OL_Ind_BldPitch'] self.OL_Ind_GenTq = ol_params['OL_Ind_GenTq'] self.OL_Ind_YawRate = ol_params['OL_Ind_YawRate'] + self.OL_Ind_Azimuth = ol_params['OL_Ind_Azimuth'] self.OL_Ind_CableControl = ol_params['OL_Ind_CableControl'] self.OL_Ind_StructControl = ol_params['OL_Ind_StructControl'] # Check that file exists because we won't write it - if not os.path.exists(self.OL_Filename): + if not os.path.exists(controller_params['open_loop']['filename']): raise Exception(f'Open-loop control set up, but the open loop file {self.OL_Filename} does not exist') @@ -790,39 +792,60 @@ def write_input(self,ol_filename): # Init indices OL_Ind_Breakpoint = 1 - OL_Ind_BldPitch = OL_Ind_GenTq = OL_Ind_YawRate = 0 + OL_Ind_Azimuth = OL_Ind_GenTq = OL_Ind_YawRate = 0 + OL_Ind_BldPitch = 3*[0] OL_Ind_CableControl = [] OL_Ind_StructControl = [] - self.OL_Ind_Breakpoint = 1 - ol_index_counter = 2 # start input index at 2 - + ol_index_counter = 0 # start input index at 2 + + # Write time first, initialize OL matrix if 'time' in ol_timeseries: ol_control_array = ol_timeseries['time'] - + Ind_Breakpoint = 1 else: raise Exception('WARNING: no time index for open loop control. This is only index currently supported') - if 'blade_pitch' in ol_timeseries: - OL_Ind_BldPitch = ol_index_counter - ol_index_counter += 1 - - ol_control_array = np.c_[ol_control_array,ol_timeseries['blade_pitch']] - - if 'generator_torque' in ol_timeseries: - OL_Ind_GenTq = ol_index_counter - ol_index_counter += 1 - - ol_control_array = np.c_[ol_control_array,ol_timeseries['generator_torque']] + for channel in ol_timeseries: - if 'nacelle_yaw_rate' in ol_timeseries: - OL_Ind_YawRate = ol_index_counter + # increment index counter first for 1-indexing in input file ol_index_counter += 1 - ol_control_array = np.c_[ol_control_array,ol_timeseries['nacelle_yaw_rate']] - - if 'nacelle_yaw' in ol_timeseries and 'nacelle_yaw_rate' not in ol_timeseries: - raise Exception('nacelle_yaw is in ol_timeseries and nacelle_yaw_rate is not. ROSCO can only command yaw rate. Use compute_yaw_rate() to convert.') + # skip writing for certain channels + skip_write = False + + # Set open loop index based on name + if channel == 'time': + OL_Ind_Breakpoint = ol_index_counter + skip_write = True + elif channel == 'blade_pitch': # collective blade pitch + OL_Ind_BldPitch = 3 * [ol_index_counter] + elif channel == 'generator_torque': + OL_Ind_GenTq = ol_index_counter + elif channel == 'nacelle_yaw_rate': + OL_Ind_YawRate = ol_index_counter + elif channel == 'nacelle_yaw': + ol_index_counter -= 1 # don't increment counter + skip_write = True + elif channel == 'blade_pitch1': + OL_Ind_BldPitch[0] = ol_index_counter + elif channel == 'blade_pitch2': + OL_Ind_BldPitch[1] = ol_index_counter + elif channel == 'blade_pitch3': + OL_Ind_BldPitch[2] = ol_index_counter + elif channel == 'azimuth': + OL_Ind_Azimuth = ol_index_counter + elif 'cable_control' in channel or 'struct_control' in channel: + skip_write = True + ol_index_counter -= 1 # don't increment counter + + + + # append open loop input array for non-ptfm channels + if not skip_write: + ol_control_array = np.c_[ol_control_array,ol_timeseries[channel]] + + ol_index_counter += 1 # Increment counter so it's 1 more than time, just like above in each iteration # Cable control is_cable_chan = np.array(['cable_control' in ol_chan for ol_chan in ol_timeseries.keys()]) @@ -856,19 +879,37 @@ def write_input(self,ol_filename): with open(ol_filename,'w') as f: # Write header + headers = [''] * ol_index_counter + units = [''] * ol_index_counter header_line = '!\tTime' unit_line = '!\t(sec.)' - if OL_Ind_BldPitch: - header_line += '\t\tBldPitch' - unit_line += '\t\t(rad.)' + + headers[0] = 'Time' + units[0] = 'sec.' if OL_Ind_GenTq: - header_line += '\t\tGenTq' - unit_line += '\t\t(Nm)' + headers[OL_Ind_GenTq-1] = 'GenTq' + units[OL_Ind_GenTq-1] = '(Nm)' if OL_Ind_YawRate: - header_line += '\t\tYawRate' - unit_line += '\t\t(rad/s)' + headers[OL_Ind_YawRate-1] = 'YawRate' + units[OL_Ind_YawRate-1] = '(rad/s)' + + if OL_Ind_Azimuth: + headers[OL_Ind_Azimuth-1] = 'Azimuth' + units[OL_Ind_Azimuth-1] = '(rad)' + + if any(OL_Ind_BldPitch): + if all_same(OL_Ind_BldPitch): + headers[OL_Ind_BldPitch[0]-1] = 'BldPitch123' + units[OL_Ind_BldPitch[0]-1] = '(rad)' + else: + headers[OL_Ind_BldPitch[0]-1] = 'BldPitch1' + units[OL_Ind_BldPitch[0]-1] = '(rad)' + headers[OL_Ind_BldPitch[1]-1] = 'BldPitch2' + units[OL_Ind_BldPitch[1]-1] = '(rad)' + headers[OL_Ind_BldPitch[2]-1] = 'BldPitch3' + units[OL_Ind_BldPitch[2]-1] = '(rad)' if OL_Ind_CableControl: for i_chan in range(1,n_cable_chan+1): @@ -884,8 +925,9 @@ def write_input(self,ol_filename): else: OL_Ind_StructControl = [0] - header_line += '\n' - unit_line += '\n' + # Join headers and units + header_line = '!' + '\t\t'.join(headers) + '\n' + unit_line = '!' + '\t\t'.join(units) + '\n' f.write(header_line) f.write(unit_line) @@ -897,15 +939,16 @@ def write_input(self,ol_filename): # Output open_loop dict for control params open_loop = {} - open_loop['flag'] = True open_loop['filename'] = ol_filename open_loop['OL_Ind_Breakpoint'] = OL_Ind_Breakpoint open_loop['OL_Ind_BldPitch'] = OL_Ind_BldPitch open_loop['OL_Ind_GenTq'] = OL_Ind_GenTq open_loop['OL_Ind_YawRate'] = OL_Ind_YawRate + open_loop['OL_Ind_Azimuth'] = OL_Ind_Azimuth open_loop['OL_Ind_CableControl'] = OL_Ind_CableControl open_loop['OL_Ind_StructControl'] = OL_Ind_StructControl + return open_loop @@ -987,3 +1030,6 @@ def multi_sigma(xx,x_bp,y_bp): plt.show() return yy + +def all_same(items): + return all(x == items[0] for x in items) diff --git a/ROSCO_toolbox/inputs/toolbox_schema.yaml b/ROSCO_toolbox/inputs/toolbox_schema.yaml index 24d4d5ef..9cad9ff6 100644 --- a/ROSCO_toolbox/inputs/toolbox_schema.yaml +++ b/ROSCO_toolbox/inputs/toolbox_schema.yaml @@ -203,6 +203,12 @@ properties: maximum: 1 default: 0 description: Pitch fault mode {0 - not used, 1 - constant offset on one or more blades} + OL_Mode: + type: number + minimum: 0 + maximum: 2 + default: 0 + description: Open loop control mode {0- no open loop control, 1- open loop control} AWC_Mode: type: number minimum: 0 @@ -458,22 +464,44 @@ properties: description: Filename of open loop input that ROSCO reads type: string default: unused - OL_Ind_Breakpoint: + Ind_Breakpoint: description: Index (column, 1-indexed) of breakpoint (time) in open loop index type: number default: 1 - OL_Ind_BldPitch: - description: Index (column, 1-indexed) of breakpoint (time) in open loop index + minimum: 0 + Ind_BldPitch: + description: Indices (columns, 1-indexed) of pitch (1,2,3) inputs in open loop input + type: array + items: + type: number + minimum: 0 + default: [0, 0, 0] + Ind_GenTq: + description: Index (column, 1-indexed) of generator torque in open loop input type: number default: 0 - OL_Ind_GenTq: - description: Index (column, 1-indexed) of breakpoint (time) in open loop index + minimum: 0 + Ind_YawRate: + description: Index (column, 1-indexed) of nacelle yaw in open loop input type: number default: 0 - OL_Ind_YawRate: - description: Index (column, 1-indexed) of breakpoint (time) in open loop index + minimum: 0 + Ind_Azimuth: type: number default: 0 + description: The column in OL_Filename that contains the desired azimuth position in rad (used if OL_Mode = 2) + Ind_CableControl: + type: array + items: + type: number + description: The column in OL_Filename that contains the cable control inputs in m + # default: [0] # No default because it's defined in controller and DISCON_Dict + Ind_StructControl: + type: array + items: + type: number + description: The column in OL_Filename that contains the structural control inputs in various units + # default: [0] # No default because it's defined in controller and DISCON_Dict PA_CornerFreq: type: number description: Pitch actuator natural frequency [rad/s] @@ -488,7 +516,7 @@ properties: DISCON: type: object - description: These are pass-through parameters for the DISCON.IN file. Use with caution. + description: These are pass-through parameters for the DISCON.IN file. Use with caution. Do not set defaults in schema. default: {} properties: LoggingLevel: @@ -498,6 +526,10 @@ properties: type: number description: 0 - no Echo, 1 - Echo input data to .echo default: 0 + DT_Out: + type: number + description: Time step to output .dbg* files, or 0 to match sampling period of OpenFAST + default: 0 F_LPFType: type: number description: 1- first-order low-pass filter, 2- second-order low-pass filter (currently filters generator speed and pitch control signals @@ -534,6 +566,9 @@ properties: Flp_Mode: type: number description: Flap control mode (0- no flap control, 1- steady state flap angle, 2- Proportional flap control) + OL_Mode: + type: number + description: Open loop control mode (0 - no open-loop control, 1 - direct open loop control, 2 - rotor position control) F_LPFCornerFreq: type: number description: Corner frequency (-3dB point) in the low-pass filters, @@ -878,7 +913,7 @@ properties: description: Input file with open loop timeseries (absolute path or relative to this file) Ind_Breakpoint: type: number - description: The column in OL_Filename that contains the breakpoint (time if OL_Mode = 1) + description: The column in OL_Filename that contains the breakpoint (time if OL_Mode > 0) Ind_BldPitch: type: number description: The column in OL_Filename that contains the blade pitch input in rad @@ -888,6 +923,15 @@ properties: Ind_YawRate: type: number description: The column in OL_Filename that contains the generator torque in Nm + Ind_Azimuth: + type: number + description: The column in OL_Filename that contains the desired azimuth position in rad (used if OL_Mode = 2) + RP_Gains: + type: array + description: PID gains and Tf of derivative for rotor position control (used if OL_Mode = 2) + default: [0,0,0,0] + items: + type: number Ind_CableControl: type: array items: diff --git a/ROSCO_toolbox/ofTools/case_gen/CaseGen_General.py b/ROSCO_toolbox/ofTools/case_gen/CaseGen_General.py index 8c46e522..2637a21d 100644 --- a/ROSCO_toolbox/ofTools/case_gen/CaseGen_General.py +++ b/ROSCO_toolbox/ofTools/case_gen/CaseGen_General.py @@ -54,7 +54,7 @@ def save_case_matrix(matrix_out, change_vars, dir_matrix): text_out.append(row_str) if not os.path.exists(dir_matrix): - os.makedirs(dir_matrix) + os.makedirs(dir_matrix) ofh = open(os.path.join(dir_matrix,'case_matrix.txt'),'w') for row in text_out: ofh.write(row) diff --git a/ROSCO_toolbox/ofTools/case_gen/CaseGen_IEC.py b/ROSCO_toolbox/ofTools/case_gen/CaseGen_IEC.py index d8cdb4ec..2fd3cf3b 100644 --- a/ROSCO_toolbox/ofTools/case_gen/CaseGen_IEC.py +++ b/ROSCO_toolbox/ofTools/case_gen/CaseGen_IEC.py @@ -190,7 +190,6 @@ def execute(self, case_inputs={}): case_inputs_i[("ElastoDyn","BlPitch2")] = {'vals':[90.], 'group':0} case_inputs_i[("ElastoDyn","BlPitch3")] = {'vals':[90.], 'group':0} case_inputs_i[("ServoDyn","PCMode")] = {'vals':[0], 'group':0} - case_inputs_i[("AeroDyn15","AFAeroMod")]= {'vals':[1], 'group':0} elif dlc == 6.3: self.dlc_inputs['U'][i] = [V_1] self.dlc_inputs['Yaw'][i] = [-20.,20.] @@ -201,11 +200,9 @@ def execute(self, case_inputs={}): case_inputs_i[("ElastoDyn","BlPitch2")] = {'vals':[90.], 'group':0} case_inputs_i[("ElastoDyn","BlPitch3")] = {'vals':[90.], 'group':0} case_inputs_i[("ServoDyn","PCMode")] = {'vals':[0], 'group':0} - case_inputs_i[("AeroDyn15","AFAeroMod")]= {'vals':[1], 'group':0} else: self.dlc_inputs['Yaw'][i] = [0.] case_inputs_i[("ServoDyn","PCMode")] = {'vals':[5], 'group':0} - case_inputs_i[("AeroDyn15","AFAeroMod")]= {'vals':[2], 'group':0} case_inputs_i[("ElastoDyn","GenDOF")] = {'vals':["True"], 'group':0} diff --git a/ROSCO_toolbox/ofTools/case_gen/CaseLibrary.py b/ROSCO_toolbox/ofTools/case_gen/CaseLibrary.py index 001844f4..2823ab8a 100644 --- a/ROSCO_toolbox/ofTools/case_gen/CaseLibrary.py +++ b/ROSCO_toolbox/ofTools/case_gen/CaseLibrary.py @@ -106,20 +106,21 @@ def base_op_case(): case_inputs[('ServoDyn', 'YCMode')] = {'vals': [5], 'group': 0} # AeroDyn - case_inputs[("AeroDyn15", "WakeMod")] = {'vals': [1], 'group': 0} - case_inputs[("AeroDyn15", "AFAeroMod")] = {'vals': [2], 'group': 0} - case_inputs[("AeroDyn15", "TwrPotent")] = {'vals': [0], 'group': 0} - case_inputs[("AeroDyn15", "TwrShadow")] = {'vals': ['False'], 'group': 0} - case_inputs[("AeroDyn15", "TwrAero")] = {'vals': ['False'], 'group': 0} - case_inputs[("AeroDyn15", "SkewMod")] = {'vals': [1], 'group': 0} - case_inputs[("AeroDyn15", "TipLoss")] = {'vals': ['True'], 'group': 0} - case_inputs[("AeroDyn15", "HubLoss")] = {'vals': ['True'], 'group': 0} - case_inputs[("AeroDyn15", "TanInd")] = {'vals': ['True'], 'group': 0} - case_inputs[("AeroDyn15", "AIDrag")] = {'vals': ['True'], 'group': 0} - case_inputs[("AeroDyn15", "TIDrag")] = {'vals': ['True'], 'group': 0} - case_inputs[("AeroDyn15", "IndToler")] = {'vals': [1.e-5], 'group': 0} - case_inputs[("AeroDyn15", "MaxIter")] = {'vals': [5000], 'group': 0} - case_inputs[("AeroDyn15", "UseBlCm")] = {'vals': ['True'], 'group': 0} + if False: + case_inputs[("AeroDyn15", "WakeMod")] = {'vals': [1], 'group': 0} + case_inputs[("AeroDyn15", "AFAeroMod")] = {'vals': [2], 'group': 0} + case_inputs[("AeroDyn15", "TwrPotent")] = {'vals': [0], 'group': 0} + case_inputs[("AeroDyn15", "TwrShadow")] = {'vals': ['False'], 'group': 0} + case_inputs[("AeroDyn15", "TwrAero")] = {'vals': ['False'], 'group': 0} + case_inputs[("AeroDyn15", "SkewMod")] = {'vals': [1], 'group': 0} + case_inputs[("AeroDyn15", "TipLoss")] = {'vals': ['True'], 'group': 0} + case_inputs[("AeroDyn15", "HubLoss")] = {'vals': ['True'], 'group': 0} + case_inputs[("AeroDyn15", "TanInd")] = {'vals': ['True'], 'group': 0} + case_inputs[("AeroDyn15", "AIDrag")] = {'vals': ['True'], 'group': 0} + case_inputs[("AeroDyn15", "TIDrag")] = {'vals': ['True'], 'group': 0} + case_inputs[("AeroDyn15", "IndToler")] = {'vals': [1.e-5], 'group': 0} + case_inputs[("AeroDyn15", "MaxIter")] = {'vals': [5000], 'group': 0} + case_inputs[("AeroDyn15", "UseBlCm")] = {'vals': ['True'], 'group': 0} return case_inputs diff --git a/ROSCO_toolbox/ofTools/case_gen/run_FAST.py b/ROSCO_toolbox/ofTools/case_gen/run_FAST.py index abec4c25..af567a26 100644 --- a/ROSCO_toolbox/ofTools/case_gen/run_FAST.py +++ b/ROSCO_toolbox/ofTools/case_gen/run_FAST.py @@ -15,7 +15,8 @@ from ROSCO_toolbox.ofTools.case_gen.CaseGen_General import CaseGen_General from ROSCO_toolbox.ofTools.case_gen import CaseLibrary as cl from wisdem.commonse.mpi_tools import MPI -import sys, os, platform +import sys, os, platform, pickle +import collections.abc import numpy as np from ROSCO_toolbox import utilities as ROSCO_utilities from ROSCO_toolbox.inputs.validation import load_rosco_yaml @@ -23,7 +24,20 @@ from ROSCO_toolbox import controller as ROSCO_controller from ROSCO_toolbox import turbine as ROSCO_turbine -this_dir = os.path.dirname(os.path.abspath(__file__)) +# Globals +this_dir = os.path.dirname(os.path.abspath(__file__)) +tune_case_dir = os.path.realpath(os.path.join(this_dir,'../../../Tune_Cases')) +rosco_dir = os.path.realpath(os.path.join(this_dir,'../../..')) + +# https://stackoverflow.com/questions/3232943/update-value-of-a-nested-dictionary-of-varying-depth +def update_deep(d, u): + for k, v in u.items(): + if isinstance(v, collections.abc.Mapping): + d[k] = update_deep(d.get(k, {}), v) + else: + d[k] = v + return d + class run_FAST_ROSCO(): def __init__(self): @@ -47,7 +61,6 @@ def __init__(self): self.rosco_dir = '' self.save_dir = '' - def run_FAST(self): # handle directories, set defaults @@ -85,7 +98,7 @@ def run_FAST(self): controller_params = inps['controller_params'] # Update user-defined controller_params - controller_params.update(self.controller_params) + update_deep(controller_params,self.controller_params) # Instantiate turbine, controller, and file processing classes turbine = ROSCO_turbine.Turbine(turbine_params) @@ -173,8 +186,8 @@ def run_FAST(self): fastBatch.channels = channels fastBatch.FAST_runDirectory = run_dir fastBatch.case_list = case_list - fastBatch.case_name_list = case_name_list fastBatch.fst_vt = self.fst_vt + fastBatch.case_name_list = case_name_list fastBatch.FAST_exe = self.openfast_exe fastBatch.use_exe = True @@ -257,57 +270,6 @@ def run_FAST(self): r.n_cores = 4 - elif sim_config == 8: - - # RAAW IPC set up - r.tuning_yaml = '/Users/dzalkind/Projects/RAAW/RAAW_OpenFAST/ROSCO/RAAW_rosco_BD.yaml' - r.wind_case_fcn = cl.power_curve - r.wind_case_opts = { - 'U': [16], - } - r.save_dir = '/Users/dzalkind/Tools/ROSCO/outputs/offset_test' - r.control_sweep_fcn = cl.test_pitch_offset - - elif sim_config == 9: - - # RAAW FAD set up - r.tuning_yaml = '/Users/dzalkind/Projects/RAAW/RAAW_OpenFAST/ROSCO/RAAW_rosco_BD.yaml' - r.wind_case_fcn = cl.simp_step - r.wind_case_opts = { - 'U_start': [13], - 'U_end': [15], - 'wind_dir': '/Users/dzalkind/Projects/RAAW/RAAW_OpenFAST/outputs/FAD_play' - } - r.save_dir = '/Users/dzalkind/Projects/RAAW/RAAW_OpenFAST/outputs/FAD_play' - r.control_sweep_fcn = cl.sweep_fad_gains - r.n_cores = 8 - - elif sim_config == 10: - - # RAAW FAD set up - r.tuning_yaml = '/Users/dzalkind/Projects/RAAW/RAAW_OpenFAST/ROSCO/RAAW_rosco_BD.yaml' - r.wind_case_fcn = cl.turb_bts - r.wind_case_opts = { - 'TMax': 720, - 'wind_filenames': ['/Users/dzalkind/Tools/WEIS-2/outputs/02_RAAW_IPC/wind/RAAW_NTM_U12.000000_Seed1693606511.0.bts'] - } - r.save_dir = '/Users/dzalkind/Projects/RAAW/RAAW_OpenFAST/outputs/PS_BD' - r.control_sweep_fcn = cl.sweep_ps_percent - r.n_cores = 8 - - elif sim_config == 11: - - # RAAW FAD set up - r.tuning_yaml = '/Users/dzalkind/Projects/RAAW/RAAW_OpenFAST/ROSCO/RAAW_rosco_BD.yaml' - r.wind_case_fcn = cl.user_hh - r.wind_case_opts = { - 'TMax': 1000., - 'wind_filenames': ['/Users/dzalkind/Projects/RAAW/RAAW_OpenFAST/Performance/GE_P3_WindStep.asc'] - } - r.save_dir = '/Users/dzalkind/Projects/RAAW/RAAW_OpenFAST/outputs/PS_steps' - r.control_sweep_fcn = cl.sweep_ps_percent - r.n_cores = 4 - else: raise Exception('This simulation configuration is not supported.') diff --git a/ROSCO_toolbox/ofTools/fast_io/update_discons.py b/ROSCO_toolbox/ofTools/fast_io/update_discons.py index 6c8b6271..72abb605 100644 --- a/ROSCO_toolbox/ofTools/fast_io/update_discons.py +++ b/ROSCO_toolbox/ofTools/fast_io/update_discons.py @@ -15,10 +15,16 @@ def update_discons(tune_to_test_map): if not isinstance(tune_to_test_map[tuning_yaml],list): tune_to_test_map[tuning_yaml] = [tune_to_test_map[tuning_yaml]] + # Handle relative directory to Cp file + yaml_dir = os.path.dirname(tuning_yaml) + cp_filename = os.path.relpath( + os.path.join(yaml_dir,path_params['rotor_performance_filename']), + os.path.join(yaml_dir,path_params['FAST_directory'])) + discon_in_files = [f for f in tune_to_test_map[tuning_yaml]] for discon in discon_in_files: write_DISCON( turbine,controller, param_file=discon, - txt_filename=path_params['rotor_performance_filename'] + txt_filename=cp_filename ) diff --git a/ROSCO_toolbox/utilities.py b/ROSCO_toolbox/utilities.py index 44b8e03f..7f43ab4f 100644 --- a/ROSCO_toolbox/utilities.py +++ b/ROSCO_toolbox/utilities.py @@ -80,6 +80,9 @@ def write_DISCON(turbine, controller, param_file='DISCON.IN', txt_filename='Cp_C rosco_vt['CC_GroupIndex'] = [rosco_vt['CC_GroupIndex']] # make an array if not hasattr(rosco_vt['StC_GroupIndex'],'__len__'): rosco_vt['StC_GroupIndex'] = [rosco_vt['StC_GroupIndex']] + # Get input descriptions + #input_schema = load_yaml(os.path.join(os.path.dirname(__file__),'inputs/toolbox_schema.yaml')) + #discon_props = input_schema['properties']['controller_params']['properties']['DISCON']['properties'] print('Writing new controller parameter file parameter file: %s.' % param_file) # Should be obvious what's going on here... @@ -87,8 +90,9 @@ def write_DISCON(turbine, controller, param_file='DISCON.IN', txt_filename='Cp_C file.write('! Controller parameter input file for the %s wind turbine\n' % turbine.TurbineName) file.write('! - File written using ROSCO version {} controller tuning logic on {}\n'.format(ROSCO_toolbox.__version__, now.strftime('%m/%d/%y'))) file.write('\n') - file.write('!------- DEBUG ------------------------------------------------------------\n') - file.write('{0:<12d} ! LoggingLevel - (0: write no debug files, 1: write standard output .dbg-file, 2: LoggingLevel 1 + ROSCO LocalVars (.dbg2) 3: LoggingLevel 2 + complete avrSWAP-array (.dbg3))\n'.format(int(rosco_vt['LoggingLevel']))) + file.write('!------- SIMULATION CONTROL ------------------------------------------------------------\n') + file.write('{0:<12d} ! LoggingLevel - {{0: write no debug files, 1: write standard output .dbg-file, 2: LoggingLevel 1 + ROSCO LocalVars (.dbg2) 3: LoggingLevel 2 + complete avrSWAP-array (.dbg3)}}\n'.format(int(rosco_vt['LoggingLevel']))) + file.write('{} ! DT_Out - {{Time step to output .dbg* files, or 0 to match sampling period of OpenFAST}}\n'.format(rosco_vt['DT_Out'])) file.write('{:<11d} ! Echo - ({})\n'.format(int(rosco_vt['Echo']), input_descriptions['Echo'])) file.write('\n') file.write('!------- CONTROLLER FLAGS -------------------------------------------------\n') @@ -105,7 +109,7 @@ def write_DISCON(turbine, controller, param_file='DISCON.IN', txt_filename='Cp_C file.write('{0:<12d} ! Fl_Mode - Floating specific feedback mode {{0: no nacelle velocity feedback, 1: feed back translational velocity, 2: feed back rotational veloicty}}\n'.format(int(rosco_vt['Fl_Mode']))) file.write('{0:<12d} ! TD_Mode - Tower damper mode {{0: no tower damper, 1: feed back translational nacelle accelleration to pitch angle}}\n'.format(int(rosco_vt['TD_Mode']))) file.write('{0:<12d} ! Flp_Mode - Flap control mode {{0: no flap control, 1: steady state flap angle, 2: Proportional flap control, 2: Cyclic (1P) flap control}}\n'.format(int(rosco_vt['Flp_Mode']))) - file.write('{0:<12d} ! OL_Mode - Open loop control mode {{0: no open loop control, 1: open loop control vs. time}}\n'.format(int(rosco_vt['OL_Mode']))) + file.write('{0:<12d} ! OL_Mode - Open loop control mode {{0: no open loop control, 1: open loop control vs. time, 2: rotor position control}}\n'.format(int(rosco_vt['OL_Mode']))) file.write('{0:<12d} ! PA_Mode - Pitch actuator mode {{0 - not used, 1 - first order filter, 2 - second order filter}}\n'.format(int(rosco_vt['PA_Mode']))) file.write('{0:<12d} ! PF_Mode - Pitch fault mode {{0 - not used, 1 - constant offset on one or more blades}}\n'.format(int(rosco_vt['PF_Mode']))) file.write('{0:<12d} ! AWC_Mode - Active wake control {{0 - not used, 1 - complex number method, 2 - Coleman transform method}}\n'.format(int(rosco_vt['AWC_Mode']))) @@ -227,9 +231,11 @@ def write_DISCON(turbine, controller, param_file='DISCON.IN', txt_filename='Cp_C file.write('!------- Open Loop Control -----------------------------------------------------\n') file.write('"{}" ! OL_Filename - Input file with open loop timeseries (absolute path or relative to this file)\n'.format(rosco_vt['OL_Filename'])) file.write('{0:<12d} ! Ind_Breakpoint - The column in OL_Filename that contains the breakpoint (time if OL_Mode = 1)\n'.format(int(rosco_vt['Ind_Breakpoint']))) - file.write('{0:<12d} ! Ind_BldPitch - The column in OL_Filename that contains the blade pitch input in rad\n'.format(int(rosco_vt['Ind_BldPitch']))) + file.write('{} ! Ind_BldPitch - The columns in OL_Filename that contains the blade pitch (1,2,3) inputs in rad [array]\n'.format(' '.join([f'{int(ipb):3d}' for ipb in rosco_vt['Ind_BldPitch']]))) file.write('{0:<12d} ! Ind_GenTq - The column in OL_Filename that contains the generator torque in Nm\n'.format(int(rosco_vt['Ind_GenTq']))) - file.write('{0:<12d} ! Ind_YawRate - The column in OL_Filename that contains the nacelle yaw rate rad/s\n'.format(int(rosco_vt['Ind_YawRate']))) + file.write('{0:<12d} ! Ind_YawRate - The column in OL_Filename that contains the yaw rate in rad/s\n'.format(int(rosco_vt['Ind_YawRate']))) + file.write('{:<12d} ! Ind_Azimuth - {}\n'.format(int(rosco_vt["Ind_Azimuth"]), input_descriptions["Ind_Azimuth"])) + file.write('{} ! {} - {}\n'.format(' '.join([f'{g:02.4f}' for g in rosco_vt["RP_Gains"]]),"RP_Gains",input_descriptions["RP_Gains"])) file.write('{} ! Ind_CableControl - The column(s) in OL_Filename that contains the cable control inputs in m [Used with CC_Mode = 2, must be the same size as CC_Group_N]\n'.format(write_array(rosco_vt['Ind_CableControl'],'<4d'))) file.write('{} ! Ind_StructControl - The column(s) in OL_Filename that contains the structural control inputs [Used with StC_Mode = 2, must be the same size as StC_Group_N]\n'.format(write_array(rosco_vt['Ind_StructControl'],'<4d'))) file.write('\n') @@ -305,6 +311,8 @@ def read_DISCON(DISCON_filename): # Remove printed quotations if string is in quotes if (value[0] == '"') or (value[0] == "'"): value = value[1:-1] + elif value == 'DEFAULT': + pass else: value = float(value) DISCON_in[param] = value @@ -574,6 +582,8 @@ def DISCON_dict(turbine, controller, txt_filename=None): DISCON_dict['Ind_YawRate'] = controller.OL_Ind_YawRate DISCON_dict['Ind_CableControl'] = controller.OL_Ind_CableControl DISCON_dict['Ind_StructControl'] = controller.OL_Ind_StructControl + DISCON_dict['Ind_Azimuth'] = controller.OL_Ind_Azimuth + # ------- Pitch Actuator ------- DISCON_dict['PA_Mode'] = controller.PA_Mode DISCON_dict['PA_CornerFreq'] = controller.PA_CornerFreq diff --git a/Test_Cases/BAR_10/BAR_10_DISCON.IN b/Test_Cases/BAR_10/BAR_10_DISCON.IN index b3636e42..64e561d6 100644 --- a/Test_Cases/BAR_10/BAR_10_DISCON.IN +++ b/Test_Cases/BAR_10/BAR_10_DISCON.IN @@ -1,8 +1,9 @@ ! Controller parameter input file for the BAR_10 wind turbine -! - File written using ROSCO version 2.8.0 controller tuning logic on 06/13/23 +! - File written using ROSCO version 2.8.0 controller tuning logic on 08/03/23 -!------- DEBUG ------------------------------------------------------------ -1 ! LoggingLevel - (0: write no debug files, 1: write standard output .dbg-file, 2: LoggingLevel 1 + ROSCO LocalVars (.dbg2) 3: LoggingLevel 2 + complete avrSWAP-array (.dbg3)) +!------- SIMULATION CONTROL ------------------------------------------------------------ +1 ! LoggingLevel - {0: write no debug files, 1: write standard output .dbg-file, 2: LoggingLevel 1 + ROSCO LocalVars (.dbg2) 3: LoggingLevel 2 + complete avrSWAP-array (.dbg3)} +0 ! DT_Out - {Time step to output .dbg* files, or 0 to match sampling period of OpenFAST} 0 ! Echo - (0 - no Echo, 1 - Echo input data to .echo) !------- CONTROLLER FLAGS ------------------------------------------------- @@ -19,7 +20,7 @@ 0 ! Fl_Mode - Floating specific feedback mode {0: no nacelle velocity feedback, 1: feed back translational velocity, 2: feed back rotational veloicty} 0 ! TD_Mode - Tower damper mode {0: no tower damper, 1: feed back translational nacelle accelleration to pitch angle} 2 ! Flp_Mode - Flap control mode {0: no flap control, 1: steady state flap angle, 2: Proportional flap control, 2: Cyclic (1P) flap control} -0 ! OL_Mode - Open loop control mode {0: no open loop control, 1: open loop control vs. time} +0 ! OL_Mode - Open loop control mode {0: no open loop control, 1: open loop control vs. time, 2: rotor position control} 0 ! PA_Mode - Pitch actuator mode {0 - not used, 1 - first order filter, 2 - second order filter} 0 ! PF_Mode - Pitch fault mode {0 - not used, 1 - constant offset on one or more blades} 0 ! AWC_Mode - Active wake control {0 - not used, 1 - complex number method, 2 - Coleman transform method} @@ -135,9 +136,11 @@ !------- Open Loop Control ----------------------------------------------------- "unused" ! OL_Filename - Input file with open loop timeseries (absolute path or relative to this file) 0 ! Ind_Breakpoint - The column in OL_Filename that contains the breakpoint (time if OL_Mode = 1) -0 ! Ind_BldPitch - The column in OL_Filename that contains the blade pitch input in rad + 0 0 0 ! Ind_BldPitch - The columns in OL_Filename that contains the blade pitch (1,2,3) inputs in rad [array] 0 ! Ind_GenTq - The column in OL_Filename that contains the generator torque in Nm -0 ! Ind_YawRate - The column in OL_Filename that contains the nacelle yaw rate rad/s +0 ! Ind_YawRate - The column in OL_Filename that contains the yaw rate in rad/s +0 ! Ind_Azimuth - The column in OL_Filename that contains the desired azimuth position in rad (used if OL_Mode = 2) +0.0000 0.0000 0.0000 0.0000 ! RP_Gains - PID gains and Tf of derivative for rotor position control (used if OL_Mode = 2) 0 ! Ind_CableControl - The column(s) in OL_Filename that contains the cable control inputs in m [Used with CC_Mode = 2, must be the same size as CC_Group_N] 0 ! Ind_StructControl - The column(s) in OL_Filename that contains the structural control inputs [Used with StC_Mode = 2, must be the same size as StC_Group_N] diff --git a/Test_Cases/IEA-15-240-RWT-UMaineSemi/DISCON-UMaineSemi.IN b/Test_Cases/IEA-15-240-RWT-UMaineSemi/DISCON-UMaineSemi.IN index be780b4c..3624b81c 100644 --- a/Test_Cases/IEA-15-240-RWT-UMaineSemi/DISCON-UMaineSemi.IN +++ b/Test_Cases/IEA-15-240-RWT-UMaineSemi/DISCON-UMaineSemi.IN @@ -1,8 +1,9 @@ ! Controller parameter input file for the IEA-15-240-RWT-UMaineSemi wind turbine -! - File written using ROSCO version 2.8.0 controller tuning logic on 06/13/23 +! - File written using ROSCO version 2.8.0 controller tuning logic on 08/03/23 -!------- DEBUG ------------------------------------------------------------ -2 ! LoggingLevel - (0: write no debug files, 1: write standard output .dbg-file, 2: LoggingLevel 1 + ROSCO LocalVars (.dbg2) 3: LoggingLevel 2 + complete avrSWAP-array (.dbg3)) +!------- SIMULATION CONTROL ------------------------------------------------------------ +2 ! LoggingLevel - {0: write no debug files, 1: write standard output .dbg-file, 2: LoggingLevel 1 + ROSCO LocalVars (.dbg2) 3: LoggingLevel 2 + complete avrSWAP-array (.dbg3)} +0 ! DT_Out - {Time step to output .dbg* files, or 0 to match sampling period of OpenFAST} 0 ! Echo - (0 - no Echo, 1 - Echo input data to .echo) !------- CONTROLLER FLAGS ------------------------------------------------- @@ -19,7 +20,7 @@ 2 ! Fl_Mode - Floating specific feedback mode {0: no nacelle velocity feedback, 1: feed back translational velocity, 2: feed back rotational veloicty} 0 ! TD_Mode - Tower damper mode {0: no tower damper, 1: feed back translational nacelle accelleration to pitch angle} 0 ! Flp_Mode - Flap control mode {0: no flap control, 1: steady state flap angle, 2: Proportional flap control, 2: Cyclic (1P) flap control} -0 ! OL_Mode - Open loop control mode {0: no open loop control, 1: open loop control vs. time} +0 ! OL_Mode - Open loop control mode {0: no open loop control, 1: open loop control vs. time, 2: rotor position control} 2 ! PA_Mode - Pitch actuator mode {0 - not used, 1 - first order filter, 2 - second order filter} 0 ! PF_Mode - Pitch fault mode {0 - not used, 1 - constant offset on one or more blades} 0 ! AWC_Mode - Active wake control {0 - not used, 1 - complex number method, 2 - Coleman transform method} @@ -135,9 +136,11 @@ !------- Open Loop Control ----------------------------------------------------- "unused" ! OL_Filename - Input file with open loop timeseries (absolute path or relative to this file) 0 ! Ind_Breakpoint - The column in OL_Filename that contains the breakpoint (time if OL_Mode = 1) -0 ! Ind_BldPitch - The column in OL_Filename that contains the blade pitch input in rad + 0 0 0 ! Ind_BldPitch - The columns in OL_Filename that contains the blade pitch (1,2,3) inputs in rad [array] 0 ! Ind_GenTq - The column in OL_Filename that contains the generator torque in Nm -0 ! Ind_YawRate - The column in OL_Filename that contains the nacelle yaw rate rad/s +0 ! Ind_YawRate - The column in OL_Filename that contains the yaw rate in rad/s +0 ! Ind_Azimuth - The column in OL_Filename that contains the desired azimuth position in rad (used if OL_Mode = 2) +0.0000 0.0000 0.0000 0.0000 ! RP_Gains - PID gains and Tf of derivative for rotor position control (used if OL_Mode = 2) 0 ! Ind_CableControl - The column(s) in OL_Filename that contains the cable control inputs in m [Used with CC_Mode = 2, must be the same size as CC_Group_N] 0 ! Ind_StructControl - The column(s) in OL_Filename that contains the structural control inputs [Used with StC_Mode = 2, must be the same size as StC_Group_N] diff --git a/Test_Cases/NREL-5MW/DISCON.IN b/Test_Cases/NREL-5MW/DISCON.IN index 22d049d4..96930d27 100644 --- a/Test_Cases/NREL-5MW/DISCON.IN +++ b/Test_Cases/NREL-5MW/DISCON.IN @@ -1,8 +1,9 @@ ! Controller parameter input file for the NREL-5MW wind turbine -! - File written using ROSCO version 2.8.0 controller tuning logic on 06/13/23 +! - File written using ROSCO version 2.8.0 controller tuning logic on 08/03/23 -!------- DEBUG ------------------------------------------------------------ -1 ! LoggingLevel - (0: write no debug files, 1: write standard output .dbg-file, 2: LoggingLevel 1 + ROSCO LocalVars (.dbg2) 3: LoggingLevel 2 + complete avrSWAP-array (.dbg3)) +!------- SIMULATION CONTROL ------------------------------------------------------------ +1 ! LoggingLevel - {0: write no debug files, 1: write standard output .dbg-file, 2: LoggingLevel 1 + ROSCO LocalVars (.dbg2) 3: LoggingLevel 2 + complete avrSWAP-array (.dbg3)} +0 ! DT_Out - {Time step to output .dbg* files, or 0 to match sampling period of OpenFAST} 0 ! Echo - (0 - no Echo, 1 - Echo input data to .echo) !------- CONTROLLER FLAGS ------------------------------------------------- @@ -19,7 +20,7 @@ 0 ! Fl_Mode - Floating specific feedback mode {0: no nacelle velocity feedback, 1: feed back translational velocity, 2: feed back rotational veloicty} 0 ! TD_Mode - Tower damper mode {0: no tower damper, 1: feed back translational nacelle accelleration to pitch angle} 0 ! Flp_Mode - Flap control mode {0: no flap control, 1: steady state flap angle, 2: Proportional flap control, 2: Cyclic (1P) flap control} -0 ! OL_Mode - Open loop control mode {0: no open loop control, 1: open loop control vs. time} +0 ! OL_Mode - Open loop control mode {0: no open loop control, 1: open loop control vs. time, 2: rotor position control} 0 ! PA_Mode - Pitch actuator mode {0 - not used, 1 - first order filter, 2 - second order filter} 0 ! PF_Mode - Pitch fault mode {0 - not used, 1 - constant offset on one or more blades} 0 ! AWC_Mode - Active wake control {0 - not used, 1 - complex number method, 2 - Coleman transform method} @@ -135,9 +136,11 @@ !------- Open Loop Control ----------------------------------------------------- "unused" ! OL_Filename - Input file with open loop timeseries (absolute path or relative to this file) 0 ! Ind_Breakpoint - The column in OL_Filename that contains the breakpoint (time if OL_Mode = 1) -0 ! Ind_BldPitch - The column in OL_Filename that contains the blade pitch input in rad + 0 0 0 ! Ind_BldPitch - The columns in OL_Filename that contains the blade pitch (1,2,3) inputs in rad [array] 0 ! Ind_GenTq - The column in OL_Filename that contains the generator torque in Nm -0 ! Ind_YawRate - The column in OL_Filename that contains the nacelle yaw rate rad/s +0 ! Ind_YawRate - The column in OL_Filename that contains the yaw rate in rad/s +0 ! Ind_Azimuth - The column in OL_Filename that contains the desired azimuth position in rad (used if OL_Mode = 2) +0.0000 0.0000 0.0000 0.0000 ! RP_Gains - PID gains and Tf of derivative for rotor position control (used if OL_Mode = 2) 0 ! Ind_CableControl - The column(s) in OL_Filename that contains the cable control inputs in m [Used with CC_Mode = 2, must be the same size as CC_Group_N] 0 ! Ind_StructControl - The column(s) in OL_Filename that contains the structural control inputs [Used with StC_Mode = 2, must be the same size as StC_Group_N] diff --git a/Test_Cases/NREL_2p8_127/NREL-2p8-127_DISCON.IN b/Test_Cases/NREL_2p8_127/NREL-2p8-127_DISCON.IN index 4366ff44..f327e491 100644 --- a/Test_Cases/NREL_2p8_127/NREL-2p8-127_DISCON.IN +++ b/Test_Cases/NREL_2p8_127/NREL-2p8-127_DISCON.IN @@ -1,8 +1,9 @@ ! Controller parameter input file for the NREL-2p8-127 wind turbine -! - File written using ROSCO version 2.8.0 controller tuning logic on 06/13/23 +! - File written using ROSCO version 2.8.0 controller tuning logic on 08/03/23 -!------- DEBUG ------------------------------------------------------------ -2 ! LoggingLevel - (0: write no debug files, 1: write standard output .dbg-file, 2: LoggingLevel 1 + ROSCO LocalVars (.dbg2) 3: LoggingLevel 2 + complete avrSWAP-array (.dbg3)) +!------- SIMULATION CONTROL ------------------------------------------------------------ +2 ! LoggingLevel - {0: write no debug files, 1: write standard output .dbg-file, 2: LoggingLevel 1 + ROSCO LocalVars (.dbg2) 3: LoggingLevel 2 + complete avrSWAP-array (.dbg3)} +0 ! DT_Out - {Time step to output .dbg* files, or 0 to match sampling period of OpenFAST} 0 ! Echo - (0 - no Echo, 1 - Echo input data to .echo) !------- CONTROLLER FLAGS ------------------------------------------------- @@ -19,7 +20,7 @@ 0 ! Fl_Mode - Floating specific feedback mode {0: no nacelle velocity feedback, 1: feed back translational velocity, 2: feed back rotational veloicty} 0 ! TD_Mode - Tower damper mode {0: no tower damper, 1: feed back translational nacelle accelleration to pitch angle} 0 ! Flp_Mode - Flap control mode {0: no flap control, 1: steady state flap angle, 2: Proportional flap control, 2: Cyclic (1P) flap control} -0 ! OL_Mode - Open loop control mode {0: no open loop control, 1: open loop control vs. time} +0 ! OL_Mode - Open loop control mode {0: no open loop control, 1: open loop control vs. time, 2: rotor position control} 0 ! PA_Mode - Pitch actuator mode {0 - not used, 1 - first order filter, 2 - second order filter} 0 ! PF_Mode - Pitch fault mode {0 - not used, 1 - constant offset on one or more blades} 0 ! AWC_Mode - Active wake control {0 - not used, 1 - complex number method, 2 - Coleman transform method} @@ -135,9 +136,11 @@ !------- Open Loop Control ----------------------------------------------------- "unused" ! OL_Filename - Input file with open loop timeseries (absolute path or relative to this file) 0 ! Ind_Breakpoint - The column in OL_Filename that contains the breakpoint (time if OL_Mode = 1) -0 ! Ind_BldPitch - The column in OL_Filename that contains the blade pitch input in rad + 0 0 0 ! Ind_BldPitch - The columns in OL_Filename that contains the blade pitch (1,2,3) inputs in rad [array] 0 ! Ind_GenTq - The column in OL_Filename that contains the generator torque in Nm -0 ! Ind_YawRate - The column in OL_Filename that contains the nacelle yaw rate rad/s +0 ! Ind_YawRate - The column in OL_Filename that contains the yaw rate in rad/s +0 ! Ind_Azimuth - The column in OL_Filename that contains the desired azimuth position in rad (used if OL_Mode = 2) +0.0000 0.0000 0.0000 0.0000 ! RP_Gains - PID gains and Tf of derivative for rotor position control (used if OL_Mode = 2) 0 ! Ind_CableControl - The column(s) in OL_Filename that contains the cable control inputs in m [Used with CC_Mode = 2, must be the same size as CC_Group_N] 0 ! Ind_StructControl - The column(s) in OL_Filename that contains the structural control inputs [Used with StC_Mode = 2, must be the same size as StC_Group_N] diff --git a/Tune_Cases/IEA15MW_OL.yaml b/Tune_Cases/IEA15MW_OL.yaml index 50e7bc81..b14e3895 100644 --- a/Tune_Cases/IEA15MW_OL.yaml +++ b/Tune_Cases/IEA15MW_OL.yaml @@ -39,6 +39,7 @@ controller_params: SD_Mode: 0 # Shutdown mode {0: no shutdown procedure, 1: pitch to max pitch at shutdown} Fl_Mode: 1 # Floating specific feedback mode {0: no nacelle velocity feedback, 1: nacelle velocity feedback} Flp_Mode: 0 # Flap control mode {0: no flap control, 1: steady state flap angle, 2: Proportional flap control} + OL_Mode: 1 # Controller parameters zeta_pc: 1.0 # Pitch controller desired damping ratio [-] omega_pc: 0.3 # Pitch controller desired natural frequency [rad/s] @@ -51,7 +52,7 @@ controller_params: open_loop: flag: True OL_Ind_Breakpoint: 1 - OL_Ind_BldPitch: 2 + OL_Ind_BldPitch: [2,2,2] filename: /Users/dzalkind/Downloads/pitch_LC2p2_4ROSCO.dat # dt: 0.05 # t_max: 200 diff --git a/Tune_Cases/IEA15MW_ballast.yaml b/Tune_Cases/IEA15MW_ballast.yaml index ab5fc90f..2781aaca 100644 --- a/Tune_Cases/IEA15MW_ballast.yaml +++ b/Tune_Cases/IEA15MW_ballast.yaml @@ -39,7 +39,8 @@ controller_params: Fl_Mode: 2 # Floating specific feedback mode {0: no nacelle velocity feedback, 1: nacelle velocity feedback} Flp_Mode: 0 # Flap control mode {0: no flap control, 1: steady state flap angle, 2: Proportional flap control} PA_Mode: 2 # Pitch actuator mode {0 - not used, 1 - first order filter, 2 - second order filter} - StC_Mode: 1 + StC_Mode: 2 + OL_Mode: 1 # Controller parameters # U_pc: [14] zeta_pc: 1.0 # Pitch controller desired damping ratio [-] diff --git a/Tune_Cases/IEA15MW_cable.yaml b/Tune_Cases/IEA15MW_cable.yaml index be81e6ec..abba79fe 100644 --- a/Tune_Cases/IEA15MW_cable.yaml +++ b/Tune_Cases/IEA15MW_cable.yaml @@ -39,7 +39,8 @@ controller_params: Fl_Mode: 2 # Floating specific feedback mode {0: no nacelle velocity feedback, 1: nacelle velocity feedback} Flp_Mode: 0 # Flap control mode {0: no flap control, 1: steady state flap angle, 2: Proportional flap control} PA_Mode: 2 # Pitch actuator mode {0 - not used, 1 - first order filter, 2 - second order filter} - CC_Mode: 1 + CC_Mode: 2 + OL_Mode: 1 # Controller parameters # U_pc: [14] zeta_pc: 1.0 # Pitch controller desired damping ratio [-] diff --git a/docs/source/api_change.rst b/docs/source/api_change.rst index 0598c0c8..86d88444 100644 --- a/docs/source/api_change.rst +++ b/docs/source/api_change.rst @@ -12,30 +12,44 @@ Thus, be sure to implement each in order so that subsequent line numbers are cor 2.8.0 to develop ------------------------------- Gain scheduling of floating feedback -- The floating feedback gain can be scheduled on the low pass filtered wind speed signal. Note that Fl_Kp can now be an array. +- The floating feedback gain can be scheduled on the low pass filtered wind speed signal. Note that Fl_Kp can now be an array. +- Control all three blade pitch inputs in open loop +- Rotor position control of azimuth position with PID (RP_Gains) control inputs +====== ================= ====================================================================================================================================================================================================== +Changed in ROSCO develop +---------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- +Line Input Name Example Value +====== ================= ====================================================================================================================================================================================================== +126 OL_mode 0 ! OL_Mode - Open loop control mode {0: no open loop control, 1: open loop control vs. time, 2: rotor position control} +126 Fl_Kp 0.0000 ! Fl_Kp - Nacelle velocity proportional feedback gain [s] +139 Ind_BldPitch 0 0 0 ! Ind_BldPitch - The columns in OL_Filename that contains the blade pitch (1,2,3) inputs in rad [array] +====== ================= ====================================================================================================================================================================================================== + ====== ================= ====================================================================================================================================================================================================== New in ROSCO develop ---------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- Line Input Name Example Value ====== ================= ====================================================================================================================================================================================================== -125 Fl_n 1 ! Fl_n - Number of Fl_Kp gains in gain scheduling, optional with default of 1 -126 Fl_Kp 0.0000 ! Fl_Kp - Nacelle velocity proportional feedback gain [s] -127 Fl_U 0.0000 ! Fl_U - Wind speeds for scheduling Fl_Kp, optional if Fl_Kp is single value [m/s] +125 Fl_n 1 ! Fl_n - Number of Fl_Kp gains in gain scheduling, optional with default of 1 +127 Fl_U 0.0000 ! Fl_U - Wind speeds for scheduling Fl_Kp, optional if Fl_Kp is single value [m/s] +142 Ind_Azimuth 0 ! Ind_Azimuth - The column in OL_Filename that contains the desired azimuth position in rad (used if OL_Mode = 2) +143 RP_Gains 0.0000 0.0000 0.0000 0.0000 ! RP_Gains - PID gains and Tf of derivative for rotor position control (used if OL_Mode = 2) ====== ================= ====================================================================================================================================================================================================== + 2.7.0 to 2.8.0 ------------------------------- Optional Inputs -- ROSCO now reads in the whole input file and searches for keywords to set the inputs. Blank spaces and specific ordering are no longer required. -- Input requirements depend on control modes. E.g., open loop inputs are not required if `OL_Mode = 0`` +- ROSCO now reads in the whole input file and searches for keywords to set the inputs. Blank spaces and specific ordering are no longer required. +- Input requirements depend on control modes. E.g., open loop inputs are not required if `OL_Mode = 0`` Cable Control -- Can control OpenFAST cables (MoorDyn or SubDyn) using ROSCO +- Can control OpenFAST cables (MoorDyn or SubDyn) using ROSCO Structural Control -- Can control OpenFAST structural control elements (ServoDyn) using ROSCO +- Can control OpenFAST structural control elements (ServoDyn) using ROSCO Active wake control -- Added Active Wake Control (AWC) implementation +- Added Active Wake Control (AWC) implementation ====== ================= ====================================================================================================================================================================================================== New in ROSCO 2.8.0 @@ -71,9 +85,9 @@ Line Input Name Example Value 2.6.0 to 2.7.0 ------------------------------- Pitch Faults -- Constant pitch actuator offsets (PF_Mode = 1) +- Constant pitch actuator offsets (PF_Mode = 1) IPC Saturation Modes -- Added options for saturating the IPC command with the peak shaving limit +- Added options for saturating the IPC command with the peak shaving limit ====== ================= ====================================================================================================================================================================================================== New in ROSCO 2.7.0 @@ -91,19 +105,19 @@ Line Input Name Example Value 2.5.0 to 2.6.0 ------------------------------- IPC -- A wind speed based soft cut-in using a sigma interpolation is added for the IPC controller +- A wind speed based soft cut-in using a sigma interpolation is added for the IPC controller Pitch Actuator -- A first or second order filter can be used to model a pitch actuator +- A first or second order filter can be used to model a pitch actuator External Control Interface -- Call another control library from ROSCO +- Call another control library from ROSCO ZeroMQ Interface -- Communicate with an external routine via ZeroMQ. Only yaw control currently supported +- Communicate with an external routine via ZeroMQ. Only yaw control currently supported Updated yaw control -- Filter wind direction with deadband, and yaw until direction error changes signs (https://iopscience.iop.org/article/10.1088/1742-6596/1037/3/032011) +- Filter wind direction with deadband, and yaw until direction error changes signs (https://iopscience.iop.org/article/10.1088/1742-6596/1037/3/032011) ====== ================= ====================================================================================================================================================================================================== New in ROSCO 2.6.0 @@ -157,18 +171,18 @@ Line Input Name Example Value ROSCO v2.4.1 to ROSCO v2.5.0 ------------------------------- Two filter parameters were added to -- change the high pass filter in the floating feedback module -- change the low pass filter of the wind speed estimator signal that is used in torque control +- change the high pass filter in the floating feedback module +- change the low pass filter of the wind speed estimator signal that is used in torque control Open loop control inputs, users must specify: -- The open loop input filename, an example can be found in Examples/Example_OL_Input.dat -- Indices (columns) of values specified in OL_Filename +- The open loop input filename, an example can be found in Examples/Example_OL_Input.dat +- Indices (columns) of values specified in OL_Filename IPC -- Proportional Control capabilities were added, 1P and 2P gains should be specified +- Proportional Control capabilities were added, 1P and 2P gains should be specified ====== ================= ====================================================================================================================================================================================================== -Line Flag Name Example Value +Line Input Name Example Value ====== ================= ====================================================================================================================================================================================================== 20 OL_Mode 0 ! OL_Mode - Open loop control mode {0: no open loop control, 1: open loop control vs. time, 2: open loop control vs. wind speed} 27 F_WECornerFreq 0.20944 ! F_WECornerFreq - Corner frequency (-3dB point) in the first order low pass filter for the wind speed estimate [rad/s]. diff --git a/docs/source/install.rst b/docs/source/install.rst index 4e310e49..023da03c 100644 --- a/docs/source/install.rst +++ b/docs/source/install.rst @@ -61,7 +61,7 @@ In order to download the most recently compiled version release, from an anacond .. code-block:: bash conda config --add channels conda-forge - conda create -y --name rosco-env python=3.8 + conda create -y --name rosco-env python=3.9 conda activate rosco-env navigate to your desired folder to save the compiled binary using: diff --git a/docs/source/toolbox_input.rst b/docs/source/toolbox_input.rst index 6e15f0e2..94ae3683 100644 --- a/docs/source/toolbox_input.rst +++ b/docs/source/toolbox_input.rst @@ -265,6 +265,14 @@ controller_params *Minimum* = 0 *Maximum* = 1 +:code:`OL_Mode` : Float + Open loop control mode {0- no open loop control, 1- open loop + control} + + *Default* = 0 + + *Minimum* = 0 *Maximum* = 2 + :code:`AWC_Mode` : Float Active wake control mode {0 - not used, 1 - SNL method, 2 - NREL method} @@ -553,23 +561,38 @@ open_loop *Default* = unused -:code:`OL_Ind_Breakpoint` : Float +:code:`Ind_Breakpoint` : Float Index (column, 1-indexed) of breakpoint (time) in open loop index *Default* = 1 -:code:`OL_Ind_BldPitch` : Float - Index (column, 1-indexed) of breakpoint (time) in open loop index + *Minimum* = 0 + +:code:`Ind_BldPitch` : Array of Floats + Indices (columns, 1-indexed) of pitch (1,2,3) inputs in open loop + input + + *Default* = [0, 0, 0] + + *Minimum* = 0 + +:code:`Ind_GenTq` : Float + Index (column, 1-indexed) of generator torque in open loop input *Default* = 0 -:code:`OL_Ind_GenTq` : Float - Index (column, 1-indexed) of breakpoint (time) in open loop index + *Minimum* = 0 + +:code:`Ind_YawRate` : Float + Index (column, 1-indexed) of nacelle yaw in open loop input *Default* = 0 -:code:`OL_Ind_YawRate` : Float - Index (column, 1-indexed) of breakpoint (time) in open loop index + *Minimum* = 0 + +:code:`Ind_Azimuth` : Float + The column in OL_Filename that contains the desired azimuth + position in rad (used if OL_Mode = 2) *Default* = 0 @@ -593,7 +616,7 @@ DISCON ######################################## -These are pass-through parameters for the DISCON.IN file. Use with caution. +These are pass-through parameters for the DISCON.IN file. Use with caution. Do not set defaults in schema. :code:`LoggingLevel` : Float (0- write no debug files, 1- write standard output .dbg-file, 2- @@ -659,6 +682,10 @@ These are pass-through parameters for the DISCON.IN file. Use with caution. Flap control mode (0- no flap control, 1- steady state flap angle, 2- Proportional flap control) +:code:`OL_Mode` : Float + Open loop control mode (0 - no open-loop control, 1 - direct open + loop control, 2 - rotor position control) + :code:`F_LPFCornerFreq` : Float, rad/s Corner frequency (-3dB point) in the low-pass filters, @@ -940,7 +967,7 @@ These are pass-through parameters for the DISCON.IN file. Use with caution. :code:`Ind_Breakpoint` : Float The column in OL_Filename that contains the breakpoint (time if - OL_Mode = 1) + OL_Mode > 0) :code:`Ind_BldPitch` : Float The column in OL_Filename that contains the blade pitch input in @@ -952,6 +979,15 @@ These are pass-through parameters for the DISCON.IN file. Use with caution. :code:`Ind_YawRate` : Float The column in OL_Filename that contains the generator torque in Nm +:code:`Ind_Azimuth` : Float + The column in OL_Filename that contains the desired azimuth + position in rad (used if OL_Mode = 2) + +:code:`RP_Gains` : Array of Floats + PID gains for rotor position control (used if OL_Mode = 2) + + *Default* = [0, 0, 0] + :code:`Ind_CableControl` : Array of Floats The column in OL_Filename that contains the cable control inputs in m From 31332d92314eae7adb49d71596c7e4178ee3b2ad Mon Sep 17 00:00:00 2001 From: Abhineet Gupta Date: Wed, 9 Aug 2023 15:40:59 -0600 Subject: [PATCH 110/224] Update .readthedocs.yaml to remove use of 'system_packages' as it is being depreciated by readthedocs (#258) --- .readthedocs.yaml | 1 - 1 file changed, 1 deletion(-) diff --git a/.readthedocs.yaml b/.readthedocs.yaml index 869209cb..ad4f1512 100644 --- a/.readthedocs.yaml +++ b/.readthedocs.yaml @@ -24,4 +24,3 @@ python: path: . extra_requirements: - docs - system_packages: true \ No newline at end of file From 63bcb0d4b6c996cfde603b4cb8465c05b345340b Mon Sep 17 00:00:00 2001 From: Athul Krishna Sundarrajan <59715652+AthulKrishnaSundarrajan@users.noreply.github.com> Date: Tue, 19 Sep 2023 09:17:17 -0600 Subject: [PATCH 111/224] Extend ROSCO for MHK (#257) * Select airfoil by reynolds_ref in turbine params * Select density based on main Fst file * Update FAST reader/writer * Add MHK example * MHK updates * Extend the number of notch filters on the generator speed and tower-top motion, and update OpenFAST input files for RM1 system * update tuning yaml for RM1 * minox fix in tuning yaml * Run run_FAST from weis more easily * Add documentation for new below rated genspeed reference * Change ROSCO version in setup.py * Line removal in ReadSetParameters * Don't change Notch type if already set and floating * Tidy up MHK example, input * Add example to CI testing * Add VS_ConstPower to simplify VS_ControlModes * Update MHK with constant power * Update WAMIT input to be same as openfast/r-test * minor change for Hydrodyn.dat * minor updates to the tuning yaml and the discon file * Add separate notch filters for Gen speed, tower top * Add start of filtering toolbox in matlab * Update DISCON files, "tune" filters using F_NotchType control param * Read notch filter inds only if N > 0 * Clean up example 26 * Update minimal DISCON inputs for test * Make GenSpdNotch inds optional based on GenSpdNotch_N * Add logic for updating discons * Clean up tune * Clean up DISCON formatting * Fix rgn2k, consistent with TSR opt now * Add filter on GenPwr for setpoint, add VS_RefSpd to LocalVars * Set initial VS_GenPwr like torque * Update 2.8 input file * Add TSR to standard outputs * Set RM1 model DT_out, ICs * Review notch filters in more depth * Add factor for fine-tuning rgn2k gain * Add function for sweeping any controller_param * Update API documentation * Tidy comments * Allow VS_ConstPowr to be optional * Declare dummy partials in robust_scheduling * Tidy edited code in turbine.py --------- Co-authored-by: dzalkind Co-authored-by: AthulKrishnaSundarrajan --- Examples/26_marine_hydro.py | 86 + Examples/example_inputs/minimal_DISCON.IN | 4 +- Examples/example_inputs/minimal_DISCON_err.IN | 9 +- Examples/test_examples.py | 1 + Matlab_Toolbox/rosco_filters.m | 65 + ROSCO/rosco_registry/rosco_types.yaml | 47 +- ROSCO/src/ControllerBlocks.f90 | 28 +- ROSCO/src/Controllers.f90 | 6 +- ROSCO/src/Filters.f90 | 68 +- ROSCO/src/ROSCO_IO.f90 | 261 +- ROSCO/src/ROSCO_Types.f90 | 19 +- ROSCO/src/ReadSetParameters.f90 | 74 +- ROSCO_toolbox/controller.py | 37 +- ROSCO_toolbox/inputs/toolbox_schema.yaml | 77 +- ROSCO_toolbox/linear/robust_scheduling.py | 3 + ROSCO_toolbox/ofTools/case_gen/CaseLibrary.py | 60 +- ROSCO_toolbox/ofTools/case_gen/run_FAST.py | 54 +- ROSCO_toolbox/ofTools/fast_io/FAST_reader.py | 9 +- ROSCO_toolbox/tune.py | 45 +- ROSCO_toolbox/turbine.py | 38 +- ROSCO_toolbox/utilities.py | 118 +- Test_Cases/BAR_10/BAR_10_DISCON.IN | 97 +- .../DISCON-UMaineSemi.IN | 97 +- Test_Cases/MHK_RM1/Airfoils/NACA6_0240.dat | 560 + .../MHK_RM1/Airfoils/NACA6_0240_coords.txt | 47 + Test_Cases/MHK_RM1/Airfoils/NACA6_0247.dat | 560 + .../MHK_RM1/Airfoils/NACA6_0247_coords.txt | 47 + Test_Cases/MHK_RM1/Airfoils/NACA6_0259.dat | 560 + .../MHK_RM1/Airfoils/NACA6_0259_coords.txt | 47 + Test_Cases/MHK_RM1/Airfoils/NACA6_0276.dat | 560 + .../MHK_RM1/Airfoils/NACA6_0276_coords.txt | 47 + Test_Cases/MHK_RM1/Airfoils/NACA6_0329.dat | 560 + .../MHK_RM1/Airfoils/NACA6_0329_coords.txt | 47 + Test_Cases/MHK_RM1/Airfoils/NACA6_0444.dat | 560 + .../MHK_RM1/Airfoils/NACA6_0444_coords.txt | 47 + Test_Cases/MHK_RM1/Airfoils/NACA6_0629.dat | 560 + .../MHK_RM1/Airfoils/NACA6_0629_coords.txt | 47 + Test_Cases/MHK_RM1/Airfoils/NACA6_0864.dat | 560 + .../MHK_RM1/Airfoils/NACA6_0864_coords.txt | 47 + Test_Cases/MHK_RM1/Airfoils/NACA6_1000.dat | 108 + .../MHK_RM1/Airfoils/NACA6_1000_coords.txt | 47 + .../MHK_RM1/MHK_RM1_AeroDyn15_Blade.dat | 38 + Test_Cases/MHK_RM1/MHK_RM1_Cp_Ct_Cq.txt | 99 + Test_Cases/MHK_RM1/MHK_RM1_DISCON.IN | 185 + .../MHK_RM1/MHK_RM1_ElastoDyn_Blade.dat | 107 + .../MHK_RM1/MHK_RM1_ElastoDyn_Tower.dat | 52 + Test_Cases/MHK_RM1/MHK_RM1_Floating.1 | 4220 +++++++ Test_Cases/MHK_RM1/MHK_RM1_Floating.3 | 10080 ++++++++++++++++ Test_Cases/MHK_RM1/MHK_RM1_Floating.fst | 71 + Test_Cases/MHK_RM1/MHK_RM1_Floating.hst | 36 + .../MHK_RM1/MHK_RM1_Floating_AeroDyn15.dat | 123 + .../MHK_RM1/MHK_RM1_Floating_ElastoDyn.dat | 134 + .../MHK_RM1/MHK_RM1_Floating_HydroDyn.dat | 207 + .../MHK_RM1/MHK_RM1_Floating_InflowWind.dat | 69 + .../MHK_RM1/MHK_RM1_Floating_MoorDyn.dat | 58 + Test_Cases/MHK_RM1/MHK_RM1_ServoDyn.dat | 111 + Test_Cases/NREL-5MW/DISCON.IN | 97 +- .../NREL_2p8_127/NREL-2p8-127_DISCON.IN | 97 +- Test_Cases/update_rosco_discons.py | 1 + Tune_Cases/IEA15MW.yaml | 1 + Tune_Cases/RM1_MHK.yaml | 68 + docs/source/api_change.rst | 43 +- docs/source/toolbox_input.rst | 116 +- 63 files changed, 21805 insertions(+), 522 deletions(-) create mode 100644 Examples/26_marine_hydro.py create mode 100644 Matlab_Toolbox/rosco_filters.m create mode 100644 Test_Cases/MHK_RM1/Airfoils/NACA6_0240.dat create mode 100644 Test_Cases/MHK_RM1/Airfoils/NACA6_0240_coords.txt create mode 100644 Test_Cases/MHK_RM1/Airfoils/NACA6_0247.dat create mode 100644 Test_Cases/MHK_RM1/Airfoils/NACA6_0247_coords.txt create mode 100644 Test_Cases/MHK_RM1/Airfoils/NACA6_0259.dat create mode 100644 Test_Cases/MHK_RM1/Airfoils/NACA6_0259_coords.txt create mode 100644 Test_Cases/MHK_RM1/Airfoils/NACA6_0276.dat create mode 100644 Test_Cases/MHK_RM1/Airfoils/NACA6_0276_coords.txt create mode 100644 Test_Cases/MHK_RM1/Airfoils/NACA6_0329.dat create mode 100644 Test_Cases/MHK_RM1/Airfoils/NACA6_0329_coords.txt create mode 100644 Test_Cases/MHK_RM1/Airfoils/NACA6_0444.dat create mode 100644 Test_Cases/MHK_RM1/Airfoils/NACA6_0444_coords.txt create mode 100644 Test_Cases/MHK_RM1/Airfoils/NACA6_0629.dat create mode 100644 Test_Cases/MHK_RM1/Airfoils/NACA6_0629_coords.txt create mode 100644 Test_Cases/MHK_RM1/Airfoils/NACA6_0864.dat create mode 100644 Test_Cases/MHK_RM1/Airfoils/NACA6_0864_coords.txt create mode 100644 Test_Cases/MHK_RM1/Airfoils/NACA6_1000.dat create mode 100644 Test_Cases/MHK_RM1/Airfoils/NACA6_1000_coords.txt create mode 100644 Test_Cases/MHK_RM1/MHK_RM1_AeroDyn15_Blade.dat create mode 100644 Test_Cases/MHK_RM1/MHK_RM1_Cp_Ct_Cq.txt create mode 100644 Test_Cases/MHK_RM1/MHK_RM1_DISCON.IN create mode 100644 Test_Cases/MHK_RM1/MHK_RM1_ElastoDyn_Blade.dat create mode 100644 Test_Cases/MHK_RM1/MHK_RM1_ElastoDyn_Tower.dat create mode 100644 Test_Cases/MHK_RM1/MHK_RM1_Floating.1 create mode 100644 Test_Cases/MHK_RM1/MHK_RM1_Floating.3 create mode 100644 Test_Cases/MHK_RM1/MHK_RM1_Floating.fst create mode 100644 Test_Cases/MHK_RM1/MHK_RM1_Floating.hst create mode 100644 Test_Cases/MHK_RM1/MHK_RM1_Floating_AeroDyn15.dat create mode 100644 Test_Cases/MHK_RM1/MHK_RM1_Floating_ElastoDyn.dat create mode 100644 Test_Cases/MHK_RM1/MHK_RM1_Floating_HydroDyn.dat create mode 100644 Test_Cases/MHK_RM1/MHK_RM1_Floating_InflowWind.dat create mode 100644 Test_Cases/MHK_RM1/MHK_RM1_Floating_MoorDyn.dat create mode 100644 Test_Cases/MHK_RM1/MHK_RM1_ServoDyn.dat create mode 100644 Tune_Cases/RM1_MHK.yaml diff --git a/Examples/26_marine_hydro.py b/Examples/26_marine_hydro.py new file mode 100644 index 00000000..0398747f --- /dev/null +++ b/Examples/26_marine_hydro.py @@ -0,0 +1,86 @@ +''' +----------- 26_marine_hydro ------------------------ +Run openfast with ROSCO and a MHK turbine +----------------------------------------------- + + +''' + +import os, platform +from ROSCO_toolbox.ofTools.case_gen.run_FAST import run_FAST_ROSCO +from ROSCO_toolbox.ofTools.case_gen import CaseLibrary as cl +from ROSCO_toolbox.ofTools.fast_io import output_processing +import numpy as np +from ROSCO_toolbox.ofTools.fast_io.FAST_reader import InputReader_OpenFAST +from ROSCO_toolbox.inputs.validation import load_rosco_yaml +import matplotlib.pyplot as plt +from ROSCO_toolbox.controller import OpenLoopControl + +''' +Run MHK turbine in OpenFAST with ROSCO torque controller + + +''' + + +#directories +this_dir = os.path.dirname(os.path.abspath(__file__)) +rosco_dir = os.path.dirname(this_dir) +example_out_dir = os.path.join(this_dir,'examples_out') +os.makedirs(example_out_dir,exist_ok=True) + +def main(): + + # Input yaml and output directory + parameter_filename = os.path.join(rosco_dir,'Tune_Cases/RM1_MHK.yaml') + run_dir = os.path.join(example_out_dir,'26_MHK/0_baseline') + os.makedirs(run_dir,exist_ok=True) + + + # simulation set up + r = run_FAST_ROSCO() + r.tuning_yaml = parameter_filename + # r.wind_case_fcn = cl.simp_step # single step wind input + r.wind_case_fcn = cl.power_curve + r.wind_case_opts = { + 'U': [2.5], + 'TMax': 100.0, + } + r.case_inputs = {} + # r.fst_vt = reader.fst_vt + # r.controller_params = controller_params + r.save_dir = run_dir + r.rosco_dir = rosco_dir + + r.run_FAST() + + print('here') + + + # op = output_processing.output_processing() + # op2 = output_processing.output_processing() + + # md_out = op.load_fast_out([os.path.join(run_dir,'IEA15MW_cable/power_curve/base/IEA15MW_cable_0.MD.Line1.out')], tmin=0) + # local_vars = op2.load_fast_out([os.path.join(run_dir,'IEA15MW_cable/power_curve/base/IEA15MW_cable_0.RO.dbg2')], tmin=0) + + # fig, axs = plt.subplots(4,1) + # axs[0].plot(local_vars[0]['Time'],local_vars[0]['CC_DesiredL'],label='CC_DesiredL') + # axs[1].plot(local_vars[0]['Time'],local_vars[0]['CC_ActuatedL'],label='CC_ActuatedL') + # axs[2].plot(local_vars[0]['Time'],local_vars[0]['CC_ActuatedDL'],label='CC_ActuatedDL') + # axs[3].plot(md_out[0]['Time'],md_out[0]['Seg20Lst'],label='Seg20Lst') + + # [a.legend() for a in axs] + # [a.grid() for a in axs] + + # if False: + # plt.show() + # else: + # plt.savefig(os.path.join(example_out_dir,'22_cable_control.png')) + + # Check that the last segment of line 1 shrinks by 10 m + # np.testing.assert_almost_equal(md_out[0]['Seg20Lst'][-1] - md_out[0]['Seg20Lst'][0], line_ends[0], 2) + + + +if __name__=="__main__": + main() \ No newline at end of file diff --git a/Examples/example_inputs/minimal_DISCON.IN b/Examples/example_inputs/minimal_DISCON.IN index 21716d03..305379fd 100644 --- a/Examples/example_inputs/minimal_DISCON.IN +++ b/Examples/example_inputs/minimal_DISCON.IN @@ -7,7 +7,8 @@ !------- 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 -3 ! VS_ControlMode - Generator torque control mode in above rated conditions {0: constant torque, 1: constant power, 2: TSR tracking PI control with constant torque, 3: TSR tracking PI control with constant power} +2 ! VS_ControlMode - Generator torque control mode in above rated conditions {0: constant torque, 1: constant power, 2: TSR tracking PI control with constant torque, 3: TSR tracking PI control with constant power} +1 ! VS_ConstPower - Do constant power torque control, where above rated torque varies, 0 for constant torque} 1 ! PC_ControlMode - Blade pitch control mode {0: No pitch, fix to fine pitch, 1: active PI blade pitch control} 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: Immersion and Invariance Estimator, 2: Extended Kalman Filter} @@ -17,6 +18,7 @@ Extra lines that ROSCO doesn't care about anymore !------- FILTERS ---------------------------------------------------------- 1.57080 ! F_LPFCornerFreq - Corner frequency (-3dB point) in the low-pass filters, [rad/s] +0 ! F_NumNotchFilts - Number of notch filters placed on sensors 0.62830 ! F_SSCornerFreq - Corner frequency (-3dB point) in the first order low pass filter for the setpoint smoother, [rad/s]. 0.20944 ! F_WECornerFreq - Corner frequency (-3dB point) in the first order low pass filter for the wind speed estimate [rad/s]. 0.17952 ! F_YawErr - Low pass filter corner frequency for yaw controller [rad/s]. diff --git a/Examples/example_inputs/minimal_DISCON_err.IN b/Examples/example_inputs/minimal_DISCON_err.IN index 327af71c..269736e0 100644 --- a/Examples/example_inputs/minimal_DISCON_err.IN +++ b/Examples/example_inputs/minimal_DISCON_err.IN @@ -7,9 +7,8 @@ !------- 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 and/or tower fore-aft motion (for floating) {0: disable, 1: generator speed, 2: tower-top fore-aft motion, 3: generator speed and tower-top fore-aft motion} -1 ! IPC_ControlMode - Turn Individual Pitch Control (IPC) for fatigue load reductions (pitch contribution) {0: off, 1: 1P reductions, 2: 1P+2P reductions} -3 ! VS_ControlMode - Generator torque control mode in above rated conditions {0: constant torque, 1: constant power, 2: TSR tracking PI control with constant torque, 3: TSR tracking PI control with constant power} +2 ! VS_ControlMode - Generator torque control mode in above rated conditions {0: constant torque, 1: constant power, 2: TSR tracking PI control with constant torque, 3: TSR tracking PI control with constant power} +1 ! VS_ConstPower - Do constant power torque control, where above rated torque varies, 0 for constant torque} 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} @@ -32,9 +31,7 @@ Extra lines that ROSCO doesn't care about anymore !------- FILTERS ---------------------------------------------------------- 1.57080 ! F_LPFCornerFreq - Corner frequency (-3dB point) in the low-pass filters, [rad/s] -0.00000 ! F_LPFDamping - Damping coefficient {used only when F_FilterType = 2} [-] -0.00000 ! F_NotchCornerFreq - Natural frequency of the notch filter, [rad/s] -0.000000 0.250000 ! F_NotchBetaNumDen - Two notch damping values (numerator and denominator, resp) - determines the width and depth of the notch, [-] +0 ! F_NumNotchFilts - Number of notch filters placed on sensors 0.62830 ! F_SSCornerFreq - Corner frequency (-3dB point) in the first order low pass filter for the setpoint smoother, [rad/s]. 0.20944 ! F_WECornerFreq - Corner frequency (-3dB point) in the first order low pass filter for the wind speed estimate [rad/s]. 0.17952 ! F_YawErr - Low pass filter corner frequency for yaw controller [rad/s]. diff --git a/Examples/test_examples.py b/Examples/test_examples.py index 244c288a..7e504f8e 100644 --- a/Examples/test_examples.py +++ b/Examples/test_examples.py @@ -28,6 +28,7 @@ '23_structural_control', '24_floating_feedback', '25_rotor_position_control', + '26_marine_hydro', 'update_rosco_discons', ] diff --git a/Matlab_Toolbox/rosco_filters.m b/Matlab_Toolbox/rosco_filters.m new file mode 100644 index 00000000..3804d5f0 --- /dev/null +++ b/Matlab_Toolbox/rosco_filters.m @@ -0,0 +1,65 @@ +%% ROSCO Filters + +clear; + +dbg = ROSCOout2Matlab('/Users/dzalkind/Tools/ROSCO1/Examples/examples_out/26_MHK/5_low_ws_debug/RM1_MHK/power_curve/base/RM1_MHK_0.RO.dbg2'); + + +%% + + + +%% + +num2 = 0.001; +den2 = 0.1; + +num1 = 0.001; +den1 = 0.1; + +NF1 = notch(1,num1,den1,0.01); +NF2 = notch(2.42,num2,den2,0.01); + +figure(1); +bode(NF1) +bode(NF2) +bode(NF1*NF2) + +% BS = fdesign.bandstop( + + + + +y = lsim(NF1*NF2,dbg.GenSpeed,dbg.Time); +% % +% % +figure(2); +plot(dbg.Time,dbg.GenSpeed) +hold on; +plot(dbg.Time,dbg.GenSpeedF) +plot(dbg.Time,y) +% % +% % +hold off + +%% Notch Filter + +function notch_filt = notch(omega,BetaNum,BetaDen,DT) + +% DT = 0.01; +% +% omega = 1; +% BetaNum = 0.01; +% BetaDen = 0.25; + + K = 2.0/DT; + b2 = (K^2.0 + 2.0*omega*BetaNum*K + omega^2.0)/(K^2.0 + 2.0*omega*BetaDen*K + omega^2.0); + b1 = (2.0*omega^2.0 - 2.0*K^2.0) / (K^2.0 + 2.0*omega*BetaDen*K + omega^2.0); + b0 = (K^2.0 - 2.0*omega*BetaNum*K + omega^2.0) / (K^2.0 + 2.0*omega*BetaDen*K + omega^2.0); + a1 = (2.0*omega^2.0 - 2.0*K^2.0) / (K^2.0 + 2.0*omega*BetaDen*K + omega^2.0); + a0 = (K^2.0 - 2.0*omega*BetaDen*K + omega^2.0)/ (K^2.0 + 2.0*omega*BetaDen*K + omega^2.0); + + notch_filt = tf([b2,b1,b0],[1,a1,a0],DT); + +end + diff --git a/ROSCO/rosco_registry/rosco_types.yaml b/ROSCO/rosco_registry/rosco_types.yaml index 91d1b90b..43a19afc 100644 --- a/ROSCO/rosco_registry/rosco_types.yaml +++ b/ROSCO/rosco_registry/rosco_types.yaml @@ -93,21 +93,40 @@ ControlParameters: F_LPFType: <<: *integer description: 'Low pass filter on the rotor and generator speed {1 - first-order low-pass filter, 2 - second-order low-pass filter}, [rad/s]' - F_NotchType: - <<: *integer - description: Notch on the measured generator speed {0 - disable, 1 - enable} F_LPFCornerFreq: <<: *real description: Corner frequency (-3dB point) in the first-order low-pass filter, [rad/s] F_LPFDamping: <<: *real description: Damping coefficient [used only when F_FilterType = 2] - F_NotchCornerFreq: + F_NumNotchFilts: + <<: *integer + description: Number of notch filters + F_GenSpdNotch_N: + <<: *integer + description: Number of gen speed notch filters + F_GenSpdNotch_Ind: + <<: *integer + description: Indices of gen speed notch filters + allocatable: True + F_TwrTopNotch_N: + <<: *integer + description: Number of tower top notch filters + F_TwrTopNotch_Ind: + <<: *integer + description: Indices of tower top notch filters + allocatable: True + F_NotchFreqs: <<: *real - description: Natural frequency of the notch filter, [rad/s] - F_NotchBetaNumDen: + description: Natural frequencies of notch filters, [rad/s] + allocatable: True + F_NotchBetaNum: + <<: *real + description: Notch Filter Numerator damping (determines width) + allocatable: True + F_NotchBetaDen: <<: *real - description: These two notch damping values (numerator and denominator) determines the width and depth of the notch + description: Notch Filter Numerator damping (determines depth?) allocatable: True F_SSCornerFreq: <<: *real @@ -226,7 +245,10 @@ ControlParameters: # Generator Torque Controller VS_ControlMode: <<: *integer - description: Generator torque control mode in above rated conditions {0 - constant torque, 1 - constant power, 2 - TSR Tracking, 3 - TSR Tracking w/ const power} + description: Generator torque control mode in above rated conditions {0 - no torque control, 1 - komega^2 with PI trans, 2 - WSE TSR Tracking, 3 - Power TSR Tracking} + VS_ConstPower: + <<: *integer + description: Constant power torque control VS_GenEff: <<: *real description: Generator efficiency mechanical power -> electrical power [-] @@ -271,6 +293,9 @@ ControlParameters: VS_TSRopt: <<: *real description: Power-maximizing region 2 tip-speed ratio [rad] + VS_PwrFiltF: + <<: *real + description: Cut-off frequency of filter on generator power for power-based tsr tracking control # Setpoint Smoother SS_Mode: @@ -876,6 +901,9 @@ LocalVariables: VS_GenPwr: <<: *real description: Generator power [W] + VS_GenPwrF: + <<: *real + description: Generator power [W] GenSpeed: <<: *real description: Generator speed (HSS) [rad/s] @@ -944,6 +972,9 @@ LocalVariables: <<: *real description: Tower fore-aft vibration damping pitch contribution [rad] size: 3 + VS_RefSpd: + <<: *real + description: Torque control generator speed set point [rad/s] RotSpeedF: <<: *real description: Filtered LSS (generator) speed [rad/s]. diff --git a/ROSCO/src/ControllerBlocks.f90 b/ROSCO/src/ControllerBlocks.f90 index a9ad8af0..1742d51a 100644 --- a/ROSCO/src/ControllerBlocks.f90 +++ b/ROSCO/src/ControllerBlocks.f90 @@ -46,36 +46,40 @@ SUBROUTINE ComputeVariablesSetpoints(CntrPar, LocalVar, objInst) LocalVar%PC_SpdErr = PC_RefSpd - LocalVar%GenSpeedF ! Speed error LocalVar%PC_PwrErr = CntrPar%VS_RtPwr - LocalVar%VS_GenPwr ! Power error - + ! ----- Torque controller reference errors ----- ! Define VS reference generator speed [rad/s] - IF ((CntrPar%VS_ControlMode == 2) .OR. (CntrPar%VS_ControlMode == 3)) THEN - VS_RefSpd = (CntrPar%VS_TSRopt * LocalVar%We_Vw_F / CntrPar%WE_BladeRadius) * CntrPar%WE_GearboxRatio - VS_RefSpd = saturate(VS_RefSpd,CntrPar%VS_MinOMSpd, CntrPar%VS_RefSpd) + IF (CntrPar%VS_ControlMode == 2) THEN + LocalVar%VS_RefSpd = (CntrPar%VS_TSRopt * LocalVar%We_Vw_F / CntrPar%WE_BladeRadius) * CntrPar%WE_GearboxRatio + ELSEIF (CntrPar%VS_ControlMode == 3) THEN + LocalVar%VS_GenPwrF = LPFilter(LocalVar%VS_GenPwr, LocalVar%DT,CntrPar%VS_PwrFiltF, LocalVar%FP, LocalVar%iStatus, LocalVar%restart, objInst%instLPF) + LocalVar%VS_RefSpd = (LocalVar%VS_GenPwrF/CntrPar%VS_Rgn2K)**(1./3.) ! Genspeed reference that doesnt depend on wind speed estimate (https://doi.org/10.2172/1259805) ELSE - VS_RefSpd = CntrPar%VS_RefSpd + LocalVar%VS_RefSpd = CntrPar%VS_RefSpd ENDIF + + LocalVar%VS_RefSpd = saturate(LocalVar%VS_RefSpd,CntrPar%VS_MinOMSpd, CntrPar%VS_RefSpd) ! Implement setpoint smoothing IF (LocalVar%SS_DelOmegaF > 0) THEN - VS_RefSpd = VS_RefSpd - LocalVar%SS_DelOmegaF + LocalVar%VS_RefSpd = LocalVar%VS_RefSpd - LocalVar%SS_DelOmegaF ENDIF ! Force zero torque in shutdown mode IF (LocalVar%SD) THEN - VS_RefSpd = CntrPar%VS_MinOMSpd + LocalVar%VS_RefSpd = CntrPar%VS_MinOMSpd ENDIF ! Force minimum rotor speed - VS_RefSpd = max(VS_RefSpd, CntrPar%VS_MinOmSpd) + LocalVar%VS_RefSpd = max(LocalVar%VS_RefSpd, CntrPar%VS_MinOmSpd) ! TSR-tracking reference error IF ((CntrPar%VS_ControlMode == 2) .OR. (CntrPar%VS_ControlMode == 3)) THEN - LocalVar%VS_SpdErr = VS_RefSpd - LocalVar%GenSpeedF + LocalVar%VS_SpdErr = LocalVar%VS_RefSpd - LocalVar%GenSpeedF ENDIF ! Define transition region setpoint errors - LocalVar%VS_SpdErrAr = VS_RefSpd - LocalVar%GenSpeedF ! Current speed error - Region 2.5 PI-control (Above Rated) + LocalVar%VS_SpdErrAr = LocalVar%VS_RefSpd - LocalVar%GenSpeedF ! Current speed error - Region 2.5 PI-control (Above Rated) LocalVar%VS_SpdErrBr = CntrPar%VS_MinOMSpd - LocalVar%GenSpeedF ! Current speed error - Region 1.5 PI-control (Below Rated) ! Region 3 minimum pitch angle for state machine @@ -107,7 +111,7 @@ SUBROUTINE StateMachine(CntrPar, LocalVar) IF (LocalVar%iStatus == 0) THEN ! .TRUE. if we're on the first call to the DLL IF (LocalVar%PitCom(1) >= LocalVar%VS_Rgn3Pitch) THEN ! We are in region 3 - IF (CntrPar%VS_ControlMode == 1) THEN ! Constant power tracking + IF (CntrPar%VS_ConstPower == 1) THEN ! Constant power tracking LocalVar%VS_State = 5 LocalVar%PC_State = 1 ELSE ! Constant torque tracking @@ -131,7 +135,7 @@ SUBROUTINE StateMachine(CntrPar, LocalVar) ! --- Torque control state machine --- IF (LocalVar%PC_PitComT >= LocalVar%VS_Rgn3Pitch) THEN - IF (CntrPar%VS_ControlMode == 1) THEN ! Region 3 + IF (CntrPar%VS_ConstPower == 1) THEN ! Region 3 LocalVar%VS_State = 5 ! Constant power tracking ELSE LocalVar%VS_State = 4 ! Constant torque tracking diff --git a/ROSCO/src/Controllers.f90 b/ROSCO/src/Controllers.f90 index 15bd2223..deca2d45 100644 --- a/ROSCO/src/Controllers.f90 +++ b/ROSCO/src/Controllers.f90 @@ -213,7 +213,7 @@ SUBROUTINE VariableSpeedControl(avrSWAP, CntrPar, LocalVar, objInst, ErrVar) ! Optimal Tip-Speed-Ratio tracking controller IF ((CntrPar%VS_ControlMode == 2) .OR. (CntrPar%VS_ControlMode == 3)) THEN ! Constant Power, update VS_MaxTq - IF (CntrPar%VS_ControlMode == 3) THEN + IF (CntrPar%VS_ConstPower == 1) THEN LocalVar%VS_MaxTq = min((CntrPar%VS_RtPwr/(CntrPar%VS_GenEff/100.0))/LocalVar%GenSpeedF, CntrPar%VS_MaxTq) END IF @@ -222,7 +222,7 @@ SUBROUTINE VariableSpeedControl(avrSWAP, CntrPar, LocalVar, objInst, ErrVar) LocalVar%GenTq = saturate(LocalVar%GenTq, CntrPar%VS_MinTq, LocalVar%VS_MaxTq) ! K*Omega^2 control law with PI torque control in transition regions - ELSE + ELSEIF (CntrPar%VS_ControlMode == 1) THEN ! 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_MaxOMTq, LocalVar%piP, LocalVar%restart, objInst%instPI) LocalVar%GenBrTq = PIController(LocalVar%VS_SpdErrBr, CntrPar%VS_KP(1), CntrPar%VS_KI(1), CntrPar%VS_MinTq, CntrPar%VS_MinOMTq, LocalVar%DT, CntrPar%VS_MinOMTq, LocalVar%piP, LocalVar%restart, objInst%instPI) @@ -242,6 +242,8 @@ SUBROUTINE VariableSpeedControl(avrSWAP, CntrPar, LocalVar, objInst, ErrVar) ! Saturate LocalVar%GenTq = saturate(LocalVar%GenTq, CntrPar%VS_MinTq, CntrPar%VS_MaxTq) + ELSE ! VS_ControlMode of 0 + LocalVar%GenTq = 0 ENDIF diff --git a/ROSCO/src/Filters.f90 b/ROSCO/src/Filters.f90 index 2a5ee24b..6e174e25 100644 --- a/ROSCO/src/Filters.f90 +++ b/ROSCO/src/Filters.f90 @@ -322,7 +322,7 @@ REAL(DbKi) FUNCTION NotchFilter(InputSignal, DT, omega, betaNum, betaDen, FP, iS END FUNCTION NotchFilter !------------------------------------------------------------------------------------------------------------------------------- SUBROUTINE PreFilterMeasuredSignals(CntrPar, LocalVar, DebugVar, objInst, ErrVar) - ! Prefilter measured wind turbine signals to separate the filtering from the actual control actions + ! Prefilter shared measured wind turbine signals USE ROSCO_Types, ONLY : ControlParameters, LocalVariables, DebugVariables, ObjectInstances, ErrorVariables @@ -332,6 +332,7 @@ SUBROUTINE PreFilterMeasuredSignals(CntrPar, LocalVar, DebugVar, objInst, ErrVar TYPE(ObjectInstances), INTENT(INOUT) :: objInst TYPE(ErrorVariables), INTENT(INOUT) :: ErrVar INTEGER(IntKi) :: K ! Integer used to loop through turbine blades + INTEGER(IntKi) :: n ! Integer used to loop through notch filters ! If there's an error, don't even try to run IF (ErrVar%aviFAIL < 0) THEN @@ -346,28 +347,45 @@ SUBROUTINE PreFilterMeasuredSignals(CntrPar, LocalVar, DebugVar, objInst, ErrVar LocalVar%GenSpeedF = SecLPFilter(LocalVar%GenSpeed, LocalVar%DT, CntrPar%F_LPFCornerFreq, CntrPar%F_LPFDamping, LocalVar%FP, LocalVar%iStatus, LocalVar%restart, objInst%instSecLPF) ! Second-order low-pass filter on generator speed LocalVar%RotSpeedF = SecLPFilter(LocalVar%RotSpeed, LocalVar%DT, CntrPar%F_LPFCornerFreq, CntrPar%F_LPFDamping, LocalVar%FP, LocalVar%iStatus, LocalVar%restart, objInst%instSecLPF) ! Second-order low-pass filter on generator speed ENDIF - ! Apply Notch Fitler - IF (CntrPar%F_NotchType == 1 .OR. CntrPar%F_NotchType == 3) THEN - LocalVar%GenSpeedF = NotchFilter(LocalVar%GenSpeedF, LocalVar%DT, CntrPar%F_NotchCornerFreq, CntrPar%F_NotchBetaNumDen(1), CntrPar%F_NotchBetaNumDen(2), LocalVar%FP, LocalVar%iStatus, LocalVar%restart, objInst%instNotch) - ENDIF + + ! Apply Notch Fitler to Gen Speed + DO n = 1,CntrPar%F_GenSpdNotch_N + LocalVar%GenSpeedF = NotchFilter(LocalVar%GenSpeedF, LocalVar%DT, & + CntrPar%F_NotchFreqs(CntrPar%F_GenSpdNotch_Ind(n)), & + CntrPar%F_NotchBetaNum(CntrPar%F_GenSpdNotch_Ind(n)), & + CntrPar%F_NotchBetaDen(CntrPar%F_GenSpdNotch_Ind(n)), & + LocalVar%FP, LocalVar%iStatus, LocalVar%restart, objInst%instNotch) + END DO ! Filtering the tower fore-aft acceleration signal - IF (CntrPar%Fl_Mode > 0) THEN - ! Force to start at 0 - IF (LocalVar%iStatus == 0 .AND. LocalVar%Time == 0) THEN - LocalVar%NacIMU_FA_Acc = 0 - LocalVar%FA_Acc = 0 - ENDIF - LocalVar%NacIMU_FA_AccF = SecLPFilter(LocalVar%NacIMU_FA_Acc, LocalVar%DT, CntrPar%F_FlCornerFreq(1), CntrPar%F_FlCornerFreq(2), LocalVar%FP, LocalVar%iStatus, LocalVar%restart, objInst%instSecLPF) ! Fixed Damping - LocalVar%FA_AccF = SecLPFilter(LocalVar%FA_Acc, LocalVar%DT, CntrPar%F_FlCornerFreq(1), CntrPar%F_FlCornerFreq(2), LocalVar%FP, LocalVar%iStatus, LocalVar%restart, objInst%instSecLPF) ! Fixed Damping - LocalVar%NacIMU_FA_AccF = HPFilter(LocalVar%NacIMU_FA_AccF, LocalVar%DT, CntrPar%F_FlHighPassFreq, LocalVar%FP, LocalVar%iStatus, LocalVar%restart, objInst%instHPF) - LocalVar%FA_AccF = HPFilter(LocalVar%FA_AccF, LocalVar%DT, CntrPar%F_FlHighPassFreq, LocalVar%FP, LocalVar%iStatus, LocalVar%restart, objInst%instHPF) + ! Force to start at 0 + IF (LocalVar%iStatus == 0 .AND. LocalVar%Time == 0) THEN + LocalVar%NacIMU_FA_Acc = 0 + LocalVar%FA_Acc = 0 + ENDIF + + ! Low pass + LocalVar%NacIMU_FA_AccF = SecLPFilter(LocalVar%NacIMU_FA_Acc, LocalVar%DT, CntrPar%F_FlCornerFreq(1), CntrPar%F_FlCornerFreq(2), LocalVar%FP, LocalVar%iStatus, LocalVar%restart, objInst%instSecLPF) ! Fixed Damping + LocalVar%FA_AccF = SecLPFilter(LocalVar%FA_Acc, LocalVar%DT, CntrPar%F_FlCornerFreq(1), CntrPar%F_FlCornerFreq(2), LocalVar%FP, LocalVar%iStatus, LocalVar%restart, objInst%instSecLPF) ! Fixed Damping + + ! High pass + LocalVar%NacIMU_FA_AccF = HPFilter(LocalVar%NacIMU_FA_AccF, LocalVar%DT, CntrPar%F_FlHighPassFreq, LocalVar%FP, LocalVar%iStatus, LocalVar%restart, objInst%instHPF) + LocalVar%FA_AccF = HPFilter(LocalVar%FA_AccF, LocalVar%DT, CntrPar%F_FlHighPassFreq, LocalVar%FP, LocalVar%iStatus, LocalVar%restart, objInst%instHPF) + + ! Notch filters + DO n = 1,CntrPar%F_TwrTopNotch_N + LocalVar%NACIMU_FA_AccF = NotchFilter(LocalVar%NacIMU_FA_AccF, LocalVar%DT, & + CntrPar%F_NotchFreqs(CntrPar%F_TwrTopNotch_Ind(n)), & + CntrPar%F_NotchBetaNum(CntrPar%F_TwrTopNotch_Ind(n)), & + CntrPar%F_NotchBetaDen(CntrPar%F_TwrTopNotch_Ind(n)), & + LocalVar%FP, LocalVar%iStatus, LocalVar%restart, objInst%instNotch) - IF (CntrPar%F_NotchType >= 2) THEN - LocalVar%NACIMU_FA_AccF = NotchFilter(LocalVar%NacIMU_FA_AccF, LocalVar%DT, CntrPar%F_NotchCornerFreq, CntrPar%F_NotchBetaNumDen(1), CntrPar%F_NotchBetaNumDen(2), LocalVar%FP, LocalVar%iStatus, LocalVar%restart, objInst%instNotch) ! Fixed Damping - LocalVar%FA_AccF = NotchFilter(LocalVar%FA_AccF, LocalVar%DT, CntrPar%F_NotchCornerFreq, CntrPar%F_NotchBetaNumDen(1), CntrPar%F_NotchBetaNumDen(2), LocalVar%FP, LocalVar%iStatus, LocalVar%restart, objInst%instNotch) ! Fixed Damping - ENDIF - ENDIF + LocalVar%FA_AccF = NotchFilter(LocalVar%FA_AccF, LocalVar%DT, & + CntrPar%F_NotchFreqs(CntrPar%F_TwrTopNotch_Ind(n)), & + CntrPar%F_NotchBetaNum(CntrPar%F_TwrTopNotch_Ind(n)), & + CntrPar%F_NotchBetaDen(CntrPar%F_TwrTopNotch_Ind(n)), & + LocalVar%FP, LocalVar%iStatus, LocalVar%restart, objInst%instNotch) + END DO ! FA acc for ForeAft damping, condition matches whether it's used in Controllers.f90 IF ((CntrPar%TD_Mode > 0) .OR. (CntrPar%Y_ControlMode == 2)) THEN @@ -375,7 +393,7 @@ SUBROUTINE PreFilterMeasuredSignals(CntrPar, LocalVar, DebugVar, objInst, ErrVar ENDIF ! Filter Wind Speed Estimator Signal - LocalVar%We_Vw_F = LPFilter(LocalVar%WE_Vw, LocalVar%DT,CntrPar%F_WECornerFreq, LocalVar%FP, LocalVar%iStatus, LocalVar%restart, objInst%instLPF) ! 30 second time constant + LocalVar%We_Vw_F = LPFilter(LocalVar%WE_Vw, LocalVar%DT,CntrPar%F_WECornerFreq, LocalVar%FP, LocalVar%iStatus, LocalVar%restart, objInst%instLPF) ! Blade root bending moment for IPC DO K = 1,LocalVar%NumBl @@ -385,8 +403,14 @@ SUBROUTINE PreFilterMeasuredSignals(CntrPar, LocalVar, DebugVar, objInst, ErrVar ELSEIF ( CntrPar%Flp_Mode == 2 ) THEN ! Filter Blade root bending moments LocalVar%RootMOOPF(K) = SecLPFilter(LocalVar%rootMOOP(K),LocalVar%DT, CntrPar%F_FlpCornerFreq(1), CntrPar%F_FlpCornerFreq(2), LocalVar%FP, LocalVar%iStatus, LocalVar%restart,objInst%instSecLPF) - LocalVar%RootMOOPF(K) = NotchFilter(LocalVar%RootMOOPF(K), LocalVar%DT, CntrPar%F_NotchCornerFreq, CntrPar%F_NotchBetaNumDen(1), CntrPar%F_NotchBetaNumDen(2), LocalVar%FP, LocalVar%iStatus, LocalVar%restart, objInst%instNotch) LocalVar%RootMOOPF(K) = HPFilter(LocalVar%rootMOOPF(K),LocalVar%DT, 0.1_DbKi, LocalVar%FP, LocalVar%iStatus, LocalVar%restart,objInst%instHPF) + + ! Use same as generator speed signal because that's how it was before + LocalVar%RootMOOPF(K) = NotchFilter(LocalVar%RootMOOPF(K), LocalVar%DT, & + CntrPar%F_NotchFreqs(CntrPar%F_GenSpdNotch_Ind(n)), & + CntrPar%F_NotchBetaNum(CntrPar%F_GenSpdNotch_Ind(n)), & + CntrPar%F_NotchBetaDen(CntrPar%F_GenSpdNotch_Ind(n)), & + LocalVar%FP, LocalVar%iStatus, LocalVar%restart, objInst%instNotch) ELSE LocalVar%RootMOOPF(K) = LocalVar%rootMOOP(K) ENDIF diff --git a/ROSCO/src/ROSCO_IO.f90 b/ROSCO/src/ROSCO_IO.f90 index b598f08f..a711e9f2 100644 --- a/ROSCO/src/ROSCO_IO.f90 +++ b/ROSCO/src/ROSCO_IO.f90 @@ -42,6 +42,7 @@ SUBROUTINE WriteRestartFile(LocalVar, CntrPar, ErrVar, objInst, RootName, size_a WRITE( Un, IOSTAT=ErrStat) LocalVar%n_DT WRITE( Un, IOSTAT=ErrStat) LocalVar%Time_Last WRITE( Un, IOSTAT=ErrStat) LocalVar%VS_GenPwr + WRITE( Un, IOSTAT=ErrStat) LocalVar%VS_GenPwrF WRITE( Un, IOSTAT=ErrStat) LocalVar%GenSpeed WRITE( Un, IOSTAT=ErrStat) LocalVar%RotSpeed WRITE( Un, IOSTAT=ErrStat) LocalVar%NacHeading @@ -72,6 +73,7 @@ SUBROUTINE WriteRestartFile(LocalVar, CntrPar, ErrVar, objInst, RootName, size_a WRITE( Un, IOSTAT=ErrStat) LocalVar%FA_PitCom(1) WRITE( Un, IOSTAT=ErrStat) LocalVar%FA_PitCom(2) WRITE( Un, IOSTAT=ErrStat) LocalVar%FA_PitCom(3) + WRITE( Un, IOSTAT=ErrStat) LocalVar%VS_RefSpd WRITE( Un, IOSTAT=ErrStat) LocalVar%RotSpeedF WRITE( Un, IOSTAT=ErrStat) LocalVar%GenSpeedF WRITE( Un, IOSTAT=ErrStat) LocalVar%GenTq @@ -322,6 +324,7 @@ SUBROUTINE ReadRestartFile(avrSWAP, LocalVar, CntrPar, objInst, PerfData, RootNa READ( Un, IOSTAT=ErrStat) LocalVar%n_DT READ( Un, IOSTAT=ErrStat) LocalVar%Time_Last READ( Un, IOSTAT=ErrStat) LocalVar%VS_GenPwr + READ( Un, IOSTAT=ErrStat) LocalVar%VS_GenPwrF READ( Un, IOSTAT=ErrStat) LocalVar%GenSpeed READ( Un, IOSTAT=ErrStat) LocalVar%RotSpeed READ( Un, IOSTAT=ErrStat) LocalVar%NacHeading @@ -352,6 +355,7 @@ SUBROUTINE ReadRestartFile(avrSWAP, LocalVar, CntrPar, objInst, PerfData, RootNa READ( Un, IOSTAT=ErrStat) LocalVar%FA_PitCom(1) READ( Un, IOSTAT=ErrStat) LocalVar%FA_PitCom(2) READ( Un, IOSTAT=ErrStat) LocalVar%FA_PitCom(3) + READ( Un, IOSTAT=ErrStat) LocalVar%VS_RefSpd READ( Un, IOSTAT=ErrStat) LocalVar%RotSpeedF READ( Un, IOSTAT=ErrStat) LocalVar%GenSpeedF READ( Un, IOSTAT=ErrStat) LocalVar%GenTq @@ -643,7 +647,7 @@ SUBROUTINE Debug(LocalVar, CntrPar, DebugVar, ErrVar, avrSWAP, RootName, size_av '[rad/s]', '[rad/s]', '[m/s]', '[rad]', '[rad]', & '[N/A]', '[N/A]', '[N/A]', '[N/A]', '[rad/s]', & '[deg]', '[deg]', '[deg]', '[N/A]'] - nLocalVars = 108 + nLocalVars = 110 Allocate(LocalVarOutData(nLocalVars)) Allocate(LocalVarOutStrings(nLocalVars)) LocalVarOutData(1) = LocalVar%iStatus @@ -652,130 +656,133 @@ SUBROUTINE Debug(LocalVar, CntrPar, DebugVar, ErrVar, avrSWAP, RootName, size_av LocalVarOutData(4) = LocalVar%n_DT LocalVarOutData(5) = LocalVar%Time_Last LocalVarOutData(6) = LocalVar%VS_GenPwr - LocalVarOutData(7) = LocalVar%GenSpeed - LocalVarOutData(8) = LocalVar%RotSpeed - LocalVarOutData(9) = LocalVar%NacHeading - LocalVarOutData(10) = LocalVar%NacVane - LocalVarOutData(11) = LocalVar%HorWindV - LocalVarOutData(12) = LocalVar%rootMOOP(1) - LocalVarOutData(13) = LocalVar%rootMOOPF(1) - LocalVarOutData(14) = LocalVar%BlPitch(1) - LocalVarOutData(15) = LocalVar%BlPitchCMeas - LocalVarOutData(16) = LocalVar%Azimuth - LocalVarOutData(17) = LocalVar%OL_Azimuth - LocalVarOutData(18) = LocalVar%AzUnwrapped - LocalVarOutData(19) = LocalVar%AzError - LocalVarOutData(20) = LocalVar%GenTqAz - LocalVarOutData(21) = LocalVar%AzBuffer(1) - LocalVarOutData(22) = LocalVar%NumBl - LocalVarOutData(23) = LocalVar%FA_Acc - LocalVarOutData(24) = LocalVar%NacIMU_FA_Acc - LocalVarOutData(25) = LocalVar%FA_AccHPF - LocalVarOutData(26) = LocalVar%FA_AccHPFI - LocalVarOutData(27) = LocalVar%FA_PitCom(1) - LocalVarOutData(28) = LocalVar%RotSpeedF - LocalVarOutData(29) = LocalVar%GenSpeedF - LocalVarOutData(30) = LocalVar%GenTq - LocalVarOutData(31) = LocalVar%GenTqMeas - LocalVarOutData(32) = LocalVar%GenArTq - LocalVarOutData(33) = LocalVar%GenBrTq - LocalVarOutData(34) = LocalVar%IPC_PitComF(1) - LocalVarOutData(35) = LocalVar%PC_KP - LocalVarOutData(36) = LocalVar%PC_KI - LocalVarOutData(37) = LocalVar%PC_KD - LocalVarOutData(38) = LocalVar%PC_TF - LocalVarOutData(39) = LocalVar%PC_MaxPit - LocalVarOutData(40) = LocalVar%PC_MinPit - LocalVarOutData(41) = LocalVar%PC_PitComT - LocalVarOutData(42) = LocalVar%PC_PitComT_Last - LocalVarOutData(43) = LocalVar%PC_PitComTF - LocalVarOutData(44) = LocalVar%PC_PitComT_IPC(1) - LocalVarOutData(45) = LocalVar%PC_PwrErr - LocalVarOutData(46) = LocalVar%PC_SpdErr - LocalVarOutData(47) = LocalVar%IPC_AxisTilt_1P - LocalVarOutData(48) = LocalVar%IPC_AxisYaw_1P - LocalVarOutData(49) = LocalVar%IPC_AxisTilt_2P - LocalVarOutData(50) = LocalVar%IPC_AxisYaw_2P - LocalVarOutData(51) = LocalVar%axisTilt_1P - LocalVarOutData(52) = LocalVar%axisYaw_1P - LocalVarOutData(53) = LocalVar%axisYawF_1P - LocalVarOutData(54) = LocalVar%axisTilt_2P - LocalVarOutData(55) = LocalVar%axisYaw_2P - LocalVarOutData(56) = LocalVar%axisYawF_2P - LocalVarOutData(57) = LocalVar%IPC_KI(1) - LocalVarOutData(58) = LocalVar%IPC_KP(1) - LocalVarOutData(59) = LocalVar%IPC_IntSat - LocalVarOutData(60) = LocalVar%PC_State - LocalVarOutData(61) = LocalVar%PitCom(1) - LocalVarOutData(62) = LocalVar%PitComAct(1) - LocalVarOutData(63) = LocalVar%SS_DelOmegaF - LocalVarOutData(64) = LocalVar%TestType - LocalVarOutData(65) = LocalVar%Kp_Float - LocalVarOutData(66) = LocalVar%VS_MaxTq - LocalVarOutData(67) = LocalVar%VS_LastGenTrq - LocalVarOutData(68) = LocalVar%VS_LastGenPwr - LocalVarOutData(69) = LocalVar%VS_MechGenPwr - LocalVarOutData(70) = LocalVar%VS_SpdErrAr - LocalVarOutData(71) = LocalVar%VS_SpdErrBr - LocalVarOutData(72) = LocalVar%VS_SpdErr - LocalVarOutData(73) = LocalVar%VS_State - LocalVarOutData(74) = LocalVar%VS_Rgn3Pitch - LocalVarOutData(75) = LocalVar%WE_Vw - LocalVarOutData(76) = LocalVar%WE_Vw_F - LocalVarOutData(77) = LocalVar%WE_VwI - LocalVarOutData(78) = LocalVar%WE_VwIdot - LocalVarOutData(79) = LocalVar%VS_LastGenTrqF - LocalVarOutData(80) = LocalVar%Fl_PitCom - LocalVarOutData(81) = LocalVar%NACIMU_FA_AccF - LocalVarOutData(82) = LocalVar%FA_AccF - LocalVarOutData(83) = LocalVar%PtfmTDX - LocalVarOutData(84) = LocalVar%PtfmTDY - LocalVarOutData(85) = LocalVar%PtfmTDZ - LocalVarOutData(86) = LocalVar%PtfmRDX - LocalVarOutData(87) = LocalVar%PtfmRDY - LocalVarOutData(88) = LocalVar%PtfmRDZ - LocalVarOutData(89) = LocalVar%PtfmTVX - LocalVarOutData(90) = LocalVar%PtfmTVY - LocalVarOutData(91) = LocalVar%PtfmTVZ - LocalVarOutData(92) = LocalVar%PtfmRVX - LocalVarOutData(93) = LocalVar%PtfmRVY - LocalVarOutData(94) = LocalVar%PtfmRVZ - LocalVarOutData(95) = LocalVar%PtfmTAX - LocalVarOutData(96) = LocalVar%PtfmTAY - LocalVarOutData(97) = LocalVar%PtfmTAZ - LocalVarOutData(98) = LocalVar%PtfmRAX - LocalVarOutData(99) = LocalVar%PtfmRAY - LocalVarOutData(100) = LocalVar%PtfmRAZ - LocalVarOutData(101) = LocalVar%CC_DesiredL(1) - LocalVarOutData(102) = LocalVar%CC_ActuatedL(1) - LocalVarOutData(103) = LocalVar%CC_ActuatedDL(1) - LocalVarOutData(104) = LocalVar%StC_Input(1) - LocalVarOutData(105) = LocalVar%Flp_Angle(1) - LocalVarOutData(106) = LocalVar%RootMyb_Last(1) - LocalVarOutData(107) = LocalVar%ACC_INFILE_SIZE - LocalVarOutData(108) = LocalVar%AWC_complexangle(1) + LocalVarOutData(7) = LocalVar%VS_GenPwrF + LocalVarOutData(8) = LocalVar%GenSpeed + LocalVarOutData(9) = LocalVar%RotSpeed + LocalVarOutData(10) = LocalVar%NacHeading + LocalVarOutData(11) = LocalVar%NacVane + LocalVarOutData(12) = LocalVar%HorWindV + LocalVarOutData(13) = LocalVar%rootMOOP(1) + LocalVarOutData(14) = LocalVar%rootMOOPF(1) + LocalVarOutData(15) = LocalVar%BlPitch(1) + LocalVarOutData(16) = LocalVar%BlPitchCMeas + LocalVarOutData(17) = LocalVar%Azimuth + LocalVarOutData(18) = LocalVar%OL_Azimuth + LocalVarOutData(19) = LocalVar%AzUnwrapped + LocalVarOutData(20) = LocalVar%AzError + LocalVarOutData(21) = LocalVar%GenTqAz + LocalVarOutData(22) = LocalVar%AzBuffer(1) + LocalVarOutData(23) = LocalVar%NumBl + LocalVarOutData(24) = LocalVar%FA_Acc + LocalVarOutData(25) = LocalVar%NacIMU_FA_Acc + LocalVarOutData(26) = LocalVar%FA_AccHPF + LocalVarOutData(27) = LocalVar%FA_AccHPFI + LocalVarOutData(28) = LocalVar%FA_PitCom(1) + LocalVarOutData(29) = LocalVar%VS_RefSpd + LocalVarOutData(30) = LocalVar%RotSpeedF + LocalVarOutData(31) = LocalVar%GenSpeedF + LocalVarOutData(32) = LocalVar%GenTq + LocalVarOutData(33) = LocalVar%GenTqMeas + LocalVarOutData(34) = LocalVar%GenArTq + LocalVarOutData(35) = LocalVar%GenBrTq + LocalVarOutData(36) = LocalVar%IPC_PitComF(1) + LocalVarOutData(37) = LocalVar%PC_KP + LocalVarOutData(38) = LocalVar%PC_KI + LocalVarOutData(39) = LocalVar%PC_KD + LocalVarOutData(40) = LocalVar%PC_TF + LocalVarOutData(41) = LocalVar%PC_MaxPit + LocalVarOutData(42) = LocalVar%PC_MinPit + LocalVarOutData(43) = LocalVar%PC_PitComT + LocalVarOutData(44) = LocalVar%PC_PitComT_Last + LocalVarOutData(45) = LocalVar%PC_PitComTF + LocalVarOutData(46) = LocalVar%PC_PitComT_IPC(1) + LocalVarOutData(47) = LocalVar%PC_PwrErr + LocalVarOutData(48) = LocalVar%PC_SpdErr + LocalVarOutData(49) = LocalVar%IPC_AxisTilt_1P + LocalVarOutData(50) = LocalVar%IPC_AxisYaw_1P + LocalVarOutData(51) = LocalVar%IPC_AxisTilt_2P + LocalVarOutData(52) = LocalVar%IPC_AxisYaw_2P + LocalVarOutData(53) = LocalVar%axisTilt_1P + LocalVarOutData(54) = LocalVar%axisYaw_1P + LocalVarOutData(55) = LocalVar%axisYawF_1P + LocalVarOutData(56) = LocalVar%axisTilt_2P + LocalVarOutData(57) = LocalVar%axisYaw_2P + LocalVarOutData(58) = LocalVar%axisYawF_2P + LocalVarOutData(59) = LocalVar%IPC_KI(1) + LocalVarOutData(60) = LocalVar%IPC_KP(1) + LocalVarOutData(61) = LocalVar%IPC_IntSat + LocalVarOutData(62) = LocalVar%PC_State + LocalVarOutData(63) = LocalVar%PitCom(1) + LocalVarOutData(64) = LocalVar%PitComAct(1) + LocalVarOutData(65) = LocalVar%SS_DelOmegaF + LocalVarOutData(66) = LocalVar%TestType + LocalVarOutData(67) = LocalVar%Kp_Float + LocalVarOutData(68) = LocalVar%VS_MaxTq + LocalVarOutData(69) = LocalVar%VS_LastGenTrq + LocalVarOutData(70) = LocalVar%VS_LastGenPwr + LocalVarOutData(71) = LocalVar%VS_MechGenPwr + LocalVarOutData(72) = LocalVar%VS_SpdErrAr + LocalVarOutData(73) = LocalVar%VS_SpdErrBr + LocalVarOutData(74) = LocalVar%VS_SpdErr + LocalVarOutData(75) = LocalVar%VS_State + LocalVarOutData(76) = LocalVar%VS_Rgn3Pitch + LocalVarOutData(77) = LocalVar%WE_Vw + LocalVarOutData(78) = LocalVar%WE_Vw_F + LocalVarOutData(79) = LocalVar%WE_VwI + LocalVarOutData(80) = LocalVar%WE_VwIdot + LocalVarOutData(81) = LocalVar%VS_LastGenTrqF + LocalVarOutData(82) = LocalVar%Fl_PitCom + LocalVarOutData(83) = LocalVar%NACIMU_FA_AccF + LocalVarOutData(84) = LocalVar%FA_AccF + LocalVarOutData(85) = LocalVar%PtfmTDX + LocalVarOutData(86) = LocalVar%PtfmTDY + LocalVarOutData(87) = LocalVar%PtfmTDZ + LocalVarOutData(88) = LocalVar%PtfmRDX + LocalVarOutData(89) = LocalVar%PtfmRDY + LocalVarOutData(90) = LocalVar%PtfmRDZ + LocalVarOutData(91) = LocalVar%PtfmTVX + LocalVarOutData(92) = LocalVar%PtfmTVY + LocalVarOutData(93) = LocalVar%PtfmTVZ + LocalVarOutData(94) = LocalVar%PtfmRVX + LocalVarOutData(95) = LocalVar%PtfmRVY + LocalVarOutData(96) = LocalVar%PtfmRVZ + LocalVarOutData(97) = LocalVar%PtfmTAX + LocalVarOutData(98) = LocalVar%PtfmTAY + LocalVarOutData(99) = LocalVar%PtfmTAZ + LocalVarOutData(100) = LocalVar%PtfmRAX + LocalVarOutData(101) = LocalVar%PtfmRAY + LocalVarOutData(102) = LocalVar%PtfmRAZ + LocalVarOutData(103) = LocalVar%CC_DesiredL(1) + LocalVarOutData(104) = LocalVar%CC_ActuatedL(1) + LocalVarOutData(105) = LocalVar%CC_ActuatedDL(1) + LocalVarOutData(106) = LocalVar%StC_Input(1) + LocalVarOutData(107) = LocalVar%Flp_Angle(1) + LocalVarOutData(108) = LocalVar%RootMyb_Last(1) + LocalVarOutData(109) = LocalVar%ACC_INFILE_SIZE + LocalVarOutData(110) = LocalVar%AWC_complexangle(1) LocalVarOutStrings = [CHARACTER(15) :: 'iStatus', 'Time', 'DT', 'n_DT', 'Time_Last', & - 'VS_GenPwr', 'GenSpeed', 'RotSpeed', 'NacHeading', 'NacVane', & - 'HorWindV', 'rootMOOP', 'rootMOOPF', 'BlPitch', 'BlPitchCMeas', & - 'Azimuth', 'OL_Azimuth', 'AzUnwrapped', 'AzError', 'GenTqAz', & - 'AzBuffer', 'NumBl', 'FA_Acc', 'NacIMU_FA_Acc', 'FA_AccHPF', & - 'FA_AccHPFI', 'FA_PitCom', 'RotSpeedF', 'GenSpeedF', 'GenTq', & - 'GenTqMeas', 'GenArTq', 'GenBrTq', 'IPC_PitComF', 'PC_KP', & - 'PC_KI', 'PC_KD', 'PC_TF', 'PC_MaxPit', 'PC_MinPit', & - 'PC_PitComT', 'PC_PitComT_Last', 'PC_PitComTF', 'PC_PitComT_IPC', 'PC_PwrErr', & - 'PC_SpdErr', 'IPC_AxisTilt_1P', 'IPC_AxisYaw_1P', 'IPC_AxisTilt_2P', 'IPC_AxisYaw_2P', & - 'axisTilt_1P', 'axisYaw_1P', 'axisYawF_1P', 'axisTilt_2P', 'axisYaw_2P', & - 'axisYawF_2P', 'IPC_KI', 'IPC_KP', 'IPC_IntSat', 'PC_State', & - 'PitCom', 'PitComAct', 'SS_DelOmegaF', 'TestType', 'Kp_Float', & - 'VS_MaxTq', 'VS_LastGenTrq', 'VS_LastGenPwr', 'VS_MechGenPwr', 'VS_SpdErrAr', & - 'VS_SpdErrBr', 'VS_SpdErr', 'VS_State', 'VS_Rgn3Pitch', 'WE_Vw', & - 'WE_Vw_F', 'WE_VwI', 'WE_VwIdot', 'VS_LastGenTrqF', 'Fl_PitCom', & - 'NACIMU_FA_AccF', 'FA_AccF', 'PtfmTDX', 'PtfmTDY', 'PtfmTDZ', & - 'PtfmRDX', 'PtfmRDY', 'PtfmRDZ', 'PtfmTVX', 'PtfmTVY', & - 'PtfmTVZ', 'PtfmRVX', 'PtfmRVY', 'PtfmRVZ', 'PtfmTAX', & - 'PtfmTAY', 'PtfmTAZ', 'PtfmRAX', 'PtfmRAY', 'PtfmRAZ', & - 'CC_DesiredL', 'CC_ActuatedL', 'CC_ActuatedDL', 'StC_Input', 'Flp_Angle', & - 'RootMyb_Last', 'ACC_INFILE_SIZE', 'AWC_complexangle'] + 'VS_GenPwr', 'VS_GenPwrF', 'GenSpeed', 'RotSpeed', 'NacHeading', & + 'NacVane', 'HorWindV', 'rootMOOP', 'rootMOOPF', 'BlPitch', & + 'BlPitchCMeas', 'Azimuth', 'OL_Azimuth', 'AzUnwrapped', 'AzError', & + 'GenTqAz', 'AzBuffer', 'NumBl', 'FA_Acc', 'NacIMU_FA_Acc', & + 'FA_AccHPF', 'FA_AccHPFI', 'FA_PitCom', 'VS_RefSpd', 'RotSpeedF', & + 'GenSpeedF', 'GenTq', 'GenTqMeas', 'GenArTq', 'GenBrTq', & + 'IPC_PitComF', 'PC_KP', 'PC_KI', 'PC_KD', 'PC_TF', & + 'PC_MaxPit', 'PC_MinPit', 'PC_PitComT', 'PC_PitComT_Last', 'PC_PitComTF', & + 'PC_PitComT_IPC', 'PC_PwrErr', 'PC_SpdErr', 'IPC_AxisTilt_1P', 'IPC_AxisYaw_1P', & + 'IPC_AxisTilt_2P', 'IPC_AxisYaw_2P', 'axisTilt_1P', 'axisYaw_1P', 'axisYawF_1P', & + 'axisTilt_2P', 'axisYaw_2P', 'axisYawF_2P', 'IPC_KI', 'IPC_KP', & + 'IPC_IntSat', 'PC_State', 'PitCom', 'PitComAct', 'SS_DelOmegaF', & + 'TestType', 'Kp_Float', 'VS_MaxTq', 'VS_LastGenTrq', 'VS_LastGenPwr', & + 'VS_MechGenPwr', 'VS_SpdErrAr', 'VS_SpdErrBr', 'VS_SpdErr', 'VS_State', & + 'VS_Rgn3Pitch', 'WE_Vw', 'WE_Vw_F', 'WE_VwI', 'WE_VwIdot', & + 'VS_LastGenTrqF', 'Fl_PitCom', 'NACIMU_FA_AccF', 'FA_AccF', 'PtfmTDX', & + 'PtfmTDY', 'PtfmTDZ', 'PtfmRDX', 'PtfmRDY', 'PtfmRDZ', & + 'PtfmTVX', 'PtfmTVY', 'PtfmTVZ', 'PtfmRVX', 'PtfmRVY', & + 'PtfmRVZ', 'PtfmTAX', 'PtfmTAY', 'PtfmTAZ', 'PtfmRAX', & + 'PtfmRAY', 'PtfmRAZ', 'CC_DesiredL', 'CC_ActuatedL', 'CC_ActuatedDL', & + 'StC_Input', 'Flp_Angle', 'RootMyb_Last', 'ACC_INFILE_SIZE', 'AWC_complexangle' & + ] ! Initialize debug file IF ((LocalVar%iStatus == 0) .OR. (LocalVar%iStatus == -9)) THEN ! .TRUE. if we're on the first call to the DLL IF (CntrPar%LoggingLevel > 0) THEN @@ -790,8 +797,8 @@ SUBROUTINE Debug(LocalVar, CntrPar, DebugVar, ErrVar, avrSWAP, RootName, size_av CALL GetNewUnit(UnDb2, ErrVar) OPEN(unit=UnDb2, FILE=TRIM(RootName)//'.RO.dbg2') WRITE(UnDb2, *) 'Generated on '//CurDate()//' at '//CurTime()//' using ROSCO-'//TRIM(rosco_version) - WRITE(UnDb2, '(109(a20,TR5:))') 'Time', LocalVarOutStrings - WRITE(UnDb2, '(109(a20,TR5:))') + WRITE(UnDb2, '(111(a20,TR5:))') 'Time', LocalVarOutStrings + WRITE(UnDb2, '(111(a20,TR5:))') END IF IF (CntrPar%LoggingLevel > 2) THEN @@ -854,7 +861,7 @@ SUBROUTINE Debug(LocalVar, CntrPar, DebugVar, ErrVar, avrSWAP, RootName, size_av END DO ! Write debug files - FmtDat = "(F20.5,TR5,108(ES20.5E2,TR5:))" ! The format of the debugging data + FmtDat = "(F20.5,TR5,110(ES20.5E2,TR5:))" ! The format of the debugging data IF ( MOD(LocalVar%n_DT, CntrPar%n_DT_Out) == 0) THEN IF(CntrPar%LoggingLevel > 0) THEN WRITE (UnDb, FmtDat) LocalVar%Time, DebugOutData diff --git a/ROSCO/src/ROSCO_Types.f90 b/ROSCO/src/ROSCO_Types.f90 index ce22b2da..77854962 100644 --- a/ROSCO/src/ROSCO_Types.f90 +++ b/ROSCO/src/ROSCO_Types.f90 @@ -13,11 +13,16 @@ MODULE ROSCO_Types REAL(DbKi) :: DT_Out ! Output time step INTEGER(IntKi) :: n_DT_Out ! output every this many steps INTEGER(IntKi) :: F_LPFType ! Low pass filter on the rotor and generator speed {1 - first-order low-pass filter, 2 - second-order low-pass filter}, [rad/s] - INTEGER(IntKi) :: F_NotchType ! Notch on the measured generator speed {0 - disable, 1 - enable} REAL(DbKi) :: F_LPFCornerFreq ! Corner frequency (-3dB point) in the first-order low-pass filter, [rad/s] REAL(DbKi) :: F_LPFDamping ! Damping coefficient [used only when F_FilterType = 2] - REAL(DbKi) :: F_NotchCornerFreq ! Natural frequency of the notch filter, [rad/s] - REAL(DbKi), DIMENSION(:), ALLOCATABLE :: F_NotchBetaNumDen ! These two notch damping values (numerator and denominator) determines the width and depth of the notch + INTEGER(IntKi) :: F_NumNotchFilts ! Number of notch filters + INTEGER(IntKi) :: F_GenSpdNotch_N ! Number of gen speed notch filters + INTEGER(IntKi), DIMENSION(:), ALLOCATABLE :: F_GenSpdNotch_Ind ! Indices of gen speed notch filters + INTEGER(IntKi) :: F_TwrTopNotch_N ! Number of tower top notch filters + INTEGER(IntKi), DIMENSION(:), ALLOCATABLE :: F_TwrTopNotch_Ind ! Indices of tower top notch filters + REAL(DbKi), DIMENSION(:), ALLOCATABLE :: F_NotchFreqs ! Natural frequencies of notch filters, [rad/s] + REAL(DbKi), DIMENSION(:), ALLOCATABLE :: F_NotchBetaNum ! Notch Filter Numerator damping (determines width) + REAL(DbKi), DIMENSION(:), ALLOCATABLE :: F_NotchBetaDen ! Notch Filter Numerator damping (determines depth?) REAL(DbKi) :: F_SSCornerFreq ! Corner frequency (-3dB point) in the first order low pass filter for the setpoint smoother [rad/s] REAL(DbKi) :: F_WECornerFreq ! Corner frequency (-3dB point) in the first order low pass filter for the wind speed estimate [rad/s] REAL(DbKi), DIMENSION(:), ALLOCATABLE :: F_FlCornerFreq ! Corner frequency (-3dB point) in the second order low pass filter of the tower-top fore-aft motion for floating feedback control [rad/s]. @@ -50,7 +55,8 @@ MODULE ROSCO_Types REAL(DbKi) :: PC_RefSpd ! Desired (reference) HSS speed for pitch controller, [rad/s]. REAL(DbKi) :: PC_FinePit ! Record 5 - Below-rated pitch angle set-point (deg) [used only with Bladed Interface] REAL(DbKi) :: PC_Switch ! Angle above lowest minimum pitch angle for switch [rad] - INTEGER(IntKi) :: VS_ControlMode ! Generator torque control mode in above rated conditions {0 - constant torque, 1 - constant power, 2 - TSR Tracking, 3 - TSR Tracking w/ const power} + INTEGER(IntKi) :: VS_ControlMode ! Generator torque control mode in above rated conditions {0 - no torque control, 1 - komega^2 with PI trans, 2 - WSE TSR Tracking, 3 - Power TSR Tracking} + INTEGER(IntKi) :: VS_ConstPower ! Constant power torque control REAL(DbKi) :: VS_GenEff ! Generator efficiency mechanical power -> electrical power [-] REAL(DbKi) :: VS_ArSatTq ! Above rated generator torque PI control saturation, [Nm] -- 212900 REAL(DbKi) :: VS_MaxRat ! Maximum torque rate (in absolute value) in torque controller, [Nm/s]. @@ -65,6 +71,7 @@ MODULE ROSCO_Types REAL(DbKi), DIMENSION(:), ALLOCATABLE :: VS_KP ! Proportional gain for generator PI torque controller, used in the transitional 2.5 region REAL(DbKi), DIMENSION(:), ALLOCATABLE :: VS_KI ! Integral gain for generator PI torque controller, used in the transitional 2.5 region REAL(DbKi) :: VS_TSRopt ! Power-maximizing region 2 tip-speed ratio [rad] + REAL(DbKi) :: VS_PwrFiltF ! Cut-off frequency of filter on generator power for power-based tsr tracking control INTEGER(IntKi) :: SS_Mode ! Setpoint Smoother mode {0 - no setpoint smoothing, 1 - introduce setpoint smoothing} REAL(DbKi) :: SS_VSGain ! Variable speed torque controller setpoint smoother gain, [-]. REAL(DbKi) :: SS_PCGain ! Collective pitch controller setpoint smoother gain, [-]. @@ -112,7 +119,7 @@ MODULE ROSCO_Types INTEGER(IntKi) :: Ind_GenTq ! The column in OL_Filename that contains the generator torque in Nm INTEGER(IntKi) :: Ind_YawRate ! The column in OL_Filename that contains the generator torque in Nm INTEGER(IntKi) :: Ind_Azimuth ! The column in OL_Filename that contains the desired azimuth position in rad (used if OL_Mode = 2) - REAL(DbKi), DIMENSION(:), ALLOCATABLE :: RP_Gains ! PID gains for rotor position control (used if OL_Mode = 2) + REAL(DbKi), DIMENSION(:), ALLOCATABLE :: RP_Gains ! PID gains and Tf on derivative term for rotor position control (used if OL_Mode = 2) INTEGER(IntKi), DIMENSION(:), ALLOCATABLE :: Ind_CableControl ! The column in OL_Filename that contains the cable control inputs in m INTEGER(IntKi), DIMENSION(:), ALLOCATABLE :: Ind_StructControl ! The column in OL_Filename that contains the structural control inputs in various units REAL(DbKi), DIMENSION(:), ALLOCATABLE :: OL_Breakpoints ! Open loop breakpoints in timeseries @@ -235,6 +242,7 @@ MODULE ROSCO_Types INTEGER(IntKi) :: n_DT ! number of timesteps since start REAL(DbKi) :: Time_Last ! Last time [s] REAL(DbKi) :: VS_GenPwr ! Generator power [W] + REAL(DbKi) :: VS_GenPwrF ! Generator power [W] REAL(DbKi) :: GenSpeed ! Generator speed (HSS) [rad/s] REAL(DbKi) :: RotSpeed ! Rotor speed (LSS) [rad/s] REAL(DbKi) :: NacHeading ! Nacelle heading of the turbine w.r.t. north [deg] @@ -256,6 +264,7 @@ MODULE ROSCO_Types REAL(DbKi) :: FA_AccHPF ! High-pass filtered fore-aft acceleration [m/s^2] REAL(DbKi) :: FA_AccHPFI ! Tower velocity, high-pass filtered and integrated fore-aft acceleration [m/s] REAL(DbKi) :: FA_PitCom(3) ! Tower fore-aft vibration damping pitch contribution [rad] + REAL(DbKi) :: VS_RefSpd ! Torque control generator speed set point [rad/s] REAL(DbKi) :: RotSpeedF ! Filtered LSS (generator) speed [rad/s]. REAL(DbKi) :: GenSpeedF ! Filtered HSS (generator) speed [rad/s]. REAL(DbKi) :: GenTq ! Electrical generator torque, [Nm]. diff --git a/ROSCO/src/ReadSetParameters.f90 b/ROSCO/src/ReadSetParameters.f90 index ee03cff0..7d5d4928 100644 --- a/ROSCO/src/ReadSetParameters.f90 +++ b/ROSCO/src/ReadSetParameters.f90 @@ -226,6 +226,7 @@ SUBROUTINE SetParameters(avrSWAP, accINFILE, size_avcMSG, CntrPar, LocalVar, obj ENDIF LocalVar%VS_LastGenTrq = LocalVar%GenTq LocalVar%VS_MaxTq = CntrPar%VS_MaxTq + LocalVar%VS_GenPwr = LocalVar%GenTq * LocalVar%GenSpeed ! Initialize variables LocalVar%CC_DesiredL = 0 @@ -337,9 +338,9 @@ SUBROUTINE ReadControlParameterFileSub(CntrPar, LocalVar, zmqVar, accINFILE, acc !----------------- CONTROLLER FLAGS --------------------- CALL ParseInput(FileLines,'F_LPFType', CntrPar%F_LPFType, accINFILE(1), ErrVar, UnEc=UnEc) - CALL ParseInput(FileLines,'F_NotchType', CntrPar%F_NotchType, accINFILE(1), ErrVar, UnEc=UnEc) CALL ParseInput(FileLines,'IPC_ControlMode', CntrPar%IPC_ControlMode, accINFILE(1), ErrVar, UnEc=UnEc) CALL ParseInput(FileLines,'VS_ControlMode', CntrPar%VS_ControlMode, accINFILE(1), ErrVar, UnEc=UnEc) + CALL ParseInput(FileLines,'VS_ConstPower', CntrPar%VS_ConstPower, accINFILE(1), ErrVar, .TRUE., UnEc=UnEc) ! Default is 0 CALL ParseInput(FileLines,'PC_ControlMode', CntrPar%PC_ControlMode, accINFILE(1), ErrVar, UnEc=UnEc) CALL ParseInput(FileLines,'Y_ControlMode', CntrPar%Y_ControlMode, accINFILE(1), ErrVar, UnEc=UnEc) CALL ParseInput(FileLines,'SS_Mode', CntrPar%SS_Mode, accINFILE(1), ErrVar, UnEc=UnEc) @@ -360,16 +361,29 @@ SUBROUTINE ReadControlParameterFileSub(CntrPar, LocalVar, zmqVar, accINFILE, acc IF (ErrVar%aviFAIL < 0) RETURN !----------------- FILTER CONSTANTS --------------------- - CALL ParseInput(FileLines, 'F_LPFCornerFreq', CntrPar%F_LPFCornerFreq, accINFILE(1), ErrVar, .FALSE., UnEc) - CALL ParseInput(FileLines, 'F_LPFDamping', CntrPar%F_LPFDamping, accINFILE(1), ErrVar, CntrPar%F_LPFType == 1, UnEc) - CALL ParseInput(FileLines, 'F_NotchCornerFreq', CntrPar%F_NotchCornerFreq, accINFILE(1), ErrVar, CntrPar%F_NotchType == 0, UnEc) - CALL ParseAry( FileLines, 'F_NotchBetaNumDen', CntrPar%F_NotchBetaNumDen, 2, accINFILE(1), ErrVar, CntrPar%F_NotchType == 0, UnEc) - CALL ParseInput(FileLines, 'F_SSCornerFreq', CntrPar%F_SSCornerFreq, accINFILE(1), ErrVar, CntrPar%SS_Mode == 0, UnEc) - CALL ParseInput(FileLines, 'F_WECornerFreq', CntrPar%F_WECornerFreq, accINFILE(1), ErrVar, .FALSE., UnEc) - CALL ParseInput(FileLines, 'F_YawErr', CntrPar%F_YawErr, accINFILE(1), ErrVar, CntrPar%Y_ControlMode == 0, UnEc) - CALL ParseAry( FileLines, 'F_FlCornerFreq', CntrPar%F_FlCornerFreq, 2, accINFILE(1), ErrVar, CntrPar%FL_Mode == 0, UnEc) - CALL ParseInput(FileLines, 'F_FlHighPassFreq', CntrPar%F_FlHighPassFreq, accINFILE(1), ErrVar, CntrPar%FL_Mode == 0, UnEc) - CALL ParseAry( FileLines, 'F_FlpCornerFreq', CntrPar%F_FlpCornerFreq, 2, accINFILE(1), ErrVar, CntrPar%Flp_Mode == 0, UnEc) + CALL ParseInput(FileLines, 'F_LPFCornerFreq', CntrPar%F_LPFCornerFreq, accINFILE(1), ErrVar, .FALSE., UnEc) + CALL ParseInput(FileLines, 'F_LPFDamping', CntrPar%F_LPFDamping, accINFILE(1), ErrVar, CntrPar%F_LPFType == 1, UnEc) + CALL ParseInput(FileLines, 'F_NumNotchFilts', CntrPar%F_NumNotchFilts, accINFILE(1), ErrVar, .FALSE., UnEc) + CALL ParseAry( FileLines, 'F_NotchFreqs', CntrPar%F_NotchFreqs, CntrPar%F_NumNotchFilts, accINFILE(1), ErrVar, CntrPar%F_NumNotchFilts == 0, UnEc) + CALL ParseAry( FileLines, 'F_NotchBetaNum', CntrPar%F_NotchBetaNum, CntrPar%F_NumNotchFilts, accINFILE(1), ErrVar, CntrPar%F_NumNotchFilts == 0, UnEc) + CALL ParseAry( FileLines, 'F_NotchBetaDen', CntrPar%F_NotchBetaDen, CntrPar%F_NumNotchFilts, accINFILE(1), ErrVar, CntrPar%F_NumNotchFilts == 0, UnEc) + CALL ParseInput(FileLines, 'F_GenSpdNotch_N', CntrPar%F_GenSpdNotch_N, accINFILE(1), ErrVar, CntrPar%F_NumNotchFilts == 0, UnEc) + CALL ParseInput(FileLines, 'F_TwrTopNotch_N', CntrPar%F_TwrTopNotch_N, accINFILE(1), ErrVar, CntrPar%F_NumNotchFilts == 0, UnEc) + CALL ParseInput(FileLines, 'F_SSCornerFreq', CntrPar%F_SSCornerFreq, accINFILE(1), ErrVar, CntrPar%SS_Mode == 0, UnEc) + CALL ParseInput(FileLines, 'F_WECornerFreq', CntrPar%F_WECornerFreq, accINFILE(1), ErrVar, .FALSE., UnEc) + CALL ParseInput(FileLines, 'F_YawErr', CntrPar%F_YawErr, accINFILE(1), ErrVar, CntrPar%Y_ControlMode == 0, UnEc) + CALL ParseAry( FileLines, 'F_FlCornerFreq', CntrPar%F_FlCornerFreq, 2, accINFILE(1), ErrVar, CntrPar%FL_Mode == 0, UnEc) + CALL ParseInput(FileLines, 'F_FlHighPassFreq', CntrPar%F_FlHighPassFreq, accINFILE(1), ErrVar, CntrPar%FL_Mode == 0, UnEc) + CALL ParseAry( FileLines, 'F_FlpCornerFreq', CntrPar%F_FlpCornerFreq, 2, accINFILE(1), ErrVar, CntrPar%Flp_Mode == 0, UnEc) + + ! Optional filter inds + IF (CntrPar%F_GenSpdNotch_N > 0) THEN + CALL ParseAry(FileLines, 'F_GenSpdNotch_Ind', CntrPar%F_GenSpdNotch_Ind, CntrPar%F_GenSpdNotch_N, accINFILE(1), ErrVar, CntrPar%F_GenSpdNotch_N == 0, UnEc) + ENDIF + IF (CntrPar%F_TwrTopNotch_N > 0) THEN + CALL ParseAry(FileLines, 'F_TwrTopNotch_Ind', CntrPar%F_TwrTopNotch_Ind, CntrPar%F_TwrTopNotch_N, accINFILE(1), ErrVar, CntrPar%F_TwrTopNotch_N == 0, UnEc) + ENDIF + IF (ErrVar%aviFAIL < 0) RETURN !----------- BLADE PITCH CONTROLLER CONSTANTS ----------- @@ -400,12 +414,12 @@ SUBROUTINE ReadControlParameterFileSub(CntrPar, LocalVar, zmqVar, accINFILE, acc !------------ VS TORQUE CONTROL CONSTANTS ---------------- CALL ParseInput(FileLines, 'VS_GenEff', CntrPar%VS_GenEff, accINFILE(1), ErrVar, .FALSE., UnEc) - CALL ParseInput(FileLines, 'VS_ArSatTq', CntrPar%VS_ArSatTq, accINFILE(1), ErrVar, CntrPar%VS_ControlMode > 1, UnEc) - CALL ParseInput(FileLines, 'VS_MaxRat', CntrPar%VS_MaxRat, accINFILE(1), ErrVar, CntrPar%VS_ControlMode > 1, UnEc) + CALL ParseInput(FileLines, 'VS_ArSatTq', CntrPar%VS_ArSatTq, accINFILE(1), ErrVar, CntrPar%VS_ControlMode .NE. 1, UnEc) + CALL ParseInput(FileLines, 'VS_MaxRat', CntrPar%VS_MaxRat, accINFILE(1), ErrVar, CntrPar%VS_ControlMode .NE. 1, UnEc) CALL ParseInput(FileLines, 'VS_MaxTq', CntrPar%VS_MaxTq, accINFILE(1), ErrVar, .FALSE., UnEc) CALL ParseInput(FileLines, 'VS_MinTq', CntrPar%VS_MinTq, accINFILE(1), ErrVar, .FALSE., UnEc) CALL ParseInput(FileLines, 'VS_MinOMSpd', CntrPar%VS_MinOMSpd, accINFILE(1), ErrVar) ! Default 0 is fin, UnEce - CALL ParseInput(FileLines, 'VS_Rgn2K', CntrPar%VS_Rgn2K, accINFILE(1), ErrVar, CntrPar%VS_ControlMode > 1, UnEc) + CALL ParseInput(FileLines, 'VS_Rgn2K', CntrPar%VS_Rgn2K, accINFILE(1), ErrVar, CntrPar%VS_ControlMode == 2, UnEc) CALL ParseInput(FileLines, 'VS_RtPwr', CntrPar%VS_RtPwr, accINFILE(1), ErrVar, .FALSE., UnEc) CALL ParseInput(FileLines, 'VS_RtTq', CntrPar%VS_RtTq, accINFILE(1), ErrVar, .FALSE., UnEc) CALL ParseInput(FileLines, 'VS_RefSpd', CntrPar%VS_RefSpd, accINFILE(1), ErrVar, .FALSE., UnEc) @@ -413,6 +427,7 @@ SUBROUTINE ReadControlParameterFileSub(CntrPar, LocalVar, zmqVar, accINFILE, acc CALL ParseAry( FileLines, 'VS_KP', CntrPar%VS_KP, CntrPar%VS_n, accINFILE(1), ErrVar, .FALSE., UnEc) CALL ParseAry( FileLines, 'VS_KI', CntrPar%VS_KI, CntrPar%VS_n, accINFILE(1), ErrVar, .FALSE., UnEc) CALL ParseInput(FileLines, 'VS_TSRopt', CntrPar%VS_TSRopt, accINFILE(1), ErrVar, CntrPar%VS_ControlMode < 2, UnEc) + CALL ParseInput(FileLines, 'VS_PwrFiltF', CntrPar%VS_PwrFiltF, accINFILE(1), ErrVar, CntrPar%VS_ControlMode .NE. 3, UnEc) IF (ErrVar%aviFAIL < 0) RETURN !------- Setpoint Smoother -------------------------------- @@ -821,12 +836,6 @@ SUBROUTINE CheckInputs(LocalVar, CntrPar, avrSWAP, ErrVar, size_avcMSG) ErrVar%ErrMsg = 'F_LPFType must be 1 or 2.' ENDIF - ! F_NotchType - IF ((CntrPar%F_NotchType < 0) .OR. (CntrPar%F_NotchType > 3)) THEN - ErrVar%aviFAIL = -1 - ErrVar%ErrMsg = 'F_NotchType must be 0, 1, 2, or 3.' - ENDIF - ! IPC_ControlMode IF ((CntrPar%IPC_ControlMode < 0) .OR. (CntrPar%IPC_ControlMode > 2)) THEN ErrVar%aviFAIL = -1 @@ -839,6 +848,12 @@ SUBROUTINE CheckInputs(LocalVar, CntrPar, avrSWAP, ErrVar, size_avcMSG) ErrVar%ErrMsg = 'VS_ControlMode must be 0, 1, 2, or 3.' ENDIF + ! VS_ConstPower + IF ((CntrPar%VS_ConstPower < 0) .OR. (CntrPar%VS_ConstPower > 1)) THEN + ErrVar%aviFAIL = -1 + ErrVar%ErrMsg = 'VS_ConstPower must be 0 or 1.' + ENDIF + ! PC_ControlMode IF ((CntrPar%PC_ControlMode < 0) .OR. (CntrPar%PC_ControlMode > 1)) THEN ErrVar%aviFAIL = -1 @@ -913,18 +928,18 @@ SUBROUTINE CheckInputs(LocalVar, CntrPar, avrSWAP, ErrVar, size_avcMSG) ENDIF ! Notch Filter Params - IF (CntrPar%F_NotchType > 0) THEN + IF (CntrPar%F_NumNotchFilts > 0) THEN ! F_NotchCornerFreq - IF (CntrPar%F_NotchCornerFreq <= 0.0) THEN + IF (ANY(CntrPar%F_NotchFreqs <= 0.0)) THEN ErrVar%aviFAIL = -1 - ErrVar%ErrMsg = 'F_NotchCornerFreq must be greater than zero.' + ErrVar%ErrMsg = 'F_NotchFreqs must be greater than zero.' ENDIF - ! F_NotchBetaNumDen(2) - IF (CntrPar%F_NotchBetaNumDen(2) <= 0.0) THEN + ! F_NotchBetaDen + IF (ANY(CntrPar%F_NotchBetaDen <= 0.0)) THEN ErrVar%aviFAIL = -1 - ErrVar%ErrMsg = 'F_NotchBetaNumDen(2) must be greater than zero.' + ErrVar%ErrMsg = 'F_NotchBetaDen must be greater than zero.' ENDIF ENDIF @@ -1196,13 +1211,6 @@ SUBROUTINE CheckInputs(LocalVar, CntrPar, avrSWAP, ErrVar, size_avcMSG) ENDIF - ! --- Floating Control --- - IF (CntrPar%Fl_Mode > 0) THEN - IF (CntrPar%F_NotchType < 1 .OR. CntrPar%F_NotchCornerFreq == 0.0) THEN - ErrVar%aviFAIL = -1 - ErrVar%ErrMsg = 'F_NotchType and F_NotchCornerFreq must be specified for Fl_Mode greater than zero.' - ENDIF - ENDIF ! --- Open loop control --- IF (CntrPar%OL_Mode > 0) THEN diff --git a/ROSCO_toolbox/controller.py b/ROSCO_toolbox/controller.py index 4f59e968..335bcd54 100644 --- a/ROSCO_toolbox/controller.py +++ b/ROSCO_toolbox/controller.py @@ -54,6 +54,7 @@ def __init__(self, controller_params): self.F_NotchType = controller_params['F_NotchType'] self.IPC_ControlMode = controller_params['IPC_ControlMode'] self.VS_ControlMode = controller_params['VS_ControlMode'] + self.VS_ConstPower = controller_params['VS_ConstPower'] self.PC_ControlMode = controller_params['PC_ControlMode'] self.Y_ControlMode = controller_params['Y_ControlMode'] self.SS_Mode = controller_params['SS_Mode'] @@ -138,6 +139,7 @@ def __init__(self, controller_params): self.f_yawerr = controller_params['filter_params']['f_yawerr'] self.f_sd_cornerfreq = controller_params['filter_params']['f_sd_cornerfreq'] + # Open loop parameters: set up and error catching self.OL_Mode = controller_params['OL_Mode'] self.OL_Filename = controller_params['open_loop']['filename'] @@ -282,7 +284,7 @@ def tune_controller(self, turbine): Pi_wind = 1/2 * rho * Ar * v**2 * dCt_dTSR * dlambda_dv + rho * Ar * v * Ct_op # Second order system coefficients - if self.VS_ControlMode in [0,2]: # Constant torque above rated + if not self.VS_ConstPower: # Constant torque above rated A = dtau_domega/J else: # Constant power above rated A = dtau_domega/J @@ -321,7 +323,8 @@ def tune_controller(self, turbine): self.vs_gain_schedule.second_order_PI(self.zeta_vs, self.omega_vs,A_vs,B_tau[0:len(v_below_rated)],linearize=False,v=v_below_rated) # -- Find K for Komega_g^2 -- - self.vs_rgn2K = (pi*rho*R**5.0 * turbine.Cp.max) / (2.0 * turbine.Cp.TSR_opt**3 * Ng**3)/ (turbine.GBoxEff/100) + self.vs_rgn2K = (pi*rho*R**5.0 * turbine.Cp.max * turbine.GBoxEff/100 * turbine.GenEff/100) / \ + (2.0 * turbine.Cp.TSR_opt**3 * Ng**3) * self.controller_params['rgn2k_factor'] self.vs_refspd = min(turbine.TSR_operational * turbine.v_rated/R, turbine.rated_rotor_speed) * Ng # -- Define some setpoints -- @@ -413,9 +416,10 @@ def tune_controller(self, turbine): - # Turn on the notch filter if floating - self.F_NotchType = 2 - + # Turn on the notch filter if floating and not already on + if not self.F_NotchType: + self.F_NotchType = 2 + # And check for .yaml input inconsistencies if self.twr_freq == 0.0 or self.ptfm_freq == 0.0: print('WARNING: twr_freq and ptfm_freq should be defined for floating turbine control!!') @@ -443,6 +447,29 @@ def tune_controller(self, turbine): # --- Set up filters --- self.f_lpf_cornerfreq = turbine.bld_edgewise_freq / 4 + # Notch filters + self.f_notch_freqs = [] + self.f_notch_beta_nums = [] + self.f_notch_beta_dens = [] + self.f_notch_gen_inds = [] + self.f_notch_twr_inds = [] + + if self.F_NotchType: + if self.Flp_Mode: + self.f_notch_freqs.append(turbine.bld_flapwise_freq) + self.f_notch_beta_nums.append(0.0) + self.f_notch_beta_dens.append(0.50) + else: + self.f_notch_freqs.append(self.twr_freq) + self.f_notch_beta_nums.append(0.0) + self.f_notch_beta_dens.append(0.25) + + if self.F_NotchType == 1 or self.F_NotchType == 3: + self.f_notch_gen_inds.append(1) + elif self.F_NotchType == 2: + self.f_notch_twr_inds.append(1) + + # --- Direct input passthrough --- if 'f_lpf_cornerfreq' in self.controller_params['filter_params']: self.f_lpf_cornerfreq = self.controller_params['filter_params']['f_lpf_cornerfreq'] diff --git a/ROSCO_toolbox/inputs/toolbox_schema.yaml b/ROSCO_toolbox/inputs/toolbox_schema.yaml index 9cad9ff6..3f267e96 100644 --- a/ROSCO_toolbox/inputs/toolbox_schema.yaml +++ b/ROSCO_toolbox/inputs/toolbox_schema.yaml @@ -90,6 +90,12 @@ properties: unit: none default: 0 minimum: 0 + reynolds_ref: + type: number + description: Reynolds number near rated speeds, used to interpolate airfoils, if provided + unit: none + default: 0 + minimum: 0 controller_params: @@ -124,7 +130,13 @@ properties: minimum: 0 maximum: 3 default: 2 - description: Generator torque control mode in above rated conditions (0- constant torque, 1- constant power, 2- TSR tracking PI control with constant torque, 3- TSR tracking with constant power) + description: Generator torque control mode in above rated conditions (0- no torque control, 1- k*omega^2 with PI transitions, 2- WSE TSR Tracking, 3- Power-based TSR Tracking) + VS_ConstPower: + type: number + minimum: 0 + maximum: 1 + default: 0 + description: Do constant power torque control, where above rated torque varies, 0 for constant torque PC_ControlMode: type: number minimum: 0 @@ -406,6 +418,11 @@ properties: minimum: 0.0 default: [0.0, 0.0] unit: m/s + rgn2k_factor: + type: number + description: Factor on VS_Rgn2K to increase/decrease optimal torque control gain, default is 1. Sometimes environmental conditions or differences in BEM solvers necessitate this change. + default: 1 + minimum: 0 filter_params: type: object @@ -533,15 +550,22 @@ properties: F_LPFType: type: number description: 1- first-order low-pass filter, 2- second-order low-pass filter (currently filters generator speed and pitch control signals + VS_ControlMode: + type: number + minimum: 0 + maximum: 3 + description: Generator torque control mode in above rated conditions (0- no torque control, 1- k*omega^2 with PI transitions, 2- WSE TSR Tracking, 3- Power-based TSR Tracking) + VS_ConstPower: + type: number + minimum: 0 + maximum: 1 + description: Do constant power torque control, where above rated torque varies F_NotchType: type: number description: Notch on the measured generator speed and/or tower fore-aft motion (for floating) (0- disable, 1- generator speed, 2- tower-top fore-aft motion, 3- generator speed and tower-top fore-aft motion) IPC_ControlMode: type: number description: Turn Individual Pitch Control (IPC) for fatigue load reductions (pitch contribution) (0- off, 1- 1P reductions, 2- 1P+2P reductions) - VS_ControlMode: - type: number - description: Generator torque control mode in above rated conditions (0- constant torque, 1- constant power, 2- TSR tracking PI control with constant torque, 3- TSR tracking PI control with constant power) PC_ControlMode: type: number description: Blade pitch control mode (0- No pitch, fix to fine pitch, 1- active PI blade pitch control) @@ -576,15 +600,41 @@ properties: F_LPFDamping: type: number description: Damping coefficient (used only when F_FilterType = 2 [-] - F_NotchCornerFreq: + F_NumNotchFilts: type: number - description: Natural frequency of the notch filter, + description: Number of notch filters placed on sensors + F_NotchFreqs: + type: [array,number] + items: + type: number + description: Natural frequency of the notch filters. Array with length F_NumNotchFilts units: rad/s - F_NotchBetaNumDen: - type: array + F_NotchBetaNum: + type: [array, number] + items: + type: number + description: Damping value of numerator (determines the width of notch). Array with length F_NumNotchFilts, [-] + F_NotchBetaDen: + type: [array, number] items: type: number - description: Two notch damping values (numerator and denominator, resp) - determines the width and depth of the notch, [-] + description: Damping value of denominator (determines the depth of notch). Array with length F_NumNotchFilts, [-] + F_GenSpdNotch_N: + type: number + description: Number of notch filters on generator speed + F_TwrTopNotch_N: + type: number + description: Number of notch filters on tower top acceleration signal + F_GenSpdNotch_Ind: + type: [array, number] + items: + type: number + description: Indices of notch filters on generator speed + F_TwrTopNotch_Ind: + type: [array, number] + items: + type: number + description: Indices of notch filters on tower top acceleration signal F_SSCornerFreq: type: number description: Corner frequency (-3dB point) in the first order low pass filter for the setpoint smoother, @@ -720,7 +770,7 @@ properties: units: rad/s VS_Rgn2K: type: number - description: Generator torque constant in Region 2 (HSS side) + description: Generator torque constant in Region 2 (HSS side). Only used in VS_ControlMode = 1,3 units: Nm/(rad/s)^2 VS_RtPwr: type: number @@ -746,8 +796,13 @@ properties: units: s VS_TSRopt: type: number - description: Power-maximizing region 2 tip-speed-ratio + description: Power-maximizing region 2 tip-speed-ratio. Only used in VS_ControlMode = 2. + units: rad + VS_PwrFiltF: + type: number + description: Low pass filter on power used to determine generator speed set point. Only used in VS_ControlMode = 3. units: rad + default: 0.314 SS_VSGain: type: number description: Variable speed torque controller setpoint smoother gain diff --git a/ROSCO_toolbox/linear/robust_scheduling.py b/ROSCO_toolbox/linear/robust_scheduling.py index 70bc418e..7f70e2de 100644 --- a/ROSCO_toolbox/linear/robust_scheduling.py +++ b/ROSCO_toolbox/linear/robust_scheduling.py @@ -101,6 +101,9 @@ def setup(self): self.add_output('omega_opt', val=0.01, units='rad/s', desc='Maximized controller bandwidth') + def setup_partials(self): + self.declare_partials('*', '*') + def compute(self, inputs, outputs): ''' Computes the stability margin for a given controller bandwidth (omega) diff --git a/ROSCO_toolbox/ofTools/case_gen/CaseLibrary.py b/ROSCO_toolbox/ofTools/case_gen/CaseLibrary.py index 2823ab8a..0422ef38 100644 --- a/ROSCO_toolbox/ofTools/case_gen/CaseLibrary.py +++ b/ROSCO_toolbox/ofTools/case_gen/CaseLibrary.py @@ -34,7 +34,7 @@ def set_channels(): "NcIMUTAxs", "NcIMUTAys", "NcIMUTAzs", "NcIMURAxs", "NcIMURAys", "NcIMURAzs", \ "NacYaw", "Wind1VelX", "Wind1VelY", "Wind1VelZ", "LSSTipMxa","LSSTipMya",\ "LSSTipMza","LSSTipMxs","LSSTipMys","LSSTipMzs","LSShftFys","LSShftFzs", \ - "TipRDxr", "TipRDyr", "TipRDzr","RtVAvgxh","RtAeroFxh"]: + "TipRDxr", "TipRDyr", "TipRDzr","RtVAvgxh","RtAeroFxh", "RtTSR"]: channels[var] = True return channels @@ -532,6 +532,64 @@ def test_pitch_offset(start_group, **control_sweep_opts): case_inputs_control[('DISCON_in','PF_Offsets')] = {'vals': [[0,float(np.radians(2)),0]], 'group': start_group} return case_inputs_control +def sweep_yaml_input(start_group, **control_sweep_opts): + ''' + Sweep any single tuning yaml input + + control_sweep_opts: + control_param: name of parameter + param_values: values of parameter (1D array) + + ''' + + required_inputs = ['control_param', 'param_values'] + check_inputs(control_sweep_opts,required_inputs) + + # load default params + control_param_yaml = control_sweep_opts['tuning_yaml'] + inps = load_rosco_yaml(control_param_yaml) + path_params = inps['path_params'] + turbine_params = inps['turbine_params'] + + # make default controller, turbine objects for ROSCO_toolbox + turbine = ROSCO_turbine.Turbine(turbine_params) + yaml_dir = os.path.dirname(control_param_yaml) + turbine.load_from_fast( path_params['FAST_InputFile'],os.path.join(yaml_dir,path_params['FAST_directory'])) + + + case_inputs = {} + discon_lists = {} + + for param_value in control_sweep_opts['param_values']: + controller_params = control_sweep_opts['controller_params'].copy() + controller_params[control_sweep_opts['control_param']] = param_value + controller = ROSCO_controller.Controller(controller_params) + + # tune default controller + controller.tune_controller(turbine) + + discon_vt = ROSCO_utilities.DISCON_dict(turbine, controller, txt_filename=path_params['rotor_performance_filename']) + + for discon_input in discon_vt: + if discon_input not in discon_lists: # initialize + discon_lists[discon_input] = [] + discon_lists[discon_input].append(discon_vt[discon_input]) + + for discon_input, input in discon_lists.items(): + case_inputs[('DISCON_in',discon_input)] = {'vals': input, 'group': start_group+1} + + case_inputs_control = case_inputs + return case_inputs_control + + +def check_inputs(control_sweep_opts,required_inputs): + for ri in required_inputs: + if ri not in control_sweep_opts: + raise Exception(f'{ri} is required for this control sweep') + + + + diff --git a/ROSCO_toolbox/ofTools/case_gen/run_FAST.py b/ROSCO_toolbox/ofTools/case_gen/run_FAST.py index af567a26..97c6b053 100644 --- a/ROSCO_toolbox/ofTools/case_gen/run_FAST.py +++ b/ROSCO_toolbox/ofTools/case_gen/run_FAST.py @@ -9,8 +9,10 @@ try: from weis.aeroelasticse.runFAST_pywrapper import runFAST_pywrapper_batch + in_weis = True except: from ROSCO_toolbox.ofTools.case_gen.runFAST_pywrapper import runFAST_pywrapper_batch + in_weis = False from ROSCO_toolbox.ofTools.case_gen.CaseGen_IEC import CaseGen_IEC from ROSCO_toolbox.ofTools.case_gen.CaseGen_General import CaseGen_General from ROSCO_toolbox.ofTools.case_gen import CaseLibrary as cl @@ -131,20 +133,30 @@ def run_FAST(self): case_inputs = self.wind_case_fcn(**self.wind_case_opts) case_inputs.update(control_base_case) - # Set up rosco_dll - if not self.rosco_dll: - if platform.system() == 'Windows': - rosco_dll = os.path.join(self.rosco_dir, 'ROSCO/build/libdiscon.dll') - elif platform.system() == 'Darwin': - rosco_dll = os.path.join(self.rosco_dir, 'ROSCO/build/libdiscon.dylib') - else: - rosco_dll = os.path.join(self.rosco_dir, 'ROSCO/build/libdiscon.so') + # Set up dll: + # OS platform + if platform.system() == 'Windows': + dll_ext = '.dll' + elif platform.system() == 'Darwin': + dll_ext = '.dylib' + else: + dll_ext = '.so' + + # lib dir + if not in_weis: # in ROSCO + dll_dir = os.path.join(self.rosco_dir, 'ROSCO/build/') + else: + dll_dir = os.path.join(self.rosco_dir,'../local/lib/') + + if not self.rosco_dll: + self.rosco_dll = os.path.join(dll_dir,'libdiscon'+dll_ext) - case_inputs[('ServoDyn','DLL_FileName')] = {'vals': [rosco_dll], 'group': 0} + case_inputs[('ServoDyn','DLL_FileName')] = {'vals': [self.rosco_dll], 'group': 0} # Sweep control parameter if self.control_sweep_fcn: self.control_sweep_opts['tuning_yaml'] = self.tuning_yaml + self.control_sweep_opts['controller_params'] = controller_params case_inputs_control = self.control_sweep_fcn(cl.find_max_group(case_inputs)+1, **self.control_sweep_opts) sweep_name = self.control_sweep_fcn.__name__ case_inputs.update(case_inputs_control) @@ -214,7 +226,7 @@ def run_FAST(self): if __name__ == "__main__": # Simulation config - sim_config = 3 + sim_config = 8 r = run_FAST_ROSCO() @@ -224,14 +236,12 @@ def run_FAST(self): # FOCAL single wind speed testing r.tuning_yaml = 'IEA15MW.yaml' r.wind_case_fcn = cl.simp_step - r.sweep_mode = None r.save_dir = '/Users/dzalkind/Tools/ROSCO/outputs' elif sim_config == 3: # IEA-22 fixed bottom r.tuning_yaml = '/Users/dzalkind/Projects/IEA-22MW/IEA-22-280-RWT/OpenFAST/IEA-22-280-RWT-Monopile/IEA-22-280-RWT-Monopile.yaml' r.wind_case_fcn = cl.power_curve - r.sweep_mode = None r.wind_case_opts = { 'U': [6,9,12,15], 'TMax': 100, @@ -270,6 +280,26 @@ def run_FAST(self): r.n_cores = 4 + elif sim_config == 8: + + # FOCAL rated wind speed tuning + r.tuning_yaml = 'IEA15MW.yaml' + r.wind_case_fcn = cl.simp_step + r.wind_case_opts = { + 'U_start': [7], + 'U_end': [9], + } + r.sweep_mode = None + r.save_dir = '/Users/dzalkind/Tools/ROSCO1/outputs/VS_Mode_2' + r.control_sweep_fcn = cl.sweep_yaml_input + r.control_sweep_opts = { + 'control_param': 'VS_ControlMode', + 'param_values': [2,3] + } + # r.controller_params = {'VS_ControlMode': 3} + + r.n_cores = 2 + else: raise Exception('This simulation configuration is not supported.') diff --git a/ROSCO_toolbox/ofTools/fast_io/FAST_reader.py b/ROSCO_toolbox/ofTools/fast_io/FAST_reader.py index 8974110b..24bc6ed4 100644 --- a/ROSCO_toolbox/ofTools/fast_io/FAST_reader.py +++ b/ROSCO_toolbox/ofTools/fast_io/FAST_reader.py @@ -209,8 +209,8 @@ def read_MainInput(self): self.fst_vt['Fst']['TrimGain'] = f.readline().split()[0] self.fst_vt['Fst']['Twr_Kdmp'] = f.readline().split()[0] self.fst_vt['Fst']['Bld_Kdmp'] = f.readline().split()[0] - self.fst_vt['Fst']['NLinTimes'] = f.readline().split()[0] - self.fst_vt['Fst']['LinTimes'] = re.findall(r'[^,\s]+', f.readline())[0:2] + self.fst_vt['Fst']['NLinTimes'] = int_read(f.readline().split()[0]) + self.fst_vt['Fst']['LinTimes'] = read_array(f,max(1,self.fst_vt['Fst']['NLinTimes']),int) # read at least 1 self.fst_vt['Fst']['LinInputs'] = f.readline().split()[0] self.fst_vt['Fst']['LinOutputs'] = f.readline().split()[0] self.fst_vt['Fst']['LinOutJac'] = f.readline().split()[0] @@ -1979,7 +1979,10 @@ def read_HydroDyn(self, hd_file): self.fst_vt['HydroDyn']['FillNumM'][i] = int(ln[0]) self.fst_vt['HydroDyn']['FillMList'][i] = [int(j) for j in ln[1:-2]] self.fst_vt['HydroDyn']['FillFSLoc'][i] = float(ln[-2]) - self.fst_vt['HydroDyn']['FillDens'][i] = float(ln[-1]) + if ln[-1] == 'DEFAULT': + self.fst_vt['HydroDyn']['FillDens'][i] = 'DEFAULT' + else: + self.fst_vt['HydroDyn']['FillDens'][i] = float(ln[-1]) #MARINE GROWTH f.readline() diff --git a/ROSCO_toolbox/tune.py b/ROSCO_toolbox/tune.py index 9a10bda1..247067cd 100644 --- a/ROSCO_toolbox/tune.py +++ b/ROSCO_toolbox/tune.py @@ -58,7 +58,7 @@ def update_discon_version(file,tuning_yaml,new_discon_filename): ] # Read original DISCON - discon_vt = read_DISCON(file) + original_vt = read_DISCON(file) # Tune dummy controller to get objects controller, turbine, _ = yaml_to_objs(tuning_yaml) @@ -66,17 +66,54 @@ def update_discon_version(file,tuning_yaml,new_discon_filename): # Load default inputs discon_defaults = DISCON_dict(turbine,controller) - # A simple update doesn't handle type changes + # If no value in old discon, set default to start. Note: a simple update doesn't handle type changes new_discon = {} for param in discon_defaults: # If the value is in the original DISCON and not excluded, use the original - if (param in discon_vt) and (param not in exclude_list): - new_discon[param] = discon_vt[param] + if (param in original_vt) and (param not in exclude_list): + new_discon[param] = original_vt[param] # Otherwise, use the new default else: new_discon[param] = discon_defaults[param] + # Now handle edge cases + + # Torque control: broken into 2 input modes after 2.9.0 + # For newer versions, where VS_ConstPower is not an option, don't do this + if 'VS_ConstPower' not in original_vt: + if original_vt['VS_ControlMode'] == 0: + new_discon['VS_ControlMode'] = 1 + new_discon['VS_ConstPower'] = 0 + elif original_vt['VS_ControlMode'] == 1: + new_discon['VS_ControlMode'] = 1 + new_discon['VS_ConstPower'] = 1 + elif original_vt['VS_ControlMode'] == 2: + new_discon['VS_ControlMode'] = 2 + new_discon['VS_ConstPower'] = 0 + elif original_vt['VS_ControlMode'] == 3: + new_discon['VS_ControlMode'] = 2 + new_discon['VS_ConstPower'] = 1 + + # Notch filters + if 'F_NumNotchFilts' not in original_vt: + if original_vt['F_NotchType'] == 0: + new_discon['F_NumNotchFilts'] = 0 + else: + new_discon['F_NumNotchFilts'] = 1 + new_discon['F_NotchFreqs'] = [original_vt['F_NotchCornerFreq']] + new_discon['F_NotchBetaNum'] = [original_vt['F_NotchBetaNumDen'][0]] + new_discon['F_NotchBetaDen'] = [original_vt['F_NotchBetaNumDen'][1]] + + if original_vt['F_NotchType'] == 1 or original_vt['F_NotchType'] == 3: + new_discon['F_GenSpdNotch_N'] = 1 + new_discon['F_GenSpdNotch_Ind'] = [1] + + if original_vt['F_NotchType'] == 2 or original_vt['F_NotchType'] == 3: + new_discon['F_TwrTopNotch_N'] = 1 + new_discon['F_TwrTopNotch_Ind'] = [1] + + # Make the DISCON write_DISCON( turbine, diff --git a/ROSCO_toolbox/turbine.py b/ROSCO_toolbox/turbine.py index 9aa61932..a900b1f9 100644 --- a/ROSCO_toolbox/turbine.py +++ b/ROSCO_toolbox/turbine.py @@ -86,6 +86,7 @@ def __init__(self, turbine_params): self.bld_edgewise_freq = turbine_params['bld_edgewise_freq'] self.TSR_operational = turbine_params['TSR_operational'] self.bld_flapwise_freq = turbine_params['bld_flapwise_freq'] + self.turbine_params = turbine_params # Allow print out of class @@ -177,8 +178,11 @@ def load_from_fast( fast.read_AeroDyn15() - fast.read_ServoDyn() - fast.read_DISCON_in() + if fast.fst_vt['Fst']['CompServo']: + fast.read_ServoDyn() + fast.read_DISCON_in() + else: + fast.fst_vt['ServoDyn']['GenEff'] = 1.0 if fast.fst_vt['Fst']['CompHydro'] == 1: # SubDyn not yet implimented @@ -202,11 +206,19 @@ def load_from_fast( self.NumBl = fast.fst_vt['ElastoDyn']['NumBl'] self.TowerHt = fast.fst_vt['ElastoDyn']['TowerHt'] self.shearExp = 0.2 #NOTE: HARD CODED + + # Fluid density if 'default' in str(fast.fst_vt['AeroDyn15']['AirDens']): - fast.fst_vt['AeroDyn15']['AirDens'] = 1.225 + if fast.fst_vt['Fst']['MHK']: + fast.fst_vt['AeroDyn15']['AirDens'] = fast.fst_vt['Fst']['WtrDens'] + else: + fast.fst_vt['AeroDyn15']['AirDens'] = fast.fst_vt['Fst']['AirDens'] self.rho = fast.fst_vt['AeroDyn15']['AirDens'] + + # Kinematic viscosity if 'default' in str(fast.fst_vt['AeroDyn15']['KinVisc']): - fast.fst_vt['AeroDyn15']['KinVisc'] = 1.460e-5 + fast.fst_vt['AeroDyn15']['KinVisc'] = fast.fst_vt['Fst']['KinVisc'] + self.mu = fast.fst_vt['AeroDyn15']['KinVisc'] self.Ng = fast.fst_vt['ElastoDyn']['GBRatio'] self.GenEff = fast.fst_vt['ServoDyn']['GenEff'] @@ -538,16 +550,24 @@ def load_blade_info(self): # Read OpenFAST Airfoil data, assumes AeroDyn > v15.03 and associated polars > v1.01 af_dict = {} for i, section in enumerate(self.fast.fst_vt['AeroDyn15']['af_data']): - Alpha = section[0]['Alpha'] if section[0]['NumTabs'] > 1: # sections with multiple airfoil tables - ref_tab = int(np.floor(section[0]['NumTabs']/2)) # get information from "center" table - Re = np.array([section[ref_tab]['Re']])*1e6 + reynolds_ref = self.turbine_params['reynolds_ref'] + if reynolds_ref: # default is 0 + # find closest table to reynolds_ref, interpolate someday, approximate is probably okay + Res_in_table = np.array([sec['Re'] for sec in section]) + ref_tab = np.abs(Res_in_table - reynolds_ref).argmin() + else: + print("ROSCO Warning: No Reynolds number provided and airfoils have multiple tables, using center table") + ref_tab = int(np.floor(section[0]['NumTabs']/2)) # get information from "center" table + Alpha = section[ref_tab]['Alpha'] + Re = np.array([section[ref_tab]['Re']]) Cl = section[ref_tab]['Cl'] Cd = section[ref_tab]['Cd'] Cm = section[ref_tab]['Cm'] af_dict[i] = CCAirfoil(Alpha, Re, Cl, Cd, Cm) - else: # sections without multiple airfoil tables - Re = np.array([section[0]['Re']])*1e6 + else: + Alpha = section[0]['Alpha'] # sections without multiple airfoil tables + Re = np.array([section[0]['Re']]) Cl = section[0]['Cl'] Cd = section[0]['Cd'] Cm = section[0]['Cm'] diff --git a/ROSCO_toolbox/utilities.py b/ROSCO_toolbox/utilities.py index 7f43ab4f..0052dd6a 100644 --- a/ROSCO_toolbox/utilities.py +++ b/ROSCO_toolbox/utilities.py @@ -92,44 +92,50 @@ def write_DISCON(turbine, controller, param_file='DISCON.IN', txt_filename='Cp_C file.write('\n') file.write('!------- SIMULATION CONTROL ------------------------------------------------------------\n') file.write('{0:<12d} ! LoggingLevel - {{0: write no debug files, 1: write standard output .dbg-file, 2: LoggingLevel 1 + ROSCO LocalVars (.dbg2) 3: LoggingLevel 2 + complete avrSWAP-array (.dbg3)}}\n'.format(int(rosco_vt['LoggingLevel']))) - file.write('{} ! DT_Out - {{Time step to output .dbg* files, or 0 to match sampling period of OpenFAST}}\n'.format(rosco_vt['DT_Out'])) + file.write('{} ! DT_Out - {{Time step to output .dbg* files, or 0 to match sampling period of OpenFAST}}\n'.format(rosco_vt['DT_Out'])) file.write('{:<11d} ! Echo - ({})\n'.format(int(rosco_vt['Echo']), input_descriptions['Echo'])) file.write('\n') file.write('!------- CONTROLLER FLAGS -------------------------------------------------\n') - file.write('{0:<12d} ! F_LPFType - (1: first-order low-pass filter, 2: second-order low-pass filter), [rad/s] (currently filters generator speed and pitch control signals\n'.format(int(rosco_vt['F_LPFType']))) - file.write('{0:<12d} ! F_NotchType - Notch on the measured generator speed and/or tower fore-aft motion (for floating) {{0: disable, 1: generator speed, 2: tower-top fore-aft motion, 3: generator speed and tower-top fore-aft motion}}\n'.format(int(rosco_vt['F_NotchType']))) + file.write('{0:<12d} ! F_LPFType - (1: first-order low-pass filter, 2: second-order low-pass filter), [rad/s] (currently filters generator speed and pitch control signals\n'.format(int(rosco_vt['F_LPFType']))) file.write('{0:<12d} ! IPC_ControlMode - Turn Individual Pitch Control (IPC) for fatigue load reductions (pitch contribution) {{0: off, 1: 1P reductions, 2: 1P+2P reductions}}\n'.format(int(rosco_vt['IPC_ControlMode']))) - file.write('{0:<12d} ! VS_ControlMode - Generator torque control mode in above rated conditions {{0: constant torque, 1: constant power, 2: TSR tracking PI control with constant torque, 3: TSR tracking PI control with constant power}}\n'.format(int(rosco_vt['VS_ControlMode']))) - file.write('{0:<12d} ! PC_ControlMode - Blade pitch control mode {{0: No pitch, fix to fine pitch, 1: active PI blade pitch control}}\n'.format(int(rosco_vt['PC_ControlMode']))) - file.write('{0:<12d} ! Y_ControlMode - Yaw control mode {{0: no yaw control, 1: yaw rate control, 2: yaw-by-IPC}}\n'.format(int(rosco_vt['Y_ControlMode']))) - file.write('{0:<12d} ! SS_Mode - Setpoint Smoother mode {{0: no setpoint smoothing, 1: introduce setpoint smoothing}}\n'.format(int(rosco_vt['SS_Mode']))) - file.write('{0:<12d} ! WE_Mode - Wind speed estimator mode {{0: One-second low pass filtered hub height wind speed, 1: Immersion and Invariance Estimator, 2: Extended Kalman Filter}}\n'.format(int(rosco_vt['WE_Mode']))) - file.write('{0:<12d} ! PS_Mode - Pitch saturation mode {{0: no pitch saturation, 1: implement pitch saturation}}\n'.format(int(rosco_vt['PS_Mode']))) - file.write('{0:<12d} ! SD_Mode - Shutdown mode {{0: no shutdown procedure, 1: pitch to max pitch at shutdown}}\n'.format(int(rosco_vt['SD_Mode']))) - file.write('{0:<12d} ! Fl_Mode - Floating specific feedback mode {{0: no nacelle velocity feedback, 1: feed back translational velocity, 2: feed back rotational veloicty}}\n'.format(int(rosco_vt['Fl_Mode']))) - file.write('{0:<12d} ! TD_Mode - Tower damper mode {{0: no tower damper, 1: feed back translational nacelle accelleration to pitch angle}}\n'.format(int(rosco_vt['TD_Mode']))) - file.write('{0:<12d} ! Flp_Mode - Flap control mode {{0: no flap control, 1: steady state flap angle, 2: Proportional flap control, 2: Cyclic (1P) flap control}}\n'.format(int(rosco_vt['Flp_Mode']))) - file.write('{0:<12d} ! OL_Mode - Open loop control mode {{0: no open loop control, 1: open loop control vs. time, 2: rotor position control}}\n'.format(int(rosco_vt['OL_Mode']))) - file.write('{0:<12d} ! PA_Mode - Pitch actuator mode {{0 - not used, 1 - first order filter, 2 - second order filter}}\n'.format(int(rosco_vt['PA_Mode']))) - file.write('{0:<12d} ! PF_Mode - Pitch fault mode {{0 - not used, 1 - constant offset on one or more blades}}\n'.format(int(rosco_vt['PF_Mode']))) - file.write('{0:<12d} ! AWC_Mode - Active wake control {{0 - not used, 1 - complex number method, 2 - Coleman transform method}}\n'.format(int(rosco_vt['AWC_Mode']))) - file.write('{0:<12d} ! Ext_Mode - External control mode {{0 - not used, 1 - call external dynamic library}}\n'.format(int(rosco_vt['Ext_Mode']))) - file.write('{0:<12d} ! ZMQ_Mode - Fuse ZeroMQ interface {{0: unused, 1: Yaw Control}}\n'.format(int(rosco_vt['ZMQ_Mode']))) - file.write('{:<12d} ! CC_Mode - {}\n'.format(int(rosco_vt['CC_Mode']),mode_descriptions['CC_Mode'])) - file.write('{:<12d} ! StC_Mode - {}\n'.format(int(rosco_vt['StC_Mode']),mode_descriptions['StC_Mode'])) + file.write('{0:<12d} ! VS_ControlMode - Generator torque control mode in above rated conditions (0- no torque control, 1- k*omega^2 with PI transitions, 2- WSE TSR Tracking, 3- Power-based TSR Tracking)}}\n'.format(int(rosco_vt['VS_ControlMode']))) + file.write('{0:<12d} ! VS_ConstPower - Do constant power torque control, where above rated torque varies, 0 for constant torque}}\n'.format(int(rosco_vt['VS_ConstPower']))) + file.write('{0:<12d} ! PC_ControlMode - Blade pitch control mode {{0: No pitch, fix to fine pitch, 1: active PI blade pitch control}}\n'.format(int(rosco_vt['PC_ControlMode']))) + file.write('{0:<12d} ! Y_ControlMode - Yaw control mode {{0: no yaw control, 1: yaw rate control, 2: yaw-by-IPC}}\n'.format(int(rosco_vt['Y_ControlMode']))) + file.write('{0:<12d} ! SS_Mode - Setpoint Smoother mode {{0: no setpoint smoothing, 1: introduce setpoint smoothing}}\n'.format(int(rosco_vt['SS_Mode']))) + file.write('{0:<12d} ! WE_Mode - Wind speed estimator mode {{0: One-second low pass filtered hub height wind speed, 1: Immersion and Invariance Estimator, 2: Extended Kalman Filter}}\n'.format(int(rosco_vt['WE_Mode']))) + file.write('{0:<12d} ! PS_Mode - Pitch saturation mode {{0: no pitch saturation, 1: implement pitch saturation}}\n'.format(int(rosco_vt['PS_Mode']))) + file.write('{0:<12d} ! SD_Mode - Shutdown mode {{0: no shutdown procedure, 1: pitch to max pitch at shutdown}}\n'.format(int(rosco_vt['SD_Mode']))) + file.write('{0:<12d} ! Fl_Mode - Floating specific feedback mode {{0: no nacelle velocity feedback, 1: feed back translational velocity, 2: feed back rotational veloicty}}\n'.format(int(rosco_vt['Fl_Mode']))) + file.write('{0:<12d} ! TD_Mode - Tower damper mode {{0: no tower damper, 1: feed back translational nacelle accelleration to pitch angle}}\n'.format(int(rosco_vt['TD_Mode']))) + file.write('{0:<12d} ! Flp_Mode - Flap control mode {{0: no flap control, 1: steady state flap angle, 2: Proportional flap control, 2: Cyclic (1P) flap control}}\n'.format(int(rosco_vt['Flp_Mode']))) + file.write('{0:<12d} ! OL_Mode - Open loop control mode {{0: no open loop control, 1: open loop control vs. time, 2: rotor position control}}\n'.format(int(rosco_vt['OL_Mode']))) + file.write('{0:<12d} ! PA_Mode - Pitch actuator mode {{0 - not used, 1 - first order filter, 2 - second order filter}}\n'.format(int(rosco_vt['PA_Mode']))) + file.write('{0:<12d} ! PF_Mode - Pitch fault mode {{0 - not used, 1 - constant offset on one or more blades}}\n'.format(int(rosco_vt['PF_Mode']))) + file.write('{0:<12d} ! AWC_Mode - Active wake control {{0 - not used, 1 - complex number method, 2 - Coleman transform method}}\n'.format(int(rosco_vt['AWC_Mode']))) + file.write('{0:<12d} ! Ext_Mode - External control mode {{0 - not used, 1 - call external dynamic library}}\n'.format(int(rosco_vt['Ext_Mode']))) + file.write('{0:<12d} ! ZMQ_Mode - Fuse ZeroMQ interface {{0: unused, 1: Yaw Control}}\n'.format(int(rosco_vt['ZMQ_Mode']))) + file.write('{:<12d} ! CC_Mode - {}\n'.format(int(rosco_vt['CC_Mode']),mode_descriptions['CC_Mode'])) + file.write('{:<12d} ! StC_Mode - {}\n'.format(int(rosco_vt['StC_Mode']),mode_descriptions['StC_Mode'])) file.write('\n') file.write('!------- FILTERS ----------------------------------------------------------\n') - file.write('{:<13.5f} ! F_LPFCornerFreq - Corner frequency (-3dB point) in the low-pass filters, [rad/s]\n'.format(rosco_vt['F_LPFCornerFreq'])) - file.write('{:<13.5f} ! F_LPFDamping - Damping coefficient {{used only when F_FilterType = 2}} [-]\n'.format(rosco_vt['F_LPFDamping'])) - file.write('{:<13.5f} ! F_NotchCornerFreq - Natural frequency of the notch filter, [rad/s]\n'.format(rosco_vt['F_NotchCornerFreq'])) - file.write('{}! F_NotchBetaNumDen - Two notch damping values (numerator and denominator, resp) - determines the width and depth of the notch, [-]\n'.format(''.join('{:<4.6f} '.format(rosco_vt['F_NotchBetaNumDen'][i]) for i in range(len(rosco_vt['F_NotchBetaNumDen']))))) + file.write('{:<13.5f} ! F_LPFCornerFreq - Corner frequency (-3dB point) in the low-pass filters, [rad/s]\n'.format(rosco_vt['F_LPFCornerFreq'])) + file.write('{:<13.5f} ! F_LPFDamping - Damping coefficient {{used only when F_FilterType = 2}} [-]\n'.format(rosco_vt['F_LPFDamping'])) + file.write('{:<12d} ! F_NumNotchFilts - {}\n'.format(int(rosco_vt["F_NumNotchFilts"]), input_descriptions["F_NumNotchFilts"])) + file.write('{} ! F_NotchFreqs - {}\n'.format(write_array(rosco_vt["F_NotchFreqs"]), input_descriptions["F_NotchFreqs"])) + file.write('{} ! F_NotchBetaNum - {}\n'.format(write_array(rosco_vt['F_NotchBetaNum']), input_descriptions["F_NotchBetaNum"])) + file.write('{} ! F_NotchBetaDen - {}\n'.format(write_array(rosco_vt['F_NotchBetaDen']), input_descriptions["F_NotchBetaDen"])) + file.write('{:<12d} ! F_GenSpdNotch_N - {}\n'.format(int(rosco_vt['F_GenSpdNotch_N']), input_descriptions["F_GenSpdNotch_N"])) + file.write('{} ! F_GenSpdNotch_Ind - {}\n'.format(write_array(rosco_vt['F_GenSpdNotch_Ind'],'d'), input_descriptions["F_GenSpdNotch_Ind"])) + file.write('{:<12d} ! F_TwrTopNotch_N - {}\n'.format(int(rosco_vt['F_TwrTopNotch_N']), input_descriptions["F_TwrTopNotch_N"])) + file.write('{} ! F_TwrTopNotch_Ind - {}\n'.format(write_array(rosco_vt['F_TwrTopNotch_Ind'],'d'), input_descriptions["F_TwrTopNotch_Ind"])) file.write('{:<13.5f} ! F_SSCornerFreq - Corner frequency (-3dB point) in the first order low pass filter for the setpoint smoother, [rad/s].\n'.format(rosco_vt['F_SSCornerFreq'])) file.write('{:<13.5f} ! F_WECornerFreq - Corner frequency (-3dB point) in the first order low pass filter for the wind speed estimate [rad/s].\n'.format(rosco_vt['F_WECornerFreq'])) file.write('{:<13.5f} ! F_YawErr - Low pass filter corner frequency for yaw controller [rad/s].\n'.format(rosco_vt['F_YawErr'])) file.write('{}! F_FlCornerFreq - Natural frequency and damping in the second order low pass filter of the tower-top fore-aft motion for floating feedback control [rad/s, -].\n'.format(''.join('{:<4.6f} '.format(rosco_vt['F_FlCornerFreq'][i]) for i in range(len(rosco_vt['F_FlCornerFreq']))))) - file.write('{:<13.5f} ! F_FlHighPassFreq - Natural frequency of first-order high-pass filter for nacelle fore-aft motion [rad/s].\n'.format(rosco_vt['F_FlHighPassFreq'])) - file.write('{}! F_FlpCornerFreq - Corner frequency and damping in the second order low pass filter of the blade root bending moment for flap control [rad/s, -].\n'.format(''.join('{:<4.6f} '.format(rosco_vt['F_FlpCornerFreq'][i]) for i in range(len(rosco_vt['F_FlpCornerFreq']))))) + file.write('{:<13.5f} ! F_FlHighPassFreq - Natural frequency of first-order high-pass filter for nacelle fore-aft motion [rad/s].\n'.format(rosco_vt['F_FlHighPassFreq'])) + file.write('{} ! F_FlpCornerFreq - {}\n'.format(write_array(rosco_vt["F_FlpCornerFreq"]), input_descriptions["F_FlpCornerFreq"])) file.write('\n') file.write('!------- BLADE PITCH CONTROL ----------------------------------------------\n') @@ -163,14 +169,15 @@ def write_DISCON(turbine, controller, param_file='DISCON.IN', txt_filename='Cp_C file.write('{:<014.5f} ! VS_MaxTq - Maximum generator torque in Region 3 (HSS side), [Nm].\n'.format(rosco_vt['VS_MaxTq'])) file.write('{:<014.5f} ! VS_MinTq - Minimum generator torque (HSS side), [Nm].\n'.format(rosco_vt['VS_MinTq'])) file.write('{:<014.5f} ! VS_MinOMSpd - Minimum generator speed [rad/s]\n'.format(rosco_vt['VS_MinOMSpd'])) - file.write('{:<014.5f} ! VS_Rgn2K - Generator torque constant in Region 2 (HSS side), [Nm/(rad/s)^2]\n'.format(rosco_vt['VS_Rgn2K'])) + file.write('{:<014.5f} ! VS_Rgn2K - {}\n'.format(float(rosco_vt['VS_Rgn2K']),input_descriptions['VS_Rgn2K'])) file.write('{:<014.5f} ! VS_RtPwr - Wind turbine rated power [W]\n'.format(rosco_vt['VS_RtPwr'])) file.write('{:<014.5f} ! VS_RtTq - Rated torque, [Nm].\n'.format(rosco_vt['VS_RtTq'])) file.write('{:<014.5f} ! VS_RefSpd - Rated generator speed [rad/s]\n'.format(rosco_vt['VS_RefSpd'])) file.write('{:<11d} ! VS_n - Number of generator PI torque controller gains\n'.format(int(rosco_vt['VS_n']))) file.write('{:<014.5f} ! VS_KP - Proportional gain for generator PI torque controller [-]. (Only used in the transitional 2.5 region if VS_ControlMode =/ 2)\n'.format(rosco_vt['VS_KP'])) file.write('{:<014.5f} ! VS_KI - Integral gain for generator PI torque controller [s]. (Only used in the transitional 2.5 region if VS_ControlMode =/ 2)\n'.format(rosco_vt['VS_KI'])) - file.write('{:<13.2f} ! VS_TSRopt - Power-maximizing region 2 tip-speed-ratio [rad].\n'.format(rosco_vt['VS_TSRopt'])) + file.write('{:<13.2f} ! VS_TSRopt - {}\n'.format(float(rosco_vt['VS_TSRopt']),input_descriptions['VS_TSRopt'])) + file.write('{:<014.5f} ! VS_PwrFiltF - {}\n'.format(float(rosco_vt['VS_PwrFiltF']),input_descriptions['VS_PwrFiltF'])) file.write('\n') file.write('!------- SETPOINT SMOOTHER ---------------------------------------------\n') file.write('{:<13.5f} ! SS_VSGain - Variable speed torque controller setpoint smoother gain, [-].\n'.format(rosco_vt['SS_VSGain'])) @@ -180,9 +187,9 @@ def write_DISCON(turbine, controller, param_file='DISCON.IN', txt_filename='Cp_C file.write('{:<13.3f} ! WE_BladeRadius - Blade length (distance from hub center to blade tip), [m]\n'.format(rosco_vt['WE_BladeRadius'])) file.write('{:<11d} ! WE_CP_n - Amount of parameters in the Cp array\n'.format(int(rosco_vt['WE_CP_n']))) file.write('{:<13.1f} ! WE_CP - Parameters that define the parameterized CP(lambda) function\n'.format(rosco_vt['WE_CP'])) - file.write('{:<13.1f} ! WE_Gamma - Adaption gain of the wind speed estimator algorithm [m/rad]\n'.format(rosco_vt['WE_Gamma'])) + file.write('{:<13.1f} ! WE_Gamma - Adaption gain of the wind speed estimator algorithm [m/rad]\n'.format(rosco_vt['WE_Gamma'])) file.write('{:<13.1f} ! WE_GearboxRatio - Gearbox ratio [>=1], [-]\n'.format(rosco_vt['WE_GearboxRatio'])) - file.write('{:<14.5f} ! WE_Jtot - Total drivetrain inertia, including blades, hub and casted generator inertia to LSS, [kg m^2]\n'.format(rosco_vt['WE_Jtot'])) + file.write('{:<14.5f} ! WE_Jtot - Total drivetrain inertia, including blades, hub and casted generator inertia to LSS, [kg m^2]\n'.format(rosco_vt['WE_Jtot'])) file.write('{:<13.3f} ! WE_RhoAir - Air density, [kg m^-3]\n'.format(rosco_vt['WE_RhoAir'])) file.write( '"{}" ! PerfFileName - File containing rotor performance tables (Cp,Ct,Cq) (absolute path or relative to this file)\n'.format(rosco_vt['PerfFileName'])) file.write('{:<7d} {:<10d} ! 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(int(rosco_vt['PerfTableSize'][0]),int(rosco_vt['PerfTableSize'][1]))) @@ -218,9 +225,9 @@ def write_DISCON(turbine, controller, param_file='DISCON.IN', txt_filename='Cp_C floatstr = 'pitching' else: floatstr = 'velocity' - file.write('{:<11d} ! Fl_n - Number of Fl_Kp gains in gain scheduling, optional with default of 1\n'.format(int(rosco_vt['Fl_n']))) - file.write('{} ! Fl_Kp - Nacelle {} proportional feedback gain [s]\n'.format(write_array(rosco_vt['Fl_Kp'],'<6.4f'), floatstr)) - file.write('{} ! Fl_U - Wind speeds for scheduling Fl_Kp, optional if Fl_Kp is single value [m/s]\n'.format(write_array(rosco_vt['Fl_U'],'<6.4f'))) + file.write('{:<11d} ! Fl_n - Number of Fl_Kp gains in gain scheduling, optional with default of 1\n'.format(int(rosco_vt['Fl_n']))) + file.write('{} ! Fl_Kp - Nacelle {} proportional feedback gain [s]\n'.format(write_array(rosco_vt['Fl_Kp'],'<6.4f'), floatstr)) + file.write('{} ! Fl_U - Wind speeds for scheduling Fl_Kp, optional if Fl_Kp is single value [m/s]\n'.format(write_array(rosco_vt['Fl_U'],'<6.4f'))) file.write('\n') file.write('!------- FLAP ACTUATION -----------------------------------------------------\n') file.write('{:<014.5f} ! Flp_Angle - Initial or steady state flap angle [rad]\n'.format(rosco_vt['Flp_Angle'])) @@ -236,23 +243,23 @@ def write_DISCON(turbine, controller, param_file='DISCON.IN', txt_filename='Cp_C file.write('{0:<12d} ! Ind_YawRate - The column in OL_Filename that contains the yaw rate in rad/s\n'.format(int(rosco_vt['Ind_YawRate']))) file.write('{:<12d} ! Ind_Azimuth - {}\n'.format(int(rosco_vt["Ind_Azimuth"]), input_descriptions["Ind_Azimuth"])) file.write('{} ! {} - {}\n'.format(' '.join([f'{g:02.4f}' for g in rosco_vt["RP_Gains"]]),"RP_Gains",input_descriptions["RP_Gains"])) - file.write('{} ! Ind_CableControl - The column(s) in OL_Filename that contains the cable control inputs in m [Used with CC_Mode = 2, must be the same size as CC_Group_N]\n'.format(write_array(rosco_vt['Ind_CableControl'],'<4d'))) - file.write('{} ! Ind_StructControl - The column(s) in OL_Filename that contains the structural control inputs [Used with StC_Mode = 2, must be the same size as StC_Group_N]\n'.format(write_array(rosco_vt['Ind_StructControl'],'<4d'))) + file.write('{} ! Ind_CableControl - The column(s) in OL_Filename that contains the cable control inputs in m [Used with CC_Mode = 2, must be the same size as CC_Group_N]\n'.format(write_array(rosco_vt['Ind_CableControl'],'<4d'))) + file.write('{} ! Ind_StructControl - The column(s) in OL_Filename that contains the structural control inputs [Used with StC_Mode = 2, must be the same size as StC_Group_N]\n'.format(write_array(rosco_vt['Ind_StructControl'],'<4d'))) file.write('\n') file.write('!------- Pitch Actuator Model -----------------------------------------------------\n') - file.write('{:<014.5f} ! PA_CornerFreq - Pitch actuator bandwidth/cut-off frequency [rad/s]\n'.format(rosco_vt['PA_CornerFreq'])) - file.write('{:<014.5f} ! PA_Damping - Pitch actuator damping ratio [-, unused if PA_Mode = 1]\n'.format(rosco_vt['PA_Damping'])) + file.write('{:<014.5f} ! PA_CornerFreq - Pitch actuator bandwidth/cut-off frequency [rad/s]\n'.format(rosco_vt['PA_CornerFreq'])) + file.write('{:<014.5f} ! PA_Damping - Pitch actuator damping ratio [-, unused if PA_Mode = 1]\n'.format(rosco_vt['PA_Damping'])) file.write('\n') file.write('!------- Pitch Actuator Faults -----------------------------------------------------\n') file.write('{} ! PF_Offsets - Constant blade pitch offsets for blades 1-3 [rad]\n'.format(''.join('{:<10.8f} '.format(rosco_vt['PF_Offsets'][i]) for i in range(3)))) file.write('\n') file.write('!------- Active Wake Control -----------------------------------------------------\n') - file.write('{0:<12d} ! AWC_NumModes - Number of user-defined AWC forcing modes \n'.format(int(rosco_vt['AWC_NumModes']))) - file.write('{} ! AWC_n - Azimuthal mode number(s) (i.e., the number and direction of the lobes of the wake structure)\n'.format(write_array(rosco_vt['AWC_n'],'<4d'))) - file.write('{} ! AWC_harmonic - Harmonic(s) to apply in the AWC Inverse Coleman Transformation (only used when AWC_Mode = 2)\n'.format(write_array(rosco_vt['AWC_harmonic'],'<4d'))) - file.write('{} ! AWC_freq - Frequency(s) of forcing mode(s) [Hz]\n'.format(write_array(rosco_vt['AWC_freq'],'<6.4f'))) - file.write('{} ! AWC_amp - Pitch amplitude(s) of individual forcing mode(s) [deg]\n'.format(write_array(rosco_vt['AWC_amp'],'<6.4f'))) - file.write('{} ! AWC_clockangle - Initial angle(s) of forcing mode(s) [deg]\n'.format(write_array(rosco_vt['AWC_clockangle'],'<6.4f'))) + file.write('{0:<12d} ! AWC_NumModes - Number of user-defined AWC forcing modes \n'.format(int(rosco_vt['AWC_NumModes']))) + file.write('{} ! AWC_n - Azimuthal mode number(s) (i.e., the number and direction of the lobes of the wake structure)\n'.format(write_array(rosco_vt['AWC_n'],'<4d'))) + file.write('{} ! AWC_harmonic - Harmonic(s) to apply in the AWC Inverse Coleman Transformation (only used when AWC_Mode = 2)\n'.format(write_array(rosco_vt['AWC_harmonic'],'<4d'))) + file.write('{} ! AWC_freq - Frequency(s) of forcing mode(s) [Hz]\n'.format(write_array(rosco_vt['AWC_freq'],'<6.4f'))) + file.write('{} ! AWC_amp - Pitch amplitude(s) of individual forcing mode(s) [deg]\n'.format(write_array(rosco_vt['AWC_amp'],'<6.4f'))) + file.write('{} ! AWC_clockangle - Initial angle(s) of forcing mode(s) [deg]\n'.format(write_array(rosco_vt['AWC_clockangle'],'<6.4f'))) file.write('\n') file.write('!------- External Controller Interface -----------------------------------------------------\n') file.write('"{}" ! DLL_FileName - Name/location of the dynamic library in the Bladed-DLL format\n'.format(rosco_vt['DLL_FileName'])) @@ -265,12 +272,12 @@ def write_DISCON(turbine, controller, param_file='DISCON.IN', txt_filename='Cp_C file.write('\n') file.write('!------- Cable Control ---------------------------------------------------------\n') file.write('{:<11d} ! CC_Group_N - {}\n'.format(len(rosco_vt['CC_GroupIndex']), input_descriptions['CC_Group_N'])) - file.write('{:^11s} ! CC_GroupIndex - {}\n'.format(write_array(rosco_vt['CC_GroupIndex'],'<6d'), input_descriptions['CC_GroupIndex'])) + file.write('{:^11s} ! CC_GroupIndex - {}\n'.format(write_array(rosco_vt['CC_GroupIndex'],'<6d'), input_descriptions['CC_GroupIndex'])) file.write('{:<11f} ! CC_ActTau - {}\n'.format(rosco_vt['CC_ActTau'], input_descriptions['CC_ActTau'] )) file.write('\n') file.write('!------- Structural Controllers ---------------------------------------------------------\n') file.write('{:<11d} ! StC_Group_N - {}\n'.format(len(rosco_vt['StC_GroupIndex']), input_descriptions['StC_Group_N'])) - file.write('{:^11s} ! StC_GroupIndex - {}\n'.format(write_array(rosco_vt['StC_GroupIndex'],'<6d'), input_descriptions['StC_GroupIndex'])) + file.write('{:^11s} ! StC_GroupIndex - {}\n'.format(write_array(rosco_vt['StC_GroupIndex'],'<6d'), input_descriptions['StC_GroupIndex'])) file.close() @@ -455,6 +462,7 @@ def DISCON_dict(turbine, controller, txt_filename=None): DISCON_dict['F_NotchType'] = int(controller.F_NotchType) DISCON_dict['IPC_ControlMode'] = int(controller.IPC_ControlMode) DISCON_dict['VS_ControlMode'] = int(controller.VS_ControlMode) + DISCON_dict['VS_ConstPower'] = int(controller.VS_ConstPower) DISCON_dict['PC_ControlMode'] = int(controller.PC_ControlMode) DISCON_dict['Y_ControlMode'] = int(controller.Y_ControlMode) DISCON_dict['SS_Mode'] = int(controller.SS_Mode) @@ -475,12 +483,14 @@ def DISCON_dict(turbine, controller, txt_filename=None): # ------- FILTERS ------- DISCON_dict['F_LPFCornerFreq'] = turbine.bld_edgewise_freq * 1/4 DISCON_dict['F_LPFDamping'] = controller.F_LPFDamping - if controller.Flp_Mode > 0: - DISCON_dict['F_NotchCornerFreq'] = turbine.bld_flapwise_freq - DISCON_dict['F_NotchBetaNumDen'] = [0.0, 0.5] - else: - DISCON_dict['F_NotchCornerFreq'] = controller.twr_freq - DISCON_dict['F_NotchBetaNumDen'] = [0.0, 0.25] + DISCON_dict['F_NumNotchFilts'] = len(controller.f_notch_freqs) + DISCON_dict['F_NotchFreqs'] = controller.f_notch_freqs if controller.f_notch_freqs else [0.0] + DISCON_dict['F_NotchBetaNum'] = controller.f_notch_beta_nums if controller.f_notch_beta_nums else [0.0] + DISCON_dict['F_NotchBetaDen'] = controller.f_notch_beta_dens if controller.f_notch_beta_dens else [0.0] + DISCON_dict['F_GenSpdNotch_N'] = len(controller.f_notch_gen_inds) + DISCON_dict['F_GenSpdNotch_Ind'] = controller.f_notch_gen_inds if controller.f_notch_gen_inds else [0] + DISCON_dict['F_TwrTopNotch_N'] = len(controller.f_notch_twr_inds) + DISCON_dict['F_TwrTopNotch_Ind'] = controller.f_notch_twr_inds if controller.f_notch_twr_inds else [0] DISCON_dict['F_WECornerFreq'] = controller.f_we_cornerfreq DISCON_dict['F_SSCornerFreq'] = controller.f_ss_cornerfreq DISCON_dict['F_FlHighPassFreq'] = controller.f_fl_highpassfreq @@ -682,7 +692,7 @@ def list_check(x, return_bool=True): else: return y -def write_array(array,format='<.4f'): +def write_array(array,format='<.4f',line_width=12): if not hasattr(array,'__len__'): #not an array array = [array] @@ -691,4 +701,4 @@ def write_array(array,format='<.4f'): if 'd' in format and type(array[0]) != int: array = [int(a) for a in array] - return ''.join(['{:{}} '.format(item,format) for item in array]) + return ''.join(['{:{}} '.format(item,format) for item in array]).ljust(line_width) diff --git a/Test_Cases/BAR_10/BAR_10_DISCON.IN b/Test_Cases/BAR_10/BAR_10_DISCON.IN index 64e561d6..580693cd 100644 --- a/Test_Cases/BAR_10/BAR_10_DISCON.IN +++ b/Test_Cases/BAR_10/BAR_10_DISCON.IN @@ -1,45 +1,51 @@ ! Controller parameter input file for the BAR_10 wind turbine -! - File written using ROSCO version 2.8.0 controller tuning logic on 08/03/23 +! - File written using ROSCO version 2.8.0 controller tuning logic on 08/23/23 !------- SIMULATION CONTROL ------------------------------------------------------------ 1 ! LoggingLevel - {0: write no debug files, 1: write standard output .dbg-file, 2: LoggingLevel 1 + ROSCO LocalVars (.dbg2) 3: LoggingLevel 2 + complete avrSWAP-array (.dbg3)} -0 ! DT_Out - {Time step to output .dbg* files, or 0 to match sampling period of OpenFAST} +0 ! DT_Out - {Time step to output .dbg* files, or 0 to match sampling period of OpenFAST} 0 ! Echo - (0 - no Echo, 1 - Echo input data to .echo) !------- CONTROLLER FLAGS ------------------------------------------------- -2 ! 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 and/or tower fore-aft motion (for floating) {0: disable, 1: generator speed, 2: tower-top fore-aft motion, 3: generator speed and tower-top fore-aft motion} +2 ! 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 ! 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 with constant torque, 3: TSR tracking PI control with constant power} -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: Immersion and Invariance Estimator, 2: Extended Kalman Filter} -1 ! PS_Mode - Pitch saturation mode {0: no pitch saturation, 1: implement pitch saturation} -0 ! SD_Mode - Shutdown mode {0: no shutdown procedure, 1: pitch to max pitch at shutdown} -0 ! Fl_Mode - Floating specific feedback mode {0: no nacelle velocity feedback, 1: feed back translational velocity, 2: feed back rotational veloicty} -0 ! TD_Mode - Tower damper mode {0: no tower damper, 1: feed back translational nacelle accelleration to pitch angle} -2 ! Flp_Mode - Flap control mode {0: no flap control, 1: steady state flap angle, 2: Proportional flap control, 2: Cyclic (1P) flap control} -0 ! OL_Mode - Open loop control mode {0: no open loop control, 1: open loop control vs. time, 2: rotor position control} -0 ! PA_Mode - Pitch actuator mode {0 - not used, 1 - first order filter, 2 - second order filter} -0 ! PF_Mode - Pitch fault mode {0 - not used, 1 - constant offset on one or more blades} -0 ! AWC_Mode - Active wake control {0 - not used, 1 - complex number method, 2 - Coleman transform method} -0 ! Ext_Mode - External control mode {0 - not used, 1 - call external dynamic library} -0 ! ZMQ_Mode - Fuse ZeroMQ interface {0: unused, 1: Yaw Control} -0 ! CC_Mode - Cable control mode [0- unused, 1- User defined, 2- Open loop control] -0 ! StC_Mode - Structural control mode [0- unused, 1- User defined, 2- Open loop control] +2 ! VS_ControlMode - Generator torque control mode in above rated conditions (0- no torque control, 1- k*omega^2 with PI transitions, 2- WSE TSR Tracking, 3- Power-based TSR Tracking)} +0 ! VS_ConstPower - Do constant power torque control, where above rated torque varies, 0 for constant torque} +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: Immersion and Invariance Estimator, 2: Extended Kalman Filter} +1 ! PS_Mode - Pitch saturation mode {0: no pitch saturation, 1: implement pitch saturation} +0 ! SD_Mode - Shutdown mode {0: no shutdown procedure, 1: pitch to max pitch at shutdown} +0 ! Fl_Mode - Floating specific feedback mode {0: no nacelle velocity feedback, 1: feed back translational velocity, 2: feed back rotational veloicty} +0 ! TD_Mode - Tower damper mode {0: no tower damper, 1: feed back translational nacelle accelleration to pitch angle} +2 ! Flp_Mode - Flap control mode {0: no flap control, 1: steady state flap angle, 2: Proportional flap control, 2: Cyclic (1P) flap control} +0 ! OL_Mode - Open loop control mode {0: no open loop control, 1: open loop control vs. time, 2: rotor position control} +0 ! PA_Mode - Pitch actuator mode {0 - not used, 1 - first order filter, 2 - second order filter} +0 ! PF_Mode - Pitch fault mode {0 - not used, 1 - constant offset on one or more blades} +0 ! AWC_Mode - Active wake control {0 - not used, 1 - complex number method, 2 - Coleman transform method} +0 ! Ext_Mode - External control mode {0 - not used, 1 - call external dynamic library} +0 ! ZMQ_Mode - Fuse ZeroMQ interface {0: unused, 1: Yaw Control} +0 ! CC_Mode - Cable control mode [0- unused, 1- User defined, 2- Open loop control] +0 ! StC_Mode - Structural control mode [0- unused, 1- User defined, 2- Open loop control] !------- FILTERS ---------------------------------------------------------- -0.81771 ! F_LPFCornerFreq - Corner frequency (-3dB point) in the low-pass filters, [rad/s] -0.70000 ! F_LPFDamping - Damping coefficient {used only when F_FilterType = 2} [-] -2.61601 ! F_NotchCornerFreq - Natural frequency of the notch filter, [rad/s] -0.000000 0.500000 ! F_NotchBetaNumDen - Two notch damping values (numerator and denominator, resp) - determines the width and depth of the notch, [-] +0.81771 ! F_LPFCornerFreq - Corner frequency (-3dB point) in the low-pass filters, [rad/s] +0.70000 ! F_LPFDamping - Damping coefficient {used only when F_FilterType = 2} [-] +0 ! F_NumNotchFilts - Number of notch filters placed on sensors +0.0000 ! F_NotchFreqs - Natural frequency of the notch filters. Array with length F_NumNotchFilts +0.0000 ! F_NotchBetaNum - Damping value of numerator (determines the width of notch). Array with length F_NumNotchFilts, [-] +0.0000 ! F_NotchBetaDen - Damping value of denominator (determines the depth of notch). Array with length F_NumNotchFilts, [-] +0 ! F_GenSpdNotch_N - Number of notch filters on generator speed +0 ! F_GenSpdNotch_Ind - Indices of notch filters on generator speed +0 ! F_TwrTopNotch_N - Number of notch filters on tower top acceleration signal +0 ! F_TwrTopNotch_Ind - Indices of notch filters on tower top acceleration signal 0.62830 ! F_SSCornerFreq - Corner frequency (-3dB point) in the first order low pass filter for the setpoint smoother, [rad/s]. 0.20944 ! F_WECornerFreq - Corner frequency (-3dB point) in the first order low pass filter for the wind speed estimate [rad/s]. 0.17952 ! F_YawErr - Low pass filter corner frequency for yaw controller [rad/s]. 0.000000 1.000000 ! F_FlCornerFreq - Natural frequency and damping in the second order low pass filter of the tower-top fore-aft motion for floating feedback control [rad/s, -]. -0.01042 ! F_FlHighPassFreq - Natural frequency of first-order high-pass filter for nacelle fore-aft motion [rad/s]. -7.848030 1.000000 ! F_FlpCornerFreq - Corner frequency and damping in the second order low pass filter of the blade root bending moment for flap control [rad/s, -]. +0.01042 ! F_FlHighPassFreq - Natural frequency of first-order high-pass filter for nacelle fore-aft motion [rad/s]. +7.8480 1.0000 ! F_FlpCornerFreq - Corner frequency and damping in the second order low pass filter of the blade root bending moment for flap control !------- BLADE PITCH CONTROL ---------------------------------------------- 30 ! PC_GS_n - Amount of gain-scheduling table entries @@ -72,14 +78,15 @@ 70282.09458000 ! VS_MaxTq - Maximum generator torque in Region 3 (HSS side), [Nm]. 0.000000000000 ! VS_MinTq - Minimum generator torque (HSS side), [Nm]. 27.49717000000 ! VS_MinOMSpd - Minimum generator speed [rad/s] -12.67229000000 ! VS_Rgn2K - Generator torque constant in Region 2 (HSS side), [Nm/(rad/s)^2] +11.20801000000 ! VS_Rgn2K - Generator torque constant in Region 2 (HSS side). Only used in VS_ControlMode = 1,3 5000000.000000 ! VS_RtPwr - Wind turbine rated power [W] 63892.81326000 ! VS_RtTq - Rated torque, [Nm]. 75.83317000000 ! VS_RefSpd - Rated generator speed [rad/s] 1 ! VS_n - Number of generator PI torque controller gains -2452.07948000 ! VS_KP - Proportional gain for generator PI torque controller [-]. (Only used in the transitional 2.5 region if VS_ControlMode =/ 2) -332.357190000 ! VS_KI - Integral gain for generator PI torque controller [s]. (Only used in the transitional 2.5 region if VS_ControlMode =/ 2) -9.76 ! VS_TSRopt - Power-maximizing region 2 tip-speed-ratio [rad]. +9.76 ! VS_TSRopt - Power-maximizing region 2 tip-speed-ratio. Only used in VS_ControlMode = 2. +0.314000000000 ! VS_PwrFiltF - Low pass filter on power used to determine generator speed set point. Only used in VS_ControlMode = 3. !------- SETPOINT SMOOTHER --------------------------------------------- 1.00000 ! SS_VSGain - Variable speed torque controller setpoint smoother gain, [-]. @@ -89,9 +96,9 @@ 102.996 ! WE_BladeRadius - Blade length (distance from hub center to blade tip), [m] 1 ! WE_CP_n - Amount of parameters in the Cp array 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] +0.0 ! WE_Gamma - Adaption gain of the wind speed estimator algorithm [m/rad] 96.8 ! WE_GearboxRatio - Gearbox ratio [>=1], [-] -311169343.31448 ! WE_Jtot - Total drivetrain inertia, including blades, hub and casted generator inertia to LSS, [kg m^2] +311169343.31448 ! 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.BAR_10.txt" ! PerfFileName - File containing rotor performance tables (Cp,Ct,Cq) (absolute path or relative to this file) 36 26 ! PerfTableSize - Size of rotor performance tables, first number refers to number of blade pitch angles, second number referse to number of tip-speed ratios @@ -123,9 +130,9 @@ 0.418880000000 ! SD_CornerFreq - Cutoff Frequency for first order low-pass filter for blade pitch angle, [rad/s] !------- Floating ----------------------------------------------------------- -1 ! Fl_n - Number of Fl_Kp gains in gain scheduling, optional with default of 1 -0.0000 ! Fl_Kp - Nacelle velocity proportional feedback gain [s] -0.0000 ! Fl_U - Wind speeds for scheduling Fl_Kp, optional if Fl_Kp is single value [m/s] +1 ! Fl_n - Number of Fl_Kp gains in gain scheduling, optional with default of 1 +0.0000 ! Fl_Kp - Nacelle velocity proportional feedback gain [s] +0.0000 ! Fl_U - Wind speeds for scheduling Fl_Kp, optional if Fl_Kp is single value [m/s] !------- FLAP ACTUATION ----------------------------------------------------- 0.000000000000 ! Flp_Angle - Initial or steady state flap angle [rad] @@ -145,19 +152,19 @@ 0 ! Ind_StructControl - The column(s) in OL_Filename that contains the structural control inputs [Used with StC_Mode = 2, must be the same size as StC_Group_N] !------- Pitch Actuator Model ----------------------------------------------------- -3.140000000000 ! PA_CornerFreq - Pitch actuator bandwidth/cut-off frequency [rad/s] -0.707000000000 ! PA_Damping - Pitch actuator damping ratio [-, unused if PA_Mode = 1] +3.140000000000 ! PA_CornerFreq - Pitch actuator bandwidth/cut-off frequency [rad/s] +0.707000000000 ! PA_Damping - Pitch actuator damping ratio [-, unused if PA_Mode = 1] !------- Pitch Actuator Faults ----------------------------------------------------- 0.00000000 0.00000000 0.00000000 ! PF_Offsets - Constant blade pitch offsets for blades 1-3 [rad] !------- Active Wake Control ----------------------------------------------------- -1 ! AWC_NumModes - Number of user-defined AWC forcing modes -1 ! AWC_n - Azimuthal mode number(s) (i.e., the number and direction of the lobes of the wake structure) -1 ! AWC_harmonic - Harmonic(s) to apply in the AWC Inverse Coleman Transformation (only used when AWC_Mode = 2) -0.0500 ! AWC_freq - Frequency(s) of forcing mode(s) [Hz] -1.0000 ! AWC_amp - Pitch amplitude(s) of individual forcing mode(s) [deg] -0.0000 ! AWC_clockangle - Initial angle(s) of forcing mode(s) [deg] +1 ! AWC_NumModes - Number of user-defined AWC forcing modes +1 ! AWC_n - Azimuthal mode number(s) (i.e., the number and direction of the lobes of the wake structure) +1 ! AWC_harmonic - Harmonic(s) to apply in the AWC Inverse Coleman Transformation (only used when AWC_Mode = 2) +0.0500 ! AWC_freq - Frequency(s) of forcing mode(s) [Hz] +1.0000 ! AWC_amp - Pitch amplitude(s) of individual forcing mode(s) [deg] +0.0000 ! AWC_clockangle - Initial angle(s) of forcing mode(s) [deg] !------- External Controller Interface ----------------------------------------------------- "unused" ! DLL_FileName - Name/location of the dynamic library in the Bladed-DLL format @@ -170,9 +177,9 @@ !------- Cable Control --------------------------------------------------------- 1 ! CC_Group_N - Number of cable control groups - 0 ! CC_GroupIndex - First index for cable control group, should correspond to deltaL +0 ! CC_GroupIndex - First index for cable control group, should correspond to deltaL 20.000000 ! CC_ActTau - Time constant for line actuator [s] !------- Structural Controllers --------------------------------------------------------- 1 ! StC_Group_N - Number of cable control groups - 0 ! StC_GroupIndex - First index for structural control group, options specified in ServoDyn summary output +0 ! StC_GroupIndex - First index for structural control group, options specified in ServoDyn summary output diff --git a/Test_Cases/IEA-15-240-RWT-UMaineSemi/DISCON-UMaineSemi.IN b/Test_Cases/IEA-15-240-RWT-UMaineSemi/DISCON-UMaineSemi.IN index 3624b81c..aeeccf66 100644 --- a/Test_Cases/IEA-15-240-RWT-UMaineSemi/DISCON-UMaineSemi.IN +++ b/Test_Cases/IEA-15-240-RWT-UMaineSemi/DISCON-UMaineSemi.IN @@ -1,45 +1,51 @@ ! Controller parameter input file for the IEA-15-240-RWT-UMaineSemi wind turbine -! - File written using ROSCO version 2.8.0 controller tuning logic on 08/03/23 +! - File written using ROSCO version 2.8.0 controller tuning logic on 09/06/23 !------- SIMULATION CONTROL ------------------------------------------------------------ 2 ! LoggingLevel - {0: write no debug files, 1: write standard output .dbg-file, 2: LoggingLevel 1 + ROSCO LocalVars (.dbg2) 3: LoggingLevel 2 + complete avrSWAP-array (.dbg3)} -0 ! DT_Out - {Time step to output .dbg* files, or 0 to match sampling period of OpenFAST} +0 ! DT_Out - {Time step to output .dbg* files, or 0 to match sampling period of OpenFAST} 0 ! Echo - (0 - no Echo, 1 - Echo input data to .echo) !------- CONTROLLER FLAGS ------------------------------------------------- -2 ! F_LPFType - (1: first-order low-pass filter, 2: second-order low-pass filter), [rad/s] (currently filters generator speed and pitch control signals -2 ! F_NotchType - Notch on the measured generator speed and/or tower fore-aft motion (for floating) {0: disable, 1: generator speed, 2: tower-top fore-aft motion, 3: generator speed and tower-top fore-aft motion} +2 ! 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 ! 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 with constant torque, 3: TSR tracking PI control with constant power} -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: Immersion and Invariance Estimator, 2: Extended Kalman Filter} -1 ! PS_Mode - Pitch saturation mode {0: no pitch saturation, 1: implement pitch saturation} -0 ! SD_Mode - Shutdown mode {0: no shutdown procedure, 1: pitch to max pitch at shutdown} -2 ! Fl_Mode - Floating specific feedback mode {0: no nacelle velocity feedback, 1: feed back translational velocity, 2: feed back rotational veloicty} -0 ! TD_Mode - Tower damper mode {0: no tower damper, 1: feed back translational nacelle accelleration to pitch angle} -0 ! Flp_Mode - Flap control mode {0: no flap control, 1: steady state flap angle, 2: Proportional flap control, 2: Cyclic (1P) flap control} -0 ! OL_Mode - Open loop control mode {0: no open loop control, 1: open loop control vs. time, 2: rotor position control} -2 ! PA_Mode - Pitch actuator mode {0 - not used, 1 - first order filter, 2 - second order filter} -0 ! PF_Mode - Pitch fault mode {0 - not used, 1 - constant offset on one or more blades} -0 ! AWC_Mode - Active wake control {0 - not used, 1 - complex number method, 2 - Coleman transform method} -0 ! Ext_Mode - External control mode {0 - not used, 1 - call external dynamic library} -0 ! ZMQ_Mode - Fuse ZeroMQ interface {0: unused, 1: Yaw Control} -0 ! CC_Mode - Cable control mode [0- unused, 1- User defined, 2- Open loop control] -0 ! StC_Mode - Structural control mode [0- unused, 1- User defined, 2- Open loop control] +2 ! VS_ControlMode - Generator torque control mode in above rated conditions (0- no torque control, 1- k*omega^2 with PI transitions, 2- WSE TSR Tracking, 3- Power-based TSR Tracking)} +0 ! VS_ConstPower - Do constant power torque control, where above rated torque varies, 0 for constant torque} +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: Immersion and Invariance Estimator, 2: Extended Kalman Filter} +1 ! PS_Mode - Pitch saturation mode {0: no pitch saturation, 1: implement pitch saturation} +0 ! SD_Mode - Shutdown mode {0: no shutdown procedure, 1: pitch to max pitch at shutdown} +2 ! Fl_Mode - Floating specific feedback mode {0: no nacelle velocity feedback, 1: feed back translational velocity, 2: feed back rotational veloicty} +0 ! TD_Mode - Tower damper mode {0: no tower damper, 1: feed back translational nacelle accelleration to pitch angle} +0 ! Flp_Mode - Flap control mode {0: no flap control, 1: steady state flap angle, 2: Proportional flap control, 2: Cyclic (1P) flap control} +0 ! OL_Mode - Open loop control mode {0: no open loop control, 1: open loop control vs. time, 2: rotor position control} +2 ! PA_Mode - Pitch actuator mode {0 - not used, 1 - first order filter, 2 - second order filter} +0 ! PF_Mode - Pitch fault mode {0 - not used, 1 - constant offset on one or more blades} +0 ! AWC_Mode - Active wake control {0 - not used, 1 - complex number method, 2 - Coleman transform method} +0 ! Ext_Mode - External control mode {0 - not used, 1 - call external dynamic library} +0 ! ZMQ_Mode - Fuse ZeroMQ interface {0: unused, 1: Yaw Control} +0 ! CC_Mode - Cable control mode [0- unused, 1- User defined, 2- Open loop control] +0 ! StC_Mode - Structural control mode [0- unused, 1- User defined, 2- Open loop control] !------- FILTERS ---------------------------------------------------------- -1.00810 ! F_LPFCornerFreq - Corner frequency (-3dB point) in the low-pass filters, [rad/s] -0.70000 ! F_LPFDamping - Damping coefficient {used only when F_FilterType = 2} [-] -3.35500 ! F_NotchCornerFreq - Natural frequency of the notch filter, [rad/s] -0.000000 0.250000 ! F_NotchBetaNumDen - Two notch damping values (numerator and denominator, resp) - determines the width and depth of the notch, [-] +1.00810 ! F_LPFCornerFreq - Corner frequency (-3dB point) in the low-pass filters, [rad/s] +0.70000 ! F_LPFDamping - Damping coefficient {used only when F_FilterType = 2} [-] +1 ! F_NumNotchFilts - Number of notch filters placed on sensors +3.3550 ! F_NotchFreqs - Natural frequency of the notch filters. Array with length F_NumNotchFilts +0.0000 ! F_NotchBetaNum - Damping value of numerator (determines the width of notch). Array with length F_NumNotchFilts, [-] +0.2500 ! F_NotchBetaDen - Damping value of denominator (determines the depth of notch). Array with length F_NumNotchFilts, [-] +0 ! F_GenSpdNotch_N - Number of notch filters on generator speed +0 ! F_GenSpdNotch_Ind - Indices of notch filters on generator speed +1 ! F_TwrTopNotch_N - Number of notch filters on tower top acceleration signal +1 ! F_TwrTopNotch_Ind - Indices of notch filters on tower top acceleration signal 0.62830 ! F_SSCornerFreq - Corner frequency (-3dB point) in the first order low pass filter for the setpoint smoother, [rad/s]. 0.20944 ! F_WECornerFreq - Corner frequency (-3dB point) in the first order low pass filter for the wind speed estimate [rad/s]. 0.17952 ! F_YawErr - Low pass filter corner frequency for yaw controller [rad/s]. 0.213000 1.000000 ! F_FlCornerFreq - Natural frequency and damping in the second order low pass filter of the tower-top fore-aft motion for floating feedback control [rad/s, -]. -0.01042 ! F_FlHighPassFreq - Natural frequency of first-order high-pass filter for nacelle fore-aft motion [rad/s]. -10.461600 1.000000 ! F_FlpCornerFreq - Corner frequency and damping in the second order low pass filter of the blade root bending moment for flap control [rad/s, -]. +0.01042 ! F_FlHighPassFreq - Natural frequency of first-order high-pass filter for nacelle fore-aft motion [rad/s]. +10.4616 1.0000 ! F_FlpCornerFreq - Corner frequency and damping in the second order low pass filter of the blade root bending moment for flap control !------- BLADE PITCH CONTROL ---------------------------------------------- 30 ! PC_GS_n - Amount of gain-scheduling table entries @@ -72,14 +78,15 @@ 21586451.33303 ! VS_MaxTq - Maximum generator torque in Region 3 (HSS side), [Nm]. 0.000000000000 ! VS_MinTq - Minimum generator torque (HSS side), [Nm]. 0.523600000000 ! VS_MinOMSpd - Minimum generator speed [rad/s] -37840583.60628 ! VS_Rgn2K - Generator torque constant in Region 2 (HSS side), [Nm/(rad/s)^2] +31393135.82403 ! VS_Rgn2K - Generator torque constant in Region 2 (HSS side). Only used in VS_ControlMode = 1,3 15000000.00000 ! VS_RtPwr - Wind turbine rated power [W] 19624046.66639 ! VS_RtTq - Rated torque, [Nm]. 0.791680000000 ! VS_RefSpd - Rated generator speed [rad/s] 1 ! VS_n - Number of generator PI torque controller gains -37877315.85935 ! VS_KP - Proportional gain for generator PI torque controller [-]. (Only used in the transitional 2.5 region if VS_ControlMode =/ 2) -4588245.18720 ! VS_KI - Integral gain for generator PI torque controller [s]. (Only used in the transitional 2.5 region if VS_ControlMode =/ 2) -9.00 ! VS_TSRopt - Power-maximizing region 2 tip-speed-ratio [rad]. +9.00 ! VS_TSRopt - Power-maximizing region 2 tip-speed-ratio. Only used in VS_ControlMode = 2. +0.314000000000 ! VS_PwrFiltF - Low pass filter on power used to determine generator speed set point. Only used in VS_ControlMode = 3. !------- SETPOINT SMOOTHER --------------------------------------------- 1.00000 ! SS_VSGain - Variable speed torque controller setpoint smoother gain, [-]. @@ -89,9 +96,9 @@ 120.000 ! WE_BladeRadius - Blade length (distance from hub center to blade tip), [m] 1 ! WE_CP_n - Amount of parameters in the Cp array 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] +0.0 ! WE_Gamma - Adaption gain of the wind speed estimator algorithm [m/rad] 1.0 ! WE_GearboxRatio - Gearbox ratio [>=1], [-] -318628138.00000 ! WE_Jtot - Total drivetrain inertia, including blades, hub and casted generator inertia to LSS, [kg m^2] +318628138.00000 ! 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.IEA15MW.txt" ! PerfFileName - File containing rotor performance tables (Cp,Ct,Cq) (absolute path or relative to this file) 36 26 ! PerfTableSize - Size of rotor performance tables, first number refers to number of blade pitch angles, second number referse to number of tip-speed ratios @@ -123,9 +130,9 @@ 0.418880000000 ! SD_CornerFreq - Cutoff Frequency for first order low-pass filter for blade pitch angle, [rad/s] !------- Floating ----------------------------------------------------------- -1 ! Fl_n - Number of Fl_Kp gains in gain scheduling, optional with default of 1 --9.3465 ! Fl_Kp - Nacelle pitching proportional feedback gain [s] -11.2770 ! Fl_U - Wind speeds for scheduling Fl_Kp, optional if Fl_Kp is single value [m/s] +1 ! Fl_n - Number of Fl_Kp gains in gain scheduling, optional with default of 1 +-9.3465 ! Fl_Kp - Nacelle pitching proportional feedback gain [s] +11.2770 ! Fl_U - Wind speeds for scheduling Fl_Kp, optional if Fl_Kp is single value [m/s] !------- FLAP ACTUATION ----------------------------------------------------- 0.000000000000 ! Flp_Angle - Initial or steady state flap angle [rad] @@ -145,19 +152,19 @@ 0 ! Ind_StructControl - The column(s) in OL_Filename that contains the structural control inputs [Used with StC_Mode = 2, must be the same size as StC_Group_N] !------- Pitch Actuator Model ----------------------------------------------------- -1.570800000000 ! PA_CornerFreq - Pitch actuator bandwidth/cut-off frequency [rad/s] -0.707000000000 ! PA_Damping - Pitch actuator damping ratio [-, unused if PA_Mode = 1] +1.570800000000 ! PA_CornerFreq - Pitch actuator bandwidth/cut-off frequency [rad/s] +0.707000000000 ! PA_Damping - Pitch actuator damping ratio [-, unused if PA_Mode = 1] !------- Pitch Actuator Faults ----------------------------------------------------- 0.00000000 0.00000000 0.00000000 ! PF_Offsets - Constant blade pitch offsets for blades 1-3 [rad] !------- Active Wake Control ----------------------------------------------------- -1 ! AWC_NumModes - Number of user-defined AWC forcing modes -1 ! AWC_n - Azimuthal mode number(s) (i.e., the number and direction of the lobes of the wake structure) -1 ! AWC_harmonic - Harmonic(s) to apply in the AWC Inverse Coleman Transformation (only used when AWC_Mode = 2) -0.0500 ! AWC_freq - Frequency(s) of forcing mode(s) [Hz] -1.0000 ! AWC_amp - Pitch amplitude(s) of individual forcing mode(s) [deg] -0.0000 ! AWC_clockangle - Initial angle(s) of forcing mode(s) [deg] +1 ! AWC_NumModes - Number of user-defined AWC forcing modes +1 ! AWC_n - Azimuthal mode number(s) (i.e., the number and direction of the lobes of the wake structure) +1 ! AWC_harmonic - Harmonic(s) to apply in the AWC Inverse Coleman Transformation (only used when AWC_Mode = 2) +0.0500 ! AWC_freq - Frequency(s) of forcing mode(s) [Hz] +1.0000 ! AWC_amp - Pitch amplitude(s) of individual forcing mode(s) [deg] +0.0000 ! AWC_clockangle - Initial angle(s) of forcing mode(s) [deg] !------- External Controller Interface ----------------------------------------------------- "unused" ! DLL_FileName - Name/location of the dynamic library in the Bladed-DLL format @@ -170,9 +177,9 @@ !------- Cable Control --------------------------------------------------------- 1 ! CC_Group_N - Number of cable control groups - 0 ! CC_GroupIndex - First index for cable control group, should correspond to deltaL +0 ! CC_GroupIndex - First index for cable control group, should correspond to deltaL 20.000000 ! CC_ActTau - Time constant for line actuator [s] !------- Structural Controllers --------------------------------------------------------- 1 ! StC_Group_N - Number of cable control groups - 0 ! StC_GroupIndex - First index for structural control group, options specified in ServoDyn summary output +0 ! StC_GroupIndex - First index for structural control group, options specified in ServoDyn summary output diff --git a/Test_Cases/MHK_RM1/Airfoils/NACA6_0240.dat b/Test_Cases/MHK_RM1/Airfoils/NACA6_0240.dat new file mode 100644 index 00000000..94b36abc --- /dev/null +++ b/Test_Cases/MHK_RM1/Airfoils/NACA6_0240.dat @@ -0,0 +1,560 @@ +! ------------ AirfoilInfo v1.01.x Input File ---------------------------------- +! NACA6_0240 airfoil, data based on values used for the design of the RM1 tidal current turbine. +! line +! line +! ------------------------------------------------------------------------------ +"default" InterpOrd ! Interpolation order to use for quasi-steady table lookup {1=linear; 3=cubic spline; "default"} [default=1] + 1.0 NonDimArea ! The non-dimensional area of the airfoil (area/chord^2) (set to 1.0 if unsure or unneeded) +@"NACA6_0240_coords.txt" NumCoords ! The number of coordinates in the airfoil shape file. Set to zero if coordinates not included. +"unused" BL_file ! The file name including the boundary layer characteristics of the profile. Ignored if the aeroacoustic module is not called. + 7 NumTabs ! Number of airfoil tables in this file. +! ------------------------------------------------------------------------------ +! data for table 1 +! ------------------------------------------------------------------------------ + 2.0 Re ! Reynolds number in millions + 0 UserProp ! User property (control) setting +False InclUAdata ! Is unsteady aerodynamics data included in this table? If TRUE, then include 30 UA coefficients below this line +!........................................ +! Table of aerodynamics coefficients + 72 NumAlf ! Number of data lines in the following table +! Alpha Cl Cd Cpmin +! (deg) (-) (-) (-) + -180 0.0000 0.0100 -1 + -170 0.3120 0.0100 -1 + -160 0.6240 0.0706 -1 + -150 0.9360 0.2428 -1 + -140 0.7699 0.4549 -1 + -130 0.6312 0.6818 -1 + -120 0.4861 0.8973 -1 + -110 0.3275 1.0763 -1 + -100 0.1610 1.1983 -1 + -90 0.0000 1.2500 -1 + -80 -0.1610 1.1983 -1 + -70 -0.3275 1.0763 -1 + -60 -0.4861 0.8973 -1 + -50 -0.6312 0.6818 -1 + -40 -0.7699 0.4549 -1 + -30 -0.9360 0.2428 -1 + -20 -0.6782 0.1306 -1 + -10 -0.6006 0.0183 -2.3658 + -9 -0.5703 0.0150 -2.1354 + -8 -0.5401 0.0124 -1.9128 + -7 -0.4863 0.0111 -1.6564 + -6 -0.3911 0.0101 -1.4075 + -5 -0.2829 0.0093 -1.2098 + -4 -0.1699 0.0086 -1.0246 + -3 -0.0547 0.0076 -0.9055 + -2 0.0671 0.0074 -0.9047 + -1 0.1884 0.0073 -0.9888 + 0 0.3092 0.0074 -1.0777 + 1 0.4307 0.0074 -1.1694 + 2 0.5503 0.0076 -1.2608 + 3 0.6677 0.0078 -1.3557 + 4 0.7807 0.0082 -1.4512 + 5 0.8921 0.0086 -1.5561 + 6 0.9830 0.0097 -1.6648 + 7 1.0196 0.0114 -1.7468 + 8 1.0527 0.0137 -1.8733 + 9 1.0932 0.0166 -2.0257 + 10 1.1352 0.0200 -2.1849 + 11 1.1432 0.0259 -2.3027 + 12 1.1730 0.0313 -2.5537 + 13 1.1826 0.0392 -2.7674 + 14 1.2087 0.0464 -3.0323 + 15 1.2272 0.0550 -3.2908 + 16 1.2557 0.0634 -3.5959 + 17 1.2806 0.0725 -3.9100 + 18 1.3037 0.0825 -4.2419 + 19 1.3252 0.0930 -4.5743 + 20 1.3439 0.1043 -4.9173 + 21 1.3613 0.1159 -5.2685 + 22 1.3809 0.1271 -5.6456 + 23 1.3894 0.1401 -5.9876 + 24 1.3961 0.1532 -6.3248 + 25 1.3970 0.1669 -6.6429 + 26 1.3922 0.1814 -6.9151 + 28 1.3673 0.2112 -7.3108 + 29 1.3488 0.2278 -7.4112 + 30 1.3371 0.2428 -7.5348 + 40 1.0999 0.4549 -1 + 50 0.9017 0.6818 -1 + 60 0.6944 0.8973 -1 + 70 0.4678 1.0763 -1 + 80 0.2300 1.1983 -1 + 90 0.0000 1.2500 -1 + 100 -0.1610 1.1983 -1 + 110 -0.3275 1.0763 -1 + 120 -0.4861 0.8973 -1 + 130 -0.6312 0.6818 -1 + 140 -0.7699 0.4549 -1 + 150 -0.9360 0.2428 -1 + 160 -0.6240 0.0706 -1 + 170 -0.3120 0.0100 -1 + 180 0.0000 0.0100 -1 +! ------------------------------------------------------------------------------ +! data for table 2 +! ------------------------------------------------------------------------------ + 4.0 Re ! Reynolds number in millions + 0 UserProp ! User property (control) setting +False InclUAdata ! Is unsteady aerodynamics data included in this table? If TRUE, then include 30 UA coefficients below this line +!........................................ +! Table of aerodynamics coefficients + 69 NumAlf ! Number of data lines in the following table +! Alpha Cl Cd Cpmin +! (deg) (-) (-) (-) + -180 0.0000 0.0100 -1 + -170 0.3270 0.0100 -1 + -160 0.6541 0.0587 -1 + -150 0.9811 0.2318 -1 + -140 0.7974 0.4451 -1 + -130 0.6474 0.6736 -1 + -120 0.4948 0.8909 -1 + -110 0.3312 1.0719 -1 + -100 0.1619 1.1961 -1 + -90 0.0000 1.2500 -1 + -80 -0.1619 1.1961 -1 + -70 -0.3312 1.0719 -1 + -60 -0.4948 0.8909 -1 + -50 -0.6474 0.6736 -1 + -40 -0.7974 0.4451 -1 + -30 -0.9811 0.2318 -1 + -20 -0.7169 0.1237 -1 + -10 -0.6467 0.0156 -2.4629 + -9 -0.5996 0.0132 -2.1912 + -8 -0.5801 0.0111 -1.9816 + -7 -0.4950 0.0100 -1.6720 + -6 -0.3910 0.0092 -1.4078 + -5 -0.2810 0.0085 -1.2080 + -4 -0.1639 0.0080 -1.0184 + -3 -0.0454 0.0073 -0.8991 + -1 0.1982 0.0065 -0.9945 + 0 0.3213 0.0064 -1.0853 + 1 0.4423 0.0066 -1.1768 + 2 0.5645 0.0066 -1.2701 + 5 0.8977 0.0083 -1.5589 + 6 0.9769 0.0097 -1.6615 + 7 1.0311 0.0109 -1.7560 + 9 1.1327 0.0147 -2.0745 + 10 1.1526 0.0188 -2.2074 + 11 1.1873 0.0230 -2.3877 + 12 1.2028 0.0291 -2.6164 + 13 1.2313 0.0351 -2.8768 + 14 1.2601 0.0417 -3.1622 + 15 1.2941 0.0485 -3.4718 + 16 1.3216 0.0564 -3.7920 + 17 1.3498 0.0647 -4.1401 + 18 1.3733 0.0740 -4.4868 + 19 1.3966 0.0838 -4.8430 + 20 1.4115 0.0951 -5.1959 + 21 1.4270 0.1066 -5.5559 + 22 1.4404 0.1187 -5.9301 + 23 1.4449 0.1319 -6.2704 + 24 1.4587 0.1437 -6.6837 + 25 1.4594 0.1573 -7.0264 + 26 1.4601 0.1706 -7.3616 + 27 1.4562 0.1845 -7.6585 + 28 1.4482 0.1989 -7.9116 + 29 1.4181 0.2163 -7.9793 + 30 1.4016 0.2318 -8.1104 + 40 1.1391 0.4451 -1 + 50 0.9249 0.6736 -1 + 60 0.7068 0.8909 -1 + 70 0.4731 1.0719 -1 + 80 0.2313 1.1961 -1 + 90 0.0000 1.2500 -1 + 100 -0.1619 1.1961 -1 + 110 -0.3312 1.0719 -1 + 120 -0.4948 0.8909 -1 + 130 -0.6474 0.6736 -1 + 140 -0.7974 0.4451 -1 + 150 -0.9811 0.2318 -1 + 160 -0.6541 0.0587 -1 + 170 -0.3270 0.0100 -1 + 180 0.0000 0.0100 -1 +! ------------------------------------------------------------------------------ +! data for table 3 +! ------------------------------------------------------------------------------ + 6.0 Re ! Reynolds number in millions + 0 UserProp ! User property (control) setting +False InclUAdata ! Is unsteady aerodynamics data included in this table? If TRUE, then include 30 UA coefficients below this line +!........................................ +! Table of aerodynamics coefficients + 71 NumAlf ! Number of data lines in the following table +! Alpha Cl Cd Cpmin +! (deg) (-) (-) (-) + -180 0.0000 0.0100 -1 + -170 0.3392 0.0100 -1 + -160 0.6784 0.0496 -1 + -150 1.0176 0.2235 -1 + -140 0.8196 0.4377 -1 + -130 0.6605 0.6674 -1 + -120 0.5018 0.8861 -1 + -110 0.3342 1.0686 -1 + -100 0.1627 1.1945 -1 + -90 0.0000 1.2500 -1 + -80 -0.1627 1.1945 -1 + -70 -0.3342 1.0686 -1 + -60 -0.5018 0.8861 -1 + -50 -0.6605 0.6674 -1 + -40 -0.8196 0.4377 -1 + -30 -1.0176 0.2235 -1 + -20 -0.7445 0.1188 -1 + -10 -0.6733 0.0141 -2.5188 + -9 -0.6311 0.0119 -2.2492 + -8 -0.5908 0.0105 -2.0003 + -7 -0.4967 0.0096 -1.6748 + -6 -0.3927 0.0088 -1.4104 + -5 -0.2789 0.0081 -1.2057 + -4 -0.1611 0.0077 -1.0152 + -3 -0.0419 0.0072 -0.8970 + -2 0.0793 0.0064 -0.9117 + -1 0.2025 0.0061 -0.9971 + 0 0.3254 0.0061 -1.0876 + 1 0.4490 0.0061 -1.1811 + 2 0.5682 0.0064 -1.2727 + 4 0.7966 0.0073 -1.4660 + 5 0.8946 0.0084 -1.5586 + 6 0.9801 0.0096 -1.6568 + 7 1.0446 0.0105 -1.7694 + 8 1.1065 0.0117 -1.9317 + 9 1.1411 0.0142 -2.0844 + 10 1.1776 0.0175 -2.2415 + 11 1.2014 0.0220 -2.4154 + 12 1.2315 0.0270 -2.6770 + 13 1.2585 0.0329 -2.9389 + 14 1.2967 0.0387 -3.2543 + 15 1.3269 0.0455 -3.5636 + 16 1.3566 0.0529 -3.8959 + 17 1.3838 0.0611 -4.2519 + 19 1.4278 0.0800 -4.9627 + 20 1.4607 0.0886 -5.3962 + 21 1.4730 0.1002 -5.7535 + 22 1.4807 0.1128 -6.1201 + 23 1.4853 0.1259 -6.4786 + 24 1.4917 0.1388 -6.8685 + 25 1.4944 0.1520 -7.2354 + 26 1.4918 0.1657 -7.5648 + 27 1.4848 0.1800 -7.8540 + 28 1.4765 0.1943 -8.1190 + 29 1.4665 0.2087 -8.3538 + 30 1.4537 0.2235 -8.5446 + 40 1.1708 0.4377 -1 + 50 0.9436 0.6674 -1 + 60 0.7169 0.8861 -1 + 70 0.4775 1.0686 -1 + 80 0.2324 1.1945 -1 + 90 0.0000 1.2500 -1 + 100 -0.1627 1.1945 -1 + 110 -0.3342 1.0686 -1 + 120 -0.5018 0.8861 -1 + 130 -0.6605 0.6674 -1 + 140 -0.8196 0.4377 -1 + 150 -1.0176 0.2235 -1 + 160 -0.6784 0.0496 -1 + 170 -0.3392 0.0100 -1 + 180 0.0000 0.0100 -1 +! ------------------------------------------------------------------------------ +! data for table 4 +! ------------------------------------------------------------------------------ + 8.0 Re ! Reynolds number in millions + 0 UserProp ! User property (control) setting +False InclUAdata ! Is unsteady aerodynamics data included in this table? If TRUE, then include 30 UA coefficients below this line +!........................................ +! Table of aerodynamics coefficients + 62 NumAlf ! Number of data lines in the following table +! Alpha Cl Cd Cpmin +! (deg) (-) (-) (-) + -180 0.0000 0.0100 -1 + -170 0.4065 0.0100 -1 + -160 0.8130 0.0656 -1 + -150 0.9585 0.2382 -1 + -140 0.7836 0.4508 -1 + -130 0.6393 0.6784 -1 + -120 0.4904 0.8946 -1 + -110 0.3293 1.0744 -1 + -100 0.1615 1.1974 -1 + -90 0.0000 1.2500 -1 + -80 -0.1615 1.1974 -1 + -70 -0.3293 1.0744 -1 + -60 -0.4904 0.8946 -1 + -50 -0.6393 0.6784 -1 + -40 -0.7836 0.4508 -1 + -30 -0.9585 0.2382 -1 + -20 -0.8400 0.1070 -1 + -10 -0.6835 0.0136 -2.5481 + -9 -0.6551 0.0110 -2.2945 + -8 -0.5990 0.0100 -2.0149 + -5 -0.2785 0.0079 -1.2051 + -4 -0.1605 0.0074 -1.0146 + -3 -0.0396 0.0070 -0.8858 + -2 0.0815 0.0064 -0.9130 + -1 0.2046 0.0060 -0.9981 + 0 0.3288 0.0059 -1.0898 + 1 0.4505 0.0059 -1.1819 + 2 0.5696 0.0062 -1.2742 + 3 0.6869 0.0066 -1.3692 + 4 0.7958 0.0074 -1.4563 + 6 0.9864 0.0094 -1.6557 + 7 1.0636 0.0101 -1.7862 + 8 1.1217 0.0112 -1.9495 + 9 1.1532 0.0137 -2.0998 + 11 1.2140 0.0213 -2.4399 + 12 1.2522 0.0256 -2.7207 + 13 1.2922 0.0304 -3.0194 + 15 1.3624 0.0423 -3.6630 + 16 1.3922 0.0494 -4.0053 + 17 1.4225 0.0570 -4.3795 + 18 1.4431 0.0660 -4.7296 + 19 1.4663 0.0753 -5.1108 + 20 1.4819 0.0860 -5.4818 + 22 1.4994 0.1103 -6.2066 + 25 1.5113 0.1495 -7.3351 + 26 1.5098 0.1631 -7.6774 + 30 1.3693 0.2382 -6.1797 + 40 1.1195 0.4508 -1 + 50 0.9133 0.6784 -1 + 60 0.7006 0.8946 -1 + 70 0.4705 1.0744 -1 + 80 0.2307 1.1974 -1 + 90 0.0000 1.2500 -1 + 100 -0.1615 1.1974 -1 + 110 -0.3293 1.0744 -1 + 120 -0.4904 0.8946 -1 + 130 -0.6393 0.6784 -1 + 140 -0.7836 0.4508 -1 + 150 -0.9585 0.2382 -1 + 160 -0.8130 0.0656 -1 + 170 -0.4065 0.0100 -1 + 180 0.0000 0.0100 -1 +! ------------------------------------------------------------------------------ +! data for table 5 +! ------------------------------------------------------------------------------ + 10.0 Re ! Reynolds number in millions + 0 UserProp ! User property (control) setting +False InclUAdata ! Is unsteady aerodynamics data included in this table? If TRUE, then include 30 UA coefficients below this line +!........................................ +! Table of aerodynamics coefficients + 67 NumAlf ! Number of data lines in the following table +! Alpha Cl Cd Cpmin +! (deg) (-) (-) (-) + -180 0.0000 0.0100 -1 + -170 0.3508 0.0100 -1 + -160 0.7017 0.0400 -1 + -150 1.0525 0.2147 -1 + -140 0.8408 0.4299 -1 + -130 0.6731 0.6609 -1 + -120 0.5085 0.8810 -1 + -110 0.3371 1.0651 -1 + -100 0.1634 1.1927 -1 + -90 0.0000 1.2500 -1 + -80 -0.1634 1.1927 -1 + -70 -0.3371 1.0651 -1 + -60 -0.5085 0.8810 -1 + -50 -0.6731 0.6609 -1 + -40 -0.8408 0.4299 -1 + -30 -1.0525 0.2147 -1 + -20 -0.7646 0.1141 -1 + -10 -0.6811 0.0135 -2.5243 + -9 -0.6851 0.0106 -2.3544 + -8 -0.6061 0.0097 -2.0276 + -6 -0.3941 0.0082 -1.4146 + -4 -0.1596 0.0072 -1.0137 + -3 -0.0388 0.0069 -0.8871 + -2 0.0830 0.0064 -0.9138 + -1 0.2067 0.0059 -0.9994 + 0 0.3302 0.0058 -1.0906 + 1 0.4512 0.0059 -1.1825 + 2 0.5700 0.0062 -1.2762 + 4 0.7938 0.0075 -1.4517 + 5 0.8930 0.0085 -1.5475 + 6 0.9896 0.0093 -1.6620 + 7 1.0843 0.0099 -1.8045 + 8 1.1285 0.0111 -1.9571 + 9 1.1695 0.0131 -2.1205 + 10 1.1873 0.0169 -2.2387 + 11 1.2351 0.0201 -2.4820 + 12 1.2707 0.0244 -2.7598 + 13 1.3094 0.0292 -3.0601 + 14 1.3479 0.0345 -3.3831 + 16 1.4132 0.0475 -4.0705 + 17 1.4381 0.0554 -4.4302 + 18 1.4631 0.0639 -4.7988 + 19 1.4825 0.0734 -5.1723 + 20 1.4971 0.0841 -5.5428 + 21 1.5047 0.0960 -5.8916 + 24 1.5435 0.1310 -7.1532 + 25 1.5472 0.1439 -7.5449 + 26 1.5476 0.1572 -7.9128 + 27 1.5436 0.1707 -8.246 + 28 1.5338 0.1849 -8.5292 + 29 1.5197 0.1997 -8.7629 + 30 1.5036 0.2147 -8.9588 + 40 1.2012 0.4299 -1 + 50 0.9615 0.6609 -1 + 60 0.7265 0.8810 -1 + 70 0.4816 1.0651 -1 + 80 0.2334 1.1927 -1 + 90 0.0000 1.2500 -1 + 100 -0.1634 1.1927 -1 + 110 -0.3371 1.0651 -1 + 120 -0.5085 0.8810 -1 + 130 -0.6731 0.6609 -1 + 140 -0.8408 0.4299 -1 + 150 -1.0525 0.2147 -1 + 160 -0.7017 0.0400 -1 + 170 -0.3508 0.0100 -1 + 180 0.0000 0.0100 -1 +! ------------------------------------------------------------------------------ +! data for table 6 +! ------------------------------------------------------------------------------ + 12.0 Re ! Reynolds number in millions + 0 UserProp ! User property (control) setting +False InclUAdata ! Is unsteady aerodynamics data included in this table? If TRUE, then include 30 UA coefficients below this line +!........................................ +! Table of aerodynamics coefficients + 68 NumAlf ! Number of data lines in the following table +! Alpha Cl Cd Cpmin +! (deg) (-) (-) (-) + -180 0.0000 0.0100 -1 + -170 0.3695 0.0100 -1 + -160 0.7389 0.0433 -1 + -150 1.0447 0.2176 -1 + -140 0.8361 0.4326 -1 + -130 0.6703 0.6631 -1 + -120 0.5070 0.8827 -1 + -110 0.3365 1.0663 -1 + -100 0.1632 1.1933 -1 + -90 0.0000 1.2500 -1 + -80 -0.1632 1.1933 -1 + -70 -0.3365 1.0663 -1 + -60 -0.5070 0.8827 -1 + -50 -0.6703 0.6631 -1 + -40 -0.8361 0.4326 -1 + -30 -1.0447 0.2176 -1 + -20 -0.7942 0.1103 -1 + -10 -0.6944 0.0129 -2.5538 + -7 -0.5051 0.0088 -1.6890 + -6 -0.3931 0.0082 -1.4033 + -5 -0.2781 0.0075 -1.2051 + -4 -0.1595 0.0071 -1.0133 + -3 -0.0379 0.0068 -0.8899 + -2 0.0846 0.0064 -0.9146 + -1 0.2078 0.0058 -1.0002 + 0 0.3310 0.0058 -1.0908 + 1 0.4519 0.0058 -1.1833 + 2 0.5708 0.0061 -1.2722 + 3 0.6863 0.0066 -1.3593 + 4 0.7943 0.0074 -1.4554 + 5 0.8937 0.0084 -1.5503 + 6 0.9965 0.0090 -1.6685 + 7 1.0919 0.0097 -1.8120 + 8 1.1354 0.0109 -1.9652 + 10 1.2027 0.0161 -2.2646 + 11 1.2478 0.0194 -2.5076 + 12 1.2911 0.0232 -2.8034 + 13 1.3319 0.0276 -3.1135 + 14 1.3618 0.0335 -3.4179 + 15 1.3958 0.0395 -3.7559 + 17 1.4529 0.0540 -4.4787 + 18 1.4764 0.0625 -4.8444 + 19 1.4956 0.0720 -5.2221 + 20 1.5053 0.0831 -5.5750 + 22 1.5459 0.1037 -6.4227 + 23 1.5538 0.1161 -6.8324 + 24 1.5595 0.1287 -7.2408 + 25 1.5622 0.1418 -7.6314 + 26 1.5612 0.1552 -7.9964 + 27 1.5539 0.1691 -8.3139 + 28 1.5433 0.1835 -8.595 + 29 1.5306 0.1980 -8.8443 + 30 1.4925 0.2176 -8.363771554 + 40 1.1944 0.4326 -1 + 50 0.9575 0.6631 -1 + 60 0.7243 0.8827 -1 + 70 0.4807 1.0663 -1 + 80 0.2332 1.1933 -1 + 90 0.0000 1.2500 -1 + 100 -0.1632 1.1933 -1 + 110 -0.3365 1.0663 -1 + 120 -0.5070 0.8827 -1 + 130 -0.6703 0.6631 -1 + 140 -0.8361 0.4326 -1 + 150 -1.0447 0.2176 -1 + 160 -0.7389 0.0433 -1 + 170 -0.3695 0.0100 -1 + 180 0.0000 0.0100 -1 +! ------------------------------------------------------------------------------ +! data for table 7 +! ------------------------------------------------------------------------------ + 14.0 Re ! Reynolds number in millions + 0 UserProp ! User property (control) setting +False InclUAdata ! Is unsteady aerodynamics data included in this table? If TRUE, then include 30 UA coefficients below this line +!........................................ +! Table of aerodynamics coefficients + 64 NumAlf ! Number of data lines in the following table +! Alpha Cl Cd Cpmin +! (deg) (-) (-) (-) + -180 0.0000 0.0100 -1 + -170 0.3561 0.0100 -1 + -160 0.7121 0.0361 -1 + -150 1.0682 0.2110 -1 + -140 0.8504 0.4267 -1 + -130 0.6787 0.6582 -1 + -120 0.5115 0.8789 -1 + -110 0.3384 1.0637 -1 + -100 0.1637 1.1919 -1 + -90 0.0000 1.2500 -1 + -80 -0.1637 1.1919 -1 + -70 -0.3384 1.0637 -1 + -60 -0.5115 0.8789 -1 + -50 -0.6787 0.6582 -1 + -40 -0.8504 0.4267 -1 + -30 -1.0682 0.2110 -1 + -20 -0.7818 0.1117 -1 + -10 -0.7078 0.0124 -2.5820 + -9 -0.6882 0.0105 -2.3471 + -8 -0.6127 0.0092 -2.0403 + -6 -0.3930 0.0081 -1.4009 + -5 -0.2780 0.0074 -1.2048 + -4 -0.1594 0.0069 -1.0132 + -3 -0.0371 0.0067 -0.8903 + -2 0.0857 0.0063 -0.9153 + -1 0.2083 0.0058 -1.0004 + 0 0.3320 0.0057 -1.0916 + 1 0.4508 0.0059 -1.1835 + 2 0.5707 0.0061 -1.2714 + 3 0.6849 0.0067 -1.3575 + 5 0.8968 0.0083 -1.5536 + 6 0.9995 0.0090 -1.6719 + 7 1.0994 0.0095 -1.8194 + 8 1.1396 0.0107 -1.9697 + 11 1.2595 0.0188 -2.5308 + 12 1.3027 0.0225 -2.8278 + 14 1.3829 0.0318 -3.4708 + 16 1.4381 0.0453 -4.1475 + 18 1.4876 0.0613 -4.8828 + 21 1.5477 0.0904 -6.0795 + 22 1.5578 0.1021 -6.4768 + 23 1.5668 0.1143 -6.8990 + 24 1.5715 0.1270 -7.3058 + 25 1.5731 0.1402 -7.6939 + 26 1.5686 0.1540 -8.0423 + 27 1.5615 0.1680 -8.3631 + 28 1.5521 0.1821 -8.6566 + 29 1.5406 0.1964 -8.9183 + 30 1.5260 0.2110 -9.1387 + 40 1.2148 0.4267 -1 + 50 0.9696 0.6582 -1 + 60 0.7308 0.8789 -1 + 70 0.4835 1.0637 -1 + 80 0.2339 1.1919 -1 + 90 0.0000 1.2500 -1 + 100 -0.1637 1.1919 -1 + 110 -0.3384 1.0637 -1 + 120 -0.5115 0.8789 -1 + 130 -0.6787 0.6582 -1 + 140 -0.8504 0.4267 -1 + 150 -1.0682 0.2110 -1 + 160 -0.7121 0.0361 -1 + 170 -0.3561 0.0100 -1 + 180 0.0000 0.0100 -1 \ No newline at end of file diff --git a/Test_Cases/MHK_RM1/Airfoils/NACA6_0240_coords.txt b/Test_Cases/MHK_RM1/Airfoils/NACA6_0240_coords.txt new file mode 100644 index 00000000..99568655 --- /dev/null +++ b/Test_Cases/MHK_RM1/Airfoils/NACA6_0240_coords.txt @@ -0,0 +1,47 @@ + 40 NumCoords ! The number of coordinates in the airfoil shape file (including an extra coordinate for airfoil reference). Set to zero if coordinates not included. +! ......... x-y coordinates are next if NumCoords > 0 ............. +! x-y coordinate of airfoil reference +! x/c y/c + 0.25 0 +! coordinates of airfoil shape +! NACA6_0240 Airfoil +! x/c y/c + 0.000000 0.000000 + 0.001740 0.009990 + 0.009990 0.025540 + 0.026840 0.043840 + 0.085380 0.081830 + 0.126020 0.098890 + 0.173070 0.113700 + 0.225630 0.125450 + 0.343100 0.136890 + 0.405650 0.135010 + 0.469030 0.128320 + 0.532130 0.117850 + 0.653880 0.089820 + 0.711010 0.074320 + 0.764750 0.059150 + 0.814500 0.045100 + 0.899560 0.022380 + 0.933650 0.014140 + 0.961390 0.007980 + 0.982280 0.002440 + 0.982280 0.001830 + 0.961390 0.002090 + 0.933510 0.000850 + 0.859090 -0.008040 + 0.813820 -0.016050 + 0.764090 -0.026350 + 0.710600 -0.038510 + 0.594970 -0.065500 + 0.534160 -0.078430 + 0.472340 -0.089680 + 0.410300 -0.098140 + 0.289530 -0.102840 + 0.233070 -0.098960 + 0.180640 -0.091900 + 0.133180 -0.082080 + 0.056790 -0.055970 + 0.029750 -0.040380 + 0.011270 -0.024430 + 0.000000 0.000000 \ No newline at end of file diff --git a/Test_Cases/MHK_RM1/Airfoils/NACA6_0247.dat b/Test_Cases/MHK_RM1/Airfoils/NACA6_0247.dat new file mode 100644 index 00000000..116e81c9 --- /dev/null +++ b/Test_Cases/MHK_RM1/Airfoils/NACA6_0247.dat @@ -0,0 +1,560 @@ +! ------------ AirfoilInfo v1.01.x Input File ---------------------------------- +! NACA6_0247 airfoil, data based on values used for the design of the RM1 tidal current turbine. +! line +! line +! ------------------------------------------------------------------------------ +"default" InterpOrd ! Interpolation order to use for quasi-steady table lookup {1=linear; 3=cubic spline; "default"} [default=1] + 1.0 NonDimArea ! The non-dimensional area of the airfoil (area/chord^2) (set to 1.0 if unsure or unneeded) +@"NACA6_0247_coords.txt" NumCoords ! The number of coordinates in the airfoil shape file. Set to zero if coordinates not included. +"unused" BL_file ! The file name including the boundary layer characteristics of the profile. Ignored if the aeroacoustic module is not called. + 7 NumTabs ! Number of airfoil tables in this file. +! ------------------------------------------------------------------------------ +! data for table 1 +! ------------------------------------------------------------------------------ + 2.000 Re ! Reynolds number in millions + 0 UserProp ! User property (control) setting +False InclUAdata ! Is unsteady aerodynamics data included in this table? If TRUE, then include 30 UA coefficients below this line +!........................................ +! Table of aerodynamics coefficients + 72 NumAlf ! Number of data lines in the following table +! Alpha Cl Cd Cpmin +! (deg) (-) (-) (-) + -180.000 0.0000 0.0127 -1.0184 + -170.000 0.3091 0.0127 -1.0184 + -160.000 0.6183 0.0727 -1.0184 + -150.000 0.9274 0.2433 -1.0184 + -140.000 0.7628 0.4535 -1.0184 + -130.000 0.6254 0.6783 -1.0184 + -120.000 0.4816 0.8918 -1.0184 + -110.000 0.3245 1.0691 -1.0184 + -100.000 0.1595 1.1900 -1.0184 + -90.000 0.0000 1.2413 -1.0184 + -80.000 -0.1595 1.1900 -1.0184 + -70.000 -0.3245 1.0691 -1.0184 + -60.000 -0.4816 0.8918 -1.0184 + -50.000 -0.6254 0.6783 -1.0184 + -40.000 -0.7628 0.4535 -1.0184 + -30.000 -0.9274 0.2433 -1.0184 + -20.000 -0.6720 0.1322 -1.0184 + -10.000 -0.5951 0.0209 -2.3716 + -9.000 -0.5650 0.0176 -2.1434 + -8.000 -0.5351 0.0150 -1.9228 + -7.000 -0.4818 0.0138 -1.6688 + -6.000 -0.3875 0.0128 -1.4222 + -5.000 -0.2803 0.0120 -1.2263 + -4.000 -0.1683 0.0113 -1.0428 + -3.000 -0.0542 0.0103 -0.9248 + -2.000 0.0665 0.0101 -0.9240 + -1.000 0.1867 0.0100 -1.0073 + 0.000 0.3064 0.0101 -1.0954 + 1.000 0.4267 0.0101 -1.1863 + 2.000 0.5452 0.0103 -1.2768 + 3.000 0.6616 0.0105 -1.3708 + 4.000 0.7735 0.0109 -1.4655 + 5.000 0.8839 0.0113 -1.5694 + 6.000 0.9739 0.0124 -1.6771 + 7.000 1.0102 0.0141 -1.7583 + 8.000 1.0430 0.0163 -1.8837 + 9.000 1.0831 0.0192 -2.0347 + 10.000 1.1247 0.0226 -2.1924 + 11.000 1.1327 0.0284 -2.3091 + 12.000 1.1622 0.0338 -2.5578 + 13.000 1.1717 0.0416 -2.7695 + 14.000 1.1976 0.0487 -3.0320 + 15.000 1.2159 0.0573 -3.2881 + 16.000 1.2441 0.0656 -3.5904 + 17.000 1.2688 0.0746 -3.9016 + 18.000 1.2917 0.0845 -4.2305 + 19.000 1.3130 0.0949 -4.5598 + 20.000 1.3315 0.1061 -4.8996 + 21.000 1.3488 0.1176 -5.2476 + 22.000 1.3682 0.1287 -5.6212 + 23.000 1.3766 0.1416 -5.9601 + 24.000 1.3832 0.1546 -6.2942 + 25.000 1.3841 0.1681 -6.6093 + 26.000 1.3794 0.1825 -6.8790 + 28.000 1.3547 0.2120 -7.2711 + 29.000 1.3364 0.2285 -7.3706 + 30.000 1.3248 0.2433 -7.4930 + 40.000 1.0898 0.4535 -1.0184 + 50.000 0.8934 0.6783 -1.0184 + 60.000 0.6880 0.8918 -1.0184 + 70.000 0.4635 1.0691 -1.0184 + 80.000 0.2279 1.1900 -1.0184 + 90.000 0.0000 1.2413 -1.0184 + 100.000 -0.1595 1.1900 -1.0184 + 110.000 -0.3245 1.0691 -1.0184 + 120.000 -0.4816 0.8918 -1.0184 + 130.000 -0.6254 0.6783 -1.0184 + 140.000 -0.7628 0.4535 -1.0184 + 150.000 -0.9274 0.2433 -1.0184 + 160.000 -0.6183 0.0727 -1.0184 + 170.000 -0.3091 0.0127 -1.0184 + 180.000 0.0000 0.0127 -1.0184 +! ------------------------------------------------------------------------------ +! data for table 2 +! ------------------------------------------------------------------------------ + 4.000 Re ! Reynolds number in millions + 0 UserProp ! User property (control) setting +False InclUAdata ! Is unsteady aerodynamics data included in this table? If TRUE, then include 30 UA coefficients below this line +!........................................ +! Table of aerodynamics coefficients + 69 NumAlf ! Number of data lines in the following table +! Alpha Cl Cd Cpmin +! (deg) (-) (-) (-) + -180.000 0.0000 0.0161 -1.0184 + -170.000 0.3240 0.0161 -1.0184 + -160.000 0.6481 0.0643 -1.0184 + -150.000 0.9721 0.2358 -1.0184 + -140.000 0.7901 0.4472 -1.0184 + -130.000 0.6414 0.6736 -1.0184 + -120.000 0.4902 0.8889 -1.0184 + -110.000 0.3281 1.0682 -1.0184 + -100.000 0.1604 1.1913 -1.0184 + -90.000 0.0000 1.2447 -1.0184 + -80.000 -0.1604 1.1913 -1.0184 + -70.000 -0.3281 1.0682 -1.0184 + -60.000 -0.4902 0.8889 -1.0184 + -50.000 -0.6414 0.6736 -1.0184 + -40.000 -0.7901 0.4472 -1.0184 + -30.000 -0.9721 0.2358 -1.0184 + -20.000 -0.7103 0.1287 -1.0184 + -10.000 -0.6407 0.0216 -2.4678 + -9.000 -0.5941 0.0192 -2.1986 + -8.000 -0.5748 0.0172 -1.9910 + -7.000 -0.4904 0.0161 -1.6842 + -6.000 -0.3874 0.0153 -1.4225 + -5.000 -0.2784 0.0146 -1.2245 + -4.000 -0.1624 0.0141 -1.0367 + -3.000 -0.0450 0.0134 -0.9185 + -1.000 0.1964 0.0126 -1.0130 + 0.000 0.3183 0.0125 -1.1029 + 1.000 0.4382 0.0127 -1.1936 + 2.000 0.5593 0.0127 -1.2860 + 5.000 0.8894 0.0144 -1.5722 + 6.000 0.9679 0.0158 -1.6738 + 7.000 1.0216 0.0170 -1.7675 + 9.000 1.1223 0.0207 -2.0830 + 10.000 1.1420 0.0248 -2.2147 + 11.000 1.1764 0.0290 -2.3933 + 12.000 1.1917 0.0350 -2.6199 + 13.000 1.2200 0.0409 -2.8779 + 14.000 1.2485 0.0475 -3.1607 + 15.000 1.2822 0.0542 -3.4675 + 16.000 1.3094 0.0621 -3.7847 + 17.000 1.3374 0.0703 -4.1296 + 18.000 1.3607 0.0795 -4.4731 + 19.000 1.3837 0.0892 -4.8260 + 20.000 1.3985 0.1004 -5.1757 + 21.000 1.4139 0.1118 -5.5324 + 22.000 1.4271 0.1238 -5.9031 + 23.000 1.4316 0.1369 -6.2403 + 24.000 1.4453 0.1485 -6.6498 + 25.000 1.4460 0.1620 -6.9893 + 26.000 1.4467 0.1752 -7.3214 + 27.000 1.4428 0.1890 -7.6156 + 28.000 1.4349 0.2032 -7.8664 + 29.000 1.4050 0.2205 -7.9334 + 30.000 1.3887 0.2358 -8.0633 + 40.000 1.1286 0.4472 -1.0184 + 50.000 0.9164 0.6736 -1.0184 + 60.000 0.7003 0.8889 -1.0184 + 70.000 0.4687 1.0682 -1.0184 + 80.000 0.2292 1.1913 -1.0184 + 90.000 0.0000 1.2447 -1.0184 + 100.000 -0.1604 1.1913 -1.0184 + 110.000 -0.3281 1.0682 -1.0184 + 120.000 -0.4902 0.8889 -1.0184 + 130.000 -0.6414 0.6736 -1.0184 + 140.000 -0.7901 0.4472 -1.0184 + 150.000 -0.9721 0.2358 -1.0184 + 160.000 -0.6481 0.0643 -1.0184 + 170.000 -0.3240 0.0161 -1.0184 + 180.000 0.0000 0.0161 -1.0184 +! ------------------------------------------------------------------------------ +! data for table 3 +! ------------------------------------------------------------------------------ + 6.000 Re ! Reynolds number in millions + 0 UserProp ! User property (control) setting +False InclUAdata ! Is unsteady aerodynamics data included in this table? If TRUE, then include 30 UA coefficients below this line +!........................................ +! Table of aerodynamics coefficients + 71 NumAlf ! Number of data lines in the following table +! Alpha Cl Cd Cpmin +! (deg) (-) (-) (-) + -180.000 0.0000 0.0164 -1.0184 + -170.000 0.3361 0.0164 -1.0184 + -160.000 0.6722 0.0556 -1.0184 + -150.000 1.0082 0.2279 -1.0184 + -140.000 0.8121 0.4401 -1.0184 + -130.000 0.6544 0.6677 -1.0184 + -120.000 0.4972 0.8844 -1.0184 + -110.000 0.3311 1.0652 -1.0184 + -100.000 0.1612 1.1899 -1.0184 + -90.000 0.0000 1.2449 -1.0184 + -80.000 -0.1612 1.1899 -1.0184 + -70.000 -0.3311 1.0652 -1.0184 + -60.000 -0.4972 0.8844 -1.0184 + -50.000 -0.6544 0.6677 -1.0184 + -40.000 -0.8121 0.4401 -1.0184 + -30.000 -1.0082 0.2279 -1.0184 + -20.000 -0.7376 0.1242 -1.0184 + -10.000 -0.6671 0.0204 -2.5232 + -9.000 -0.6253 0.0182 -2.2561 + -8.000 -0.5854 0.0169 -2.0095 + -7.000 -0.4921 0.0160 -1.6870 + -6.000 -0.3891 0.0152 -1.4250 + -5.000 -0.2763 0.0145 -1.2222 + -4.000 -0.1596 0.0141 -1.0335 + -3.000 -0.0415 0.0136 -0.9164 + -2.000 0.0786 0.0128 -0.9309 + -1.000 0.2006 0.0125 -1.0155 + 0.000 0.3224 0.0125 -1.1052 + 1.000 0.4449 0.0125 -1.1979 + 2.000 0.5630 0.0128 -1.2886 + 4.000 0.7893 0.0137 -1.4801 + 5.000 0.8864 0.0148 -1.5719 + 6.000 0.9711 0.0160 -1.6692 + 7.000 1.0350 0.0169 -1.7807 + 8.000 1.0963 0.0180 -1.9415 + 9.000 1.1306 0.0205 -2.0928 + 10.000 1.1668 0.0238 -2.2485 + 11.000 1.1903 0.0282 -2.4208 + 12.000 1.2202 0.0332 -2.6800 + 13.000 1.2469 0.0390 -2.9395 + 14.000 1.2848 0.0448 -3.2520 + 15.000 1.3147 0.0515 -3.5584 + 16.000 1.3441 0.0589 -3.8876 + 17.000 1.3711 0.0670 -4.2404 + 19.000 1.4146 0.0857 -4.9446 + 20.000 1.4472 0.0942 -5.3741 + 21.000 1.4594 0.1057 -5.7281 + 22.000 1.4671 0.1182 -6.0914 + 23.000 1.4716 0.1312 -6.4466 + 24.000 1.4780 0.1440 -6.8329 + 25.000 1.4806 0.1570 -7.1964 + 26.000 1.4781 0.1706 -7.5228 + 27.000 1.4711 0.1848 -7.8093 + 28.000 1.4629 0.1990 -8.0719 + 29.000 1.4530 0.2132 -8.3045 + 30.000 1.4403 0.2279 -8.4935 + 40.000 1.1600 0.4401 -1.0184 + 50.000 0.9349 0.6677 -1.0184 + 60.000 0.7103 0.8844 -1.0184 + 70.000 0.4731 1.0652 -1.0184 + 80.000 0.2303 1.1899 -1.0184 + 90.000 0.0000 1.2449 -1.0184 + 100.000 -0.1612 1.1899 -1.0184 + 110.000 -0.3311 1.0652 -1.0184 + 120.000 -0.4972 0.8844 -1.0184 + 130.000 -0.6544 0.6677 -1.0184 + 140.000 -0.8121 0.4401 -1.0184 + 150.000 -1.0082 0.2279 -1.0184 + 160.000 -0.6722 0.0556 -1.0184 + 170.000 -0.3361 0.0164 -1.0184 + 180.000 0.0000 0.0164 -1.0184 +! ------------------------------------------------------------------------------ +! data for table 4 +! ------------------------------------------------------------------------------ + 8.000 Re ! Reynolds number in millions + 0 UserProp ! User property (control) setting +False InclUAdata ! Is unsteady aerodynamics data included in this table? If TRUE, then include 30 UA coefficients below this line +!........................................ +! Table of aerodynamics coefficients + 62 NumAlf ! Number of data lines in the following table +! Alpha Cl Cd Cpmin +! (deg) (-) (-) (-) + -180.000 0.0000 0.0164 -1.0184 + -170.000 0.4028 0.0164 -1.0184 + -160.000 0.8055 0.0714 -1.0184 + -150.000 0.9497 0.2425 -1.0184 + -140.000 0.7764 0.4531 -1.0184 + -130.000 0.6334 0.6786 -1.0184 + -120.000 0.4859 0.8928 -1.0184 + -110.000 0.3263 1.0710 -1.0184 + -100.000 0.1600 1.1928 -1.0184 + -90.000 0.0000 1.2449 -1.0184 + -80.000 -0.1600 1.1928 -1.0184 + -70.000 -0.3263 1.0710 -1.0184 + -60.000 -0.4859 0.8928 -1.0184 + -50.000 -0.6334 0.6786 -1.0184 + -40.000 -0.7764 0.4531 -1.0184 + -30.000 -0.9497 0.2425 -1.0184 + -20.000 -0.8323 0.1125 -1.0184 + -10.000 -0.6772 0.0199 -2.5523 + -9.000 -0.6491 0.0173 -2.3010 + -8.000 -0.5935 0.0164 -2.0240 + -5.000 -0.2759 0.0143 -1.2216 + -4.000 -0.1590 0.0138 -1.0329 + -3.000 -0.0392 0.0134 -0.9053 + -2.000 0.0807 0.0128 -0.9322 + -1.000 0.2027 0.0124 -1.0165 + 0.000 0.3258 0.0123 -1.1074 + 1.000 0.4464 0.0123 -1.1986 + 2.000 0.5644 0.0126 -1.2901 + 3.000 0.6806 0.0130 -1.3842 + 4.000 0.7885 0.0138 -1.4705 + 6.000 0.9773 0.0158 -1.6681 + 7.000 1.0538 0.0165 -1.7974 + 8.000 1.1114 0.0175 -1.9592 + 9.000 1.1426 0.0200 -2.1081 + 11.000 1.2028 0.0276 -2.4451 + 12.000 1.2407 0.0318 -2.7233 + 13.000 1.2803 0.0366 -3.0192 + 15.000 1.3499 0.0484 -3.6569 + 16.000 1.3794 0.0554 -3.9960 + 17.000 1.4094 0.0629 -4.3668 + 18.000 1.4298 0.0718 -4.7137 + 19.000 1.4528 0.0811 -5.0914 + 20.000 1.4683 0.0917 -5.4589 + 22.000 1.4856 0.1157 -6.1771 + 25.000 1.4974 0.1546 -7.2952 + 26.000 1.4959 0.1680 -7.6343 + 30.000 1.3567 0.2425 -6.1504 + 40.000 1.1092 0.4531 -1.0184 + 50.000 0.9049 0.6786 -1.0184 + 60.000 0.6941 0.8928 -1.0184 + 70.000 0.4662 1.0710 -1.0184 + 80.000 0.2286 1.1928 -1.0184 + 90.000 0.0000 1.2449 -1.0184 + 100.000 -0.1600 1.1928 -1.0184 + 110.000 -0.3263 1.0710 -1.0184 + 120.000 -0.4859 0.8928 -1.0184 + 130.000 -0.6334 0.6786 -1.0184 + 140.000 -0.7764 0.4531 -1.0184 + 150.000 -0.9497 0.2425 -1.0184 + 160.000 -0.8055 0.0714 -1.0184 + 170.000 -0.4028 0.0164 -1.0184 + 180.000 0.0000 0.0164 -1.0184 +! ------------------------------------------------------------------------------ +! data for table 5 +! ------------------------------------------------------------------------------ + 10.000 Re ! Reynolds number in millions + 0 UserProp ! User property (control) setting +False InclUAdata ! Is unsteady aerodynamics data included in this table? If TRUE, then include 30 UA coefficients below this line +!........................................ +! Table of aerodynamics coefficients + 67 NumAlf ! Number of data lines in the following table +! Alpha Cl Cd Cpmin +! (deg) (-) (-) (-) + -180.000 0.0000 0.0164 -1.0184 + -170.000 0.3476 0.0164 -1.0184 + -160.000 0.6952 0.0461 -1.0184 + -150.000 1.0428 0.2192 -1.0184 + -140.000 0.8331 0.4324 -1.0184 + -130.000 0.6669 0.6613 -1.0184 + -120.000 0.5038 0.8793 -1.0184 + -110.000 0.3340 1.0617 -1.0184 + -100.000 0.1619 1.1882 -1.0184 + -90.000 0.0000 1.2449 -1.0184 + -80.000 -0.1619 1.1882 -1.0184 + -70.000 -0.3340 1.0617 -1.0184 + -60.000 -0.5038 0.8793 -1.0184 + -50.000 -0.6669 0.6613 -1.0184 + -40.000 -0.8331 0.4324 -1.0184 + -30.000 -1.0428 0.2192 -1.0184 + -20.000 -0.7576 0.1195 -1.0184 + -10.000 -0.6748 0.0198 -2.5287 + -9.000 -0.6788 0.0169 -2.3603 + -8.000 -0.6005 0.0161 -2.0366 + -6.000 -0.3905 0.0146 -1.4292 + -4.000 -0.1581 0.0136 -1.0320 + -3.000 -0.0384 0.0133 -0.9066 + -2.000 0.0822 0.0128 -0.9330 + -1.000 0.2048 0.0123 -1.0178 + 0.000 0.3272 0.0122 -1.1082 + 1.000 0.4470 0.0123 -1.1992 + 2.000 0.5647 0.0126 -1.2921 + 4.000 0.7865 0.0139 -1.4660 + 5.000 0.8848 0.0149 -1.5609 + 6.000 0.9805 0.0157 -1.6743 + 7.000 1.0743 0.0163 -1.8155 + 8.000 1.1181 0.0174 -1.9667 + 9.000 1.1587 0.0194 -2.1286 + 10.000 1.1764 0.0232 -2.2457 + 11.000 1.2237 0.0264 -2.4868 + 12.000 1.2590 0.0306 -2.7620 + 13.000 1.2973 0.0354 -3.0595 + 14.000 1.3355 0.0406 -3.3796 + 16.000 1.4002 0.0535 -4.0606 + 17.000 1.4249 0.0613 -4.4170 + 18.000 1.4496 0.0698 -4.7822 + 19.000 1.4688 0.0792 -5.1523 + 20.000 1.4833 0.0898 -5.5194 + 21.000 1.4908 0.1016 -5.8650 + 24.000 1.5293 0.1362 -7.1149 + 25.000 1.5329 0.1490 -7.5030 + 26.000 1.5333 0.1622 -7.8676 + 27.000 1.5294 0.1756 -8.1977 + 28.000 1.5197 0.1896 -8.4783 + 29.000 1.5057 0.2043 -8.7098 + 30.000 1.4898 0.2192 -8.9039 + 40.000 1.1901 0.4324 -1.0184 + 50.000 0.9526 0.6613 -1.0184 + 60.000 0.7198 0.8793 -1.0184 + 70.000 0.4772 1.0617 -1.0184 + 80.000 0.2313 1.1882 -1.0184 + 90.000 0.0000 1.2449 -1.0184 + 100.000 -0.1619 1.1882 -1.0184 + 110.000 -0.3340 1.0617 -1.0184 + 120.000 -0.5038 0.8793 -1.0184 + 130.000 -0.6669 0.6613 -1.0184 + 140.000 -0.8331 0.4324 -1.0184 + 150.000 -1.0428 0.2192 -1.0184 + 160.000 -0.6952 0.0461 -1.0184 + 170.000 -0.3476 0.0164 -1.0184 + 180.000 0.0000 0.0164 -1.0184 +! ------------------------------------------------------------------------------ +! data for table 6 +! ------------------------------------------------------------------------------ + 12.000 Re ! Reynolds number in millions + 0 UserProp ! User property (control) setting +False InclUAdata ! Is unsteady aerodynamics data included in this table? If TRUE, then include 30 UA coefficients below this line +!........................................ +! Table of aerodynamics coefficients + 68 NumAlf ! Number of data lines in the following table +! Alpha Cl Cd Cpmin +! (deg) (-) (-) (-) + -180.000 0.0000 0.0164 -1.0184 + -170.000 0.3661 0.0164 -1.0184 + -160.000 0.7321 0.0493 -1.0184 + -150.000 1.0351 0.2220 -1.0184 + -140.000 0.8284 0.4351 -1.0184 + -130.000 0.6641 0.6634 -1.0184 + -120.000 0.5023 0.8810 -1.0184 + -110.000 0.3334 1.0629 -1.0184 + -100.000 0.1617 1.1888 -1.0184 + -90.000 0.0000 1.2449 -1.0184 + -80.000 -0.1617 1.1888 -1.0184 + -70.000 -0.3334 1.0629 -1.0184 + -60.000 -0.5023 0.8810 -1.0184 + -50.000 -0.6641 0.6634 -1.0184 + -40.000 -0.8284 0.4351 -1.0184 + -30.000 -1.0351 0.2220 -1.0184 + -20.000 -0.7869 0.1157 -1.0184 + -10.000 -0.6880 0.0192 -2.5579 + -7.000 -0.5004 0.0152 -1.7011 + -6.000 -0.3895 0.0146 -1.4180 + -5.000 -0.2755 0.0139 -1.2216 + -4.000 -0.1580 0.0135 -1.0316 + -3.000 -0.0376 0.0132 -0.9093 + -2.000 0.0838 0.0128 -0.9338 + -1.000 0.2059 0.0122 -1.0186 + 0.000 0.3280 0.0122 -1.1084 + 1.000 0.4477 0.0122 -1.2000 + 2.000 0.5655 0.0125 -1.2881 + 3.000 0.6800 0.0130 -1.3744 + 4.000 0.7870 0.0138 -1.4696 + 5.000 0.8855 0.0148 -1.5637 + 6.000 0.9873 0.0154 -1.6808 + 7.000 1.0818 0.0161 -1.8229 + 8.000 1.1249 0.0172 -1.9747 + 10.000 1.1916 0.0224 -2.2714 + 11.000 1.2363 0.0257 -2.5121 + 12.000 1.2792 0.0294 -2.8052 + 13.000 1.3196 0.0338 -3.1125 + 14.000 1.3493 0.0396 -3.4141 + 15.000 1.3829 0.0456 -3.7489 + 17.000 1.4395 0.0600 -4.4651 + 18.000 1.4628 0.0684 -4.8274 + 19.000 1.4818 0.0778 -5.2016 + 20.000 1.4914 0.0888 -5.5513 + 22.000 1.5317 0.1092 -6.3912 + 23.000 1.5395 0.1215 -6.7971 + 24.000 1.5451 0.1340 -7.2017 + 25.000 1.5478 0.1469 -7.5887 + 26.000 1.5468 0.1602 -7.9504 + 27.000 1.5396 0.1740 -8.2650 + 28.000 1.5291 0.1883 -8.5435 + 29.000 1.5165 0.2026 -8.7905 + 30.000 1.4788 0.2220 -8.3144 + 40.000 1.1834 0.4351 -1.0184 + 50.000 0.9487 0.6634 -1.0184 + 60.000 0.7176 0.8810 -1.0184 + 70.000 0.4763 1.0629 -1.0184 + 80.000 0.2311 1.1888 -1.0184 + 90.000 0.0000 1.2449 -1.0184 + 100.000 -0.1617 1.1888 -1.0184 + 110.000 -0.3334 1.0629 -1.0184 + 120.000 -0.5023 0.8810 -1.0184 + 130.000 -0.6641 0.6634 -1.0184 + 140.000 -0.8284 0.4351 -1.0184 + 150.000 -1.0351 0.2220 -1.0184 + 160.000 -0.7321 0.0493 -1.0184 + 170.000 -0.3661 0.0164 -1.0184 + 180.000 0.0000 0.0164 -1.0184 +! ------------------------------------------------------------------------------ +! data for table 7 +! ------------------------------------------------------------------------------ + 14.000 Re ! Reynolds number in millions + 0 UserProp ! User property (control) setting +False InclUAdata ! Is unsteady aerodynamics data included in this table? If TRUE, then include 30 UA coefficients below this line +!........................................ +! Table of aerodynamics coefficients + 64 NumAlf ! Number of data lines in the following table +! Alpha Cl Cd Cpmin +! (deg) (-) (-) (-) + -180.000 0.0000 0.0164 -1.0184 + -170.000 0.3528 0.0164 -1.0184 + -160.000 0.7055 0.0422 -1.0184 + -150.000 1.0584 0.2155 -1.0184 + -140.000 0.8426 0.4292 -1.0184 + -130.000 0.6724 0.6586 -1.0184 + -120.000 0.5068 0.8773 -1.0184 + -110.000 0.3353 1.0604 -1.0184 + -100.000 0.1622 1.1874 -1.0184 + -90.000 0.0000 1.2449 -1.0184 + -80.000 -0.1622 1.1874 -1.0184 + -70.000 -0.3353 1.0604 -1.0184 + -60.000 -0.5068 0.8773 -1.0184 + -50.000 -0.6724 0.6586 -1.0184 + -40.000 -0.8426 0.4292 -1.0184 + -30.000 -1.0584 0.2155 -1.0184 + -20.000 -0.7746 0.1171 -1.0184 + -10.000 -0.7013 0.0187 -2.5858 + -9.000 -0.6819 0.0169 -2.3531 + -8.000 -0.6071 0.0156 -2.0491 + -6.000 -0.3894 0.0145 -1.4156 + -5.000 -0.2754 0.0138 -1.2213 + -4.000 -0.1579 0.0133 -1.0315 + -3.000 -0.0368 0.0131 -0.9097 + -2.000 0.0849 0.0127 -0.9345 + -1.000 0.2064 0.0122 -1.0188 + 0.000 0.3289 0.0121 -1.1092 + 1.000 0.4466 0.0123 -1.2002 + 2.000 0.5654 0.0125 -1.2873 + 3.000 0.6786 0.0131 -1.3726 + 5.000 0.8885 0.0147 -1.5669 + 6.000 0.9903 0.0154 -1.6841 + 7.000 1.0893 0.0159 -1.8303 + 8.000 1.1291 0.0170 -1.9792 + 11.000 1.2479 0.0251 -2.5351 + 12.000 1.2907 0.0287 -2.8294 + 14.000 1.3702 0.0380 -3.4665 + 16.000 1.4249 0.0513 -4.1369 + 18.000 1.4739 0.0672 -4.8655 + 21.000 1.5334 0.0960 -6.0511 + 22.000 1.5435 0.1076 -6.4448 + 23.000 1.5524 0.1197 -6.8631 + 24.000 1.5570 0.1323 -7.2661 + 25.000 1.5586 0.1454 -7.6507 + 26.000 1.5542 0.1590 -7.9959 + 27.000 1.5471 0.1729 -8.3137 + 28.000 1.5378 0.1869 -8.6045 + 29.000 1.5264 0.2010 -8.8638 + 30.000 1.5119 0.2155 -9.0822 + 40.000 1.2036 0.4292 -1.0184 + 50.000 0.9607 0.6586 -1.0184 + 60.000 0.7241 0.8773 -1.0184 + 70.000 0.4790 1.0604 -1.0184 + 80.000 0.2317 1.1874 -1.0184 + 90.000 0.0000 1.2449 -1.0184 + 100.000 -0.1622 1.1874 -1.0184 + 110.000 -0.3353 1.0604 -1.0184 + 120.000 -0.5068 0.8773 -1.0184 + 130.000 -0.6724 0.6586 -1.0184 + 140.000 -0.8426 0.4292 -1.0184 + 150.000 -1.0584 0.2155 -1.0184 + 160.000 -0.7055 0.0422 -1.0184 + 170.000 -0.3528 0.0164 -1.0184 + 180.000 0.0000 0.0164 -1.0184 \ No newline at end of file diff --git a/Test_Cases/MHK_RM1/Airfoils/NACA6_0247_coords.txt b/Test_Cases/MHK_RM1/Airfoils/NACA6_0247_coords.txt new file mode 100644 index 00000000..76becdc1 --- /dev/null +++ b/Test_Cases/MHK_RM1/Airfoils/NACA6_0247_coords.txt @@ -0,0 +1,47 @@ + 40 NumCoords ! The number of coordinates in the airfoil shape file (including an extra coordinate for airfoil reference). Set to zero if coordinates not included. +! ......... x-y coordinates are next if NumCoords > 0 ............. +! x-y coordinate of airfoil reference +! x/c y/c + 0.25 0 +! coordinates of airfoil shape +! NACA6_0247 Airfoil +! x/c y/c + 0.000000 0.000000 + 0.006819 0.021573 + 0.027091 0.045571 + 0.060263 0.070519 + 0.105430 0.093593 + 0.161359 0.113695 + 0.226526 0.129332 + 0.299152 0.139084 + 0.377257 0.140958 + 0.458710 0.134375 + 0.541290 0.120926 + 0.622743 0.102688 + 0.700848 0.081979 + 0.773474 0.061268 + 0.838641 0.042604 + 0.894570 0.027238 + 0.939737 0.015604 + 0.972909 0.007552 + 0.993181 0.002511 + 1.000000 0.000000 + 0.993181 -0.000009 + 0.972909 0.000021 + 0.939737 -0.001786 + 0.894570 -0.006851 + 0.838641 -0.015998 + 0.773474 -0.029320 + 0.700848 -0.046093 + 0.622743 -0.064559 + 0.541290 -0.082348 + 0.458710 -0.096978 + 0.377257 -0.106009 + 0.299152 -0.107583 + 0.226526 -0.102345 + 0.161359 -0.091881 + 0.105430 -0.077436 + 0.060263 -0.059906 + 0.027091 -0.040088 + 0.006819 -0.019333 + 0.000000 0.000000 \ No newline at end of file diff --git a/Test_Cases/MHK_RM1/Airfoils/NACA6_0259.dat b/Test_Cases/MHK_RM1/Airfoils/NACA6_0259.dat new file mode 100644 index 00000000..2122f139 --- /dev/null +++ b/Test_Cases/MHK_RM1/Airfoils/NACA6_0259.dat @@ -0,0 +1,560 @@ +! ------------ AirfoilInfo v1.01.x Input File ---------------------------------- +! NACA6_0259 airfoil, data based on values used for the design of the RM1 tidal current turbine. +! line +! line +! ------------------------------------------------------------------------------ +"default" InterpOrd ! Interpolation order to use for quasi-steady table lookup {1=linear; 3=cubic spline; "default"} [default=1] + 1.0 NonDimArea ! The non-dimensional area of the airfoil (area/chord^2) (set to 1.0 if unsure or unneeded) +@"NACA6_0259_coords.txt" NumCoords ! The number of coordinates in the airfoil shape file. Set to zero if coordinates not included. +"unused" BL_file ! The file name including the boundary layer characteristics of the profile. Ignored if the aeroacoustic module is not called. + 7 NumTabs ! Number of airfoil tables in this file. +! ------------------------------------------------------------------------------ +! data for table 1 +! ------------------------------------------------------------------------------ + 2.000 Re ! Reynolds number in millions + 0 UserProp ! User property (control) setting +False InclUAdata ! Is unsteady aerodynamics data included in this table? If TRUE, then include 30 UA coefficients below this line +!........................................ +! Table of aerodynamics coefficients + 72 NumAlf ! Number of data lines in the following table +! Alpha Cl Cd Cpmin +! (deg) (-) (-) (-) + -180.000 0.0000 0.0173 -1.0500 + -170.000 0.3042 0.0173 -1.0500 + -160.000 0.6084 0.0763 -1.0500 + -150.000 0.9126 0.2442 -1.0500 + -140.000 0.7507 0.4510 -1.0500 + -130.000 0.6154 0.6723 -1.0500 + -120.000 0.4739 0.8824 -1.0500 + -110.000 0.3193 1.0569 -1.0500 + -100.000 0.1570 1.1758 -1.0500 + -90.000 0.0000 1.2263 -1.0500 + -80.000 -0.1570 1.1758 -1.0500 + -70.000 -0.3193 1.0569 -1.0500 + -60.000 -0.4739 0.8824 -1.0500 + -50.000 -0.6154 0.6723 -1.0500 + -40.000 -0.7507 0.4510 -1.0500 + -30.000 -0.9126 0.2442 -1.0500 + -20.000 -0.6612 0.1348 -1.0500 + -10.000 -0.5856 0.0253 -2.3817 + -9.000 -0.5560 0.0221 -2.1570 + -8.000 -0.5266 0.0196 -1.9400 + -7.000 -0.4741 0.0183 -1.6900 + -6.000 -0.3813 0.0173 -1.4473 + -5.000 -0.2758 0.0166 -1.2546 + -4.000 -0.1657 0.0159 -1.0740 + -3.000 -0.0533 0.0149 -0.9579 + -2.000 0.0654 0.0147 -0.9571 + -1.000 0.1837 0.0146 -1.0391 + 0.000 0.3015 0.0147 -1.1258 + 1.000 0.4199 0.0147 -1.2152 + 2.000 0.5365 0.0149 -1.3043 + 3.000 0.6510 0.0151 -1.3968 + 4.000 0.7612 0.0155 -1.4899 + 5.000 0.8698 0.0159 -1.5922 + 6.000 0.9584 0.0170 -1.6982 + 7.000 0.9941 0.0186 -1.7781 + 8.000 1.0264 0.0209 -1.9015 + 9.000 1.0659 0.0237 -2.0501 + 10.000 1.1068 0.0270 -2.2053 + 11.000 1.1146 0.0328 -2.3201 + 12.000 1.1437 0.0380 -2.5649 + 13.000 1.1530 0.0457 -2.7732 + 14.000 1.1785 0.0527 -3.0315 + 15.000 1.1965 0.0611 -3.2835 + 16.000 1.2243 0.0693 -3.5810 + 17.000 1.2486 0.0782 -3.8873 + 18.000 1.2711 0.0879 -4.2109 + 19.000 1.2921 0.0982 -4.5349 + 20.000 1.3103 0.1092 -4.8694 + 21.000 1.3273 0.1205 -5.2118 + 22.000 1.3464 0.1314 -5.5795 + 23.000 1.3547 0.1441 -5.9129 + 24.000 1.3612 0.1569 -6.2417 + 25.000 1.3621 0.1702 -6.5518 + 26.000 1.3574 0.1844 -6.8172 + 28.000 1.3331 0.2134 -7.2030 + 29.000 1.3151 0.2296 -7.3009 + 30.000 1.3037 0.2442 -7.4214 + 40.000 1.0724 0.4510 -1.0500 + 50.000 0.8792 0.6723 -1.0500 + 60.000 0.6770 0.8824 -1.0500 + 70.000 0.4561 1.0569 -1.0500 + 80.000 0.2243 1.1758 -1.0500 + 90.000 0.0000 1.2263 -1.0500 + 100.000 -0.1570 1.1758 -1.0500 + 110.000 -0.3193 1.0569 -1.0500 + 120.000 -0.4739 0.8824 -1.0500 + 130.000 -0.6154 0.6723 -1.0500 + 140.000 -0.7507 0.4510 -1.0500 + 150.000 -0.9126 0.2442 -1.0500 + 160.000 -0.6084 0.0763 -1.0500 + 170.000 -0.3042 0.0173 -1.0500 + 180.000 0.0000 0.0173 -1.0500 +! ------------------------------------------------------------------------------ +! data for table 2 +! ------------------------------------------------------------------------------ + 4.000 Re ! Reynolds number in millions + 0 UserProp ! User property (control) setting +False InclUAdata ! Is unsteady aerodynamics data included in this table? If TRUE, then include 30 UA coefficients below this line +!........................................ +! Table of aerodynamics coefficients + 69 NumAlf ! Number of data lines in the following table +! Alpha Cl Cd Cpmin +! (deg) (-) (-) (-) + -180.000 0.0000 0.0265 -1.0500 + -170.000 0.3188 0.0265 -1.0500 + -160.000 0.6377 0.0740 -1.0500 + -150.000 0.9566 0.2428 -1.0500 + -140.000 0.7775 0.4507 -1.0500 + -130.000 0.6312 0.6735 -1.0500 + -120.000 0.4824 0.8854 -1.0500 + -110.000 0.3229 1.0619 -1.0500 + -100.000 0.1579 1.1829 -1.0500 + -90.000 0.0000 1.2355 -1.0500 + -80.000 -0.1579 1.1829 -1.0500 + -70.000 -0.3229 1.0619 -1.0500 + -60.000 -0.4824 0.8854 -1.0500 + -50.000 -0.6312 0.6735 -1.0500 + -40.000 -0.7775 0.4507 -1.0500 + -30.000 -0.9566 0.2428 -1.0500 + -20.000 -0.6990 0.1374 -1.0500 + -10.000 -0.6305 0.0320 -2.4763 + -9.000 -0.5846 0.0296 -2.2114 + -8.000 -0.5656 0.0276 -2.0071 + -7.000 -0.4826 0.0265 -1.7052 + -6.000 -0.3812 0.0257 -1.4476 + -5.000 -0.2740 0.0250 -1.2528 + -4.000 -0.1598 0.0246 -1.0679 + -3.000 -0.0443 0.0239 -0.9516 + -1.000 0.1932 0.0231 -1.0446 + 0.000 0.3133 0.0230 -1.1332 + 1.000 0.4312 0.0232 -1.2224 + 2.000 0.5504 0.0232 -1.3133 + 5.000 0.8753 0.0248 -1.5949 + 6.000 0.9525 0.0262 -1.6950 + 7.000 1.0053 0.0274 -1.7871 + 9.000 1.1044 0.0311 -2.0976 + 10.000 1.1238 0.0351 -2.2272 + 11.000 1.1576 0.0392 -2.4030 + 12.000 1.1727 0.0451 -2.6260 + 13.000 1.2005 0.0510 -2.8799 + 14.000 1.2286 0.0574 -3.1581 + 15.000 1.2617 0.0640 -3.4600 + 16.000 1.2886 0.0717 -3.7722 + 17.000 1.3161 0.0798 -4.1116 + 18.000 1.3390 0.0889 -4.4496 + 19.000 1.3617 0.0985 -4.7969 + 20.000 1.3762 0.1095 -5.1410 + 21.000 1.3913 0.1207 -5.4920 + 22.000 1.4044 0.1325 -5.8568 + 23.000 1.4088 0.1454 -6.1886 + 24.000 1.4222 0.1569 -6.5916 + 25.000 1.4229 0.1701 -6.9257 + 26.000 1.4236 0.1831 -7.2526 + 27.000 1.4198 0.1966 -7.5420 + 28.000 1.4120 0.2107 -7.7888 + 29.000 1.3826 0.2276 -7.8548 + 30.000 1.3666 0.2428 -7.9826 + 40.000 1.1106 0.4507 -1.0500 + 50.000 0.9018 0.6735 -1.0500 + 60.000 0.6891 0.8854 -1.0500 + 70.000 0.4613 1.0619 -1.0500 + 80.000 0.2255 1.1829 -1.0500 + 90.000 0.0000 1.2355 -1.0500 + 100.000 -0.1579 1.1829 -1.0500 + 110.000 -0.3229 1.0619 -1.0500 + 120.000 -0.4824 0.8854 -1.0500 + 130.000 -0.6312 0.6735 -1.0500 + 140.000 -0.7775 0.4507 -1.0500 + 150.000 -0.9566 0.2428 -1.0500 + 160.000 -0.6377 0.0740 -1.0500 + 170.000 -0.3188 0.0265 -1.0500 + 180.000 0.0000 0.0265 -1.0500 +! ------------------------------------------------------------------------------ +! data for table 3 +! ------------------------------------------------------------------------------ + 6.000 Re ! Reynolds number in millions + 0 UserProp ! User property (control) setting +False InclUAdata ! Is unsteady aerodynamics data included in this table? If TRUE, then include 30 UA coefficients below this line +!........................................ +! Table of aerodynamics coefficients + 71 NumAlf ! Number of data lines in the following table +! Alpha Cl Cd Cpmin +! (deg) (-) (-) (-) + -180.000 0.0000 0.0273 -1.0500 + -170.000 0.3307 0.0273 -1.0500 + -160.000 0.6614 0.0659 -1.0500 + -150.000 0.9922 0.2354 -1.0500 + -140.000 0.7991 0.4443 -1.0500 + -130.000 0.6440 0.6682 -1.0500 + -120.000 0.4893 0.8814 -1.0500 + -110.000 0.3258 1.0594 -1.0500 + -100.000 0.1586 1.1821 -1.0500 + -90.000 0.0000 1.2363 -1.0500 + -80.000 -0.1586 1.1821 -1.0500 + -70.000 -0.3258 1.0594 -1.0500 + -60.000 -0.4893 0.8814 -1.0500 + -50.000 -0.6440 0.6682 -1.0500 + -40.000 -0.7991 0.4443 -1.0500 + -30.000 -0.9922 0.2354 -1.0500 + -20.000 -0.7259 0.1333 -1.0500 + -10.000 -0.6565 0.0312 -2.5308 + -9.000 -0.6153 0.0291 -2.2680 + -8.000 -0.5760 0.0277 -2.0253 + -7.000 -0.4843 0.0269 -1.7079 + -6.000 -0.3829 0.0261 -1.4501 + -5.000 -0.2719 0.0254 -1.2506 + -4.000 -0.1571 0.0250 -1.0648 + -3.000 -0.0409 0.0245 -0.9496 + -2.000 0.0773 0.0237 -0.9639 + -1.000 0.1974 0.0234 -1.0472 + 0.000 0.3173 0.0234 -1.1354 + 1.000 0.4378 0.0234 -1.2266 + 2.000 0.5540 0.0237 -1.3159 + 4.000 0.7767 0.0246 -1.5044 + 5.000 0.8722 0.0257 -1.5946 + 6.000 0.9556 0.0269 -1.6904 + 7.000 1.0185 0.0277 -1.8002 + 8.000 1.0788 0.0289 -1.9584 + 9.000 1.1126 0.0313 -2.1073 + 10.000 1.1482 0.0346 -2.2605 + 11.000 1.1714 0.0390 -2.4300 + 12.000 1.2007 0.0438 -2.6851 + 13.000 1.2270 0.0496 -2.9404 + 14.000 1.2643 0.0552 -3.2479 + 15.000 1.2937 0.0619 -3.5495 + 16.000 1.3227 0.0691 -3.8735 + 17.000 1.3492 0.0771 -4.2206 + 19.000 1.3921 0.0955 -4.9136 + 20.000 1.4242 0.1039 -5.3363 + 21.000 1.4362 0.1152 -5.6847 + 22.000 1.4437 0.1275 -6.0421 + 23.000 1.4482 0.1403 -6.3916 + 24.000 1.4544 0.1528 -6.7718 + 25.000 1.4570 0.1657 -7.1295 + 26.000 1.4545 0.1791 -7.4507 + 27.000 1.4477 0.1930 -7.7327 + 28.000 1.4396 0.2069 -7.9910 + 29.000 1.4298 0.2210 -8.2200 + 30.000 1.4174 0.2354 -8.4060 + 40.000 1.1415 0.4443 -1.0500 + 50.000 0.9200 0.6682 -1.0500 + 60.000 0.6990 0.8814 -1.0500 + 70.000 0.4656 1.0594 -1.0500 + 80.000 0.2266 1.1821 -1.0500 + 90.000 0.0000 1.2363 -1.0500 + 100.000 -0.1586 1.1821 -1.0500 + 110.000 -0.3258 1.0594 -1.0500 + 120.000 -0.4893 0.8814 -1.0500 + 130.000 -0.6440 0.6682 -1.0500 + 140.000 -0.7991 0.4443 -1.0500 + 150.000 -0.9922 0.2354 -1.0500 + 160.000 -0.6614 0.0659 -1.0500 + 170.000 -0.3307 0.0273 -1.0500 + 180.000 0.0000 0.0273 -1.0500 +! ------------------------------------------------------------------------------ +! data for table 4 +! ------------------------------------------------------------------------------ + 8.000 Re ! Reynolds number in millions + 0 UserProp ! User property (control) setting +False InclUAdata ! Is unsteady aerodynamics data included in this table? If TRUE, then include 30 UA coefficients below this line +!........................................ +! Table of aerodynamics coefficients + 62 NumAlf ! Number of data lines in the following table +! Alpha Cl Cd Cpmin +! (deg) (-) (-) (-) + -180.000 0.0000 0.0273 -1.0500 + -170.000 0.3963 0.0273 -1.0500 + -160.000 0.7927 0.0815 -1.0500 + -150.000 0.9345 0.2497 -1.0500 + -140.000 0.7640 0.4570 -1.0500 + -130.000 0.6233 0.6789 -1.0500 + -120.000 0.4781 0.8897 -1.0500 + -110.000 0.3211 1.0650 -1.0500 + -100.000 0.1575 1.1850 -1.0500 + -90.000 0.0000 1.2363 -1.0500 + -80.000 -0.1575 1.1850 -1.0500 + -70.000 -0.3211 1.0650 -1.0500 + -60.000 -0.4781 0.8897 -1.0500 + -50.000 -0.6233 0.6789 -1.0500 + -40.000 -0.7640 0.4570 -1.0500 + -30.000 -0.9345 0.2497 -1.0500 + -20.000 -0.8190 0.1218 -1.0500 + -10.000 -0.6664 0.0308 -2.5594 + -9.000 -0.6387 0.0282 -2.3121 + -8.000 -0.5840 0.0273 -2.0395 + -5.000 -0.2715 0.0252 -1.2500 + -4.000 -0.1565 0.0247 -1.0642 + -3.000 -0.0386 0.0243 -0.9387 + -2.000 0.0795 0.0237 -0.9652 + -1.000 0.1995 0.0234 -1.0481 + 0.000 0.3206 0.0233 -1.1376 + 1.000 0.4392 0.0233 -1.2274 + 2.000 0.5554 0.0235 -1.3173 + 3.000 0.6697 0.0239 -1.4100 + 4.000 0.7759 0.0247 -1.4949 + 6.000 0.9617 0.0267 -1.6893 + 7.000 1.0370 0.0273 -1.8165 + 8.000 1.0937 0.0284 -1.9758 + 9.000 1.1244 0.0309 -2.1223 + 11.000 1.1836 0.0383 -2.4539 + 12.000 1.2209 0.0425 -2.7277 + 13.000 1.2599 0.0471 -3.0189 + 15.000 1.3283 0.0587 -3.6464 + 16.000 1.3574 0.0657 -3.9802 + 17.000 1.3869 0.0731 -4.3450 + 18.000 1.4070 0.0819 -4.6864 + 19.000 1.4296 0.0909 -5.0580 + 20.000 1.4449 0.1014 -5.4198 + 22.000 1.4619 0.1250 -6.1264 + 25.000 1.4735 0.1633 -7.2267 + 26.000 1.4721 0.1765 -7.5605 + 30.000 1.3351 0.2497 -6.1002 + 40.000 1.0915 0.4570 -1.0500 + 50.000 0.8905 0.6789 -1.0500 + 60.000 0.6831 0.8897 -1.0500 + 70.000 0.4587 1.0650 -1.0500 + 80.000 0.2249 1.1850 -1.0500 + 90.000 0.0000 1.2363 -1.0500 + 100.000 -0.1575 1.1850 -1.0500 + 110.000 -0.3211 1.0650 -1.0500 + 120.000 -0.4781 0.8897 -1.0500 + 130.000 -0.6233 0.6789 -1.0500 + 140.000 -0.7640 0.4570 -1.0500 + 150.000 -0.9345 0.2497 -1.0500 + 160.000 -0.7927 0.0815 -1.0500 + 170.000 -0.3963 0.0273 -1.0500 + 180.000 0.0000 0.0273 -1.0500 +! ------------------------------------------------------------------------------ +! data for table 5 +! ------------------------------------------------------------------------------ + 10.000 Re ! Reynolds number in millions + 0 UserProp ! User property (control) setting +False InclUAdata ! Is unsteady aerodynamics data included in this table? If TRUE, then include 30 UA coefficients below this line +!........................................ +! Table of aerodynamics coefficients + 67 NumAlf ! Number of data lines in the following table +! Alpha Cl Cd Cpmin +! (deg) (-) (-) (-) + -180.000 0.0000 0.0273 -1.0500 + -170.000 0.3420 0.0273 -1.0500 + -160.000 0.6842 0.0565 -1.0500 + -150.000 1.0262 0.2268 -1.0500 + -140.000 0.8198 0.4367 -1.0500 + -130.000 0.6563 0.6619 -1.0500 + -120.000 0.4958 0.8765 -1.0500 + -110.000 0.3287 1.0560 -1.0500 + -100.000 0.1593 1.1804 -1.0500 + -90.000 0.0000 1.2363 -1.0500 + -80.000 -0.1593 1.1804 -1.0500 + -70.000 -0.3287 1.0560 -1.0500 + -60.000 -0.4958 0.8765 -1.0500 + -50.000 -0.6563 0.6619 -1.0500 + -40.000 -0.8198 0.4367 -1.0500 + -30.000 -1.0262 0.2268 -1.0500 + -20.000 -0.7455 0.1287 -1.0500 + -10.000 -0.6641 0.0307 -2.5362 + -9.000 -0.6680 0.0278 -2.3705 + -8.000 -0.5909 0.0270 -2.0519 + -6.000 -0.3842 0.0255 -1.4542 + -4.000 -0.1556 0.0245 -1.0634 + -3.000 -0.0378 0.0242 -0.9399 + -2.000 0.0809 0.0237 -0.9660 + -1.000 0.2015 0.0233 -1.0494 + 0.000 0.3219 0.0232 -1.1383 + 1.000 0.4399 0.0233 -1.2279 + 2.000 0.5557 0.0235 -1.3193 + 4.000 0.7740 0.0248 -1.4904 + 5.000 0.8707 0.0258 -1.5838 + 6.000 0.9649 0.0266 -1.6955 + 7.000 1.0572 0.0272 -1.8344 + 8.000 1.1003 0.0283 -1.9832 + 9.000 1.1403 0.0303 -2.1425 + 10.000 1.1576 0.0340 -2.2577 + 11.000 1.2042 0.0371 -2.4950 + 12.000 1.2389 0.0413 -2.7658 + 13.000 1.2767 0.0460 -3.0586 + 14.000 1.3142 0.0511 -3.3735 + 16.000 1.3779 0.0638 -4.0437 + 17.000 1.4021 0.0715 -4.3944 + 18.000 1.4265 0.0798 -4.7538 + 19.000 1.4454 0.0891 -5.1180 + 20.000 1.4597 0.0995 -5.4792 + 21.000 1.4671 0.1111 -5.8193 + 24.000 1.5049 0.1452 -7.0494 + 25.000 1.5085 0.1578 -7.4313 + 26.000 1.5089 0.1708 -7.7900 + 27.000 1.5050 0.1839 -8.1148 + 28.000 1.4955 0.1978 -8.3910 + 29.000 1.4817 0.2122 -8.6188 + 30.000 1.4660 0.2268 -8.8098 + 40.000 1.1712 0.4367 -1.0500 + 50.000 0.9375 0.6619 -1.0500 + 60.000 0.7083 0.8765 -1.0500 + 70.000 0.4696 1.0560 -1.0500 + 80.000 0.2276 1.1804 -1.0500 + 90.000 0.0000 1.2363 -1.0500 + 100.000 -0.1593 1.1804 -1.0500 + 110.000 -0.3287 1.0560 -1.0500 + 120.000 -0.4958 0.8765 -1.0500 + 130.000 -0.6563 0.6619 -1.0500 + 140.000 -0.8198 0.4367 -1.0500 + 150.000 -1.0262 0.2268 -1.0500 + 160.000 -0.6842 0.0565 -1.0500 + 170.000 -0.3420 0.0273 -1.0500 + 180.000 0.0000 0.0273 -1.0500 +! ------------------------------------------------------------------------------ +! data for table 6 +! ------------------------------------------------------------------------------ + 12.000 Re ! Reynolds number in millions + 0 UserProp ! User property (control) setting +False InclUAdata ! Is unsteady aerodynamics data included in this table? If TRUE, then include 30 UA coefficients below this line +!........................................ +! Table of aerodynamics coefficients + 68 NumAlf ! Number of data lines in the following table +! Alpha Cl Cd Cpmin +! (deg) (-) (-) (-) + -180.000 0.0000 0.0273 -1.0500 + -170.000 0.3603 0.0273 -1.0500 + -160.000 0.7204 0.0597 -1.0500 + -150.000 1.0186 0.2297 -1.0500 + -140.000 0.8152 0.4393 -1.0500 + -130.000 0.6535 0.6640 -1.0500 + -120.000 0.4943 0.8781 -1.0500 + -110.000 0.3281 1.0571 -1.0500 + -100.000 0.1591 1.1810 -1.0500 + -90.000 0.0000 1.2363 -1.0500 + -80.000 -0.1591 1.1810 -1.0500 + -70.000 -0.3281 1.0571 -1.0500 + -60.000 -0.4943 0.8781 -1.0500 + -50.000 -0.6535 0.6640 -1.0500 + -40.000 -0.8152 0.4393 -1.0500 + -30.000 -1.0186 0.2297 -1.0500 + -20.000 -0.7743 0.1250 -1.0500 + -10.000 -0.6770 0.0301 -2.5650 + -7.000 -0.4925 0.0261 -1.7218 + -6.000 -0.3833 0.0255 -1.4432 + -5.000 -0.2711 0.0248 -1.2500 + -4.000 -0.1555 0.0244 -1.0630 + -3.000 -0.0370 0.0241 -0.9427 + -2.000 0.0825 0.0237 -0.9667 + -1.000 0.2026 0.0232 -1.0502 + 0.000 0.3227 0.0232 -1.1385 + 1.000 0.4406 0.0232 -1.2287 + 2.000 0.5565 0.0234 -1.3154 + 3.000 0.6691 0.0239 -1.4003 + 4.000 0.7744 0.0247 -1.4940 + 5.000 0.8714 0.0257 -1.5865 + 6.000 0.9716 0.0263 -1.7018 + 7.000 1.0646 0.0270 -1.8417 + 8.000 1.1070 0.0281 -1.9911 + 10.000 1.1726 0.0332 -2.2830 + 11.000 1.2166 0.0364 -2.5199 + 12.000 1.2588 0.0401 -2.8083 + 13.000 1.2986 0.0444 -3.1107 + 14.000 1.3278 0.0502 -3.4075 + 15.000 1.3609 0.0560 -3.7370 + 17.000 1.4166 0.0702 -4.4417 + 18.000 1.4395 0.0784 -4.7983 + 19.000 1.4582 0.0877 -5.1665 + 20.000 1.4677 0.0985 -5.5106 + 22.000 1.5073 0.1186 -6.3371 + 23.000 1.5150 0.1307 -6.7366 + 24.000 1.5205 0.1430 -7.1348 + 25.000 1.5231 0.1558 -7.5156 + 26.000 1.5222 0.1688 -7.8715 + 27.000 1.5151 0.1824 -8.1811 + 28.000 1.5047 0.1964 -8.4551 + 29.000 1.4923 0.2106 -8.6982 + 30.000 1.4552 0.2297 -8.2297 + 40.000 1.1645 0.4393 -1.0500 + 50.000 0.9336 0.6640 -1.0500 + 60.000 0.7062 0.8781 -1.0500 + 70.000 0.4687 1.0571 -1.0500 + 80.000 0.2274 1.1810 -1.0500 + 90.000 0.0000 1.2363 -1.0500 + 100.000 -0.1591 1.1810 -1.0500 + 110.000 -0.3281 1.0571 -1.0500 + 120.000 -0.4943 0.8781 -1.0500 + 130.000 -0.6535 0.6640 -1.0500 + 140.000 -0.8152 0.4393 -1.0500 + 150.000 -1.0186 0.2297 -1.0500 + 160.000 -0.7204 0.0597 -1.0500 + 170.000 -0.3603 0.0273 -1.0500 + 180.000 0.0000 0.0273 -1.0500 +! ------------------------------------------------------------------------------ +! data for table 7 +! ------------------------------------------------------------------------------ + 14.000 Re ! Reynolds number in millions + 0 UserProp ! User property (control) setting +False InclUAdata ! Is unsteady aerodynamics data included in this table? If TRUE, then include 30 UA coefficients below this line +!........................................ +! Table of aerodynamics coefficients + 64 NumAlf ! Number of data lines in the following table +! Alpha Cl Cd Cpmin +! (deg) (-) (-) (-) + -180.000 0.0000 0.0273 -1.0500 + -170.000 0.3472 0.0273 -1.0500 + -160.000 0.6943 0.0527 -1.0500 + -150.000 1.0415 0.2232 -1.0500 + -140.000 0.8291 0.4335 -1.0500 + -130.000 0.6617 0.6592 -1.0500 + -120.000 0.4987 0.8744 -1.0500 + -110.000 0.3299 1.0546 -1.0500 + -100.000 0.1596 1.1796 -1.0500 + -90.000 0.0000 1.2363 -1.0500 + -80.000 -0.1596 1.1796 -1.0500 + -70.000 -0.3299 1.0546 -1.0500 + -60.000 -0.4987 0.8744 -1.0500 + -50.000 -0.6617 0.6592 -1.0500 + -40.000 -0.8291 0.4335 -1.0500 + -30.000 -1.0415 0.2232 -1.0500 + -20.000 -0.7623 0.1264 -1.0500 + -10.000 -0.6901 0.0296 -2.5924 + -9.000 -0.6710 0.0277 -2.3634 + -8.000 -0.5974 0.0265 -2.0643 + -6.000 -0.3832 0.0254 -1.4409 + -5.000 -0.2711 0.0247 -1.2497 + -4.000 -0.1554 0.0242 -1.0629 + -3.000 -0.0362 0.0240 -0.9430 + -2.000 0.0836 0.0236 -0.9674 + -1.000 0.2031 0.0232 -1.0504 + 0.000 0.3237 0.0231 -1.1393 + 1.000 0.4395 0.0233 -1.2289 + 2.000 0.5564 0.0234 -1.3146 + 3.000 0.6678 0.0240 -1.3986 + 5.000 0.8744 0.0256 -1.5898 + 6.000 0.9745 0.0263 -1.7051 + 7.000 1.0719 0.0268 -1.8489 + 8.000 1.1111 0.0279 -1.9955 + 11.000 1.2280 0.0358 -2.5425 + 12.000 1.2701 0.0394 -2.8321 + 14.000 1.3483 0.0485 -3.4590 + 16.000 1.4021 0.0617 -4.1188 + 18.000 1.4504 0.0773 -4.8357 + 21.000 1.5090 0.1056 -6.0025 + 22.000 1.5189 0.1170 -6.3899 + 23.000 1.5276 0.1289 -6.8015 + 24.000 1.5322 0.1413 -7.1982 + 25.000 1.5338 0.1542 -7.5766 + 26.000 1.5294 0.1677 -7.9162 + 27.000 1.5225 0.1813 -8.2290 + 28.000 1.5133 0.1950 -8.5152 + 29.000 1.5021 0.2090 -8.7703 + 30.000 1.4878 0.2232 -8.9852 + 40.000 1.1844 0.4335 -1.0500 + 50.000 0.9454 0.6592 -1.0500 + 60.000 0.7125 0.8744 -1.0500 + 70.000 0.4714 1.0546 -1.0500 + 80.000 0.2281 1.1796 -1.0500 + 90.000 0.0000 1.2363 -1.0500 + 100.000 -0.1596 1.1796 -1.0500 + 110.000 -0.3299 1.0546 -1.0500 + 120.000 -0.4987 0.8744 -1.0500 + 130.000 -0.6617 0.6592 -1.0500 + 140.000 -0.8291 0.4335 -1.0500 + 150.000 -1.0415 0.2232 -1.0500 + 160.000 -0.6943 0.0527 -1.0500 + 170.000 -0.3472 0.0273 -1.0500 + 180.000 0.0000 0.0273 -1.0500 \ No newline at end of file diff --git a/Test_Cases/MHK_RM1/Airfoils/NACA6_0259_coords.txt b/Test_Cases/MHK_RM1/Airfoils/NACA6_0259_coords.txt new file mode 100644 index 00000000..94bdcf9e --- /dev/null +++ b/Test_Cases/MHK_RM1/Airfoils/NACA6_0259_coords.txt @@ -0,0 +1,47 @@ + 40 NumCoords ! The number of coordinates in the airfoil shape file (including an extra coordinate for airfoil reference). Set to zero if coordinates not included. +! ......... x-y coordinates are next if NumCoords > 0 ............. +! x-y coordinate of airfoil reference +! x/c y/c + 0.25 0 +! coordinates of airfoil shape +! NACA6_0259 Airfoil +! x/c y/c + 0.000000 0.000000 + 0.006819 0.022584 + 0.027091 0.047510 + 0.060263 0.073301 + 0.105430 0.097140 + 0.161359 0.117917 + 0.226526 0.134137 + 0.299152 0.144379 + 0.377257 0.146668 + 0.458710 0.140419 + 0.541290 0.127194 + 0.622743 0.109034 + 0.700848 0.088223 + 0.773474 0.067204 + 0.838641 0.048007 + 0.894570 0.031887 + 0.939737 0.019298 + 0.972909 0.010124 + 0.993181 0.003839 + 1.000000 0.000000 + 0.993181 -0.001378 + 0.972909 -0.002676 + 0.939737 -0.005710 + 0.894570 -0.011838 + 0.838641 -0.021843 + 0.773474 -0.035786 + 0.700848 -0.052933 + 0.622743 -0.071538 + 0.541290 -0.089257 + 0.458710 -0.103644 + 0.377257 -0.112299 + 0.299152 -0.113402 + 0.226526 -0.107598 + 0.161359 -0.096465 + 0.105430 -0.081252 + 0.060263 -0.062864 + 0.027091 -0.042119 + 0.006819 -0.020381 + 0.000000 0.000000 \ No newline at end of file diff --git a/Test_Cases/MHK_RM1/Airfoils/NACA6_0276.dat b/Test_Cases/MHK_RM1/Airfoils/NACA6_0276.dat new file mode 100644 index 00000000..05644926 --- /dev/null +++ b/Test_Cases/MHK_RM1/Airfoils/NACA6_0276.dat @@ -0,0 +1,560 @@ +! ------------ AirfoilInfo v1.01.x Input File ---------------------------------- +! NACA6_0276 airfoil, data based on values used for the design of the RM1 tidal current turbine. +! line +! line +! ------------------------------------------------------------------------------ +"default" InterpOrd ! Interpolation order to use for quasi-steady table lookup {1=linear; 3=cubic spline; "default"} [default=1] + 1.0 NonDimArea ! The non-dimensional area of the airfoil (area/chord^2) (set to 1.0 if unsure or unneeded) +@"NACA6_0276_coords.txt" NumCoords ! The number of coordinates in the airfoil shape file. Set to zero if coordinates not included. +"unused" BL_file ! The file name including the boundary layer characteristics of the profile. Ignored if the aeroacoustic module is not called. + 7 NumTabs ! Number of airfoil tables in this file. +! ------------------------------------------------------------------------------ +! data for table 1 +! ------------------------------------------------------------------------------ + 2.000 Re ! Reynolds number in millions + 0 UserProp ! User property (control) setting +False InclUAdata ! Is unsteady aerodynamics data included in this table? If TRUE, then include 30 UA coefficients below this line +!........................................ +! Table of aerodynamics coefficients + 72 NumAlf ! Number of data lines in the following table +! Alpha Cl Cd Cpmin +! (deg) (-) (-) (-) + -180.000 0.0000 0.0237 -1.0947 + -170.000 0.2972 0.0237 -1.0947 + -160.000 0.5944 0.0815 -1.0947 + -150.000 0.8917 0.2455 -1.0947 + -140.000 0.7334 0.4476 -1.0947 + -130.000 0.6013 0.6637 -1.0947 + -120.000 0.4631 0.8690 -1.0947 + -110.000 0.3120 1.0395 -1.0947 + -100.000 0.1534 1.1557 -1.0947 + -90.000 0.0000 1.2050 -1.0947 + -80.000 -0.1534 1.1557 -1.0947 + -70.000 -0.3120 1.0395 -1.0947 + -60.000 -0.4631 0.8690 -1.0947 + -50.000 -0.6013 0.6637 -1.0947 + -40.000 -0.7334 0.4476 -1.0947 + -30.000 -0.8917 0.2455 -1.0947 + -20.000 -0.6461 0.1386 -1.0947 + -10.000 -0.5722 0.0316 -2.3958 + -9.000 -0.5433 0.0285 -2.1764 + -8.000 -0.5145 0.0260 -1.9643 + -7.000 -0.4633 0.0248 -1.7200 + -6.000 -0.3726 0.0238 -1.4829 + -5.000 -0.2695 0.0231 -1.2946 + -4.000 -0.1619 0.0224 -1.1182 + -3.000 -0.0521 0.0215 -1.0047 + -2.000 0.0639 0.0213 -1.0040 + -1.000 0.1795 0.0212 -1.0841 + 0.000 0.2946 0.0213 -1.1688 + 1.000 0.4103 0.0213 -1.2561 + 2.000 0.5242 0.0215 -1.3432 + 3.000 0.6361 0.0216 -1.4336 + 4.000 0.7437 0.0220 -1.5246 + 5.000 0.8498 0.0224 -1.6245 + 6.000 0.9364 0.0235 -1.7280 + 7.000 0.9713 0.0251 -1.8062 + 8.000 1.0028 0.0273 -1.9267 + 9.000 1.0414 0.0300 -2.0719 + 10.000 1.0814 0.0333 -2.2235 + 11.000 1.0890 0.0389 -2.3357 + 12.000 1.1174 0.0440 -2.5748 + 13.000 1.1266 0.0516 -2.7784 + 14.000 1.1514 0.0584 -3.0308 + 15.000 1.1691 0.0666 -3.2770 + 16.000 1.1962 0.0746 -3.5677 + 17.000 1.2199 0.0833 -3.8669 + 18.000 1.2419 0.0928 -4.1831 + 19.000 1.2624 0.1028 -4.4997 + 20.000 1.2802 0.1136 -4.8265 + 21.000 1.2968 0.1246 -5.1610 + 22.000 1.3155 0.1353 -5.5203 + 23.000 1.3236 0.1477 -5.8461 + 24.000 1.3300 0.1602 -6.1673 + 25.000 1.3308 0.1732 -6.4703 + 26.000 1.3263 0.1870 -6.7296 + 28.000 1.3025 0.2154 -7.1066 + 29.000 1.2849 0.2312 -7.2022 + 30.000 1.2738 0.2455 -7.3200 + 40.000 1.0478 0.4476 -1.0947 + 50.000 0.8590 0.6637 -1.0947 + 60.000 0.6615 0.8690 -1.0947 + 70.000 0.4456 1.0395 -1.0947 + 80.000 0.2191 1.1557 -1.0947 + 90.000 0.0000 1.2050 -1.0947 + 100.000 -0.1534 1.1557 -1.0947 + 110.000 -0.3120 1.0395 -1.0947 + 120.000 -0.4631 0.8690 -1.0947 + 130.000 -0.6013 0.6637 -1.0947 + 140.000 -0.7334 0.4476 -1.0947 + 150.000 -0.8917 0.2455 -1.0947 + 160.000 -0.5944 0.0815 -1.0947 + 170.000 -0.2972 0.0237 -1.0947 + 180.000 0.0000 0.0237 -1.0947 +! ------------------------------------------------------------------------------ +! data for table 2 +! ------------------------------------------------------------------------------ + 4.000 Re ! Reynolds number in millions + 0 UserProp ! User property (control) setting +False InclUAdata ! Is unsteady aerodynamics data included in this table? If TRUE, then include 30 UA coefficients below this line +!........................................ +! Table of aerodynamics coefficients + 69 NumAlf ! Number of data lines in the following table +! Alpha Cl Cd Cpmin +! (deg) (-) (-) (-) + -180.000 0.0000 0.0413 -1.0947 + -170.000 0.3115 0.0413 -1.0947 + -160.000 0.6231 0.0877 -1.0947 + -150.000 0.9346 0.2526 -1.0947 + -140.000 0.7596 0.4558 -1.0947 + -130.000 0.6167 0.6734 -1.0947 + -120.000 0.4714 0.8804 -1.0947 + -110.000 0.3155 1.0529 -1.0947 + -100.000 0.1542 1.1712 -1.0947 + -90.000 0.0000 1.2225 -1.0947 + -80.000 -0.1542 1.1712 -1.0947 + -70.000 -0.3155 1.0529 -1.0947 + -60.000 -0.4714 0.8804 -1.0947 + -50.000 -0.6167 0.6734 -1.0947 + -40.000 -0.7596 0.4558 -1.0947 + -30.000 -0.9346 0.2526 -1.0947 + -20.000 -0.6829 0.1496 -1.0947 + -10.000 -0.6161 0.0466 -2.4883 + -9.000 -0.5712 0.0443 -2.2295 + -8.000 -0.5526 0.0423 -2.0298 + -7.000 -0.4716 0.0413 -1.7349 + -6.000 -0.3725 0.0405 -1.4832 + -5.000 -0.2677 0.0398 -1.2929 + -4.000 -0.1561 0.0394 -1.1123 + -3.000 -0.0432 0.0387 -0.9986 + -1.000 0.1888 0.0379 -1.0895 + 0.000 0.3061 0.0378 -1.1760 + 1.000 0.4213 0.0380 -1.2632 + 2.000 0.5378 0.0380 -1.3520 + 5.000 0.8552 0.0396 -1.6272 + 6.000 0.9306 0.0410 -1.7249 + 7.000 0.9823 0.0421 -1.8149 + 9.000 1.0790 0.0457 -2.1183 + 10.000 1.0980 0.0496 -2.2449 + 11.000 1.1311 0.0536 -2.4167 + 12.000 1.1458 0.0595 -2.6346 + 13.000 1.1730 0.0652 -2.8826 + 14.000 1.2004 0.0715 -3.1545 + 15.000 1.2328 0.0779 -3.4495 + 16.000 1.2590 0.0855 -3.7545 + 17.000 1.2859 0.0934 -4.0861 + 18.000 1.3082 0.1022 -4.4164 + 19.000 1.3304 0.1116 -4.7557 + 20.000 1.3446 0.1223 -5.0919 + 21.000 1.3594 0.1333 -5.4348 + 22.000 1.3722 0.1448 -5.7913 + 23.000 1.3765 0.1574 -6.1155 + 24.000 1.3896 0.1686 -6.5092 + 25.000 1.3903 0.1816 -6.8357 + 26.000 1.3909 0.1943 -7.1550 + 27.000 1.3872 0.2075 -7.4378 + 28.000 1.3796 0.2212 -7.6789 + 29.000 1.3509 0.2378 -7.7434 + 30.000 1.3352 0.2526 -7.8683 + 40.000 1.0851 0.4558 -1.0947 + 50.000 0.8811 0.6734 -1.0947 + 60.000 0.6733 0.8804 -1.0947 + 70.000 0.4507 1.0529 -1.0947 + 80.000 0.2203 1.1712 -1.0947 + 90.000 0.0000 1.2225 -1.0947 + 100.000 -0.1542 1.1712 -1.0947 + 110.000 -0.3155 1.0529 -1.0947 + 120.000 -0.4714 0.8804 -1.0947 + 130.000 -0.6167 0.6734 -1.0947 + 140.000 -0.7596 0.4558 -1.0947 + 150.000 -0.9346 0.2526 -1.0947 + 160.000 -0.6231 0.0877 -1.0947 + 170.000 -0.3115 0.0413 -1.0947 + 180.000 0.0000 0.0413 -1.0947 +! ------------------------------------------------------------------------------ +! data for table 3 +! ------------------------------------------------------------------------------ + 6.000 Re ! Reynolds number in millions + 0 UserProp ! User property (control) setting +False InclUAdata ! Is unsteady aerodynamics data included in this table? If TRUE, then include 30 UA coefficients below this line +!........................................ +! Table of aerodynamics coefficients + 71 NumAlf ! Number of data lines in the following table +! Alpha Cl Cd Cpmin +! (deg) (-) (-) (-) + -180.000 0.0000 0.0427 -1.0947 + -170.000 0.3231 0.0427 -1.0947 + -160.000 0.6463 0.0804 -1.0947 + -150.000 0.9694 0.2461 -1.0947 + -140.000 0.7808 0.4501 -1.0947 + -130.000 0.6292 0.6689 -1.0947 + -120.000 0.4780 0.8773 -1.0947 + -110.000 0.3184 1.0511 -1.0947 + -100.000 0.1550 1.1711 -1.0947 + -90.000 0.0000 1.2239 -1.0947 + -80.000 -0.1550 1.1711 -1.0947 + -70.000 -0.3184 1.0511 -1.0947 + -60.000 -0.4780 0.8773 -1.0947 + -50.000 -0.6292 0.6689 -1.0947 + -40.000 -0.7808 0.4501 -1.0947 + -30.000 -0.9694 0.2461 -1.0947 + -20.000 -0.7092 0.1463 -1.0947 + -10.000 -0.6414 0.0466 -2.5416 + -9.000 -0.6012 0.0445 -2.2848 + -8.000 -0.5628 0.0432 -2.0477 + -7.000 -0.4732 0.0423 -1.7376 + -6.000 -0.3741 0.0415 -1.4857 + -5.000 -0.2657 0.0409 -1.2907 + -4.000 -0.1535 0.0405 -1.1092 + -3.000 -0.0399 0.0400 -0.9966 + -2.000 0.0755 0.0393 -1.0106 + -1.000 0.1929 0.0390 -1.0920 + 0.000 0.3100 0.0390 -1.1782 + 1.000 0.4277 0.0390 -1.2673 + 2.000 0.5413 0.0393 -1.3545 + 4.000 0.7589 0.0401 -1.5387 + 5.000 0.8522 0.0412 -1.6269 + 6.000 0.9337 0.0423 -1.7204 + 7.000 0.9951 0.0432 -1.8277 + 8.000 1.0541 0.0443 -1.9823 + 9.000 1.0870 0.0467 -2.1278 + 10.000 1.1218 0.0498 -2.2774 + 11.000 1.1445 0.0541 -2.4431 + 12.000 1.1732 0.0589 -2.6923 + 13.000 1.1989 0.0645 -2.9418 + 14.000 1.2353 0.0700 -3.2423 + 15.000 1.2640 0.0765 -3.5369 + 16.000 1.2923 0.0836 -3.8535 + 17.000 1.3183 0.0914 -4.1926 + 19.000 1.3602 0.1094 -4.8697 + 20.000 1.3915 0.1176 -5.2827 + 21.000 1.4032 0.1286 -5.6231 + 22.000 1.4106 0.1406 -5.9723 + 23.000 1.4149 0.1531 -6.3138 + 24.000 1.4210 0.1654 -6.6853 + 25.000 1.4236 0.1780 -7.0348 + 26.000 1.4211 0.1910 -7.3486 + 27.000 1.4145 0.2046 -7.6241 + 28.000 1.4066 0.2183 -7.8765 + 29.000 1.3970 0.2320 -8.1002 + 30.000 1.3848 0.2461 -8.2820 + 40.000 1.1153 0.4501 -1.0947 + 50.000 0.8989 0.6689 -1.0947 + 60.000 0.6829 0.8773 -1.0947 + 70.000 0.4549 1.0511 -1.0947 + 80.000 0.2214 1.1711 -1.0947 + 90.000 0.0000 1.2239 -1.0947 + 100.000 -0.1550 1.1711 -1.0947 + 110.000 -0.3184 1.0511 -1.0947 + 120.000 -0.4780 0.8773 -1.0947 + 130.000 -0.6292 0.6689 -1.0947 + 140.000 -0.7808 0.4501 -1.0947 + 150.000 -0.9694 0.2461 -1.0947 + 160.000 -0.6463 0.0804 -1.0947 + 170.000 -0.3231 0.0427 -1.0947 + 180.000 0.0000 0.0427 -1.0947 +! ------------------------------------------------------------------------------ +! data for table 4 +! ------------------------------------------------------------------------------ + 8.000 Re ! Reynolds number in millions + 0 UserProp ! User property (control) setting +False InclUAdata ! Is unsteady aerodynamics data included in this table? If TRUE, then include 30 UA coefficients below this line +!........................................ +! Table of aerodynamics coefficients + 62 NumAlf ! Number of data lines in the following table +! Alpha Cl Cd Cpmin +! (deg) (-) (-) (-) + -180.000 0.0000 0.0427 -1.0947 + -170.000 0.3872 0.0427 -1.0947 + -160.000 0.7745 0.0957 -1.0947 + -150.000 0.9131 0.2601 -1.0947 + -140.000 0.7465 0.4626 -1.0947 + -130.000 0.6090 0.6794 -1.0947 + -120.000 0.4672 0.8854 -1.0947 + -110.000 0.3137 1.0567 -1.0947 + -100.000 0.1539 1.1738 -1.0947 + -90.000 0.0000 1.2239 -1.0947 + -80.000 -0.1539 1.1738 -1.0947 + -70.000 -0.3137 1.0567 -1.0947 + -60.000 -0.4672 0.8854 -1.0947 + -50.000 -0.6090 0.6794 -1.0947 + -40.000 -0.7465 0.4626 -1.0947 + -30.000 -0.9131 0.2601 -1.0947 + -20.000 -0.8002 0.1351 -1.0947 + -10.000 -0.6511 0.0461 -2.5695 + -9.000 -0.6241 0.0436 -2.3279 + -8.000 -0.5706 0.0427 -2.0616 + -5.000 -0.2653 0.0407 -1.2901 + -4.000 -0.1529 0.0402 -1.1086 + -3.000 -0.0377 0.0398 -0.9859 + -2.000 0.0776 0.0393 -1.0119 + -1.000 0.1949 0.0389 -1.0929 + 0.000 0.3132 0.0388 -1.1803 + 1.000 0.4292 0.0388 -1.2680 + 2.000 0.5426 0.0391 -1.3559 + 3.000 0.6544 0.0394 -1.4464 + 4.000 0.7581 0.0402 -1.5294 + 6.000 0.9397 0.0421 -1.7194 + 7.000 1.0132 0.0428 -1.8437 + 8.000 1.0686 0.0438 -1.9993 + 9.000 1.0986 0.0462 -2.1424 + 11.000 1.1565 0.0534 -2.4664 + 12.000 1.1929 0.0575 -2.7339 + 13.000 1.2310 0.0621 -3.0185 + 15.000 1.2979 0.0735 -3.6316 + 16.000 1.3263 0.0802 -3.9577 + 17.000 1.3551 0.0875 -4.3142 + 18.000 1.3747 0.0960 -4.6477 + 19.000 1.3968 0.1049 -5.0108 + 20.000 1.4117 0.1151 -5.3642 + 22.000 1.4284 0.1382 -6.0547 + 25.000 1.4397 0.1756 -7.1298 + 26.000 1.4383 0.1885 -7.4558 + 30.000 1.3044 0.2601 -6.0291 + 40.000 1.0665 0.4626 -1.0947 + 50.000 0.8700 0.6794 -1.0947 + 60.000 0.6674 0.8854 -1.0947 + 70.000 0.4482 1.0567 -1.0947 + 80.000 0.2198 1.1738 -1.0947 + 90.000 0.0000 1.2239 -1.0947 + 100.000 -0.1539 1.1738 -1.0947 + 110.000 -0.3137 1.0567 -1.0947 + 120.000 -0.4672 0.8854 -1.0947 + 130.000 -0.6090 0.6794 -1.0947 + 140.000 -0.7465 0.4626 -1.0947 + 150.000 -0.9131 0.2601 -1.0947 + 160.000 -0.7745 0.0957 -1.0947 + 170.000 -0.3872 0.0427 -1.0947 + 180.000 0.0000 0.0427 -1.0947 +! ------------------------------------------------------------------------------ +! data for table 5 +! ------------------------------------------------------------------------------ + 10.000 Re ! Reynolds number in millions + 0 UserProp ! User property (control) setting +False InclUAdata ! Is unsteady aerodynamics data included in this table? If TRUE, then include 30 UA coefficients below this line +!........................................ +! Table of aerodynamics coefficients + 67 NumAlf ! Number of data lines in the following table +! Alpha Cl Cd Cpmin +! (deg) (-) (-) (-) + -180.000 0.0000 0.0427 -1.0947 + -170.000 0.3342 0.0427 -1.0947 + -160.000 0.6685 0.0713 -1.0947 + -150.000 1.0026 0.2377 -1.0947 + -140.000 0.8010 0.4427 -1.0947 + -130.000 0.6412 0.6628 -1.0947 + -120.000 0.4844 0.8724 -1.0947 + -110.000 0.3211 1.0478 -1.0947 + -100.000 0.1557 1.1694 -1.0947 + -90.000 0.0000 1.2239 -1.0947 + -80.000 -0.1557 1.1694 -1.0947 + -70.000 -0.3211 1.0478 -1.0947 + -60.000 -0.4844 0.8724 -1.0947 + -50.000 -0.6412 0.6628 -1.0947 + -40.000 -0.8010 0.4427 -1.0947 + -30.000 -1.0026 0.2377 -1.0947 + -20.000 -0.7284 0.1419 -1.0947 + -10.000 -0.6488 0.0460 -2.5468 + -9.000 -0.6526 0.0433 -2.3850 + -8.000 -0.5774 0.0424 -2.0737 + -6.000 -0.3754 0.0410 -1.4897 + -4.000 -0.1520 0.0400 -1.1078 + -3.000 -0.0370 0.0397 -0.9872 + -2.000 0.0791 0.0393 -1.0126 + -1.000 0.1969 0.0388 -1.0942 + 0.000 0.3146 0.0387 -1.1810 + 1.000 0.4298 0.0388 -1.2686 + 2.000 0.5430 0.0391 -1.3579 + 4.000 0.7562 0.0403 -1.5250 + 5.000 0.8507 0.0413 -1.6163 + 6.000 0.9427 0.0420 -1.7254 + 7.000 1.0329 0.0426 -1.8611 + 8.000 1.0750 0.0437 -2.0065 + 9.000 1.1141 0.0456 -2.1622 + 10.000 1.1311 0.0493 -2.2748 + 11.000 1.1766 0.0523 -2.5065 + 12.000 1.2105 0.0564 -2.7712 + 13.000 1.2474 0.0610 -3.0573 + 14.000 1.2841 0.0660 -3.3650 + 16.000 1.3463 0.0784 -4.0198 + 17.000 1.3700 0.0859 -4.3625 + 18.000 1.3938 0.0940 -4.7136 + 19.000 1.4123 0.1031 -5.0694 + 20.000 1.4262 0.1133 -5.4224 + 21.000 1.4334 0.1246 -5.7546 + 24.000 1.4704 0.1580 -6.9565 + 25.000 1.4739 0.1702 -7.3296 + 26.000 1.4743 0.1829 -7.6801 + 27.000 1.4705 0.1958 -7.9975 + 28.000 1.4611 0.2093 -8.2673 + 29.000 1.4477 0.2234 -8.4899 + 30.000 1.4324 0.2377 -8.6765 + 40.000 1.1443 0.4427 -1.0947 + 50.000 0.9160 0.6628 -1.0947 + 60.000 0.6921 0.8724 -1.0947 + 70.000 0.4588 1.0478 -1.0947 + 80.000 0.2223 1.1694 -1.0947 + 90.000 0.0000 1.2239 -1.0947 + 100.000 -0.1557 1.1694 -1.0947 + 110.000 -0.3211 1.0478 -1.0947 + 120.000 -0.4844 0.8724 -1.0947 + 130.000 -0.6412 0.6628 -1.0947 + 140.000 -0.8010 0.4427 -1.0947 + 150.000 -1.0026 0.2377 -1.0947 + 160.000 -0.6685 0.0713 -1.0947 + 170.000 -0.3342 0.0427 -1.0947 + 180.000 0.0000 0.0427 -1.0947 +! ------------------------------------------------------------------------------ +! data for table 6 +! ------------------------------------------------------------------------------ + 12.000 Re ! Reynolds number in millions + 0 UserProp ! User property (control) setting +False InclUAdata ! Is unsteady aerodynamics data included in this table? If TRUE, then include 30 UA coefficients below this line +!........................................ +! Table of aerodynamics coefficients + 68 NumAlf ! Number of data lines in the following table +! Alpha Cl Cd Cpmin +! (deg) (-) (-) (-) + -180.000 0.0000 0.0427 -1.0947 + -170.000 0.3520 0.0427 -1.0947 + -160.000 0.7039 0.0744 -1.0947 + -150.000 0.9952 0.2405 -1.0947 + -140.000 0.7965 0.4453 -1.0947 + -130.000 0.6385 0.6648 -1.0947 + -120.000 0.4830 0.8740 -1.0947 + -110.000 0.3206 1.0489 -1.0947 + -100.000 0.1555 1.1699 -1.0947 + -90.000 0.0000 1.2239 -1.0947 + -80.000 -0.1555 1.1699 -1.0947 + -70.000 -0.3206 1.0489 -1.0947 + -60.000 -0.4830 0.8740 -1.0947 + -50.000 -0.6385 0.6648 -1.0947 + -40.000 -0.7965 0.4453 -1.0947 + -30.000 -0.9952 0.2405 -1.0947 + -20.000 -0.7566 0.1382 -1.0947 + -10.000 -0.6615 0.0454 -2.5749 + -7.000 -0.4812 0.0415 -1.7511 + -6.000 -0.3745 0.0410 -1.4789 + -5.000 -0.2649 0.0403 -1.2901 + -4.000 -0.1519 0.0399 -1.1074 + -3.000 -0.0361 0.0396 -0.9899 + -2.000 0.0806 0.0393 -1.0134 + -1.000 0.1980 0.0387 -1.0949 + 0.000 0.3153 0.0387 -1.1812 + 1.000 0.4305 0.0387 -1.2694 + 2.000 0.5438 0.0390 -1.3540 + 3.000 0.6538 0.0394 -1.4370 + 4.000 0.7567 0.0402 -1.5286 + 5.000 0.8514 0.0412 -1.6190 + 6.000 0.9493 0.0417 -1.7316 + 7.000 1.0402 0.0424 -1.8683 + 8.000 1.0816 0.0435 -2.0142 + 10.000 1.1457 0.0485 -2.2994 + 11.000 1.1887 0.0516 -2.5309 + 12.000 1.2299 0.0553 -2.8127 + 13.000 1.2688 0.0595 -3.1081 + 14.000 1.2973 0.0651 -3.3981 + 15.000 1.3297 0.0708 -3.7201 + 17.000 1.3841 0.0846 -4.4087 + 18.000 1.4065 0.0927 -4.7570 + 19.000 1.4248 0.1017 -5.1168 + 20.000 1.4340 0.1123 -5.4530 + 22.000 1.4727 0.1319 -6.2606 + 23.000 1.4802 0.1438 -6.6509 + 24.000 1.4856 0.1558 -7.0399 + 25.000 1.4882 0.1682 -7.4120 + 26.000 1.4872 0.1810 -7.7597 + 27.000 1.4803 0.1942 -8.0622 + 28.000 1.4702 0.2080 -8.3300 + 29.000 1.4581 0.2218 -8.5675 + 30.000 1.4218 0.2405 -8.1097 + 40.000 1.1378 0.4453 -1.0947 + 50.000 0.9121 0.6648 -1.0947 + 60.000 0.6900 0.8740 -1.0947 + 70.000 0.4579 1.0489 -1.0947 + 80.000 0.2222 1.1699 -1.0947 + 90.000 0.0000 1.2239 -1.0947 + 100.000 -0.1555 1.1699 -1.0947 + 110.000 -0.3206 1.0489 -1.0947 + 120.000 -0.4830 0.8740 -1.0947 + 130.000 -0.6385 0.6648 -1.0947 + 140.000 -0.7965 0.4453 -1.0947 + 150.000 -0.9952 0.2405 -1.0947 + 160.000 -0.7039 0.0744 -1.0947 + 170.000 -0.3520 0.0427 -1.0947 + 180.000 0.0000 0.0427 -1.0947 +! ------------------------------------------------------------------------------ +! data for table 7 +! ------------------------------------------------------------------------------ + 14.000 Re ! Reynolds number in millions + 0 UserProp ! User property (control) setting +False InclUAdata ! Is unsteady aerodynamics data included in this table? If TRUE, then include 30 UA coefficients below this line +!........................................ +! Table of aerodynamics coefficients + 64 NumAlf ! Number of data lines in the following table +! Alpha Cl Cd Cpmin +! (deg) (-) (-) (-) + -180.000 0.0000 0.0427 -1.0947 + -170.000 0.3392 0.0427 -1.0947 + -160.000 0.6784 0.0675 -1.0947 + -150.000 1.0176 0.2342 -1.0947 + -140.000 0.8101 0.4396 -1.0947 + -130.000 0.6466 0.6602 -1.0947 + -120.000 0.4873 0.8704 -1.0947 + -110.000 0.3224 1.0465 -1.0947 + -100.000 0.1559 1.1686 -1.0947 + -90.000 0.0000 1.2239 -1.0947 + -80.000 -0.1559 1.1686 -1.0947 + -70.000 -0.3224 1.0465 -1.0947 + -60.000 -0.4873 0.8704 -1.0947 + -50.000 -0.6466 0.6602 -1.0947 + -40.000 -0.8101 0.4396 -1.0947 + -30.000 -1.0176 0.2342 -1.0947 + -20.000 -0.7448 0.1396 -1.0947 + -10.000 -0.6743 0.0450 -2.6018 + -9.000 -0.6556 0.0432 -2.3780 + -8.000 -0.5837 0.0419 -2.0858 + -6.000 -0.3744 0.0409 -1.4766 + -5.000 -0.2648 0.0402 -1.2898 + -4.000 -0.1518 0.0397 -1.1073 + -3.000 -0.0353 0.0395 -0.9902 + -2.000 0.0816 0.0392 -1.0140 + -1.000 0.1984 0.0387 -1.0951 + 0.000 0.3163 0.0386 -1.1820 + 1.000 0.4294 0.0388 -1.2695 + 2.000 0.5437 0.0390 -1.3533 + 3.000 0.6525 0.0395 -1.4353 + 5.000 0.8543 0.0411 -1.6221 + 6.000 0.9522 0.0417 -1.7348 + 7.000 1.0473 0.0422 -1.8753 + 8.000 1.0856 0.0434 -2.0185 + 11.000 1.1998 0.0511 -2.5530 + 12.000 1.2410 0.0546 -2.8360 + 14.000 1.3174 0.0635 -3.4485 + 16.000 1.3700 0.0763 -4.0931 + 18.000 1.4171 0.0916 -4.7936 + 21.000 1.4744 0.1193 -5.9336 + 22.000 1.4840 0.1304 -6.3121 + 23.000 1.4926 0.1420 -6.7143 + 24.000 1.4971 0.1541 -7.1018 + 25.000 1.4986 0.1667 -7.4716 + 26.000 1.4943 0.1799 -7.8035 + 27.000 1.4875 0.1932 -8.1091 + 28.000 1.4786 0.2066 -8.3887 + 29.000 1.4676 0.2203 -8.6380 + 30.000 1.4537 0.2342 -8.8479 + 40.000 1.1573 0.4396 -1.0947 + 50.000 0.9237 0.6602 -1.0947 + 60.000 0.6962 0.8704 -1.0947 + 70.000 0.4606 1.0465 -1.0947 + 80.000 0.2228 1.1686 -1.0947 + 90.000 0.0000 1.2239 -1.0947 + 100.000 -0.1559 1.1686 -1.0947 + 110.000 -0.3224 1.0465 -1.0947 + 120.000 -0.4873 0.8704 -1.0947 + 130.000 -0.6466 0.6602 -1.0947 + 140.000 -0.8101 0.4396 -1.0947 + 150.000 -1.0176 0.2342 -1.0947 + 160.000 -0.6784 0.0675 -1.0947 + 170.000 -0.3392 0.0427 -1.0947 + 180.000 0.0000 0.0427 -1.0947 \ No newline at end of file diff --git a/Test_Cases/MHK_RM1/Airfoils/NACA6_0276_coords.txt b/Test_Cases/MHK_RM1/Airfoils/NACA6_0276_coords.txt new file mode 100644 index 00000000..c2553444 --- /dev/null +++ b/Test_Cases/MHK_RM1/Airfoils/NACA6_0276_coords.txt @@ -0,0 +1,47 @@ + 40 NumCoords ! The number of coordinates in the airfoil shape file (including an extra coordinate for airfoil reference). Set to zero if coordinates not included. +! ......... x-y coordinates are next if NumCoords > 0 ............. +! x-y coordinate of airfoil reference +! x/c y/c + 0.25 0 +! coordinates of airfoil shape +! NACA6_0276 Airfoil +! x/c y/c + 0.000000 0.000000 + 0.006819 0.024017 + 0.027091 0.050261 + 0.060263 0.077244 + 0.105430 0.102168 + 0.161359 0.123903 + 0.226526 0.140948 + 0.299152 0.151887 + 0.377257 0.154763 + 0.458710 0.148989 + 0.541290 0.136081 + 0.622743 0.118030 + 0.700848 0.097075 + 0.773474 0.075618 + 0.838641 0.055666 + 0.894570 0.038477 + 0.939737 0.024535 + 0.972909 0.013769 + 0.993181 0.005721 + 1.000000 0.000000 + 0.993181 -0.003319 + 0.972909 -0.006500 + 0.939737 -0.011272 + 0.894570 -0.018909 + 0.838641 -0.030129 + 0.773474 -0.044953 + 0.700848 -0.062630 + 0.622743 -0.081432 + 0.541290 -0.099052 + 0.458710 -0.113095 + 0.377257 -0.121217 + 0.299152 -0.121652 + 0.226526 -0.115046 + 0.161359 -0.102964 + 0.105430 -0.086660 + 0.060263 -0.067057 + 0.027091 -0.044998 + 0.006819 -0.021867 + 0.000000 0.000000 \ No newline at end of file diff --git a/Test_Cases/MHK_RM1/Airfoils/NACA6_0329.dat b/Test_Cases/MHK_RM1/Airfoils/NACA6_0329.dat new file mode 100644 index 00000000..b975b05e --- /dev/null +++ b/Test_Cases/MHK_RM1/Airfoils/NACA6_0329.dat @@ -0,0 +1,560 @@ +! ------------ AirfoilInfo v1.01.x Input File ---------------------------------- +! NACA6_0329 airfoil, data based on values used for the design of the RM1 tidal current turbine. +! line +! line +! ------------------------------------------------------------------------------ +"default" InterpOrd ! Interpolation order to use for quasi-steady table lookup {1=linear; 3=cubic spline; "default"} [default=1] + 1.0 NonDimArea ! The non-dimensional area of the airfoil (area/chord^2) (set to 1.0 if unsure or unneeded) +@"NACA6_0329_coords.txt" NumCoords ! The number of coordinates in the airfoil shape file. Set to zero if coordinates not included. +"unused" BL_file ! The file name including the boundary layer characteristics of the profile. Ignored if the aeroacoustic module is not called. + 7 NumTabs ! Number of airfoil tables in this file. +! ------------------------------------------------------------------------------ +! data for table 1 +! ------------------------------------------------------------------------------ + 2.000 Re ! Reynolds number in millions + 0 UserProp ! User property (control) setting +False InclUAdata ! Is unsteady aerodynamics data included in this table? If TRUE, then include 30 UA coefficients below this line +!........................................ +! Table of aerodynamics coefficients + 72 NumAlf ! Number of data lines in the following table +! Alpha Cl Cd Cpmin +! (deg) (-) (-) (-) + -180.000 0.0000 0.0440 -1.2342 + -170.000 0.2755 0.0440 -1.2342 + -160.000 0.5509 0.0975 -1.2342 + -150.000 0.8264 0.2495 -1.2342 + -140.000 0.6797 0.4368 -1.2342 + -130.000 0.5573 0.6371 -1.2342 + -120.000 0.4292 0.8274 -1.2342 + -110.000 0.2891 0.9854 -1.2342 + -100.000 0.1421 1.0931 -1.2342 + -90.000 0.0000 1.1387 -1.2342 + -80.000 -0.1421 1.0931 -1.2342 + -70.000 -0.2891 0.9854 -1.2342 + -60.000 -0.4292 0.8274 -1.2342 + -50.000 -0.5573 0.6371 -1.2342 + -40.000 -0.6797 0.4368 -1.2342 + -30.000 -0.8264 0.2495 -1.2342 + -20.000 -0.5988 0.1504 -1.2342 + -10.000 -0.5303 0.0513 -2.4401 + -9.000 -0.5035 0.0484 -2.2366 + -8.000 -0.4769 0.0461 -2.0401 + -7.000 -0.4294 0.0449 -1.8137 + -6.000 -0.3453 0.0440 -1.5940 + -5.000 -0.2498 0.0433 -1.4194 + -4.000 -0.1500 0.0427 -1.2559 + -3.000 -0.0483 0.0418 -1.1508 + -2.000 0.0592 0.0417 -1.1501 + -1.000 0.1663 0.0416 -1.2243 + 0.000 0.2730 0.0417 -1.3028 + 1.000 0.3803 0.0417 -1.3838 + 2.000 0.4859 0.0418 -1.4645 + 3.000 0.5895 0.0420 -1.5483 + 4.000 0.6893 0.0424 -1.6326 + 5.000 0.7876 0.0427 -1.7252 + 6.000 0.8679 0.0437 -1.8212 + 7.000 0.9002 0.0452 -1.8936 + 8.000 0.9294 0.0472 -2.0052 + 9.000 0.9652 0.0498 -2.1398 + 10.000 1.0023 0.0528 -2.2804 + 11.000 1.0093 0.0580 -2.3844 + 12.000 1.0356 0.0628 -2.6060 + 13.000 1.0441 0.0697 -2.7946 + 14.000 1.0672 0.0761 -3.0285 + 15.000 1.0835 0.0837 -3.2567 + 16.000 1.1087 0.0911 -3.5261 + 17.000 1.1306 0.0991 -3.8034 + 18.000 1.1510 0.1080 -4.0965 + 19.000 1.1700 0.1172 -4.3899 + 20.000 1.1865 0.1272 -4.6928 + 21.000 1.2019 0.1375 -5.0028 + 22.000 1.2192 0.1473 -5.3358 + 23.000 1.2267 0.1588 -5.6377 + 24.000 1.2326 0.1704 -5.9354 + 25.000 1.2334 0.1825 -6.2163 + 26.000 1.2292 0.1953 -6.4566 + 28.000 1.2072 0.2216 -6.8060 + 29.000 1.1908 0.2363 -6.8946 + 30.000 1.1805 0.2495 -7.0038 + 40.000 0.9711 0.4368 -1.2342 + 50.000 0.7961 0.6371 -1.2342 + 60.000 0.6131 0.8274 -1.2342 + 70.000 0.4130 0.9854 -1.2342 + 80.000 0.2031 1.0931 -1.2342 + 90.000 0.0000 1.1387 -1.2342 + 100.000 -0.1421 1.0931 -1.2342 + 110.000 -0.2891 0.9854 -1.2342 + 120.000 -0.4292 0.8274 -1.2342 + 130.000 -0.5573 0.6371 -1.2342 + 140.000 -0.6797 0.4368 -1.2342 + 150.000 -0.8264 0.2495 -1.2342 + 160.000 -0.5509 0.0975 -1.2342 + 170.000 -0.2755 0.0440 -1.2342 + 180.000 0.0000 0.0440 -1.2342 +! ------------------------------------------------------------------------------ +! data for table 2 +! ------------------------------------------------------------------------------ + 4.000 Re ! Reynolds number in millions + 0 UserProp ! User property (control) setting +False InclUAdata ! Is unsteady aerodynamics data included in this table? If TRUE, then include 30 UA coefficients below this line +!........................................ +! Table of aerodynamics coefficients + 69 NumAlf ! Number of data lines in the following table +! Alpha Cl Cd Cpmin +! (deg) (-) (-) (-) + -180.000 0.0000 0.0873 -1.2342 + -170.000 0.2887 0.0873 -1.2342 + -160.000 0.5775 0.1303 -1.2342 + -150.000 0.8662 0.2831 -1.2342 + -140.000 0.7040 0.4714 -1.2342 + -130.000 0.5716 0.6732 -1.2342 + -120.000 0.4369 0.8650 -1.2342 + -110.000 0.2924 1.0248 -1.2342 + -100.000 0.1429 1.1345 -1.2342 + -90.000 0.0000 1.1821 -1.2342 + -80.000 -0.1429 1.1345 -1.2342 + -70.000 -0.2924 1.0248 -1.2342 + -60.000 -0.4369 0.8650 -1.2342 + -50.000 -0.5716 0.6732 -1.2342 + -40.000 -0.7040 0.4714 -1.2342 + -30.000 -0.8662 0.2831 -1.2342 + -20.000 -0.6329 0.1877 -1.2342 + -10.000 -0.5710 0.0922 -2.5258 + -9.000 -0.5294 0.0901 -2.2859 + -8.000 -0.5122 0.0883 -2.1009 + -7.000 -0.4370 0.0873 -1.8275 + -6.000 -0.3452 0.0866 -1.5943 + -5.000 -0.2481 0.0860 -1.4179 + -4.000 -0.1447 0.0855 -1.2505 + -3.000 -0.0401 0.0849 -1.1451 + -1.000 0.1750 0.0842 -1.2294 + 0.000 0.2837 0.0841 -1.3095 + 1.000 0.3905 0.0843 -1.3903 + 2.000 0.4984 0.0843 -1.4727 + 5.000 0.7926 0.0858 -1.7277 + 6.000 0.8625 0.0870 -1.8182 + 7.000 0.9104 0.0881 -1.9017 + 9.000 1.0001 0.0914 -2.1829 + 10.000 1.0176 0.0951 -2.3002 + 11.000 1.0483 0.0988 -2.4594 + 12.000 1.0619 0.1042 -2.6613 + 13.000 1.0871 0.1095 -2.8912 + 14.000 1.1125 0.1153 -3.1432 + 15.000 1.1426 0.1213 -3.4165 + 16.000 1.1668 0.1283 -3.6993 + 17.000 1.1917 0.1356 -4.0066 + 18.000 1.2125 0.1438 -4.3127 + 19.000 1.2331 0.1524 -4.6272 + 20.000 1.2462 0.1624 -4.9387 + 21.000 1.2599 0.1726 -5.2566 + 22.000 1.2717 0.1833 -5.5870 + 23.000 1.2757 0.1949 -5.8874 + 24.000 1.2879 0.2053 -6.2523 + 25.000 1.2885 0.2173 -6.5549 + 26.000 1.2891 0.2291 -6.8508 + 27.000 1.2857 0.2414 -7.1130 + 28.000 1.2786 0.2541 -7.3364 + 29.000 1.2520 0.2694 -7.3962 + 30.000 1.2375 0.2831 -7.5119 + 40.000 1.0057 0.4714 -1.2342 + 50.000 0.8166 0.6732 -1.2342 + 60.000 0.6240 0.8650 -1.2342 + 70.000 0.4177 1.0248 -1.2342 + 80.000 0.2042 1.1345 -1.2342 + 90.000 0.0000 1.1821 -1.2342 + 100.000 -0.1429 1.1345 -1.2342 + 110.000 -0.2924 1.0248 -1.2342 + 120.000 -0.4369 0.8650 -1.2342 + 130.000 -0.5716 0.6732 -1.2342 + 140.000 -0.7040 0.4714 -1.2342 + 150.000 -0.8662 0.2831 -1.2342 + 160.000 -0.5775 0.1303 -1.2342 + 170.000 -0.2887 0.0873 -1.2342 + 180.000 0.0000 0.0873 -1.2342 +! ------------------------------------------------------------------------------ +! data for table 3 +! ------------------------------------------------------------------------------ + 6.000 Re ! Reynolds number in millions + 0 UserProp ! User property (control) setting +False InclUAdata ! Is unsteady aerodynamics data included in this table? If TRUE, then include 30 UA coefficients below this line +!........................................ +! Table of aerodynamics coefficients + 71 NumAlf ! Number of data lines in the following table +! Alpha Cl Cd Cpmin +! (deg) (-) (-) (-) + -180.000 0.0000 0.0908 -1.2342 + -170.000 0.2995 0.0908 -1.2342 + -160.000 0.5990 0.1258 -1.2342 + -150.000 0.8984 0.2793 -1.2342 + -140.000 0.7236 0.4684 -1.2342 + -130.000 0.5832 0.6712 -1.2342 + -120.000 0.4430 0.8643 -1.2342 + -110.000 0.2951 1.0254 -1.2342 + -100.000 0.1436 1.1366 -1.2342 + -90.000 0.0000 1.1856 -1.2342 + -80.000 -0.1436 1.1366 -1.2342 + -70.000 -0.2951 1.0254 -1.2342 + -60.000 -0.4430 0.8643 -1.2342 + -50.000 -0.5832 0.6712 -1.2342 + -40.000 -0.7236 0.4684 -1.2342 + -30.000 -0.8984 0.2793 -1.2342 + -20.000 -0.6573 0.1869 -1.2342 + -10.000 -0.5945 0.0944 -2.5752 + -9.000 -0.5572 0.0925 -2.3371 + -8.000 -0.5216 0.0912 -2.1174 + -7.000 -0.4385 0.0904 -1.8300 + -6.000 -0.3467 0.0897 -1.5966 + -5.000 -0.2462 0.0891 -1.4158 + -4.000 -0.1422 0.0888 -1.2476 + -3.000 -0.0370 0.0883 -1.1433 + -2.000 0.0700 0.0876 -1.1563 + -1.000 0.1788 0.0874 -1.2317 + 0.000 0.2873 0.0874 -1.3116 + 1.000 0.3964 0.0874 -1.3941 + 2.000 0.5017 0.0876 -1.4750 + 4.000 0.7033 0.0884 -1.6456 + 5.000 0.7898 0.0894 -1.7274 + 6.000 0.8653 0.0904 -1.8141 + 7.000 0.9223 0.0912 -1.9135 + 8.000 0.9769 0.0923 -2.0568 + 9.000 1.0075 0.0945 -2.1916 + 10.000 1.0397 0.0974 -2.3303 + 11.000 1.0607 0.1014 -2.4839 + 12.000 1.0873 0.1058 -2.7148 + 13.000 1.1111 0.1110 -2.9461 + 14.000 1.1448 0.1161 -3.2245 + 15.000 1.1715 0.1221 -3.4976 + 16.000 1.1977 0.1287 -3.7910 + 17.000 1.2217 0.1359 -4.1053 + 19.000 1.2606 0.1526 -4.7329 + 20.000 1.2896 0.1602 -5.1156 + 21.000 1.3005 0.1704 -5.4311 + 22.000 1.3073 0.1816 -5.7547 + 23.000 1.3114 0.1931 -6.0712 + 24.000 1.3170 0.2045 -6.4155 + 25.000 1.3194 0.2162 -6.7394 + 26.000 1.3171 0.2283 -7.0302 + 27.000 1.3109 0.2409 -7.2856 + 28.000 1.3036 0.2535 -7.5195 + 29.000 1.2948 0.2662 -7.7268 + 30.000 1.2835 0.2793 -7.8953 + 40.000 1.0337 0.4684 -1.2342 + 50.000 0.8331 0.6712 -1.2342 + 60.000 0.6329 0.8643 -1.2342 + 70.000 0.4216 1.0254 -1.2342 + 80.000 0.2052 1.1366 -1.2342 + 90.000 0.0000 1.1856 -1.2342 + 100.000 -0.1436 1.1366 -1.2342 + 110.000 -0.2951 1.0254 -1.2342 + 120.000 -0.4430 0.8643 -1.2342 + 130.000 -0.5832 0.6712 -1.2342 + 140.000 -0.7236 0.4684 -1.2342 + 150.000 -0.8984 0.2793 -1.2342 + 160.000 -0.5990 0.1258 -1.2342 + 170.000 -0.2995 0.0908 -1.2342 + 180.000 0.0000 0.0908 -1.2342 +! ------------------------------------------------------------------------------ +! data for table 4 +! ------------------------------------------------------------------------------ + 8.000 Re ! Reynolds number in millions + 0 UserProp ! User property (control) setting +False InclUAdata ! Is unsteady aerodynamics data included in this table? If TRUE, then include 30 UA coefficients below this line +!........................................ +! Table of aerodynamics coefficients + 62 NumAlf ! Number of data lines in the following table +! Alpha Cl Cd Cpmin +! (deg) (-) (-) (-) + -180.000 0.0000 0.0908 -1.2342 + -170.000 0.3589 0.0908 -1.2342 + -160.000 0.7178 0.1399 -1.2342 + -150.000 0.8463 0.2923 -1.2342 + -140.000 0.6918 0.4800 -1.2342 + -130.000 0.5644 0.6809 -1.2342 + -120.000 0.4330 0.8718 -1.2342 + -110.000 0.2907 1.0306 -1.2342 + -100.000 0.1426 1.1392 -1.2342 + -90.000 0.0000 1.1856 -1.2342 + -80.000 -0.1426 1.1392 -1.2342 + -70.000 -0.2907 1.0306 -1.2342 + -60.000 -0.4330 0.8718 -1.2342 + -50.000 -0.5644 0.6809 -1.2342 + -40.000 -0.6918 0.4800 -1.2342 + -30.000 -0.8463 0.2923 -1.2342 + -20.000 -0.7416 0.1764 -1.2342 + -10.000 -0.6035 0.0940 -2.6010 + -9.000 -0.5784 0.0917 -2.3771 + -8.000 -0.5289 0.0908 -2.1303 + -5.000 -0.2459 0.0889 -1.4153 + -4.000 -0.1417 0.0885 -1.2471 + -3.000 -0.0350 0.0882 -1.1334 + -2.000 0.0720 0.0876 -1.1574 + -1.000 0.1806 0.0873 -1.2325 + 0.000 0.2903 0.0872 -1.3135 + 1.000 0.3977 0.0872 -1.3948 + 2.000 0.5029 0.0874 -1.4763 + 3.000 0.6065 0.0878 -1.5602 + 4.000 0.7026 0.0885 -1.6371 + 6.000 0.8709 0.0903 -1.8131 + 7.000 0.9390 0.0909 -1.9283 + 8.000 0.9903 0.0919 -2.0725 + 9.000 1.0182 0.0941 -2.2052 + 11.000 1.0718 0.1008 -2.5055 + 12.000 1.1056 0.1046 -2.7534 + 13.000 1.1409 0.1088 -3.0171 + 15.000 1.2029 0.1193 -3.5854 + 16.000 1.2292 0.1256 -3.8876 + 17.000 1.2559 0.1323 -4.2180 + 18.000 1.2741 0.1402 -4.5271 + 19.000 1.2946 0.1485 -4.8636 + 20.000 1.3084 0.1579 -5.1912 + 22.000 1.3238 0.1794 -5.8311 + 25.000 1.3343 0.2140 -6.8274 + 26.000 1.3330 0.2260 -7.1297 + 30.000 1.2089 0.2923 -5.8073 + 40.000 0.9884 0.4800 -1.2342 + 50.000 0.8063 0.6809 -1.2342 + 60.000 0.6186 0.8718 -1.2342 + 70.000 0.4154 1.0306 -1.2342 + 80.000 0.2037 1.1392 -1.2342 + 90.000 0.0000 1.1856 -1.2342 + 100.000 -0.1426 1.1392 -1.2342 + 110.000 -0.2907 1.0306 -1.2342 + 120.000 -0.4330 0.8718 -1.2342 + 130.000 -0.5644 0.6809 -1.2342 + 140.000 -0.6918 0.4800 -1.2342 + 150.000 -0.8463 0.2923 -1.2342 + 160.000 -0.7178 0.1399 -1.2342 + 170.000 -0.3589 0.0908 -1.2342 + 180.000 0.0000 0.0908 -1.2342 +! ------------------------------------------------------------------------------ +! data for table 5 +! ------------------------------------------------------------------------------ + 10.000 Re ! Reynolds number in millions + 0 UserProp ! User property (control) setting +False InclUAdata ! Is unsteady aerodynamics data included in this table? If TRUE, then include 30 UA coefficients below this line +!........................................ +! Table of aerodynamics coefficients + 67 NumAlf ! Number of data lines in the following table +! Alpha Cl Cd Cpmin +! (deg) (-) (-) (-) + -180.000 0.0000 0.0908 -1.2342 + -170.000 0.3097 0.0908 -1.2342 + -160.000 0.6195 0.1173 -1.2342 + -150.000 0.9292 0.2715 -1.2342 + -140.000 0.7423 0.4615 -1.2342 + -130.000 0.5943 0.6655 -1.2342 + -120.000 0.4490 0.8598 -1.2342 + -110.000 0.2976 1.0223 -1.2342 + -100.000 0.1443 1.1350 -1.2342 + -90.000 0.0000 1.1856 -1.2342 + -80.000 -0.1443 1.1350 -1.2342 + -70.000 -0.2976 1.0223 -1.2342 + -60.000 -0.4490 0.8598 -1.2342 + -50.000 -0.5943 0.6655 -1.2342 + -40.000 -0.7423 0.4615 -1.2342 + -30.000 -0.9292 0.2715 -1.2342 + -20.000 -0.6751 0.1827 -1.2342 + -10.000 -0.6013 0.0939 -2.5800 + -9.000 -0.6049 0.0913 -2.4300 + -8.000 -0.5351 0.0905 -2.1415 + -6.000 -0.3479 0.0892 -1.6003 + -4.000 -0.1409 0.0883 -1.2463 + -3.000 -0.0343 0.0881 -1.1345 + -2.000 0.0733 0.0876 -1.1581 + -1.000 0.1825 0.0872 -1.2337 + 0.000 0.2915 0.0871 -1.3142 + 1.000 0.3984 0.0872 -1.3953 + 2.000 0.5032 0.0874 -1.4781 + 4.000 0.7008 0.0886 -1.6330 + 5.000 0.7884 0.0895 -1.7176 + 6.000 0.8737 0.0902 -1.8187 + 7.000 0.9573 0.0907 -1.9445 + 8.000 0.9963 0.0918 -2.0792 + 9.000 1.0325 0.0935 -2.2235 + 10.000 1.0483 0.0969 -2.3279 + 11.000 1.0905 0.0997 -2.5427 + 12.000 1.1219 0.1035 -2.7879 + 13.000 1.1561 0.1078 -3.0531 + 14.000 1.1901 0.1124 -3.3382 + 16.000 1.2477 0.1239 -3.9451 + 17.000 1.2697 0.1309 -4.2627 + 18.000 1.2918 0.1384 -4.5882 + 19.000 1.3089 0.1468 -4.9179 + 20.000 1.3218 0.1562 -5.2450 + 21.000 1.3285 0.1667 -5.5530 + 24.000 1.3627 0.1976 -6.6668 + 25.000 1.3660 0.2090 -7.0127 + 26.000 1.3664 0.2208 -7.3375 + 27.000 1.3628 0.2327 -7.6317 + 28.000 1.3542 0.2452 -7.8817 + 29.000 1.3417 0.2583 -8.0880 + 30.000 1.3275 0.2715 -8.2610 + 40.000 1.0605 0.4615 -1.2342 + 50.000 0.8489 0.6655 -1.2342 + 60.000 0.6414 0.8598 -1.2342 + 70.000 0.4252 1.0223 -1.2342 + 80.000 0.2061 1.1350 -1.2342 + 90.000 0.0000 1.1856 -1.2342 + 100.000 -0.1443 1.1350 -1.2342 + 110.000 -0.2976 1.0223 -1.2342 + 120.000 -0.4490 0.8598 -1.2342 + 130.000 -0.5943 0.6655 -1.2342 + 140.000 -0.7423 0.4615 -1.2342 + 150.000 -0.9292 0.2715 -1.2342 + 160.000 -0.6195 0.1173 -1.2342 + 170.000 -0.3097 0.0908 -1.2342 + 180.000 0.0000 0.0908 -1.2342 +! ------------------------------------------------------------------------------ +! data for table 6 +! ------------------------------------------------------------------------------ + 12.000 Re ! Reynolds number in millions + 0 UserProp ! User property (control) setting +False InclUAdata ! Is unsteady aerodynamics data included in this table? If TRUE, then include 30 UA coefficients below this line +!........................................ +! Table of aerodynamics coefficients + 68 NumAlf ! Number of data lines in the following table +! Alpha Cl Cd Cpmin +! (deg) (-) (-) (-) + -180.000 0.0000 0.0908 -1.2342 + -170.000 0.3262 0.0908 -1.2342 + -160.000 0.6524 0.1202 -1.2342 + -150.000 0.9224 0.2741 -1.2342 + -140.000 0.7382 0.4639 -1.2342 + -130.000 0.5918 0.6674 -1.2342 + -120.000 0.4476 0.8613 -1.2342 + -110.000 0.2971 1.0234 -1.2342 + -100.000 0.1441 1.1355 -1.2342 + -90.000 0.0000 1.1856 -1.2342 + -80.000 -0.1441 1.1355 -1.2342 + -70.000 -0.2971 1.0234 -1.2342 + -60.000 -0.4476 0.8613 -1.2342 + -50.000 -0.5918 0.6674 -1.2342 + -40.000 -0.7382 0.4639 -1.2342 + -30.000 -0.9224 0.2741 -1.2342 + -20.000 -0.7012 0.1794 -1.2342 + -10.000 -0.6131 0.0934 -2.6061 + -7.000 -0.4460 0.0897 -1.8425 + -6.000 -0.3471 0.0892 -1.5903 + -5.000 -0.2455 0.0886 -1.4153 + -4.000 -0.1408 0.0882 -1.2460 + -3.000 -0.0335 0.0880 -1.1370 + -2.000 0.0747 0.0876 -1.1588 + -1.000 0.1835 0.0871 -1.2344 + 0.000 0.2922 0.0871 -1.3144 + 1.000 0.3990 0.0871 -1.3960 + 2.000 0.5040 0.0874 -1.4745 + 3.000 0.6059 0.0878 -1.5514 + 4.000 0.7013 0.0885 -1.6363 + 5.000 0.7890 0.0894 -1.7201 + 6.000 0.8798 0.0899 -1.8244 + 7.000 0.9640 0.0905 -1.9511 + 8.000 1.0024 0.0916 -2.0864 + 10.000 1.0619 0.0962 -2.3507 + 11.000 1.1017 0.0991 -2.5653 + 12.000 1.1399 0.1025 -2.8264 + 13.000 1.1759 0.1063 -3.1002 + 14.000 1.2023 0.1116 -3.3690 + 15.000 1.2323 0.1168 -3.6674 + 17.000 1.2828 0.1297 -4.3055 + 18.000 1.3035 0.1372 -4.6284 + 19.000 1.3205 0.1455 -4.9619 + 20.000 1.3290 0.1553 -5.2735 + 22.000 1.3649 0.1735 -6.0219 + 23.000 1.3718 0.1845 -6.3836 + 24.000 1.3769 0.1956 -6.7442 + 25.000 1.3793 0.2072 -7.0890 + 26.000 1.3784 0.2190 -7.4113 + 27.000 1.3719 0.2313 -7.6916 + 28.000 1.3626 0.2440 -7.9398 + 29.000 1.3514 0.2568 -8.1599 + 30.000 1.3177 0.2741 -7.7356 + 40.000 1.0545 0.4639 -1.2342 + 50.000 0.8454 0.6674 -1.2342 + 60.000 0.6395 0.8613 -1.2342 + 70.000 0.4244 1.0234 -1.2342 + 80.000 0.2059 1.1355 -1.2342 + 90.000 0.0000 1.1856 -1.2342 + 100.000 -0.1441 1.1355 -1.2342 + 110.000 -0.2971 1.0234 -1.2342 + 120.000 -0.4476 0.8613 -1.2342 + 130.000 -0.5918 0.6674 -1.2342 + 140.000 -0.7382 0.4639 -1.2342 + 150.000 -0.9224 0.2741 -1.2342 + 160.000 -0.6524 0.1202 -1.2342 + 170.000 -0.3262 0.0908 -1.2342 + 180.000 0.0000 0.0908 -1.2342 +! ------------------------------------------------------------------------------ +! data for table 7 +! ------------------------------------------------------------------------------ + 14.000 Re ! Reynolds number in millions + 0 UserProp ! User property (control) setting +False InclUAdata ! Is unsteady aerodynamics data included in this table? If TRUE, then include 30 UA coefficients below this line +!........................................ +! Table of aerodynamics coefficients + 64 NumAlf ! Number of data lines in the following table +! Alpha Cl Cd Cpmin +! (deg) (-) (-) (-) + -180.000 0.0000 0.0908 -1.2342 + -170.000 0.3144 0.0908 -1.2342 + -160.000 0.6287 0.1138 -1.2342 + -150.000 0.9431 0.2683 -1.2342 + -140.000 0.7508 0.4587 -1.2342 + -130.000 0.5992 0.6631 -1.2342 + -120.000 0.4516 0.8579 -1.2342 + -110.000 0.2988 1.0211 -1.2342 + -100.000 0.1445 1.1343 -1.2342 + -90.000 0.0000 1.1856 -1.2342 + -80.000 -0.1445 1.1343 -1.2342 + -70.000 -0.2988 1.0211 -1.2342 + -60.000 -0.4516 0.8579 -1.2342 + -50.000 -0.5992 0.6631 -1.2342 + -40.000 -0.7508 0.4587 -1.2342 + -30.000 -0.9431 0.2683 -1.2342 + -20.000 -0.6902 0.1806 -1.2342 + -10.000 -0.6249 0.0929 -2.6310 + -9.000 -0.6076 0.0912 -2.4236 + -8.000 -0.5409 0.0901 -2.1527 + -6.000 -0.3470 0.0891 -1.5882 + -5.000 -0.2454 0.0885 -1.4150 + -4.000 -0.1407 0.0881 -1.2459 + -3.000 -0.0328 0.0879 -1.1374 + -2.000 0.0757 0.0875 -1.1594 + -1.000 0.1839 0.0871 -1.2346 + 0.000 0.2931 0.0870 -1.3151 + 1.000 0.3980 0.0872 -1.3962 + 2.000 0.5039 0.0874 -1.4738 + 3.000 0.6047 0.0879 -1.5498 + 5.000 0.7918 0.0893 -1.7230 + 6.000 0.8825 0.0899 -1.8274 + 7.000 0.9707 0.0904 -1.9577 + 8.000 1.0061 0.0914 -2.0904 + 11.000 1.1120 0.0986 -2.5857 + 12.000 1.1501 0.1018 -2.8480 + 14.000 1.2210 0.1100 -3.4157 + 16.000 1.2697 0.1220 -4.0131 + 18.000 1.3134 0.1361 -4.6623 + 21.000 1.3665 0.1618 -5.7189 + 22.000 1.3754 0.1721 -6.0696 + 23.000 1.3833 0.1829 -6.4424 + 24.000 1.3875 0.1941 -6.8016 + 25.000 1.3889 0.2058 -7.1442 + 26.000 1.3849 0.2179 -7.4518 + 27.000 1.3786 0.2303 -7.7351 + 28.000 1.3703 0.2427 -7.9942 + 29.000 1.3602 0.2554 -8.2252 + 30.000 1.3473 0.2683 -8.4198 + 40.000 1.0725 0.4587 -1.2342 + 50.000 0.8561 0.6631 -1.2342 + 60.000 0.6452 0.8579 -1.2342 + 70.000 0.4269 1.0211 -1.2342 + 80.000 0.2065 1.1343 -1.2342 + 90.000 0.0000 1.1856 -1.2342 + 100.000 -0.1445 1.1343 -1.2342 + 110.000 -0.2988 1.0211 -1.2342 + 120.000 -0.4516 0.8579 -1.2342 + 130.000 -0.5992 0.6631 -1.2342 + 140.000 -0.7508 0.4587 -1.2342 + 150.000 -0.9431 0.2683 -1.2342 + 160.000 -0.6287 0.1138 -1.2342 + 170.000 -0.3144 0.0908 -1.2342 + 180.000 0.0000 0.0908 -1.2342 \ No newline at end of file diff --git a/Test_Cases/MHK_RM1/Airfoils/NACA6_0329_coords.txt b/Test_Cases/MHK_RM1/Airfoils/NACA6_0329_coords.txt new file mode 100644 index 00000000..00d5ebe9 --- /dev/null +++ b/Test_Cases/MHK_RM1/Airfoils/NACA6_0329_coords.txt @@ -0,0 +1,47 @@ + 40 NumCoords ! The number of coordinates in the airfoil shape file (including an extra coordinate for airfoil reference). Set to zero if coordinates not included. +! ......... x-y coordinates are next if NumCoords > 0 ............. +! x-y coordinate of airfoil reference +! x/c y/c + 0.25 0 +! coordinates of airfoil shape +! NACA6_0329 Airfoil +! x/c y/c + 0.000000 0.000000 + 0.006819 0.028484 + 0.027091 0.058831 + 0.060263 0.089532 + 0.105430 0.117836 + 0.161359 0.142554 + 0.226526 0.162174 + 0.299152 0.175281 + 0.377257 0.179988 + 0.458710 0.175693 + 0.541290 0.163772 + 0.622743 0.146064 + 0.700848 0.124660 + 0.773474 0.101839 + 0.838641 0.079535 + 0.894570 0.059015 + 0.939737 0.040853 + 0.972909 0.025130 + 0.993181 0.011587 + 1.000000 0.000000 + 0.993181 -0.009368 + 0.972909 -0.018416 + 0.939737 -0.028604 + 0.894570 -0.040942 + 0.838641 -0.055950 + 0.773474 -0.073518 + 0.700848 -0.092848 + 0.622743 -0.112264 + 0.541290 -0.129574 + 0.458710 -0.142543 + 0.377257 -0.149007 + 0.299152 -0.147357 + 0.226526 -0.138252 + 0.161359 -0.123216 + 0.105430 -0.103514 + 0.060263 -0.080124 + 0.027091 -0.053971 + 0.006819 -0.026499 + 0.000000 0.000000 \ No newline at end of file diff --git a/Test_Cases/MHK_RM1/Airfoils/NACA6_0444.dat b/Test_Cases/MHK_RM1/Airfoils/NACA6_0444.dat new file mode 100644 index 00000000..1957eb43 --- /dev/null +++ b/Test_Cases/MHK_RM1/Airfoils/NACA6_0444.dat @@ -0,0 +1,560 @@ +! ------------ AirfoilInfo v1.01.x Input File ---------------------------------- +! NACA6_0444 airfoil, data based on values used for the design of the RM1 tidal current turbine. +! line +! line +! ------------------------------------------------------------------------------ +"default" InterpOrd ! Interpolation order to use for quasi-steady table lookup {1=linear; 3=cubic spline; "default"} [default=1] + 1.0 NonDimArea ! The non-dimensional area of the airfoil (area/chord^2) (set to 1.0 if unsure or unneeded) +@"NACA6_0444_coords.txt" NumCoords ! The number of coordinates in the airfoil shape file. Set to zero if coordinates not included. +"unused" BL_file ! The file name including the boundary layer characteristics of the profile. Ignored if the aeroacoustic module is not called. + 7 NumTabs ! Number of airfoil tables in this file. +! ------------------------------------------------------------------------------ +! data for table 1 +! ------------------------------------------------------------------------------ + 2.000 Re ! Reynolds number in millions + 0 UserProp ! User property (control) setting +False InclUAdata ! Is unsteady aerodynamics data included in this table? If TRUE, then include 30 UA coefficients below this line +!........................................ +! Table of aerodynamics coefficients + 72 NumAlf ! Number of data lines in the following table +! Alpha Cl Cd Cpmin +! (deg) (-) (-) (-) + -180.000 0.0000 0.0878 -1.5368 + -170.000 0.2283 0.0878 -1.5368 + -160.000 0.4565 0.1322 -1.5368 + -150.000 0.6848 0.2582 -1.5368 + -140.000 0.5632 0.4133 -1.5368 + -130.000 0.4618 0.5793 -1.5368 + -120.000 0.3556 0.7370 -1.5368 + -110.000 0.2396 0.8679 -1.5368 + -100.000 0.1178 0.9572 -1.5368 + -90.000 0.0000 0.9950 -1.5368 + -80.000 -0.1178 0.9572 -1.5368 + -70.000 -0.2396 0.8679 -1.5368 + -60.000 -0.3556 0.7370 -1.5368 + -50.000 -0.4618 0.5793 -1.5368 + -40.000 -0.5632 0.4133 -1.5368 + -30.000 -0.6848 0.2582 -1.5368 + -20.000 -0.4962 0.1761 -1.5368 + -10.000 -0.4394 0.0939 -2.5360 + -9.000 -0.4172 0.0915 -2.3675 + -8.000 -0.3951 0.0896 -2.2046 + -7.000 -0.3558 0.0886 -2.0171 + -6.000 -0.2861 0.0879 -1.8350 + -5.000 -0.2070 0.0873 -1.6903 + -4.000 -0.1243 0.0868 -1.5548 + -3.000 -0.0400 0.0861 -1.4677 + -2.000 0.0491 0.0859 -1.4671 + -1.000 0.1378 0.0859 -1.5286 + 0.000 0.2262 0.0859 -1.5937 + 1.000 0.3151 0.0859 -1.6608 + 2.000 0.4026 0.0861 -1.7276 + 3.000 0.4885 0.0862 -1.7971 + 4.000 0.5711 0.0865 -1.8669 + 5.000 0.6526 0.0868 -1.9437 + 6.000 0.7191 0.0876 -2.0232 + 7.000 0.7459 0.0889 -2.0832 + 8.000 0.7701 0.0905 -2.1757 + 9.000 0.7998 0.0927 -2.2872 + 10.000 0.8305 0.0952 -2.4037 + 11.000 0.8363 0.0995 -2.4899 + 12.000 0.8581 0.1034 -2.6735 + 13.000 0.8652 0.1092 -2.8298 + 14.000 0.8843 0.1145 -3.0236 + 15.000 0.8978 0.1208 -3.2127 + 16.000 0.9186 0.1269 -3.4359 + 17.000 0.9369 0.1336 -3.6657 + 18.000 0.9538 0.1409 -3.9085 + 19.000 0.9695 0.1486 -4.1517 + 20.000 0.9832 0.1568 -4.4027 + 21.000 0.9959 0.1653 -4.6596 + 22.000 1.0102 0.1735 -4.9355 + 23.000 1.0165 0.1830 -5.1857 + 24.000 1.0214 0.1926 -5.4324 + 25.000 1.0220 0.2026 -5.6651 + 26.000 1.0185 0.2132 -5.8642 + 28.000 1.0003 0.2350 -6.1537 + 29.000 0.9868 0.2472 -6.2271 + 30.000 0.9782 0.2582 -6.3176 + 40.000 0.8047 0.4133 -1.5368 + 50.000 0.6597 0.5793 -1.5368 + 60.000 0.5080 0.7370 -1.5368 + 70.000 0.3422 0.8679 -1.5368 + 80.000 0.1683 0.9572 -1.5368 + 90.000 0.0000 0.9950 -1.5368 + 100.000 -0.1178 0.9572 -1.5368 + 110.000 -0.2396 0.8679 -1.5368 + 120.000 -0.3556 0.7370 -1.5368 + 130.000 -0.4618 0.5793 -1.5368 + 140.000 -0.5632 0.4133 -1.5368 + 150.000 -0.6848 0.2582 -1.5368 + 160.000 -0.4565 0.1322 -1.5368 + 170.000 -0.2283 0.0878 -1.5368 + 180.000 0.0000 0.0878 -1.5368 +! ------------------------------------------------------------------------------ +! data for table 2 +! ------------------------------------------------------------------------------ + 4.000 Re ! Reynolds number in millions + 0 UserProp ! User property (control) setting +False InclUAdata ! Is unsteady aerodynamics data included in this table? If TRUE, then include 30 UA coefficients below this line +!........................................ +! Table of aerodynamics coefficients + 69 NumAlf ! Number of data lines in the following table +! Alpha Cl Cd Cpmin +! (deg) (-) (-) (-) + -180.000 0.0000 0.1872 -1.5368 + -170.000 0.2392 0.1872 -1.5368 + -160.000 0.4785 0.2228 -1.5368 + -150.000 0.7178 0.3494 -1.5368 + -140.000 0.5834 0.5055 -1.5368 + -130.000 0.4736 0.6726 -1.5368 + -120.000 0.3620 0.8316 -1.5368 + -110.000 0.2423 0.9640 -1.5368 + -100.000 0.1184 1.0549 -1.5368 + -90.000 0.0000 1.0943 -1.5368 + -80.000 -0.1184 1.0549 -1.5368 + -70.000 -0.2423 0.9640 -1.5368 + -60.000 -0.3620 0.8316 -1.5368 + -50.000 -0.4736 0.6726 -1.5368 + -40.000 -0.5834 0.5055 -1.5368 + -30.000 -0.7178 0.3494 -1.5368 + -20.000 -0.5245 0.2703 -1.5368 + -10.000 -0.4731 0.1913 -2.6071 + -9.000 -0.4387 0.1895 -2.4083 + -8.000 -0.4244 0.1880 -2.2550 + -7.000 -0.3621 0.1872 -2.0285 + -6.000 -0.2860 0.1866 -1.8352 + -5.000 -0.2056 0.1861 -1.6890 + -4.000 -0.1199 0.1857 -1.5503 + -3.000 -0.0332 0.1852 -1.4630 + -1.000 0.1450 0.1846 -1.5328 + 0.000 0.2351 0.1845 -1.5992 + 1.000 0.3236 0.1847 -1.6662 + 2.000 0.4130 0.1847 -1.7344 + 5.000 0.6567 0.1859 -1.9457 + 6.000 0.7147 0.1869 -2.0208 + 7.000 0.7543 0.1878 -2.0899 + 9.000 0.8287 0.1906 -2.3229 + 10.000 0.8432 0.1936 -2.4202 + 11.000 0.8686 0.1967 -2.5521 + 12.000 0.8799 0.2011 -2.7194 + 13.000 0.9008 0.2055 -2.9099 + 14.000 0.9219 0.2103 -3.1187 + 15.000 0.9467 0.2153 -3.3452 + 16.000 0.9669 0.2211 -3.5794 + 17.000 0.9875 0.2272 -3.8341 + 18.000 1.0047 0.2340 -4.0877 + 19.000 1.0217 0.2411 -4.3483 + 20.000 1.0326 0.2494 -4.6065 + 21.000 1.0440 0.2578 -4.8698 + 22.000 1.0538 0.2667 -5.1436 + 23.000 1.0571 0.2763 -5.3926 + 24.000 1.0672 0.2850 -5.6949 + 25.000 1.0677 0.2949 -5.9456 + 26.000 1.0682 0.3046 -6.1909 + 27.000 1.0653 0.3148 -6.4081 + 28.000 1.0595 0.3254 -6.5932 + 29.000 1.0375 0.3381 -6.6428 + 30.000 1.0254 0.3494 -6.7387 + 40.000 0.8333 0.5055 -1.5368 + 50.000 0.6766 0.6726 -1.5368 + 60.000 0.5171 0.8316 -1.5368 + 70.000 0.3461 0.9640 -1.5368 + 80.000 0.1692 1.0549 -1.5368 + 90.000 0.0000 1.0943 -1.5368 + 100.000 -0.1184 1.0549 -1.5368 + 110.000 -0.2423 0.9640 -1.5368 + 120.000 -0.3620 0.8316 -1.5368 + 130.000 -0.4736 0.6726 -1.5368 + 140.000 -0.5834 0.5055 -1.5368 + 150.000 -0.7178 0.3494 -1.5368 + 160.000 -0.4785 0.2228 -1.5368 + 170.000 -0.2392 0.1872 -1.5368 + 180.000 0.0000 0.1872 -1.5368 +! ------------------------------------------------------------------------------ +! data for table 3 +! ------------------------------------------------------------------------------ + 6.000 Re ! Reynolds number in millions + 0 UserProp ! User property (control) setting +False InclUAdata ! Is unsteady aerodynamics data included in this table? If TRUE, then include 30 UA coefficients below this line +!........................................ +! Table of aerodynamics coefficients + 71 NumAlf ! Number of data lines in the following table +! Alpha Cl Cd Cpmin +! (deg) (-) (-) (-) + -180.000 0.0000 0.1952 -1.5368 + -170.000 0.2482 0.1952 -1.5368 + -160.000 0.4963 0.2242 -1.5368 + -150.000 0.7445 0.3514 -1.5368 + -140.000 0.5996 0.5081 -1.5368 + -130.000 0.4832 0.6762 -1.5368 + -120.000 0.3671 0.8361 -1.5368 + -110.000 0.2445 0.9697 -1.5368 + -100.000 0.1190 1.0618 -1.5368 + -90.000 0.0000 1.1024 -1.5368 + -80.000 -0.1190 1.0618 -1.5368 + -70.000 -0.2445 0.9697 -1.5368 + -60.000 -0.3671 0.8361 -1.5368 + -50.000 -0.4832 0.6762 -1.5368 + -40.000 -0.5996 0.5081 -1.5368 + -30.000 -0.7445 0.3514 -1.5368 + -20.000 -0.5447 0.2748 -1.5368 + -10.000 -0.4926 0.1982 -2.6480 + -9.000 -0.4617 0.1966 -2.4507 + -8.000 -0.4322 0.1956 -2.2686 + -7.000 -0.3634 0.1949 -2.0305 + -6.000 -0.2873 0.1943 -1.8371 + -5.000 -0.2040 0.1938 -1.6873 + -4.000 -0.1179 0.1935 -1.5480 + -3.000 -0.0307 0.1932 -1.4615 + -2.000 0.0580 0.1926 -1.4722 + -1.000 0.1481 0.1924 -1.5347 + 0.000 0.2381 0.1924 -1.6009 + 1.000 0.3285 0.1924 -1.6693 + 2.000 0.4157 0.1926 -1.7363 + 4.000 0.5828 0.1932 -1.8778 + 5.000 0.6545 0.1940 -1.9455 + 6.000 0.7170 0.1949 -2.0173 + 7.000 0.7642 0.1956 -2.0997 + 8.000 0.8095 0.1965 -2.2185 + 9.000 0.8348 0.1983 -2.3302 + 10.000 0.8615 0.2007 -2.4451 + 11.000 0.8789 0.2040 -2.5723 + 12.000 0.9009 0.2076 -2.7637 + 13.000 0.9207 0.2120 -2.9553 + 14.000 0.9486 0.2162 -3.1860 + 15.000 0.9707 0.2212 -3.4123 + 16.000 0.9925 0.2266 -3.6554 + 17.000 1.0124 0.2326 -3.9159 + 19.000 1.0445 0.2464 -4.4359 + 20.000 1.0686 0.2527 -4.7530 + 21.000 1.0776 0.2612 -5.0144 + 22.000 1.0832 0.2704 -5.2826 + 23.000 1.0866 0.2800 -5.5449 + 24.000 1.0913 0.2894 -5.8301 + 25.000 1.0933 0.2991 -6.0985 + 26.000 1.0914 0.3091 -6.3395 + 27.000 1.0862 0.3196 -6.5511 + 28.000 1.0802 0.3300 -6.7450 + 29.000 1.0729 0.3406 -6.9167 + 30.000 1.0635 0.3514 -7.0563 + 40.000 0.8565 0.5081 -1.5368 + 50.000 0.6903 0.6762 -1.5368 + 60.000 0.5245 0.8361 -1.5368 + 70.000 0.3493 0.9697 -1.5368 + 80.000 0.1700 1.0618 -1.5368 + 90.000 0.0000 1.1024 -1.5368 + 100.000 -0.1190 1.0618 -1.5368 + 110.000 -0.2445 0.9697 -1.5368 + 120.000 -0.3671 0.8361 -1.5368 + 130.000 -0.4832 0.6762 -1.5368 + 140.000 -0.5996 0.5081 -1.5368 + 150.000 -0.7445 0.3514 -1.5368 + 160.000 -0.4963 0.2242 -1.5368 + 170.000 -0.2482 0.1952 -1.5368 + 180.000 0.0000 0.1952 -1.5368 +! ------------------------------------------------------------------------------ +! data for table 4 +! ------------------------------------------------------------------------------ + 8.000 Re ! Reynolds number in millions + 0 UserProp ! User property (control) setting +False InclUAdata ! Is unsteady aerodynamics data included in this table? If TRUE, then include 30 UA coefficients below this line +!........................................ +! Table of aerodynamics coefficients + 62 NumAlf ! Number of data lines in the following table +! Alpha Cl Cd Cpmin +! (deg) (-) (-) (-) + -180.000 0.0000 0.1952 -1.5368 + -170.000 0.2974 0.1952 -1.5368 + -160.000 0.5948 0.2359 -1.5368 + -150.000 0.7012 0.3622 -1.5368 + -140.000 0.5733 0.5177 -1.5368 + -130.000 0.4677 0.6842 -1.5368 + -120.000 0.3588 0.8424 -1.5368 + -110.000 0.2409 0.9739 -1.5368 + -100.000 0.1181 1.0639 -1.5368 + -90.000 0.0000 1.1024 -1.5368 + -80.000 -0.1181 1.0639 -1.5368 + -70.000 -0.2409 0.9739 -1.5368 + -60.000 -0.3588 0.8424 -1.5368 + -50.000 -0.4677 0.6842 -1.5368 + -40.000 -0.5733 0.5177 -1.5368 + -30.000 -0.7012 0.3622 -1.5368 + -20.000 -0.6145 0.2662 -1.5368 + -10.000 -0.5000 0.1978 -2.6694 + -9.000 -0.4793 0.1959 -2.4839 + -8.000 -0.4382 0.1952 -2.2793 + -5.000 -0.2037 0.1937 -1.6869 + -4.000 -0.1174 0.1933 -1.5475 + -3.000 -0.0290 0.1930 -1.4533 + -2.000 0.0596 0.1926 -1.4732 + -1.000 0.1497 0.1923 -1.5355 + 0.000 0.2405 0.1922 -1.6025 + 1.000 0.3296 0.1922 -1.6699 + 2.000 0.4167 0.1924 -1.7374 + 3.000 0.5025 0.1927 -1.8069 + 4.000 0.5822 0.1933 -1.8707 + 6.000 0.7216 0.1948 -2.0165 + 7.000 0.7781 0.1953 -2.1120 + 8.000 0.8206 0.1961 -2.2315 + 9.000 0.8437 0.1979 -2.3414 + 11.000 0.8881 0.2035 -2.5902 + 12.000 0.9161 0.2066 -2.7957 + 13.000 0.9453 0.2101 -3.0142 + 15.000 0.9967 0.2188 -3.4850 + 16.000 1.0185 0.2240 -3.7355 + 17.000 1.0407 0.2296 -4.0092 + 18.000 1.0557 0.2362 -4.2653 + 19.000 1.0727 0.2430 -4.5442 + 20.000 1.0841 0.2508 -4.8156 + 22.000 1.0969 0.2686 -5.3459 + 25.000 1.1056 0.2973 -6.1715 + 26.000 1.1045 0.3072 -6.4219 + 30.000 1.0018 0.3622 -5.3262 + 40.000 0.8190 0.5177 -1.5368 + 50.000 0.6682 0.6842 -1.5368 + 60.000 0.5125 0.8424 -1.5368 + 70.000 0.3442 0.9739 -1.5368 + 80.000 0.1688 1.0639 -1.5368 + 90.000 0.0000 1.1024 -1.5368 + 100.000 -0.1181 1.0639 -1.5368 + 110.000 -0.2409 0.9739 -1.5368 + 120.000 -0.3588 0.8424 -1.5368 + 130.000 -0.4677 0.6842 -1.5368 + 140.000 -0.5733 0.5177 -1.5368 + 150.000 -0.7012 0.3622 -1.5368 + 160.000 -0.5948 0.2359 -1.5368 + 170.000 -0.2974 0.1952 -1.5368 + 180.000 0.0000 0.1952 -1.5368 +! ------------------------------------------------------------------------------ +! data for table 5 +! ------------------------------------------------------------------------------ + 10.000 Re ! Reynolds number in millions + 0 UserProp ! User property (control) setting +False InclUAdata ! Is unsteady aerodynamics data included in this table? If TRUE, then include 30 UA coefficients below this line +!........................................ +! Table of aerodynamics coefficients + 67 NumAlf ! Number of data lines in the following table +! Alpha Cl Cd Cpmin +! (deg) (-) (-) (-) + -180.000 0.0000 0.1952 -1.5368 + -170.000 0.2566 0.1952 -1.5368 + -160.000 0.5133 0.2172 -1.5368 + -150.000 0.7700 0.3450 -1.5368 + -140.000 0.6151 0.5024 -1.5368 + -130.000 0.4924 0.6714 -1.5368 + -120.000 0.3720 0.8324 -1.5368 + -110.000 0.2466 0.9671 -1.5368 + -100.000 0.1195 1.0604 -1.5368 + -90.000 0.0000 1.1024 -1.5368 + -80.000 -0.1195 1.0604 -1.5368 + -70.000 -0.2466 0.9671 -1.5368 + -60.000 -0.3720 0.8324 -1.5368 + -50.000 -0.4924 0.6714 -1.5368 + -40.000 -0.6151 0.5024 -1.5368 + -30.000 -0.7700 0.3450 -1.5368 + -20.000 -0.5594 0.2714 -1.5368 + -10.000 -0.4983 0.1978 -2.6520 + -9.000 -0.5012 0.1956 -2.5277 + -8.000 -0.4434 0.1950 -2.2886 + -6.000 -0.2883 0.1939 -1.8402 + -4.000 -0.1168 0.1932 -1.5469 + -3.000 -0.0284 0.1929 -1.4542 + -2.000 0.0607 0.1926 -1.4738 + -1.000 0.1512 0.1922 -1.5364 + 0.000 0.2416 0.1921 -1.6031 + 1.000 0.3301 0.1922 -1.6704 + 2.000 0.4170 0.1924 -1.7389 + 4.000 0.5807 0.1934 -1.8673 + 5.000 0.6533 0.1941 -1.9374 + 6.000 0.7240 0.1947 -2.0211 + 7.000 0.7933 0.1951 -2.1254 + 8.000 0.8256 0.1960 -2.2370 + 9.000 0.8556 0.1975 -2.3566 + 10.000 0.8686 0.2003 -2.4430 + 11.000 0.9036 0.2026 -2.6210 + 12.000 0.9296 0.2057 -2.8243 + 13.000 0.9579 0.2093 -3.0440 + 14.000 0.9861 0.2131 -3.2803 + 16.000 1.0339 0.2226 -3.7832 + 17.000 1.0521 0.2284 -4.0463 + 18.000 1.0704 0.2346 -4.3160 + 19.000 1.0846 0.2416 -4.5892 + 20.000 1.0952 0.2494 -4.8603 + 21.000 1.1008 0.2581 -5.1154 + 24.000 1.1292 0.2837 -6.0384 + 25.000 1.1319 0.2932 -6.3250 + 26.000 1.1322 0.3029 -6.5941 + 27.000 1.1293 0.3128 -6.8379 + 28.000 1.1221 0.3232 -7.0450 + 29.000 1.1118 0.3340 -7.2160 + 30.000 1.1000 0.3450 -7.3593 + 40.000 0.8788 0.5024 -1.5368 + 50.000 0.7034 0.6714 -1.5368 + 60.000 0.5315 0.8324 -1.5368 + 70.000 0.3523 0.9671 -1.5368 + 80.000 0.1708 1.0604 -1.5368 + 90.000 0.0000 1.1024 -1.5368 + 100.000 -0.1195 1.0604 -1.5368 + 110.000 -0.2466 0.9671 -1.5368 + 120.000 -0.3720 0.8324 -1.5368 + 130.000 -0.4924 0.6714 -1.5368 + 140.000 -0.6151 0.5024 -1.5368 + 150.000 -0.7700 0.3450 -1.5368 + 160.000 -0.5133 0.2172 -1.5368 + 170.000 -0.2566 0.1952 -1.5368 + 180.000 0.0000 0.1952 -1.5368 +! ------------------------------------------------------------------------------ +! data for table 6 +! ------------------------------------------------------------------------------ + 12.000 Re ! Reynolds number in millions + 0 UserProp ! User property (control) setting +False InclUAdata ! Is unsteady aerodynamics data included in this table? If TRUE, then include 30 UA coefficients below this line +!........................................ +! Table of aerodynamics coefficients + 68 NumAlf ! Number of data lines in the following table +! Alpha Cl Cd Cpmin +! (deg) (-) (-) (-) + -180.000 0.0000 0.1952 -1.5368 + -170.000 0.2703 0.1952 -1.5368 + -160.000 0.5406 0.2196 -1.5368 + -150.000 0.7643 0.3471 -1.5368 + -140.000 0.6117 0.5044 -1.5368 + -130.000 0.4904 0.6730 -1.5368 + -120.000 0.3709 0.8337 -1.5368 + -110.000 0.2462 0.9680 -1.5368 + -100.000 0.1194 1.0609 -1.5368 + -90.000 0.0000 1.1024 -1.5368 + -80.000 -0.1194 1.0609 -1.5368 + -70.000 -0.2462 0.9680 -1.5368 + -60.000 -0.3709 0.8337 -1.5368 + -50.000 -0.4904 0.6730 -1.5368 + -40.000 -0.6117 0.5044 -1.5368 + -30.000 -0.7643 0.3471 -1.5368 + -20.000 -0.5810 0.2686 -1.5368 + -10.000 -0.5080 0.1973 -2.6736 + -7.000 -0.3695 0.1943 -2.0409 + -6.000 -0.2876 0.1939 -1.8319 + -5.000 -0.2035 0.1934 -1.6869 + -4.000 -0.1167 0.1931 -1.5466 + -3.000 -0.0277 0.1929 -1.4563 + -2.000 0.0619 0.1926 -1.4744 + -1.000 0.1520 0.1921 -1.5370 + 0.000 0.2422 0.1921 -1.6033 + 1.000 0.3306 0.1921 -1.6709 + 2.000 0.4176 0.1924 -1.7360 + 3.000 0.5021 0.1927 -1.7997 + 4.000 0.5811 0.1933 -1.8700 + 5.000 0.6538 0.1940 -1.9394 + 6.000 0.7290 0.1945 -2.0259 + 7.000 0.7988 0.1950 -2.1309 + 8.000 0.8306 0.1959 -2.2430 + 10.000 0.8799 0.1997 -2.4620 + 11.000 0.9129 0.2021 -2.6398 + 12.000 0.9445 0.2049 -2.8562 + 13.000 0.9744 0.2081 -3.0830 + 14.000 0.9963 0.2124 -3.3057 + 15.000 1.0211 0.2168 -3.5530 + 17.000 1.0629 0.2274 -4.0818 + 18.000 1.0801 0.2336 -4.3493 + 19.000 1.0941 0.2406 -4.6256 + 20.000 1.1012 0.2487 -4.8838 + 22.000 1.1309 0.2638 -5.5040 + 23.000 1.1367 0.2728 -5.8037 + 24.000 1.1409 0.2820 -6.1025 + 25.000 1.1429 0.2916 -6.3882 + 26.000 1.1421 0.3014 -6.6553 + 27.000 1.1368 0.3116 -6.8875 + 28.000 1.1290 0.3221 -7.0932 + 29.000 1.1198 0.3327 -7.2756 + 30.000 1.0919 0.3471 -6.9240 + 40.000 0.8738 0.5044 -1.5368 + 50.000 0.7005 0.6730 -1.5368 + 60.000 0.5299 0.8337 -1.5368 + 70.000 0.3517 0.9680 -1.5368 + 80.000 0.1706 1.0609 -1.5368 + 90.000 0.0000 1.1024 -1.5368 + 100.000 -0.1194 1.0609 -1.5368 + 110.000 -0.2462 0.9680 -1.5368 + 120.000 -0.3709 0.8337 -1.5368 + 130.000 -0.4904 0.6730 -1.5368 + 140.000 -0.6117 0.5044 -1.5368 + 150.000 -0.7643 0.3471 -1.5368 + 160.000 -0.5406 0.2196 -1.5368 + 170.000 -0.2703 0.1952 -1.5368 + 180.000 0.0000 0.1952 -1.5368 +! ------------------------------------------------------------------------------ +! data for table 7 +! ------------------------------------------------------------------------------ + 14.000 Re ! Reynolds number in millions + 0 UserProp ! User property (control) setting +False InclUAdata ! Is unsteady aerodynamics data included in this table? If TRUE, then include 30 UA coefficients below this line +!........................................ +! Table of aerodynamics coefficients + 64 NumAlf ! Number of data lines in the following table +! Alpha Cl Cd Cpmin +! (deg) (-) (-) (-) + -180.000 0.0000 0.1952 -1.5368 + -170.000 0.2605 0.1952 -1.5368 + -160.000 0.5210 0.2143 -1.5368 + -150.000 0.7815 0.3423 -1.5368 + -140.000 0.6221 0.5001 -1.5368 + -130.000 0.4965 0.6694 -1.5368 + -120.000 0.3742 0.8309 -1.5368 + -110.000 0.2476 0.9661 -1.5368 + -100.000 0.1198 1.0599 -1.5368 + -90.000 0.0000 1.1024 -1.5368 + -80.000 -0.1198 1.0599 -1.5368 + -70.000 -0.2476 0.9661 -1.5368 + -60.000 -0.3742 0.8309 -1.5368 + -50.000 -0.4965 0.6694 -1.5368 + -40.000 -0.6221 0.5001 -1.5368 + -30.000 -0.7815 0.3423 -1.5368 + -20.000 -0.5719 0.2696 -1.5368 + -10.000 -0.5178 0.1970 -2.6942 + -9.000 -0.5035 0.1956 -2.5224 + -8.000 -0.4482 0.1946 -2.2979 + -6.000 -0.2875 0.1938 -1.8301 + -5.000 -0.2034 0.1933 -1.6867 + -4.000 -0.1166 0.1929 -1.5465 + -3.000 -0.0271 0.1928 -1.4566 + -2.000 0.0627 0.1925 -1.4749 + -1.000 0.1524 0.1921 -1.5371 + 0.000 0.2429 0.1921 -1.6039 + 1.000 0.3298 0.1922 -1.6711 + 2.000 0.4175 0.1924 -1.7354 + 3.000 0.5011 0.1928 -1.7984 + 5.000 0.6561 0.1940 -1.9418 + 6.000 0.7312 0.1945 -2.0284 + 7.000 0.8043 0.1948 -2.1363 + 8.000 0.8337 0.1957 -2.2463 + 11.000 0.9214 0.2016 -2.6567 + 12.000 0.9530 0.2044 -2.8740 + 14.000 1.0117 0.2112 -3.3444 + 16.000 1.0521 0.2210 -3.8395 + 18.000 1.0883 0.2327 -4.3774 + 21.000 1.1323 0.2540 -5.2529 + 22.000 1.1397 0.2626 -5.5436 + 23.000 1.1462 0.2715 -5.8524 + 24.000 1.1497 0.2808 -6.1500 + 25.000 1.1508 0.2905 -6.4340 + 26.000 1.1476 0.3006 -6.6888 + 27.000 1.1424 0.3108 -6.9235 + 28.000 1.1355 0.3211 -7.1382 + 29.000 1.1271 0.3316 -7.3297 + 30.000 1.1164 0.3423 -7.4909 + 40.000 0.8887 0.5001 -1.5368 + 50.000 0.7093 0.6694 -1.5368 + 60.000 0.5346 0.8309 -1.5368 + 70.000 0.3537 0.9661 -1.5368 + 80.000 0.1711 1.0599 -1.5368 + 90.000 0.0000 1.1024 -1.5368 + 100.000 -0.1198 1.0599 -1.5368 + 110.000 -0.2476 0.9661 -1.5368 + 120.000 -0.3742 0.8309 -1.5368 + 130.000 -0.4965 0.6694 -1.5368 + 140.000 -0.6221 0.5001 -1.5368 + 150.000 -0.7815 0.3423 -1.5368 + 160.000 -0.5210 0.2143 -1.5368 + 170.000 -0.2605 0.1952 -1.5368 + 180.000 0.0000 0.1952 -1.5368 \ No newline at end of file diff --git a/Test_Cases/MHK_RM1/Airfoils/NACA6_0444_coords.txt b/Test_Cases/MHK_RM1/Airfoils/NACA6_0444_coords.txt new file mode 100644 index 00000000..690c1efd --- /dev/null +++ b/Test_Cases/MHK_RM1/Airfoils/NACA6_0444_coords.txt @@ -0,0 +1,47 @@ + 40 NumCoords ! The number of coordinates in the airfoil shape file (including an extra coordinate for airfoil reference). Set to zero if coordinates not included. +! ......... x-y coordinates are next if NumCoords > 0 ............. +! x-y coordinate of airfoil reference +! x/c y/c + 0.25 0 +! coordinates of airfoil shape +! NACA6_0444 Airfoil +! x/c y/c + 0.000000 0.000000 + 0.006819 0.038173 + 0.027091 0.077420 + 0.060263 0.116187 + 0.105430 0.151821 + 0.161359 0.183011 + 0.226526 0.208215 + 0.299152 0.226025 + 0.377257 0.234704 + 0.458710 0.233617 + 0.541290 0.223836 + 0.622743 0.206871 + 0.700848 0.184493 + 0.773474 0.158713 + 0.838641 0.131307 + 0.894570 0.103562 + 0.939737 0.076248 + 0.972909 0.049770 + 0.993181 0.024310 + 1.000000 0.000000 + 0.993181 -0.022489 + 0.972909 -0.044262 + 0.939737 -0.066198 + 0.894570 -0.088734 + 0.838641 -0.111957 + 0.773474 -0.135477 + 0.700848 -0.158393 + 0.622743 -0.179140 + 0.541290 -0.195779 + 0.458710 -0.206420 + 0.377257 -0.209286 + 0.299152 -0.203115 + 0.226526 -0.188588 + 0.161359 -0.167145 + 0.105430 -0.140070 + 0.060263 -0.108468 + 0.027091 -0.073433 + 0.006819 -0.036544 + 0.000000 0.000000 \ No newline at end of file diff --git a/Test_Cases/MHK_RM1/Airfoils/NACA6_0629.dat b/Test_Cases/MHK_RM1/Airfoils/NACA6_0629.dat new file mode 100644 index 00000000..c6856a16 --- /dev/null +++ b/Test_Cases/MHK_RM1/Airfoils/NACA6_0629.dat @@ -0,0 +1,560 @@ +! ------------ AirfoilInfo v1.01.x Input File ---------------------------------- +! NACA6_0629 airfoil, data based on values used for the design of the RM1 tidal current turbine. +! line +! line +! ------------------------------------------------------------------------------ +"default" InterpOrd ! Interpolation order to use for quasi-steady table lookup {1=linear; 3=cubic spline; "default"} [default=1] + 1.0 NonDimArea ! The non-dimensional area of the airfoil (area/chord^2) (set to 1.0 if unsure or unneeded) +@"NACA6_0629_coords.txt" NumCoords ! The number of coordinates in the airfoil shape file. Set to zero if coordinates not included. +"unused" BL_file ! The file name including the boundary layer characteristics of the profile. Ignored if the aeroacoustic module is not called. + 7 NumTabs ! Number of airfoil tables in this file. +! ------------------------------------------------------------------------------ +! data for table 1 +! ------------------------------------------------------------------------------ + 2.000 Re ! Reynolds number in millions + 0 UserProp ! User property (control) setting +False InclUAdata ! Is unsteady aerodynamics data included in this table? If TRUE, then include 30 UA coefficients below this line +!........................................ +! Table of aerodynamics coefficients + 72 NumAlf ! Number of data lines in the following table +! Alpha Cl Cd Cpmin +! (deg) (-) (-) (-) + -180.000 0.0000 0.1584 -2.0237 + -170.000 0.1523 0.1584 -2.0237 + -160.000 0.3046 0.1880 -2.0237 + -150.000 0.4569 0.2721 -2.0237 + -140.000 0.3758 0.3756 -2.0237 + -130.000 0.3081 0.4864 -2.0237 + -120.000 0.2373 0.5916 -2.0237 + -110.000 0.1599 0.6790 -2.0237 + -100.000 0.0786 0.7385 -2.0237 + -90.000 0.0000 0.7637 -2.0237 + -80.000 -0.0786 0.7385 -2.0237 + -70.000 -0.1599 0.6790 -2.0237 + -60.000 -0.2373 0.5916 -2.0237 + -50.000 -0.3081 0.4864 -2.0237 + -40.000 -0.3758 0.3756 -2.0237 + -30.000 -0.4569 0.2721 -2.0237 + -20.000 -0.3311 0.2173 -2.0237 + -10.000 -0.2932 0.1625 -2.6904 + -9.000 -0.2784 0.1609 -2.5779 + -8.000 -0.2637 0.1596 -2.4693 + -7.000 -0.2374 0.1590 -2.3441 + -6.000 -0.1909 0.1585 -2.2226 + -5.000 -0.1381 0.1581 -2.1261 + -4.000 -0.0829 0.1578 -2.0357 + -3.000 -0.0267 0.1573 -1.9776 + -2.000 0.0328 0.1572 -1.9772 + -1.000 0.0920 0.1571 -2.0182 + 0.000 0.1509 0.1572 -2.0616 + 1.000 0.2102 0.1572 -2.1064 + 2.000 0.2686 0.1573 -2.1510 + 3.000 0.3259 0.1574 -2.1973 + 4.000 0.3811 0.1576 -2.2439 + 5.000 0.4355 0.1578 -2.2951 + 6.000 0.4799 0.1583 -2.3482 + 7.000 0.4977 0.1591 -2.3882 + 8.000 0.5139 0.1602 -2.4500 + 9.000 0.5337 0.1617 -2.5244 + 10.000 0.5542 0.1633 -2.6021 + 11.000 0.5581 0.1662 -2.6596 + 12.000 0.5726 0.1688 -2.7821 + 13.000 0.5773 0.1727 -2.8865 + 14.000 0.5900 0.1762 -3.0158 + 15.000 0.5991 0.1804 -3.1420 + 16.000 0.6130 0.1845 -3.2909 + 17.000 0.6251 0.1889 -3.4442 + 18.000 0.6364 0.1938 -3.6062 + 19.000 0.6469 0.1990 -3.7685 + 20.000 0.6560 0.2045 -3.9359 + 21.000 0.6645 0.2101 -4.1074 + 22.000 0.6741 0.2156 -4.2915 + 23.000 0.6782 0.2219 -4.4584 + 24.000 0.6815 0.2283 -4.6230 + 25.000 0.6820 0.2350 -4.7783 + 26.000 0.6796 0.2421 -4.9112 + 28.000 0.6675 0.2567 -5.1044 + 29.000 0.6584 0.2648 -5.1534 + 30.000 0.6527 0.2721 -5.2137 + 40.000 0.5369 0.3756 -2.0237 + 50.000 0.4402 0.4864 -2.0237 + 60.000 0.3390 0.5916 -2.0237 + 70.000 0.2284 0.6790 -2.0237 + 80.000 0.1123 0.7385 -2.0237 + 90.000 0.0000 0.7637 -2.0237 + 100.000 -0.0786 0.7385 -2.0237 + 110.000 -0.1599 0.6790 -2.0237 + 120.000 -0.2373 0.5916 -2.0237 + 130.000 -0.3081 0.4864 -2.0237 + 140.000 -0.3758 0.3756 -2.0237 + 150.000 -0.4569 0.2721 -2.0237 + 160.000 -0.3046 0.1880 -2.0237 + 170.000 -0.1523 0.1584 -2.0237 + 180.000 0.0000 0.1584 -2.0237 +! ------------------------------------------------------------------------------ +! data for table 2 +! ------------------------------------------------------------------------------ + 4.000 Re ! Reynolds number in millions + 0 UserProp ! User property (control) setting +False InclUAdata ! Is unsteady aerodynamics data included in this table? If TRUE, then include 30 UA coefficients below this line +!........................................ +! Table of aerodynamics coefficients + 69 NumAlf ! Number of data lines in the following table +! Alpha Cl Cd Cpmin +! (deg) (-) (-) (-) + -180.000 0.0000 0.3478 -2.0237 + -170.000 0.1596 0.3478 -2.0237 + -160.000 0.3193 0.3716 -2.0237 + -150.000 0.4789 0.4561 -2.0237 + -140.000 0.3893 0.5602 -2.0237 + -130.000 0.3160 0.6718 -2.0237 + -120.000 0.2415 0.7778 -2.0237 + -110.000 0.1617 0.8662 -2.0237 + -100.000 0.0790 0.9268 -2.0237 + -90.000 0.0000 0.9531 -2.0237 + -80.000 -0.0790 0.9268 -2.0237 + -70.000 -0.1617 0.8662 -2.0237 + -60.000 -0.2415 0.7778 -2.0237 + -50.000 -0.3160 0.6718 -2.0237 + -40.000 -0.3893 0.5602 -2.0237 + -30.000 -0.4789 0.4561 -2.0237 + -20.000 -0.3500 0.4033 -2.0237 + -10.000 -0.3157 0.3505 -2.7378 + -9.000 -0.2927 0.3494 -2.6052 + -8.000 -0.2832 0.3484 -2.5029 + -7.000 -0.2416 0.3478 -2.3517 + -6.000 -0.1909 0.3474 -2.2228 + -5.000 -0.1372 0.3471 -2.1252 + -4.000 -0.0800 0.3468 -2.0327 + -3.000 -0.0222 0.3465 -1.9744 + -1.000 0.0968 0.3461 -2.0210 + 0.000 0.1568 0.3461 -2.0653 + 1.000 0.2159 0.3462 -2.1100 + 2.000 0.2756 0.3462 -2.1555 + 5.000 0.4382 0.3470 -2.2965 + 6.000 0.4769 0.3477 -2.3466 + 7.000 0.5033 0.3483 -2.3927 + 9.000 0.5529 0.3501 -2.5482 + 10.000 0.5627 0.3521 -2.6131 + 11.000 0.5796 0.3542 -2.7011 + 12.000 0.5872 0.3571 -2.8127 + 13.000 0.6011 0.3601 -2.9399 + 14.000 0.6151 0.3633 -3.0792 + 15.000 0.6317 0.3666 -3.2303 + 16.000 0.6451 0.3705 -3.3866 + 17.000 0.6589 0.3745 -3.5565 + 18.000 0.6704 0.3791 -3.7258 + 19.000 0.6818 0.3838 -3.8997 + 20.000 0.6890 0.3894 -4.0719 + 21.000 0.6966 0.3950 -4.2477 + 22.000 0.7031 0.4009 -4.4304 + 23.000 0.7053 0.4073 -4.5965 + 24.000 0.7121 0.4131 -4.7982 + 25.000 0.7124 0.4197 -4.9655 + 26.000 0.7128 0.4262 -5.1291 + 27.000 0.7109 0.4330 -5.2741 + 28.000 0.7070 0.4400 -5.3976 + 29.000 0.6923 0.4485 -5.4307 + 30.000 0.6842 0.4561 -5.4947 + 40.000 0.5561 0.5602 -2.0237 + 50.000 0.4515 0.6718 -2.0237 + 60.000 0.3450 0.7778 -2.0237 + 70.000 0.2309 0.8662 -2.0237 + 80.000 0.1129 0.9268 -2.0237 + 90.000 0.0000 0.9531 -2.0237 + 100.000 -0.0790 0.9268 -2.0237 + 110.000 -0.1617 0.8662 -2.0237 + 120.000 -0.2415 0.7778 -2.0237 + 130.000 -0.3160 0.6718 -2.0237 + 140.000 -0.3893 0.5602 -2.0237 + 150.000 -0.4789 0.4561 -2.0237 + 160.000 -0.3193 0.3716 -2.0237 + 170.000 -0.1596 0.3478 -2.0237 + 180.000 0.0000 0.3478 -2.0237 +! ------------------------------------------------------------------------------ +! data for table 3 +! ------------------------------------------------------------------------------ + 6.000 Re ! Reynolds number in millions + 0 UserProp ! User property (control) setting +False InclUAdata ! Is unsteady aerodynamics data included in this table? If TRUE, then include 30 UA coefficients below this line +!........................................ +! Table of aerodynamics coefficients + 71 NumAlf ! Number of data lines in the following table +! Alpha Cl Cd Cpmin +! (deg) (-) (-) (-) + -180.000 0.0000 0.3632 -2.0237 + -170.000 0.1656 0.3632 -2.0237 + -160.000 0.3312 0.3825 -2.0237 + -150.000 0.4967 0.4674 -2.0237 + -140.000 0.4001 0.5720 -2.0237 + -130.000 0.3224 0.6841 -2.0237 + -120.000 0.2450 0.7908 -2.0237 + -110.000 0.1631 0.8799 -2.0237 + -100.000 0.0794 0.9414 -2.0237 + -90.000 0.0000 0.9685 -2.0237 + -80.000 -0.0794 0.9414 -2.0237 + -70.000 -0.1631 0.8799 -2.0237 + -60.000 -0.2450 0.7908 -2.0237 + -50.000 -0.3224 0.6841 -2.0237 + -40.000 -0.4001 0.5720 -2.0237 + -30.000 -0.4967 0.4674 -2.0237 + -20.000 -0.3634 0.4163 -2.0237 + -10.000 -0.3287 0.3652 -2.7651 + -9.000 -0.3081 0.3641 -2.6335 + -8.000 -0.2884 0.3634 -2.5120 + -7.000 -0.2425 0.3630 -2.3531 + -6.000 -0.1917 0.3626 -2.2240 + -5.000 -0.1361 0.3622 -2.1241 + -4.000 -0.0786 0.3620 -2.0311 + -3.000 -0.0205 0.3618 -1.9734 + -2.000 0.0387 0.3614 -1.9806 + -1.000 0.0989 0.3613 -2.0223 + 0.000 0.1588 0.3613 -2.0664 + 1.000 0.2192 0.3613 -2.1121 + 2.000 0.2774 0.3614 -2.1568 + 4.000 0.3889 0.3619 -2.2512 + 5.000 0.4367 0.3624 -2.2964 + 6.000 0.4784 0.3630 -2.3443 + 7.000 0.5099 0.3634 -2.3993 + 8.000 0.5401 0.3640 -2.4785 + 9.000 0.5570 0.3652 -2.5530 + 10.000 0.5749 0.3668 -2.6297 + 11.000 0.5865 0.3690 -2.7146 + 12.000 0.6012 0.3715 -2.8423 + 13.000 0.6143 0.3743 -2.9702 + 14.000 0.6330 0.3772 -3.1241 + 15.000 0.6477 0.3805 -3.2751 + 16.000 0.6622 0.3841 -3.4373 + 17.000 0.6755 0.3881 -3.6111 + 19.000 0.6970 0.3973 -3.9581 + 20.000 0.7131 0.4015 -4.1697 + 21.000 0.7191 0.4072 -4.3441 + 22.000 0.7228 0.4134 -4.5231 + 23.000 0.7251 0.4197 -4.6981 + 24.000 0.7282 0.4260 -4.8884 + 25.000 0.7295 0.4325 -5.0675 + 26.000 0.7282 0.4392 -5.2283 + 27.000 0.7248 0.4462 -5.3695 + 28.000 0.7208 0.4531 -5.4989 + 29.000 0.7159 0.4602 -5.6135 + 30.000 0.7096 0.4674 -5.7066 + 40.000 0.5715 0.5720 -2.0237 + 50.000 0.4606 0.6841 -2.0237 + 60.000 0.3500 0.7908 -2.0237 + 70.000 0.2331 0.8799 -2.0237 + 80.000 0.1134 0.9414 -2.0237 + 90.000 0.0000 0.9685 -2.0237 + 100.000 -0.0794 0.9414 -2.0237 + 110.000 -0.1631 0.8799 -2.0237 + 120.000 -0.2450 0.7908 -2.0237 + 130.000 -0.3224 0.6841 -2.0237 + 140.000 -0.4001 0.5720 -2.0237 + 150.000 -0.4967 0.4674 -2.0237 + 160.000 -0.3312 0.3825 -2.0237 + 170.000 -0.1656 0.3632 -2.0237 + 180.000 0.0000 0.3632 -2.0237 +! ------------------------------------------------------------------------------ +! data for table 4 +! ------------------------------------------------------------------------------ + 8.000 Re ! Reynolds number in millions + 0 UserProp ! User property (control) setting +False InclUAdata ! Is unsteady aerodynamics data included in this table? If TRUE, then include 30 UA coefficients below this line +!........................................ +! Table of aerodynamics coefficients + 62 NumAlf ! Number of data lines in the following table +! Alpha Cl Cd Cpmin +! (deg) (-) (-) (-) + -180.000 0.0000 0.3632 -2.0237 + -170.000 0.1984 0.3632 -2.0237 + -160.000 0.3969 0.3903 -2.0237 + -150.000 0.4679 0.4746 -2.0237 + -140.000 0.3825 0.5784 -2.0237 + -130.000 0.3121 0.6895 -2.0237 + -120.000 0.2394 0.7950 -2.0237 + -110.000 0.1608 0.8828 -2.0237 + -100.000 0.0788 0.9428 -2.0237 + -90.000 0.0000 0.9685 -2.0237 + -80.000 -0.0788 0.9428 -2.0237 + -70.000 -0.1608 0.8828 -2.0237 + -60.000 -0.2394 0.7950 -2.0237 + -50.000 -0.3121 0.6895 -2.0237 + -40.000 -0.3825 0.5784 -2.0237 + -30.000 -0.4679 0.4746 -2.0237 + -20.000 -0.4101 0.4105 -2.0237 + -10.000 -0.3337 0.3649 -2.7794 + -9.000 -0.3198 0.3637 -2.6556 + -8.000 -0.2924 0.3632 -2.5191 + -5.000 -0.1360 0.3621 -2.1238 + -4.000 -0.0783 0.3619 -2.0308 + -3.000 -0.0193 0.3617 -1.9679 + -2.000 0.0398 0.3614 -1.9812 + -1.000 0.0999 0.3612 -2.0228 + 0.000 0.1605 0.3612 -2.0675 + 1.000 0.2199 0.3612 -2.1125 + 2.000 0.2781 0.3613 -2.1575 + 3.000 0.3353 0.3615 -2.2039 + 4.000 0.3885 0.3619 -2.2464 + 6.000 0.4815 0.3629 -2.3438 + 7.000 0.5192 0.3632 -2.4075 + 8.000 0.5476 0.3638 -2.4872 + 9.000 0.5629 0.3650 -2.5606 + 11.000 0.5926 0.3687 -2.7266 + 12.000 0.6113 0.3708 -2.8637 + 13.000 0.6308 0.3731 -3.0095 + 15.000 0.6651 0.3789 -3.3236 + 16.000 0.6796 0.3824 -3.4907 + 17.000 0.6944 0.3861 -3.6734 + 18.000 0.7045 0.3905 -3.8443 + 19.000 0.7158 0.3950 -4.0304 + 20.000 0.7234 0.4003 -4.2115 + 22.000 0.7319 0.4121 -4.5653 + 25.000 0.7378 0.4313 -5.1162 + 26.000 0.7370 0.4379 -5.2833 + 30.000 0.6684 0.4746 -4.5522 + 40.000 0.5465 0.5784 -2.0237 + 50.000 0.4458 0.6895 -2.0237 + 60.000 0.3420 0.7950 -2.0237 + 70.000 0.2297 0.8828 -2.0237 + 80.000 0.1126 0.9428 -2.0237 + 90.000 0.0000 0.9685 -2.0237 + 100.000 -0.0788 0.9428 -2.0237 + 110.000 -0.1608 0.8828 -2.0237 + 120.000 -0.2394 0.7950 -2.0237 + 130.000 -0.3121 0.6895 -2.0237 + 140.000 -0.3825 0.5784 -2.0237 + 150.000 -0.4679 0.4746 -2.0237 + 160.000 -0.3969 0.3903 -2.0237 + 170.000 -0.1984 0.3632 -2.0237 + 180.000 0.0000 0.3632 -2.0237 +! ------------------------------------------------------------------------------ +! data for table 5 +! ------------------------------------------------------------------------------ + 10.000 Re ! Reynolds number in millions + 0 UserProp ! User property (control) setting +False InclUAdata ! Is unsteady aerodynamics data included in this table? If TRUE, then include 30 UA coefficients below this line +!........................................ +! Table of aerodynamics coefficients + 67 NumAlf ! Number of data lines in the following table +! Alpha Cl Cd Cpmin +! (deg) (-) (-) (-) + -180.000 0.0000 0.3632 -2.0237 + -170.000 0.1712 0.3632 -2.0237 + -160.000 0.3425 0.3778 -2.0237 + -150.000 0.5138 0.4631 -2.0237 + -140.000 0.4104 0.5681 -2.0237 + -130.000 0.3286 0.6809 -2.0237 + -120.000 0.2482 0.7884 -2.0237 + -110.000 0.1646 0.8782 -2.0237 + -100.000 0.0798 0.9405 -2.0237 + -90.000 0.0000 0.9685 -2.0237 + -80.000 -0.0798 0.9405 -2.0237 + -70.000 -0.1646 0.8782 -2.0237 + -60.000 -0.2482 0.7884 -2.0237 + -50.000 -0.3286 0.6809 -2.0237 + -40.000 -0.4104 0.5681 -2.0237 + -30.000 -0.5138 0.4631 -2.0237 + -20.000 -0.3732 0.4140 -2.0237 + -10.000 -0.3325 0.3649 -2.7678 + -9.000 -0.3344 0.3635 -2.6848 + -8.000 -0.2959 0.3630 -2.5253 + -6.000 -0.1924 0.3623 -2.2261 + -4.000 -0.0779 0.3618 -2.0304 + -3.000 -0.0189 0.3617 -1.9686 + -2.000 0.0405 0.3614 -1.9816 + -1.000 0.1009 0.3612 -2.0234 + 0.000 0.1612 0.3611 -2.0679 + 1.000 0.2203 0.3612 -2.1128 + 2.000 0.2782 0.3613 -2.1585 + 4.000 0.3875 0.3620 -2.2442 + 5.000 0.4359 0.3624 -2.2910 + 6.000 0.4831 0.3628 -2.3468 + 7.000 0.5293 0.3631 -2.4164 + 8.000 0.5509 0.3637 -2.4909 + 9.000 0.5709 0.3647 -2.5707 + 10.000 0.5796 0.3665 -2.6284 + 11.000 0.6029 0.3681 -2.7471 + 12.000 0.6203 0.3702 -2.8827 + 13.000 0.6392 0.3725 -3.0293 + 14.000 0.6580 0.3751 -3.1870 + 16.000 0.6899 0.3815 -3.5226 + 17.000 0.7020 0.3853 -3.6982 + 18.000 0.7142 0.3895 -3.8781 + 19.000 0.7237 0.3941 -4.0604 + 20.000 0.7308 0.3993 -4.2413 + 21.000 0.7345 0.4052 -4.4116 + 24.000 0.7535 0.4222 -5.0274 + 25.000 0.7553 0.4285 -5.2186 + 26.000 0.7555 0.4350 -5.3982 + 27.000 0.7535 0.4416 -5.5609 + 28.000 0.7487 0.4485 -5.6991 + 29.000 0.7419 0.4558 -5.8132 + 30.000 0.7340 0.4631 -5.9088 + 40.000 0.5864 0.5681 -2.0237 + 50.000 0.4694 0.6809 -2.0237 + 60.000 0.3546 0.7884 -2.0237 + 70.000 0.2351 0.8782 -2.0237 + 80.000 0.1139 0.9405 -2.0237 + 90.000 0.0000 0.9685 -2.0237 + 100.000 -0.0798 0.9405 -2.0237 + 110.000 -0.1646 0.8782 -2.0237 + 120.000 -0.2482 0.7884 -2.0237 + 130.000 -0.3286 0.6809 -2.0237 + 140.000 -0.4104 0.5681 -2.0237 + 150.000 -0.5138 0.4631 -2.0237 + 160.000 -0.3425 0.3778 -2.0237 + 170.000 -0.1712 0.3632 -2.0237 + 180.000 0.0000 0.3632 -2.0237 +! ------------------------------------------------------------------------------ +! data for table 6 +! ------------------------------------------------------------------------------ + 12.000 Re ! Reynolds number in millions + 0 UserProp ! User property (control) setting +False InclUAdata ! Is unsteady aerodynamics data included in this table? If TRUE, then include 30 UA coefficients below this line +!........................................ +! Table of aerodynamics coefficients + 68 NumAlf ! Number of data lines in the following table +! Alpha Cl Cd Cpmin +! (deg) (-) (-) (-) + -180.000 0.0000 0.3632 -2.0237 + -170.000 0.1804 0.3632 -2.0237 + -160.000 0.3607 0.3794 -2.0237 + -150.000 0.5100 0.4645 -2.0237 + -140.000 0.4081 0.5695 -2.0237 + -130.000 0.3272 0.6820 -2.0237 + -120.000 0.2475 0.7892 -2.0237 + -110.000 0.1643 0.8788 -2.0237 + -100.000 0.0797 0.9408 -2.0237 + -90.000 0.0000 0.9685 -2.0237 + -80.000 -0.0797 0.9408 -2.0237 + -70.000 -0.1643 0.8788 -2.0237 + -60.000 -0.2475 0.7892 -2.0237 + -50.000 -0.3272 0.6820 -2.0237 + -40.000 -0.4081 0.5695 -2.0237 + -30.000 -0.5100 0.4645 -2.0237 + -20.000 -0.3877 0.4121 -2.0237 + -10.000 -0.3390 0.3646 -2.7822 + -7.000 -0.2466 0.3626 -2.3600 + -6.000 -0.1919 0.3623 -2.2206 + -5.000 -0.1358 0.3620 -2.1238 + -4.000 -0.0779 0.3618 -2.0302 + -3.000 -0.0185 0.3616 -1.9699 + -2.000 0.0413 0.3614 -1.9820 + -1.000 0.1014 0.3611 -2.0238 + 0.000 0.1616 0.3611 -2.0680 + 1.000 0.2206 0.3611 -2.1132 + 2.000 0.2786 0.3613 -2.1566 + 3.000 0.3350 0.3615 -2.1991 + 4.000 0.3877 0.3619 -2.2460 + 5.000 0.4363 0.3624 -2.2923 + 6.000 0.4864 0.3627 -2.3500 + 7.000 0.5330 0.3630 -2.4201 + 8.000 0.5543 0.3636 -2.4949 + 10.000 0.5871 0.3661 -2.6410 + 11.000 0.6091 0.3678 -2.7596 + 12.000 0.6303 0.3696 -2.9040 + 13.000 0.6502 0.3718 -3.0554 + 14.000 0.6648 0.3746 -3.2040 + 15.000 0.6814 0.3776 -3.3690 + 17.000 0.7092 0.3846 -3.7218 + 18.000 0.7207 0.3888 -3.9004 + 19.000 0.7301 0.3934 -4.0847 + 20.000 0.7348 0.3989 -4.2570 + 22.000 0.7546 0.4089 -4.6708 + 23.000 0.7585 0.4150 -4.8708 + 24.000 0.7613 0.4211 -5.0702 + 25.000 0.7626 0.4275 -5.2609 + 26.000 0.7621 0.4341 -5.4390 + 27.000 0.7585 0.4408 -5.5940 + 28.000 0.7534 0.4479 -5.7312 + 29.000 0.7472 0.4549 -5.8529 + 30.000 0.7286 0.4645 -5.6184 + 40.000 0.5831 0.5695 -2.0237 + 50.000 0.4674 0.6820 -2.0237 + 60.000 0.3536 0.7892 -2.0237 + 70.000 0.2347 0.8788 -2.0237 + 80.000 0.1138 0.9408 -2.0237 + 90.000 0.0000 0.9685 -2.0237 + 100.000 -0.0797 0.9408 -2.0237 + 110.000 -0.1643 0.8788 -2.0237 + 120.000 -0.2475 0.7892 -2.0237 + 130.000 -0.3272 0.6820 -2.0237 + 140.000 -0.4081 0.5695 -2.0237 + 150.000 -0.5100 0.4645 -2.0237 + 160.000 -0.3607 0.3794 -2.0237 + 170.000 -0.1804 0.3632 -2.0237 + 180.000 0.0000 0.3632 -2.0237 +! ------------------------------------------------------------------------------ +! data for table 7 +! ------------------------------------------------------------------------------ + 14.000 Re ! Reynolds number in millions + 0 UserProp ! User property (control) setting +False InclUAdata ! Is unsteady aerodynamics data included in this table? If TRUE, then include 30 UA coefficients below this line +!........................................ +! Table of aerodynamics coefficients + 64 NumAlf ! Number of data lines in the following table +! Alpha Cl Cd Cpmin +! (deg) (-) (-) (-) + -180.000 0.0000 0.3632 -2.0237 + -170.000 0.1738 0.3632 -2.0237 + -160.000 0.3476 0.3759 -2.0237 + -150.000 0.5215 0.4613 -2.0237 + -140.000 0.4151 0.5666 -2.0237 + -130.000 0.3313 0.6796 -2.0237 + -120.000 0.2497 0.7873 -2.0237 + -110.000 0.1652 0.8775 -2.0237 + -100.000 0.0799 0.9401 -2.0237 + -90.000 0.0000 0.9685 -2.0237 + -80.000 -0.0799 0.9401 -2.0237 + -70.000 -0.1652 0.8775 -2.0237 + -60.000 -0.2497 0.7873 -2.0237 + -50.000 -0.3313 0.6796 -2.0237 + -40.000 -0.4151 0.5666 -2.0237 + -30.000 -0.5215 0.4613 -2.0237 + -20.000 -0.3816 0.4128 -2.0237 + -10.000 -0.3455 0.3643 -2.7960 + -9.000 -0.3360 0.3634 -2.6813 + -8.000 -0.2991 0.3628 -2.5315 + -6.000 -0.1918 0.3622 -2.2194 + -5.000 -0.1357 0.3619 -2.1237 + -4.000 -0.0778 0.3617 -2.0301 + -3.000 -0.0181 0.3616 -1.9701 + -2.000 0.0418 0.3614 -1.9823 + -1.000 0.1017 0.3611 -2.0239 + 0.000 0.1621 0.3611 -2.0684 + 1.000 0.2201 0.3612 -2.1133 + 2.000 0.2786 0.3613 -2.1562 + 3.000 0.3343 0.3616 -2.1982 + 5.000 0.4378 0.3623 -2.2939 + 6.000 0.4879 0.3627 -2.3517 + 7.000 0.5367 0.3629 -2.4237 + 8.000 0.5563 0.3635 -2.4971 + 11.000 0.6148 0.3675 -2.7710 + 12.000 0.6359 0.3693 -2.9159 + 14.000 0.6751 0.3738 -3.2298 + 16.000 0.7020 0.3804 -3.5602 + 18.000 0.7262 0.3882 -3.9191 + 21.000 0.7555 0.4024 -4.5033 + 22.000 0.7605 0.4081 -4.6972 + 23.000 0.7648 0.4141 -4.9033 + 24.000 0.7671 0.4203 -5.1019 + 25.000 0.7679 0.4267 -5.2914 + 26.000 0.7657 0.4335 -5.4614 + 27.000 0.7623 0.4403 -5.6180 + 28.000 0.7577 0.4472 -5.7613 + 29.000 0.7521 0.4542 -5.8891 + 30.000 0.7449 0.4613 -5.9967 + 40.000 0.5930 0.5666 -2.0237 + 50.000 0.4733 0.6796 -2.0237 + 60.000 0.3567 0.7873 -2.0237 + 70.000 0.2360 0.8775 -2.0237 + 80.000 0.1142 0.9401 -2.0237 + 90.000 0.0000 0.9685 -2.0237 + 100.000 -0.0799 0.9401 -2.0237 + 110.000 -0.1652 0.8775 -2.0237 + 120.000 -0.2497 0.7873 -2.0237 + 130.000 -0.3313 0.6796 -2.0237 + 140.000 -0.4151 0.5666 -2.0237 + 150.000 -0.5215 0.4613 -2.0237 + 160.000 -0.3476 0.3759 -2.0237 + 170.000 -0.1738 0.3632 -2.0237 + 180.000 0.0000 0.3632 -2.0237 \ No newline at end of file diff --git a/Test_Cases/MHK_RM1/Airfoils/NACA6_0629_coords.txt b/Test_Cases/MHK_RM1/Airfoils/NACA6_0629_coords.txt new file mode 100644 index 00000000..0384c9cb --- /dev/null +++ b/Test_Cases/MHK_RM1/Airfoils/NACA6_0629_coords.txt @@ -0,0 +1,47 @@ + 40 NumCoords ! The number of coordinates in the airfoil shape file (including an extra coordinate for airfoil reference). Set to zero if coordinates not included. +! ......... x-y coordinates are next if NumCoords > 0 ............. +! x-y coordinate of airfoil reference +! x/c y/c + 0.25 0 +! coordinates of airfoil shape +! NACA6_0629 Airfoil +! x/c y/c + 0.000000 0.000000 + 0.006819 0.053204 + 0.027091 0.106260 + 0.060263 0.157538 + 0.105430 0.204545 + 0.161359 0.245774 + 0.226526 0.279641 + 0.299152 0.304748 + 0.377257 0.319589 + 0.458710 0.323479 + 0.541290 0.317019 + 0.622743 0.301206 + 0.700848 0.277317 + 0.773474 0.246947 + 0.838641 0.211626 + 0.894570 0.172671 + 0.939737 0.131160 + 0.972909 0.087998 + 0.993181 0.044048 + 1.000000 0.000000 + 0.993181 -0.042845 + 0.972909 -0.084360 + 0.939737 -0.124522 + 0.894570 -0.162878 + 0.838641 -0.198845 + 0.773474 -0.231600 + 0.700848 -0.260079 + 0.622743 -0.282891 + 0.541290 -0.298488 + 0.458710 -0.305516 + 0.377257 -0.302801 + 0.299152 -0.289617 + 0.226526 -0.266678 + 0.161359 -0.235296 + 0.105430 -0.196784 + 0.060263 -0.152440 + 0.027091 -0.103626 + 0.006819 -0.052128 + 0.000000 0.000000 \ No newline at end of file diff --git a/Test_Cases/MHK_RM1/Airfoils/NACA6_0864.dat b/Test_Cases/MHK_RM1/Airfoils/NACA6_0864.dat new file mode 100644 index 00000000..d9dc199d --- /dev/null +++ b/Test_Cases/MHK_RM1/Airfoils/NACA6_0864.dat @@ -0,0 +1,560 @@ +! ------------ AirfoilInfo v1.01.x Input File ---------------------------------- +! NACA6_0864 airfoil, data based on values used for the design of the RM1 tidal current turbine. +! line +! line +! ------------------------------------------------------------------------------ +"default" InterpOrd ! Interpolation order to use for quasi-steady table lookup {1=linear; 3=cubic spline; "default"} [default=1] + 1.0 NonDimArea ! The non-dimensional area of the airfoil (area/chord^2) (set to 1.0 if unsure or unneeded) +@"NACA6_0864_coords.txt" NumCoords ! The number of coordinates in the airfoil shape file. Set to zero if coordinates not included. +"unused" BL_file ! The file name including the boundary layer characteristics of the profile. Ignored if the aeroacoustic module is not called. + 7 NumTabs ! Number of airfoil tables in this file. +! ------------------------------------------------------------------------------ +! data for table 1 +! ------------------------------------------------------------------------------ + 2.000 Re ! Reynolds number in millions + 0 UserProp ! User property (control) setting +False InclUAdata ! Is unsteady aerodynamics data included in this table? If TRUE, then include 30 UA coefficients below this line +!........................................ +! Table of aerodynamics coefficients + 72 NumAlf ! Number of data lines in the following table +! Alpha Cl Cd Cpmin +! (deg) (-) (-) (-) + -180.000 0.0000 0.2481 -2.6421 + -170.000 0.0558 0.2481 -2.6421 + -160.000 0.1117 0.2589 -2.6421 + -150.000 0.1675 0.2898 -2.6421 + -140.000 0.1378 0.3277 -2.6421 + -130.000 0.1130 0.3683 -2.6421 + -120.000 0.0870 0.4069 -2.6421 + -110.000 0.0586 0.4389 -2.6421 + -100.000 0.0288 0.4607 -2.6421 + -90.000 0.0000 0.4700 -2.6421 + -80.000 -0.0288 0.4607 -2.6421 + -70.000 -0.0586 0.4389 -2.6421 + -60.000 -0.0870 0.4069 -2.6421 + -50.000 -0.1130 0.3683 -2.6421 + -40.000 -0.1378 0.3277 -2.6421 + -30.000 -0.1675 0.2898 -2.6421 + -20.000 -0.1214 0.2697 -2.6421 + -10.000 -0.1075 0.2496 -2.8865 + -9.000 -0.1021 0.2490 -2.8453 + -8.000 -0.0966 0.2485 -2.8054 + -7.000 -0.0870 0.2483 -2.7596 + -6.000 -0.0700 0.2481 -2.7150 + -5.000 -0.0506 0.2480 -2.6796 + -4.000 -0.0304 0.2479 -2.6465 + -3.000 -0.0098 0.2477 -2.6252 + -2.000 0.0120 0.2476 -2.6251 + -1.000 0.0337 0.2476 -2.6401 + 0.000 0.0553 0.2476 -2.6560 + 1.000 0.0771 0.2476 -2.6724 + 2.000 0.0985 0.2477 -2.6888 + 3.000 0.1195 0.2477 -2.7058 + 4.000 0.1397 0.2478 -2.7228 + 5.000 0.1596 0.2479 -2.7416 + 6.000 0.1759 0.2481 -2.7611 + 7.000 0.1825 0.2484 -2.7757 + 8.000 0.1884 0.2488 -2.7984 + 9.000 0.1956 0.2493 -2.8257 + 10.000 0.2031 0.2499 -2.8541 + 11.000 0.2046 0.2510 -2.8752 + 12.000 0.2099 0.2519 -2.9201 + 13.000 0.2116 0.2533 -2.9584 + 14.000 0.2163 0.2546 -3.0058 + 15.000 0.2196 0.2562 -3.0520 + 16.000 0.2247 0.2577 -3.1066 + 17.000 0.2292 0.2593 -3.1628 + 18.000 0.2333 0.2611 -3.2222 + 19.000 0.2371 0.2630 -3.2817 + 20.000 0.2405 0.2650 -3.3431 + 21.000 0.2436 0.2671 -3.4059 + 22.000 0.2471 0.2691 -3.4734 + 23.000 0.2486 0.2714 -3.5346 + 24.000 0.2498 0.2737 -3.5950 + 25.000 0.2500 0.2762 -3.6519 + 26.000 0.2491 0.2788 -3.7006 + 28.000 0.2447 0.2841 -3.7714 + 29.000 0.2414 0.2871 -3.7894 + 30.000 0.2393 0.2898 -3.8115 + 40.000 0.1968 0.3277 -2.6421 + 50.000 0.1614 0.3683 -2.6421 + 60.000 0.1243 0.4069 -2.6421 + 70.000 0.0837 0.4389 -2.6421 + 80.000 0.0412 0.4607 -2.6421 + 90.000 0.0000 0.4700 -2.6421 + 100.000 -0.0288 0.4607 -2.6421 + 110.000 -0.0586 0.4389 -2.6421 + 120.000 -0.0870 0.4069 -2.6421 + 130.000 -0.1130 0.3683 -2.6421 + 140.000 -0.1378 0.3277 -2.6421 + 150.000 -0.1675 0.2898 -2.6421 + 160.000 -0.1117 0.2589 -2.6421 + 170.000 -0.0558 0.2481 -2.6421 + 180.000 0.0000 0.2481 -2.6421 +! ------------------------------------------------------------------------------ +! data for table 2 +! ------------------------------------------------------------------------------ + 4.000 Re ! Reynolds number in millions + 0 UserProp ! User property (control) setting +False InclUAdata ! Is unsteady aerodynamics data included in this table? If TRUE, then include 30 UA coefficients below this line +!........................................ +! Table of aerodynamics coefficients + 69 NumAlf ! Number of data lines in the following table +! Alpha Cl Cd Cpmin +! (deg) (-) (-) (-) + -180.000 0.0000 0.5519 -2.6421 + -170.000 0.0585 0.5519 -2.6421 + -160.000 0.1170 0.5606 -2.6421 + -150.000 0.1756 0.5916 -2.6421 + -140.000 0.1427 0.6298 -2.6421 + -130.000 0.1159 0.6706 -2.6421 + -120.000 0.0885 0.7095 -2.6421 + -110.000 0.0593 0.7419 -2.6421 + -100.000 0.0290 0.7641 -2.6421 + -90.000 0.0000 0.7738 -2.6421 + -80.000 -0.0290 0.7641 -2.6421 + -70.000 -0.0593 0.7419 -2.6421 + -60.000 -0.0885 0.7095 -2.6421 + -50.000 -0.1159 0.6706 -2.6421 + -40.000 -0.1427 0.6298 -2.6421 + -30.000 -0.1756 0.5916 -2.6421 + -20.000 -0.1283 0.5722 -2.6421 + -10.000 -0.1157 0.5529 -2.9039 + -9.000 -0.1073 0.5525 -2.8553 + -8.000 -0.1038 0.5521 -2.8178 + -7.000 -0.0886 0.5519 -2.7624 + -6.000 -0.0700 0.5518 -2.7151 + -5.000 -0.0503 0.5516 -2.6793 + -4.000 -0.0293 0.5515 -2.6454 + -3.000 -0.0081 0.5514 -2.6240 + -1.000 0.0355 0.5513 -2.6411 + 0.000 0.0575 0.5513 -2.6574 + 1.000 0.0791 0.5513 -2.6737 + 2.000 0.1010 0.5513 -2.6904 + 5.000 0.1606 0.5516 -2.7421 + 6.000 0.1748 0.5518 -2.7605 + 7.000 0.1845 0.5521 -2.7774 + 9.000 0.2027 0.5527 -2.8344 + 10.000 0.2063 0.5535 -2.8582 + 11.000 0.2125 0.5542 -2.8904 + 12.000 0.2152 0.5553 -2.9314 + 13.000 0.2203 0.5564 -2.9780 + 14.000 0.2255 0.5576 -3.0290 + 15.000 0.2316 0.5588 -3.0844 + 16.000 0.2365 0.5602 -3.1417 + 17.000 0.2415 0.5617 -3.2040 + 18.000 0.2457 0.5633 -3.2661 + 19.000 0.2499 0.5651 -3.3298 + 20.000 0.2526 0.5671 -3.3930 + 21.000 0.2554 0.5692 -3.4574 + 22.000 0.2578 0.5713 -3.5243 + 23.000 0.2586 0.5737 -3.5852 + 24.000 0.2610 0.5758 -3.6592 + 25.000 0.2612 0.5783 -3.7205 + 26.000 0.2613 0.5806 -3.7805 + 27.000 0.2606 0.5831 -3.8336 + 28.000 0.2592 0.5857 -3.8789 + 29.000 0.2538 0.5888 -3.8910 + 30.000 0.2508 0.5916 -3.9145 + 40.000 0.2038 0.6298 -2.6421 + 50.000 0.1655 0.6706 -2.6421 + 60.000 0.1265 0.7095 -2.6421 + 70.000 0.0847 0.7419 -2.6421 + 80.000 0.0414 0.7641 -2.6421 + 90.000 0.0000 0.7738 -2.6421 + 100.000 -0.0290 0.7641 -2.6421 + 110.000 -0.0593 0.7419 -2.6421 + 120.000 -0.0885 0.7095 -2.6421 + 130.000 -0.1159 0.6706 -2.6421 + 140.000 -0.1427 0.6298 -2.6421 + 150.000 -0.1756 0.5916 -2.6421 + 160.000 -0.1170 0.5606 -2.6421 + 170.000 -0.0585 0.5519 -2.6421 + 180.000 0.0000 0.5519 -2.6421 +! ------------------------------------------------------------------------------ +! data for table 3 +! ------------------------------------------------------------------------------ + 6.000 Re ! Reynolds number in millions + 0 UserProp ! User property (control) setting +False InclUAdata ! Is unsteady aerodynamics data included in this table? If TRUE, then include 30 UA coefficients below this line +!........................................ +! Table of aerodynamics coefficients + 71 NumAlf ! Number of data lines in the following table +! Alpha Cl Cd Cpmin +! (deg) (-) (-) (-) + -180.000 0.0000 0.5765 -2.6421 + -170.000 0.0607 0.5765 -2.6421 + -160.000 0.1214 0.5836 -2.6421 + -150.000 0.1821 0.6147 -2.6421 + -140.000 0.1467 0.6531 -2.6421 + -130.000 0.1182 0.6942 -2.6421 + -120.000 0.0898 0.7333 -2.6421 + -110.000 0.0598 0.7660 -2.6421 + -100.000 0.0291 0.7885 -2.6421 + -90.000 0.0000 0.7984 -2.6421 + -80.000 -0.0291 0.7885 -2.6421 + -70.000 -0.0598 0.7660 -2.6421 + -60.000 -0.0898 0.7333 -2.6421 + -50.000 -0.1182 0.6942 -2.6421 + -40.000 -0.1467 0.6531 -2.6421 + -30.000 -0.1821 0.6147 -2.6421 + -20.000 -0.1332 0.5960 -2.6421 + -10.000 -0.1205 0.5773 -2.9139 + -9.000 -0.1129 0.5769 -2.8656 + -8.000 -0.1057 0.5766 -2.8211 + -7.000 -0.0889 0.5765 -2.7629 + -6.000 -0.0703 0.5763 -2.7155 + -5.000 -0.0499 0.5762 -2.6789 + -4.000 -0.0288 0.5761 -2.6448 + -3.000 -0.0075 0.5760 -2.6237 + -2.000 0.0142 0.5759 -2.6263 + -1.000 0.0362 0.5758 -2.6416 + 0.000 0.0582 0.5758 -2.6578 + 1.000 0.0803 0.5758 -2.6745 + 2.000 0.1017 0.5759 -2.6909 + 4.000 0.1425 0.5760 -2.7255 + 5.000 0.1601 0.5762 -2.7421 + 6.000 0.1754 0.5765 -2.7596 + 7.000 0.1869 0.5766 -2.7798 + 8.000 0.1980 0.5768 -2.8088 + 9.000 0.2042 0.5773 -2.8362 + 10.000 0.2107 0.5779 -2.8643 + 11.000 0.2150 0.5787 -2.8954 + 12.000 0.2204 0.5796 -2.9422 + 13.000 0.2252 0.5806 -2.9891 + 14.000 0.2320 0.5817 -3.0455 + 15.000 0.2374 0.5829 -3.1009 + 16.000 0.2428 0.5842 -3.1603 + 17.000 0.2476 0.5857 -3.2240 + 19.000 0.2555 0.5891 -3.3512 + 20.000 0.2614 0.5906 -3.4288 + 21.000 0.2636 0.5927 -3.4927 + 22.000 0.2650 0.5949 -3.5583 + 23.000 0.2658 0.5973 -3.6225 + 24.000 0.2669 0.5996 -3.6923 + 25.000 0.2674 0.6019 -3.7579 + 26.000 0.2670 0.6044 -3.8169 + 27.000 0.2657 0.6069 -3.8686 + 28.000 0.2642 0.6095 -3.9160 + 29.000 0.2624 0.6121 -3.9580 + 30.000 0.2601 0.6147 -3.9922 + 40.000 0.2095 0.6531 -2.6421 + 50.000 0.1689 0.6942 -2.6421 + 60.000 0.1283 0.7333 -2.6421 + 70.000 0.0854 0.7660 -2.6421 + 80.000 0.0416 0.7885 -2.6421 + 90.000 0.0000 0.7984 -2.6421 + 100.000 -0.0291 0.7885 -2.6421 + 110.000 -0.0598 0.7660 -2.6421 + 120.000 -0.0898 0.7333 -2.6421 + 130.000 -0.1182 0.6942 -2.6421 + 140.000 -0.1467 0.6531 -2.6421 + 150.000 -0.1821 0.6147 -2.6421 + 160.000 -0.1214 0.5836 -2.6421 + 170.000 -0.0607 0.5765 -2.6421 + 180.000 0.0000 0.5765 -2.6421 +! ------------------------------------------------------------------------------ +! data for table 4 +! ------------------------------------------------------------------------------ + 8.000 Re ! Reynolds number in millions + 0 UserProp ! User property (control) setting +False InclUAdata ! Is unsteady aerodynamics data included in this table? If TRUE, then include 30 UA coefficients below this line +!........................................ +! Table of aerodynamics coefficients + 62 NumAlf ! Number of data lines in the following table +! Alpha Cl Cd Cpmin +! (deg) (-) (-) (-) + -180.000 0.0000 0.5765 -2.6421 + -170.000 0.0727 0.5765 -2.6421 + -160.000 0.1455 0.5865 -2.6421 + -150.000 0.1715 0.6174 -2.6421 + -140.000 0.1402 0.6554 -2.6421 + -130.000 0.1144 0.6961 -2.6421 + -120.000 0.0878 0.7348 -2.6421 + -110.000 0.0589 0.7670 -2.6421 + -100.000 0.0289 0.7890 -2.6421 + -90.000 0.0000 0.7984 -2.6421 + -80.000 -0.0289 0.7890 -2.6421 + -70.000 -0.0589 0.7670 -2.6421 + -60.000 -0.0878 0.7348 -2.6421 + -50.000 -0.1144 0.6961 -2.6421 + -40.000 -0.1402 0.6554 -2.6421 + -30.000 -0.1715 0.6174 -2.6421 + -20.000 -0.1503 0.5939 -2.6421 + -10.000 -0.1223 0.5772 -2.9191 + -9.000 -0.1172 0.5767 -2.8738 + -8.000 -0.1072 0.5765 -2.8237 + -5.000 -0.0498 0.5762 -2.6788 + -4.000 -0.0287 0.5761 -2.6447 + -3.000 -0.0071 0.5760 -2.6217 + -2.000 0.0146 0.5759 -2.6265 + -1.000 0.0366 0.5758 -2.6418 + 0.000 0.0588 0.5758 -2.6582 + 1.000 0.0806 0.5758 -2.6747 + 2.000 0.1019 0.5758 -2.6912 + 3.000 0.1229 0.5759 -2.7082 + 4.000 0.1424 0.5761 -2.7238 + 6.000 0.1765 0.5764 -2.7594 + 7.000 0.1903 0.5765 -2.7828 + 8.000 0.2007 0.5767 -2.8120 + 9.000 0.2064 0.5772 -2.8389 + 11.000 0.2172 0.5785 -2.8998 + 12.000 0.2241 0.5793 -2.9500 + 13.000 0.2312 0.5802 -3.0035 + 15.000 0.2438 0.5823 -3.1186 + 16.000 0.2491 0.5836 -3.1799 + 17.000 0.2546 0.5849 -3.2469 + 18.000 0.2582 0.5865 -3.3095 + 19.000 0.2624 0.5882 -3.3777 + 20.000 0.2652 0.5901 -3.4441 + 22.000 0.2683 0.5945 -3.5738 + 25.000 0.2704 0.6015 -3.7758 + 26.000 0.2702 0.6039 -3.8370 + 30.000 0.2450 0.6174 -3.5690 + 40.000 0.2003 0.6554 -2.6421 + 50.000 0.1634 0.6961 -2.6421 + 60.000 0.1254 0.7348 -2.6421 + 70.000 0.0842 0.7670 -2.6421 + 80.000 0.0413 0.7890 -2.6421 + 90.000 0.0000 0.7984 -2.6421 + 100.000 -0.0289 0.7890 -2.6421 + 110.000 -0.0589 0.7670 -2.6421 + 120.000 -0.0878 0.7348 -2.6421 + 130.000 -0.1144 0.6961 -2.6421 + 140.000 -0.1402 0.6554 -2.6421 + 150.000 -0.1715 0.6174 -2.6421 + 160.000 -0.1455 0.5865 -2.6421 + 170.000 -0.0727 0.5765 -2.6421 + 180.000 0.0000 0.5765 -2.6421 +! ------------------------------------------------------------------------------ +! data for table 5 +! ------------------------------------------------------------------------------ + 10.000 Re ! Reynolds number in millions + 0 UserProp ! User property (control) setting +False InclUAdata ! Is unsteady aerodynamics data included in this table? If TRUE, then include 30 UA coefficients below this line +!........................................ +! Table of aerodynamics coefficients + 67 NumAlf ! Number of data lines in the following table +! Alpha Cl Cd Cpmin +! (deg) (-) (-) (-) + -180.000 0.0000 0.5765 -2.6421 + -170.000 0.0628 0.5765 -2.6421 + -160.000 0.1256 0.5819 -2.6421 + -150.000 0.1883 0.6132 -2.6421 + -140.000 0.1505 0.6517 -2.6421 + -130.000 0.1204 0.6930 -2.6421 + -120.000 0.0910 0.7324 -2.6421 + -110.000 0.0603 0.7653 -2.6421 + -100.000 0.0292 0.7882 -2.6421 + -90.000 0.0000 0.7984 -2.6421 + -80.000 -0.0292 0.7882 -2.6421 + -70.000 -0.0603 0.7653 -2.6421 + -60.000 -0.0910 0.7324 -2.6421 + -50.000 -0.1204 0.6930 -2.6421 + -40.000 -0.1505 0.6517 -2.6421 + -30.000 -0.1883 0.6132 -2.6421 + -20.000 -0.1368 0.5952 -2.6421 + -10.000 -0.1219 0.5772 -2.9149 + -9.000 -0.1226 0.5766 -2.8845 + -8.000 -0.1085 0.5765 -2.8260 + -6.000 -0.0705 0.5762 -2.7163 + -4.000 -0.0286 0.5760 -2.6446 + -3.000 -0.0069 0.5760 -2.6219 + -2.000 0.0149 0.5759 -2.6267 + -1.000 0.0370 0.5758 -2.6420 + 0.000 0.0591 0.5758 -2.6583 + 1.000 0.0807 0.5758 -2.6748 + 2.000 0.1020 0.5758 -2.6915 + 4.000 0.1420 0.5761 -2.7229 + 5.000 0.1598 0.5763 -2.7401 + 6.000 0.1771 0.5764 -2.7606 + 7.000 0.1940 0.5765 -2.7861 + 8.000 0.2019 0.5767 -2.8134 + 9.000 0.2093 0.5771 -2.8426 + 10.000 0.2125 0.5778 -2.8638 + 11.000 0.2210 0.5783 -2.9073 + 12.000 0.2274 0.5791 -2.9570 + 13.000 0.2343 0.5800 -3.0108 + 14.000 0.2412 0.5809 -3.0686 + 16.000 0.2529 0.5832 -3.1916 + 17.000 0.2573 0.5847 -3.2559 + 18.000 0.2618 0.5862 -3.3219 + 19.000 0.2653 0.5879 -3.3887 + 20.000 0.2679 0.5898 -3.4550 + 21.000 0.2693 0.5919 -3.5174 + 24.000 0.2762 0.5982 -3.7432 + 25.000 0.2769 0.6005 -3.8133 + 26.000 0.2769 0.6029 -3.8791 + 27.000 0.2762 0.6053 -3.9388 + 28.000 0.2745 0.6078 -3.9894 + 29.000 0.2719 0.6105 -4.0313 + 30.000 0.2691 0.6132 -4.0663 + 40.000 0.2150 0.6517 -2.6421 + 50.000 0.1721 0.6930 -2.6421 + 60.000 0.1300 0.7324 -2.6421 + 70.000 0.0862 0.7653 -2.6421 + 80.000 0.0418 0.7882 -2.6421 + 90.000 0.0000 0.7984 -2.6421 + 100.000 -0.0292 0.7882 -2.6421 + 110.000 -0.0603 0.7653 -2.6421 + 120.000 -0.0910 0.7324 -2.6421 + 130.000 -0.1204 0.6930 -2.6421 + 140.000 -0.1505 0.6517 -2.6421 + 150.000 -0.1883 0.6132 -2.6421 + 160.000 -0.1256 0.5819 -2.6421 + 170.000 -0.0628 0.5765 -2.6421 + 180.000 0.0000 0.5765 -2.6421 +! ------------------------------------------------------------------------------ +! data for table 6 +! ------------------------------------------------------------------------------ + 12.000 Re ! Reynolds number in millions + 0 UserProp ! User property (control) setting +False InclUAdata ! Is unsteady aerodynamics data included in this table? If TRUE, then include 30 UA coefficients below this line +!........................................ +! Table of aerodynamics coefficients + 68 NumAlf ! Number of data lines in the following table +! Alpha Cl Cd Cpmin +! (deg) (-) (-) (-) + -180.000 0.0000 0.5765 -2.6421 + -170.000 0.0661 0.5765 -2.6421 + -160.000 0.1322 0.5825 -2.6421 + -150.000 0.1869 0.6137 -2.6421 + -140.000 0.1496 0.6521 -2.6421 + -130.000 0.1199 0.6934 -2.6421 + -120.000 0.0907 0.7327 -2.6421 + -110.000 0.0602 0.7655 -2.6421 + -100.000 0.0292 0.7883 -2.6421 + -90.000 0.0000 0.7984 -2.6421 + -80.000 -0.0292 0.7883 -2.6421 + -70.000 -0.0602 0.7655 -2.6421 + -60.000 -0.0907 0.7327 -2.6421 + -50.000 -0.1199 0.6934 -2.6421 + -40.000 -0.1496 0.6521 -2.6421 + -30.000 -0.1869 0.6137 -2.6421 + -20.000 -0.1421 0.5945 -2.6421 + -10.000 -0.1243 0.5770 -2.9202 + -7.000 -0.0904 0.5763 -2.7654 + -6.000 -0.0703 0.5762 -2.7143 + -5.000 -0.0498 0.5761 -2.6788 + -4.000 -0.0285 0.5760 -2.6445 + -3.000 -0.0068 0.5760 -2.6224 + -2.000 0.0151 0.5759 -2.6268 + -1.000 0.0372 0.5758 -2.6421 + 0.000 0.0592 0.5758 -2.6584 + 1.000 0.0809 0.5758 -2.6749 + 2.000 0.1021 0.5758 -2.6908 + 3.000 0.1228 0.5759 -2.7064 + 4.000 0.1421 0.5761 -2.7236 + 5.000 0.1599 0.5762 -2.7406 + 6.000 0.1783 0.5763 -2.7617 + 7.000 0.1954 0.5765 -2.7874 + 8.000 0.2032 0.5767 -2.8148 + 10.000 0.2152 0.5776 -2.8684 + 11.000 0.2233 0.5782 -2.9119 + 12.000 0.2310 0.5789 -2.9648 + 13.000 0.2383 0.5797 -3.0203 + 14.000 0.2437 0.5807 -3.0748 + 15.000 0.2498 0.5818 -3.1353 + 17.000 0.2600 0.5844 -3.2646 + 18.000 0.2642 0.5859 -3.3301 + 19.000 0.2676 0.5876 -3.3976 + 20.000 0.2694 0.5896 -3.4608 + 22.000 0.2766 0.5933 -3.6125 + 23.000 0.2780 0.5955 -3.6858 + 24.000 0.2791 0.5978 -3.7589 + 25.000 0.2796 0.6001 -3.8288 + 26.000 0.2794 0.6025 -3.8941 + 27.000 0.2781 0.6050 -3.9509 + 28.000 0.2762 0.6076 -4.0012 + 29.000 0.2739 0.6102 -4.0458 + 30.000 0.2671 0.6137 -3.9598 + 40.000 0.2137 0.6521 -2.6421 + 50.000 0.1713 0.6934 -2.6421 + 60.000 0.1296 0.7327 -2.6421 + 70.000 0.0860 0.7655 -2.6421 + 80.000 0.0417 0.7883 -2.6421 + 90.000 0.0000 0.7984 -2.6421 + 100.000 -0.0292 0.7883 -2.6421 + 110.000 -0.0602 0.7655 -2.6421 + 120.000 -0.0907 0.7327 -2.6421 + 130.000 -0.1199 0.6934 -2.6421 + 140.000 -0.1496 0.6521 -2.6421 + 150.000 -0.1869 0.6137 -2.6421 + 160.000 -0.1322 0.5825 -2.6421 + 170.000 -0.0661 0.5765 -2.6421 + 180.000 0.0000 0.5765 -2.6421 +! ------------------------------------------------------------------------------ +! data for table 7 +! ------------------------------------------------------------------------------ + 14.000 Re ! Reynolds number in millions + 0 UserProp ! User property (control) setting +False InclUAdata ! Is unsteady aerodynamics data included in this table? If TRUE, then include 30 UA coefficients below this line +!........................................ +! Table of aerodynamics coefficients + 64 NumAlf ! Number of data lines in the following table +! Alpha Cl Cd Cpmin +! (deg) (-) (-) (-) + -180.000 0.0000 0.5765 -2.6421 + -170.000 0.0637 0.5765 -2.6421 + -160.000 0.1274 0.5812 -2.6421 + -150.000 0.1912 0.6125 -2.6421 + -140.000 0.1522 0.6511 -2.6421 + -130.000 0.1215 0.6925 -2.6421 + -120.000 0.0915 0.7320 -2.6421 + -110.000 0.0606 0.7651 -2.6421 + -100.000 0.0293 0.7880 -2.6421 + -90.000 0.0000 0.7984 -2.6421 + -80.000 -0.0293 0.7880 -2.6421 + -70.000 -0.0606 0.7651 -2.6421 + -60.000 -0.0915 0.7320 -2.6421 + -50.000 -0.1215 0.6925 -2.6421 + -40.000 -0.1522 0.6511 -2.6421 + -30.000 -0.1912 0.6125 -2.6421 + -20.000 -0.1399 0.5947 -2.6421 + -10.000 -0.1267 0.5770 -2.9252 + -9.000 -0.1232 0.5766 -2.8832 + -8.000 -0.1096 0.5764 -2.8283 + -6.000 -0.0703 0.5762 -2.7138 + -5.000 -0.0497 0.5761 -2.6788 + -4.000 -0.0285 0.5760 -2.6445 + -3.000 -0.0066 0.5759 -2.6225 + -2.000 0.0153 0.5759 -2.6269 + -1.000 0.0373 0.5758 -2.6422 + 0.000 0.0594 0.5758 -2.6585 + 1.000 0.0807 0.5758 -2.6749 + 2.000 0.1021 0.5758 -2.6907 + 3.000 0.1226 0.5759 -2.7061 + 5.000 0.1605 0.5762 -2.7412 + 6.000 0.1789 0.5763 -2.7623 + 7.000 0.1967 0.5764 -2.7887 + 8.000 0.2039 0.5767 -2.8156 + 11.000 0.2254 0.5781 -2.9160 + 12.000 0.2331 0.5788 -2.9692 + 14.000 0.2475 0.5804 -3.0842 + 16.000 0.2573 0.5828 -3.2053 + 18.000 0.2662 0.5857 -3.3369 + 21.000 0.2770 0.5909 -3.5511 + 22.000 0.2788 0.5930 -3.6222 + 23.000 0.2804 0.5952 -3.6977 + 24.000 0.2812 0.5975 -3.7705 + 25.000 0.2815 0.5998 -3.8400 + 26.000 0.2807 0.6023 -3.9023 + 27.000 0.2794 0.6048 -3.9597 + 28.000 0.2777 0.6073 -4.0122 + 29.000 0.2757 0.6099 -4.0591 + 30.000 0.2731 0.6125 -4.0985 + 40.000 0.2174 0.6511 -2.6421 + 50.000 0.1735 0.6925 -2.6421 + 60.000 0.1308 0.7320 -2.6421 + 70.000 0.0865 0.7651 -2.6421 + 80.000 0.0419 0.7880 -2.6421 + 90.000 0.0000 0.7984 -2.6421 + 100.000 -0.0293 0.7880 -2.6421 + 110.000 -0.0606 0.7651 -2.6421 + 120.000 -0.0915 0.7320 -2.6421 + 130.000 -0.1215 0.6925 -2.6421 + 140.000 -0.1522 0.6511 -2.6421 + 150.000 -0.1912 0.6125 -2.6421 + 160.000 -0.1274 0.5812 -2.6421 + 170.000 -0.0637 0.5765 -2.6421 + 180.000 0.0000 0.5765 -2.6421 \ No newline at end of file diff --git a/Test_Cases/MHK_RM1/Airfoils/NACA6_0864_coords.txt b/Test_Cases/MHK_RM1/Airfoils/NACA6_0864_coords.txt new file mode 100644 index 00000000..8a9382a1 --- /dev/null +++ b/Test_Cases/MHK_RM1/Airfoils/NACA6_0864_coords.txt @@ -0,0 +1,47 @@ + 40 NumCoords ! The number of coordinates in the airfoil shape file (including an extra coordinate for airfoil reference). Set to zero if coordinates not included. +! ......... x-y coordinates are next if NumCoords > 0 ............. +! x-y coordinate of airfoil reference +! x/c y/c + 0.25 0 +! coordinates of airfoil shape +! NACA6_0864 Airfoil +! x/c y/c + 0.000000 0.000000 + 0.006819 0.071897 + 0.027091 0.142126 + 0.060263 0.208964 + 0.105430 0.270115 + 0.161359 0.323830 + 0.226526 0.368470 + 0.299152 0.402651 + 0.377257 0.425156 + 0.458710 0.435236 + 0.541290 0.432906 + 0.622743 0.418526 + 0.700848 0.392758 + 0.773474 0.356678 + 0.838641 0.311513 + 0.894570 0.258619 + 0.939737 0.199450 + 0.972909 0.135539 + 0.993181 0.068594 + 1.000000 0.000000 + 0.993181 -0.068161 + 0.972909 -0.134227 + 0.939737 -0.197056 + 0.894570 -0.255087 + 0.838641 -0.306904 + 0.773474 -0.351143 + 0.700848 -0.386540 + 0.622743 -0.411920 + 0.541290 -0.426222 + 0.458710 -0.428757 + 0.377257 -0.419101 + 0.299152 -0.397194 + 0.226526 -0.363795 + 0.161359 -0.320050 + 0.105430 -0.267316 + 0.060263 -0.207125 + 0.027091 -0.141176 + 0.006819 -0.071509 + 0.000000 0.000000 \ No newline at end of file diff --git a/Test_Cases/MHK_RM1/Airfoils/NACA6_1000.dat b/Test_Cases/MHK_RM1/Airfoils/NACA6_1000.dat new file mode 100644 index 00000000..7c3e8471 --- /dev/null +++ b/Test_Cases/MHK_RM1/Airfoils/NACA6_1000.dat @@ -0,0 +1,108 @@ +! ------------ AirfoilInfo v1.01.x Input File ---------------------------------- +! NACA6_1000 airfoil, data based on values used for the design of the RM1 tidal current turbine. +! line +! line +! ------------------------------------------------------------------------------ +"default" InterpOrd ! Interpolation order to use for quasi-steady table lookup {1=linear; 3=cubic spline; "default"} [default=1] + 1.0 NonDimArea ! The non-dimensional area of the airfoil (area/chord^2) (set to 1.0 if unsure or unneeded) +@"NACA6_1000_coords.txt" NumCoords ! The number of coordinates in the airfoil shape file. Set to zero if coordinates not included. +"unused" BL_file ! The file name including the boundary layer characteristics of the profile. Ignored if the aeroacoustic module is not called. + 7 NumTabs ! Number of airfoil tables in this file. +! ------------------------------------------------------------------------------ +! data for table 1 +! ------------------------------------------------------------------------------ + 2.0 Re ! Reynolds number in millions + 0 UserProp ! User property (control) setting +False InclUAdata ! Is unsteady aerodynamics data included in this table? If TRUE, then include 30 UA coefficients below this line +!........................................ +! Table of aerodynamics coefficients + 3 NumAlf ! Number of data lines in the following table +! Alpha Cl Cd Cpmin +! (deg) (-) (-) (-) + -180.00 0.0 0.3 -3.0 + 0.00 0.0 0.3 -3.0 + 180.00 0.0 0.3 -3.0 +! ------------------------------------------------------------------------------ +! data for table 2 +! ------------------------------------------------------------------------------ + 4.0 Re ! Reynolds number in millions + 0 UserProp ! User property (control) setting +False InclUAdata ! Is unsteady aerodynamics data included in this table? If TRUE, then include 30 UA coefficients below this line +!........................................ +! Table of aerodynamics coefficients + 3 NumAlf ! Number of data lines in the following table +! Alpha Cl Cd Cpmin +! (deg) (-) (-) (-) + -180.00 0.0 0.67 -3.0 + 0.00 0.0 0.67 -3.0 + 180.00 0.0 0.67 -3.0 +! ------------------------------------------------------------------------------ +! data for table 3 +! ------------------------------------------------------------------------------ + 6.0 Re ! Reynolds number in millions + 0 UserProp ! User property (control) setting +False InclUAdata ! Is unsteady aerodynamics data included in this table? If TRUE, then include 30 UA coefficients below this line +!........................................ +! Table of aerodynamics coefficients + 3 NumAlf ! Number of data lines in the following table +! Alpha Cl Cd Cpmin +! (deg) (-) (-) (-) + -180.00 0.0 0.7 -3.0 + 0.00 0.0 0.7 -3.0 + 180.00 0.0 0.7 -3.0 +! ------------------------------------------------------------------------------ +! data for table 4 +! ------------------------------------------------------------------------------ + 8.0 Re ! Reynolds number in millions + 0 UserProp ! User property (control) setting +False InclUAdata ! Is unsteady aerodynamics data included in this table? If TRUE, then include 30 UA coefficients below this line +!........................................ +! Table of aerodynamics coefficients + 3 NumAlf ! Number of data lines in the following table +! Alpha Cl Cd Cpmin +! (deg) (-) (-) (-) + -180.00 0.0 0.7 -3.0 + 0.00 0.0 0.7 -3.0 + 180.00 0.0 0.7 -3.0 +! ------------------------------------------------------------------------------ +! data for table 5 +! ------------------------------------------------------------------------------ + 10.0 Re ! Reynolds number in millions + 0 UserProp ! User property (control) setting +False InclUAdata ! Is unsteady aerodynamics data included in this table? If TRUE, then include 30 UA coefficients below this line +!........................................ +! Table of aerodynamics coefficients + 3 NumAlf ! Number of data lines in the following table +! Alpha Cl Cd Cpmin +! (deg) (-) (-) (-) + -180.00 0.0 0.7 -3.0 + 0.00 0.0 0.7 -3.0 + 180.00 0.0 0.7 -3.0 +! ------------------------------------------------------------------------------ +! data for table 6 +! ------------------------------------------------------------------------------ + 12.0 Re ! Reynolds number in millions + 0 UserProp ! User property (control) setting +False InclUAdata ! Is unsteady aerodynamics data included in this table? If TRUE, then include 30 UA coefficients below this line +!........................................ +! Table of aerodynamics coefficients + 3 NumAlf ! Number of data lines in the following table +! Alpha Cl Cd Cpmin +! (deg) (-) (-) (-) + -180.00 0.0 0.7 -3.0 + 0.00 0.0 0.7 -3.0 + 180.00 0.0 0.7 -3.0 +! ------------------------------------------------------------------------------ +! data for table 7 +! ------------------------------------------------------------------------------ + 14.0 Re ! Reynolds number in millions + 0 UserProp ! User property (control) setting +False InclUAdata ! Is unsteady aerodynamics data included in this table? If TRUE, then include 30 UA coefficients below this line +!........................................ +! Table of aerodynamics coefficients + 3 NumAlf ! Number of data lines in the following table +! Alpha Cl Cd Cpmin +! (deg) (-) (-) (-) + -180.00 0.0 0.7 -3.0 + 0.00 0.0 0.7 -3.0 + 180.00 0.0 0.7 -3.0 \ No newline at end of file diff --git a/Test_Cases/MHK_RM1/Airfoils/NACA6_1000_coords.txt b/Test_Cases/MHK_RM1/Airfoils/NACA6_1000_coords.txt new file mode 100644 index 00000000..e9876cf7 --- /dev/null +++ b/Test_Cases/MHK_RM1/Airfoils/NACA6_1000_coords.txt @@ -0,0 +1,47 @@ + 40 NumCoords ! The number of coordinates in the airfoil shape file (including an extra coordinate for airfoil reference). Set to zero if coordinates not included. +! ......... x-y coordinates are next if NumCoords > 0 ............. +! x-y coordinate of airfoil reference +! x/c y/c + 0.25 0 +! coordinates of airfoil shape +! NACA6_1000 Airfoil +! x/c y/c + 0.000000 0.000000 + 0.006819 0.082442 + 0.027091 0.162359 + 0.060263 0.237976 + 0.105430 0.307106 + 0.161359 0.367865 + 0.226526 0.418583 + 0.299152 0.457883 + 0.377257 0.484712 + 0.458710 0.498283 + 0.541290 0.498283 + 0.622743 0.484712 + 0.700848 0.457883 + 0.773474 0.418583 + 0.838641 0.367865 + 0.894570 0.307106 + 0.939737 0.237976 + 0.972909 0.162359 + 0.993181 0.082442 + 1.000000 0.000000 + 0.993181 -0.082442 + 0.972909 -0.162359 + 0.939737 -0.237976 + 0.894570 -0.307106 + 0.838641 -0.367865 + 0.773474 -0.418583 + 0.700848 -0.457883 + 0.622743 -0.484712 + 0.541290 -0.498283 + 0.458710 -0.498283 + 0.377257 -0.484712 + 0.299152 -0.457883 + 0.226526 -0.418583 + 0.161359 -0.367865 + 0.105430 -0.307106 + 0.060263 -0.237976 + 0.027091 -0.162359 + 0.006819 -0.082442 + 0.000000 0.000000 \ No newline at end of file diff --git a/Test_Cases/MHK_RM1/MHK_RM1_AeroDyn15_Blade.dat b/Test_Cases/MHK_RM1/MHK_RM1_AeroDyn15_Blade.dat new file mode 100644 index 00000000..29c7548a --- /dev/null +++ b/Test_Cases/MHK_RM1/MHK_RM1_AeroDyn15_Blade.dat @@ -0,0 +1,38 @@ +------- AERODYN v15.00.* BLADE DEFINITION INPUT FILE ------------------------------------- +Floating MHK turbine hydrodynamic blade input properties, based on the RM1 tidal current rotor +====== Blade Properties ================================================================= +32 NumBlNds - Number of blade nodes used in the analysis (-) +BlSpn BlCrvAC BlSwpAC BlCrvAng BlTwist BlChord BlAFID BlCb BlCenBn BlCenBt +(m) (m) (m) (deg) (deg) (m) (-) (-) (m) (m) +0.000 0.00 0.00 0.00 12.86 0.800 1 0.9956 0.0000 0.2000 +0.150 0.00 0.00 0.00 12.86 0.800 1 0.9956 0.0000 0.2000 +0.450 0.00 0.00 0.00 12.86 0.894 2 0.8572 0.0023 0.2202 +0.750 0.00 0.00 0.00 12.86 1.118 3 0.6118 0.0082 0.2637 +1.050 0.00 0.00 0.00 12.86 1.386 4 0.4145 0.0153 0.3027 +1.350 0.00 0.00 0.00 12.86 1.610 5 0.2873 0.0217 0.3131 +1.650 0.00 0.00 0.00 12.86 1.704 6 0.2287 0.0250 0.2973 +1.950 0.00 0.00 0.00 11.54 1.662 7 0.2099 0.0250 0.2753 +2.250 0.00 0.00 0.00 10.44 1.619 8 0.1966 0.0247 0.2565 +2.550 0.00 0.00 0.00 9.50 1.577 9 0.1870 0.0245 0.2386 +2.850 0.00 0.00 0.00 8.71 1.534 9 0.1870 0.0238 0.2321 +3.150 0.00 0.00 0.00 8.02 1.492 9 0.1870 0.0232 0.2258 +3.450 0.00 0.00 0.00 7.43 1.450 9 0.1870 0.0225 0.2194 +3.750 0.00 0.00 0.00 6.91 1.407 9 0.1870 0.0218 0.2129 +4.050 0.00 0.00 0.00 6.45 1.365 9 0.1870 0.0212 0.2066 +4.350 0.00 0.00 0.00 6.04 1.322 9 0.1870 0.0205 0.2001 +4.650 0.00 0.00 0.00 5.68 1.279 9 0.1870 0.0198 0.1935 +4.950 0.00 0.00 0.00 5.35 1.235 9 0.1870 0.0192 0.1869 +5.250 0.00 0.00 0.00 5.05 1.192 9 0.1870 0.0185 0.1804 +5.550 0.00 0.00 0.00 4.77 1.148 9 0.1870 0.0178 0.1737 +5.850 0.00 0.00 0.00 4.51 1.103 9 0.1870 0.0171 0.1669 +6.150 0.00 0.00 0.00 4.26 1.058 9 0.1870 0.0164 0.1601 +6.450 0.00 0.00 0.00 4.03 1.012 9 0.1870 0.0157 0.1531 +6.750 0.00 0.00 0.00 3.80 0.966 9 0.1870 0.0150 0.1462 +7.050 0.00 0.00 0.00 3.57 0.920 9 0.1870 0.0143 0.1392 +7.350 0.00 0.00 0.00 3.35 0.872 9 0.1870 0.0135 0.1320 +7.650 0.00 0.00 0.00 3.13 0.824 9 0.1870 0.0128 0.1247 +7.950 0.00 0.00 0.00 2.90 0.776 9 0.1870 0.0120 0.1174 +8.250 0.00 0.00 0.00 2.67 0.726 9 0.1870 0.0113 0.1099 +8.550 0.00 0.00 0.00 2.43 0.676 9 0.1870 0.0105 0.1023 +8.850 0.00 0.00 0.00 2.18 0.626 9 0.1870 0.0097 0.0947 +9.000 0.00 0.00 0.00 2.18 0.626 9 0.1870 0.0097 0.0947 \ No newline at end of file diff --git a/Test_Cases/MHK_RM1/MHK_RM1_Cp_Ct_Cq.txt b/Test_Cases/MHK_RM1/MHK_RM1_Cp_Ct_Cq.txt new file mode 100644 index 00000000..da7445bf --- /dev/null +++ b/Test_Cases/MHK_RM1/MHK_RM1_Cp_Ct_Cq.txt @@ -0,0 +1,99 @@ +# ----- Rotor performance tables for the MHK_RM1_Floating wind turbine ----- +# ------------ Written on Apr-12-23 using the ROSCO toolbox ------------ + +# Pitch angle vector, 36 entries - x axis (matrix columns) (deg) +-5.0 -4.0 -3.0 -2.0 -1.0 0.0 1.0 2.0 3.0 4.0 5.0 6.0 7.0 8.0 9.0 10.0 11.0 12.0 13.0 14.0 15.0 16.0 17.0 18.0 19.0 20.0 21.0 22.0 23.0 24.0 25.0 26.0 27.0 28.0 29.0 30.0 +# TSR vector, 26 entries - y axis (matrix rows) (-) +2.0 2.5 3.0 3.5 4.0 4.5 5.0 5.5 6.0 6.5 7.0 7.5 8.0 8.5 9.0 9.5 10.0 10.5 11.0 11.5 12.0 12.5 13.0 13.5 14.0 14.5 +# Wind speed vector - z axis (m/s) +2.0 + +# Power coefficient + +0.074944 0.079726 0.084378 0.088881 0.093217 0.097364 0.101301 0.105005 0.108455 0.111627 0.114499 0.117048 0.119254 0.121097 0.122559 0.123624 0.124278 0.124507 0.124300 0.123645 0.122533 0.120953 0.118899 0.116363 0.113340 0.109825 0.105817 0.101315 0.096316 0.090822 0.084833 0.078355 0.071398 0.063985 0.056154 0.047964 +0.130952 0.137109 0.142870 0.148203 0.153074 0.157453 0.161312 0.164628 0.167372 0.169517 0.171039 0.171924 0.172157 0.171726 0.170619 0.168827 0.166341 0.163154 0.159260 0.154654 0.149334 0.143297 0.136543 0.129071 0.120881 0.111975 0.102356 0.092036 0.081046 0.069441 0.057307 0.044758 0.031932 0.018970 0.006005 -0.006847 +0.195638 0.202139 0.207875 0.212814 0.216927 0.220183 0.222553 0.224026 0.224594 0.224263 0.222996 0.220777 0.217599 0.213457 0.208343 0.202253 0.195185 0.187134 0.178099 0.168078 0.157067 0.145065 0.132070 0.118086 0.103136 0.087277 0.070607 0.053271 0.035454 0.017370 -0.000779 -0.018814 -0.036579 -0.053937 -0.070772 -0.086985 +0.262033 0.267729 0.272255 0.275602 0.277770 0.278772 0.278626 0.277286 0.274722 0.270950 0.265956 0.259691 0.252150 0.243325 0.233208 0.221791 0.209065 0.195021 0.179649 0.162940 0.144884 0.125492 0.104814 0.082960 0.060099 0.036466 0.012350 -0.011952 -0.036178 -0.060102 -0.083527 -0.106282 -0.128227 -0.149248 -0.169259 -0.188203 +0.322926 0.327173 0.329927 0.331189 0.330966 0.329268 0.326118 0.321556 0.315485 0.307866 0.298685 0.287857 0.275361 0.261178 0.245286 0.227663 0.208287 0.187132 0.164179 0.139430 0.112946 0.084868 0.055418 0.024908 -0.006270 -0.037714 -0.069075 -0.100049 -0.130376 -0.159832 -0.188230 -0.215422 -0.241296 -0.265780 -0.288840 -0.310479 +0.372380 0.375319 0.376595 0.376163 0.373941 0.369893 0.364015 0.356336 0.346830 0.335323 0.321769 0.306044 0.288110 0.267928 0.245459 0.220662 0.193502 0.163952 0.132049 0.097926 0.061824 0.024095 -0.014788 -0.054287 -0.093913 -0.133250 -0.171936 -0.209660 -0.246161 -0.281224 -0.314687 -0.346436 -0.376411 -0.404602 -0.431047 -0.455838 +0.405840 0.408981 0.410112 0.409159 0.406069 0.400647 0.392786 0.382501 0.369826 0.354510 0.336432 0.315446 0.291501 0.264544 0.234524 0.201389 0.165121 0.125794 0.083613 0.038921 -0.007794 -0.055894 -0.104692 -0.153592 -0.202082 -0.249721 -0.296127 -0.340984 -0.384037 -0.425096 -0.464037 -0.500803 -0.535402 -0.567911 -0.598467 -0.627270 +0.419815 0.426133 0.429721 0.430398 0.428020 0.422533 0.413665 0.401397 0.385844 0.366737 0.343872 0.317114 0.286411 0.251710 0.212957 0.170136 0.123352 0.072872 0.019131 -0.037250 -0.095463 -0.154643 -0.214052 -0.273053 -0.331092 -0.387697 -0.442469 -0.495093 -0.545333 -0.593039 -0.638145 -0.680670 -0.720718 -0.758469 -0.794184 -0.828187 +0.416203 0.426901 0.435700 0.440694 0.441121 0.436927 0.428055 0.414373 0.396136 0.373105 0.345026 0.311802 0.273402 0.229785 0.180939 0.126984 0.068233 0.005200 -0.061381 -0.130534 -0.201181 -0.272387 -0.343354 -0.413383 -0.481873 -0.548318 -0.612312 -0.673550 -0.731832 -0.787064 -0.839260 -0.888535 -0.935107 -0.979287 -1.021467 -1.062112 +0.405435 0.418564 0.430778 0.441391 0.446693 0.445250 0.437234 0.422572 0.401692 0.374435 0.340533 0.299965 0.252737 0.198854 0.138441 0.071834 -0.000397 -0.077426 -0.158137 -0.241210 -0.325451 -0.409848 -0.493517 -0.575688 -0.655711 -0.733053 -0.807309 -0.878198 -0.945571 -1.009410 -1.069825 -1.127051 -1.181434 -1.233429 -1.283586 -1.332529 +0.390503 0.406666 0.421413 0.435076 0.446065 0.448699 0.442235 0.426873 0.403229 0.371269 0.330765 0.281798 0.224440 0.158821 0.085281 0.004419 -0.082876 -0.175390 -0.271577 -0.369910 -0.469102 -0.568030 -0.665710 -0.761300 -0.854102 -0.943564 -1.029289 -1.111036 -1.188722 -1.262423 -1.332361 -1.398905 -1.462560 -1.523949 -1.583795 -1.642861 +0.371667 0.391683 0.409587 0.425790 0.440553 0.448186 0.443843 0.427902 0.401216 0.363917 0.315877 0.257305 0.188389 0.109467 0.021145 -0.075662 -0.179678 -0.289215 -0.402371 -0.517492 -0.633155 -0.748106 -0.861259 -0.971696 -1.078673 -1.181626 -1.280179 -1.374141 -1.463512 -1.548474 -1.629388 -1.706786 -1.781347 -1.853884 -1.925308 -1.996461 +0.348976 0.373677 0.395430 0.414664 0.431984 0.444452 0.442628 0.426075 0.395932 0.352522 0.295876 0.226363 0.144361 0.050473 -0.054383 -0.168912 -0.291369 -0.419564 -0.551360 -0.684950 -0.818747 -0.951358 -1.081586 -1.208436 -1.331122 -1.449075 -1.561948 -1.669615 -1.772174 -1.869941 -1.963438 -2.053377 -2.140642 -2.226257 -2.311298 -2.396626 +0.322447 0.352671 0.378963 0.401764 0.421785 0.438064 0.438990 0.421654 0.387518 0.337104 0.270664 0.188770 0.092059 -0.018557 -0.141791 -0.275900 -0.418590 -0.567224 -0.719482 -0.873361 -1.027094 -1.179135 -1.328171 -1.473129 -1.613185 -1.747771 -1.876578 -1.999566 -2.116951 -2.229204 -2.337032 -2.441358 -2.543286 -2.644065 -2.744885 -2.846626 +0.292104 0.328674 0.360194 0.387092 0.410155 0.429464 0.433189 0.414787 0.376018 0.317600 0.240072 0.144265 0.031127 -0.098072 -0.241618 -0.397243 -0.562049 -0.733059 -0.907740 -1.083862 -1.259459 -1.432826 -1.602527 -1.767409 -1.926613 -2.079580 -2.226059 -2.366108 -2.500086 -2.628644 -2.752697 -2.873398 -2.992099 -3.110271 -3.229166 -3.349696 +0.257934 0.301688 0.339118 0.370637 0.397092 0.419035 0.425380 0.405542 0.361401 0.293886 0.203884 0.092545 -0.038828 -0.188556 -0.354435 -0.533590 -0.722527 -0.917988 -1.117178 -1.317621 -1.517135 -1.713843 -1.906181 -2.092918 -2.273163 -2.446378 -2.612385 -2.771358 -2.923825 -3.070638 -3.212946 -3.352157 -3.489890 -3.627813 -3.767210 -3.909048 +0.219932 0.271699 0.315725 0.352385 0.382573 0.407064 0.415649 0.393924 0.343586 0.265797 0.161855 0.033279 -0.118226 -0.290520 -0.480838 -0.685625 -0.900846 -1.122958 -1.348868 -1.575829 -1.801429 -2.023608 -2.240672 -2.451307 -2.654600 -2.850044 -3.037549 -3.217434 -3.390412 -3.557560 -3.720288 -3.880284 -4.039448 -4.199603 -4.362066 -4.527873 +0.178135 0.238694 0.290002 0.332317 0.366567 0.393662 0.404032 0.379897 0.322460 0.233142 0.113714 -0.033886 -0.207507 -0.404491 -0.621444 -0.854066 -1.097853 -1.348937 -1.603896 -1.859687 -2.113658 -2.363555 -2.607543 -2.844231 -3.072689 -3.292456 -3.503551 -3.706453 -3.902085 -4.091779 -4.277226 -4.460416 -4.643543 -4.828535 -5.016766 -5.209342 +0.132703 0.202667 0.261930 0.310408 0.349034 0.378811 0.390525 0.363396 0.297884 0.195706 0.059174 -0.109316 -0.307124 -0.531014 -0.776881 -1.039657 -1.314414 -1.596907 -1.883356 -2.170409 -2.455151 -2.735120 -3.008340 -3.273345 -3.529196 -3.775497 -4.012387 -4.240529 -4.461083 -4.675657 -4.886250 -5.095180 -5.304925 -5.517492 -5.734327 -5.956614 +0.084224 0.163639 0.231485 0.286625 0.329931 0.362460 0.375097 0.344332 0.269698 0.153266 -0.002060 -0.193389 -0.417541 -0.670640 -0.947787 -1.243159 -1.551402 -1.867855 -2.188355 -2.509214 -2.827235 -3.139741 -3.444611 -3.740306 -4.025892 -4.301046 -4.566051 -4.821776 -5.069639 -5.311551 -5.549845 -5.787192 -6.026332 -6.269342 -6.517755 -6.772836 +0.034952 0.121693 0.198644 0.260932 0.309208 0.344544 0.357698 0.322599 0.237730 0.105587 -0.070294 -0.286489 -0.539230 -0.823928 -1.134814 -1.465339 -1.809699 -2.162779 -2.520003 -2.877323 -3.231243 -3.578859 -3.917904 -4.246774 -4.564545 -4.870985 -5.166539 -5.452304 -5.729981 -6.001811 -6.270488 -6.539057 -6.810494 -7.086946 -7.370046 -7.661142 +-0.011115 0.077127 0.163389 0.233290 0.286813 0.324991 0.338262 0.298075 0.201799 0.052429 -0.145838 -0.389008 -0.672666 -0.991441 -1.338622 -1.706972 -2.090192 -2.482680 -2.879417 -3.275962 -3.668506 -4.053914 -4.429770 -4.794407 -5.146925 -5.487194 -5.815843 -6.134218 -6.444332 -6.748781 -7.050649 -7.353371 -7.660131 -7.973156 -8.294185 -8.624661 +-0.050911 0.031047 0.125717 0.203658 0.262692 0.303728 0.316707 0.270625 0.161721 -0.006451 -0.229008 -0.501339 -0.818328 -1.173745 -1.559880 -1.968838 -2.393776 -2.828568 -3.267710 -3.706353 -4.140357 -4.566348 -4.981760 -5.384866 -5.774799 -6.151551 -6.515951 -6.869621 -7.214911 -7.554801 -7.892791 -8.232723 -8.577956 -8.930816 -9.293154 -9.666511 +-0.083826 -0.014210 0.085661 0.171992 0.236785 0.280676 0.292937 0.240111 0.117308 -0.071300 -0.320120 -0.623879 -0.976697 -1.371406 -1.799263 -2.251722 -2.721350 -3.201448 -3.685999 -4.169721 -4.648130 -5.117604 -5.575423 -6.019808 -6.449935 -6.865932 -7.268850 -7.660612 -8.043932 -8.422205 -8.799374 -9.179693 -9.566677 -9.962766 -10.369925 -10.789805 +-0.112321 -0.056414 0.043373 0.138247 0.209032 0.255752 0.266847 0.206391 0.068370 -0.142368 -0.419492 -0.757024 -1.148255 -1.584993 -2.057449 -2.556414 -3.073813 -3.602329 -4.135402 -4.667292 -5.193160 -5.709124 -6.212312 -6.700894 -7.174100 -7.632211 -8.076523 -8.509287 -8.933609 -9.353325 -9.772854 -10.196858 -10.628998 -11.071839 -11.527466 -11.997652 +-0.138289 -0.094091 -0.000597 0.102378 0.179367 0.228869 0.238326 0.169319 0.014717 -0.219903 -0.527445 -0.901172 -1.333484 -1.815079 -2.335120 -2.883708 -3.452066 -4.032220 -4.617034 -5.200293 -5.776782 -6.342352 -6.893976 -7.429778 -7.949056 -8.452259 -8.940954 -9.417741 -9.886149 -10.350489 -10.815681 -11.286791 -11.767617 -12.260864 -12.768741 -13.293158 + + +# Thrust coefficient + +0.173936 0.174545 0.175105 0.175604 0.176027 0.176357 0.176576 0.176665 0.176604 0.176373 0.175951 0.175317 0.174451 0.173333 0.171944 0.170267 0.168285 0.165982 0.163343 0.160355 0.157004 0.153277 0.149165 0.144659 0.139751 0.134439 0.128718 0.122589 0.116054 0.109113 0.101773 0.094042 0.085936 0.077488 0.068744 0.059773 +0.244110 0.244807 0.245270 0.245468 0.245368 0.244940 0.244155 0.242988 0.241410 0.239388 0.236896 0.233914 0.230421 0.226400 0.221834 0.216710 0.211014 0.204738 0.197875 0.190421 0.182376 0.173742 0.164522 0.154724 0.144354 0.133423 0.121945 0.109944 0.097467 0.084590 0.071416 0.058076 0.044718 0.031490 0.018521 0.005920 +0.329058 0.328652 0.327699 0.326163 0.324010 0.321203 0.317708 0.313503 0.308574 0.302916 0.296490 0.289274 0.281258 0.272437 0.262806 0.252366 0.241123 0.229082 0.216256 0.202654 0.188292 0.173184 0.157347 0.140807 0.123614 0.105857 0.087669 0.069222 0.050725 0.032400 0.014449 -0.002964 -0.019698 -0.035638 -0.050689 -0.064777 +0.423724 0.420631 0.416601 0.411609 0.405640 0.398694 0.390781 0.381862 0.371916 0.360960 0.348987 0.335961 0.321889 0.306782 0.290656 0.273525 0.255410 0.236329 0.216303 0.195352 0.173503 0.150806 0.127362 0.103332 0.078936 0.054443 0.030163 0.006389 -0.016641 -0.038731 -0.059724 -0.079492 -0.097938 -0.114987 -0.130589 -0.144718 +0.522708 0.515320 0.506632 0.496639 0.485349 0.472781 0.458970 0.443976 0.427746 0.410278 0.391592 0.371635 0.350431 0.328001 0.304369 0.279560 0.253599 0.226508 0.198319 0.169094 0.138969 0.108161 0.076963 0.045733 0.014882 -0.015203 -0.044217 -0.071919 -0.098118 -0.122660 -0.145431 -0.166347 -0.185356 -0.202436 -0.217593 -0.230865 +0.620986 0.607920 0.593333 0.577234 0.559606 0.540466 0.519860 0.497874 0.474551 0.449800 0.423636 0.395993 0.366897 0.336377 0.304459 0.271170 0.236538 0.200616 0.163534 0.125537 0.086962 0.048236 0.009863 -0.027633 -0.063829 -0.098403 -0.131103 -0.161729 -0.190133 -0.216204 -0.239873 -0.261109 -0.279917 -0.296336 -0.310444 -0.322349 +0.714037 0.694660 0.673585 0.650833 0.626441 0.600346 0.572544 0.543137 0.512256 0.479758 0.445598 0.409704 0.372107 0.332841 0.291934 0.249425 0.205397 0.160063 0.113768 0.066972 0.020233 -0.025799 -0.070499 -0.113396 -0.154133 -0.192434 -0.228087 -0.260935 -0.290868 -0.317827 -0.341795 -0.362800 -0.380914 -0.396253 -0.408976 -0.419282 +0.797619 0.772416 0.745286 0.716196 0.685139 0.652162 0.617157 0.580209 0.541535 0.500976 0.458403 0.413758 0.367089 0.318440 0.267859 0.215464 0.161536 0.106521 0.050989 -0.004371 -0.058762 -0.111433 -0.161837 -0.209563 -0.254300 -0.295806 -0.333907 -0.368486 -0.399482 -0.426887 -0.450748 -0.471165 -0.488287 -0.502317 -0.513506 -0.522151 +0.870407 0.839307 0.807149 0.772800 0.735851 0.696368 0.654402 0.609945 0.563343 0.514447 0.463055 0.409157 0.352830 0.294145 0.233245 0.170467 0.106342 0.041549 -0.023101 -0.086663 -0.148218 -0.207098 -0.262819 -0.315010 -0.363387 -0.407744 -0.447945 -0.483917 -0.515653 -0.543208 -0.566698 -0.586303 -0.602262 -0.614871 -0.624481 -0.631491 +0.937801 0.898777 0.859871 0.820832 0.779117 0.733820 0.685207 0.633320 0.578660 0.521127 0.460477 0.396782 0.330166 0.260796 0.189045 0.115524 0.041008 -0.033579 -0.107154 -0.178587 -0.247028 -0.311881 -0.372693 -0.429119 -0.480906 -0.527879 -0.569945 -0.607081 -0.639338 -0.666842 -0.689787 -0.708441 -0.723135 -0.734268 -0.742302 -0.747750 +1.002272 0.954818 0.907800 0.861790 0.815766 0.765455 0.710516 0.651256 0.588370 0.521837 0.451428 0.377331 0.299768 0.219135 0.136104 0.051544 -0.033517 -0.117878 -0.200191 -0.279333 -0.354544 -0.425257 -0.491041 -0.551574 -0.606630 -0.656072 -0.699848 -0.737992 -0.770621 -0.797933 -0.820208 -0.837806 -0.851169 -0.860810 -0.867314 -0.871279 +1.064598 1.008390 0.952917 0.898894 0.846816 0.792132 0.731177 0.664544 0.593190 0.517221 0.436491 0.351342 0.262208 0.169811 0.075110 -0.020766 -0.116510 -0.210609 -0.301585 -0.388416 -0.470381 -0.546930 -0.617647 -0.682232 -0.740484 -0.792304 -0.837690 -0.876733 -0.909619 -0.936626 -0.958130 -0.974602 -0.986598 -0.994763 -0.999805 -1.002335 +1.125286 1.060007 0.995803 0.933481 0.873901 0.814638 0.747903 0.673814 0.593683 0.507777 0.416109 0.319252 0.217981 0.113352 0.006598 -0.100867 -0.207420 -0.311262 -0.410956 -0.505547 -0.594326 -0.676752 -0.752421 -0.821050 -0.882469 -0.936617 -0.983541 -1.023394 -1.056440 -1.083052 -1.103712 -1.119007 -1.129628 -1.136358 -1.139998 -1.141107 +1.184710 1.110050 1.036840 0.965984 0.898504 0.833644 0.761274 0.679565 0.590284 0.493877 0.390619 0.281434 0.167495 0.050167 -0.069022 -0.188346 -0.305833 -0.419523 -0.528075 -0.630559 -0.726266 -0.814657 -0.895336 -0.968037 -1.032619 -1.089062 -1.137468 -1.178060 -1.211191 -1.237335 -1.257092 -1.271183 -1.280440 -1.285786 -1.288054 -1.287742 +1.243183 1.158809 1.076317 0.996699 0.921110 0.849734 0.771746 0.682183 0.583321 0.475803 0.360302 0.238207 0.111071 -0.019424 -0.151434 -0.282888 -0.411466 -0.535198 -0.652809 -0.763367 -0.866154 -0.960628 -1.046399 -1.123218 -1.190975 -1.249694 -1.299539 -1.340814 -1.373965 -1.399583 -1.418398 -1.431272 -1.439187 -1.443198 -1.444104 -1.442358 +1.300910 1.206519 1.114465 1.025858 0.941977 0.863452 0.779673 0.681967 0.573037 0.453771 0.325405 0.189827 0.048963 -0.095175 -0.240399 -0.384254 -0.524144 -0.658173 -0.785084 -0.903927 -1.013972 -1.114667 -1.205628 -1.286626 -1.357580 -1.418567 -1.469819 -1.511728 -1.544850 -1.569899 -1.587742 -1.599395 -1.606003 -1.608709 -1.608248 -1.605042 +1.358030 1.253357 1.151469 1.053649 0.961301 0.875262 0.785334 0.679149 0.559618 0.427966 0.286133 0.136500 -0.018634 -0.176899 -0.335733 -0.492272 -0.643762 -0.788382 -0.924861 -1.052225 -1.169720 -1.276789 -1.373051 -1.458293 -1.532476 -1.595730 -1.648366 -1.690874 -1.723926 -1.748368 -1.765221 -1.775661 -1.780996 -1.782408 -1.780566 -1.775864 +1.414606 1.299461 1.187483 1.080229 0.979241 0.885469 0.788952 0.673911 0.543212 0.398553 0.242657 0.078384 -0.091569 -0.264451 -0.437297 -0.606831 -0.770255 -0.925787 -1.072124 -1.208256 -1.333409 -1.447015 -1.548693 -1.638256 -1.715703 -1.781230 -1.835235 -1.878313 -1.911261 -1.935071 -1.950921 -1.960159 -1.964252 -1.964367 -1.961118 -1.954875 +1.470532 1.344931 1.222636 1.105728 0.995928 0.894246 0.790705 0.666394 0.523941 0.365671 0.195109 0.015606 -0.169725 -0.357724 -0.544986 -0.727861 -0.903585 -1.070368 -1.226864 -1.372026 -1.505055 -1.625365 -1.732582 -1.826543 -1.907297 -1.975112 -2.030478 -2.074103 -2.106920 -2.130075 -2.144914 -2.152966 -2.155836 -2.154640 -2.149953 -2.142116 +1.525176 1.389818 1.257032 1.130259 1.011475 0.901713 0.790737 0.656712 0.501917 0.329434 0.143594 -0.051741 -0.253016 -0.456636 -0.658718 -0.855321 -1.043728 -1.222114 -1.389084 -1.543550 -1.684675 -1.811862 -1.924743 -2.023186 -2.107295 -2.177416 -2.234138 -2.278294 -2.310959 -2.333441 -2.347264 -2.354147 -2.355801 -2.353275 -2.347110 -2.337621 +1.576091 1.434083 1.290759 1.153917 1.025975 0.907968 0.789164 0.644957 0.477240 0.289934 0.088194 -0.123583 -0.341376 -0.561121 -0.778437 -0.989180 -1.190668 -1.381024 -1.558795 -1.722840 -1.872286 -2.006525 -2.125198 -2.228212 -2.315729 -2.388179 -2.446258 -2.490931 -2.523425 -2.545218 -2.558024 -2.563754 -2.564189 -2.560306 -2.552619 -2.541411 +1.619386 1.477421 1.323881 1.176784 1.039511 0.913087 0.786080 0.631211 0.449991 0.247242 0.028971 -0.199866 -0.434753 -0.671127 -0.904104 -1.129421 -1.344401 -1.547104 -1.736007 -1.909909 -2.067905 -2.209372 -2.333972 -2.441648 -2.532629 -2.607434 -2.666876 -2.712055 -2.744361 -2.765452 -2.777239 -2.781831 -2.781036 -2.775765 -2.766503 -2.753507 +1.652707 1.518703 1.356434 1.198932 1.052154 0.917137 0.781560 0.615550 0.420232 0.201412 -0.034029 -0.280547 -0.533104 -0.786614 -1.035692 -1.276032 -1.504928 -1.720362 -1.920730 -2.104772 -2.271546 -2.420424 -2.551086 -2.663519 -2.758022 -2.835212 -2.896022 -2.941699 -2.973802 -2.994180 -3.004949 -3.008412 -3.006369 -2.999674 -2.988782 -2.973920 +1.676548 1.555748 1.388396 1.220422 1.063964 0.920174 0.775668 0.598036 0.388014 0.152485 -0.100769 -0.365591 -0.636398 -0.907545 -1.173186 -1.429010 -1.672256 -1.900808 -2.112976 -2.307439 -2.483223 -2.639696 -2.776559 -2.893846 -2.991934 -3.071540 -3.133725 -3.179893 -3.211780 -3.231435 -3.241187 -3.243526 -3.240212 -3.232052 -3.219469 -3.202660 +1.694200 1.586793 1.419603 1.241302 1.074992 0.922243 0.768461 0.578719 0.353374 0.100493 -0.171219 -0.454970 -0.744605 -1.033891 -1.316576 -1.588357 -1.846391 -2.088450 -2.312754 -2.517922 -2.702952 -2.867206 -3.010409 -3.132651 -3.234386 -3.316440 -3.380010 -3.426664 -3.458323 -3.477245 -3.485985 -3.487195 -3.482585 -3.472915 -3.458574 -3.439733 +1.707980 1.611070 1.449551 1.261610 1.085283 0.923387 0.759987 0.557635 0.316341 0.045462 -0.245357 -0.548663 -0.857703 -1.165632 -1.465857 -1.754078 -2.027339 -2.283295 -2.520073 -2.736234 -2.930745 -3.102968 -3.252655 -3.379952 -3.485399 -3.569934 -3.634900 -3.682034 -3.713454 -3.731636 -3.739365 -3.739440 -3.733504 -3.722276 -3.706107 -3.685146 + + +# Torque coefficient + +0.037472 0.039863 0.042189 0.044441 0.046608 0.048682 0.050650 0.052503 0.054227 0.055813 0.057249 0.058524 0.059627 0.060548 0.061279 0.061812 0.062139 0.062254 0.062150 0.061823 0.061266 0.060477 0.059449 0.058181 0.056670 0.054913 0.052909 0.050657 0.048158 0.045411 0.042417 0.039178 0.035699 0.031992 0.028077 0.023982 +0.052381 0.054844 0.057148 0.059281 0.061230 0.062981 0.064525 0.065851 0.066949 0.067807 0.068416 0.068770 0.068863 0.068690 0.068248 0.067531 0.066537 0.065262 0.063704 0.061862 0.059734 0.057319 0.054617 0.051628 0.048352 0.044790 0.040942 0.036815 0.032418 0.027777 0.022923 0.017903 0.012773 0.007588 0.002402 -0.002739 +0.065213 0.067380 0.069292 0.070938 0.072309 0.073394 0.074184 0.074675 0.074865 0.074754 0.074332 0.073592 0.072533 0.071152 0.069448 0.067418 0.065062 0.062378 0.059366 0.056026 0.052356 0.048355 0.044023 0.039362 0.034379 0.029092 0.023536 0.017757 0.011818 0.005790 -0.000260 -0.006271 -0.012193 -0.017979 -0.023591 -0.028995 +0.074866 0.076494 0.077787 0.078743 0.079363 0.079649 0.079608 0.079225 0.078492 0.077414 0.075987 0.074198 0.072043 0.069521 0.066631 0.063369 0.059733 0.055720 0.051328 0.046554 0.041395 0.035855 0.029947 0.023703 0.017171 0.010419 0.003529 -0.003415 -0.010337 -0.017172 -0.023865 -0.030366 -0.036636 -0.042642 -0.048360 -0.053772 +0.080732 0.081793 0.082482 0.082797 0.082742 0.082317 0.081529 0.080389 0.078871 0.076967 0.074671 0.071964 0.068840 0.065294 0.061321 0.056916 0.052072 0.046783 0.041045 0.034858 0.028237 0.021217 0.013854 0.006227 -0.001568 -0.009429 -0.017269 -0.025012 -0.032594 -0.039958 -0.047058 -0.053856 -0.060324 -0.066445 -0.072210 -0.077620 +0.082751 0.083404 0.083688 0.083592 0.083098 0.082198 0.080892 0.079186 0.077073 0.074516 0.071504 0.068010 0.064024 0.059540 0.054546 0.049036 0.043000 0.036434 0.029344 0.021761 0.013739 0.005354 -0.003286 -0.012064 -0.020870 -0.029611 -0.038208 -0.046591 -0.054702 -0.062494 -0.069930 -0.076986 -0.083647 -0.089911 -0.095788 -0.101297 +0.081168 0.081796 0.082022 0.081832 0.081214 0.080129 0.078557 0.076500 0.073965 0.070902 0.067286 0.063089 0.058300 0.052909 0.046905 0.040278 0.033024 0.025159 0.016723 0.007784 -0.001559 -0.011179 -0.020938 -0.030718 -0.040416 -0.049944 -0.059225 -0.068197 -0.076807 -0.085019 -0.092807 -0.100161 -0.107080 -0.113582 -0.119693 -0.125454 +0.076330 0.077479 0.078131 0.078254 0.077822 0.076824 0.075212 0.072981 0.070153 0.066679 0.062522 0.057657 0.052075 0.045766 0.038719 0.030934 0.022428 0.013249 0.003478 -0.006773 -0.017357 -0.028117 -0.038919 -0.049646 -0.060199 -0.070490 -0.080449 -0.090017 -0.099151 -0.107825 -0.116026 -0.123758 -0.131040 -0.137904 -0.144397 -0.150580 +0.069367 0.071150 0.072617 0.073449 0.073520 0.072821 0.071343 0.069062 0.066023 0.062184 0.057504 0.051967 0.045567 0.038298 0.030157 0.021164 0.011372 0.000867 -0.010230 -0.021756 -0.033530 -0.045398 -0.057226 -0.068897 -0.080312 -0.091386 -0.102052 -0.112258 -0.121972 -0.131177 -0.139877 -0.148089 -0.155851 -0.163214 -0.170244 -0.177019 +0.062375 0.064394 0.066274 0.067906 0.068722 0.068500 0.067267 0.065011 0.061799 0.057605 0.052390 0.046148 0.038883 0.030593 0.021299 0.011051 -0.000061 -0.011912 -0.024329 -0.037109 -0.050069 -0.063054 -0.075926 -0.088567 -0.100879 -0.112777 -0.124201 -0.135107 -0.145472 -0.155294 -0.164589 -0.173392 -0.181759 -0.189758 -0.197475 -0.205004 +0.055786 0.058095 0.060202 0.062154 0.063724 0.064100 0.063176 0.060982 0.057604 0.053038 0.047252 0.040257 0.032063 0.022689 0.012183 0.000631 -0.011839 -0.025056 -0.038797 -0.052844 -0.067015 -0.081147 -0.095101 -0.108757 -0.122015 -0.134795 -0.147041 -0.158719 -0.169817 -0.180346 -0.190337 -0.199844 -0.208937 -0.217707 -0.226256 -0.234694 +0.049556 0.052224 0.054612 0.056772 0.058740 0.059758 0.059179 0.057054 0.053496 0.048522 0.042117 0.034307 0.025119 0.014596 0.002819 -0.010088 -0.023957 -0.038562 -0.053649 -0.068999 -0.084421 -0.099747 -0.114835 -0.129559 -0.143823 -0.157550 -0.170690 -0.183219 -0.195135 -0.206463 -0.217252 -0.227571 -0.237513 -0.247185 -0.256708 -0.266195 +0.043622 0.046710 0.049429 0.051833 0.053998 0.055556 0.055329 0.053259 0.049491 0.044065 0.036985 0.028295 0.018045 0.006309 -0.006798 -0.021114 -0.036421 -0.052446 -0.068920 -0.085619 -0.102343 -0.118920 -0.135198 -0.151054 -0.166390 -0.181134 -0.195243 -0.208702 -0.221522 -0.233743 -0.245430 -0.256672 -0.267580 -0.278282 -0.288912 -0.299578 +0.037935 0.041491 0.044584 0.047266 0.049622 0.051537 0.051646 0.049606 0.045590 0.039659 0.031843 0.022208 0.010830 -0.002183 -0.016681 -0.032459 -0.049246 -0.066732 -0.084645 -0.102748 -0.120835 -0.138722 -0.156255 -0.173309 -0.189786 -0.205620 -0.220774 -0.235243 -0.249053 -0.262259 -0.274945 -0.287219 -0.299210 -0.311066 -0.322928 -0.334897 +0.032456 0.036519 0.040022 0.043010 0.045573 0.047718 0.048132 0.046087 0.041780 0.035289 0.026675 0.016029 0.003459 -0.010897 -0.026846 -0.044138 -0.062450 -0.081451 -0.100860 -0.120429 -0.139940 -0.159203 -0.178059 -0.196379 -0.214068 -0.231064 -0.247340 -0.262901 -0.277787 -0.292072 -0.305855 -0.319266 -0.332455 -0.345586 -0.358796 -0.372188 +0.027151 0.031757 0.035697 0.039014 0.041799 0.044109 0.044777 0.042689 0.038042 0.030935 0.021462 0.009742 -0.004087 -0.019848 -0.037309 -0.056167 -0.076055 -0.096630 -0.117598 -0.138697 -0.159698 -0.180404 -0.200651 -0.220307 -0.239280 -0.257514 -0.274988 -0.291722 -0.307771 -0.323225 -0.338205 -0.352859 -0.367357 -0.381875 -0.396548 -0.411479 +0.021993 0.027170 0.031573 0.035239 0.038257 0.040706 0.041565 0.039392 0.034359 0.026580 0.016186 0.003328 -0.011823 -0.029052 -0.048084 -0.068562 -0.090085 -0.112296 -0.134887 -0.157583 -0.180143 -0.202361 -0.224067 -0.245131 -0.265460 -0.285004 -0.303755 -0.321743 -0.339041 -0.355756 -0.372029 -0.388028 -0.403945 -0.419960 -0.436207 -0.452787 +0.016965 0.022733 0.027619 0.031649 0.034911 0.037492 0.038479 0.036181 0.030710 0.022204 0.010830 -0.003227 -0.019763 -0.038523 -0.059185 -0.081340 -0.104557 -0.128470 -0.152752 -0.177113 -0.201301 -0.225100 -0.248337 -0.270879 -0.292637 -0.313567 -0.333672 -0.352996 -0.371627 -0.389693 -0.407355 -0.424802 -0.442242 -0.459860 -0.477787 -0.496128 +0.012064 0.018424 0.023812 0.028219 0.031730 0.034437 0.035502 0.033036 0.027080 0.017791 0.005379 -0.009938 -0.027920 -0.048274 -0.070626 -0.094514 -0.119492 -0.145173 -0.171214 -0.197310 -0.223196 -0.248647 -0.273485 -0.297577 -0.320836 -0.343227 -0.364762 -0.385503 -0.405553 -0.425060 -0.444205 -0.463198 -0.482266 -0.501590 -0.521302 -0.541510 +0.007324 0.014229 0.020129 0.024924 0.028690 0.031518 0.032617 0.029942 0.023452 0.013327 -0.000179 -0.016816 -0.036308 -0.058317 -0.082416 -0.108101 -0.134905 -0.162422 -0.190292 -0.218192 -0.245847 -0.273021 -0.299531 -0.325244 -0.350078 -0.374004 -0.397048 -0.419285 -0.440838 -0.461874 -0.482595 -0.503234 -0.524029 -0.545160 -0.566761 -0.588942 +0.002913 0.010141 0.016554 0.021744 0.025767 0.028712 0.029808 0.026883 0.019811 0.008799 -0.005858 -0.023874 -0.044936 -0.068661 -0.094568 -0.122112 -0.150808 -0.180232 -0.210000 -0.239777 -0.269270 -0.298238 -0.326492 -0.353898 -0.380379 -0.405915 -0.430545 -0.454359 -0.477498 -0.500151 -0.522541 -0.544921 -0.567541 -0.590579 -0.614170 -0.638429 +-0.000889 0.006170 0.013071 0.018663 0.022945 0.025999 0.027061 0.023846 0.016144 0.004194 -0.011667 -0.031121 -0.053813 -0.079315 -0.107090 -0.136558 -0.167215 -0.198614 -0.230353 -0.262077 -0.293480 -0.324313 -0.354382 -0.383553 -0.411754 -0.438976 -0.465267 -0.490737 -0.515547 -0.539903 -0.564052 -0.588270 -0.612810 -0.637852 -0.663535 -0.689973 +-0.003916 0.002388 0.009671 0.015666 0.020207 0.023364 0.024362 0.020817 0.012440 -0.000496 -0.017616 -0.038565 -0.062948 -0.090288 -0.119991 -0.151449 -0.184137 -0.217582 -0.251362 -0.285104 -0.318489 -0.351258 -0.383212 -0.414220 -0.444215 -0.473196 -0.501227 -0.528432 -0.554993 -0.581139 -0.607138 -0.633286 -0.659843 -0.686986 -0.714858 -0.743578 +-0.006209 -0.001053 0.006345 0.012740 0.017540 0.020791 0.021699 0.017786 0.008689 -0.005281 -0.023713 -0.046213 -0.072348 -0.101586 -0.133279 -0.166794 -0.201581 -0.237144 -0.273037 -0.308868 -0.344306 -0.379082 -0.412994 -0.445912 -0.477773 -0.508588 -0.538433 -0.567453 -0.595847 -0.623867 -0.651805 -0.679977 -0.708643 -0.737983 -0.768143 -0.799245 +-0.008023 -0.004030 0.003098 0.009875 0.014931 0.018268 0.019060 0.014742 0.004884 -0.010169 -0.029964 -0.054073 -0.082018 -0.113214 -0.146961 -0.182601 -0.219558 -0.257309 -0.295386 -0.333378 -0.370940 -0.407795 -0.443737 -0.478635 -0.512436 -0.545158 -0.576895 -0.607806 -0.638115 -0.668095 -0.698061 -0.728347 -0.759214 -0.790846 -0.823390 -0.856975 +-0.009537 -0.006489 -0.000041 0.007061 0.012370 0.015784 0.016436 0.011677 0.001015 -0.015166 -0.036375 -0.062150 -0.091964 -0.125178 -0.161043 -0.198876 -0.238074 -0.278084 -0.318416 -0.358641 -0.398399 -0.437404 -0.475447 -0.512399 -0.548211 -0.582914 -0.616617 -0.649499 -0.681803 -0.713827 -0.745909 -0.778399 -0.811560 -0.845577 -0.880603 -0.916770 + diff --git a/Test_Cases/MHK_RM1/MHK_RM1_DISCON.IN b/Test_Cases/MHK_RM1/MHK_RM1_DISCON.IN new file mode 100644 index 00000000..1216f1c0 --- /dev/null +++ b/Test_Cases/MHK_RM1/MHK_RM1_DISCON.IN @@ -0,0 +1,185 @@ +! Controller parameter input file for the MHK_RM1_Floating wind turbine +! - File written using ROSCO version 2.8.0 controller tuning logic on 08/23/23 + +!------- SIMULATION CONTROL ------------------------------------------------------------ +2 ! LoggingLevel - {0: write no debug files, 1: write standard output .dbg-file, 2: LoggingLevel 1 + ROSCO LocalVars (.dbg2) 3: LoggingLevel 2 + complete avrSWAP-array (.dbg3)} +0 ! DT_Out - {Time step to output .dbg* files, or 0 to match sampling period of OpenFAST} +0 ! Echo - (0 - no Echo, 1 - Echo input data to .echo) + +!------- 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 ! IPC_ControlMode - Turn Individual Pitch Control (IPC) for fatigue load reductions (pitch contribution) {0: off, 1: 1P reductions, 2: 1P+2P reductions} +3 ! VS_ControlMode - Generator torque control mode in above rated conditions (0- no torque control, 1- k*omega^2 with PI transitions, 2- WSE TSR Tracking, 3- Power-based TSR Tracking)} +1 ! VS_ConstPower - Do constant power torque control, where above rated torque varies, 0 for constant torque} +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} +0 ! WE_Mode - Wind speed estimator mode {0: One-second low pass filtered hub height wind speed, 1: Immersion and Invariance Estimator, 2: Extended Kalman Filter} +0 ! PS_Mode - Pitch saturation mode {0: no pitch saturation, 1: implement pitch saturation} +0 ! SD_Mode - Shutdown mode {0: no shutdown procedure, 1: pitch to max pitch at shutdown} +1 ! Fl_Mode - Floating specific feedback mode {0: no nacelle velocity feedback, 1: feed back translational velocity, 2: feed back rotational veloicty} +0 ! TD_Mode - Tower damper mode {0: no tower damper, 1: feed back translational nacelle accelleration to pitch angle} +0 ! Flp_Mode - Flap control mode {0: no flap control, 1: steady state flap angle, 2: Proportional flap control, 2: Cyclic (1P) flap control} +0 ! OL_Mode - Open loop control mode {0: no open loop control, 1: open loop control vs. time, 2: rotor position control} +0 ! PA_Mode - Pitch actuator mode {0 - not used, 1 - first order filter, 2 - second order filter} +0 ! PF_Mode - Pitch fault mode {0 - not used, 1 - constant offset on one or more blades} +0 ! AWC_Mode - Active wake control {0 - not used, 1 - complex number method, 2 - Coleman transform method} +0 ! Ext_Mode - External control mode {0 - not used, 1 - call external dynamic library} +0 ! ZMQ_Mode - Fuse ZeroMQ interface {0: unused, 1: Yaw Control} +0 ! CC_Mode - Cable control mode [0- unused, 1- User defined, 2- Open loop control] +0 ! StC_Mode - Structural control mode [0- unused, 1- User defined, 2- Open loop control] + +!------- FILTERS ---------------------------------------------------------- +15.07080 ! F_LPFCornerFreq - Corner frequency (-3dB point) in the low-pass filters, [rad/s] +0.00000 ! F_LPFDamping - Damping coefficient {used only when F_FilterType = 2} [-] +2 ! F_NumNotchFilts - Number of notch filters placed on sensors +1.0000 2.4200 ! F_NotchFreqs - Natural frequency of the notch filters. Array with length F_NumNotchFilts +0.0010 0.0010 ! F_NotchBetaNum - Damping value of numerator (determines the width of notch). Array with length F_NumNotchFilts, [-] +0.1000 0.1000 ! F_NotchBetaDen - Damping value of denominator (determines the depth of notch). Array with length F_NumNotchFilts, [-] +2 ! F_GenSpdNotch_N - Number of notch filters on generator speed +1 2 ! F_GenSpdNotch_Ind - Indices of notch filters on generator speed +2 ! F_TwrTopNotch_N - Number of notch filters on tower top acceleration signal +1 2 ! F_TwrTopNotch_Ind - Indices of notch filters on tower top acceleration signal +0.62830 ! F_SSCornerFreq - Corner frequency (-3dB point) in the first order low pass filter for the setpoint smoother, [rad/s]. +0.20944 ! F_WECornerFreq - Corner frequency (-3dB point) in the first order low pass filter for the wind speed estimate [rad/s]. +0.17952 ! F_YawErr - Low pass filter corner frequency for yaw controller [rad/s]. +0.661300 1.000000 ! F_FlCornerFreq - Natural frequency and damping in the second order low pass filter of the tower-top fore-aft motion for floating feedback control [rad/s, -]. +1.50000 ! F_FlHighPassFreq - Natural frequency of first-order high-pass filter for nacelle fore-aft motion [rad/s]. +0.0000 1.0000 ! F_FlpCornerFreq - Corner frequency and damping in the second order low pass filter of the blade root bending moment for flap control + +!------- BLADE PITCH CONTROL ---------------------------------------------- +30 ! PC_GS_n - Amount of gain-scheduling table entries +0.030335 0.049075 0.063610 0.076093 0.087460 0.097196 0.106672 0.115225 0.123634 0.131302 0.139019 0.146056 0.153083 0.159873 0.166338 0.172854 0.178999 0.185046 0.191143 0.196863 0.202559 0.208301 0.213742 0.219137 0.224575 0.229836 0.234972 0.240145 0.245291 0.250200 ! PC_GS_angles - Gain-schedule table: pitch angles [rad]. +-0.010178 -0.008780 -0.007625 -0.006655 -0.005829 -0.005116 -0.004495 -0.003950 -0.003467 -0.003036 -0.002650 -0.002301 -0.001984 -0.001696 -0.001432 -0.001190 -0.000966 -0.000760 -0.000568 -0.000390 -0.000225 -0.000069 0.000076 0.000212 0.000340 0.000461 0.000575 0.000682 0.000784 0.000881 ! PC_GS_KP - Gain-schedule table: pitch controller kp gains [s]. +-0.005272 -0.004770 -0.004355 -0.004007 -0.003710 -0.003454 -0.003232 -0.003036 -0.002862 -0.002708 -0.002569 -0.002443 -0.002330 -0.002226 -0.002132 -0.002045 -0.001964 -0.001890 -0.001822 -0.001758 -0.001698 -0.001642 -0.001590 -0.001541 -0.001495 -0.001452 -0.001411 -0.001372 -0.001336 -0.001301 ! PC_GS_KI - Gain-schedule table: pitch controller ki gains [-]. +0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 ! PC_GS_KD - Gain-schedule table: pitch controller kd gains +0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 ! PC_GS_TF - Gain-schedule table: pitch controller tf gains (derivative filter) +1.570000000000 ! PC_MaxPit - Maximum physical pitch limit, [rad]. +0.000690000000 ! PC_MinPit - Minimum physical pitch limit, [rad]. +0.174500000000 ! PC_MaxRat - Maximum pitch rate (in absolute value) in pitch controller, [rad/s]. +-0.17450000000 ! PC_MinRat - Minimum pitch rate (in absolute value) in pitch controller, [rad/s]. +63.81200000000 ! PC_RefSpd - Desired (reference) HSS speed for pitch controller, [rad/s]. +0.000690000000 ! PC_FinePit - Record 5: Below-rated pitch angle set-point, [rad] +0.017450000000 ! PC_Switch - Angle above lowest minimum pitch angle for switch, [rad] + +!------- INDIVIDUAL PITCH CONTROL ----------------------------------------- +1.600000 2.000000 ! IPC_Vramp - Start and end wind speeds for cut-in ramp function. First entry: IPC inactive, second entry: IPC fully active. [m/s] +2 ! IPC_SatMode - IPC Saturation method (0 - no saturation (except by PC_MinPit), 1 - saturate by PS_BldPitchMin, 2 - saturate sotfly (full IPC cycle) by PC_MinPit, 3 - saturate softly by PS_BldPitchMin) +0.3 ! IPC_IntSat - Integrator saturation (maximum signal amplitude contribution to pitch from IPC), [rad] +0.000e+00 0.000e+00 ! IPC_KP - Proportional gain for the individual pitch controller: first parameter for 1P reductions, second for 2P reductions, [-] +0.000e+00 0.000e+00 ! IPC_KI - Integral gain for the individual pitch controller: first parameter for 1P reductions, second for 2P reductions, [-] +0.000000 0.000000 ! 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 ------------------------------------------------ +94.40000000000 ! VS_GenEff - Generator efficiency mechanical power -> electrical power, [should match the efficiency defined in the generator properties!], [%] +8300.335630000 ! VS_ArSatTq - Above rated generator torque PI control saturation, [Nm] +1500000.000000 ! VS_MaxRat - Maximum torque rate (in absolute value) in torque controller, [Nm/s]. +12450.50344000 ! VS_MaxTq - Maximum generator torque in Region 3 (HSS side), [Nm]. +0.000000000000 ! VS_MinTq - Minimum generator torque (HSS side), [Nm]. +19.00309000000 ! VS_MinOMSpd - Minimum generator speed [rad/s] +1.142870000000 ! VS_Rgn2K - Generator torque constant in Region 2 (HSS side). Only used in VS_ControlMode = 1,3 +500000.0000000 ! VS_RtPwr - Wind turbine rated power [W] +8300.335630000 ! VS_RtTq - Rated torque, [Nm]. +63.81200000000 ! VS_RefSpd - Rated generator speed [rad/s] +1 ! VS_n - Number of generator PI torque controller gains +-63.8796200000 ! VS_KP - Proportional gain for generator PI torque controller [-]. (Only used in the transitional 2.5 region if VS_ControlMode =/ 2) +-84.4329000000 ! VS_KI - Integral gain for generator PI torque controller [s]. (Only used in the transitional 2.5 region if VS_ControlMode =/ 2) +7.17 ! VS_TSRopt - Power-maximizing region 2 tip-speed-ratio. Only used in VS_ControlMode = 2. +0.314000000000 ! VS_PwrFiltF - Low pass filter on power used to determine generator speed set point. Only used in VS_ControlMode = 3. + +!------- SETPOINT SMOOTHER --------------------------------------------- +1.00000 ! SS_VSGain - Variable speed torque controller setpoint smoother gain, [-]. +0.00100 ! SS_PCGain - Collective pitch controller setpoint smoother gain, [-]. + +!------- WIND SPEED ESTIMATOR --------------------------------------------- +10.000 ! WE_BladeRadius - Blade length (distance from hub center to blade tip), [m] +1 ! WE_CP_n - Amount of parameters in the Cp array +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] +53.0 ! WE_GearboxRatio - Gearbox ratio [>=1], [-] +484024.50000 ! WE_Jtot - Total drivetrain inertia, including blades, hub and casted generator inertia to LSS, [kg m^2] +1025.000 ! WE_RhoAir - Air density, [kg m^-3] +"MHK_RM1_Cp_Ct_Cq.txt" ! PerfFileName - File containing rotor performance tables (Cp,Ct,Cq) (absolute path or relative to this file) +36 26 ! PerfTableSize - Size of rotor performance tables, first number refers to number of blade pitch angles, second number referse to number of tip-speed ratios +60 ! WE_FOPoles_N - Number of first-order system poles used in EKF +0.5000 0.5517 0.6034 0.6552 0.7069 0.7586 0.8103 0.8621 0.9138 0.9655 1.0172 1.0690 1.1207 1.1724 1.2241 1.2759 1.3276 1.3793 1.4310 1.4828 1.5345 1.5862 1.6379 1.6897 1.7414 1.7931 1.8448 1.8966 1.9483 2.0000 2.0333 2.0667 2.1000 2.1333 2.1667 2.2000 2.2333 2.2667 2.3000 2.3333 2.3667 2.4000 2.4333 2.4667 2.5000 2.5333 2.5667 2.6000 2.6333 2.6667 2.7000 2.7333 2.7667 2.8000 2.8333 2.8667 2.9000 2.9333 2.9667 3.0000 ! WE_FOPoles_v - Wind speeds corresponding to first-order system poles [m/s] +-0.14364445 -0.15850422 -0.17336400 -0.18822377 -0.20308354 -0.21794331 -0.23280308 -0.24766285 -0.26252262 -0.27738239 -0.29224216 -0.30710193 -0.32196171 -0.33682148 -0.35168125 -0.36654102 -0.38140079 -0.39626056 -0.41112033 -0.42598010 -0.44083987 -0.45569965 -0.47055942 -0.48666545 -0.50602877 -0.52082936 -0.60274133 -0.60720589 -0.60927938 -0.55668516 0.17844923 0.15174296 0.10860051 0.05753679 0.00176535 -0.05812003 -0.11803585 -0.18146508 -0.24666701 -0.31440662 -0.38335107 -0.45418067 -0.52480063 -0.59662243 -0.67000720 -0.74481113 -0.82056059 -0.89753628 -0.97589183 -1.05446405 -1.13345094 -1.21374047 -1.29379323 -1.37507241 -1.45808464 -1.54093580 -1.62426617 -1.70957888 -1.79610923 -1.88140848 ! WE_FOPoles - First order system poles [1/s] + +!------- YAW CONTROL ------------------------------------------------------ +0.00000 ! Y_uSwitch - Wind speed to switch between Y_ErrThresh. If zero, only the second value of Y_ErrThresh is used [m/s] +4.000000 8.000000 ! Y_ErrThresh - Yaw error threshold/deadbands. Turbine begins to yaw when it passes this. If Y_uSwitch is zero, only the second value is used. [deg]. +0.00870 ! Y_Rate - Yaw rate [rad/s] +0.00000 ! Y_MErrSet - Integrator saturation (maximum signal amplitude contribution to pitch from yaw-by-IPC), [rad] +0.00000 ! Y_IPC_IntSat - Integrator saturation (maximum signal amplitude contribution to pitch from yaw-by-IPC), [rad] +0.00000 ! Y_IPC_KP - Yaw-by-IPC proportional controller gain Kp +0.00000 ! Y_IPC_KI - Yaw-by-IPC integral controller gain Ki + +!------- TOWER FORE-AFT DAMPING ------------------------------------------- +-1.00000 ! FA_KI - Integral gain for the fore-aft tower damper controller [rad s/m] +0.0 ! FA_HPFCornerFreq - 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] + +!------- MINIMUM PITCH SATURATION ------------------------------------------- +60 ! PS_BldPitchMin_N - Number of values in minimum blade pitch lookup table (should equal number of values in PS_WindSpeeds and PS_BldPitchMin) +0.5000 0.5517 0.6034 0.6552 0.7069 0.7586 0.8103 0.8621 0.9138 0.9655 1.0172 1.0690 1.1207 1.1724 1.2241 1.2759 1.3276 1.3793 1.4310 1.4828 1.5345 1.5862 1.6379 1.6897 1.7414 1.7931 1.8448 1.8966 1.9483 2.0000 2.0333 2.0667 2.1000 2.1333 2.1667 2.2000 2.2333 2.2667 2.3000 2.3333 2.3667 2.4000 2.4333 2.4667 2.5000 2.5333 2.5667 2.6000 2.6333 2.6667 2.7000 2.7333 2.7667 2.8000 2.8333 2.8667 2.9000 2.9333 2.9667 3.0000 ! PS_WindSpeeds - Wind speeds corresponding to minimum blade pitch angles [m/s] +0.00069304 0.00069304 0.00069304 0.00069304 0.00069304 0.00069304 0.00069304 0.00069304 0.00069304 0.00069304 0.00069304 0.00069304 0.00069304 0.00069304 0.00069304 0.00069304 0.00069304 0.00069304 0.00069304 0.00069304 0.00069304 0.00069304 0.00069304 0.00069304 0.00069304 0.00069304 0.00069304 0.00069304 0.00069304 0.00069304 0.00069304 0.00069304 0.00069304 0.00069304 0.00069304 0.00069304 0.00069304 0.00069304 0.00069304 0.00069304 0.00069304 0.00069304 0.00069304 0.00069304 0.00069304 0.00069304 0.00069304 0.00069304 0.00069304 0.00069304 0.00069304 0.00069304 0.00069304 0.00069304 0.00069304 0.00069304 0.00069304 0.00069304 0.00069304 0.00069304 ! PS_BldPitchMin - Minimum blade pitch angles [rad] + +!------- SHUTDOWN ----------------------------------------------------------- +0.436300000000 ! SD_MaxPit - Maximum blade pitch angle to initiate shutdown, [rad] +0.418880000000 ! SD_CornerFreq - Cutoff Frequency for first order low-pass filter for blade pitch angle, [rad/s] + +!------- Floating ----------------------------------------------------------- +1 ! Fl_n - Number of Fl_Kp gains in gain scheduling, optional with default of 1 +-0.3999 ! Fl_Kp - Nacelle velocity proportional feedback gain [s] +2.1000 ! Fl_U - Wind speeds for scheduling Fl_Kp, optional if Fl_Kp is single value [m/s] + +!------- FLAP ACTUATION ----------------------------------------------------- +0.000000000000 ! Flp_Angle - Initial or steady state flap angle [rad] +0.00000000e+00 ! Flp_Kp - Blade root bending moment proportional gain for flap control [s] +0.00000000e+00 ! Flp_Ki - Flap displacement integral gain for flap control [-] +0.174500000000 ! Flp_MaxPit - Maximum (and minimum) flap pitch angle [rad] + +!------- Open Loop Control ----------------------------------------------------- +"unused" ! OL_Filename - Input file with open loop timeseries (absolute path or relative to this file) +0 ! Ind_Breakpoint - The column in OL_Filename that contains the breakpoint (time if OL_Mode = 1) + 0 0 0 ! Ind_BldPitch - The columns in OL_Filename that contains the blade pitch (1,2,3) inputs in rad [array] +0 ! Ind_GenTq - The column in OL_Filename that contains the generator torque in Nm +0 ! Ind_YawRate - The column in OL_Filename that contains the yaw rate in rad/s +0 ! Ind_Azimuth - The column in OL_Filename that contains the desired azimuth position in rad (used if OL_Mode = 2) +0.0000 0.0000 0.0000 0.0000 ! RP_Gains - PID gains and Tf of derivative for rotor position control (used if OL_Mode = 2) +0 ! Ind_CableControl - The column(s) in OL_Filename that contains the cable control inputs in m [Used with CC_Mode = 2, must be the same size as CC_Group_N] +0 ! Ind_StructControl - The column(s) in OL_Filename that contains the structural control inputs [Used with StC_Mode = 2, must be the same size as StC_Group_N] + +!------- Pitch Actuator Model ----------------------------------------------------- +3.140000000000 ! PA_CornerFreq - Pitch actuator bandwidth/cut-off frequency [rad/s] +0.707000000000 ! PA_Damping - Pitch actuator damping ratio [-, unused if PA_Mode = 1] + +!------- Pitch Actuator Faults ----------------------------------------------------- +0.00000000 0.00000000 0.00000000 ! PF_Offsets - Constant blade pitch offsets for blades 1-3 [rad] + +!------- Active Wake Control ----------------------------------------------------- +1 ! AWC_NumModes - Number of user-defined AWC forcing modes +1 ! AWC_n - Azimuthal mode number(s) (i.e., the number and direction of the lobes of the wake structure) +1 ! AWC_harmonic - Harmonic(s) to apply in the AWC Inverse Coleman Transformation (only used when AWC_Mode = 2) +0.0500 ! AWC_freq - Frequency(s) of forcing mode(s) [Hz] +1.0000 ! AWC_amp - Pitch amplitude(s) of individual forcing mode(s) [deg] +0.0000 ! AWC_clockangle - Initial angle(s) of forcing mode(s) [deg] + +!------- External Controller Interface ----------------------------------------------------- +"unused" ! DLL_FileName - Name/location of the dynamic library in the Bladed-DLL format +"unused" ! DLL_InFile - Name of input file sent to the DLL (-) +"DISCON" ! DLL_ProcName - Name of procedure in DLL to be called (-) + +!------- ZeroMQ Interface --------------------------------------------------------- +"tcp://localhost:5555" ! ZMQ_CommAddress - Communication address for ZMQ server, (e.g. "tcp://localhost:5555") +2 ! ZMQ_UpdatePeriod - Call ZeroMQ every [x] seconds, [s] + +!------- Cable Control --------------------------------------------------------- +1 ! CC_Group_N - Number of cable control groups +0 ! CC_GroupIndex - First index for cable control group, should correspond to deltaL +20.000000 ! CC_ActTau - Time constant for line actuator [s] + +!------- Structural Controllers --------------------------------------------------------- +1 ! StC_Group_N - Number of cable control groups +0 ! StC_GroupIndex - First index for structural control group, options specified in ServoDyn summary output diff --git a/Test_Cases/MHK_RM1/MHK_RM1_ElastoDyn_Blade.dat b/Test_Cases/MHK_RM1/MHK_RM1_ElastoDyn_Blade.dat new file mode 100644 index 00000000..df6ab8c8 --- /dev/null +++ b/Test_Cases/MHK_RM1/MHK_RM1_ElastoDyn_Blade.dat @@ -0,0 +1,107 @@ +------- ELASTODYN V1.00.* INDIVIDUAL BLADE INPUT FILE -------------------------- +Floating MHK turbine structural blade input properties, based on the RM1 tidal current rotor +---------------------- BLADE PARAMETERS ---------------------------------------- + 75 NBlInpSt - Number of blade input stations (-) + 1 BldFlDmp(1) - Blade flap mode #1 structural damping in percent of critical (%) + 1 BldFlDmp(2) - Blade flap mode #2 structural damping in percent of critical (%) + 1 BldEdDmp(1) - Blade edge mode #1 structural damping in percent of critical (%) +---------------------- BLADE ADJUSTMENT FACTORS -------------------------------- + 1 FlStTunr(1) - Blade flapwise modal stiffness tuner, 1st mode (-) + 1 FlStTunr(2) - Blade flapwise modal stiffness tuner, 2nd mode (-) + 2.5 AdjBlMs - Factor to adjust blade mass density (-) + 1.0E-05 AdjFlSt - Factor to adjust blade flap stiffness (-) + 1.0E-05 AdjEdSt - Factor to adjust blade edge stiffness (-) +---------------------- DISTRIBUTED BLADE PROPERTIES ---------------------------- +BlFract PitchAxis StrcTwst BMassDen FlpStff EdgStff +(-) (-) (deg) (kg/m) (Nm^2) (Nm^2) +0.0000 0.5000 12.860 818.68 2.43E+14 2.52E+14 +0.0083 0.4953 12.860 833.60 2.47E+14 2.69E+14 +0.0167 0.4907 12.860 846.44 2.47E+14 2.84E+14 +0.0250 0.4860 12.860 858.68 2.46E+14 3.00E+14 +0.0333 0.4813 12.860 870.32 2.44E+14 3.15E+14 +0.0417 0.4701 12.860 900.64 2.50E+14 3.59E+14 +0.0500 0.4590 12.860 932.64 2.49E+14 4.03E+14 +0.0583 0.4478 12.860 681.32 1.70E+14 1.12E+14 +0.0667 0.4366 12.860 628.00 1.48E+14 1.11E+14 +0.0750 0.4233 12.860 575.28 1.30E+14 1.10E+14 +0.0833 0.4100 12.860 528.96 1.12E+14 1.07E+14 +0.0917 0.3967 12.860 458.92 8.82E+13 9.56E+13 +0.1000 0.3834 12.860 401.60 6.72E+13 8.55E+13 +0.1083 0.3722 12.860 411.16 6.45E+13 9.15E+13 +0.1167 0.3611 12.860 410.28 6.00E+13 9.53E+13 +0.1250 0.3499 12.860 415.36 5.62E+13 1.01E+14 +0.1333 0.3387 12.860 421.00 5.17E+13 1.06E+14 +0.1417 0.3340 12.860 421.28 4.94E+13 1.08E+14 +0.1500 0.3294 12.860 421.40 4.70E+13 1.10E+14 +0.1583 0.3247 12.860 424.96 4.45E+13 1.12E+14 +0.1667 0.3200 12.860 435.48 4.30E+13 1.16E+14 +0.1750 0.3200 12.530 428.40 4.09E+13 1.13E+14 +0.1833 0.3200 12.200 423.88 3.89E+13 1.10E+14 +0.1917 0.3200 11.870 435.68 3.84E+13 1.15E+14 +0.2000 0.3200 11.540 430.60 3.62E+13 1.12E+14 +0.2083 0.3200 11.265 434.52 3.57E+13 1.11E+14 +0.2167 0.3200 10.990 430.28 3.41E+13 1.09E+14 +0.2250 0.3200 10.715 426.04 3.26E+13 1.06E+14 +0.2333 0.3200 10.440 421.84 3.11E+13 1.03E+14 +0.2500 0.3200 9.970 415.00 2.91E+13 9.84E+13 +0.2667 0.3200 9.500 411.20 2.72E+13 9.54E+13 +0.2833 0.3200 9.105 395.88 2.54E+13 8.96E+13 +0.3000 0.3200 8.710 390.40 2.43E+13 8.59E+13 +0.3167 0.3200 8.365 377.84 2.26E+13 8.06E+13 +0.3333 0.3200 8.020 362.44 2.15E+13 7.34E+13 +0.3500 0.3200 7.725 347.48 2.00E+13 6.87E+13 +0.3667 0.3200 7.430 335.60 1.85E+13 6.42E+13 +0.3833 0.3200 7.170 330.64 1.77E+13 6.14E+13 +0.4000 0.3200 6.910 318.96 1.63E+13 5.72E+13 +0.4167 0.3200 6.680 302.84 1.50E+13 5.33E+13 +0.4333 0.3200 6.450 298.24 1.43E+13 5.09E+13 +0.4500 0.3200 6.245 287.12 1.32E+13 4.73E+13 +0.4667 0.3200 6.040 267.24 1.19E+13 4.12E+13 +0.4833 0.3200 5.860 256.68 1.09E+13 3.81E+13 +0.5000 0.3200 5.680 249.96 1.04E+13 3.62E+13 +0.5167 0.3200 5.515 239.68 9.42E+12 3.33E+13 +0.5333 0.3200 5.350 227.76 8.54E+12 3.06E+13 +0.5500 0.3200 5.200 215.64 7.73E+12 2.81E+13 +0.5667 0.3200 5.050 206.16 6.97E+12 2.58E+13 +0.5833 0.3200 4.910 188.80 6.17E+12 2.17E+13 +0.6000 0.3200 4.770 179.80 5.51E+12 1.97E+13 +0.6167 0.3200 4.640 176.28 5.19E+12 1.85E+13 +0.6333 0.3200 4.510 165.32 4.61E+12 1.68E+13 +0.6500 0.3200 4.385 156.80 4.07E+12 1.51E+13 +0.6667 0.3200 4.260 144.88 3.57E+12 1.36E+13 +0.6833 0.3200 4.145 136.80 3.11E+12 1.21E+13 +0.7000 0.3200 4.030 128.92 2.69E+12 1.08E+13 +0.7167 0.3200 3.915 119.36 2.31E+12 9.55E+12 +0.7333 0.3200 3.800 111.96 1.96E+12 8.42E+12 +0.7500 0.3200 3.685 103.00 1.65E+12 7.39E+12 +0.7667 0.3200 3.570 94.72 1.37E+12 6.45E+12 +0.7833 0.3200 3.460 87.96 1.12E+12 5.57E+12 +0.8000 0.3200 3.350 79.76 8.91E+11 4.77E+12 +0.8167 0.3200 3.240 73.52 6.93E+11 4.05E+12 +0.8333 0.3200 3.130 71.44 6.36E+11 3.72E+12 +0.8500 0.3200 3.015 64.00 4.76E+11 3.11E+12 +0.8667 0.3200 2.900 57.24 3.38E+11 2.56E+12 +0.8833 0.3200 2.785 50.36 2.19E+11 2.04E+12 +0.9000 0.3200 2.670 48.68 1.98E+11 1.84E+12 +0.9167 0.3200 2.550 47.00 1.78E+11 1.66E+12 +0.9333 0.3200 2.430 45.32 1.59E+11 1.49E+12 +0.9500 0.3200 2.305 46.76 1.98E+11 1.51E+12 +0.9667 0.3200 2.180 44.04 1.76E+11 1.34E+12 +0.9833 0.3200 2.060 42.28 1.56E+11 1.19E+12 +1.0000 0.3200 2.060 42.28 1.56E+11 1.19E+12 +---------------------- BLADE MODE SHAPES --------------------------------------- + 1.88070 BldFl1Sh(2) - Flap mode 1, coeff of x^2 +-1.44580 BldFl1Sh(3) - , coeff of x^3 + 0.71967 BldFl1Sh(4) - , coeff of x^4 +-0.03633 BldFl1Sh(5) - , coeff of x^5 +-0.11822 BldFl1Sh(6) - , coeff of x^6 +-5.52180 BldFl2Sh(2) - Flap mode 2, coeff of x^2 + 7.45710 BldFl2Sh(3) - , coeff of x^3 + 2.84170 BldFl2Sh(4) - , coeff of x^4 +-3.97820 BldFl2Sh(5) - , coeff of x^5 + 0.20116 BldFl2Sh(6) - , coeff of x^6 + 2.48090 BldEdgSh(2) - Edge mode 1, coeff of x^2 +-4.17160 BldEdgSh(3) - , coeff of x^3 + 5.03260 BldEdgSh(4) - , coeff of x^4 +-2.86170 BldEdgSh(5) - , coeff of x^5 + 0.51983 BldEdgSh(6) - , coeff of x^6 \ No newline at end of file diff --git a/Test_Cases/MHK_RM1/MHK_RM1_ElastoDyn_Tower.dat b/Test_Cases/MHK_RM1/MHK_RM1_ElastoDyn_Tower.dat new file mode 100644 index 00000000..3c04a12f --- /dev/null +++ b/Test_Cases/MHK_RM1/MHK_RM1_ElastoDyn_Tower.dat @@ -0,0 +1,52 @@ +------- ELASTODYN V1.00.* TOWER INPUT FILE ------------------------------------- +Floating MHK turbine structural tower input properties, based on the RM1 tidal current rotor +---------------------- TOWER PARAMETERS ---------------------------------------- + 11 NTwInpSt - Number of input stations to specify tower geometry + 1 TwrFADmp(1) - Tower 1st fore-aft mode structural damping ratio (%) + 1 TwrFADmp(2) - Tower 2nd fore-aft mode structural damping ratio (%) + 1 TwrSSDmp(1) - Tower 1st side-to-side mode structural damping ratio (%) + 1 TwrSSDmp(2) - Tower 2nd side-to-side mode structural damping ratio (%) +---------------------- TOWER ADJUSTMUNT FACTORS -------------------------------- + 1 FAStTunr(1) - Tower fore-aft modal stiffness tuner, 1st mode (-) + 1 FAStTunr(2) - Tower fore-aft modal stiffness tuner, 2nd mode (-) + 1 SSStTunr(1) - Tower side-to-side stiffness tuner, 1st mode (-) + 1 SSStTunr(2) - Tower side-to-side stiffness tuner, 2nd mode (-) + 1 AdjTwMa - Factor to adjust tower mass density (-) + 1.0E-03 AdjFASt - Factor to adjust tower fore-aft stiffness (-) + 1.0E-03 AdjSSSt - Factor to adjust tower side-to-side stiffness (-) +---------------------- DISTRIBUTED TOWER PROPERTIES ---------------------------- +HtFract TMassDen TwFAStif TwSSStif +(-) (kg/m) (Nm^2) (Nm^2) +0.0000000E+00 5076.39 1.27E+11 1.27E+11 +1.0000000E-01 5076.39 1.27E+11 1.27E+11 +2.0000000E-01 5076.39 1.27E+11 1.27E+11 +3.0000000E-01 5076.39 1.27E+11 1.27E+11 +4.0000000E-01 5076.39 1.27E+11 1.27E+11 +5.0000000E-01 5076.39 1.27E+11 1.27E+11 +6.0000000E-01 5076.39 1.27E+11 1.27E+11 +7.0000000E-01 5076.39 1.27E+11 1.27E+11 +8.0000000E-01 5076.39 1.27E+11 1.27E+11 +9.0000000E-01 5076.39 1.27E+11 1.27E+11 +1.0000000E+00 5076.39 1.27E+11 1.27E+11 +---------------------- TOWER FORE-AFT MODE SHAPES ------------------------------ + -5.6786 TwFAM1Sh(2) - Mode 1, coefficient of x^2 term + 41.5614 TwFAM1Sh(3) - , coefficient of x^3 term + -93.3287 TwFAM1Sh(4) - , coefficient of x^4 term + 89.2568 TwFAM1Sh(5) - , coefficient of x^5 term + -30.8109 TwFAM1Sh(6) - , coefficient of x^6 term + 0.6979 TwFAM2Sh(2) - Mode 2, coefficient of x^2 term + 1.2146 TwFAM2Sh(3) - , coefficient of x^3 term + -1.6999 TwFAM2Sh(4) - , coefficient of x^4 term + 0.8473 TwFAM2Sh(5) - , coefficient of x^5 term + -0.0599 TwFAM2Sh(6) - , coefficient of x^6 term +---------------------- TOWER SIDE-TO-SIDE MODE SHAPES -------------------------- + 0.5640 TwSSM1Sh(2) - Mode 1, coefficient of x^2 term + 4.7082 TwSSM1Sh(3) - , coefficient of x^3 term + -14.9130 TwSSM1Sh(4) - , coefficient of x^4 term + 18.2340 TwSSM1Sh(5) - , coefficient of x^5 term + -7.5932 TwSSM1Sh(6) - , coefficient of x^6 term + 0.9525 TwSSM2Sh(2) - Mode 2, coefficient of x^2 term + 0.4369 TwSSM2Sh(3) - , coefficient of x^3 term + -1.1374 TwSSM2Sh(4) - , coefficient of x^4 term + 1.1954 TwSSM2Sh(5) - , coefficient of x^5 term + -0.4474 TwSSM2Sh(6) - , coefficient of x^6 term \ No newline at end of file diff --git a/Test_Cases/MHK_RM1/MHK_RM1_Floating.1 b/Test_Cases/MHK_RM1/MHK_RM1_Floating.1 new file mode 100644 index 00000000..c32060dc --- /dev/null +++ b/Test_Cases/MHK_RM1/MHK_RM1_Floating.1 @@ -0,0 +1,4220 @@ + -1.000000E+00 1 1 1.999545E+03 + -1.000000E+00 1 5 -1.038155E+04 + -1.000000E+00 2 2 2.266626E+03 + -1.000000E+00 2 4 1.450345E+04 + -1.000000E+00 3 3 2.167146E+03 + -1.000000E+00 4 2 1.451960E+04 + -1.000000E+00 4 4 2.703220E+05 + -1.000000E+00 5 1 -1.039882E+04 + -1.000000E+00 5 5 8.266187E+05 + -1.000000E+00 6 6 9.046082E+05 + 0.000000E+00 1 1 1.411834E+03 + 0.000000E+00 1 5 -9.031812E+03 + 0.000000E+00 2 2 1.657916E+03 + 0.000000E+00 2 4 1.228014E+04 + 0.000000E+00 3 3 2.166489E+03 + 0.000000E+00 4 2 1.229162E+04 + 0.000000E+00 4 4 2.611510E+05 + 0.000000E+00 5 1 -9.043577E+03 + 0.000000E+00 5 5 8.192453E+05 + 0.000000E+00 6 6 6.521804E+05 + 1.000000E-01 1 1 1.647323E+03 6.332432E-04 + 1.000000E-01 1 5 -9.712987E+03 1.055422E-06 + 1.000000E-01 2 2 1.921107E+03 -6.797895E-06 + 1.000000E-01 2 4 1.298169E+04 -4.832497E-06 + 1.000000E-01 3 3 2.120432E+03 -1.464990E-06 + 1.000000E-01 4 2 1.312899E+04 2.916794E-05 + 1.000000E-01 4 4 2.638432E+05 2.756118E-05 + 1.000000E-01 5 1 -9.566795E+03 -3.792644E-03 + 1.000000E-01 5 5 8.247277E+05 -3.473593E-07 + 1.000000E-01 6 6 8.442138E+05 7.588721E+03 + 2.000000E-01 1 1 1.489483E+03 -5.117749E-03 + 2.000000E-01 1 5 -9.217624E+03 7.927747E-03 + 2.000000E-01 2 2 1.736418E+03 8.147049E-03 + 2.000000E-01 2 4 1.245268E+04 1.932775E-02 + 2.000000E-01 3 3 2.164448E+03 9.414506E-04 + 2.000000E-01 4 2 1.251272E+04 -4.435483E-02 + 2.000000E-01 4 4 2.615695E+05 -1.109551E-01 + 2.000000E-01 5 1 -9.202860E+03 1.644901E-04 + 2.000000E-01 5 5 8.194167E+05 -1.930356E-04 + 2.000000E-01 6 6 6.884296E+05 -1.733961E-01 + 3.000000E-01 1 1 1.444033E+03 6.269322E-03 + 3.000000E-01 1 5 -9.111029E+03 7.101058E-03 + 3.000000E-01 2 2 1.690542E+03 1.995744E-02 + 3.000000E-01 2 4 1.235828E+04 2.445857E-02 + 3.000000E-01 3 3 2.169583E+03 1.453299E-03 + 3.000000E-01 4 2 1.236276E+04 -1.233631E-01 + 3.000000E-01 4 4 2.614335E+05 -1.543396E-01 + 3.000000E-01 5 1 -9.125158E+03 3.700770E-04 + 3.000000E-01 5 5 8.191486E+05 -7.132935E-04 + 3.000000E-01 6 6 6.673795E+05 -4.440385E-02 + 4.000000E-01 1 1 1.425401E+03 -4.108052E-02 + 4.000000E-01 1 5 -9.064186E+03 5.634245E-02 + 4.000000E-01 2 2 1.671785E+03 -6.710615E-03 + 4.000000E-01 2 4 1.231083E+04 -6.929412E-02 + 4.000000E-01 3 3 2.166178E+03 5.495228E-03 + 4.000000E-01 4 2 1.232969E+04 -6.580804E-02 + 4.000000E-01 4 4 2.612587E+05 6.190121E-02 + 4.000000E-01 5 1 -9.060692E+03 6.707626E-03 + 4.000000E-01 5 5 8.194138E+05 -6.489989E-03 + 4.000000E-01 6 6 6.587328E+05 -1.063728E+01 + 5.000000E-01 1 1 1.414171E+03 3.453698E-01 + 5.000000E-01 1 5 -9.040007E+03 -3.437867E-01 + 5.000000E-01 2 2 1.660540E+03 3.550050E-01 + 5.000000E-01 2 4 1.228412E+04 2.817520E-01 + 5.000000E-01 3 3 2.162501E+03 2.197521E-02 + 5.000000E-01 4 2 1.229900E+04 5.180726E-03 + 5.000000E-01 4 4 2.611725E+05 8.319525E-01 + 5.000000E-01 5 1 -9.049924E+03 -4.966549E-02 + 5.000000E-01 5 5 8.193651E+05 8.510031E-02 + 5.000000E-01 6 6 6.535414E+05 1.552287E+02 + 6.000000E-01 1 1 1.405576E+03 7.597563E-02 + 6.000000E-01 1 5 -9.019186E+03 3.253367E-02 + 6.000000E-01 2 2 1.652408E+03 -6.845129E-02 + 6.000000E-01 2 4 1.226468E+04 -3.525721E-01 + 6.000000E-01 3 3 2.164061E+03 2.654704E-02 + 6.000000E-01 4 2 1.227475E+04 -2.927428E-01 + 6.000000E-01 4 4 2.610847E+05 9.614539E-01 + 6.000000E-01 5 1 -9.029830E+03 -4.355243E-05 + 6.000000E-01 5 5 8.191937E+05 -2.194798E-02 + 6.000000E-01 6 6 6.497349E+05 -5.169302E+01 + 7.000000E-01 1 1 1.395932E+03 2.687031E+00 + 7.000000E-01 1 5 -8.998733E+03 -2.345758E+00 + 7.000000E-01 2 2 1.643188E+03 2.431145E+00 + 7.000000E-01 2 4 1.224100E+04 2.120982E+00 + 7.000000E-01 3 3 2.166201E+03 5.592055E-02 + 7.000000E-01 4 2 1.225460E+04 6.609563E-01 + 7.000000E-01 4 4 2.610094E+05 3.439912E+00 + 7.000000E-01 5 1 -9.010243E+03 -4.799671E-01 + 7.000000E-01 5 5 8.189821E+05 4.613745E-01 + 7.000000E-01 6 6 6.454252E+05 1.170501E+03 + 8.000001E-01 1 1 1.384360E+03 1.642901E-01 + 8.000001E-01 1 5 -8.978327E+03 2.553241E+00 + 8.000001E-01 2 2 1.631998E+03 -1.413633E-02 + 8.000001E-01 2 4 1.221956E+04 -2.684513E+00 + 8.000001E-01 3 3 2.165785E+03 4.677046E-02 + 8.000001E-01 4 2 1.223349E+04 -4.235556E-01 + 8.000001E-01 4 4 2.609263E+05 2.081753E+00 + 8.000001E-01 5 1 -8.987876E+03 -9.826274E-03 + 8.000001E-01 5 5 8.190675E+05 -5.485277E-01 + 8.000001E-01 6 6 6.402148E+05 -3.896221E+01 + 9.000001E-01 1 1 1.378177E+03 7.398844E+00 + 9.000001E-01 1 5 -8.957874E+03 -6.925296E+00 + 9.000001E-01 2 2 1.627581E+03 5.964404E+00 + 9.000001E-01 2 4 1.220009E+04 4.984253E+00 + 9.000001E-01 3 3 2.165009E+03 1.034568E-01 + 9.000001E-01 4 2 1.220971E+04 5.667600E-01 + 9.000001E-01 4 4 2.608499E+05 7.644433E+00 + 9.000001E-01 5 1 -8.968889E+03 -1.710251E+00 + 9.000001E-01 5 5 8.189044E+05 1.618641E+00 + 9.000001E-01 6 6 6.380893E+05 2.840782E+03 + 1.000000E+00 1 1 1.362969E+03 1.615517E+00 + 1.000000E+00 1 5 -8.932901E+03 5.044086E+00 + 1.000000E+00 2 2 1.611138E+03 9.922764E-01 + 1.000000E+00 2 4 1.216958E+04 -5.591891E+00 + 1.000000E+00 3 3 2.165247E+03 2.016310E-01 + 1.000000E+00 4 2 1.218151E+04 -1.473536E+00 + 1.000000E+00 4 4 2.607715E+05 7.036344E+00 + 1.000000E+00 5 1 -8.944518E+03 -3.480948E-01 + 1.000000E+00 5 5 8.189051E+05 -1.422689E+00 + 1.000000E+00 6 6 6.303638E+05 4.558491E+02 + 1.100000E+00 1 1 1.363987E+03 -2.531477E+00 + 1.100000E+00 1 5 -8.926103E+03 6.271327E+00 + 1.100000E+00 2 2 1.611693E+03 -1.364930E+00 + 1.100000E+00 2 4 1.216229E+04 -4.610226E+00 + 1.100000E+00 3 3 2.165244E+03 2.358969E-01 + 1.100000E+00 4 2 1.216006E+04 -6.359519E+00 + 1.100000E+00 4 4 2.606747E+05 5.233872E-02 + 1.100000E+00 5 1 -8.920106E+03 1.063921E+00 + 1.100000E+00 5 5 8.188067E+05 -2.253227E+00 + 1.100000E+00 6 6 6.310228E+05 -1.073627E+03 + 1.200000E+00 1 1 1.341250E+03 1.548859E+01 + 1.200000E+00 1 5 -8.873159E+03 -6.809859E+00 + 1.200000E+00 2 2 1.586134E+03 1.391513E+01 + 1.200000E+00 2 4 1.211250E+04 4.959229E+00 + 1.200000E+00 3 3 2.164715E+03 3.401773E-01 + 1.200000E+00 4 2 1.212701E+04 3.459318E+00 + 1.200000E+00 4 4 2.605578E+05 1.085976E+01 + 1.200000E+00 5 1 -8.887145E+03 -5.441040E+00 + 1.200000E+00 5 5 8.187148E+05 2.547801E+00 + 1.200000E+00 6 6 6.198414E+05 6.079765E+03 + 1.300000E+00 1 1 1.317477E+03 1.786603E+01 + 1.300000E+00 1 5 -8.835250E+03 -4.428756E+00 + 1.300000E+00 2 2 1.567642E+03 1.936374E+01 + 1.300000E+00 2 4 1.207500E+04 -3.296340E+00 + 1.300000E+00 3 3 2.163520E+03 6.429050E-01 + 1.300000E+00 4 2 1.208866E+04 1.633794E+00 + 1.300000E+00 4 4 2.604250E+05 1.361215E+01 + 1.300000E+00 5 1 -8.846683E+03 -7.834044E+00 + 1.300000E+00 5 5 8.186024E+05 2.022286E+00 + 1.300000E+00 6 6 6.112214E+05 7.741492E+03 + 1.400000E+00 1 1 1.302752E+03 4.014243E+01 + 1.400000E+00 1 5 -8.796211E+03 -2.097240E+01 + 1.400000E+00 2 2 1.559435E+03 3.202108E+01 + 1.400000E+00 2 4 1.202891E+04 4.779904E+00 + 1.400000E+00 3 3 2.164057E+03 9.372752E-01 + 1.400000E+00 4 2 1.204261E+04 3.293264E+00 + 1.400000E+00 4 4 2.602875E+05 2.683385E+01 + 1.400000E+00 5 1 -8.809545E+03 -1.970354E+01 + 1.400000E+00 5 5 8.184987E+05 1.044662E+01 + 1.400000E+00 6 6 6.065062E+05 1.238738E+04 + 1.500000E+00 1 1 1.305815E+03 6.491683E+01 + 1.500000E+00 1 5 -8.772146E+03 -5.825910E+01 + 1.500000E+00 2 2 1.552037E+03 5.264654E+01 + 1.500000E+00 2 4 1.198437E+04 1.699949E+01 + 1.500000E+00 3 3 2.163969E+03 8.035405E-01 + 1.500000E+00 4 2 1.199230E+04 -6.595213E+00 + 1.500000E+00 4 4 2.601701E+05 4.169799E+01 + 1.500000E+00 5 1 -8.775944E+03 -3.643074E+01 + 1.500000E+00 5 5 8.183611E+05 3.319314E+01 + 1.500000E+00 6 6 6.043392E+05 1.849497E+04 + 1.600000E+00 1 1 1.252716E+03 3.327114E+01 + 1.600000E+00 1 5 -8.693517E+03 -1.871183E+01 + 1.600000E+00 2 2 1.525129E+03 4.072418E+01 + 1.600000E+00 2 4 1.192106E+04 1.475205E+01 + 1.600000E+00 3 3 2.162847E+03 2.077548E+00 + 1.600000E+00 4 2 1.193497E+04 1.744354E+01 + 1.600000E+00 4 4 2.599660E+05 2.792954E+01 + 1.600000E+00 5 1 -8.706070E+03 -2.088443E+01 + 1.600000E+00 5 5 8.181992E+05 1.237664E+01 + 1.600000E+00 6 6 5.862862E+05 1.873653E+04 + 1.700000E+00 1 1 1.263750E+03 4.159086E+01 + 1.700000E+00 1 5 -8.659005E+03 -3.006438E+01 + 1.700000E+00 2 2 1.499287E+03 5.819635E+01 + 1.700000E+00 2 4 1.187052E+04 1.416955E+01 + 1.700000E+00 3 3 2.164139E+03 8.063655E-01 + 1.700000E+00 4 2 1.188380E+04 1.460832E+01 + 1.700000E+00 4 4 2.597760E+05 4.624529E+01 + 1.700000E+00 5 1 -8.672770E+03 -2.952167E+01 + 1.700000E+00 5 5 8.180617E+05 2.236001E+01 + 1.700000E+00 6 6 5.827302E+05 2.159274E+04 + 1.800000E+00 1 1 1.189232E+03 1.561305E+02 + 1.800000E+00 1 5 -8.555380E+03 -1.342970E+02 + 1.800000E+00 2 2 1.504885E+03 9.247465E+01 + 1.800000E+00 2 4 1.178999E+04 3.150293E+01 + 1.800000E+00 3 3 2.163042E+03 1.313273E+00 + 1.800000E+00 4 2 1.180293E+04 3.034780E+01 + 1.800000E+00 4 4 2.595717E+05 6.551591E+01 + 1.800000E+00 5 1 -8.569188E+03 -1.318952E+02 + 1.800000E+00 5 5 8.178374E+05 1.150578E+02 + 1.800000E+00 6 6 5.727449E+05 3.621642E+04 + 1.900000E+00 1 1 1.226731E+03 5.598594E+01 + 1.900000E+00 1 5 -8.539219E+03 -5.221244E+01 + 1.900000E+00 2 2 1.484238E+03 6.774551E+01 + 1.900000E+00 2 4 1.170991E+04 5.493768E+01 + 1.900000E+00 3 3 2.162584E+03 1.752707E+00 + 1.900000E+00 4 2 1.172212E+04 5.261831E+01 + 1.900000E+00 4 4 2.593096E+05 8.803828E+01 + 1.900000E+00 5 1 -8.551688E+03 -5.053044E+01 + 1.900000E+00 5 5 8.176388E+05 4.843289E+01 + 1.900000E+00 6 6 5.656957E+05 3.362212E+04 + 2.000000E+00 1 1 1.087300E+03 1.198298E+02 + 2.000000E+00 1 5 -8.342403E+03 -1.376728E+02 + 2.000000E+00 2 2 1.441709E+03 1.099168E+02 + 2.000000E+00 2 4 1.162081E+04 1.143344E+02 + 2.000000E+00 3 3 2.162366E+03 1.870794E+00 + 2.000000E+00 4 2 1.163232E+04 1.028961E+02 + 2.000000E+00 4 4 2.590200E+05 1.522620E+02 + 2.000000E+00 5 1 -8.362664E+03 -1.267002E+02 + 2.000000E+00 5 5 8.172602E+05 1.471770E+02 + 2.000000E+00 6 6 5.488098E+05 5.315241E+04 + 2.100000E+00 1 1 1.255987E+03 1.175194E+02 + 2.100000E+00 1 5 -8.462438E+03 -1.145313E+02 + 2.100000E+00 2 2 1.445970E+03 1.372894E+02 + 2.100000E+00 2 4 1.156079E+04 1.278852E+02 + 2.100000E+00 3 3 2.162340E+03 2.534883E+00 + 2.100000E+00 4 2 1.157829E+04 1.415270E+02 + 2.100000E+00 4 4 2.587445E+05 1.772284E+02 + 2.100000E+00 5 1 -8.483445E+03 -1.251749E+02 + 2.100000E+00 5 5 8.172242E+05 1.242277E+02 + 2.100000E+00 6 6 5.477408E+05 5.859570E+04 + 2.200000E+00 1 1 1.161857E+03 8.277615E+01 + 2.200000E+00 1 5 -8.305616E+03 -9.694767E+01 + 2.200000E+00 2 2 1.429704E+03 1.234183E+02 + 2.200000E+00 2 4 1.147599E+04 1.348589E+02 + 2.200000E+00 3 3 2.161439E+03 4.401815E+00 + 2.200000E+00 4 2 1.149046E+04 1.381628E+02 + 2.200000E+00 4 4 2.583983E+05 2.061866E+02 + 2.200000E+00 5 1 -8.319411E+03 -9.914822E+01 + 2.200000E+00 5 5 8.168261E+05 1.187337E+02 + 2.200000E+00 6 6 5.324512E+05 5.808795E+04 + 2.300000E+00 1 1 1.015164E+03 1.006042E+02 + 2.300000E+00 1 5 -8.054513E+03 -1.371125E+02 + 2.300000E+00 2 2 1.385527E+03 1.660816E+02 + 2.300000E+00 2 4 1.133986E+04 1.926234E+02 + 2.300000E+00 3 3 2.164200E+03 5.022234E+00 + 2.300000E+00 4 2 1.135328E+04 1.947626E+02 + 2.300000E+00 4 4 2.579466E+05 2.966538E+02 + 2.300000E+00 5 1 -8.066244E+03 -1.383375E+02 + 2.300000E+00 5 5 8.162890E+05 1.932015E+02 + 2.300000E+00 6 6 5.070252E+05 7.404296E+04 + 2.400000E+00 1 1 1.214906E+03 5.852307E+02 + 2.400000E+00 1 5 -8.268893E+03 -8.177158E+02 + 2.400000E+00 2 2 1.387516E+03 1.894508E+02 + 2.400000E+00 2 4 1.122504E+04 2.547854E+02 + 2.400000E+00 3 3 2.163273E+03 2.346359E+00 + 2.400000E+00 4 2 1.123836E+04 2.560267E+02 + 2.400000E+00 4 4 2.574243E+05 4.518562E+02 + 2.400000E+00 5 1 -8.282180E+03 -8.209977E+02 + 2.400000E+00 5 5 8.163470E+05 1.156790E+03 + 2.400000E+00 6 6 5.116156E+05 1.178427E+05 + 2.500000E+00 1 1 1.246471E+03 2.142013E+02 + 2.500000E+00 1 5 -8.248199E+03 -3.329355E+02 + 2.500000E+00 2 2 1.357654E+03 2.025255E+02 + 2.500000E+00 2 4 1.107015E+04 3.476158E+02 + 2.500000E+00 3 3 2.161670E+03 2.311961E+00 + 2.500000E+00 4 2 1.108291E+04 3.480320E+02 + 2.500000E+00 4 4 2.568296E+05 7.940952E+02 + 2.500000E+00 5 1 -8.261192E+03 -3.337436E+02 + 2.500000E+00 5 5 8.160553E+05 5.377015E+02 + 2.500000E+00 6 6 5.215977E+05 1.176396E+05 + 2.600000E+00 1 1 1.152141E+03 1.682242E+02 + 2.600000E+00 1 5 -8.041700E+03 -2.895229E+02 + 2.600000E+00 2 2 1.304580E+03 2.326107E+02 + 2.600000E+00 2 4 1.090560E+04 5.031878E+02 + 2.600000E+00 3 3 2.160825E+03 3.126930E+00 + 2.600000E+00 4 2 1.091793E+04 5.049114E+02 + 2.600000E+00 4 4 2.563096E+05 1.381231E+03 + 2.600000E+00 5 1 -8.053100E+03 -2.900639E+02 + 2.600000E+00 5 5 8.154575E+05 5.286125E+02 + 2.600000E+00 6 6 5.093822E+05 1.192501E+05 + 2.700000E+00 1 1 1.035172E+03 1.608131E+02 + 2.700000E+00 1 5 -7.790863E+03 -3.237605E+02 + 2.700000E+00 2 2 1.266582E+03 3.277071E+02 + 2.700000E+00 2 4 1.085689E+04 7.817658E+02 + 2.700000E+00 3 3 2.160143E+03 4.236008E+00 + 2.700000E+00 4 2 1.086863E+04 7.819337E+02 + 2.700000E+00 4 4 2.564252E+05 2.109151E+03 + 2.700000E+00 5 1 -7.802771E+03 -3.243824E+02 + 2.700000E+00 5 5 8.147674E+05 6.867380E+02 + 2.700000E+00 6 6 4.884454E+05 1.238860E+05 + 2.799999E+00 1 1 8.628414E+02 1.778566E+02 + 2.799999E+00 1 5 -7.430020E+03 -3.774420E+02 + 2.799999E+00 2 2 1.293632E+03 3.825009E+02 + 2.799999E+00 2 4 1.088742E+04 8.311805E+02 + 2.799999E+00 3 3 2.159710E+03 5.450130E+00 + 2.799999E+00 4 2 1.089878E+04 8.314925E+02 + 2.799999E+00 4 4 2.562536E+05 1.832187E+03 + 2.799999E+00 5 1 -7.441687E+03 -3.780771E+02 + 2.799999E+00 5 5 8.138429E+05 8.621034E+02 + 2.799999E+00 6 6 4.470920E+05 1.495096E+05 + 2.899999E+00 1 1 4.788242E+02 4.073611E+02 + 2.899999E+00 1 5 -6.634616E+03 -7.981046E+02 + 2.899999E+00 2 2 1.286692E+03 4.327466E+02 + 2.899999E+00 2 4 1.075176E+04 9.386442E+02 + 2.899999E+00 3 3 2.160150E+03 7.244529E+00 + 2.899999E+00 4 2 1.076280E+04 9.389468E+02 + 2.899999E+00 4 4 2.554582E+05 2.041500E+03 + 2.899999E+00 5 1 -6.647493E+03 -7.984279E+02 + 2.899999E+00 5 5 8.120112E+05 1.683417E+03 + 2.899999E+00 6 6 4.254066E+05 2.188972E+05 + 2.999999E+00 1 1 8.676102E+02 1.330944E+03 + 2.999999E+00 1 5 -7.176687E+03 -2.660807E+03 + 2.999999E+00 2 2 1.320125E+03 4.957027E+02 + 2.999999E+00 2 4 1.069429E+04 1.124392E+03 + 2.999999E+00 3 3 2.161853E+03 8.607779E+00 + 2.999999E+00 4 2 1.070511E+04 1.124652E+03 + 2.999999E+00 4 4 2.548333E+05 2.578703E+03 + 2.999999E+00 5 1 -7.188262E+03 -2.658969E+03 + 2.999999E+00 5 5 8.124259E+05 5.464042E+03 + 2.999999E+00 6 6 4.548885E+05 2.814697E+05 + 3.099999E+00 1 1 1.489484E+03 9.715460E+02 + 3.099999E+00 1 5 -8.387819E+03 -2.143894E+03 + 3.099999E+00 2 2 1.352241E+03 4.908422E+02 + 3.099999E+00 2 4 1.064030E+04 1.206893E+03 + 3.099999E+00 3 3 2.164565E+03 8.339890E+00 + 3.099999E+00 4 2 1.065052E+04 1.207257E+03 + 3.099999E+00 4 4 2.542144E+05 3.023530E+03 + 3.099999E+00 5 1 -8.397405E+03 -2.142834E+03 + 3.099999E+00 5 5 8.144962E+05 4.911563E+03 + 3.099999E+00 6 6 4.956156E+05 3.123367E+05 + 3.199999E+00 1 1 1.552024E+03 6.866681E+02 + 3.199999E+00 1 5 -8.523776E+03 -1.651808E+03 + 3.199999E+00 2 2 1.317350E+03 4.811824E+02 + 3.199999E+00 2 4 1.045333E+04 1.308174E+03 + 3.199999E+00 3 3 2.165616E+03 5.539555E+00 + 3.199999E+00 4 2 1.046322E+04 1.308772E+03 + 3.199999E+00 4 4 2.533207E+05 3.628707E+03 + 3.199999E+00 5 1 -8.532786E+03 -1.651589E+03 + 3.199999E+00 5 5 8.144799E+05 4.254115E+03 + 3.199999E+00 6 6 5.333272E+05 3.238614E+05 + 3.299999E+00 1 1 1.519504E+03 5.044711E+02 + 3.299999E+00 1 5 -8.430406E+03 -1.328371E+03 + 3.299999E+00 2 2 1.244961E+03 5.202350E+02 + 3.299999E+00 2 4 1.019846E+04 1.549934E+03 + 3.299999E+00 3 3 2.164487E+03 3.300210E+00 + 3.299999E+00 4 2 1.020778E+04 1.550881E+03 + 3.299999E+00 4 4 2.523155E+05 4.681091E+03 + 3.299999E+00 5 1 -8.438989E+03 -1.328675E+03 + 3.299999E+00 5 5 8.139069E+05 3.954610E+03 + 3.299999E+00 6 6 5.629063E+05 3.183922E+05 + 3.399999E+00 1 1 1.429316E+03 3.587855E+02 + 3.399999E+00 1 5 -8.166790E+03 -1.082057E+03 + 3.399999E+00 2 2 1.186506E+03 6.180828E+02 + 3.399999E+00 2 4 1.000604E+04 1.949967E+03 + 3.399999E+00 3 3 2.162645E+03 2.077040E+00 + 3.399999E+00 4 2 1.001519E+04 1.951426E+03 + 3.399999E+00 4 4 2.515476E+05 6.202599E+03 + 3.399999E+00 5 1 -8.174550E+03 -1.082855E+03 + 3.399999E+00 5 5 8.128979E+05 3.939292E+03 + 3.399999E+00 6 6 5.734689E+05 2.999054E+05 + 3.499999E+00 1 1 1.253319E+03 2.631412E+02 + 3.499999E+00 1 5 -7.686133E+03 -1.006373E+03 + 3.499999E+00 2 2 1.168802E+03 7.364794E+02 + 3.499999E+00 2 4 9.936361E+03 2.405336E+03 + 3.499999E+00 3 3 2.159954E+03 2.400041E+00 + 3.499999E+00 4 2 9.945477E+03 2.407414E+03 + 3.499999E+00 4 4 2.511583E+05 7.909718E+03 + 3.499999E+00 5 1 -7.692891E+03 -1.008493E+03 + 3.499999E+00 5 5 8.114382E+05 4.566627E+03 + 3.499999E+00 6 6 5.554653E+05 2.852625E+05 + 3.599999E+00 1 1 1.035358E+03 2.876351E+02 + 3.599999E+00 1 5 -7.169593E+03 -1.269149E+03 + 3.599999E+00 2 2 1.171625E+03 8.513398E+02 + 3.599999E+00 2 4 9.931645E+03 2.860456E+03 + 3.599999E+00 3 3 2.158543E+03 4.722716E+00 + 3.599999E+00 4 2 9.940586E+03 2.863186E+03 + 3.599999E+00 4 4 2.509897E+05 9.670100E+03 + 3.599999E+00 5 1 -7.176320E+03 -1.273618E+03 + 3.599999E+00 5 5 8.102191E+05 6.195654E+03 + 3.599999E+00 6 6 5.199856E+05 2.974018E+05 + 3.699999E+00 1 1 8.653893E+02 4.021774E+02 + 3.699999E+00 1 5 -6.861894E+03 -1.715858E+03 + 3.699999E+00 2 2 1.176039E+03 9.740475E+02 + 3.699999E+00 2 4 9.947188E+03 3.355576E+03 + 3.699999E+00 3 3 2.159710E+03 6.722109E+00 + 3.699999E+00 4 2 9.956570E+03 3.358951E+03 + 3.699999E+00 4 4 2.509371E+05 1.161879E+04 + 3.699999E+00 5 1 -6.869617E+03 -1.722578E+03 + 3.699999E+00 5 5 8.099283E+05 8.157991E+03 + 3.699999E+00 6 6 4.924562E+05 3.377067E+05 + 3.799999E+00 1 1 7.344095E+02 5.368340E+02 + 3.799999E+00 1 5 -6.670849E+03 -2.110418E+03 + 3.799999E+00 2 2 1.187228E+03 1.129501E+03 + 3.799999E+00 2 4 1.001379E+04 3.962422E+03 + 3.799999E+00 3 3 2.161339E+03 6.376057E+00 + 3.799999E+00 4 2 1.002361E+04 3.966385E+03 + 3.799999E+00 4 4 2.511428E+05 1.396322E+04 + 3.799999E+00 5 1 -6.680824E+03 -2.118444E+03 + 3.799999E+00 5 5 8.101197E+05 9.580111E+03 + 3.799999E+00 6 6 4.834378E+05 3.896431E+05 + 3.899998E+00 1 1 5.949812E+02 6.974046E+02 + 3.899998E+00 1 5 -6.384929E+03 -2.498325E+03 + 3.899998E+00 2 2 1.238032E+03 1.334278E+03 + 3.899998E+00 2 4 1.024290E+04 4.716964E+03 + 3.899998E+00 3 3 2.161552E+03 5.115295E+00 + 3.899998E+00 4 2 1.025345E+04 4.721289E+03 + 3.899998E+00 4 4 2.519866E+05 1.676777E+04 + 3.899998E+00 5 1 -6.396908E+03 -2.506805E+03 + 3.899998E+00 5 5 8.099074E+05 1.060047E+04 + 3.899998E+00 6 6 4.874768E+05 4.423460E+05 + 3.999998E+00 1 1 4.450232E+02 9.303323E+02 + 3.999998E+00 1 5 -5.969588E+03 -3.085815E+03 + 3.999998E+00 2 2 1.378535E+03 1.572897E+03 + 3.999998E+00 2 4 1.078900E+04 5.550558E+03 + 3.999998E+00 3 3 2.160886E+03 4.168301E+00 + 3.999998E+00 4 2 1.080032E+04 5.554992E+03 + 3.999998E+00 4 4 2.539513E+05 1.975279E+04 + 3.999998E+00 5 1 -5.983599E+03 -3.094308E+03 + 3.999998E+00 5 5 8.089868E+05 1.202890E+04 + 3.999998E+00 6 6 4.982582E+05 4.964733E+05 + 4.099998E+00 1 1 3.213549E+02 1.272431E+03 + 4.099998E+00 1 5 -5.556480E+03 -4.045225E+03 + 4.099998E+00 2 2 1.644181E+03 1.786194E+03 + 4.099998E+00 2 4 1.175033E+04 6.261296E+03 + 4.099998E+00 3 3 2.159966E+03 3.734381E+00 + 4.099998E+00 4 2 1.176255E+04 6.265514E+03 + 4.099998E+00 4 4 2.573100E+05 2.222593E+04 + 4.099998E+00 5 1 -5.572396E+03 -4.053451E+03 + 4.099998E+00 5 5 8.077581E+05 1.462175E+04 + 4.099998E+00 6 6 5.168934E+05 5.566446E+05 + 4.199998E+00 1 1 2.837065E+02 1.745616E+03 + 4.199998E+00 1 5 -5.372986E+03 -5.475365E+03 + 4.199998E+00 2 2 2.021457E+03 1.891318E+03 + 4.199998E+00 2 4 1.306499E+04 6.578083E+03 + 4.199998E+00 3 3 2.159081E+03 3.634046E+00 + 4.199998E+00 4 2 1.307794E+04 6.581710E+03 + 4.199998E+00 4 4 2.618055E+05 2.329030E+04 + 4.199998E+00 5 1 -5.391368E+03 -5.482950E+03 + 4.199998E+00 5 5 8.070315E+05 1.884529E+04 + 4.199998E+00 6 6 5.500119E+05 6.233448E+05 + 4.299998E+00 1 1 4.283814E+02 2.352158E+03 + 4.299998E+00 1 5 -5.764863E+03 -7.385773E+03 + 4.299998E+00 2 2 2.437146E+03 1.823655E+03 + 4.299998E+00 2 4 1.447431E+04 6.295638E+03 + 4.299998E+00 3 3 2.158338E+03 3.688311E+00 + 4.299998E+00 4 2 1.448777E+04 6.298275E+03 + 4.299998E+00 4 4 2.665226E+05 2.228728E+04 + 4.299998E+00 5 1 -5.785992E+03 -7.391787E+03 + 4.299998E+00 5 5 8.080489E+05 2.478460E+04 + 4.299998E+00 6 6 6.038834E+05 6.911415E+05 + 4.399998E+00 1 1 9.079855E+02 3.018073E+03 + 4.399998E+00 1 5 -7.247806E+03 -9.523347E+03 + 4.399998E+00 2 2 2.782287E+03 1.581769E+03 + 4.399998E+00 2 4 1.560401E+04 5.428034E+03 + 4.399998E+00 3 3 2.157615E+03 3.792120E+00 + 4.399998E+00 4 2 1.561741E+04 5.429461E+03 + 4.399998E+00 4 4 2.701726E+05 1.932651E+04 + 4.399998E+00 5 1 -7.272055E+03 -9.525975E+03 + 4.399998E+00 5 5 8.125672E+05 3.159983E+04 + 4.399998E+00 6 6 6.810822E+05 7.511041E+05 + 4.499998E+00 1 1 1.844521E+03 3.468470E+03 + 4.499998E+00 1 5 -1.022216E+04 -1.098010E+04 + 4.499998E+00 2 2 2.973472E+03 1.241134E+03 + 4.499998E+00 2 4 1.617862E+04 4.252971E+03 + 4.499998E+00 3 3 2.157036E+03 3.889959E+00 + 4.499998E+00 4 2 1.619135E+04 4.253312E+03 + 4.499998E+00 4 4 2.718470E+05 1.542462E+04 + 4.499998E+00 5 1 -1.024756E+04 -1.097690E+04 + 4.499998E+00 5 5 8.219297E+05 3.629821E+04 + 4.499998E+00 6 6 7.797110E+05 7.932092E+05 + 4.599998E+00 1 1 3.006497E+03 3.288463E+03 + 4.599998E+00 1 5 -1.393009E+04 -1.040451E+04 + 4.599998E+00 2 2 3.003075E+03 9.052584E+02 + 4.599998E+00 2 4 1.619231E+04 3.134248E+03 + 4.599998E+00 3 3 2.156441E+03 3.947880E+00 + 4.599998E+00 4 2 1.620390E+04 3.133939E+03 + 4.599998E+00 4 4 2.715950E+05 1.185781E+04 + 4.599998E+00 5 1 -1.395269E+04 -1.039487E+04 + 4.599998E+00 5 5 8.336579E+05 3.448041E+04 + 4.599998E+00 6 6 8.930994E+05 8.082519E+05 + 4.699998E+00 1 1 3.794680E+03 2.495065E+03 + 4.699998E+00 1 5 -1.642829E+04 -7.858628E+03 + 4.699998E+00 2 2 2.923092E+03 6.415554E+02 + 4.699998E+00 2 4 1.584282E+04 2.298043E+03 + 4.699998E+00 3 3 2.155818E+03 3.930626E+00 + 4.699998E+00 4 2 1.585324E+04 2.297627E+03 + 4.699998E+00 4 4 2.701639E+05 9.380751E+03 + 4.699998E+00 5 1 -1.644485E+04 -7.845549E+03 + 4.699998E+00 5 5 8.414570E+05 2.637521E+04 + 4.699998E+00 6 6 1.010009E+06 7.903299E+05 + 4.799998E+00 1 1 3.985248E+03 1.611070E+03 + 4.799998E+00 1 5 -1.700283E+04 -5.037604E+03 + 4.799998E+00 2 2 2.794854E+03 4.658022E+02 + 4.799998E+00 2 4 1.535110E+04 1.786286E+03 + 4.799998E+00 3 3 2.155229E+03 3.795074E+00 + 4.799998E+00 4 2 1.536034E+04 1.786196E+03 + 4.799998E+00 4 4 2.683482E+05 8.090887E+03 + 4.799998E+00 5 1 -1.701342E+04 -5.024928E+03 + 4.799998E+00 5 5 8.430764E+05 1.747628E+04 + 4.799998E+00 6 6 1.116654E+06 7.396004E+05 + 4.899998E+00 1 1 3.827402E+03 9.634639E+02 + 4.899998E+00 1 5 -1.646776E+04 -2.990666E+03 + 4.899998E+00 2 2 2.660283E+03 3.640230E+02 + 4.899998E+00 2 4 1.486350E+04 1.538998E+03 + 4.899998E+00 3 3 2.154426E+03 3.535414E+00 + 4.899998E+00 4 2 1.487189E+04 1.539512E+03 + 4.899998E+00 4 4 2.666564E+05 7.737369E+03 + 4.899998E+00 5 1 -1.647437E+04 -2.980337E+03 + 4.899998E+00 5 5 8.411734E+05 1.114036E+04 + 4.899998E+00 6 6 1.200763E+06 6.633247E+05 + 4.999998E+00 1 1 3.566480E+03 5.624658E+02 + 4.999998E+00 1 5 -1.561565E+04 -1.741451E+03 + 4.999998E+00 2 2 2.540084E+03 3.146508E+02 + 4.999998E+00 2 4 1.444920E+04 1.473245E+03 + 4.999998E+00 3 3 2.153303E+03 3.274325E+00 + 4.999998E+00 4 2 1.445684E+04 1.474538E+03 + 4.999998E+00 4 4 2.653165E+05 8.002011E+03 + 4.999998E+00 5 1 -1.562004E+04 -1.733859E+03 + 4.999998E+00 5 5 8.383096E+05 7.408785E+03 + 4.999998E+00 6 6 1.255646E+06 5.736627E+05 + 5.099998E+00 1 1 3.311354E+03 3.283456E+02 + 5.099998E+00 1 5 -1.479400E+04 -1.026911E+03 + 5.099998E+00 2 2 2.441361E+03 2.988572E+02 + 5.099998E+00 2 4 1.412894E+04 1.518558E+03 + 5.099998E+00 3 3 2.151823E+03 3.256433E+00 + 5.099998E+00 4 2 1.413615E+04 1.520705E+03 + 5.099998E+00 4 4 2.643879E+05 8.620332E+03 + 5.099998E+00 5 1 -1.479733E+04 -1.021795E+03 + 5.099998E+00 5 5 8.355992E+05 5.414550E+03 + 5.099998E+00 6 6 1.281620E+06 4.832948E+05 + 5.199997E+00 1 1 3.093402E+03 1.941337E+02 + 5.199997E+00 1 5 -1.409953E+04 -6.287033E+02 + 5.199997E+00 2 2 2.364365E+03 3.029778E+02 + 5.199997E+00 2 4 1.389976E+04 1.624414E+03 + 5.199997E+00 3 3 2.150268E+03 3.657035E+00 + 5.199997E+00 4 2 1.390667E+04 1.627437E+03 + 5.199997E+00 4 4 2.638413E+05 9.404403E+03 + 5.199997E+00 5 1 -1.410244E+04 -6.256587E+02 + 5.199997E+00 5 5 8.333331E+05 4.449737E+03 + 5.199997E+00 6 6 1.284211E+06 4.016602E+05 + 5.299997E+00 1 1 2.915262E+03 1.179255E+02 + 5.299997E+00 1 5 -1.353667E+04 -4.115366E+02 + 5.299997E+00 2 2 2.306565E+03 3.179202E+02 + 5.299997E+00 2 4 1.374927E+04 1.757467E+03 + 5.299997E+00 3 3 2.148804E+03 4.470127E+00 + 5.299997E+00 4 2 1.375611E+04 1.761369E+03 + 5.299997E+00 4 4 2.636210E+05 1.023076E+04 + 5.299997E+00 5 1 -1.353960E+04 -4.101665E+02 + 5.299997E+00 5 5 8.315229E+05 4.081402E+03 + 5.299997E+00 6 6 1.270988E+06 3.336173E+05 + 5.399997E+00 1 1 2.771403E+03 7.535029E+01 + 5.399997E+00 1 5 -1.308473E+04 -2.980706E+02 + 5.399997E+00 2 2 2.264599E+03 3.379569E+02 + 5.399997E+00 2 4 1.366264E+04 1.896994E+03 + 5.399997E+00 3 3 2.147620E+03 5.584976E+00 + 5.399997E+00 4 2 1.366955E+04 1.901729E+03 + 5.399997E+00 4 4 2.636598E+05 1.102346E+04 + 5.399997E+00 5 1 -1.308783E+04 -2.980390E+02 + 5.399997E+00 5 5 8.301076E+05 4.066760E+03 + 5.399997E+00 6 6 1.249024E+06 2.801717E+05 + 5.499997E+00 1 1 2.654982E+03 5.237862E+01 + 5.499997E+00 1 5 -1.271948E+04 -2.452442E+02 + 5.499997E+00 2 2 2.235198E+03 3.596556E+02 + 5.499997E+00 2 4 1.362563E+04 2.030902E+03 + 5.499997E+00 3 3 2.146740E+03 6.866094E+00 + 5.499997E+00 4 2 1.363269E+04 2.036442E+03 + 5.499997E+00 4 4 2.638968E+05 1.173945E+04 + 5.499997E+00 5 1 -1.272269E+04 -2.462640E+02 + 5.499997E+00 5 5 8.290118E+05 4.272639E+03 + 5.499997E+00 6 6 1.223694E+06 2.399705E+05 + 5.599997E+00 1 1 2.559889E+03 4.090048E+01 + 5.599997E+00 1 5 -1.242047E+04 -2.296341E+02 + 5.599997E+00 2 2 2.215537E+03 3.810944E+02 + 5.599997E+00 2 4 1.362599E+04 2.152860E+03 + 5.599997E+00 3 3 2.146235E+03 8.188703E+00 + 5.599997E+00 4 2 1.363331E+04 2.159134E+03 + 5.599997E+00 4 4 2.642781E+05 1.235779E+04 + 5.599997E+00 5 1 -1.242398E+04 -2.314803E+02 + 5.599997E+00 5 5 8.281864E+05 4.624792E+03 + 5.599997E+00 6 6 1.198520E+06 2.106349E+05 + 5.699997E+00 1 1 2.481134E+03 3.622530E+01 + 5.699997E+00 1 5 -1.217205E+04 -2.390406E+02 + 5.699997E+00 2 2 2.203338E+03 4.012977E+02 + 5.699997E+00 2 4 1.365389E+04 2.260206E+03 + 5.699997E+00 3 3 2.146061E+03 9.437527E+00 + 5.699997E+00 4 2 1.366151E+04 2.267152E+03 + 5.699997E+00 4 4 2.647607E+05 1.287284E+04 + 5.699997E+00 5 1 -1.217571E+04 -2.415526E+02 + 5.699997E+00 5 5 8.276000E+05 5.077591E+03 + 5.699997E+00 6 6 1.175510E+06 1.896114E+05 + 5.799997E+00 1 1 2.414801E+03 3.571963E+01 + 5.799997E+00 1 5 -1.196363E+04 -2.675559E+02 + 5.799997E+00 2 2 2.196878E+03 4.198519E+02 + 5.799997E+00 2 4 1.370169E+04 2.352441E+03 + 5.799997E+00 3 3 2.146153E+03 1.050976E+01 + 5.799997E+00 4 2 1.370968E+04 2.360014E+03 + 5.799997E+00 4 4 2.653059E+05 1.328700E+04 + 5.799997E+00 5 1 -1.196734E+04 -2.706225E+02 + 5.799997E+00 5 5 8.272393E+05 5.595674E+03 + 5.799997E+00 6 6 1.155582E+06 1.745987E+05 + 5.899997E+00 1 1 2.357922E+03 3.801922E+01 + 5.899997E+00 1 5 -1.178885E+04 -3.124327E+02 + 5.899997E+00 2 2 2.194862E+03 4.366475E+02 + 5.899997E+00 2 4 1.376376E+04 2.430229E+03 + 5.899997E+00 3 3 2.146511E+03 1.132461E+01 + 5.899997E+00 4 2 1.377225E+04 2.438366E+03 + 5.899997E+00 4 4 2.658924E+05 1.360790E+04 + 5.899997E+00 5 1 -1.179261E+04 -3.160218E+02 + 5.899997E+00 5 5 8.270986E+05 6.141441E+03 + 5.899997E+00 6 6 1.138981E+06 1.637083E+05 + 5.999997E+00 1 1 2.308324E+03 4.254660E+01 + 5.999997E+00 1 5 -1.164482E+04 -3.718600E+02 + 5.999997E+00 2 2 2.196359E+03 4.517130E+02 + 5.999997E+00 2 4 1.383614E+04 2.494713E+03 + 5.999997E+00 3 3 2.146963E+03 1.182240E+01 + 5.999997E+00 4 2 1.384510E+04 2.503334E+03 + 5.999997E+00 4 4 2.665013E+05 1.384496E+04 + 5.999997E+00 5 1 -1.164849E+04 -3.759966E+02 + 5.999997E+00 5 5 8.271738E+05 6.672120E+03 + 5.999997E+00 6 6 1.125527E+06 1.554829E+05 + 6.099997E+00 1 1 2.264572E+03 4.916754E+01 + 6.099997E+00 1 5 -1.153115E+04 -4.434497E+02 + 6.099997E+00 2 2 2.200714E+03 4.651149E+02 + 6.099997E+00 2 4 1.391590E+04 2.547103E+03 + 6.099997E+00 3 3 2.147508E+03 1.197464E+01 + 6.099997E+00 4 2 1.392542E+04 2.556143E+03 + 6.099997E+00 4 4 2.671198E+05 1.400747E+04 + 6.099997E+00 5 1 -1.153461E+04 -4.482232E+02 + 6.099997E+00 5 5 8.274449E+05 7.137406E+03 + 6.099997E+00 6 6 1.114846E+06 1.488498E+05 + 6.199996E+00 1 1 2.225845E+03 5.791336E+01 + 6.199996E+00 1 5 -1.144855E+04 -5.233252E+02 + 6.199996E+00 2 2 2.207427E+03 4.769182E+02 + 6.199996E+00 2 4 1.400112E+04 2.588469E+03 + 6.199996E+00 3 3 2.147983E+03 1.177742E+01 + 6.199996E+00 4 2 1.401124E+04 2.597856E+03 + 6.199996E+00 4 4 2.677387E+05 1.410379E+04 + 6.199996E+00 5 1 -1.145172E+04 -5.288552E+02 + 6.199996E+00 5 5 8.278942E+05 7.486343E+03 + 6.199996E+00 6 6 1.106466E+06 1.430567E+05 + 6.299996E+00 1 1 2.191787E+03 6.876836E+01 + 6.299996E+00 1 5 -1.139713E+04 -6.060628E+02 + 6.299996E+00 2 2 2.216136E+03 4.871554E+02 + 6.299996E+00 2 4 1.409027E+04 2.619675E+03 + 6.299996E+00 3 3 2.148326E+03 1.125918E+01 + 6.299996E+00 4 2 1.410091E+04 2.629354E+03 + 6.299996E+00 4 4 2.683526E+05 1.414116E+04 + 6.299996E+00 5 1 -1.140029E+04 -6.124946E+02 + 6.299996E+00 5 5 8.284701E+05 7.676410E+03 + 6.299996E+00 6 6 1.099910E+06 1.376037E+05 + 6.399996E+00 1 1 2.162298E+03 8.153858E+01 + 6.399996E+00 1 5 -1.137579E+04 -6.853342E+02 + 6.399996E+00 2 2 2.226521E+03 4.958389E+02 + 6.399996E+00 2 4 1.418227E+04 2.641381E+03 + 6.399996E+00 3 3 2.148450E+03 1.045967E+01 + 6.399996E+00 4 2 1.419349E+04 2.651291E+03 + 6.399996E+00 4 4 2.689549E+05 1.412553E+04 + 6.399996E+00 5 1 -1.137890E+04 -6.927547E+02 + 6.399996E+00 5 5 8.291241E+05 7.681978E+03 + 6.399996E+00 6 6 1.094727E+06 1.321838E+05 + 6.499996E+00 1 1 2.137414E+03 9.581681E+01 + 6.499996E+00 1 5 -1.138117E+04 -7.549782E+02 + 6.499996E+00 2 2 2.238330E+03 5.029627E+02 + 6.499996E+00 2 4 1.427607E+04 2.654099E+03 + 6.499996E+00 3 3 2.148310E+03 9.437737E+00 + 6.499996E+00 4 2 1.428792E+04 2.664201E+03 + 6.499996E+00 4 4 2.695456E+05 1.406176E+04 + 6.499996E+00 5 1 -1.138441E+04 -7.634878E+02 + 6.499996E+00 5 5 8.297768E+05 7.499819E+03 + 6.499996E+00 6 6 1.090528E+06 1.266324E+05 + 6.599996E+00 1 1 2.117061E+03 1.110347E+02 + 6.599996E+00 1 5 -1.140839E+04 -8.100574E+02 + 6.599996E+00 2 2 2.251300E+03 5.085111E+02 + 6.599996E+00 2 4 1.437086E+04 2.658243E+03 + 6.599996E+00 3 3 2.147839E+03 8.258938E+00 + 6.599996E+00 4 2 1.438327E+04 2.668446E+03 + 6.599996E+00 4 4 2.701200E+05 1.395409E+04 + 6.599996E+00 5 1 -1.141190E+04 -8.196803E+02 + 6.599996E+00 5 5 8.303829E+05 7.147120E+03 + 6.599996E+00 6 6 1.086990E+06 1.208826E+05 + 6.699996E+00 1 1 2.101058E+03 1.265616E+02 + 6.699996E+00 1 5 -1.145151E+04 -8.475231E+02 + 6.699996E+00 2 2 2.265208E+03 5.124736E+02 + 6.699996E+00 2 4 1.446587E+04 2.654156E+03 + 6.699996E+00 3 3 2.147059E+03 6.990735E+00 + 6.699996E+00 4 2 1.447884E+04 2.664420E+03 + 6.699996E+00 4 4 2.706753E+05 1.380617E+04 + 6.699996E+00 5 1 -1.145549E+04 -8.582006E+02 + 6.699996E+00 5 5 8.309059E+05 6.657472E+03 + 6.699996E+00 6 6 1.083849E+06 1.149360E+05 + 6.799996E+00 1 1 2.089061E+03 1.418042E+02 + 6.799996E+00 1 5 -1.150458E+04 -8.662194E+02 + 6.799996E+00 2 2 2.279823E+03 5.148475E+02 + 6.799996E+00 2 4 1.456021E+04 2.642193E+03 + 6.799996E+00 3 3 2.145892E+03 5.702897E+00 + 6.799996E+00 4 2 1.457378E+04 2.652465E+03 + 6.799996E+00 4 4 2.712104E+05 1.362124E+04 + 6.799996E+00 5 1 -1.150923E+04 -8.779100E+02 + 6.799996E+00 5 5 8.313066E+05 6.069667E+03 + 6.799996E+00 6 6 1.080908E+06 1.088340E+05 + 6.899996E+00 1 1 2.080629E+03 1.562687E+02 + 6.899996E+00 1 5 -1.156227E+04 -8.666884E+02 + 6.899996E+00 2 2 2.294929E+03 5.156463E+02 + 6.899996E+00 2 4 1.465322E+04 2.622711E+03 + 6.899996E+00 3 3 2.144403E+03 4.455389E+00 + 6.899996E+00 4 2 1.466733E+04 2.632958E+03 + 6.899996E+00 4 4 2.717231E+05 1.340240E+04 + 6.899996E+00 5 1 -1.156771E+04 -8.792554E+02 + 6.899996E+00 5 5 8.315797E+05 5.424942E+03 + 6.899996E+00 6 6 1.078029E+06 1.026409E+05 + 6.999996E+00 1 1 2.075260E+03 1.695943E+02 + 6.999996E+00 1 5 -1.162010E+04 -8.505952E+02 + 6.999996E+00 2 2 2.310312E+03 5.149020E+02 + 6.999996E+00 2 4 1.474421E+04 2.596136E+03 + 6.999996E+00 3 3 2.142583E+03 3.305560E+00 + 6.999996E+00 4 2 1.475881E+04 2.606313E+03 + 6.999996E+00 4 4 2.722094E+05 1.315296E+04 + 6.999996E+00 5 1 -1.162643E+04 -8.639541E+02 + 6.999996E+00 5 5 8.317351E+05 4.758364E+03 + 6.999996E+00 6 6 1.075111E+06 9.642911E+04 + 7.099996E+00 1 1 2.072439E+03 1.815470E+02 + 7.099996E+00 1 5 -1.167486E+04 -8.202302E+02 + 7.099996E+00 2 2 2.325777E+03 5.126632E+02 + 7.099996E+00 2 4 1.483244E+04 2.562913E+03 + 7.099996E+00 3 3 2.140477E+03 2.306333E+00 + 7.099996E+00 4 2 1.484754E+04 2.572995E+03 + 7.099996E+00 4 4 2.726711E+05 1.287586E+04 + 7.099996E+00 5 1 -1.168208E+04 -8.342277E+02 + 7.099996E+00 5 5 8.317692E+05 4.099196E+03 + 7.099996E+00 6 6 1.072095E+06 9.026942E+04 + 7.199996E+00 1 1 2.071695E+03 1.920041E+02 + 7.199996E+00 1 5 -1.172426E+04 -7.781377E+02 + 7.199996E+00 2 2 2.341146E+03 5.089946E+02 + 7.199996E+00 2 4 1.491744E+04 2.523556E+03 + 7.199996E+00 3 3 2.138098E+03 1.499131E+00 + 7.199996E+00 4 2 1.493301E+04 2.533487E+03 + 7.199996E+00 4 4 2.731030E+05 1.257439E+04 + 7.199996E+00 5 1 -1.173251E+04 -7.926338E+02 + 7.199996E+00 5 5 8.317095E+05 3.469617E+03 + 7.199996E+00 6 6 1.068946E+06 8.422774E+04 + 7.299995E+00 1 1 2.072606E+03 2.009275E+02 + 7.299995E+00 1 5 -1.176687E+04 -7.268240E+02 + 7.299995E+00 2 2 2.356259E+03 5.039792E+02 + 7.299995E+00 2 4 1.499860E+04 2.478589E+03 + 7.299995E+00 3 3 2.135474E+03 9.279532E-01 + 7.299995E+00 4 2 1.501468E+04 2.488349E+03 + 7.299995E+00 4 4 2.735058E+05 1.225183E+04 + 7.299995E+00 5 1 -1.177615E+04 -7.416753E+02 + 7.299995E+00 5 5 8.315663E+05 2.884156E+03 + 7.299995E+00 6 6 1.065660E+06 7.835938E+04 + 7.399995E+00 1 1 2.074787E+03 2.083378E+02 + 7.399995E+00 1 5 -1.180199E+04 -6.685760E+02 + 7.399995E+00 2 2 2.370966E+03 4.977119E+02 + 7.399995E+00 2 4 1.507554E+04 2.428592E+03 + 7.399995E+00 3 3 2.132635E+03 6.037473E-01 + 7.399995E+00 4 2 1.509203E+04 2.438173E+03 + 7.399995E+00 4 4 2.738805E+05 1.191124E+04 + 7.399995E+00 5 1 -1.181220E+04 -6.836787E+02 + 7.399995E+00 5 5 8.313497E+05 2.351062E+03 + 7.399995E+00 6 6 1.062236E+06 7.270938E+04 + 7.499995E+00 1 1 2.077932E+03 2.142973E+02 + 7.499995E+00 1 5 -1.182921E+04 -6.054490E+02 + 7.499995E+00 2 2 2.385135E+03 4.902971E+02 + 7.499995E+00 2 4 1.514793E+04 2.374177E+03 + 7.499995E+00 3 3 2.129649E+03 5.671070E-01 + 7.499995E+00 4 2 1.516477E+04 2.383516E+03 + 7.499995E+00 4 4 2.742241E+05 1.155591E+04 + 7.499995E+00 5 1 -1.184038E+04 -6.206963E+02 + 7.499995E+00 5 5 8.310848E+05 1.877915E+03 + 7.499995E+00 6 6 1.058691E+06 6.731214E+04 + 7.599995E+00 1 1 2.081773E+03 2.188925E+02 + 7.599995E+00 1 5 -1.184871E+04 -5.391864E+02 + 7.599995E+00 2 2 2.398670E+03 4.818479E+02 + 7.599995E+00 2 4 1.521542E+04 2.315932E+03 + 7.599995E+00 3 3 2.126565E+03 8.177404E-01 + 7.599995E+00 4 2 1.523262E+04 2.325047E+03 + 7.599995E+00 4 4 2.745371E+05 1.118883E+04 + 7.599995E+00 5 1 -1.186081E+04 -5.544869E+02 + 7.599995E+00 5 5 8.307815E+05 1.463640E+03 + 7.599995E+00 6 6 1.055047E+06 6.219123E+04 + 7.699995E+00 1 1 2.086093E+03 2.222232E+02 + 7.699995E+00 1 5 -1.186067E+04 -4.712784E+02 + 7.699995E+00 2 2 2.411483E+03 4.724805E+02 + 7.699995E+00 2 4 1.527788E+04 2.254471E+03 + 7.699995E+00 3 3 2.123444E+03 1.365790E+00 + 7.699995E+00 4 2 1.529545E+04 2.263340E+03 + 7.699995E+00 4 4 2.748192E+05 1.081316E+04 + 7.699995E+00 5 1 -1.187376E+04 -4.865450E+02 + 7.699995E+00 5 5 8.304544E+05 1.108845E+03 + 7.699995E+00 6 6 1.051326E+06 5.736161E+04 + 7.799995E+00 1 1 2.090712E+03 2.243958E+02 + 7.799995E+00 1 5 -1.186565E+04 -4.029154E+02 + 7.799995E+00 2 2 2.423494E+03 4.623121E+02 + 7.799995E+00 2 4 1.533516E+04 2.190390E+03 + 7.799995E+00 3 3 2.120203E+03 2.217513E+00 + 7.799995E+00 4 2 1.535297E+04 2.198995E+03 + 7.799995E+00 4 4 2.750714E+05 1.043161E+04 + 7.799995E+00 5 1 -1.187954E+04 -4.180592E+02 + 7.799995E+00 5 5 8.301100E+05 8.121940E+02 + 7.799995E+00 6 6 1.047555E+06 5.283081E+04 + 7.899995E+00 1 1 2.095488E+03 2.255192E+02 + 7.899995E+00 1 5 -1.186409E+04 -3.351206E+02 + 7.899995E+00 2 2 2.434678E+03 4.514663E+02 + 7.899995E+00 2 4 1.538724E+04 2.124265E+03 + 7.899995E+00 3 3 2.116944E+03 3.360539E+00 + 7.899995E+00 4 2 1.540535E+04 2.132591E+03 + 7.899995E+00 4 4 2.752947E+05 1.004683E+04 + 7.899995E+00 5 1 -1.187884E+04 -3.501150E+02 + 7.899995E+00 5 5 8.297590E+05 5.689839E+02 + 7.899995E+00 6 6 1.043756E+06 4.859913E+04 + 7.999995E+00 1 1 2.100296E+03 2.256954E+02 + 7.999995E+00 1 5 -1.185661E+04 -2.686796E+02 + 7.999995E+00 2 2 2.444984E+03 4.400553E+02 + 7.999995E+00 2 4 1.543411E+04 2.056642E+03 + 7.999995E+00 3 3 2.113878E+03 4.791380E+00 + 7.999995E+00 4 2 1.545251E+04 2.064698E+03 + 7.999995E+00 4 4 2.754896E+05 9.661417E+03 + 7.999995E+00 5 1 -1.187211E+04 -2.834257E+02 + 7.999995E+00 5 5 8.294042E+05 3.772042E+02 + 7.999995E+00 6 6 1.039954E+06 4.466331E+04 + 8.099995E+00 1 1 2.105043E+03 2.250288E+02 + 8.099995E+00 1 5 -1.184374E+04 -2.042322E+02 + 8.099995E+00 2 2 2.454391E+03 4.281921E+02 + 8.099995E+00 2 4 1.547590E+04 1.988044E+03 + 8.099995E+00 3 3 2.110774E+03 6.490849E+00 + 8.099995E+00 4 2 1.549449E+04 1.995820E+03 + 8.099995E+00 4 4 2.756571E+05 9.277499E+03 + 8.099995E+00 5 1 -1.186001E+04 -2.187066E+02 + 8.099995E+00 5 5 8.290612E+05 2.299006E+02 + 8.099995E+00 6 6 1.036167E+06 4.101462E+04 + 8.199995E+00 1 1 2.109657E+03 2.236175E+02 + 8.199995E+00 1 5 -1.182620E+04 -1.422705E+02 + 8.199995E+00 2 2 2.462898E+03 4.159829E+02 + 8.199995E+00 2 4 1.551268E+04 1.918951E+03 + 8.199995E+00 3 3 2.107748E+03 8.447360E+00 + 8.199995E+00 4 2 1.553151E+04 1.926441E+03 + 8.199995E+00 4 4 2.757995E+05 8.897201E+03 + 8.199995E+00 5 1 -1.184303E+04 -1.564419E+02 + 8.199995E+00 5 5 8.287231E+05 1.246058E+02 + 8.199995E+00 6 6 1.032420E+06 3.764148E+04 + 8.299995E+00 1 1 2.114084E+03 2.215516E+02 + 8.299995E+00 1 5 -1.180446E+04 -8.315440E+01 + 8.299995E+00 2 2 2.470516E+03 4.035282E+02 + 8.299995E+00 2 4 1.554465E+04 1.849790E+03 + 8.299995E+00 3 3 2.104778E+03 1.064496E+01 + 8.299995E+00 4 2 1.556365E+04 1.857000E+03 + 8.299995E+00 4 4 2.759166E+05 8.522346E+03 + 8.299995E+00 5 1 -1.182185E+04 -9.698260E+01 + 8.299995E+00 5 5 8.284002E+05 5.721358E+01 + 8.299995E+00 6 6 1.028722E+06 3.453144E+04 + 8.399996E+00 1 1 2.118270E+03 2.189154E+02 + 8.399996E+00 1 5 -1.177912E+04 -2.715824E+01 + 8.399996E+00 2 2 2.477254E+03 3.909195E+02 + 8.399996E+00 2 4 1.557200E+04 1.780962E+03 + 8.399996E+00 3 3 2.102108E+03 1.305641E+01 + 8.399996E+00 4 2 1.559114E+04 1.787888E+03 + 8.399996E+00 4 4 2.760100E+05 8.154471E+03 + 8.399996E+00 5 1 -1.179728E+04 -4.061836E+01 + 8.399996E+00 5 5 8.280962E+05 2.171890E+01 + 8.399996E+00 6 6 1.025088E+06 3.166960E+04 + 8.499996E+00 1 1 2.122186E+03 2.157903E+02 + 8.499996E+00 1 5 -1.175079E+04 2.553195E+01 + 8.499996E+00 2 2 2.483139E+03 3.782419E+02 + 8.499996E+00 2 4 1.559496E+04 1.712812E+03 + 8.499996E+00 3 3 2.099453E+03 1.566890E+01 + 8.499996E+00 4 2 1.561420E+04 1.719462E+03 + 8.499996E+00 4 4 2.760831E+05 7.794858E+03 + 8.499996E+00 5 1 -1.176919E+04 1.244153E+01 + 8.499996E+00 5 5 8.278067E+05 1.413896E+01 + 8.499996E+00 6 6 1.021530E+06 2.904142E+04 + 8.599997E+00 1 1 2.125807E+03 2.122490E+02 + 8.599997E+00 1 5 -1.171985E+04 7.481567E+01 + 8.599997E+00 2 2 2.488220E+03 3.655711E+02 + 8.599997E+00 2 4 1.561375E+04 1.645655E+03 + 8.599997E+00 3 3 2.097045E+03 1.845528E+01 + 8.599997E+00 4 2 1.563320E+04 1.652033E+03 + 8.599997E+00 4 4 2.761368E+05 7.444747E+03 + 8.599997E+00 5 1 -1.173875E+04 6.210162E+01 + 8.599997E+00 5 5 8.275368E+05 3.248663E+01 + 8.599997E+00 6 6 1.018057E+06 2.663150E+04 + 8.699997E+00 1 1 2.129122E+03 2.083591E+02 + 8.699997E+00 1 5 -1.168679E+04 1.206401E+02 + 8.699997E+00 2 2 2.492500E+03 3.529729E+02 + 8.699997E+00 2 4 1.562877E+04 1.579750E+03 + 8.699997E+00 3 3 2.094784E+03 2.139310E+01 + 8.699997E+00 4 2 1.564822E+04 1.585861E+03 + 8.699997E+00 4 4 2.761712E+05 7.104951E+03 + 8.699997E+00 5 1 -1.170619E+04 1.083546E+02 + 8.699997E+00 5 5 8.272876E+05 7.108610E+01 + 8.699997E+00 6 6 1.014673E+06 2.442441E+04 + 8.799997E+00 1 1 2.132108E+03 2.041796E+02 + 8.799997E+00 1 5 -1.165208E+04 1.630059E+02 + 8.799997E+00 2 2 2.496054E+03 3.405104E+02 + 8.799997E+00 2 4 1.564011E+04 1.515317E+03 + 8.799997E+00 3 3 2.092668E+03 2.446405E+01 + 8.799997E+00 4 2 1.565965E+04 1.521175E+03 + 8.799997E+00 4 4 2.761891E+05 6.776250E+03 + 8.799997E+00 5 1 -1.167177E+04 1.511158E+02 + 8.799997E+00 5 5 8.270590E+05 1.277786E+02 + 8.799997E+00 6 6 1.011389E+06 2.240512E+04 + 8.899998E+00 1 1 2.134787E+03 1.997698E+02 + 8.899998E+00 1 5 -1.161606E+04 2.019601E+02 + 8.899998E+00 2 2 2.498899E+03 3.282321E+02 + 8.899998E+00 2 4 1.564816E+04 1.452547E+03 + 8.899998E+00 3 3 2.090809E+03 2.764819E+01 + 8.899998E+00 4 2 1.566773E+04 1.458146E+03 + 8.899998E+00 4 4 2.761923E+05 6.459099E+03 + 8.899998E+00 5 1 -1.163613E+04 1.904809E+02 + 8.899998E+00 5 5 8.268539E+05 1.984217E+02 + 8.899998E+00 6 6 1.008203E+06 2.055934E+04 + 8.999998E+00 1 1 2.137139E+03 1.951779E+02 + 8.999998E+00 1 5 -1.157913E+04 2.375940E+02 + 8.999998E+00 2 2 2.501099E+03 3.161833E+02 + 8.999998E+00 2 4 1.565312E+04 1.391578E+03 + 8.999998E+00 3 3 2.089147E+03 3.091510E+01 + 8.999998E+00 4 2 1.567273E+04 1.396935E+03 + 8.999998E+00 4 4 2.761813E+05 6.153932E+03 + 8.999998E+00 5 1 -1.159956E+04 2.265213E+02 + 8.999998E+00 5 5 8.266658E+05 2.798887E+02 + 8.999998E+00 6 6 1.005116E+06 1.887311E+04 + 9.099998E+00 1 1 2.139179E+03 1.904497E+02 + 9.099998E+00 1 5 -1.154158E+04 2.699872E+02 + 9.099998E+00 2 2 2.502697E+03 3.043991E+02 + 9.099998E+00 2 4 1.565532E+04 1.332532E+03 + 9.099998E+00 3 3 2.087586E+03 3.426651E+01 + 9.099998E+00 4 2 1.567497E+04 1.337655E+03 + 9.099998E+00 4 4 2.761585E+05 5.861023E+03 + 9.099998E+00 5 1 -1.156220E+04 2.593232E+02 + 9.099998E+00 5 5 8.264962E+05 3.718103E+02 + 9.099998E+00 6 6 1.002138E+06 1.733350E+04 + 9.199999E+00 1 1 2.140917E+03 1.856276E+02 + 9.199999E+00 1 5 -1.150366E+04 2.992821E+02 + 9.199999E+00 2 2 2.503735E+03 2.929104E+02 + 9.199999E+00 2 4 1.565494E+04 1.275499E+03 + 9.199999E+00 3 3 2.086263E+03 3.766659E+01 + 9.199999E+00 4 2 1.567466E+04 1.280395E+03 + 9.199999E+00 4 4 2.761253E+05 5.580450E+03 + 9.199999E+00 5 1 -1.152461E+04 2.890033E+02 + 9.199999E+00 5 5 8.263453E+05 4.689281E+02 + 9.199999E+00 6 6 9.992583E+05 1.592806E+04 + 9.299999E+00 1 1 2.142360E+03 1.807444E+02 + 9.299999E+00 1 5 -1.146577E+04 3.256198E+02 + 9.299999E+00 2 2 2.504263E+03 2.817413E+02 + 9.299999E+00 2 4 1.565232E+04 1.220524E+03 + 9.299999E+00 3 3 2.085159E+03 4.110686E+01 + 9.299999E+00 4 2 1.567206E+04 1.225203E+03 + 9.299999E+00 4 4 2.760819E+05 5.312197E+03 + 9.299999E+00 5 1 -1.148686E+04 3.157380E+02 + 9.299999E+00 5 5 8.262131E+05 5.715813E+02 + 9.299999E+00 6 6 9.964791E+05 1.464538E+04 + 9.400000E+00 1 1 2.143522E+03 1.758346E+02 + 9.400000E+00 1 5 -1.142796E+04 3.491375E+02 + 9.400000E+00 2 2 2.504321E+03 2.709106E+02 + 9.400000E+00 2 4 1.564766E+04 1.167654E+03 + 9.400000E+00 3 3 2.084164E+03 4.457240E+01 + 9.400000E+00 4 2 1.566744E+04 1.172125E+03 + 9.400000E+00 4 4 2.760290E+05 5.056130E+03 + 9.400000E+00 5 1 -1.144924E+04 3.396265E+02 + 9.400000E+00 5 5 8.260980E+05 6.765178E+02 + 9.400000E+00 6 6 9.938049E+05 1.347482E+04 + 9.500000E+00 1 1 2.144417E+03 1.709239E+02 + 9.500000E+00 1 5 -1.139042E+04 3.700067E+02 + 9.500000E+00 2 2 2.503960E+03 2.604297E+02 + 9.500000E+00 2 4 1.564121E+04 1.116898E+03 + 9.500000E+00 3 3 2.083362E+03 4.804810E+01 + 9.500000E+00 4 2 1.566090E+04 1.121167E+03 + 9.500000E+00 4 4 2.759722E+05 4.812139E+03 + 9.500000E+00 5 1 -1.141188E+04 3.608785E+02 + 9.500000E+00 5 5 8.260032E+05 7.829916E+02 + 9.500000E+00 6 6 9.912272E+05 1.240666E+04 + 9.600000E+00 1 1 2.145063E+03 1.660383E+02 + 9.600000E+00 1 5 -1.135346E+04 3.883761E+02 + 9.600000E+00 2 2 2.503218E+03 2.503093E+02 + 9.600000E+00 2 4 1.563313E+04 1.068251E+03 + 9.600000E+00 3 3 2.082737E+03 5.152150E+01 + 9.600000E+00 4 2 1.565285E+04 1.072326E+03 + 9.600000E+00 4 4 2.759075E+05 4.579906E+03 + 9.600000E+00 5 1 -1.137502E+04 3.796046E+02 + 9.600000E+00 5 5 8.259168E+05 8.892158E+02 + 9.600000E+00 6 6 9.887462E+05 1.143185E+04 + 9.700001E+00 1 1 2.145472E+03 1.611957E+02 + 9.700001E+00 1 5 -1.131713E+04 4.044158E+02 + 9.700001E+00 2 2 2.502142E+03 2.405545E+02 + 9.700001E+00 2 4 1.562367E+04 1.021697E+03 + 9.700001E+00 3 3 2.082276E+03 5.498514E+01 + 9.700001E+00 4 2 1.564341E+04 1.025586E+03 + 9.700001E+00 4 4 2.758360E+05 4.359174E+03 + 9.700001E+00 5 1 -1.133862E+04 3.960084E+02 + 9.700001E+00 5 5 8.258537E+05 9.951490E+02 + 9.700001E+00 6 6 9.863594E+05 1.054168E+04 + 9.800001E+00 1 1 2.145671E+03 1.564165E+02 + 9.800001E+00 1 5 -1.128141E+04 4.183023E+02 + 9.800001E+00 2 2 2.500755E+03 2.311662E+02 + 9.800001E+00 2 4 1.561294E+04 9.772015E+02 + 9.800001E+00 3 3 2.081937E+03 5.842216E+01 + 9.800001E+00 4 2 1.563265E+04 9.809180E+02 + 9.800001E+00 4 4 2.757614E+05 4.149600E+03 + 9.800001E+00 5 1 -1.130307E+04 4.102207E+02 + 9.800001E+00 5 5 8.257966E+05 1.098057E+03 + 9.800001E+00 6 6 9.840654E+05 9.728938E+03 + 9.900002E+00 1 1 2.145658E+03 1.517129E+02 + 9.900002E+00 1 5 -1.124661E+04 4.301864E+02 + 9.900002E+00 2 2 2.499100E+03 2.221429E+02 + 9.900002E+00 2 4 1.560114E+04 9.347197E+02 + 9.900002E+00 3 3 2.081755E+03 6.183162E+01 + 9.900002E+00 4 2 1.562081E+04 9.382680E+02 + 9.900002E+00 4 4 2.756829E+05 3.950739E+03 + 9.900002E+00 5 1 -1.126836E+04 4.224308E+02 + 9.900002E+00 5 5 8.257466E+05 1.198787E+03 + 9.900002E+00 6 6 9.818568E+05 8.986440E+03 + 1.000000E+01 1 1 2.145465E+03 1.470993E+02 + 1.000000E+01 1 5 -1.121264E+04 4.402153E+02 + 1.000000E+01 2 2 2.497211E+03 2.134834E+02 + 1.000000E+01 2 4 1.558852E+04 8.942076E+02 + 1.000000E+01 3 3 2.081736E+03 6.520229E+01 + 1.000000E+01 4 2 1.560818E+04 8.975975E+02 + 1.000000E+01 4 4 2.756025E+05 3.762234E+03 + 1.000000E+01 5 1 -1.123443E+04 4.327898E+02 + 1.000000E+01 5 5 8.257079E+05 1.295562E+03 + 1.000000E+01 6 6 9.797342E+05 8.307854E+03 + 1.010000E+01 1 1 2.145102E+03 1.425842E+02 + 1.010000E+01 1 5 -1.117965E+04 4.485279E+02 + 1.010000E+01 2 2 2.495111E+03 2.051799E+02 + 1.010000E+01 2 4 1.557513E+04 8.556025E+02 + 1.010000E+01 3 3 2.081813E+03 6.852578E+01 + 1.010000E+01 4 2 1.559459E+04 8.588407E+02 + 1.010000E+01 4 4 2.755189E+05 3.583694E+03 + 1.010000E+01 5 1 -1.120152E+04 4.414140E+02 + 1.010000E+01 5 5 8.256924E+05 1.389465E+03 + 1.010000E+01 6 6 9.776943E+05 7.687389E+03 + 1.020000E+01 1 1 2.144577E+03 1.381759E+02 + 1.020000E+01 1 5 -1.114771E+04 4.553047E+02 + 1.020000E+01 2 2 2.492841E+03 1.972271E+02 + 1.020000E+01 2 4 1.556101E+04 8.188411E+02 + 1.020000E+01 3 3 2.082054E+03 7.180158E+01 + 1.020000E+01 4 2 1.558062E+04 8.219407E+02 + 1.020000E+01 4 4 2.754333E+05 3.414641E+03 + 1.020000E+01 5 1 -1.116960E+04 4.484713E+02 + 1.020000E+01 5 5 8.256652E+05 1.478140E+03 + 1.020000E+01 6 6 9.757329E+05 7.119680E+03 + 1.030000E+01 1 1 2.143912E+03 1.338805E+02 + 1.030000E+01 1 5 -1.111675E+04 4.606376E+02 + 1.030000E+01 2 2 2.490404E+03 1.896145E+02 + 1.030000E+01 2 4 1.554646E+04 7.838583E+02 + 1.030000E+01 3 3 2.082380E+03 7.501859E+01 + 1.030000E+01 4 2 1.556596E+04 7.868245E+02 + 1.030000E+01 4 4 2.753469E+05 3.254677E+03 + 1.030000E+01 5 1 -1.113858E+04 4.540824E+02 + 1.030000E+01 5 5 8.256712E+05 1.562478E+03 + 1.030000E+01 6 6 9.738463E+05 6.599924E+03 + 1.040000E+01 1 1 2.143127E+03 1.297027E+02 + 1.040000E+01 1 5 -1.108676E+04 4.646914E+02 + 1.040000E+01 2 2 2.487852E+03 1.823339E+02 + 1.040000E+01 2 4 1.553150E+04 7.505894E+02 + 1.040000E+01 3 3 2.082812E+03 7.818211E+01 + 1.040000E+01 4 2 1.555099E+04 7.534227E+02 + 1.040000E+01 4 4 2.752601E+05 3.103319E+03 + 1.040000E+01 5 1 -1.110876E+04 4.584017E+02 + 1.040000E+01 5 5 8.256668E+05 1.642683E+03 + 1.040000E+01 6 6 9.720320E+05 6.123848E+03 + 1.050000E+01 1 1 2.142212E+03 1.256457E+02 + 1.050000E+01 1 5 -1.105802E+04 4.675668E+02 + 1.050000E+01 2 2 2.485180E+03 1.753749E+02 + 1.050000E+01 2 4 1.551622E+04 7.189579E+02 + 1.050000E+01 3 3 2.083348E+03 8.127702E+01 + 1.050000E+01 4 2 1.553561E+04 7.216663E+02 + 1.050000E+01 4 4 2.751720E+05 2.960191E+03 + 1.050000E+01 5 1 -1.107979E+04 4.615325E+02 + 1.050000E+01 5 5 8.256658E+05 1.717788E+03 + 1.050000E+01 6 6 9.702887E+05 5.687414E+03 + 1.060000E+01 1 1 2.141205E+03 1.217116E+02 + 1.060000E+01 1 5 -1.103006E+04 4.693828E+02 + 1.060000E+01 2 2 2.482431E+03 1.687262E+02 + 1.060000E+01 2 4 1.550066E+04 6.888983E+02 + 1.060000E+01 3 3 2.083969E+03 8.431265E+01 + 1.060000E+01 4 2 1.552005E+04 6.914917E+02 + 1.060000E+01 4 4 2.750842E+05 2.824860E+03 + 1.060000E+01 5 1 -1.105195E+04 4.635920E+02 + 1.060000E+01 5 5 8.256779E+05 1.788114E+03 + 1.060000E+01 6 6 9.686122E+05 5.287014E+03 + 1.070000E+01 1 1 2.140107E+03 1.179014E+02 + 1.070000E+01 1 5 -1.100345E+04 4.702292E+02 + 1.070000E+01 2 2 2.479598E+03 1.623760E+02 + 1.070000E+01 2 4 1.548502E+04 6.603346E+02 + 1.070000E+01 3 3 2.084695E+03 8.728065E+01 + 1.070000E+01 4 2 1.550429E+04 6.628145E+02 + 1.070000E+01 4 4 2.749969E+05 2.696889E+03 + 1.070000E+01 5 1 -1.102518E+04 4.646789E+02 + 1.070000E+01 5 5 8.256959E+05 1.853688E+03 + 1.070000E+01 6 6 9.669974E+05 4.919559E+03 + 1.080000E+01 1 1 2.138926E+03 1.142137E+02 + 1.080000E+01 1 5 -1.097759E+04 4.702310E+02 + 1.080000E+01 2 2 2.476715E+03 1.563144E+02 + 1.080000E+01 2 4 1.546918E+04 6.331996E+02 + 1.080000E+01 3 3 2.085490E+03 9.018382E+01 + 1.080000E+01 4 2 1.548842E+04 6.355766E+02 + 1.080000E+01 4 4 2.749096E+05 2.575933E+03 + 1.080000E+01 5 1 -1.099937E+04 4.648986E+02 + 1.080000E+01 5 5 8.257069E+05 1.914251E+03 + 1.080000E+01 6 6 9.654451E+05 4.581916E+03 + 1.090001E+01 1 1 2.137670E+03 1.106502E+02 + 1.090001E+01 1 5 -1.095299E+04 4.694513E+02 + 1.090001E+01 2 2 2.473783E+03 1.505286E+02 + 1.090001E+01 2 4 1.545333E+04 6.074255E+02 + 1.090001E+01 3 3 2.086341E+03 9.301959E+01 + 1.090001E+01 4 2 1.547258E+04 6.097039E+02 + 1.090001E+01 4 4 2.748224E+05 2.461529E+03 + 1.090001E+01 5 1 -1.097454E+04 4.643502E+02 + 1.090001E+01 5 5 8.257381E+05 1.970232E+03 + 1.090001E+01 6 6 9.639502E+05 4.271438E+03 + 1.100001E+01 1 1 2.136364E+03 1.072084E+02 + 1.100001E+01 1 5 -1.092918E+04 4.680009E+02 + 1.100001E+01 2 2 2.470831E+03 1.450070E+02 + 1.100001E+01 2 4 1.543755E+04 5.829437E+02 + 1.100001E+01 3 3 2.087261E+03 9.578189E+01 + 1.100001E+01 4 2 1.545666E+04 5.851293E+02 + 1.100001E+01 4 4 2.747374E+05 2.353424E+03 + 1.100001E+01 5 1 -1.095086E+04 4.630921E+02 + 1.100001E+01 5 5 8.257575E+05 2.021854E+03 + 1.100001E+01 6 6 9.625105E+05 3.985717E+03 + 1.110001E+01 1 1 2.134999E+03 1.038862E+02 + 1.110001E+01 1 5 -1.090647E+04 4.659317E+02 + 1.110001E+01 2 2 2.467854E+03 1.397381E+02 + 1.110001E+01 2 4 1.542175E+04 5.596920E+02 + 1.110001E+01 3 3 2.088266E+03 9.847754E+01 + 1.110001E+01 4 2 1.544090E+04 5.617880E+02 + 1.110001E+01 4 4 2.746530E+05 2.251185E+03 + 1.110001E+01 5 1 -1.092806E+04 4.612215E+02 + 1.110001E+01 5 5 8.257892E+05 2.068661E+03 + 1.110001E+01 6 6 9.611222E+05 3.722606E+03 + 1.120001E+01 1 1 2.133589E+03 1.006825E+02 + 1.120001E+01 1 5 -1.088462E+04 4.633327E+02 + 1.120001E+01 2 2 2.464867E+03 1.347108E+02 + 1.120001E+01 2 4 1.540606E+04 5.376023E+02 + 1.120001E+01 3 3 2.089307E+03 1.011065E+02 + 1.120001E+01 4 2 1.542512E+04 5.396155E+02 + 1.120001E+01 4 4 2.745692E+05 2.154438E+03 + 1.120001E+01 5 1 -1.090628E+04 4.588030E+02 + 1.120001E+01 5 5 8.258142E+05 2.111276E+03 + 1.120001E+01 6 6 9.597874E+05 3.480049E+03 + 1.130001E+01 1 1 2.132145E+03 9.759343E+01 + 1.130001E+01 1 5 -1.086372E+04 4.602499E+02 + 1.130001E+01 2 2 2.461884E+03 1.299144E+02 + 1.130001E+01 2 4 1.539056E+04 5.166194E+02 + 1.130001E+01 3 3 2.090402E+03 1.036618E+02 + 1.130001E+01 4 2 1.540961E+04 5.185527E+02 + 1.130001E+01 4 4 2.744871E+05 2.062993E+03 + 1.130001E+01 5 1 -1.088540E+04 4.559028E+02 + 1.130001E+01 5 5 8.258488E+05 2.149967E+03 + 1.130001E+01 6 6 9.584996E+05 3.256323E+03 + 1.140001E+01 1 1 2.130662E+03 9.461726E+01 + 1.140001E+01 1 5 -1.084381E+04 4.567544E+02 + 1.140001E+01 2 2 2.458892E+03 1.253371E+02 + 1.140001E+01 2 4 1.537518E+04 4.966835E+02 + 1.140001E+01 3 3 2.091546E+03 1.061545E+02 + 1.140001E+01 4 2 1.539409E+04 4.985375E+02 + 1.140001E+01 4 4 2.744073E+05 1.976416E+03 + 1.140001E+01 5 1 -1.086519E+04 4.525659E+02 + 1.140001E+01 5 5 8.258861E+05 2.184761E+03 + 1.140001E+01 6 6 9.572577E+05 3.049736E+03 + 1.150001E+01 1 1 2.129159E+03 9.174998E+01 + 1.150001E+01 1 5 -1.082464E+04 4.528948E+02 + 1.150001E+01 2 2 2.455925E+03 1.209695E+02 + 1.150001E+01 2 4 1.535997E+04 4.777368E+02 + 1.150001E+01 3 3 2.092718E+03 1.085756E+02 + 1.150001E+01 4 2 1.537888E+04 4.795195E+02 + 1.150001E+01 4 4 2.743275E+05 1.894500E+03 + 1.150001E+01 5 1 -1.084610E+04 4.488746E+02 + 1.150001E+01 5 5 8.259156E+05 2.215852E+03 + 1.150001E+01 6 6 9.560608E+05 2.858746E+03 + 1.160001E+01 1 1 2.127638E+03 8.898923E+01 + 1.160001E+01 1 5 -1.080628E+04 4.487243E+02 + 1.160001E+01 2 2 2.452972E+03 1.168008E+02 + 1.160001E+01 2 4 1.534493E+04 4.597283E+02 + 1.160001E+01 3 3 2.093933E+03 1.109317E+02 + 1.160001E+01 4 2 1.536379E+04 4.614388E+02 + 1.160001E+01 4 4 2.742490E+05 1.816965E+03 + 1.160001E+01 5 1 -1.082768E+04 4.448535E+02 + 1.160001E+01 5 5 8.259459E+05 2.243294E+03 + 1.160001E+01 6 6 9.549045E+05 2.682162E+03 + 1.170001E+01 1 1 2.126100E+03 8.633121E+01 + 1.170001E+01 1 5 -1.078880E+04 4.442795E+02 + 1.170001E+01 2 2 2.450047E+03 1.128212E+02 + 1.170001E+01 2 4 1.533011E+04 4.426050E+02 + 1.170001E+01 3 3 2.095180E+03 1.132257E+02 + 1.170001E+01 4 2 1.534890E+04 4.442519E+02 + 1.170001E+01 4 4 2.741736E+05 1.743508E+03 + 1.170001E+01 5 1 -1.081031E+04 4.405491E+02 + 1.170001E+01 5 5 8.259912E+05 2.267439E+03 + 1.170001E+01 6 6 9.537879E+05 2.518749E+03 + 1.180001E+01 1 1 2.124550E+03 8.377260E+01 + 1.180001E+01 1 5 -1.077201E+04 4.396074E+02 + 1.180001E+01 2 2 2.447151E+03 1.090218E+02 + 1.180001E+01 2 4 1.531550E+04 4.263197E+02 + 1.180001E+01 3 3 2.096469E+03 1.154567E+02 + 1.180001E+01 4 2 1.533431E+04 4.279048E+02 + 1.180001E+01 4 4 2.740985E+05 1.673901E+03 + 1.180001E+01 5 1 -1.079330E+04 4.360281E+02 + 1.180001E+01 5 5 8.260214E+05 2.288327E+03 + 1.180001E+01 6 6 9.527109E+05 2.367267E+03 + 1.190001E+01 1 1 2.122995E+03 8.131019E+01 + 1.190001E+01 1 5 -1.075599E+04 4.347395E+02 + 1.190001E+01 2 2 2.444285E+03 1.053936E+02 + 1.190001E+01 2 4 1.530115E+04 4.108290E+02 + 1.190001E+01 3 3 2.097785E+03 1.176215E+02 + 1.190001E+01 4 2 1.531993E+04 4.123534E+02 + 1.190001E+01 4 4 2.740252E+05 1.607962E+03 + 1.190001E+01 5 1 -1.077738E+04 4.312895E+02 + 1.190001E+01 5 5 8.260572E+05 2.306321E+03 + 1.190001E+01 6 6 9.516712E+05 2.226846E+03 + 1.200001E+01 1 1 2.121434E+03 7.894044E+01 + 1.200001E+01 1 5 -1.074063E+04 4.297101E+02 + 1.200001E+01 2 2 2.441449E+03 1.019280E+02 + 1.200001E+01 2 4 1.528709E+04 3.960870E+02 + 1.200001E+01 3 3 2.099118E+03 1.197286E+02 + 1.200001E+01 4 2 1.530580E+04 3.975568E+02 + 1.200001E+01 4 4 2.739543E+05 1.545426E+03 + 1.200001E+01 5 1 -1.076188E+04 4.263846E+02 + 1.200001E+01 5 5 8.260926E+05 2.321299E+03 + 1.200001E+01 6 6 9.506649E+05 2.096431E+03 + 1.210001E+01 1 1 2.119878E+03 7.666012E+01 + 1.210001E+01 1 5 -1.072603E+04 4.245444E+02 + 1.210001E+01 2 2 2.438656E+03 9.861677E+01 + 1.210001E+01 2 4 1.527324E+04 3.820515E+02 + 1.210001E+01 3 3 2.100477E+03 1.217811E+02 + 1.210001E+01 4 2 1.529188E+04 3.834702E+02 + 1.210001E+01 4 4 2.738842E+05 1.486106E+03 + 1.210001E+01 5 1 -1.074728E+04 4.213397E+02 + 1.210001E+01 5 5 8.261277E+05 2.333569E+03 + 1.210001E+01 6 6 9.496948E+05 1.975356E+03 + 1.220001E+01 1 1 2.118321E+03 7.446576E+01 + 1.220001E+01 1 5 -1.071203E+04 4.192750E+02 + 1.220001E+01 2 2 2.435906E+03 9.545207E+01 + 1.220001E+01 2 4 1.525966E+04 3.686877E+02 + 1.220001E+01 3 3 2.101841E+03 1.237651E+02 + 1.220001E+01 4 2 1.527830E+04 3.700542E+02 + 1.220001E+01 4 4 2.738165E+05 1.429824E+03 + 1.220001E+01 5 1 -1.073302E+04 4.161903E+02 + 1.220001E+01 5 5 8.261690E+05 2.343536E+03 + 1.220001E+01 6 6 9.487539E+05 1.862762E+03 + 1.230001E+01 1 1 2.116769E+03 7.235358E+01 + 1.230001E+01 1 5 -1.069859E+04 4.139212E+02 + 1.230001E+01 2 2 2.433190E+03 9.242647E+01 + 1.230001E+01 2 4 1.524637E+04 3.559544E+02 + 1.230001E+01 3 3 2.103232E+03 1.256946E+02 + 1.230001E+01 4 2 1.526485E+04 3.572729E+02 + 1.230001E+01 4 4 2.737493E+05 1.376394E+03 + 1.230001E+01 5 1 -1.071966E+04 4.109430E+02 + 1.230001E+01 5 5 8.261975E+05 2.351000E+03 + 1.230001E+01 6 6 9.478432E+05 1.758019E+03 + 1.240001E+01 1 1 2.115230E+03 7.032137E+01 + 1.240001E+01 1 5 -1.068579E+04 4.085052E+02 + 1.240001E+01 2 2 2.430518E+03 8.953334E+01 + 1.240001E+01 2 4 1.523330E+04 3.438208E+02 + 1.240001E+01 3 3 2.104630E+03 1.275721E+02 + 1.240001E+01 4 2 1.525182E+04 3.450954E+02 + 1.240001E+01 4 4 2.736838E+05 1.325624E+03 + 1.240001E+01 5 1 -1.070680E+04 4.056277E+02 + 1.240001E+01 5 5 8.262332E+05 2.356286E+03 + 1.240001E+01 6 6 9.469648E+05 1.660457E+03 + 1.250001E+01 1 1 2.113698E+03 6.836533E+01 + 1.250001E+01 1 5 -1.067347E+04 4.030426E+02 + 1.250001E+01 2 2 2.427898E+03 8.676517E+01 + 1.250001E+01 2 4 1.522051E+04 3.322523E+02 + 1.250001E+01 3 3 2.106044E+03 1.293969E+02 + 1.250001E+01 4 2 1.523901E+04 3.334811E+02 + 1.250001E+01 4 4 2.736212E+05 1.277405E+03 + 1.250001E+01 5 1 -1.069435E+04 4.002670E+02 + 1.250001E+01 5 5 8.262628E+05 2.359874E+03 + 1.250001E+01 6 6 9.461124E+05 1.569530E+03 + 1.260001E+01 1 1 2.112180E+03 6.648254E+01 + 1.260001E+01 1 5 -1.066185E+04 3.975528E+02 + 1.260001E+01 2 2 2.425312E+03 8.411627E+01 + 1.260001E+01 2 4 1.520798E+04 3.212180E+02 + 1.260001E+01 3 3 2.107452E+03 1.311695E+02 + 1.260001E+01 4 2 1.522640E+04 3.224063E+02 + 1.260001E+01 4 4 2.735586E+05 1.231549E+03 + 1.260001E+01 5 1 -1.068282E+04 3.948681E+02 + 1.260001E+01 5 5 8.263016E+05 2.361182E+03 + 1.260001E+01 6 6 9.452871E+05 1.484709E+03 + 1.270001E+01 1 1 2.110668E+03 6.466995E+01 + 1.270001E+01 1 5 -1.065067E+04 3.920472E+02 + 1.270001E+01 2 2 2.422773E+03 8.158038E+01 + 1.270001E+01 2 4 1.519573E+04 3.106885E+02 + 1.270001E+01 3 3 2.108894E+03 1.328926E+02 + 1.270001E+01 4 2 1.521411E+04 3.118379E+02 + 1.270001E+01 4 4 2.734992E+05 1.187930E+03 + 1.270001E+01 5 1 -1.067151E+04 3.894570E+02 + 1.270001E+01 5 5 8.263347E+05 2.360984E+03 + 1.270001E+01 6 6 9.444876E+05 1.405492E+03 + 1.280001E+01 1 1 2.109177E+03 6.292468E+01 + 1.280001E+01 1 5 -1.063990E+04 3.865463E+02 + 1.280001E+01 2 2 2.420291E+03 7.915163E+01 + 1.280001E+01 2 4 1.518379E+04 3.006381E+02 + 1.280001E+01 3 3 2.110333E+03 1.345651E+02 + 1.280001E+01 4 2 1.520208E+04 3.017477E+02 + 1.280001E+01 4 4 2.734404E+05 1.146440E+03 + 1.280001E+01 5 1 -1.066063E+04 3.840481E+02 + 1.280001E+01 5 5 8.263615E+05 2.359094E+03 + 1.280001E+01 6 6 9.437115E+05 1.331517E+03 + 1.290001E+01 1 1 2.107699E+03 6.124414E+01 + 1.290001E+01 1 5 -1.062966E+04 3.810516E+02 + 1.290001E+01 2 2 2.417847E+03 7.682533E+01 + 1.290001E+01 2 4 1.517203E+04 2.910394E+02 + 1.290001E+01 3 3 2.111769E+03 1.361919E+02 + 1.290001E+01 4 2 1.519037E+04 2.921137E+02 + 1.290001E+01 4 4 2.733828E+05 1.106919E+03 + 1.290001E+01 5 1 -1.065035E+04 3.786324E+02 + 1.290001E+01 5 5 8.263971E+05 2.355927E+03 + 1.290001E+01 6 6 9.429603E+05 1.262324E+03 + 1.300001E+01 1 1 2.106239E+03 5.962539E+01 + 1.300001E+01 1 5 -1.061992E+04 3.755821E+02 + 1.300001E+01 2 2 2.415445E+03 7.459554E+01 + 1.300001E+01 2 4 1.516055E+04 2.818689E+02 + 1.300001E+01 3 3 2.113217E+03 1.377701E+02 + 1.300001E+01 4 2 1.517887E+04 2.829082E+02 + 1.300001E+01 4 4 2.733258E+05 1.069281E+03 + 1.300001E+01 5 1 -1.064062E+04 3.732501E+02 + 1.300001E+01 5 5 8.264338E+05 2.351114E+03 + 1.300001E+01 6 6 9.422327E+05 1.197565E+03 + 1.310001E+01 1 1 2.104794E+03 5.806616E+01 + 1.310001E+01 1 5 -1.061043E+04 3.701445E+02 + 1.310001E+01 2 2 2.413100E+03 7.245785E+01 + 1.310001E+01 2 4 1.514936E+04 2.731026E+02 + 1.310001E+01 3 3 2.114666E+03 1.393071E+02 + 1.310001E+01 4 2 1.516762E+04 2.741091E+02 + 1.310001E+01 4 4 2.732713E+05 1.033417E+03 + 1.310001E+01 5 1 -1.063108E+04 3.678736E+02 + 1.310001E+01 5 5 8.264561E+05 2.345078E+03 + 1.310001E+01 6 6 9.415256E+05 1.136929E+03 + 1.320001E+01 1 1 2.103368E+03 5.656347E+01 + 1.320001E+01 1 5 -1.060147E+04 3.647414E+02 + 1.320001E+01 2 2 2.410791E+03 7.040732E+01 + 1.320001E+01 2 4 1.513839E+04 2.647195E+02 + 1.320001E+01 3 3 2.116120E+03 1.407977E+02 + 1.320001E+01 4 2 1.515654E+04 2.656937E+02 + 1.320001E+01 4 4 2.732178E+05 9.992125E+02 + 1.320001E+01 5 1 -1.062196E+04 3.625555E+02 + 1.320001E+01 5 5 8.264901E+05 2.337926E+03 + 1.320001E+01 6 6 9.408400E+05 1.080085E+03 + 1.330001E+01 1 1 2.101961E+03 5.511522E+01 + 1.330001E+01 1 5 -1.059288E+04 3.593916E+02 + 1.330001E+01 2 2 2.408532E+03 6.844022E+01 + 1.330001E+01 2 4 1.512766E+04 2.567007E+02 + 1.330001E+01 3 3 2.117555E+03 1.422505E+02 + 1.330001E+01 4 2 1.514582E+04 2.576465E+02 + 1.330001E+01 4 4 2.731667E+05 9.666104E+02 + 1.330001E+01 5 1 -1.061341E+04 3.572649E+02 + 1.330001E+01 5 5 8.265143E+05 2.329631E+03 + 1.330001E+01 6 6 9.401749E+05 1.026808E+03 + 1.340001E+01 1 1 2.100570E+03 5.371916E+01 + 1.340001E+01 1 5 -1.058467E+04 3.540811E+02 + 1.340001E+01 2 2 2.406317E+03 6.655184E+01 + 1.340001E+01 2 4 1.511717E+04 2.490257E+02 + 1.340001E+01 3 3 2.119003E+03 1.436666E+02 + 1.340001E+01 4 2 1.513535E+04 2.499415E+02 + 1.340001E+01 4 4 2.731150E+05 9.354659E+02 + 1.340001E+01 5 1 -1.060515E+04 3.520350E+02 + 1.340001E+01 5 5 8.265472E+05 2.320512E+03 + 1.340001E+01 6 6 9.395264E+05 9.767414E+02 + 1.350002E+01 1 1 2.099205E+03 5.237311E+01 + 1.350002E+01 1 5 -1.057670E+04 3.488342E+02 + 1.350002E+01 2 2 2.404147E+03 6.473885E+01 + 1.350002E+01 2 4 1.510695E+04 2.416740E+02 + 1.350002E+01 3 3 2.120441E+03 1.450347E+02 + 1.350002E+01 4 2 1.512504E+04 2.425639E+02 + 1.350002E+01 4 4 2.730665E+05 9.057045E+02 + 1.350002E+01 5 1 -1.059721E+04 3.468398E+02 + 1.350002E+01 5 5 8.265730E+05 2.310202E+03 + 1.350002E+01 6 6 9.388989E+05 9.297352E+02 + 1.360002E+01 1 1 2.097856E+03 5.107493E+01 + 1.360002E+01 1 5 -1.056917E+04 3.436465E+02 + 1.360002E+01 2 2 2.402019E+03 6.299704E+01 + 1.360002E+01 2 4 1.509691E+04 2.346342E+02 + 1.360002E+01 3 3 2.121882E+03 1.463661E+02 + 1.360002E+01 4 2 1.511499E+04 2.354969E+02 + 1.360002E+01 4 4 2.730179E+05 8.773123E+02 + 1.360002E+01 5 1 -1.058957E+04 3.417159E+02 + 1.360002E+01 5 5 8.265993E+05 2.299260E+03 + 1.360002E+01 6 6 9.382879E+05 8.855363E+02 + 1.370002E+01 1 1 2.096529E+03 4.982215E+01 + 1.370002E+01 1 5 -1.056192E+04 3.385222E+02 + 1.370002E+01 2 2 2.399936E+03 6.132322E+01 + 1.370002E+01 2 4 1.508712E+04 2.278861E+02 + 1.370002E+01 3 3 2.123323E+03 1.476655E+02 + 1.370002E+01 4 2 1.510520E+04 2.287258E+02 + 1.370002E+01 4 4 2.729711E+05 8.501495E+02 + 1.370002E+01 5 1 -1.058229E+04 3.366470E+02 + 1.370002E+01 5 5 8.266270E+05 2.287270E+03 + 1.370002E+01 6 6 9.376954E+05 8.439335E+02 + 1.380002E+01 1 1 2.095216E+03 4.861351E+01 + 1.380002E+01 1 5 -1.055499E+04 3.334639E+02 + 1.380002E+01 2 2 2.397894E+03 5.971392E+01 + 1.380002E+01 2 4 1.507760E+04 2.214170E+02 + 1.380002E+01 3 3 2.124749E+03 1.489263E+02 + 1.380002E+01 4 2 1.509560E+04 2.222306E+02 + 1.380002E+01 4 4 2.729254E+05 8.241840E+02 + 1.380002E+01 5 1 -1.057513E+04 3.316495E+02 + 1.380002E+01 5 5 8.266494E+05 2.275118E+03 + 1.380002E+01 6 6 9.371171E+05 8.048163E+02 + 1.390002E+01 1 1 2.093933E+03 4.744718E+01 + 1.390002E+01 1 5 -1.054833E+04 3.284787E+02 + 1.390002E+01 2 2 2.395897E+03 5.816627E+01 + 1.390002E+01 2 4 1.506825E+04 2.152124E+02 + 1.390002E+01 3 3 2.126180E+03 1.501581E+02 + 1.390002E+01 4 2 1.508624E+04 2.160014E+02 + 1.390002E+01 4 4 2.728797E+05 7.993529E+02 + 1.390002E+01 5 1 -1.056856E+04 3.267156E+02 + 1.390002E+01 5 5 8.266769E+05 2.261749E+03 + 1.390002E+01 6 6 9.365554E+05 7.679352E+02 + 1.400002E+01 1 1 2.092667E+03 4.632070E+01 + 1.400002E+01 1 5 -1.054198E+04 3.235636E+02 + 1.400002E+01 2 2 2.393941E+03 5.667736E+01 + 1.400002E+01 2 4 1.505914E+04 2.092574E+02 + 1.400002E+01 3 3 2.127597E+03 1.513539E+02 + 1.400002E+01 4 2 1.507707E+04 2.100287E+02 + 1.400002E+01 4 4 2.728362E+05 7.755717E+02 + 1.400002E+01 5 1 -1.056215E+04 3.218545E+02 + 1.400002E+01 5 5 8.266979E+05 2.248237E+03 + 1.400002E+01 6 6 9.360094E+05 7.331602E+02 + 1.410002E+01 1 1 2.091419E+03 4.523307E+01 + 1.410002E+01 1 5 -1.053582E+04 3.187205E+02 + 1.410002E+01 2 2 2.392023E+03 5.524433E+01 + 1.410002E+01 2 4 1.505023E+04 2.035427E+02 + 1.410002E+01 3 3 2.129027E+03 1.525149E+02 + 1.410002E+01 4 2 1.506817E+04 2.042896E+02 + 1.410002E+01 4 4 2.727942E+05 7.528195E+02 + 1.410002E+01 5 1 -1.055597E+04 3.170571E+02 + 1.410002E+01 5 5 8.267213E+05 2.234132E+03 + 1.410002E+01 6 6 9.354781E+05 7.003802E+02 + 1.420002E+01 1 1 2.090195E+03 4.418240E+01 + 1.420002E+01 1 5 -1.052992E+04 3.139538E+02 + 1.420002E+01 2 2 2.390145E+03 5.386454E+01 + 1.420002E+01 2 4 1.504148E+04 1.980522E+02 + 1.420002E+01 3 3 2.130434E+03 1.536453E+02 + 1.420002E+01 4 2 1.505939E+04 1.987785E+02 + 1.420002E+01 4 4 2.727521E+05 7.310227E+02 + 1.420002E+01 5 1 -1.055006E+04 3.123406E+02 + 1.420002E+01 5 5 8.267371E+05 2.219379E+03 + 1.420002E+01 6 6 9.349612E+05 6.694067E+02 + 1.430002E+01 1 1 2.088986E+03 4.316705E+01 + 1.430002E+01 1 5 -1.052431E+04 3.092633E+02 + 1.430002E+01 2 2 2.388311E+03 5.253564E+01 + 1.430002E+01 2 4 1.503297E+04 1.927776E+02 + 1.430002E+01 3 3 2.131842E+03 1.547496E+02 + 1.430002E+01 4 2 1.505086E+04 1.934848E+02 + 1.430002E+01 4 4 2.727125E+05 7.101144E+02 + 1.430002E+01 5 1 -1.054430E+04 3.076932E+02 + 1.430002E+01 5 5 8.267571E+05 2.204616E+03 + 1.430002E+01 6 6 9.344564E+05 6.401974E+02 + 1.440002E+01 1 1 2.087800E+03 4.218559E+01 + 1.440002E+01 1 5 -1.051887E+04 3.046481E+02 + 1.440002E+01 2 2 2.386503E+03 5.125491E+01 + 1.440002E+01 2 4 1.502466E+04 1.877069E+02 + 1.440002E+01 3 3 2.133250E+03 1.558226E+02 + 1.440002E+01 4 2 1.504250E+04 1.883958E+02 + 1.440002E+01 4 4 2.726728E+05 6.900616E+02 + 1.440002E+01 5 1 -1.053893E+04 3.031208E+02 + 1.440002E+01 5 5 8.267798E+05 2.189091E+03 + 1.440002E+01 6 6 9.339664E+05 6.125146E+02 + 1.450002E+01 1 1 2.086630E+03 4.123684E+01 + 1.450002E+01 1 5 -1.051367E+04 3.001110E+02 + 1.450002E+01 2 2 2.384744E+03 5.002060E+01 + 1.450002E+01 2 4 1.501651E+04 1.828318E+02 + 1.450002E+01 3 3 2.134643E+03 1.568708E+02 + 1.450002E+01 4 2 1.503431E+04 1.835009E+02 + 1.450002E+01 4 4 2.726331E+05 6.708359E+02 + 1.450002E+01 5 1 -1.053365E+04 2.986237E+02 + 1.450002E+01 5 5 8.268024E+05 2.173301E+03 + 1.450002E+01 6 6 9.334872E+05 5.863661E+02 + 1.460002E+01 1 1 2.085483E+03 4.031923E+01 + 1.460002E+01 1 5 -1.050862E+04 2.956489E+02 + 1.460002E+01 2 2 2.383020E+03 4.882990E+01 + 1.460002E+01 2 4 1.500857E+04 1.781401E+02 + 1.460002E+01 3 3 2.136024E+03 1.578860E+02 + 1.460002E+01 4 2 1.502636E+04 1.787920E+02 + 1.460002E+01 4 4 2.725966E+05 6.523698E+02 + 1.460002E+01 5 1 -1.052853E+04 2.942045E+02 + 1.460002E+01 5 5 8.268162E+05 2.157346E+03 + 1.460002E+01 6 6 9.330229E+05 5.616545E+02 + 1.470002E+01 1 1 2.084361E+03 3.943158E+01 + 1.470002E+01 1 5 -1.050388E+04 2.912632E+02 + 1.470002E+01 2 2 2.381325E+03 4.768178E+01 + 1.470002E+01 2 4 1.500078E+04 1.736267E+02 + 1.470002E+01 3 3 2.137404E+03 1.588762E+02 + 1.470002E+01 4 2 1.501855E+04 1.742603E+02 + 1.470002E+01 4 4 2.725603E+05 6.346516E+02 + 1.470002E+01 5 1 -1.052373E+04 2.898618E+02 + 1.470002E+01 5 5 8.268378E+05 2.141207E+03 + 1.470002E+01 6 6 9.325686E+05 5.382223E+02 + 1.480002E+01 1 1 2.083249E+03 3.857278E+01 + 1.480002E+01 1 5 -1.049920E+04 2.869577E+02 + 1.480002E+01 2 2 2.379666E+03 4.657336E+01 + 1.480002E+01 2 4 1.499321E+04 1.692799E+02 + 1.480002E+01 3 3 2.138773E+03 1.598436E+02 + 1.480002E+01 4 2 1.501094E+04 1.698969E+02 + 1.480002E+01 4 4 2.725249E+05 6.176179E+02 + 1.480002E+01 5 1 -1.051915E+04 2.855866E+02 + 1.480002E+01 5 5 8.268512E+05 2.124499E+03 + 1.480002E+01 6 6 9.321253E+05 5.160158E+02 + 1.490002E+01 1 1 2.082164E+03 3.774136E+01 + 1.490002E+01 1 5 -1.049480E+04 2.827262E+02 + 1.490002E+01 2 2 2.378054E+03 4.550396E+01 + 1.490002E+01 2 4 1.498577E+04 1.650944E+02 + 1.490002E+01 3 3 2.140139E+03 1.607877E+02 + 1.490002E+01 4 2 1.500344E+04 1.656964E+02 + 1.490002E+01 4 4 2.724897E+05 6.012692E+02 + 1.490002E+01 5 1 -1.051463E+04 2.813920E+02 + 1.490002E+01 5 5 8.268743E+05 2.108086E+03 + 1.490002E+01 6 6 9.316939E+05 4.950198E+02 + 1.500002E+01 1 1 2.081091E+03 3.693649E+01 + 1.500002E+01 1 5 -1.049057E+04 2.785714E+02 + 1.500002E+01 2 2 2.376464E+03 4.447095E+01 + 1.500002E+01 2 4 1.497853E+04 1.610604E+02 + 1.500002E+01 3 3 2.141480E+03 1.617033E+02 + 1.500002E+01 4 2 1.499619E+04 1.616474E+02 + 1.500002E+01 4 4 2.724553E+05 5.855309E+02 + 1.500002E+01 5 1 -1.051033E+04 2.772770E+02 + 1.500002E+01 5 5 8.268852E+05 2.091138E+03 + 1.500002E+01 6 6 9.312731E+05 4.750409E+02 + 1.510002E+01 1 1 2.080040E+03 3.615698E+01 + 1.510002E+01 1 5 -1.048644E+04 2.744925E+02 + 1.510002E+01 2 2 2.374910E+03 4.347293E+01 + 1.510002E+01 2 4 1.497140E+04 1.571724E+02 + 1.510002E+01 3 3 2.142820E+03 1.626021E+02 + 1.510002E+01 4 2 1.498905E+04 1.577446E+02 + 1.510002E+01 4 4 2.724219E+05 5.703980E+02 + 1.510002E+01 5 1 -1.050612E+04 2.732291E+02 + 1.510002E+01 5 5 8.268959E+05 2.074233E+03 + 1.510002E+01 6 6 9.308612E+05 4.561140E+02 + 1.520002E+01 1 1 2.079005E+03 3.540192E+01 + 1.520002E+01 1 5 -1.048248E+04 2.704842E+02 + 1.520002E+01 2 2 2.373389E+03 4.250876E+01 + 1.520002E+01 2 4 1.496444E+04 1.534227E+02 + 1.520002E+01 3 3 2.144167E+03 1.634731E+02 + 1.520002E+01 4 2 1.498212E+04 1.539825E+02 + 1.520002E+01 4 4 2.723893E+05 5.558321E+02 + 1.520002E+01 5 1 -1.050218E+04 2.692577E+02 + 1.520002E+01 5 5 8.269194E+05 2.057312E+03 + 1.520002E+01 6 6 9.304605E+05 4.380757E+02 + 1.530002E+01 1 1 2.077990E+03 3.467028E+01 + 1.530002E+01 1 5 -1.047869E+04 2.665553E+02 + 1.530002E+01 2 2 2.371897E+03 4.157639E+01 + 1.530002E+01 2 4 1.495767E+04 1.498059E+02 + 1.530002E+01 3 3 2.145491E+03 1.643267E+02 + 1.530002E+01 4 2 1.497529E+04 1.503531E+02 + 1.530002E+01 4 4 2.723578E+05 5.418108E+02 + 1.530002E+01 5 1 -1.049838E+04 2.653550E+02 + 1.530002E+01 5 5 8.269261E+05 2.040102E+03 + 1.530002E+01 6 6 9.300689E+05 4.209901E+02 + 1.540002E+01 1 1 2.076993E+03 3.396120E+01 + 1.540002E+01 1 5 -1.047507E+04 2.626942E+02 + 1.540002E+01 2 2 2.370436E+03 4.067495E+01 + 1.540002E+01 2 4 1.495101E+04 1.463179E+02 + 1.540002E+01 3 3 2.146810E+03 1.651566E+02 + 1.540002E+01 4 2 1.496861E+04 1.468497E+02 + 1.540002E+01 4 4 2.723265E+05 5.283426E+02 + 1.540002E+01 5 1 -1.049469E+04 2.615269E+02 + 1.540002E+01 5 5 8.269438E+05 2.023000E+03 + 1.540002E+01 6 6 9.296864E+05 4.047350E+02 + 1.550002E+01 1 1 2.076013E+03 3.327344E+01 + 1.550002E+01 1 5 -1.047153E+04 2.589065E+02 + 1.550002E+01 2 2 2.369007E+03 3.980273E+01 + 1.550002E+01 2 4 1.494455E+04 1.429486E+02 + 1.550002E+01 3 3 2.148116E+03 1.659677E+02 + 1.550002E+01 4 2 1.496212E+04 1.434692E+02 + 1.550002E+01 4 4 2.722966E+05 5.153308E+02 + 1.550002E+01 5 1 -1.049112E+04 2.577680E+02 + 1.550002E+01 5 5 8.269541E+05 2.005682E+03 + 1.550002E+01 6 6 9.293126E+05 3.892980E+02 + 1.560002E+01 1 1 2.075051E+03 3.260694E+01 + 1.560002E+01 1 5 -1.046815E+04 2.551922E+02 + 1.560002E+01 2 2 2.367606E+03 3.895897E+01 + 1.560002E+01 2 4 1.493817E+04 1.396942E+02 + 1.560002E+01 3 3 2.149407E+03 1.667584E+02 + 1.560002E+01 4 2 1.495576E+04 1.402030E+02 + 1.560002E+01 4 4 2.722664E+05 5.027727E+02 + 1.560002E+01 5 1 -1.048774E+04 2.540764E+02 + 1.560002E+01 5 5 8.269706E+05 1.988470E+03 + 1.560002E+01 6 6 9.289479E+05 3.745744E+02 + 1.570002E+01 1 1 2.074105E+03 3.196018E+01 + 1.570002E+01 1 5 -1.046487E+04 2.515442E+02 + 1.570002E+01 2 2 2.366228E+03 3.814221E+01 + 1.570002E+01 2 4 1.493197E+04 1.365507E+02 + 1.570002E+01 3 3 2.150707E+03 1.675297E+02 + 1.570002E+01 4 2 1.494948E+04 1.370478E+02 + 1.570002E+01 4 4 2.722373E+05 4.906886E+02 + 1.570002E+01 5 1 -1.048435E+04 2.504556E+02 + 1.570002E+01 5 5 8.269825E+05 1.971414E+03 + 1.570002E+01 6 6 9.285927E+05 3.605742E+02 + 1.580002E+01 1 1 2.073177E+03 3.133257E+01 + 1.580002E+01 1 5 -1.046171E+04 2.479682E+02 + 1.580002E+01 2 2 2.364879E+03 3.735137E+01 + 1.580002E+01 2 4 1.492585E+04 1.335133E+02 + 1.580002E+01 3 3 2.151987E+03 1.682820E+02 + 1.580002E+01 4 2 1.494334E+04 1.340023E+02 + 1.580002E+01 4 4 2.722095E+05 4.790283E+02 + 1.580002E+01 5 1 -1.048124E+04 2.469087E+02 + 1.580002E+01 5 5 8.269909E+05 1.953933E+03 + 1.580002E+01 6 6 9.282444E+05 3.471773E+02 + 1.590002E+01 1 1 2.072261E+03 3.072359E+01 + 1.590002E+01 1 5 -1.045869E+04 2.444564E+02 + 1.590002E+01 2 2 2.363563E+03 3.658521E+01 + 1.590002E+01 2 4 1.491990E+04 1.305775E+02 + 1.590002E+01 3 3 2.153257E+03 1.690168E+02 + 1.590002E+01 4 2 1.493744E+04 1.310534E+02 + 1.590002E+01 4 4 2.721814E+05 4.677970E+02 + 1.590002E+01 5 1 -1.047818E+04 2.434140E+02 + 1.590002E+01 5 5 8.270022E+05 1.936942E+03 + 1.590002E+01 6 6 9.279032E+05 3.344916E+02 + 1.600002E+01 1 1 2.071366E+03 3.013219E+01 + 1.600002E+01 1 5 -1.045578E+04 2.410121E+02 + 1.600002E+01 2 2 2.362272E+03 3.584298E+01 + 1.600002E+01 2 4 1.491406E+04 1.277372E+02 + 1.600002E+01 3 3 2.154517E+03 1.697373E+02 + 1.600002E+01 4 2 1.493153E+04 1.282041E+02 + 1.600002E+01 4 4 2.721539E+05 4.569208E+02 + 1.600002E+01 5 1 -1.047521E+04 2.400044E+02 + 1.600002E+01 5 5 8.270164E+05 1.919702E+03 + 1.600002E+01 6 6 9.275708E+05 3.223495E+02 + 1.610003E+01 1 1 2.070484E+03 2.955817E+01 + 1.610003E+01 1 5 -1.045294E+04 2.376343E+02 + 1.610003E+01 2 2 2.361004E+03 3.512328E+01 + 1.610003E+01 2 4 1.490836E+04 1.249913E+02 + 1.610003E+01 3 3 2.155781E+03 1.704411E+02 + 1.610003E+01 4 2 1.492584E+04 1.254452E+02 + 1.610003E+01 4 4 2.721288E+05 4.464518E+02 + 1.610003E+01 5 1 -1.047237E+04 2.366466E+02 + 1.610003E+01 5 5 8.270226E+05 1.902542E+03 + 1.610003E+01 6 6 9.272455E+05 3.107794E+02 + 1.620003E+01 1 1 2.069616E+03 2.900060E+01 + 1.620003E+01 1 5 -1.045020E+04 2.343210E+02 + 1.620003E+01 2 2 2.359761E+03 3.442596E+01 + 1.620003E+01 2 4 1.490279E+04 1.223333E+02 + 1.620003E+01 3 3 2.157026E+03 1.711245E+02 + 1.620003E+01 4 2 1.492020E+04 1.227781E+02 + 1.620003E+01 4 4 2.721026E+05 4.363372E+02 + 1.620003E+01 5 1 -1.046956E+04 2.333506E+02 + 1.620003E+01 5 5 8.270325E+05 1.885493E+03 + 1.620003E+01 6 6 9.269280E+05 2.997424E+02 + 1.630003E+01 1 1 2.068766E+03 2.845874E+01 + 1.630003E+01 1 5 -1.044763E+04 2.310678E+02 + 1.630003E+01 2 2 2.358545E+03 3.374945E+01 + 1.630003E+01 2 4 1.489730E+04 1.197599E+02 + 1.630003E+01 3 3 2.158250E+03 1.717934E+02 + 1.630003E+01 4 2 1.491471E+04 1.201951E+02 + 1.630003E+01 4 4 2.720770E+05 4.265562E+02 + 1.630003E+01 5 1 -1.046698E+04 2.301221E+02 + 1.630003E+01 5 5 8.270442E+05 1.868405E+03 + 1.630003E+01 6 6 9.266187E+05 2.891885E+02 + 1.640003E+01 1 1 2.067928E+03 2.793233E+01 + 1.640003E+01 1 5 -1.044513E+04 2.278778E+02 + 1.640003E+01 2 2 2.357353E+03 3.309323E+01 + 1.640003E+01 2 4 1.489195E+04 1.172682E+02 + 1.640003E+01 3 3 2.159478E+03 1.724470E+02 + 1.640003E+01 4 2 1.490937E+04 1.176936E+02 + 1.640003E+01 4 4 2.720522E+05 4.170867E+02 + 1.640003E+01 5 1 -1.046442E+04 2.269559E+02 + 1.640003E+01 5 5 8.270501E+05 1.851661E+03 + 1.640003E+01 6 6 9.263129E+05 2.791281E+02 + 1.650003E+01 1 1 2.067111E+03 2.742050E+01 + 1.650003E+01 1 5 -1.044264E+04 2.247480E+02 + 1.650003E+01 2 2 2.356185E+03 3.245648E+01 + 1.650003E+01 2 4 1.488669E+04 1.148537E+02 + 1.650003E+01 3 3 2.160696E+03 1.730935E+02 + 1.650003E+01 4 2 1.490406E+04 1.152725E+02 + 1.650003E+01 4 4 2.720282E+05 4.079402E+02 + 1.650003E+01 5 1 -1.046200E+04 2.238463E+02 + 1.650003E+01 5 5 8.270595E+05 1.834824E+03 + 1.650003E+01 6 6 9.260153E+05 2.694910E+02 + 1.660003E+01 1 1 2.066301E+03 2.692302E+01 + 1.660003E+01 1 5 -1.044032E+04 2.216787E+02 + 1.660003E+01 2 2 2.355030E+03 3.183842E+01 + 1.660003E+01 2 4 1.488153E+04 1.125153E+02 + 1.660003E+01 3 3 2.161904E+03 1.737168E+02 + 1.660003E+01 4 2 1.489894E+04 1.129257E+02 + 1.660003E+01 4 4 2.720042E+05 3.991012E+02 + 1.660003E+01 5 1 -1.045955E+04 2.207931E+02 + 1.660003E+01 5 5 8.270729E+05 1.817911E+03 + 1.660003E+01 6 6 9.257228E+05 2.602718E+02 + 1.670003E+01 1 1 2.065512E+03 2.643911E+01 + 1.670003E+01 1 5 -1.043803E+04 2.186671E+02 + 1.670003E+01 2 2 2.353910E+03 3.123835E+01 + 1.670003E+01 2 4 1.487652E+04 1.102490E+02 + 1.670003E+01 3 3 2.163101E+03 1.743276E+02 + 1.670003E+01 4 2 1.489390E+04 1.106499E+02 + 1.670003E+01 4 4 2.719815E+05 3.905549E+02 + 1.670003E+01 5 1 -1.045730E+04 2.178046E+02 + 1.670003E+01 5 5 8.270786E+05 1.801339E+03 + 1.670003E+01 6 6 9.254366E+05 2.514675E+02 + 1.680003E+01 1 1 2.064729E+03 2.596842E+01 + 1.680003E+01 1 5 -1.043582E+04 2.157118E+02 + 1.680003E+01 2 2 2.352802E+03 3.065560E+01 + 1.680003E+01 2 4 1.487159E+04 1.080519E+02 + 1.680003E+01 3 3 2.164293E+03 1.749266E+02 + 1.680003E+01 4 2 1.488892E+04 1.084453E+02 + 1.680003E+01 4 4 2.719588E+05 3.822675E+02 + 1.680003E+01 5 1 -1.045502E+04 2.148672E+02 + 1.680003E+01 5 5 8.270844E+05 1.784897E+03 + 1.680003E+01 6 6 9.251572E+05 2.430606E+02 + 1.690003E+01 1 1 2.063964E+03 2.551030E+01 + 1.690003E+01 1 5 -1.043371E+04 2.128134E+02 + 1.690003E+01 2 2 2.351719E+03 3.008941E+01 + 1.690003E+01 2 4 1.486673E+04 1.059205E+02 + 1.690003E+01 3 3 2.165474E+03 1.755150E+02 + 1.690003E+01 4 2 1.488408E+04 1.063057E+02 + 1.690003E+01 4 4 2.719358E+05 3.742552E+02 + 1.690003E+01 5 1 -1.045286E+04 2.119846E+02 + 1.690003E+01 5 5 8.270939E+05 1.768436E+03 + 1.690003E+01 6 6 9.248847E+05 2.349536E+02 + 1.700003E+01 1 1 2.063209E+03 2.506457E+01 + 1.700003E+01 1 5 -1.043165E+04 2.099697E+02 + 1.700003E+01 2 2 2.350652E+03 2.953933E+01 + 1.700003E+01 2 4 1.486197E+04 1.038516E+02 + 1.700003E+01 3 3 2.166653E+03 1.760840E+02 + 1.700003E+01 4 2 1.487930E+04 1.042311E+02 + 1.700003E+01 4 4 2.719141E+05 3.664562E+02 + 1.700003E+01 5 1 -1.045088E+04 2.091586E+02 + 1.700003E+01 5 5 8.271021E+05 1.752063E+03 + 1.700003E+01 6 6 9.246164E+05 2.272261E+02 + 1.710003E+01 1 1 2.062470E+03 2.463075E+01 + 1.710003E+01 1 5 -1.042968E+04 2.071769E+02 + 1.710003E+01 2 2 2.349615E+03 2.900439E+01 + 1.710003E+01 2 4 1.485737E+04 1.018465E+02 + 1.710003E+01 3 3 2.167818E+03 1.766457E+02 + 1.710003E+01 4 2 1.487468E+04 1.022170E+02 + 1.710003E+01 4 4 2.718934E+05 3.589480E+02 + 1.710003E+01 5 1 -1.044881E+04 2.063858E+02 + 1.710003E+01 5 5 8.271076E+05 1.735944E+03 + 1.710003E+01 6 6 9.243549E+05 2.198451E+02 + 1.720003E+01 1 1 2.061742E+03 2.420838E+01 + 1.720003E+01 1 5 -1.042781E+04 2.044397E+02 + 1.720003E+01 2 2 2.348598E+03 2.848452E+01 + 1.720003E+01 2 4 1.485284E+04 9.989874E+01 + 1.720003E+01 3 3 2.168974E+03 1.771941E+02 + 1.720003E+01 4 2 1.487010E+04 1.002615E+02 + 1.720003E+01 4 4 2.718733E+05 3.516508E+02 + 1.720003E+01 5 1 -1.044685E+04 2.036589E+02 + 1.720003E+01 5 5 8.271099E+05 1.719808E+03 + 1.720003E+01 6 6 9.240961E+05 2.127342E+02 + 1.730003E+01 1 1 2.061026E+03 2.379716E+01 + 1.730003E+01 1 5 -1.042594E+04 2.017511E+02 + 1.730003E+01 2 2 2.347590E+03 2.797889E+01 + 1.730003E+01 2 4 1.484834E+04 9.800805E+01 + 1.730003E+01 3 3 2.170129E+03 1.777283E+02 + 1.730003E+01 4 2 1.486565E+04 9.836308E+01 + 1.730003E+01 4 4 2.718520E+05 3.445775E+02 + 1.730003E+01 5 1 -1.044493E+04 2.009904E+02 + 1.730003E+01 5 5 8.271202E+05 1.704027E+03 + 1.730003E+01 6 6 9.238454E+05 2.059225E+02 + 1.740003E+01 1 1 2.060324E+03 2.339627E+01 + 1.740003E+01 1 5 -1.042415E+04 1.991144E+02 + 1.740003E+01 2 2 2.346608E+03 2.748712E+01 + 1.740003E+01 2 4 1.484396E+04 9.617191E+01 + 1.740003E+01 3 3 2.171259E+03 1.782491E+02 + 1.740003E+01 4 2 1.486128E+04 9.652121E+01 + 1.740003E+01 4 4 2.718323E+05 3.377369E+02 + 1.740003E+01 5 1 -1.044318E+04 1.983685E+02 + 1.740003E+01 5 5 8.271267E+05 1.688139E+03 + 1.740003E+01 6 6 9.235982E+05 1.994094E+02 + 1.750003E+01 1 1 2.059634E+03 2.300596E+01 + 1.750003E+01 1 5 -1.042243E+04 1.965280E+02 + 1.750003E+01 2 2 2.345637E+03 2.700851E+01 + 1.750003E+01 2 4 1.483970E+04 9.438749E+01 + 1.750003E+01 3 3 2.172393E+03 1.787659E+02 + 1.750003E+01 4 2 1.485691E+04 9.473090E+01 + 1.750003E+01 4 4 2.718115E+05 3.310837E+02 + 1.750003E+01 5 1 -1.044150E+04 1.957994E+02 + 1.750003E+01 5 5 8.271300E+05 1.672497E+03 + 1.750003E+01 6 6 9.233557E+05 1.931149E+02 + 1.760003E+01 1 1 2.058954E+03 2.262552E+01 + 1.760003E+01 1 5 -1.042073E+04 1.939864E+02 + 1.760003E+01 2 2 2.344687E+03 2.654274E+01 + 1.760003E+01 2 4 1.483547E+04 9.265537E+01 + 1.760003E+01 3 3 2.173507E+03 1.792697E+02 + 1.760003E+01 4 2 1.485272E+04 9.298941E+01 + 1.760003E+01 4 4 2.717932E+05 3.246413E+02 + 1.760003E+01 5 1 -1.043976E+04 1.932696E+02 + 1.760003E+01 5 5 8.271320E+05 1.657040E+03 + 1.760003E+01 6 6 9.231200E+05 1.871032E+02 + 1.770003E+01 1 1 2.058286E+03 2.225474E+01 + 1.770003E+01 1 5 -1.041911E+04 1.914942E+02 + 1.770003E+01 2 2 2.343760E+03 2.608939E+01 + 1.770003E+01 2 4 1.483137E+04 9.096959E+01 + 1.770003E+01 3 3 2.174629E+03 1.797623E+02 + 1.770003E+01 4 2 1.484857E+04 9.129957E+01 + 1.770003E+01 4 4 2.717740E+05 3.183698E+02 + 1.770003E+01 5 1 -1.043807E+04 1.907895E+02 + 1.770003E+01 5 5 8.271378E+05 1.641710E+03 + 1.770003E+01 6 6 9.228866E+05 1.813262E+02 + 1.780003E+01 1 1 2.057630E+03 2.189306E+01 + 1.780003E+01 1 5 -1.041756E+04 1.890476E+02 + 1.780003E+01 2 2 2.342843E+03 2.564802E+01 + 1.780003E+01 2 4 1.482732E+04 8.933209E+01 + 1.780003E+01 3 3 2.175732E+03 1.802451E+02 + 1.780003E+01 4 2 1.484451E+04 8.965611E+01 + 1.780003E+01 4 4 2.717548E+05 3.123017E+02 + 1.780003E+01 5 1 -1.043651E+04 1.883601E+02 + 1.780003E+01 5 5 8.271411E+05 1.626481E+03 + 1.780003E+01 6 6 9.226586E+05 1.758039E+02 + 1.790003E+01 1 1 2.056979E+03 2.154061E+01 + 1.790003E+01 1 5 -1.041605E+04 1.866453E+02 + 1.790003E+01 2 2 2.341945E+03 2.521803E+01 + 1.790003E+01 2 4 1.482331E+04 8.773805E+01 + 1.790003E+01 3 3 2.176833E+03 1.807188E+02 + 1.790003E+01 4 2 1.484051E+04 8.805619E+01 + 1.790003E+01 4 4 2.717376E+05 3.063807E+02 + 1.790003E+01 5 1 -1.043498E+04 1.859703E+02 + 1.790003E+01 5 5 8.271443E+05 1.611391E+03 + 1.790003E+01 6 6 9.224355E+05 1.704742E+02 + 1.800003E+01 1 1 2.056345E+03 2.119668E+01 + 1.800003E+01 1 5 -1.041461E+04 1.842881E+02 + 1.800003E+01 2 2 2.341061E+03 2.479934E+01 + 1.800003E+01 2 4 1.481941E+04 8.618948E+01 + 1.800003E+01 3 3 2.177930E+03 1.811826E+02 + 1.800003E+01 4 2 1.483661E+04 8.650233E+01 + 1.800003E+01 4 4 2.717198E+05 3.006520E+02 + 1.800003E+01 5 1 -1.043344E+04 1.836254E+02 + 1.800003E+01 5 5 8.271499E+05 1.596410E+03 + 1.800003E+01 6 6 9.222149E+05 1.653296E+02 + 1.810003E+01 1 1 2.055720E+03 2.086128E+01 + 1.810003E+01 1 5 -1.041317E+04 1.819731E+02 + 1.810003E+01 2 2 2.340197E+03 2.439112E+01 + 1.810003E+01 2 4 1.481561E+04 8.468084E+01 + 1.810003E+01 3 3 2.179028E+03 1.816369E+02 + 1.810003E+01 4 2 1.483279E+04 8.498753E+01 + 1.810003E+01 4 4 2.717028E+05 2.950850E+02 + 1.810003E+01 5 1 -1.043208E+04 1.813213E+02 + 1.810003E+01 5 5 8.271562E+05 1.581557E+03 + 1.810003E+01 6 6 9.220011E+05 1.603738E+02 + 1.820003E+01 1 1 2.055104E+03 2.053393E+01 + 1.820003E+01 1 5 -1.041181E+04 1.796993E+02 + 1.820003E+01 2 2 2.339348E+03 2.399349E+01 + 1.820003E+01 2 4 1.481184E+04 8.321352E+01 + 1.820003E+01 3 3 2.180094E+03 1.820844E+02 + 1.820003E+01 4 2 1.482906E+04 8.351611E+01 + 1.820003E+01 4 4 2.716851E+05 2.896564E+02 + 1.820003E+01 5 1 -1.043072E+04 1.790640E+02 + 1.820003E+01 5 5 8.271657E+05 1.567039E+03 + 1.820003E+01 6 6 9.217888E+05 1.556339E+02 + 1.830003E+01 1 1 2.054502E+03 2.021455E+01 + 1.830003E+01 1 5 -1.041048E+04 1.774697E+02 + 1.830003E+01 2 2 2.338513E+03 2.360573E+01 + 1.830003E+01 2 4 1.480814E+04 8.178493E+01 + 1.830003E+01 3 3 2.181152E+03 1.825197E+02 + 1.830003E+01 4 2 1.482531E+04 8.208099E+01 + 1.830003E+01 4 4 2.716680E+05 2.844013E+02 + 1.830003E+01 5 1 -1.042929E+04 1.768469E+02 + 1.830003E+01 5 5 8.271634E+05 1.552448E+03 + 1.830003E+01 6 6 9.215821E+05 1.510820E+02 + 1.840003E+01 1 1 2.053909E+03 1.990290E+01 + 1.840003E+01 1 5 -1.040918E+04 1.752774E+02 + 1.840003E+01 2 2 2.337692E+03 2.322764E+01 + 1.840003E+01 2 4 1.480456E+04 8.039359E+01 + 1.840003E+01 3 3 2.182225E+03 1.829501E+02 + 1.840003E+01 4 2 1.482169E+04 8.068610E+01 + 1.840003E+01 4 4 2.716522E+05 2.792823E+02 + 1.840003E+01 5 1 -1.042802E+04 1.746610E+02 + 1.840003E+01 5 5 8.271635E+05 1.538224E+03 + 1.840003E+01 6 6 9.213790E+05 1.466810E+02 + 1.850003E+01 1 1 2.053320E+03 1.959850E+01 + 1.850003E+01 1 5 -1.040793E+04 1.731259E+02 + 1.850003E+01 2 2 2.336886E+03 2.285887E+01 + 1.850003E+01 2 4 1.480099E+04 7.903979E+01 + 1.850003E+01 3 3 2.183267E+03 1.833716E+02 + 1.850003E+01 4 2 1.481814E+04 7.932382E+01 + 1.850003E+01 4 4 2.716357E+05 2.743032E+02 + 1.850003E+01 5 1 -1.042672E+04 1.725223E+02 + 1.850003E+01 5 5 8.271721E+05 1.523950E+03 + 1.850003E+01 6 6 9.211794E+05 1.424494E+02 + 1.860003E+01 1 1 2.052746E+03 1.930129E+01 + 1.860003E+01 1 5 -1.040671E+04 1.710121E+02 + 1.860003E+01 2 2 2.336096E+03 2.249916E+01 + 1.860003E+01 2 4 1.479749E+04 7.771886E+01 + 1.860003E+01 3 3 2.184322E+03 1.837843E+02 + 1.860003E+01 4 2 1.481466E+04 7.800043E+01 + 1.860003E+01 4 4 2.716191E+05 2.694428E+02 + 1.860003E+01 5 1 -1.042551E+04 1.704225E+02 + 1.860003E+01 5 5 8.271738E+05 1.509914E+03 + 1.860003E+01 6 6 9.209849E+05 1.383857E+02 + 1.870004E+01 1 1 2.052183E+03 1.901094E+01 + 1.870004E+01 1 5 -1.040557E+04 1.689366E+02 + 1.870004E+01 2 2 2.335311E+03 2.214833E+01 + 1.870004E+01 2 4 1.479409E+04 7.643378E+01 + 1.870004E+01 3 3 2.185352E+03 1.841807E+02 + 1.870004E+01 4 2 1.481118E+04 7.670943E+01 + 1.870004E+01 4 4 2.716044E+05 2.647291E+02 + 1.870004E+01 5 1 -1.042427E+04 1.683552E+02 + 1.870004E+01 5 5 8.271734E+05 1.495996E+03 + 1.870004E+01 6 6 9.207909E+05 1.344660E+02 + 1.880004E+01 1 1 2.051628E+03 1.872726E+01 + 1.880004E+01 1 5 -1.040444E+04 1.668994E+02 + 1.880004E+01 2 2 2.334550E+03 2.180602E+01 + 1.880004E+01 2 4 1.479072E+04 7.518122E+01 + 1.880004E+01 3 3 2.186382E+03 1.845765E+02 + 1.880004E+01 4 2 1.480782E+04 7.545424E+01 + 1.880004E+01 4 4 2.715896E+05 2.601515E+02 + 1.880004E+01 5 1 -1.042326E+04 1.663279E+02 + 1.880004E+01 5 5 8.271764E+05 1.482188E+03 + 1.880004E+01 6 6 9.206021E+05 1.306727E+02 + 1.890004E+01 1 1 2.051073E+03 1.845038E+01 + 1.890004E+01 1 5 -1.040334E+04 1.648945E+02 + 1.890004E+01 2 2 2.333793E+03 2.147164E+01 + 1.890004E+01 2 4 1.478741E+04 7.396050E+01 + 1.890004E+01 3 3 2.187406E+03 1.849668E+02 + 1.890004E+01 4 2 1.480450E+04 7.422672E+01 + 1.890004E+01 4 4 2.715736E+05 2.557082E+02 + 1.890004E+01 5 1 -1.042207E+04 1.643343E+02 + 1.890004E+01 5 5 8.271801E+05 1.468711E+03 + 1.890004E+01 6 6 9.204173E+05 1.270228E+02 + 1.900004E+01 1 1 2.050531E+03 1.817950E+01 + 1.900004E+01 1 5 -1.040224E+04 1.629282E+02 + 1.900004E+01 2 2 2.333057E+03 2.114543E+01 + 1.900004E+01 2 4 1.478419E+04 7.276846E+01 + 1.900004E+01 3 3 2.188413E+03 1.853446E+02 + 1.900004E+01 4 2 1.480126E+04 7.303304E+01 + 1.900004E+01 4 4 2.715604E+05 2.513305E+02 + 1.900004E+01 5 1 -1.042097E+04 1.623760E+02 + 1.900004E+01 5 5 8.271833E+05 1.455291E+03 + 1.900004E+01 6 6 9.202351E+05 1.234795E+02 + 1.910004E+01 1 1 2.050006E+03 1.791492E+01 + 1.910004E+01 1 5 -1.040121E+04 1.609936E+02 + 1.910004E+01 2 2 2.332327E+03 2.082673E+01 + 1.910004E+01 2 4 1.478098E+04 7.160725E+01 + 1.910004E+01 3 3 2.189432E+03 1.857226E+02 + 1.910004E+01 4 2 1.479808E+04 7.186718E+01 + 1.910004E+01 4 4 2.715451E+05 2.471007E+02 + 1.910004E+01 5 1 -1.041999E+04 1.604564E+02 + 1.910004E+01 5 5 8.271872E+05 1.441932E+03 + 1.910004E+01 6 6 9.200559E+05 1.201205E+02 + 1.920004E+01 1 1 2.049483E+03 1.765621E+01 + 1.920004E+01 1 5 -1.040026E+04 1.590964E+02 + 1.920004E+01 2 2 2.331615E+03 2.051542E+01 + 1.920004E+01 2 4 1.477788E+04 7.047442E+01 + 1.920004E+01 3 3 2.190425E+03 1.860850E+02 + 1.920004E+01 4 2 1.479489E+04 7.072854E+01 + 1.920004E+01 4 4 2.715305E+05 2.429766E+02 + 1.920004E+01 5 1 -1.041893E+04 1.585637E+02 + 1.920004E+01 5 5 8.271846E+05 1.428767E+03 + 1.920004E+01 6 6 9.198796E+05 1.168207E+02 + 1.930004E+01 1 1 2.048965E+03 1.740320E+01 + 1.930004E+01 1 5 -1.039924E+04 1.572290E+02 + 1.930004E+01 2 2 2.330912E+03 2.021156E+01 + 1.930004E+01 2 4 1.477479E+04 6.936960E+01 + 1.930004E+01 3 3 2.191418E+03 1.864453E+02 + 1.930004E+01 4 2 1.479185E+04 6.962022E+01 + 1.930004E+01 4 4 2.715169E+05 2.389581E+02 + 1.930004E+01 5 1 -1.041793E+04 1.567098E+02 + 1.930004E+01 5 5 8.271876E+05 1.415792E+03 + 1.930004E+01 6 6 9.197066E+05 1.136690E+02 + 1.940004E+01 1 1 2.048461E+03 1.715591E+01 + 1.940004E+01 1 5 -1.039833E+04 1.553941E+02 + 1.940004E+01 2 2 2.330222E+03 1.991453E+01 + 1.940004E+01 2 4 1.477176E+04 6.829047E+01 + 1.940004E+01 3 3 2.192412E+03 1.867998E+02 + 1.940004E+01 4 2 1.478880E+04 6.853768E+01 + 1.940004E+01 4 4 2.715025E+05 2.350184E+02 + 1.940004E+01 5 1 -1.041693E+04 1.548798E+02 + 1.940004E+01 5 5 8.271892E+05 1.402910E+03 + 1.940004E+01 6 6 9.195372E+05 1.106253E+02 + 1.950004E+01 1 1 2.047965E+03 1.691395E+01 + 1.950004E+01 1 5 -1.039738E+04 1.535927E+02 + 1.950004E+01 2 2 2.329543E+03 1.962435E+01 + 1.950004E+01 2 4 1.476878E+04 6.723826E+01 + 1.950004E+01 3 3 2.193378E+03 1.871498E+02 + 1.950004E+01 4 2 1.478586E+04 6.748221E+01 + 1.950004E+01 4 4 2.714897E+05 2.312206E+02 + 1.950004E+01 5 1 -1.041604E+04 1.530889E+02 + 1.950004E+01 5 5 8.271920E+05 1.390185E+03 + 1.950004E+01 6 6 9.193708E+05 1.076600E+02 + 1.960004E+01 1 1 2.047471E+03 1.667731E+01 + 1.960004E+01 1 5 -1.039650E+04 1.518212E+02 + 1.960004E+01 2 2 2.328873E+03 1.934076E+01 + 1.960004E+01 2 4 1.476587E+04 6.621005E+01 + 1.960004E+01 3 3 2.194353E+03 1.874906E+02 + 1.960004E+01 4 2 1.478289E+04 6.645112E+01 + 1.960004E+01 4 4 2.714757E+05 2.274843E+02 + 1.960004E+01 5 1 -1.041511E+04 1.513279E+02 + 1.960004E+01 5 5 8.271972E+05 1.377511E+03 + 1.960004E+01 6 6 9.192068E+05 1.048207E+02 + 1.970004E+01 1 1 2.046986E+03 1.644575E+01 + 1.970004E+01 1 5 -1.039560E+04 1.500790E+02 + 1.970004E+01 2 2 2.328215E+03 1.906352E+01 + 1.970004E+01 2 4 1.476300E+04 6.520600E+01 + 1.970004E+01 3 3 2.195329E+03 1.878243E+02 + 1.970004E+01 4 2 1.477999E+04 6.544521E+01 + 1.970004E+01 4 4 2.714634E+05 2.238466E+02 + 1.970004E+01 5 1 -1.041429E+04 1.495925E+02 + 1.970004E+01 5 5 8.271948E+05 1.365125E+03 + 1.970004E+01 6 6 9.190450E+05 1.020527E+02 + 1.980004E+01 1 1 2.046512E+03 1.621911E+01 + 1.980004E+01 1 5 -1.039480E+04 1.483693E+02 + 1.980004E+01 2 2 2.327573E+03 1.879211E+01 + 1.980004E+01 2 4 1.476018E+04 6.422812E+01 + 1.980004E+01 3 3 2.196280E+03 1.881516E+02 + 1.980004E+01 4 2 1.477718E+04 6.445956E+01 + 1.980004E+01 4 4 2.714500E+05 2.203193E+02 + 1.980004E+01 5 1 -1.041339E+04 1.478867E+02 + 1.980004E+01 5 5 8.271914E+05 1.352687E+03 + 1.980004E+01 6 6 9.188865E+05 9.938832E+01 + 1.990004E+01 1 1 2.046042E+03 1.599738E+01 + 1.990004E+01 1 5 -1.039398E+04 1.466865E+02 + 1.990004E+01 2 2 2.326934E+03 1.852710E+01 + 1.990004E+01 2 4 1.475738E+04 6.326960E+01 + 1.990004E+01 3 3 2.197233E+03 1.884762E+02 + 1.990004E+01 4 2 1.477441E+04 6.349908E+01 + 1.990004E+01 4 4 2.714381E+05 2.168449E+02 + 1.990004E+01 5 1 -1.041256E+04 1.462119E+02 + 1.990004E+01 5 5 8.271924E+05 1.340653E+03 + 1.990004E+01 6 6 9.187299E+05 9.683757E+01 + 2.000004E+01 1 1 2.045585E+03 1.578026E+01 + 2.000004E+01 1 5 -1.039323E+04 1.450318E+02 + 2.000004E+01 2 2 2.326304E+03 1.826778E+01 + 2.000004E+01 2 4 1.475468E+04 6.233554E+01 + 2.000004E+01 3 3 2.198189E+03 1.887917E+02 + 2.000004E+01 4 2 1.477165E+04 6.256093E+01 + 2.000004E+01 4 4 2.714253E+05 2.135000E+02 + 2.000004E+01 5 1 -1.041179E+04 1.445639E+02 + 2.000004E+01 5 5 8.271966E+05 1.328640E+03 + 2.000004E+01 6 6 9.185784E+05 9.434976E+01 + 2.010004E+01 1 1 2.045125E+03 1.556776E+01 + 2.010004E+01 1 5 -1.039244E+04 1.434056E+02 + 2.010004E+01 2 2 2.325691E+03 1.801404E+01 + 2.010004E+01 2 4 1.475198E+04 6.142097E+01 + 2.010004E+01 3 3 2.199134E+03 1.891055E+02 + 2.010004E+01 4 2 1.476897E+04 6.164350E+01 + 2.010004E+01 4 4 2.714142E+05 2.101818E+02 + 2.010004E+01 5 1 -1.041102E+04 1.429480E+02 + 2.010004E+01 5 5 8.271989E+05 1.316722E+03 + 2.010004E+01 6 6 9.184271E+05 9.191343E+01 + 2.020004E+01 1 1 2.044676E+03 1.535972E+01 + 2.020004E+01 1 5 -1.039172E+04 1.418049E+02 + 2.020004E+01 2 2 2.325084E+03 1.776595E+01 + 2.020004E+01 2 4 1.474935E+04 6.052758E+01 + 2.020004E+01 3 3 2.200063E+03 1.894135E+02 + 2.020004E+01 4 2 1.476634E+04 6.074775E+01 + 2.020004E+01 4 4 2.714013E+05 2.069709E+02 + 2.020004E+01 5 1 -1.041023E+04 1.413513E+02 + 2.020004E+01 5 5 8.272012E+05 1.305076E+03 + 2.020004E+01 6 6 9.182805E+05 8.961385E+01 + 2.030004E+01 1 1 2.044239E+03 1.515596E+01 + 2.030004E+01 1 5 -1.039100E+04 1.402321E+02 + 2.030004E+01 2 2 2.324486E+03 1.752291E+01 + 2.030004E+01 2 4 1.474676E+04 5.965457E+01 + 2.030004E+01 3 3 2.200991E+03 1.897112E+02 + 2.030004E+01 4 2 1.476376E+04 5.987170E+01 + 2.030004E+01 4 4 2.713893E+05 2.038347E+02 + 2.030004E+01 5 1 -1.040953E+04 1.397888E+02 + 2.030004E+01 5 5 8.272011E+05 1.293445E+03 + 2.030004E+01 6 6 9.181336E+05 8.735389E+01 + 2.040004E+01 1 1 2.043802E+03 1.495623E+01 + 2.040004E+01 1 5 -1.039028E+04 1.386837E+02 + 2.040004E+01 2 2 2.323908E+03 1.728514E+01 + 2.040004E+01 2 4 1.474422E+04 5.880129E+01 + 2.040004E+01 3 3 2.201927E+03 1.900100E+02 + 2.040004E+01 4 2 1.476116E+04 5.901313E+01 + 2.040004E+01 4 4 2.713787E+05 2.007744E+02 + 2.040004E+01 5 1 -1.040880E+04 1.382498E+02 + 2.040004E+01 5 5 8.271992E+05 1.281930E+03 + 2.040004E+01 6 6 9.179906E+05 8.516948E+01 + 2.050004E+01 1 1 2.043376E+03 1.476065E+01 + 2.050004E+01 1 5 -1.038959E+04 1.371617E+02 + 2.050004E+01 2 2 2.323322E+03 1.705247E+01 + 2.050004E+01 2 4 1.474168E+04 5.796666E+01 + 2.050004E+01 3 3 2.202838E+03 1.902937E+02 + 2.050004E+01 4 2 1.475862E+04 5.817687E+01 + 2.050004E+01 4 4 2.713673E+05 1.977805E+02 + 2.050004E+01 5 1 -1.040812E+04 1.367334E+02 + 2.050004E+01 5 5 8.271939E+05 1.270525E+03 + 2.050004E+01 6 6 9.178493E+05 8.307088E+01 + 2.060004E+01 1 1 2.042954E+03 1.456914E+01 + 2.060004E+01 1 5 -1.038892E+04 1.356651E+02 + 2.060004E+01 2 2 2.322754E+03 1.682451E+01 + 2.060004E+01 2 4 1.473921E+04 5.715059E+01 + 2.060004E+01 3 3 2.203731E+03 1.905823E+02 + 2.060004E+01 4 2 1.475616E+04 5.735726E+01 + 2.060004E+01 4 4 2.713563E+05 1.948603E+02 + 2.060004E+01 5 1 -1.040740E+04 1.352437E+02 + 2.060004E+01 5 5 8.271967E+05 1.259360E+03 + 2.060004E+01 6 6 9.177097E+05 8.102791E+01 + 2.070004E+01 1 1 2.042534E+03 1.438127E+01 + 2.070004E+01 1 5 -1.038830E+04 1.341935E+02 + 2.070004E+01 2 2 2.322198E+03 1.660144E+01 + 2.070004E+01 2 4 1.473680E+04 5.635143E+01 + 2.070004E+01 3 3 2.204645E+03 1.908608E+02 + 2.070004E+01 4 2 1.475372E+04 5.655698E+01 + 2.070004E+01 4 4 2.713456E+05 1.919953E+02 + 2.070004E+01 5 1 -1.040679E+04 1.337789E+02 + 2.070004E+01 5 5 8.271989E+05 1.248252E+03 + 2.070004E+01 6 6 9.175752E+05 7.903664E+01 + 2.080004E+01 1 1 2.042128E+03 1.419732E+01 + 2.080004E+01 1 5 -1.038767E+04 1.327458E+02 + 2.080004E+01 2 2 2.321642E+03 1.638292E+01 + 2.080004E+01 2 4 1.473439E+04 5.556999E+01 + 2.080004E+01 3 3 2.205545E+03 1.911388E+02 + 2.080004E+01 4 2 1.475132E+04 5.577240E+01 + 2.080004E+01 4 4 2.713351E+05 1.891891E+02 + 2.080004E+01 5 1 -1.040618E+04 1.323369E+02 + 2.080004E+01 5 5 8.272017E+05 1.237373E+03 + 2.080004E+01 6 6 9.174412E+05 7.712577E+01 + 2.090004E+01 1 1 2.041725E+03 1.401705E+01 + 2.090004E+01 1 5 -1.038704E+04 1.313200E+02 + 2.090004E+01 2 2 2.321099E+03 1.616871E+01 + 2.090004E+01 2 4 1.473205E+04 5.480648E+01 + 2.090004E+01 3 3 2.206437E+03 1.914103E+02 + 2.090004E+01 4 2 1.474894E+04 5.500297E+01 + 2.090004E+01 4 4 2.713241E+05 1.864643E+02 + 2.090004E+01 5 1 -1.040560E+04 1.309183E+02 + 2.090004E+01 5 5 8.272052E+05 1.226451E+03 + 2.090004E+01 6 6 9.173101E+05 7.527367E+01 + 2.100004E+01 1 1 2.041327E+03 1.384010E+01 + 2.100004E+01 1 5 -1.038649E+04 1.299190E+02 + 2.100004E+01 2 2 2.320566E+03 1.595914E+01 + 2.100004E+01 2 4 1.472971E+04 5.405708E+01 + 2.100004E+01 3 3 2.207311E+03 1.916773E+02 + 2.100004E+01 4 2 1.474664E+04 5.425408E+01 + 2.100004E+01 4 4 2.713145E+05 1.837754E+02 + 2.100004E+01 5 1 -1.040490E+04 1.295189E+02 + 2.100004E+01 5 5 8.272031E+05 1.215755E+03 + 2.100004E+01 6 6 9.171781E+05 7.347575E+01 + 2.110004E+01 1 1 2.040935E+03 1.366674E+01 + 2.110004E+01 1 5 -1.038594E+04 1.285374E+02 + 2.110004E+01 2 2 2.320041E+03 1.575354E+01 + 2.110004E+01 2 4 1.472747E+04 5.332546E+01 + 2.110004E+01 3 3 2.208215E+03 1.919347E+02 + 2.110004E+01 4 2 1.474433E+04 5.351843E+01 + 2.110004E+01 4 4 2.713036E+05 1.811644E+02 + 2.110004E+01 5 1 -1.040444E+04 1.281440E+02 + 2.110004E+01 5 5 8.272006E+05 1.205271E+03 + 2.110004E+01 6 6 9.170503E+05 7.173104E+01 + 2.120004E+01 1 1 2.040545E+03 1.349668E+01 + 2.120004E+01 1 5 -1.038537E+04 1.271811E+02 + 2.120004E+01 2 2 2.319518E+03 1.555222E+01 + 2.120004E+01 2 4 1.472518E+04 5.260789E+01 + 2.120004E+01 3 3 2.209068E+03 1.921973E+02 + 2.120004E+01 4 2 1.474211E+04 5.279823E+01 + 2.120004E+01 4 4 2.712929E+05 1.785933E+02 + 2.120004E+01 5 1 -1.040375E+04 1.267931E+02 + 2.120004E+01 5 5 8.272009E+05 1.194779E+03 + 2.120004E+01 6 6 9.169239E+05 7.004704E+01 + 2.130005E+01 1 1 2.040163E+03 1.333006E+01 + 2.130005E+01 1 5 -1.038483E+04 1.258438E+02 + 2.130005E+01 2 2 2.319005E+03 1.535498E+01 + 2.130005E+01 2 4 1.472300E+04 5.190788E+01 + 2.130005E+01 3 3 2.209932E+03 1.924512E+02 + 2.130005E+01 4 2 1.473989E+04 5.209476E+01 + 2.130005E+01 4 4 2.712835E+05 1.761176E+02 + 2.130005E+01 5 1 -1.040319E+04 1.254624E+02 + 2.130005E+01 5 5 8.271999E+05 1.184527E+03 + 2.130005E+01 6 6 9.168002E+05 6.840921E+01 + 2.140005E+01 1 1 2.039790E+03 1.316657E+01 + 2.140005E+01 1 5 -1.038429E+04 1.245276E+02 + 2.140005E+01 2 2 2.318509E+03 1.516140E+01 + 2.140005E+01 2 4 1.472081E+04 5.122044E+01 + 2.140005E+01 3 3 2.210812E+03 1.927012E+02 + 2.140005E+01 4 2 1.473769E+04 5.140326E+01 + 2.140005E+01 4 4 2.712734E+05 1.736811E+02 + 2.140005E+01 5 1 -1.040272E+04 1.241534E+02 + 2.140005E+01 5 5 8.271966E+05 1.174315E+03 + 2.140005E+01 6 6 9.166779E+05 6.679897E+01 + 2.150005E+01 1 1 2.039421E+03 1.300604E+01 + 2.150005E+01 1 5 -1.038382E+04 1.232327E+02 + 2.150005E+01 2 2 2.318014E+03 1.497173E+01 + 2.150005E+01 2 4 1.471868E+04 5.054661E+01 + 2.150005E+01 3 3 2.211674E+03 1.929450E+02 + 2.150005E+01 4 2 1.473557E+04 5.072710E+01 + 2.150005E+01 4 4 2.712644E+05 1.712669E+02 + 2.150005E+01 5 1 -1.040220E+04 1.228634E+02 + 2.150005E+01 5 5 8.271976E+05 1.164182E+03 + 2.150005E+01 6 6 9.165571E+05 6.528036E+01 + 2.160005E+01 1 1 2.039057E+03 1.284880E+01 + 2.160005E+01 1 5 -1.038330E+04 1.219590E+02 + 2.160005E+01 2 2 2.317519E+03 1.478582E+01 + 2.160005E+01 2 4 1.471653E+04 4.988591E+01 + 2.160005E+01 3 3 2.212511E+03 1.931867E+02 + 2.160005E+01 4 2 1.473342E+04 5.006529E+01 + 2.160005E+01 4 4 2.712549E+05 1.689041E+02 + 2.160005E+01 5 1 -1.040170E+04 1.215938E+02 + 2.160005E+01 5 5 8.272002E+05 1.154037E+03 + 2.160005E+01 6 6 9.164384E+05 6.376656E+01 + 2.170005E+01 1 1 2.038695E+03 1.269431E+01 + 2.170005E+01 1 5 -1.038282E+04 1.207042E+02 + 2.170005E+01 2 2 2.317043E+03 1.460325E+01 + 2.170005E+01 2 4 1.471450E+04 4.924081E+01 + 2.170005E+01 3 3 2.213365E+03 1.934295E+02 + 2.170005E+01 4 2 1.473132E+04 4.941448E+01 + 2.170005E+01 4 4 2.712455E+05 1.666196E+02 + 2.170005E+01 5 1 -1.040119E+04 1.203417E+02 + 2.170005E+01 5 5 8.271990E+05 1.144272E+03 + 2.170005E+01 6 6 9.163224E+05 6.229789E+01 + 2.180005E+01 1 1 2.038337E+03 1.254278E+01 + 2.180005E+01 1 5 -1.038239E+04 1.194680E+02 + 2.180005E+01 2 2 2.316567E+03 1.442472E+01 + 2.180005E+01 2 4 1.471242E+04 4.860685E+01 + 2.180005E+01 3 3 2.214200E+03 1.936623E+02 + 2.180005E+01 4 2 1.472929E+04 4.878252E+01 + 2.180005E+01 4 4 2.712359E+05 1.643719E+02 + 2.180005E+01 5 1 -1.040068E+04 1.191137E+02 + 2.180005E+01 5 5 8.271991E+05 1.134515E+03 + 2.180005E+01 6 6 9.162071E+05 6.089412E+01 + 2.190005E+01 1 1 2.037989E+03 1.239400E+01 + 2.190005E+01 1 5 -1.038188E+04 1.182522E+02 + 2.190005E+01 2 2 2.316103E+03 1.424912E+01 + 2.190005E+01 2 4 1.471041E+04 4.798604E+01 + 2.190005E+01 3 3 2.215061E+03 1.938943E+02 + 2.190005E+01 4 2 1.472726E+04 4.815831E+01 + 2.190005E+01 4 4 2.712270E+05 1.621767E+02 + 2.190005E+01 5 1 -1.040027E+04 1.179015E+02 + 2.190005E+01 5 5 8.271982E+05 1.124841E+03 + 2.190005E+01 6 6 9.160946E+05 5.951931E+01 + 2.200005E+01 1 1 2.037649E+03 1.224808E+01 + 2.200005E+01 1 5 -1.038147E+04 1.170528E+02 + 2.200005E+01 2 2 2.315639E+03 1.407682E+01 + 2.200005E+01 2 4 1.470844E+04 4.737843E+01 + 2.200005E+01 3 3 2.215873E+03 1.941264E+02 + 2.200005E+01 4 2 1.472529E+04 4.754744E+01 + 2.200005E+01 4 4 2.712183E+05 1.600185E+02 + 2.200005E+01 5 1 -1.039992E+04 1.167101E+02 + 2.200005E+01 5 5 8.271976E+05 1.115430E+03 + 2.200005E+01 6 6 9.159816E+05 5.819202E+01 + 2.210005E+01 1 1 2.037308E+03 1.210470E+01 + 2.210005E+01 1 5 -1.038102E+04 1.158736E+02 + 2.210005E+01 2 2 2.315182E+03 1.390803E+01 + 2.210005E+01 2 4 1.470646E+04 4.678249E+01 + 2.210005E+01 3 3 2.216712E+03 1.943450E+02 + 2.210005E+01 4 2 1.472329E+04 4.695055E+01 + 2.210005E+01 4 4 2.712093E+05 1.579354E+02 + 2.210005E+01 5 1 -1.039939E+04 1.155343E+02 + 2.210005E+01 5 5 8.271957E+05 1.106022E+03 + 2.210005E+01 6 6 9.158721E+05 5.688284E+01 + 2.220005E+01 1 1 2.036969E+03 1.196400E+01 + 2.220005E+01 1 5 -1.038063E+04 1.147114E+02 + 2.220005E+01 2 2 2.314739E+03 1.374230E+01 + 2.220005E+01 2 4 1.470454E+04 4.619685E+01 + 2.220005E+01 3 3 2.217524E+03 1.945665E+02 + 2.220005E+01 4 2 1.472136E+04 4.636358E+01 + 2.220005E+01 4 4 2.712004E+05 1.558597E+02 + 2.220005E+01 5 1 -1.039897E+04 1.143771E+02 + 2.220005E+01 5 5 8.271941E+05 1.096781E+03 + 2.220005E+01 6 6 9.157641E+05 5.563345E+01 + 2.230005E+01 1 1 2.036637E+03 1.182575E+01 + 2.230005E+01 1 5 -1.038026E+04 1.135683E+02 + 2.230005E+01 2 2 2.314296E+03 1.357960E+01 + 2.230005E+01 2 4 1.470264E+04 4.562354E+01 + 2.230005E+01 3 3 2.218334E+03 1.947845E+02 + 2.230005E+01 4 2 1.471949E+04 4.578807E+01 + 2.230005E+01 4 4 2.711918E+05 1.538298E+02 + 2.230005E+01 5 1 -1.039849E+04 1.132363E+02 + 2.230005E+01 5 5 8.271973E+05 1.087464E+03 + 2.230005E+01 6 6 9.156574E+05 5.442185E+01 + 2.240005E+01 1 1 2.036311E+03 1.168988E+01 + 2.240005E+01 1 5 -1.037981E+04 1.124409E+02 + 2.240005E+01 2 2 2.313863E+03 1.341987E+01 + 2.240005E+01 2 4 1.470077E+04 4.506102E+01 + 2.240005E+01 3 3 2.219161E+03 1.949962E+02 + 2.240005E+01 4 2 1.471759E+04 4.522205E+01 + 2.240005E+01 4 4 2.711828E+05 1.518387E+02 + 2.240005E+01 5 1 -1.039809E+04 1.121140E+02 + 2.240005E+01 5 5 8.271967E+05 1.078192E+03 + 2.240005E+01 6 6 9.155534E+05 5.319827E+01 + 2.250005E+01 1 1 2.035988E+03 1.155664E+01 + 2.250005E+01 1 5 -1.037943E+04 1.113303E+02 + 2.250005E+01 2 2 2.313435E+03 1.326312E+01 + 2.250005E+01 2 4 1.469893E+04 4.451097E+01 + 2.250005E+01 3 3 2.219965E+03 1.952088E+02 + 2.250005E+01 4 2 1.471570E+04 4.466977E+01 + 2.250005E+01 4 4 2.711756E+05 1.499245E+02 + 2.250005E+01 5 1 -1.039769E+04 1.110101E+02 + 2.250005E+01 5 5 8.271958E+05 1.069337E+03 + 2.250005E+01 6 6 9.154492E+05 5.207079E+01 + 2.260005E+01 1 1 2.035668E+03 1.142559E+01 + 2.260005E+01 1 5 -1.037899E+04 1.102374E+02 + 2.260005E+01 2 2 2.313012E+03 1.310918E+01 + 2.260005E+01 2 4 1.469711E+04 4.396895E+01 + 2.260005E+01 3 3 2.220759E+03 1.954165E+02 + 2.260005E+01 4 2 1.471388E+04 4.412612E+01 + 2.260005E+01 4 4 2.711669E+05 1.480203E+02 + 2.260005E+01 5 1 -1.039733E+04 1.099194E+02 + 2.260005E+01 5 5 8.271949E+05 1.060400E+03 + 2.260005E+01 6 6 9.153475E+05 5.092782E+01 + 2.270005E+01 1 1 2.035357E+03 1.129714E+01 + 2.270005E+01 1 5 -1.037867E+04 1.091581E+02 + 2.270005E+01 2 2 2.312599E+03 1.295820E+01 + 2.270005E+01 2 4 1.469534E+04 4.343785E+01 + 2.270005E+01 3 3 2.221554E+03 1.956181E+02 + 2.270005E+01 4 2 1.471213E+04 4.359325E+01 + 2.270005E+01 4 4 2.711593E+05 1.461311E+02 + 2.270005E+01 5 1 -1.039698E+04 1.088451E+02 + 2.270005E+01 5 5 8.271948E+05 1.051773E+03 + 2.270005E+01 6 6 9.152474E+05 4.985772E+01 + 2.280005E+01 1 1 2.035051E+03 1.117065E+01 + 2.280005E+01 1 5 -1.037832E+04 1.080965E+02 + 2.280005E+01 2 2 2.312185E+03 1.280977E+01 + 2.280005E+01 2 4 1.469355E+04 4.291696E+01 + 2.280005E+01 3 3 2.222362E+03 1.958172E+02 + 2.280005E+01 4 2 1.471033E+04 4.307096E+01 + 2.280005E+01 4 4 2.711515E+05 1.443114E+02 + 2.280005E+01 5 1 -1.039657E+04 1.077888E+02 + 2.280005E+01 5 5 8.271949E+05 1.042962E+03 + 2.280005E+01 6 6 9.151476E+05 4.881584E+01 + 2.290005E+01 1 1 2.034748E+03 1.104653E+01 + 2.290005E+01 1 5 -1.037800E+04 1.070498E+02 + 2.290005E+01 2 2 2.311784E+03 1.266404E+01 + 2.290005E+01 2 4 1.469180E+04 4.240533E+01 + 2.290005E+01 3 3 2.223147E+03 1.960163E+02 + 2.290005E+01 4 2 1.470862E+04 4.255819E+01 + 2.290005E+01 4 4 2.711436E+05 1.425061E+02 + 2.290005E+01 5 1 -1.039627E+04 1.067465E+02 + 2.290005E+01 5 5 8.271956E+05 1.034468E+03 + 2.290005E+01 6 6 9.150489E+05 4.774730E+01 + 2.300005E+01 1 1 2.034443E+03 1.092434E+01 + 2.300005E+01 1 5 -1.037765E+04 1.060190E+02 + 2.300005E+01 2 2 2.311383E+03 1.252069E+01 + 2.300005E+01 2 4 1.469011E+04 4.190488E+01 + 2.300005E+01 3 3 2.223921E+03 1.962105E+02 + 2.300005E+01 4 2 1.470688E+04 4.205219E+01 + 2.300005E+01 4 4 2.711359E+05 1.407608E+02 + 2.300005E+01 5 1 -1.039589E+04 1.057175E+02 + 2.300005E+01 5 5 8.271911E+05 1.025958E+03 + 2.300005E+01 6 6 9.149519E+05 4.675128E+01 + 2.310005E+01 1 1 2.034148E+03 1.080445E+01 + 2.310005E+01 1 5 -1.037733E+04 1.050034E+02 + 2.310005E+01 2 2 2.310981E+03 1.237996E+01 + 2.310005E+01 2 4 1.468841E+04 4.141182E+01 + 2.310005E+01 3 3 2.224703E+03 1.964054E+02 + 2.310005E+01 4 2 1.470514E+04 4.155864E+01 + 2.310005E+01 4 4 2.711282E+05 1.390386E+02 + 2.310005E+01 5 1 -1.039559E+04 1.047043E+02 + 2.310005E+01 5 5 8.271901E+05 1.017580E+03 + 2.310005E+01 6 6 9.148575E+05 4.576733E+01 + 2.320005E+01 1 1 2.033849E+03 1.068652E+01 + 2.320005E+01 1 5 -1.037704E+04 1.040022E+02 + 2.320005E+01 2 2 2.310599E+03 1.224202E+01 + 2.320005E+01 2 4 1.468675E+04 4.092871E+01 + 2.320005E+01 3 3 2.225478E+03 1.965968E+02 + 2.320005E+01 4 2 1.470356E+04 4.107518E+01 + 2.320005E+01 4 4 2.711210E+05 1.373338E+02 + 2.320005E+01 5 1 -1.039518E+04 1.037093E+02 + 2.320005E+01 5 5 8.271895E+05 1.009331E+03 + 2.320005E+01 6 6 9.147649E+05 4.482122E+01 + 2.330005E+01 1 1 2.033559E+03 1.057042E+01 + 2.330005E+01 1 5 -1.037676E+04 1.030166E+02 + 2.330005E+01 2 2 2.310214E+03 1.210602E+01 + 2.330005E+01 2 4 1.468507E+04 4.045424E+01 + 2.330005E+01 3 3 2.226240E+03 1.967788E+02 + 2.330005E+01 4 2 1.470188E+04 4.059764E+01 + 2.330005E+01 4 4 2.711132E+05 1.356642E+02 + 2.330005E+01 5 1 -1.039495E+04 1.027238E+02 + 2.330005E+01 5 5 8.271878E+05 1.001008E+03 + 2.330005E+01 6 6 9.146716E+05 4.388947E+01 + 2.340005E+01 1 1 2.033273E+03 1.045655E+01 + 2.340005E+01 1 5 -1.037643E+04 1.020423E+02 + 2.340005E+01 2 2 2.309837E+03 1.197268E+01 + 2.340005E+01 2 4 1.468345E+04 3.998836E+01 + 2.340005E+01 3 3 2.227008E+03 1.969655E+02 + 2.340005E+01 4 2 1.470022E+04 4.013037E+01 + 2.340005E+01 4 4 2.711061E+05 1.340341E+02 + 2.340005E+01 5 1 -1.039461E+04 1.017547E+02 + 2.340005E+01 5 5 8.271899E+05 9.931252E+02 + 2.340005E+01 6 6 9.145817E+05 4.299681E+01 + 2.350005E+01 1 1 2.032994E+03 1.034446E+01 + 2.350005E+01 1 5 -1.037612E+04 1.010847E+02 + 2.350005E+01 2 2 2.309460E+03 1.184148E+01 + 2.350005E+01 2 4 1.468187E+04 3.953109E+01 + 2.350005E+01 3 3 2.227773E+03 1.971446E+02 + 2.350005E+01 4 2 1.469865E+04 3.967077E+01 + 2.350005E+01 4 4 2.710999E+05 1.324319E+02 + 2.350005E+01 5 1 -1.039433E+04 1.007999E+02 + 2.350005E+01 5 5 8.271886E+05 9.849613E+02 + 2.350005E+01 6 6 9.144915E+05 4.211162E+01 + 2.360005E+01 1 1 2.032715E+03 1.023431E+01 + 2.360005E+01 1 5 -1.037586E+04 1.001379E+02 + 2.360005E+01 2 2 2.309094E+03 1.171263E+01 + 2.360005E+01 2 4 1.468028E+04 3.908125E+01 + 2.360005E+01 3 3 2.228521E+03 1.973266E+02 + 2.360005E+01 4 2 1.469707E+04 3.922056E+01 + 2.360005E+01 4 4 2.710927E+05 1.308755E+02 + 2.360005E+01 5 1 -1.039407E+04 9.985751E+01 + 2.360005E+01 5 5 8.271896E+05 9.771481E+02 + 2.360005E+01 6 6 9.144030E+05 4.124708E+01 + 2.370005E+01 1 1 2.032438E+03 1.012587E+01 + 2.370005E+01 1 5 -1.037555E+04 9.920699E+01 + 2.370005E+01 2 2 2.308731E+03 1.158590E+01 + 2.370005E+01 2 4 1.467874E+04 3.863985E+01 + 2.370005E+01 3 3 2.229279E+03 1.975036E+02 + 2.370005E+01 4 2 1.469549E+04 3.877715E+01 + 2.370005E+01 4 4 2.710864E+05 1.293232E+02 + 2.370005E+01 5 1 -1.039373E+04 9.892930E+01 + 2.370005E+01 5 5 8.271887E+05 9.692566E+02 + 2.370005E+01 6 6 9.143159E+05 4.041645E+01 + 2.380005E+01 1 1 2.032171E+03 1.001928E+01 + 2.380005E+01 1 5 -1.037528E+04 9.828754E+01 + 2.380005E+01 2 2 2.308376E+03 1.146121E+01 + 2.380005E+01 2 4 1.467721E+04 3.820537E+01 + 2.380005E+01 3 3 2.230031E+03 1.976775E+02 + 2.380005E+01 4 2 1.469398E+04 3.834073E+01 + 2.380005E+01 4 4 2.710787E+05 1.278101E+02 + 2.380005E+01 5 1 -1.039351E+04 9.801326E+01 + 2.380005E+01 5 5 8.271858E+05 9.615890E+02 + 2.380005E+01 6 6 9.142285E+05 3.960041E+01 + 2.390005E+01 1 1 2.031903E+03 9.914342E+00 + 2.390005E+01 1 5 -1.037502E+04 9.738152E+01 + 2.390005E+01 2 2 2.308018E+03 1.133885E+01 + 2.390005E+01 2 4 1.467568E+04 3.777906E+01 + 2.390005E+01 3 3 2.230778E+03 1.978476E+02 + 2.390005E+01 4 2 1.469244E+04 3.791449E+01 + 2.390005E+01 4 4 2.710722E+05 1.263223E+02 + 2.390005E+01 5 1 -1.039319E+04 9.711163E+01 + 2.390005E+01 5 5 8.271860E+05 9.539293E+02 + 2.390005E+01 6 6 9.141447E+05 3.882231E+01 + 2.400006E+01 1 1 2.031634E+03 9.811126E+00 + 2.400006E+01 1 5 -1.037478E+04 9.648814E+01 + 2.400006E+01 2 2 2.307672E+03 1.121838E+01 + 2.400006E+01 2 4 1.467422E+04 3.736005E+01 + 2.400006E+01 3 3 2.231508E+03 1.980149E+02 + 2.400006E+01 4 2 1.469097E+04 3.749390E+01 + 2.400006E+01 4 4 2.710653E+05 1.248615E+02 + 2.400006E+01 5 1 -1.039290E+04 9.622011E+01 + 2.400006E+01 5 5 8.271822E+05 9.463295E+02 + 2.400006E+01 6 6 9.140606E+05 3.803633E+01 + 2.410006E+01 1 1 2.031377E+03 9.709634E+00 + 2.410006E+01 1 5 -1.037453E+04 9.560735E+01 + 2.410006E+01 2 2 2.307326E+03 1.109978E+01 + 2.410006E+01 2 4 1.467273E+04 3.694786E+01 + 2.410006E+01 3 3 2.232253E+03 1.981839E+02 + 2.410006E+01 4 2 1.468944E+04 3.707983E+01 + 2.410006E+01 4 4 2.710592E+05 1.234255E+02 + 2.410006E+01 5 1 -1.039270E+04 9.534648E+01 + 2.410006E+01 5 5 8.271782E+05 9.387194E+02 + 2.410006E+01 6 6 9.139781E+05 3.730908E+01 + 2.420006E+01 1 1 2.031112E+03 9.609752E+00 + 2.420006E+01 1 5 -1.037431E+04 9.473851E+01 + 2.420006E+01 2 2 2.306985E+03 1.098335E+01 + 2.420006E+01 2 4 1.467128E+04 3.654422E+01 + 2.420006E+01 3 3 2.232986E+03 1.983488E+02 + 2.420006E+01 4 2 1.468798E+04 3.667476E+01 + 2.420006E+01 4 4 2.710523E+05 1.220480E+02 + 2.420006E+01 5 1 -1.039244E+04 9.447757E+01 + 2.420006E+01 5 5 8.271759E+05 9.313820E+02 + 2.420006E+01 6 6 9.138958E+05 3.654898E+01 + 2.430006E+01 1 1 2.030863E+03 9.511484E+00 + 2.430006E+01 1 5 -1.037415E+04 9.388129E+01 + 2.430006E+01 2 2 2.306656E+03 1.086845E+01 + 2.430006E+01 2 4 1.466984E+04 3.614560E+01 + 2.430006E+01 3 3 2.233718E+03 1.985104E+02 + 2.430006E+01 4 2 1.468658E+04 3.627436E+01 + 2.430006E+01 4 4 2.710465E+05 1.206483E+02 + 2.430006E+01 5 1 -1.039221E+04 9.362186E+01 + 2.430006E+01 5 5 8.271740E+05 9.240085E+02 + 2.430006E+01 6 6 9.138143E+05 3.586105E+01 + 2.440006E+01 1 1 2.030609E+03 9.414827E+00 + 2.440006E+01 1 5 -1.037391E+04 9.303546E+01 + 2.440006E+01 2 2 2.306322E+03 1.075568E+01 + 2.440006E+01 2 4 1.466841E+04 3.575534E+01 + 2.440006E+01 3 3 2.234436E+03 1.986674E+02 + 2.440006E+01 4 2 1.468513E+04 3.588192E+01 + 2.440006E+01 4 4 2.710398E+05 1.192928E+02 + 2.440006E+01 5 1 -1.039196E+04 9.278113E+01 + 2.440006E+01 5 5 8.271754E+05 9.168135E+02 + 2.440006E+01 6 6 9.137352E+05 3.514493E+01 + 2.450006E+01 1 1 2.030361E+03 9.319529E+00 + 2.450006E+01 1 5 -1.037363E+04 9.220276E+01 + 2.450006E+01 2 2 2.305993E+03 1.064490E+01 + 2.450006E+01 2 4 1.466702E+04 3.537190E+01 + 2.450006E+01 3 3 2.235165E+03 1.988278E+02 + 2.450006E+01 4 2 1.468375E+04 3.549681E+01 + 2.450006E+01 4 4 2.710335E+05 1.179643E+02 + 2.450006E+01 5 1 -1.039174E+04 9.194997E+01 + 2.450006E+01 5 5 8.271759E+05 9.095566E+02 + 2.450006E+01 6 6 9.136572E+05 3.445596E+01 + 2.460006E+01 1 1 2.030117E+03 9.225826E+00 + 2.460006E+01 1 5 -1.037340E+04 9.138032E+01 + 2.460006E+01 2 2 2.305668E+03 1.053581E+01 + 2.460006E+01 2 4 1.466565E+04 3.499251E+01 + 2.460006E+01 3 3 2.235873E+03 1.989822E+02 + 2.460006E+01 4 2 1.468234E+04 3.511721E+01 + 2.460006E+01 4 4 2.710272E+05 1.166416E+02 + 2.460006E+01 5 1 -1.039152E+04 9.113002E+01 + 2.460006E+01 5 5 8.271744E+05 9.025378E+02 + 2.460006E+01 6 6 9.135802E+05 3.381790E+01 + 2.470006E+01 1 1 2.029873E+03 9.133606E+00 + 2.470006E+01 1 5 -1.037318E+04 9.056837E+01 + 2.470006E+01 2 2 2.305353E+03 1.042826E+01 + 2.470006E+01 2 4 1.466428E+04 3.462143E+01 + 2.470006E+01 3 3 2.236587E+03 1.991355E+02 + 2.470006E+01 4 2 1.468099E+04 3.474391E+01 + 2.470006E+01 4 4 2.710212E+05 1.153483E+02 + 2.470006E+01 5 1 -1.039129E+04 9.032232E+01 + 2.470006E+01 5 5 8.271716E+05 8.955177E+02 + 2.470006E+01 6 6 9.135034E+05 3.313776E+01 + 2.480006E+01 1 1 2.029630E+03 9.042878E+00 + 2.480006E+01 1 5 -1.037298E+04 8.976824E+01 + 2.480006E+01 2 2 2.305035E+03 1.032270E+01 + 2.480006E+01 2 4 1.466295E+04 3.425539E+01 + 2.480006E+01 3 3 2.237302E+03 1.992867E+02 + 2.480006E+01 4 2 1.467967E+04 3.437832E+01 + 2.480006E+01 4 4 2.710157E+05 1.140821E+02 + 2.480006E+01 5 1 -1.039106E+04 8.952290E+01 + 2.480006E+01 5 5 8.271679E+05 8.886054E+02 + 2.480006E+01 6 6 9.134277E+05 3.253455E+01 + 2.490006E+01 1 1 2.029394E+03 8.953331E+00 + 2.490006E+01 1 5 -1.037281E+04 8.897883E+01 + 2.490006E+01 2 2 2.304724E+03 1.021857E+01 + 2.490006E+01 2 4 1.466162E+04 3.389667E+01 + 2.490006E+01 3 3 2.237998E+03 1.994348E+02 + 2.490006E+01 4 2 1.467831E+04 3.401699E+01 + 2.490006E+01 4 4 2.710087E+05 1.128555E+02 + 2.490006E+01 5 1 -1.039082E+04 8.874215E+01 + 2.490006E+01 5 5 8.271696E+05 8.818109E+02 + 2.490006E+01 6 6 9.133528E+05 3.192215E+01 + 2.500006E+01 1 1 2.029163E+03 8.865359E+00 + 2.500006E+01 1 5 -1.037263E+04 8.819851E+01 + 2.500006E+01 2 2 2.304419E+03 1.011612E+01 + 2.500006E+01 2 4 1.466032E+04 3.354252E+01 + 2.500006E+01 3 3 2.238706E+03 1.995865E+02 + 2.500006E+01 4 2 1.467700E+04 3.366219E+01 + 2.500006E+01 4 4 2.710033E+05 1.116153E+02 + 2.500006E+01 5 1 -1.039066E+04 8.796290E+01 + 2.500006E+01 5 5 8.271669E+05 8.751105E+02 + 2.500006E+01 6 6 9.132793E+05 3.132604E+01 + 2.510006E+01 1 1 2.028934E+03 8.778656E+00 + 2.510006E+01 1 5 -1.037237E+04 8.743025E+01 + 2.510006E+01 2 2 2.304118E+03 1.001532E+01 + 2.510006E+01 2 4 1.465900E+04 3.319426E+01 + 2.510006E+01 3 3 2.239400E+03 1.997308E+02 + 2.510006E+01 4 2 1.467571E+04 3.331283E+01 + 2.510006E+01 4 4 2.709972E+05 1.104066E+02 + 2.510006E+01 5 1 -1.039050E+04 8.719435E+01 + 2.510006E+01 5 5 8.271693E+05 8.684067E+02 + 2.510006E+01 6 6 9.132068E+05 3.071132E+01 + 2.520006E+01 1 1 2.028703E+03 8.693321E+00 + 2.520006E+01 1 5 -1.037219E+04 8.667213E+01 + 2.520006E+01 2 2 2.303819E+03 9.916179E+00 + 2.520006E+01 2 4 1.465776E+04 3.285224E+01 + 2.520006E+01 3 3 2.240094E+03 1.998740E+02 + 2.520006E+01 4 2 1.467443E+04 3.297049E+01 + 2.520006E+01 4 4 2.709916E+05 1.092366E+02 + 2.520006E+01 5 1 -1.039028E+04 8.643800E+01 + 2.520006E+01 5 5 8.271694E+05 8.618149E+02 + 2.520006E+01 6 6 9.131358E+05 3.016357E+01 + 2.530006E+01 1 1 2.028479E+03 8.609179E+00 + 2.530006E+01 1 5 -1.037204E+04 8.592427E+01 + 2.530006E+01 2 2 2.303526E+03 9.818414E+00 + 2.530006E+01 2 4 1.465649E+04 3.251585E+01 + 2.530006E+01 3 3 2.240780E+03 2.000163E+02 + 2.530006E+01 4 2 1.467319E+04 3.263248E+01 + 2.530006E+01 4 4 2.709859E+05 1.080735E+02 + 2.530006E+01 5 1 -1.039008E+04 8.569388E+01 + 2.530006E+01 5 5 8.271659E+05 8.552576E+02 + 2.530006E+01 6 6 9.130642E+05 2.958306E+01 + 2.540006E+01 1 1 2.028260E+03 8.526321E+00 + 2.540006E+01 1 5 -1.037186E+04 8.518460E+01 + 2.540006E+01 2 2 2.303233E+03 9.722049E+00 + 2.540006E+01 2 4 1.465524E+04 3.218387E+01 + 2.540006E+01 3 3 2.241477E+03 2.001544E+02 + 2.540006E+01 4 2 1.467192E+04 3.229755E+01 + 2.540006E+01 4 4 2.709805E+05 1.069268E+02 + 2.540006E+01 5 1 -1.038993E+04 8.495767E+01 + 2.540006E+01 5 5 8.271612E+05 8.487145E+02 + 2.540006E+01 6 6 9.129948E+05 2.904381E+01 + 2.550006E+01 1 1 2.028036E+03 8.444819E+00 + 2.550006E+01 1 5 -1.037168E+04 8.445553E+01 + 2.550006E+01 2 2 2.302943E+03 9.627226E+00 + 2.550006E+01 2 4 1.465403E+04 3.185727E+01 + 2.550006E+01 3 3 2.242153E+03 2.002938E+02 + 2.550006E+01 4 2 1.467067E+04 3.196987E+01 + 2.550006E+01 4 4 2.709756E+05 1.058044E+02 + 2.550006E+01 5 1 -1.038976E+04 8.422741E+01 + 2.550006E+01 5 5 8.271586E+05 8.422817E+02 + 2.550006E+01 6 6 9.129251E+05 2.850357E+01 + 2.560006E+01 1 1 2.027823E+03 8.364308E+00 + 2.560006E+01 1 5 -1.037155E+04 8.373588E+01 + 2.560006E+01 2 2 2.302657E+03 9.533985E+00 + 2.560006E+01 2 4 1.465281E+04 3.153700E+01 + 2.560006E+01 3 3 2.242827E+03 2.004348E+02 + 2.560006E+01 4 2 1.466947E+04 3.164940E+01 + 2.560006E+01 4 4 2.709701E+05 1.047038E+02 + 2.560006E+01 5 1 -1.038962E+04 8.351262E+01 + 2.560006E+01 5 5 8.271565E+05 8.359814E+02 + 2.560006E+01 6 6 9.128584E+05 2.799725E+01 + 2.570006E+01 1 1 2.027606E+03 8.285014E+00 + 2.570006E+01 1 5 -1.037137E+04 8.302389E+01 + 2.570006E+01 2 2 2.302380E+03 9.442121E+00 + 2.570006E+01 2 4 1.465162E+04 3.121981E+01 + 2.570006E+01 3 3 2.243504E+03 2.005645E+02 + 2.570006E+01 4 2 1.466828E+04 3.133272E+01 + 2.570006E+01 4 4 2.709648E+05 1.036158E+02 + 2.570006E+01 5 1 -1.038941E+04 8.280424E+01 + 2.570006E+01 5 5 8.271548E+05 8.298326E+02 + 2.570006E+01 6 6 9.127900E+05 2.749338E+01 + 2.580006E+01 1 1 2.027392E+03 8.206997E+00 + 2.580006E+01 1 5 -1.037125E+04 8.232254E+01 + 2.580006E+01 2 2 2.302102E+03 9.351472E+00 + 2.580006E+01 2 4 1.465043E+04 3.090963E+01 + 2.580006E+01 3 3 2.244165E+03 2.007012E+02 + 2.580006E+01 4 2 1.466709E+04 3.101912E+01 + 2.580006E+01 4 4 2.709602E+05 1.025484E+02 + 2.580006E+01 5 1 -1.038929E+04 8.210590E+01 + 2.580006E+01 5 5 8.271551E+05 8.235336E+02 + 2.580006E+01 6 6 9.127228E+05 2.699221E+01 + 2.590006E+01 1 1 2.027182E+03 8.130158E+00 + 2.590006E+01 1 5 -1.037112E+04 8.162987E+01 + 2.590006E+01 2 2 2.301826E+03 9.262368E+00 + 2.590006E+01 2 4 1.464928E+04 3.060220E+01 + 2.590006E+01 3 3 2.244849E+03 2.008306E+02 + 2.590006E+01 4 2 1.466592E+04 3.071286E+01 + 2.590006E+01 4 4 2.709549E+05 1.014891E+02 + 2.590006E+01 5 1 -1.038912E+04 8.141292E+01 + 2.590006E+01 5 5 8.271537E+05 8.174359E+02 + 2.590006E+01 6 6 9.126582E+05 2.651291E+01 + 2.600006E+01 1 1 2.026976E+03 8.054261E+00 + 2.600006E+01 1 5 -1.037096E+04 8.094625E+01 + 2.600006E+01 2 2 2.301557E+03 9.174356E+00 + 2.600006E+01 2 4 1.464809E+04 3.030066E+01 + 2.600006E+01 3 3 2.245509E+03 2.009578E+02 + 2.600006E+01 4 2 1.466478E+04 3.040839E+01 + 2.600006E+01 4 4 2.709496E+05 1.004428E+02 + 2.600006E+01 5 1 -1.038898E+04 8.073370E+01 + 2.600006E+01 5 5 8.271520E+05 8.113566E+02 + 2.600006E+01 6 6 9.125938E+05 2.603255E+01 + 2.610006E+01 1 1 2.026770E+03 7.979511E+00 + 2.610006E+01 1 5 -1.037085E+04 8.027102E+01 + 2.610006E+01 2 2 2.301287E+03 9.087890E+00 + 2.610006E+01 2 4 1.464696E+04 3.000399E+01 + 2.610006E+01 3 3 2.246179E+03 2.010886E+02 + 2.610006E+01 4 2 1.466362E+04 3.011195E+01 + 2.610006E+01 4 4 2.709448E+05 9.942530E+01 + 2.610006E+01 5 1 -1.038877E+04 8.006023E+01 + 2.610006E+01 5 5 8.271528E+05 8.053268E+02 + 2.610006E+01 6 6 9.125300E+05 2.558108E+01 + 2.620006E+01 1 1 2.026568E+03 7.906063E+00 + 2.620006E+01 1 5 -1.037070E+04 7.960527E+01 + 2.620006E+01 2 2 2.301020E+03 9.002596E+00 + 2.620006E+01 2 4 1.464582E+04 2.971134E+01 + 2.620006E+01 3 3 2.246840E+03 2.012124E+02 + 2.620006E+01 4 2 1.466249E+04 2.982026E+01 + 2.620006E+01 4 4 2.709401E+05 9.841453E+01 + 2.620006E+01 5 1 -1.038868E+04 7.939495E+01 + 2.620006E+01 5 5 8.271547E+05 7.993817E+02 + 2.620006E+01 6 6 9.124662E+05 2.512825E+01 + 2.630006E+01 1 1 2.026369E+03 7.833481E+00 + 2.630006E+01 1 5 -1.037054E+04 7.894700E+01 + 2.630006E+01 2 2 2.300758E+03 8.918515E+00 + 2.630006E+01 2 4 1.464473E+04 2.942456E+01 + 2.630006E+01 3 3 2.247492E+03 2.013382E+02 + 2.630006E+01 4 2 1.466139E+04 2.953014E+01 + 2.630006E+01 4 4 2.709352E+05 9.743958E+01 + 2.630006E+01 5 1 -1.038856E+04 7.873937E+01 + 2.630006E+01 5 5 8.271514E+05 7.933781E+02 + 2.630006E+01 6 6 9.124036E+05 2.467591E+01 + 2.640006E+01 1 1 2.026170E+03 7.761918E+00 + 2.640006E+01 1 5 -1.037043E+04 7.829729E+01 + 2.640006E+01 2 2 2.300500E+03 8.835664E+00 + 2.640006E+01 2 4 1.464364E+04 2.913994E+01 + 2.640006E+01 3 3 2.248145E+03 2.014608E+02 + 2.640006E+01 4 2 1.466025E+04 2.924344E+01 + 2.640006E+01 4 4 2.709298E+05 9.645932E+01 + 2.640006E+01 5 1 -1.038839E+04 7.809048E+01 + 2.640006E+01 5 5 8.271487E+05 7.876584E+02 + 2.640006E+01 6 6 9.123422E+05 2.422641E+01 + 2.650006E+01 1 1 2.025971E+03 7.691275E+00 + 2.650006E+01 1 5 -1.037028E+04 7.765542E+01 + 2.650006E+01 2 2 2.300242E+03 8.754071E+00 + 2.650006E+01 2 4 1.464257E+04 2.886089E+01 + 2.650006E+01 3 3 2.248790E+03 2.015837E+02 + 2.650006E+01 4 2 1.465918E+04 2.896592E+01 + 2.650006E+01 4 4 2.709252E+05 9.550850E+01 + 2.650006E+01 5 1 -1.038830E+04 7.745103E+01 + 2.650006E+01 5 5 8.271478E+05 7.818662E+02 + 2.650006E+01 6 6 9.122811E+05 2.380852E+01 + 2.660007E+01 1 1 2.025781E+03 7.621777E+00 + 2.660007E+01 1 5 -1.037016E+04 7.702213E+01 + 2.660007E+01 2 2 2.299993E+03 8.673573E+00 + 2.660007E+01 2 4 1.464148E+04 2.858478E+01 + 2.660007E+01 3 3 2.249433E+03 2.017079E+02 + 2.660007E+01 4 2 1.465809E+04 2.868768E+01 + 2.660007E+01 4 4 2.709197E+05 9.456152E+01 + 2.660007E+01 5 1 -1.038811E+04 7.682086E+01 + 2.660007E+01 5 5 8.271452E+05 7.761916E+02 + 2.660007E+01 6 6 9.122217E+05 2.341624E+01 + 2.670007E+01 1 1 2.025589E+03 7.553147E+00 + 2.670007E+01 1 5 -1.036999E+04 7.639590E+01 + 2.670007E+01 2 2 2.299744E+03 8.594369E+00 + 2.670007E+01 2 4 1.464042E+04 2.831405E+01 + 2.670007E+01 3 3 2.250092E+03 2.018210E+02 + 2.670007E+01 4 2 1.465705E+04 2.841756E+01 + 2.670007E+01 4 4 2.709153E+05 9.364024E+01 + 2.670007E+01 5 1 -1.038798E+04 7.619834E+01 + 2.670007E+01 5 5 8.271442E+05 7.705438E+02 + 2.670007E+01 6 6 9.121616E+05 2.302403E+01 + 2.680007E+01 1 1 2.025398E+03 7.485611E+00 + 2.680007E+01 1 5 -1.036985E+04 7.577713E+01 + 2.680007E+01 2 2 2.299498E+03 8.516093E+00 + 2.680007E+01 2 4 1.463934E+04 2.804749E+01 + 2.680007E+01 3 3 2.250717E+03 2.019380E+02 + 2.680007E+01 4 2 1.465599E+04 2.814923E+01 + 2.680007E+01 4 4 2.709104E+05 9.271354E+01 + 2.680007E+01 5 1 -1.038785E+04 7.557999E+01 + 2.680007E+01 5 5 8.271412E+05 7.649456E+02 + 2.680007E+01 6 6 9.121021E+05 2.261722E+01 + 2.690007E+01 1 1 2.025213E+03 7.418912E+00 + 2.690007E+01 1 5 -1.036984E+04 7.516774E+01 + 2.690007E+01 2 2 2.299252E+03 8.439022E+00 + 2.690007E+01 2 4 1.463833E+04 2.778351E+01 + 2.690007E+01 3 3 2.251357E+03 2.020509E+02 + 2.690007E+01 4 2 1.465495E+04 2.788507E+01 + 2.690007E+01 4 4 2.709064E+05 9.180151E+01 + 2.690007E+01 5 1 -1.038777E+04 7.497178E+01 + 2.690007E+01 5 5 8.271384E+05 7.593719E+02 + 2.690007E+01 6 6 9.120447E+05 2.221501E+01 + 2.700007E+01 1 1 2.025029E+03 7.353319E+00 + 2.700007E+01 1 5 -1.036971E+04 7.456400E+01 + 2.700007E+01 2 2 2.299008E+03 8.362997E+00 + 2.700007E+01 2 4 1.463733E+04 2.752589E+01 + 2.700007E+01 3 3 2.251990E+03 2.021681E+02 + 2.700007E+01 4 2 1.465391E+04 2.762262E+01 + 2.700007E+01 4 4 2.709012E+05 9.091588E+01 + 2.700007E+01 5 1 -1.038770E+04 7.436827E+01 + 2.700007E+01 5 5 8.271402E+05 7.539083E+02 + 2.700007E+01 6 6 9.119880E+05 2.184375E+01 + 2.710007E+01 1 1 2.024842E+03 7.288342E+00 + 2.710007E+01 1 5 -1.036959E+04 7.396838E+01 + 2.710007E+01 2 2 2.298773E+03 8.288078E+00 + 2.710007E+01 2 4 1.463628E+04 2.726971E+01 + 2.710007E+01 3 3 2.252618E+03 2.022818E+02 + 2.710007E+01 4 2 1.465294E+04 2.736761E+01 + 2.710007E+01 4 4 2.708975E+05 9.004169E+01 + 2.710007E+01 5 1 -1.038757E+04 7.377531E+01 + 2.710007E+01 5 5 8.271379E+05 7.485558E+02 + 2.710007E+01 6 6 9.119296E+05 2.146154E+01 + 2.720007E+01 1 1 2.024660E+03 7.224402E+00 + 2.720007E+01 1 5 -1.036949E+04 7.338126E+01 + 2.720007E+01 2 2 2.298535E+03 8.214152E+00 + 2.720007E+01 2 4 1.463534E+04 2.701756E+01 + 2.720007E+01 3 3 2.253254E+03 2.023945E+02 + 2.720007E+01 4 2 1.465191E+04 2.711414E+01 + 2.720007E+01 4 4 2.708927E+05 8.917516E+01 + 2.720007E+01 5 1 -1.038744E+04 7.319016E+01 + 2.720007E+01 5 5 8.271361E+05 7.432085E+02 + 2.720007E+01 6 6 9.118745E+05 2.110249E+01 + 2.730007E+01 1 1 2.024485E+03 7.161346E+00 + 2.730007E+01 1 5 -1.036944E+04 7.279700E+01 + 2.730007E+01 2 2 2.298305E+03 8.141392E+00 + 2.730007E+01 2 4 1.463432E+04 2.676848E+01 + 2.730007E+01 3 3 2.253865E+03 2.025052E+02 + 2.730007E+01 4 2 1.465092E+04 2.686798E+01 + 2.730007E+01 4 4 2.708882E+05 8.831751E+01 + 2.730007E+01 5 1 -1.038731E+04 7.260977E+01 + 2.730007E+01 5 5 8.271354E+05 7.380906E+02 + 2.730007E+01 6 6 9.118178E+05 2.074540E+01 + 2.740007E+01 1 1 2.024305E+03 7.099033E+00 + 2.740007E+01 1 5 -1.036927E+04 7.222258E+01 + 2.740007E+01 2 2 2.298073E+03 8.069516E+00 + 2.740007E+01 2 4 1.463330E+04 2.652415E+01 + 2.740007E+01 3 3 2.254494E+03 2.026157E+02 + 2.740007E+01 4 2 1.464994E+04 2.662088E+01 + 2.740007E+01 4 4 2.708835E+05 8.749374E+01 + 2.740007E+01 5 1 -1.038720E+04 7.203725E+01 + 2.740007E+01 5 5 8.271338E+05 7.327724E+02 + 2.740007E+01 6 6 9.117642E+05 2.041133E+01 + 2.750007E+01 1 1 2.024130E+03 7.037647E+00 + 2.750007E+01 1 5 -1.036916E+04 7.165567E+01 + 2.750007E+01 2 2 2.297844E+03 7.998565E+00 + 2.750007E+01 2 4 1.463234E+04 2.628375E+01 + 2.750007E+01 3 3 2.255115E+03 2.027203E+02 + 2.750007E+01 4 2 1.464895E+04 2.637799E+01 + 2.750007E+01 4 4 2.708794E+05 8.667188E+01 + 2.750007E+01 5 1 -1.038707E+04 7.146989E+01 + 2.750007E+01 5 5 8.271309E+05 7.276382E+02 + 2.750007E+01 6 6 9.117089E+05 2.006933E+01 + 2.760007E+01 1 1 2.023955E+03 6.977025E+00 + 2.760007E+01 1 5 -1.036909E+04 7.109379E+01 + 2.760007E+01 2 2 2.297618E+03 7.928640E+00 + 2.760007E+01 2 4 1.463141E+04 2.604533E+01 + 2.760007E+01 3 3 2.255740E+03 2.028272E+02 + 2.760007E+01 4 2 1.464803E+04 2.613900E+01 + 2.760007E+01 4 4 2.708758E+05 8.586026E+01 + 2.760007E+01 5 1 -1.038699E+04 7.091207E+01 + 2.760007E+01 5 5 8.271269E+05 7.225269E+02 + 2.760007E+01 6 6 9.116554E+05 1.974953E+01 + 2.770007E+01 1 1 2.023784E+03 6.917323E+00 + 2.770007E+01 1 5 -1.036900E+04 7.053949E+01 + 2.770007E+01 2 2 2.297396E+03 7.859682E+00 + 2.770007E+01 2 4 1.463049E+04 2.581096E+01 + 2.770007E+01 3 3 2.256353E+03 2.029345E+02 + 2.770007E+01 4 2 1.464711E+04 2.590321E+01 + 2.770007E+01 4 4 2.708718E+05 8.506426E+01 + 2.770007E+01 5 1 -1.038695E+04 7.036079E+01 + 2.770007E+01 5 5 8.271243E+05 7.174827E+02 + 2.770007E+01 6 6 9.116028E+05 1.942171E+01 + 2.780007E+01 1 1 2.023617E+03 6.858329E+00 + 2.780007E+01 1 5 -1.036893E+04 6.999146E+01 + 2.780007E+01 2 2 2.297175E+03 7.791627E+00 + 2.780007E+01 2 4 1.462958E+04 2.557955E+01 + 2.780007E+01 3 3 2.256959E+03 2.030356E+02 + 2.780007E+01 4 2 1.464617E+04 2.567141E+01 + 2.780007E+01 4 4 2.708678E+05 8.427245E+01 + 2.780007E+01 5 1 -1.038686E+04 6.981249E+01 + 2.780007E+01 5 5 8.271239E+05 7.124775E+02 + 2.780007E+01 6 6 9.115508E+05 1.909354E+01 + 2.790007E+01 1 1 2.023452E+03 6.800189E+00 + 2.790007E+01 1 5 -1.036882E+04 6.944979E+01 + 2.790007E+01 2 2 2.296957E+03 7.724570E+00 + 2.790007E+01 2 4 1.462867E+04 2.535101E+01 + 2.790007E+01 3 3 2.257559E+03 2.031380E+02 + 2.790007E+01 4 2 1.464524E+04 2.544406E+01 + 2.790007E+01 4 4 2.708638E+05 8.349791E+01 + 2.790007E+01 5 1 -1.038676E+04 6.927383E+01 + 2.790007E+01 5 5 8.271224E+05 7.076198E+02 + 2.790007E+01 6 6 9.114988E+05 1.877842E+01 + 2.800007E+01 1 1 2.023283E+03 6.742652E+00 + 2.800007E+01 1 5 -1.036878E+04 6.891540E+01 + 2.800007E+01 2 2 2.296742E+03 7.658345E+00 + 2.800007E+01 2 4 1.462775E+04 2.512676E+01 + 2.800007E+01 3 3 2.258170E+03 2.032396E+02 + 2.800007E+01 4 2 1.464432E+04 2.521779E+01 + 2.800007E+01 4 4 2.708600E+05 8.273849E+01 + 2.800007E+01 5 1 -1.038664E+04 6.874118E+01 + 2.800007E+01 5 5 8.271211E+05 7.025291E+02 + 2.800007E+01 6 6 9.114471E+05 1.849010E+01 + 2.810007E+01 1 1 2.023123E+03 6.686055E+00 + 2.810007E+01 1 5 -1.036874E+04 6.838612E+01 + 2.810007E+01 2 2 2.296533E+03 7.593006E+00 + 2.810007E+01 2 4 1.462683E+04 2.490490E+01 + 2.810007E+01 3 3 2.258761E+03 2.033406E+02 + 2.810007E+01 4 2 1.464339E+04 2.499499E+01 + 2.810007E+01 4 4 2.708557E+05 8.199215E+01 + 2.810007E+01 5 1 -1.038655E+04 6.821239E+01 + 2.810007E+01 5 5 8.271199E+05 6.977377E+02 + 2.810007E+01 6 6 9.113975E+05 1.816499E+01 + 2.820007E+01 1 1 2.022958E+03 6.630203E+00 + 2.820007E+01 1 5 -1.036865E+04 6.786447E+01 + 2.820007E+01 2 2 2.296320E+03 7.528441E+00 + 2.820007E+01 2 4 1.462592E+04 2.468571E+01 + 2.820007E+01 3 3 2.259373E+03 2.034409E+02 + 2.820007E+01 4 2 1.464251E+04 2.477601E+01 + 2.820007E+01 4 4 2.708516E+05 8.123376E+01 + 2.820007E+01 5 1 -1.038648E+04 6.769152E+01 + 2.820007E+01 5 5 8.271199E+05 6.929471E+02 + 2.820007E+01 6 6 9.113474E+05 1.788164E+01 + 2.830007E+01 1 1 2.022800E+03 6.574834E+00 + 2.830007E+01 1 5 -1.036855E+04 6.734870E+01 + 2.830007E+01 2 2 2.296111E+03 7.464828E+00 + 2.830007E+01 2 4 1.462505E+04 2.447008E+01 + 2.830007E+01 3 3 2.259954E+03 2.035383E+02 + 2.830007E+01 4 2 1.464161E+04 2.455857E+01 + 2.830007E+01 4 4 2.708472E+05 8.050271E+01 + 2.830007E+01 5 1 -1.038641E+04 6.717837E+01 + 2.830007E+01 5 5 8.271189E+05 6.880599E+02 + 2.830007E+01 6 6 9.112978E+05 1.759614E+01 + 2.840007E+01 1 1 2.022639E+03 6.520379E+00 + 2.840007E+01 1 5 -1.036848E+04 6.683736E+01 + 2.840007E+01 2 2 2.295906E+03 7.402006E+00 + 2.840007E+01 2 4 1.462417E+04 2.425698E+01 + 2.840007E+01 3 3 2.260552E+03 2.036387E+02 + 2.840007E+01 4 2 1.464076E+04 2.434486E+01 + 2.840007E+01 4 4 2.708432E+05 7.977916E+01 + 2.840007E+01 5 1 -1.038631E+04 6.666644E+01 + 2.840007E+01 5 5 8.271157E+05 6.834644E+02 + 2.840007E+01 6 6 9.112480E+05 1.732650E+01 + 2.850007E+01 1 1 2.022484E+03 6.466599E+00 + 2.850007E+01 1 5 -1.036837E+04 6.633269E+01 + 2.850007E+01 2 2 2.295702E+03 7.340121E+00 + 2.850007E+01 2 4 1.462332E+04 2.404779E+01 + 2.850007E+01 3 3 2.261145E+03 2.037362E+02 + 2.850007E+01 4 2 1.463989E+04 2.413595E+01 + 2.850007E+01 4 4 2.708399E+05 7.907157E+01 + 2.850007E+01 5 1 -1.038626E+04 6.616535E+01 + 2.850007E+01 5 5 8.271139E+05 6.787702E+02 + 2.850007E+01 6 6 9.112001E+05 1.703636E+01 + 2.860007E+01 1 1 2.022328E+03 6.413464E+00 + 2.860007E+01 1 5 -1.036833E+04 6.583296E+01 + 2.860007E+01 2 2 2.295498E+03 7.278941E+00 + 2.860007E+01 2 4 1.462247E+04 2.384022E+01 + 2.860007E+01 3 3 2.261726E+03 2.038280E+02 + 2.860007E+01 4 2 1.463903E+04 2.392797E+01 + 2.860007E+01 4 4 2.708364E+05 7.836884E+01 + 2.860007E+01 5 1 -1.038620E+04 6.566795E+01 + 2.860007E+01 5 5 8.271121E+05 6.740529E+02 + 2.860007E+01 6 6 9.111522E+05 1.674174E+01 + 2.870007E+01 1 1 2.022170E+03 6.361094E+00 + 2.870007E+01 1 5 -1.036829E+04 6.534035E+01 + 2.870007E+01 2 2 2.295301E+03 7.218606E+00 + 2.870007E+01 2 4 1.462165E+04 2.363672E+01 + 2.870007E+01 3 3 2.262323E+03 2.039178E+02 + 2.870007E+01 4 2 1.463819E+04 2.372230E+01 + 2.870007E+01 4 4 2.708327E+05 7.768160E+01 + 2.870007E+01 5 1 -1.038616E+04 6.517496E+01 + 2.870007E+01 5 5 8.271101E+05 6.694837E+02 + 2.870007E+01 6 6 9.111051E+05 1.650031E+01 + 2.880007E+01 1 1 2.022024E+03 6.309087E+00 + 2.880007E+01 1 5 -1.036821E+04 6.485181E+01 + 2.880007E+01 2 2 2.295105E+03 7.158854E+00 + 2.880007E+01 2 4 1.462082E+04 2.343510E+01 + 2.880007E+01 3 3 2.262901E+03 2.040123E+02 + 2.880007E+01 4 2 1.463736E+04 2.351902E+01 + 2.880007E+01 4 4 2.708287E+05 7.700045E+01 + 2.880007E+01 5 1 -1.038609E+04 6.468934E+01 + 2.880007E+01 5 5 8.271091E+05 6.650147E+02 + 2.880007E+01 6 6 9.110579E+05 1.625590E+01 + 2.890007E+01 1 1 2.021871E+03 6.258068E+00 + 2.890007E+01 1 5 -1.036815E+04 6.437022E+01 + 2.890007E+01 2 2 2.294912E+03 7.100051E+00 + 2.890007E+01 2 4 1.461996E+04 2.323535E+01 + 2.890007E+01 3 3 2.263477E+03 2.041029E+02 + 2.890007E+01 4 2 1.463655E+04 2.331953E+01 + 2.890007E+01 4 4 2.708250E+05 7.632709E+01 + 2.890007E+01 5 1 -1.038606E+04 6.420971E+01 + 2.890007E+01 5 5 8.271060E+05 6.604647E+02 + 2.890007E+01 6 6 9.110112E+05 1.598374E+01 + 2.900007E+01 1 1 2.021721E+03 6.207590E+00 + 2.900007E+01 1 5 -1.036804E+04 6.389341E+01 + 2.900007E+01 2 2 2.294715E+03 7.041935E+00 + 2.900007E+01 2 4 1.461917E+04 2.304024E+01 + 2.900007E+01 3 3 2.264055E+03 2.041899E+02 + 2.900007E+01 4 2 1.463569E+04 2.312125E+01 + 2.900007E+01 4 4 2.708212E+05 7.566386E+01 + 2.900007E+01 5 1 -1.038595E+04 6.373272E+01 + 2.900007E+01 5 5 8.271059E+05 6.560548E+02 + 2.900007E+01 6 6 9.109660E+05 1.574792E+01 + 2.910007E+01 1 1 2.021573E+03 6.157659E+00 + 2.910007E+01 1 5 -1.036800E+04 6.342225E+01 + 2.910007E+01 2 2 2.294522E+03 6.984544E+00 + 2.910007E+01 2 4 1.461833E+04 2.284501E+01 + 2.910007E+01 3 3 2.264625E+03 2.042838E+02 + 2.910007E+01 4 2 1.463491E+04 2.292676E+01 + 2.910007E+01 4 4 2.708181E+05 7.500017E+01 + 2.910007E+01 5 1 -1.038590E+04 6.326410E+01 + 2.910007E+01 5 5 8.271073E+05 6.516302E+02 + 2.910007E+01 6 6 9.109204E+05 1.547230E+01 + 2.920008E+01 1 1 2.021426E+03 6.108489E+00 + 2.920008E+01 1 5 -1.036796E+04 6.295671E+01 + 2.920008E+01 2 2 2.294335E+03 6.927901E+00 + 2.920008E+01 2 4 1.461756E+04 2.265427E+01 + 2.920008E+01 3 3 2.265196E+03 2.043726E+02 + 2.920008E+01 4 2 1.463408E+04 2.273553E+01 + 2.920008E+01 4 4 2.708147E+05 7.435568E+01 + 2.920008E+01 5 1 -1.038581E+04 6.280007E+01 + 2.920008E+01 5 5 8.271033E+05 6.472724E+02 + 2.920008E+01 6 6 9.108755E+05 1.525361E+01 + 2.930008E+01 1 1 2.021280E+03 6.059825E+00 + 2.930008E+01 1 5 -1.036789E+04 6.249568E+01 + 2.930008E+01 2 2 2.294149E+03 6.872046E+00 + 2.930008E+01 2 4 1.461680E+04 2.246572E+01 + 2.930008E+01 3 3 2.265770E+03 2.044607E+02 + 2.930008E+01 4 2 1.463332E+04 2.254597E+01 + 2.930008E+01 4 4 2.708115E+05 7.371797E+01 + 2.930008E+01 5 1 -1.038576E+04 6.234050E+01 + 2.930008E+01 5 5 8.270998E+05 6.429332E+02 + 2.930008E+01 6 6 9.108319E+05 1.502413E+01 + 2.940008E+01 1 1 2.021138E+03 6.011852E+00 + 2.940008E+01 1 5 -1.036782E+04 6.203848E+01 + 2.940008E+01 2 2 2.293958E+03 6.816762E+00 + 2.940008E+01 2 4 1.461598E+04 2.227993E+01 + 2.940008E+01 3 3 2.266332E+03 2.045479E+02 + 2.940008E+01 4 2 1.463253E+04 2.235858E+01 + 2.940008E+01 4 4 2.708084E+05 7.308825E+01 + 2.940008E+01 5 1 -1.038572E+04 6.188339E+01 + 2.940008E+01 5 5 8.270981E+05 6.387080E+02 + 2.940008E+01 6 6 9.107879E+05 1.480074E+01 + 2.950008E+01 1 1 2.020998E+03 5.964438E+00 + 2.950008E+01 1 5 -1.036776E+04 6.158921E+01 + 2.950008E+01 2 2 2.293778E+03 6.762341E+00 + 2.950008E+01 2 4 1.461521E+04 2.209564E+01 + 2.950008E+01 3 3 2.266894E+03 2.046373E+02 + 2.950008E+01 4 2 1.463177E+04 2.217491E+01 + 2.950008E+01 4 4 2.708047E+05 7.246009E+01 + 2.950008E+01 5 1 -1.038566E+04 6.143720E+01 + 2.950008E+01 5 5 8.270965E+05 6.344276E+02 + 2.950008E+01 6 6 9.107442E+05 1.456672E+01 + 2.960008E+01 1 1 2.020856E+03 5.917544E+00 + 2.960008E+01 1 5 -1.036768E+04 6.114288E+01 + 2.960008E+01 2 2 2.293596E+03 6.708459E+00 + 2.960008E+01 2 4 1.461445E+04 2.191437E+01 + 2.960008E+01 3 3 2.267466E+03 2.047225E+02 + 2.960008E+01 4 2 1.463100E+04 2.199310E+01 + 2.960008E+01 4 4 2.708009E+05 7.186835E+01 + 2.960008E+01 5 1 -1.038560E+04 6.099097E+01 + 2.960008E+01 5 5 8.270942E+05 6.302792E+02 + 2.960008E+01 6 6 9.107021E+05 1.434396E+01 + 2.970008E+01 1 1 2.020719E+03 5.871214E+00 + 2.970008E+01 1 5 -1.036767E+04 6.070256E+01 + 2.970008E+01 2 2 2.293414E+03 6.655274E+00 + 2.970008E+01 2 4 1.461368E+04 2.173527E+01 + 2.970008E+01 3 3 2.268023E+03 2.048034E+02 + 2.970008E+01 4 2 1.463019E+04 2.181270E+01 + 2.970008E+01 4 4 2.707975E+05 7.125802E+01 + 2.970008E+01 5 1 -1.038563E+04 6.055035E+01 + 2.970008E+01 5 5 8.270915E+05 6.261959E+02 + 2.970008E+01 6 6 9.106592E+05 1.412324E+01 + 2.980008E+01 1 1 2.020583E+03 5.825470E+00 + 2.980008E+01 1 5 -1.036769E+04 6.026657E+01 + 2.980008E+01 2 2 2.293240E+03 6.602677E+00 + 2.980008E+01 2 4 1.461294E+04 2.155863E+01 + 2.980008E+01 3 3 2.268576E+03 2.048897E+02 + 2.980008E+01 4 2 1.462945E+04 2.163625E+01 + 2.980008E+01 4 4 2.707938E+05 7.064493E+01 + 2.980008E+01 5 1 -1.038553E+04 6.011567E+01 + 2.980008E+01 5 5 8.270897E+05 6.220324E+02 + 2.980008E+01 6 6 9.106178E+05 1.393097E+01 + 2.990008E+01 1 1 2.020447E+03 5.780306E+00 + 2.990008E+01 1 5 -1.036763E+04 5.983643E+01 + 2.990008E+01 2 2 2.293064E+03 6.550907E+00 + 2.990008E+01 2 4 1.461221E+04 2.138336E+01 + 2.990008E+01 3 3 2.269145E+03 2.049725E+02 + 2.990008E+01 4 2 1.462872E+04 2.146172E+01 + 2.990008E+01 4 4 2.707909E+05 7.004963E+01 + 2.990008E+01 5 1 -1.038549E+04 5.968921E+01 + 2.990008E+01 5 5 8.270876E+05 6.179717E+02 + 2.990008E+01 6 6 9.105762E+05 1.371025E+01 + 3.000008E+01 1 1 2.020311E+03 5.735516E+00 + 3.000008E+01 1 5 -1.036755E+04 5.940879E+01 + 3.000008E+01 2 2 2.292889E+03 6.499515E+00 + 3.000008E+01 2 4 1.461148E+04 2.121048E+01 + 3.000008E+01 3 3 2.269689E+03 2.050517E+02 + 3.000008E+01 4 2 1.462802E+04 2.128679E+01 + 3.000008E+01 4 4 2.707882E+05 6.946275E+01 + 3.000008E+01 5 1 -1.038544E+04 5.926148E+01 + 3.000008E+01 5 5 8.270874E+05 6.139026E+02 + 3.000008E+01 6 6 9.105343E+05 1.350836E+01 + 3.010008E+01 1 1 2.020176E+03 5.691556E+00 + 3.010008E+01 1 5 -1.036749E+04 5.898837E+01 + 3.010008E+01 2 2 2.292721E+03 6.448809E+00 + 3.010008E+01 2 4 1.461075E+04 2.104004E+01 + 3.010008E+01 3 3 2.270232E+03 2.051338E+02 + 3.010008E+01 4 2 1.462729E+04 2.111545E+01 + 3.010008E+01 4 4 2.707848E+05 6.888127E+01 + 3.010008E+01 5 1 -1.038534E+04 5.883812E+01 + 3.010008E+01 5 5 8.270859E+05 6.097963E+02 + 3.010008E+01 6 6 9.104941E+05 1.329061E+01 + 3.020008E+01 1 1 2.020045E+03 5.647838E+00 + 3.020008E+01 1 5 -1.036748E+04 5.856982E+01 + 3.020008E+01 2 2 2.292547E+03 6.398825E+00 + 3.020008E+01 2 4 1.461003E+04 2.087177E+01 + 3.020008E+01 3 3 2.270784E+03 2.052098E+02 + 3.020008E+01 4 2 1.462657E+04 2.094711E+01 + 3.020008E+01 4 4 2.707821E+05 6.832902E+01 + 3.020008E+01 5 1 -1.038530E+04 5.842654E+01 + 3.020008E+01 5 5 8.270849E+05 6.059205E+02 + 3.020008E+01 6 6 9.104534E+05 1.311851E+01 + 3.030008E+01 1 1 2.019914E+03 5.604763E+00 + 3.030008E+01 1 5 -1.036745E+04 5.815787E+01 + 3.030008E+01 2 2 2.292382E+03 6.349491E+00 + 3.030008E+01 2 4 1.460933E+04 2.070590E+01 + 3.030008E+01 3 3 2.271326E+03 2.052895E+02 + 3.030008E+01 4 2 1.462586E+04 2.078091E+01 + 3.030008E+01 4 4 2.707782E+05 6.777458E+01 + 3.030008E+01 5 1 -1.038526E+04 5.801655E+01 + 3.030008E+01 5 5 8.270829E+05 6.018796E+02 + 3.030008E+01 6 6 9.104129E+05 1.291759E+01 + 3.040008E+01 1 1 2.019788E+03 5.562180E+00 + 3.040008E+01 1 5 -1.036744E+04 5.774894E+01 + 3.040008E+01 2 2 2.292213E+03 6.300581E+00 + 3.040008E+01 2 4 1.460862E+04 2.054165E+01 + 3.040008E+01 3 3 2.271875E+03 2.053652E+02 + 3.040008E+01 4 2 1.462515E+04 2.061540E+01 + 3.040008E+01 4 4 2.707755E+05 6.721703E+01 + 3.040008E+01 5 1 -1.038523E+04 5.760820E+01 + 3.040008E+01 5 5 8.270799E+05 5.981005E+02 + 3.040008E+01 6 6 9.103738E+05 1.272697E+01 + 3.050008E+01 1 1 2.019657E+03 5.520111E+00 + 3.050008E+01 1 5 -1.036739E+04 5.734531E+01 + 3.050008E+01 2 2 2.292048E+03 6.252312E+00 + 3.050008E+01 2 4 1.460792E+04 2.037868E+01 + 3.050008E+01 3 3 2.272415E+03 2.054393E+02 + 3.050008E+01 4 2 1.462445E+04 2.045273E+01 + 3.050008E+01 4 4 2.707728E+05 6.665411E+01 + 3.050008E+01 5 1 -1.038520E+04 5.720720E+01 + 3.050008E+01 5 5 8.270796E+05 5.941226E+02 + 3.050008E+01 6 6 9.103344E+05 1.254307E+01 + 3.060008E+01 1 1 2.019536E+03 5.478503E+00 + 3.060008E+01 1 5 -1.036736E+04 5.694650E+01 + 3.060008E+01 2 2 2.291885E+03 6.204667E+00 + 3.060008E+01 2 4 1.460723E+04 2.022026E+01 + 3.060008E+01 3 3 2.272950E+03 2.055196E+02 + 3.060008E+01 4 2 1.462376E+04 2.029109E+01 + 3.060008E+01 4 4 2.707699E+05 6.612585E+01 + 3.060008E+01 5 1 -1.038516E+04 5.680798E+01 + 3.060008E+01 5 5 8.270776E+05 5.904149E+02 + 3.060008E+01 6 6 9.102960E+05 1.237752E+01 + 3.070008E+01 1 1 2.019405E+03 5.437555E+00 + 3.070008E+01 1 5 -1.036729E+04 5.655041E+01 + 3.070008E+01 2 2 2.291720E+03 6.157564E+00 + 3.070008E+01 2 4 1.460656E+04 2.006185E+01 + 3.070008E+01 3 3 2.273484E+03 2.055976E+02 + 3.070008E+01 4 2 1.462307E+04 2.013314E+01 + 3.070008E+01 4 4 2.707660E+05 6.559805E+01 + 3.070008E+01 5 1 -1.038508E+04 5.641356E+01 + 3.070008E+01 5 5 8.270776E+05 5.865265E+02 + 3.070008E+01 6 6 9.102575E+05 1.220172E+01 + 3.080008E+01 1 1 2.019276E+03 5.396836E+00 + 3.080008E+01 1 5 -1.036728E+04 5.615812E+01 + 3.080008E+01 2 2 2.291559E+03 6.110959E+00 + 3.080008E+01 2 4 1.460588E+04 1.990582E+01 + 3.080008E+01 3 3 2.274016E+03 2.056712E+02 + 3.080008E+01 4 2 1.462238E+04 1.997769E+01 + 3.080008E+01 4 4 2.707626E+05 6.506673E+01 + 3.080008E+01 5 1 -1.038507E+04 5.602548E+01 + 3.080008E+01 5 5 8.270770E+05 5.828536E+02 + 3.080008E+01 6 6 9.102211E+05 1.201544E+01 + 3.090008E+01 1 1 2.019156E+03 5.356817E+00 + 3.090008E+01 1 5 -1.036729E+04 5.577095E+01 + 3.090008E+01 2 2 2.291398E+03 6.064867E+00 + 3.090008E+01 2 4 1.460524E+04 1.975068E+01 + 3.090008E+01 3 3 2.274535E+03 2.057437E+02 + 3.090008E+01 4 2 1.462171E+04 1.982124E+01 + 3.090008E+01 4 4 2.707598E+05 6.454514E+01 + 3.090008E+01 5 1 -1.038501E+04 5.563477E+01 + 3.090008E+01 5 5 8.270751E+05 5.790355E+02 + 3.090008E+01 6 6 9.101829E+05 1.183959E+01 + 3.100008E+01 1 1 2.019033E+03 5.317164E+00 + 3.100008E+01 1 5 -1.036725E+04 5.538704E+01 + 3.100008E+01 2 2 2.291246E+03 6.019514E+00 + 3.100008E+01 2 4 1.460456E+04 1.959860E+01 + 3.100008E+01 3 3 2.275073E+03 2.058216E+02 + 3.100008E+01 4 2 1.462105E+04 1.966796E+01 + 3.100008E+01 4 4 2.707573E+05 6.404614E+01 + 3.100008E+01 5 1 -1.038495E+04 5.525334E+01 + 3.100008E+01 5 5 8.270769E+05 5.755447E+02 + 3.100008E+01 6 6 9.101450E+05 1.168376E+01 + 3.110008E+01 1 1 2.018913E+03 5.277853E+00 + 3.110008E+01 1 5 -1.036723E+04 5.500767E+01 + 3.110008E+01 2 2 2.291091E+03 5.974467E+00 + 3.110008E+01 2 4 1.460391E+04 1.944839E+01 + 3.110008E+01 3 3 2.275623E+03 2.058917E+02 + 3.110008E+01 4 2 1.462045E+04 1.951746E+01 + 3.110008E+01 4 4 2.707550E+05 6.353241E+01 + 3.110008E+01 5 1 -1.038495E+04 5.487522E+01 + 3.110008E+01 5 5 8.270759E+05 5.717247E+02 + 3.110008E+01 6 6 9.101077E+05 1.152268E+01 + 3.120008E+01 1 1 2.018791E+03 5.239028E+00 + 3.120008E+01 1 5 -1.036722E+04 5.463159E+01 + 3.120008E+01 2 2 2.290933E+03 5.930074E+00 + 3.120008E+01 2 4 1.460327E+04 1.929932E+01 + 3.120008E+01 3 3 2.276146E+03 2.059699E+02 + 3.120008E+01 4 2 1.461975E+04 1.936892E+01 + 3.120008E+01 4 4 2.707526E+05 6.303081E+01 + 3.120008E+01 5 1 -1.038495E+04 5.449835E+01 + 3.120008E+01 5 5 8.270733E+05 5.683505E+02 + 3.120008E+01 6 6 9.100716E+05 1.135478E+01 + 3.130008E+01 1 1 2.018671E+03 5.200728E+00 + 3.130008E+01 1 5 -1.036720E+04 5.426095E+01 + 3.130008E+01 2 2 2.290780E+03 5.886132E+00 + 3.130008E+01 2 4 1.460259E+04 1.915292E+01 + 3.130008E+01 3 3 2.276664E+03 2.060374E+02 + 3.130008E+01 4 2 1.461911E+04 1.922163E+01 + 3.130008E+01 4 4 2.707492E+05 6.254450E+01 + 3.130008E+01 5 1 -1.038491E+04 5.413215E+01 + 3.130008E+01 5 5 8.270704E+05 5.646052E+02 + 3.130008E+01 6 6 9.100346E+05 1.118837E+01 + 3.140008E+01 1 1 2.018555E+03 5.162685E+00 + 3.140008E+01 1 5 -1.036716E+04 5.389315E+01 + 3.140008E+01 2 2 2.290628E+03 5.842745E+00 + 3.140008E+01 2 4 1.460196E+04 1.900646E+01 + 3.140008E+01 3 3 2.277192E+03 2.061052E+02 + 3.140008E+01 4 2 1.461847E+04 1.907387E+01 + 3.140008E+01 4 4 2.707464E+05 6.204185E+01 + 3.140008E+01 5 1 -1.038491E+04 5.376302E+01 + 3.140008E+01 5 5 8.270689E+05 5.611432E+02 + 3.140008E+01 6 6 9.100006E+05 1.101737E+01 + 3.150008E+01 1 1 2.018440E+03 5.125191E+00 + 3.150008E+01 1 5 -1.036712E+04 5.352942E+01 + 3.150008E+01 2 2 2.290478E+03 5.799845E+00 + 3.150008E+01 2 4 1.460136E+04 1.886304E+01 + 3.150008E+01 3 3 2.277707E+03 2.061735E+02 + 3.150008E+01 4 2 1.461787E+04 1.893100E+01 + 3.150008E+01 4 4 2.707439E+05 6.156284E+01 + 3.150008E+01 5 1 -1.038488E+04 5.339945E+01 + 3.150008E+01 5 5 8.270657E+05 5.576572E+02 + 3.150008E+01 6 6 9.099652E+05 1.087240E+01 + 3.160008E+01 1 1 2.018327E+03 5.088073E+00 + 3.160008E+01 1 5 -1.036709E+04 5.316983E+01 + 3.160008E+01 2 2 2.290333E+03 5.757326E+00 + 3.160008E+01 2 4 1.460073E+04 1.872107E+01 + 3.160008E+01 3 3 2.278215E+03 2.062425E+02 + 3.160008E+01 4 2 1.461724E+04 1.878803E+01 + 3.160008E+01 4 4 2.707412E+05 6.109447E+01 + 3.160008E+01 5 1 -1.038488E+04 5.304378E+01 + 3.160008E+01 5 5 8.270635E+05 5.541365E+02 + 3.160008E+01 6 6 9.099310E+05 1.072399E+01 + 3.170008E+01 1 1 2.018213E+03 5.051478E+00 + 3.170008E+01 1 5 -1.036707E+04 5.281169E+01 + 3.170008E+01 2 2 2.290188E+03 5.715494E+00 + 3.170008E+01 2 4 1.460011E+04 1.858160E+01 + 3.170008E+01 3 3 2.278729E+03 2.063118E+02 + 3.170008E+01 4 2 1.461665E+04 1.864968E+01 + 3.170008E+01 4 4 2.707382E+05 6.062715E+01 + 3.170008E+01 5 1 -1.038485E+04 5.268708E+01 + 3.170008E+01 5 5 8.270635E+05 5.507777E+02 + 3.170008E+01 6 6 9.098956E+05 1.056697E+01 + 3.180009E+01 1 1 2.018096E+03 5.015356E+00 + 3.180009E+01 1 5 -1.036704E+04 5.246017E+01 + 3.180009E+01 2 2 2.290042E+03 5.674034E+00 + 3.180009E+01 2 4 1.459948E+04 1.844287E+01 + 3.180009E+01 3 3 2.279241E+03 2.063776E+02 + 3.180009E+01 4 2 1.461601E+04 1.850991E+01 + 3.180009E+01 4 4 2.707358E+05 6.015704E+01 + 3.180009E+01 5 1 -1.038482E+04 5.233337E+01 + 3.180009E+01 5 5 8.270618E+05 5.472370E+02 + 3.180009E+01 6 6 9.098625E+05 1.042886E+01 + 3.190009E+01 1 1 2.017987E+03 4.979373E+00 + 3.190009E+01 1 5 -1.036703E+04 5.211030E+01 + 3.190009E+01 2 2 2.289895E+03 5.632864E+00 + 3.190009E+01 2 4 1.459887E+04 1.830628E+01 + 3.190009E+01 3 3 2.279764E+03 2.064400E+02 + 3.190009E+01 4 2 1.461540E+04 1.837126E+01 + 3.190009E+01 4 4 2.707333E+05 5.970638E+01 + 3.190009E+01 5 1 -1.038481E+04 5.198465E+01 + 3.190009E+01 5 5 8.270599E+05 5.440458E+02 + 3.190009E+01 6 6 9.098271E+05 1.028428E+01 + 3.200008E+01 1 1 2.017874E+03 4.943982E+00 + 3.200008E+01 1 5 -1.036702E+04 5.176426E+01 + 3.200008E+01 2 2 2.289757E+03 5.592231E+00 + 3.200008E+01 2 4 1.459829E+04 1.817052E+01 + 3.200008E+01 3 3 2.280292E+03 2.065081E+02 + 3.200008E+01 4 2 1.461478E+04 1.823516E+01 + 3.200008E+01 4 4 2.707302E+05 5.924137E+01 + 3.200008E+01 5 1 -1.038482E+04 5.163935E+01 + 3.200008E+01 5 5 8.270562E+05 5.406495E+02 + 3.200008E+01 6 6 9.097942E+05 1.014167E+01 + 3.210008E+01 1 1 2.017764E+03 4.908949E+00 + 3.210008E+01 1 5 -1.036700E+04 5.142149E+01 + 3.210008E+01 2 2 2.289612E+03 5.552336E+00 + 3.210008E+01 2 4 1.459767E+04 1.803678E+01 + 3.210008E+01 3 3 2.280788E+03 2.065727E+02 + 3.210008E+01 4 2 1.461417E+04 1.810139E+01 + 3.210008E+01 4 4 2.707278E+05 5.879571E+01 + 3.210008E+01 5 1 -1.038478E+04 5.129827E+01 + 3.210008E+01 5 5 8.270566E+05 5.372954E+02 + 3.210008E+01 6 6 9.097607E+05 1.001906E+01 + 3.220008E+01 1 1 2.017659E+03 4.874296E+00 + 3.220008E+01 1 5 -1.036699E+04 5.108210E+01 + 3.220008E+01 2 2 2.289474E+03 5.512514E+00 + 3.220008E+01 2 4 1.459714E+04 1.790340E+01 + 3.220008E+01 3 3 2.281296E+03 2.066397E+02 + 3.220008E+01 4 2 1.461361E+04 1.796741E+01 + 3.220008E+01 4 4 2.707253E+05 5.835419E+01 + 3.220008E+01 5 1 -1.038477E+04 5.096151E+01 + 3.220008E+01 5 5 8.270564E+05 5.340329E+02 + 3.220008E+01 6 6 9.097281E+05 9.872394E+00 + 3.230008E+01 1 1 2.017551E+03 4.839922E+00 + 3.230008E+01 1 5 -1.036698E+04 5.074788E+01 + 3.230008E+01 2 2 2.289334E+03 5.473316E+00 + 3.230008E+01 2 4 1.459653E+04 1.777277E+01 + 3.230008E+01 3 3 2.281800E+03 2.067076E+02 + 3.230008E+01 4 2 1.461301E+04 1.783599E+01 + 3.230008E+01 4 4 2.707227E+05 5.790337E+01 + 3.230008E+01 5 1 -1.038477E+04 5.062877E+01 + 3.230008E+01 5 5 8.270556E+05 5.307462E+02 + 3.230008E+01 6 6 9.096941E+05 9.739921E+00 + 3.240008E+01 1 1 2.017437E+03 4.805939E+00 + 3.240008E+01 1 5 -1.036695E+04 5.041497E+01 + 3.240008E+01 2 2 2.289196E+03 5.434473E+00 + 3.240008E+01 2 4 1.459595E+04 1.764435E+01 + 3.240008E+01 3 3 2.282287E+03 2.067744E+02 + 3.240008E+01 4 2 1.461248E+04 1.770653E+01 + 3.240008E+01 4 4 2.707203E+05 5.750328E+01 + 3.240008E+01 5 1 -1.038471E+04 5.029712E+01 + 3.240008E+01 5 5 8.270545E+05 5.275226E+02 + 3.240008E+01 6 6 9.096628E+05 9.595244E+00 + 3.250008E+01 1 1 2.017340E+03 4.772391E+00 + 3.250008E+01 1 5 -1.036696E+04 5.008792E+01 + 3.250008E+01 2 2 2.289060E+03 5.396129E+00 + 3.250008E+01 2 4 1.459537E+04 1.751562E+01 + 3.250008E+01 3 3 2.282792E+03 2.068363E+02 + 3.250008E+01 4 2 1.461189E+04 1.757891E+01 + 3.250008E+01 4 4 2.707179E+05 5.705292E+01 + 3.250008E+01 5 1 -1.038473E+04 4.996671E+01 + 3.250008E+01 5 5 8.270538E+05 5.243102E+02 + 3.250008E+01 6 6 9.096309E+05 9.462701E+00 + 3.260007E+01 1 1 2.017234E+03 4.739207E+00 + 3.260007E+01 1 5 -1.036696E+04 4.976168E+01 + 3.260007E+01 2 2 2.288923E+03 5.358119E+00 + 3.260007E+01 2 4 1.459480E+04 1.738945E+01 + 3.260007E+01 3 3 2.283295E+03 2.068985E+02 + 3.260007E+01 4 2 1.461133E+04 1.745126E+01 + 3.260007E+01 4 4 2.707153E+05 5.663148E+01 + 3.260007E+01 5 1 -1.038470E+04 4.964454E+01 + 3.260007E+01 5 5 8.270504E+05 5.211184E+02 + 3.260007E+01 6 6 9.095991E+05 9.349185E+00 + 3.270007E+01 1 1 2.017130E+03 4.706257E+00 + 3.270007E+01 1 5 -1.036695E+04 4.943787E+01 + 3.270007E+01 2 2 2.288792E+03 5.320659E+00 + 3.270007E+01 2 4 1.459423E+04 1.726386E+01 + 3.270007E+01 3 3 2.283775E+03 2.069594E+02 + 3.270007E+01 4 2 1.461072E+04 1.732748E+01 + 3.270007E+01 4 4 2.707130E+05 5.620590E+01 + 3.270007E+01 5 1 -1.038468E+04 4.932141E+01 + 3.270007E+01 5 5 8.270479E+05 5.179899E+02 + 3.270007E+01 6 6 9.095683E+05 9.226877E+00 + 3.280007E+01 1 1 2.017021E+03 4.673912E+00 + 3.280007E+01 1 5 -1.036695E+04 4.911926E+01 + 3.280007E+01 2 2 2.288657E+03 5.283504E+00 + 3.280007E+01 2 4 1.459371E+04 1.714091E+01 + 3.280007E+01 3 3 2.284278E+03 2.070224E+02 + 3.280007E+01 4 2 1.461020E+04 1.720206E+01 + 3.280007E+01 4 4 2.707109E+05 5.580116E+01 + 3.280007E+01 5 1 -1.038467E+04 4.900334E+01 + 3.280007E+01 5 5 8.270487E+05 5.147988E+02 + 3.280007E+01 6 6 9.095362E+05 9.102610E+00 + 3.290007E+01 1 1 2.016920E+03 4.641672E+00 + 3.290007E+01 1 5 -1.036695E+04 4.880312E+01 + 3.290007E+01 2 2 2.288530E+03 5.246795E+00 + 3.290007E+01 2 4 1.459318E+04 1.701746E+01 + 3.290007E+01 3 3 2.284770E+03 2.070830E+02 + 3.290007E+01 4 2 1.460967E+04 1.707979E+01 + 3.290007E+01 4 4 2.707084E+05 5.538412E+01 + 3.290007E+01 5 1 -1.038466E+04 4.868804E+01 + 3.290007E+01 5 5 8.270472E+05 5.117176E+02 + 3.290007E+01 6 6 9.095062E+05 8.964191E+00 + 3.300007E+01 1 1 2.016823E+03 4.609921E+00 + 3.300007E+01 1 5 -1.036692E+04 4.849102E+01 + 3.300007E+01 2 2 2.288396E+03 5.210488E+00 + 3.300007E+01 2 4 1.459259E+04 1.689742E+01 + 3.300007E+01 3 3 2.285267E+03 2.071416E+02 + 3.300007E+01 4 2 1.460912E+04 1.695896E+01 + 3.300007E+01 4 4 2.707057E+05 5.499294E+01 + 3.300007E+01 5 1 -1.038465E+04 4.837271E+01 + 3.300007E+01 5 5 8.270472E+05 5.086148E+02 + 3.300007E+01 6 6 9.094754E+05 8.860820E+00 + 3.310007E+01 1 1 2.016723E+03 4.578347E+00 + 3.310007E+01 1 5 -1.036692E+04 4.818066E+01 + 3.310007E+01 2 2 2.288265E+03 5.174525E+00 + 3.310007E+01 2 4 1.459206E+04 1.677721E+01 + 3.310007E+01 3 3 2.285750E+03 2.072039E+02 + 3.310007E+01 4 2 1.460856E+04 1.683876E+01 + 3.310007E+01 4 4 2.707030E+05 5.458032E+01 + 3.310007E+01 5 1 -1.038462E+04 4.806683E+01 + 3.310007E+01 5 5 8.270457E+05 5.056040E+02 + 3.310007E+01 6 6 9.094449E+05 8.742088E+00 + 3.320007E+01 1 1 2.016624E+03 4.547227E+00 + 3.320007E+01 1 5 -1.036691E+04 4.787306E+01 + 3.320007E+01 2 2 2.288140E+03 5.138874E+00 + 3.320007E+01 2 4 1.459153E+04 1.665984E+01 + 3.320007E+01 3 3 2.286236E+03 2.072601E+02 + 3.320007E+01 4 2 1.460801E+04 1.671791E+01 + 3.320007E+01 4 4 2.707005E+05 5.419601E+01 + 3.320007E+01 5 1 -1.038464E+04 4.775983E+01 + 3.320007E+01 5 5 8.270449E+05 5.025326E+02 + 3.320007E+01 6 6 9.094157E+05 8.613149E+00 + 3.330006E+01 1 1 2.016520E+03 4.516479E+00 + 3.330006E+01 1 5 -1.036689E+04 4.756926E+01 + 3.330006E+01 2 2 2.288014E+03 5.103774E+00 + 3.330006E+01 2 4 1.459101E+04 1.654124E+01 + 3.330006E+01 3 3 2.286714E+03 2.073202E+02 + 3.330006E+01 4 2 1.460747E+04 1.660173E+01 + 3.330006E+01 4 4 2.706984E+05 5.380000E+01 + 3.330006E+01 5 1 -1.038461E+04 4.745464E+01 + 3.330006E+01 5 5 8.270425E+05 4.996131E+02 + 3.330006E+01 6 6 9.093857E+05 8.524786E+00 + 3.340006E+01 1 1 2.016426E+03 4.485881E+00 + 3.340006E+01 1 5 -1.036688E+04 4.726738E+01 + 3.340006E+01 2 2 2.287889E+03 5.068748E+00 + 3.340006E+01 2 4 1.459050E+04 1.642647E+01 + 3.340006E+01 3 3 2.287211E+03 2.073812E+02 + 3.340006E+01 4 2 1.460694E+04 1.648383E+01 + 3.340006E+01 4 4 2.706957E+05 5.341031E+01 + 3.340006E+01 5 1 -1.038461E+04 4.715745E+01 + 3.340006E+01 5 5 8.270424E+05 4.966593E+02 + 3.340006E+01 6 6 9.093561E+05 8.395782E+00 + 3.350006E+01 1 1 2.016330E+03 4.455670E+00 + 3.350006E+01 1 5 -1.036687E+04 4.696966E+01 + 3.350006E+01 2 2 2.287764E+03 5.034426E+00 + 3.350006E+01 2 4 1.458995E+04 1.631194E+01 + 3.350006E+01 3 3 2.287693E+03 2.074359E+02 + 3.350006E+01 4 2 1.460639E+04 1.636994E+01 + 3.350006E+01 4 4 2.706933E+05 5.303030E+01 + 3.350006E+01 5 1 -1.038459E+04 4.685500E+01 + 3.350006E+01 5 5 8.270410E+05 4.938537E+02 + 3.350006E+01 6 6 9.093272E+05 8.291888E+00 + 3.360006E+01 1 1 2.016233E+03 4.425919E+00 + 3.360006E+01 1 5 -1.036687E+04 4.667384E+01 + 3.360006E+01 2 2 2.287640E+03 5.000275E+00 + 3.360006E+01 2 4 1.458945E+04 1.619874E+01 + 3.360006E+01 3 3 2.288165E+03 2.074917E+02 + 3.360006E+01 4 2 1.460593E+04 1.625585E+01 + 3.360006E+01 4 4 2.706908E+05 5.266426E+01 + 3.360006E+01 5 1 -1.038460E+04 4.656364E+01 + 3.360006E+01 5 5 8.270392E+05 4.909771E+02 + 3.360006E+01 6 6 9.092985E+05 8.204824E+00 + 3.370006E+01 1 1 2.016138E+03 4.396338E+00 + 3.370006E+01 1 5 -1.036684E+04 4.638142E+01 + 3.370006E+01 2 2 2.287520E+03 4.966541E+00 + 3.370006E+01 2 4 1.458894E+04 1.608651E+01 + 3.370006E+01 3 3 2.288650E+03 2.075475E+02 + 3.370006E+01 4 2 1.460541E+04 1.614312E+01 + 3.370006E+01 4 4 2.706893E+05 5.229510E+01 + 3.370006E+01 5 1 -1.038457E+04 4.627055E+01 + 3.370006E+01 5 5 8.270355E+05 4.880962E+02 + 3.370006E+01 6 6 9.092703E+05 8.084464E+00 + 3.380006E+01 1 1 2.016045E+03 4.367103E+00 + 3.380006E+01 1 5 -1.036684E+04 4.609216E+01 + 3.380006E+01 2 2 2.287403E+03 4.933120E+00 + 3.380006E+01 2 4 1.458843E+04 1.597518E+01 + 3.380006E+01 3 3 2.289120E+03 2.076039E+02 + 3.380006E+01 4 2 1.460491E+04 1.603291E+01 + 3.380006E+01 4 4 2.706877E+05 5.190708E+01 + 3.380006E+01 5 1 -1.038455E+04 4.598060E+01 + 3.380006E+01 5 5 8.270350E+05 4.853094E+02 + 3.380006E+01 6 6 9.092412E+05 7.976162E+00 + 3.390005E+01 1 1 2.015949E+03 4.338196E+00 + 3.390005E+01 1 5 -1.036685E+04 4.580481E+01 + 3.390005E+01 2 2 2.287287E+03 4.900265E+00 + 3.390005E+01 2 4 1.458795E+04 1.586637E+01 + 3.390005E+01 3 3 2.289604E+03 2.076568E+02 + 3.390005E+01 4 2 1.460442E+04 1.592403E+01 + 3.390005E+01 4 4 2.706852E+05 5.156547E+01 + 3.390005E+01 5 1 -1.038453E+04 4.569720E+01 + 3.390005E+01 5 5 8.270338E+05 4.825604E+02 + 3.390005E+01 6 6 9.092121E+05 7.871105E+00 + 3.400005E+01 1 1 2.015856E+03 4.309593E+00 + 3.400005E+01 1 5 -1.036685E+04 4.552005E+01 + 3.400005E+01 2 2 2.287164E+03 4.867426E+00 + 3.400005E+01 2 4 1.458746E+04 1.575765E+01 + 3.400005E+01 3 3 2.290076E+03 2.077110E+02 + 3.400005E+01 4 2 1.460389E+04 1.581393E+01 + 3.400005E+01 4 4 2.706827E+05 5.119024E+01 + 3.400005E+01 5 1 -1.038452E+04 4.541109E+01 + 3.400005E+01 5 5 8.270326E+05 4.797548E+02 + 3.400005E+01 6 6 9.091851E+05 7.758340E+00 + 3.410005E+01 1 1 2.015768E+03 4.281193E+00 + 3.410005E+01 1 5 -1.036686E+04 4.523862E+01 + 3.410005E+01 2 2 2.287047E+03 4.835074E+00 + 3.410005E+01 2 4 1.458695E+04 1.565111E+01 + 3.410005E+01 3 3 2.290538E+03 2.077658E+02 + 3.410005E+01 4 2 1.460339E+04 1.570616E+01 + 3.410005E+01 4 4 2.706812E+05 5.084045E+01 + 3.410005E+01 5 1 -1.038454E+04 4.513220E+01 + 3.410005E+01 5 5 8.270311E+05 4.770114E+02 + 3.410005E+01 6 6 9.091584E+05 7.683731E+00 + 3.420005E+01 1 1 2.015675E+03 4.253048E+00 + 3.420005E+01 1 5 -1.036686E+04 4.495928E+01 + 3.420005E+01 2 2 2.286929E+03 4.803030E+00 + 3.420005E+01 2 4 1.458647E+04 1.554398E+01 + 3.420005E+01 3 3 2.291025E+03 2.078207E+02 + 3.420005E+01 4 2 1.460291E+04 1.560094E+01 + 3.420005E+01 4 4 2.706788E+05 5.048122E+01 + 3.420005E+01 5 1 -1.038451E+04 4.485680E+01 + 3.420005E+01 5 5 8.270290E+05 4.742709E+02 + 3.420005E+01 6 6 9.091312E+05 7.576797E+00 + 3.430005E+01 1 1 2.015585E+03 4.225290E+00 + 3.430005E+01 1 5 -1.036684E+04 4.468171E+01 + 3.430005E+01 2 2 2.286815E+03 4.771332E+00 + 3.430005E+01 2 4 1.458599E+04 1.543985E+01 + 3.430005E+01 3 3 2.291477E+03 2.078787E+02 + 3.430005E+01 4 2 1.460240E+04 1.549469E+01 + 3.430005E+01 4 4 2.706766E+05 5.015277E+01 + 3.430005E+01 5 1 -1.038451E+04 4.457838E+01 + 3.430005E+01 5 5 8.270272E+05 4.715522E+02 + 3.430005E+01 6 6 9.091040E+05 7.477554E+00 + 3.440005E+01 1 1 2.015496E+03 4.197728E+00 + 3.440005E+01 1 5 -1.036685E+04 4.440840E+01 + 3.440005E+01 2 2 2.286698E+03 4.739777E+00 + 3.440005E+01 2 4 1.458552E+04 1.533499E+01 + 3.440005E+01 3 3 2.291962E+03 2.079289E+02 + 3.440005E+01 4 2 1.460196E+04 1.538827E+01 + 3.440005E+01 4 4 2.706739E+05 4.978912E+01 + 3.440005E+01 5 1 -1.038449E+04 4.430622E+01 + 3.440005E+01 5 5 8.270241E+05 4.688404E+02 + 3.440005E+01 6 6 9.090772E+05 7.395940E+00 + 3.450005E+01 1 1 2.015405E+03 4.170412E+00 + 3.450005E+01 1 5 -1.036687E+04 4.413768E+01 + 3.450005E+01 2 2 2.286585E+03 4.708874E+00 + 3.450005E+01 2 4 1.458503E+04 1.523254E+01 + 3.450005E+01 3 3 2.292417E+03 2.079803E+02 + 3.450005E+01 4 2 1.460149E+04 1.528508E+01 + 3.450005E+01 4 4 2.706719E+05 4.945317E+01 + 3.450005E+01 5 1 -1.038447E+04 4.403661E+01 + 3.450005E+01 5 5 8.270231E+05 4.661466E+02 + 3.450005E+01 6 6 9.090508E+05 7.301067E+00 + 3.460004E+01 1 1 2.015315E+03 4.143480E+00 + 3.460004E+01 1 5 -1.036686E+04 4.386974E+01 + 3.460004E+01 2 2 2.286471E+03 4.678228E+00 + 3.460004E+01 2 4 1.458455E+04 1.513015E+01 + 3.460004E+01 3 3 2.292882E+03 2.080340E+02 + 3.460004E+01 4 2 1.460100E+04 1.518415E+01 + 3.460004E+01 4 4 2.706701E+05 4.910672E+01 + 3.460004E+01 5 1 -1.038452E+04 4.376566E+01 + 3.460004E+01 5 5 8.270216E+05 4.635054E+02 + 3.460004E+01 6 6 9.090237E+05 7.195186E+00 + 3.470004E+01 1 1 2.015227E+03 4.116714E+00 + 3.470004E+01 1 5 -1.036687E+04 4.360286E+01 + 3.470004E+01 2 2 2.286358E+03 4.647609E+00 + 3.470004E+01 2 4 1.458411E+04 1.502911E+01 + 3.470004E+01 3 3 2.293344E+03 2.080855E+02 + 3.470004E+01 4 2 1.460052E+04 1.508169E+01 + 3.470004E+01 4 4 2.706681E+05 4.875842E+01 + 3.470004E+01 5 1 -1.038448E+04 4.350167E+01 + 3.470004E+01 5 5 8.270191E+05 4.608852E+02 + 3.470004E+01 6 6 9.089982E+05 7.106136E+00 + 3.480004E+01 1 1 2.015142E+03 4.090320E+00 + 3.480004E+01 1 5 -1.036687E+04 4.333912E+01 + 3.480004E+01 2 2 2.286249E+03 4.617640E+00 + 3.480004E+01 2 4 1.458365E+04 1.492969E+01 + 3.480004E+01 3 3 2.293805E+03 2.081361E+02 + 3.480004E+01 4 2 1.460007E+04 1.498302E+01 + 3.480004E+01 4 4 2.706668E+05 4.842900E+01 + 3.480004E+01 5 1 -1.038448E+04 4.323824E+01 + 3.480004E+01 5 5 8.270191E+05 4.582971E+02 + 3.480004E+01 6 6 9.089728E+05 7.022690E+00 + 3.490004E+01 1 1 2.015057E+03 4.064059E+00 + 3.490004E+01 1 5 -1.036686E+04 4.307823E+01 + 3.490004E+01 2 2 2.286138E+03 4.587818E+00 + 3.490004E+01 2 4 1.458317E+04 1.483146E+01 + 3.490004E+01 3 3 2.294267E+03 2.081891E+02 + 3.490004E+01 4 2 1.459957E+04 1.488393E+01 + 3.490004E+01 4 4 2.706646E+05 4.811267E+01 + 3.490004E+01 5 1 -1.038453E+04 4.297769E+01 + 3.490004E+01 5 5 8.270183E+05 4.556540E+02 + 3.490004E+01 6 6 9.089462E+05 6.917991E+00 + 3.500004E+01 1 1 2.014974E+03 4.038242E+00 + 3.500004E+01 1 5 -1.036686E+04 4.281962E+01 + 3.500004E+01 2 2 2.286031E+03 4.558277E+00 + 3.500004E+01 2 4 1.458272E+04 1.473320E+01 + 3.500004E+01 3 3 2.294720E+03 2.082394E+02 + 3.500004E+01 4 2 1.459917E+04 1.478656E+01 + 3.500004E+01 4 4 2.706616E+05 4.778054E+01 + 3.500004E+01 5 1 -1.038451E+04 4.272221E+01 + 3.500004E+01 5 5 8.270163E+05 4.531314E+02 + 3.500004E+01 6 6 9.089202E+05 6.880600E+00 + 3.510004E+01 1 1 2.014890E+03 4.012558E+00 + 3.510004E+01 1 5 -1.036687E+04 4.256192E+01 + 3.510004E+01 2 2 2.285925E+03 4.529027E+00 + 3.510004E+01 2 4 1.458226E+04 1.463627E+01 + 3.510004E+01 3 3 2.295181E+03 2.082935E+02 + 3.510004E+01 4 2 1.459873E+04 1.468997E+01 + 3.510004E+01 4 4 2.706599E+05 4.745867E+01 + 3.510004E+01 5 1 -1.038449E+04 4.246300E+01 + 3.510004E+01 5 5 8.270154E+05 4.506443E+02 + 3.510004E+01 6 6 9.088964E+05 6.768374E+00 + 3.520004E+01 1 1 2.014806E+03 3.987145E+00 + 3.520004E+01 1 5 -1.036688E+04 4.230813E+01 + 3.520004E+01 2 2 2.285819E+03 4.500180E+00 + 3.520004E+01 2 4 1.458183E+04 1.454078E+01 + 3.520004E+01 3 3 2.295638E+03 2.083421E+02 + 3.520004E+01 4 2 1.459829E+04 1.459465E+01 + 3.520004E+01 4 4 2.706578E+05 4.714349E+01 + 3.520004E+01 5 1 -1.038453E+04 4.221143E+01 + 3.520004E+01 5 5 8.270118E+05 4.480451E+02 + 3.520004E+01 6 6 9.088716E+05 6.701797E+00 + 3.530003E+01 1 1 2.014721E+03 3.961967E+00 + 3.530003E+01 1 5 -1.036688E+04 4.205690E+01 + 3.530003E+01 2 2 2.285710E+03 4.471429E+00 + 3.530003E+01 2 4 1.458140E+04 1.444557E+01 + 3.530003E+01 3 3 2.296075E+03 2.083899E+02 + 3.530003E+01 4 2 1.459782E+04 1.449875E+01 + 3.530003E+01 4 4 2.706565E+05 4.682458E+01 + 3.530003E+01 5 1 -1.038452E+04 4.196109E+01 + 3.530003E+01 5 5 8.270114E+05 4.454631E+02 + 3.530003E+01 6 6 9.088451E+05 6.628009E+00 + 3.540003E+01 1 1 2.014641E+03 3.937112E+00 + 3.540003E+01 1 5 -1.036688E+04 4.180603E+01 + 3.540003E+01 2 2 2.285606E+03 4.443066E+00 + 3.540003E+01 2 4 1.458094E+04 1.435173E+01 + 3.540003E+01 3 3 2.296527E+03 2.084387E+02 + 3.540003E+01 4 2 1.459735E+04 1.440475E+01 + 3.540003E+01 4 4 2.706543E+05 4.650591E+01 + 3.540003E+01 5 1 -1.038454E+04 4.170706E+01 + 3.540003E+01 5 5 8.270109E+05 4.429214E+02 + 3.540003E+01 6 6 9.088219E+05 6.531374E+00 + 3.550003E+01 1 1 2.014556E+03 3.912279E+00 + 3.550003E+01 1 5 -1.036689E+04 4.155991E+01 + 3.550003E+01 2 2 2.285500E+03 4.415036E+00 + 3.550003E+01 2 4 1.458051E+04 1.425879E+01 + 3.550003E+01 3 3 2.296977E+03 2.084841E+02 + 3.550003E+01 4 2 1.459695E+04 1.431260E+01 + 3.550003E+01 4 4 2.706526E+05 4.621085E+01 + 3.550003E+01 5 1 -1.038454E+04 4.146176E+01 + 3.550003E+01 5 5 8.270087E+05 4.403772E+02 + 3.550003E+01 6 6 9.087980E+05 6.446043E+00 + 3.560003E+01 1 1 2.014475E+03 3.887846E+00 + 3.560003E+01 1 5 -1.036690E+04 4.131449E+01 + 3.560003E+01 2 2 2.285396E+03 4.387096E+00 + 3.560003E+01 2 4 1.458007E+04 1.416779E+01 + 3.560003E+01 3 3 2.297422E+03 2.085316E+02 + 3.560003E+01 4 2 1.459651E+04 1.421849E+01 + 3.560003E+01 4 4 2.706507E+05 4.590120E+01 + 3.560003E+01 5 1 -1.038455E+04 4.121673E+01 + 3.560003E+01 5 5 8.270053E+05 4.379384E+02 + 3.560003E+01 6 6 9.087743E+05 6.395988E+00 + 3.570003E+01 1 1 2.014398E+03 3.863588E+00 + 3.570003E+01 1 5 -1.036689E+04 4.107110E+01 + 3.570003E+01 2 2 2.285297E+03 4.359519E+00 + 3.570003E+01 2 4 1.457967E+04 1.407619E+01 + 3.570003E+01 3 3 2.297862E+03 2.085768E+02 + 3.570003E+01 4 2 1.459609E+04 1.412744E+01 + 3.570003E+01 4 4 2.706492E+05 4.560065E+01 + 3.570003E+01 5 1 -1.038456E+04 4.097281E+01 + 3.570003E+01 5 5 8.270068E+05 4.355299E+02 + 3.570003E+01 6 6 9.087491E+05 6.296206E+00 + 3.580003E+01 1 1 2.014319E+03 3.839559E+00 + 3.580003E+01 1 5 -1.036694E+04 4.082942E+01 + 3.580003E+01 2 2 2.285198E+03 4.332125E+00 + 3.580003E+01 2 4 1.457925E+04 1.398566E+01 + 3.580003E+01 3 3 2.298314E+03 2.086242E+02 + 3.580003E+01 4 2 1.459565E+04 1.403448E+01 + 3.580003E+01 4 4 2.706472E+05 4.530075E+01 + 3.580003E+01 5 1 -1.038456E+04 4.073407E+01 + 3.580003E+01 5 5 8.270059E+05 4.330670E+02 + 3.580003E+01 6 6 9.087256E+05 6.223383E+00 + 3.590002E+01 1 1 2.014238E+03 3.815865E+00 + 3.590002E+01 1 5 -1.036691E+04 4.059029E+01 + 3.590002E+01 2 2 2.285099E+03 4.305130E+00 + 3.590002E+01 2 4 1.457883E+04 1.389585E+01 + 3.590002E+01 3 3 2.298744E+03 2.086712E+02 + 3.590002E+01 4 2 1.459520E+04 1.394486E+01 + 3.590002E+01 4 4 2.706457E+05 4.501206E+01 + 3.590002E+01 5 1 -1.038456E+04 4.049460E+01 + 3.590002E+01 5 5 8.270036E+05 4.307480E+02 + 3.590002E+01 6 6 9.087024E+05 6.137192E+00 + 3.600002E+01 1 1 2.014161E+03 3.792371E+00 + 3.600002E+01 1 5 -1.036691E+04 4.035513E+01 + 3.600002E+01 2 2 2.284994E+03 4.278384E+00 + 3.600002E+01 2 4 1.457840E+04 1.380830E+01 + 3.600002E+01 3 3 2.299196E+03 2.087150E+02 + 3.600002E+01 4 2 1.459481E+04 1.385685E+01 + 3.600002E+01 4 4 2.706433E+05 4.471947E+01 + 3.600002E+01 5 1 -1.038454E+04 4.025945E+01 + 3.600002E+01 5 5 8.270007E+05 4.284082E+02 + 3.600002E+01 6 6 9.086797E+05 6.051591E+00 + 3.610002E+01 1 1 2.014086E+03 3.769116E+00 + 3.610002E+01 1 5 -1.036692E+04 4.011861E+01 + 3.610002E+01 2 2 2.284889E+03 4.251763E+00 + 3.610002E+01 2 4 1.457801E+04 1.371976E+01 + 3.610002E+01 3 3 2.299630E+03 2.087659E+02 + 3.610002E+01 4 2 1.459439E+04 1.376857E+01 + 3.610002E+01 4 4 2.706420E+05 4.443511E+01 + 3.610002E+01 5 1 -1.038457E+04 4.002705E+01 + 3.610002E+01 5 5 8.269984E+05 4.259442E+02 + 3.610002E+01 6 6 9.086563E+05 5.992987E+00 + 3.620002E+01 1 1 2.014006E+03 3.746111E+00 + 3.620002E+01 1 5 -1.036692E+04 3.988753E+01 + 3.620002E+01 2 2 2.284796E+03 4.225507E+00 + 3.620002E+01 2 4 1.457761E+04 1.363379E+01 + 3.620002E+01 3 3 2.300075E+03 2.088064E+02 + 3.620002E+01 4 2 1.459399E+04 1.368159E+01 + 3.620002E+01 4 4 2.706406E+05 4.413845E+01 + 3.620002E+01 5 1 -1.038455E+04 3.979681E+01 + 3.620002E+01 5 5 8.269968E+05 4.236597E+02 + 3.620002E+01 6 6 9.086326E+05 5.921138E+00 + 3.630002E+01 1 1 2.013929E+03 3.723092E+00 + 3.630002E+01 1 5 -1.036695E+04 3.965751E+01 + 3.630002E+01 2 2 2.284698E+03 4.199479E+00 + 3.630002E+01 2 4 1.457719E+04 1.354688E+01 + 3.630002E+01 3 3 2.300512E+03 2.088537E+02 + 3.630002E+01 4 2 1.459358E+04 1.359741E+01 + 3.630002E+01 4 4 2.706387E+05 4.384367E+01 + 3.630002E+01 5 1 -1.038454E+04 3.956541E+01 + 3.630002E+01 5 5 8.269961E+05 4.213336E+02 + 3.630002E+01 6 6 9.086108E+05 5.842680E+00 + 3.640002E+01 1 1 2.013854E+03 3.700585E+00 + 3.640002E+01 1 5 -1.036697E+04 3.942788E+01 + 3.640002E+01 2 2 2.284603E+03 4.173742E+00 + 3.640002E+01 2 4 1.457679E+04 1.346271E+01 + 3.640002E+01 3 3 2.300946E+03 2.088989E+02 + 3.640002E+01 4 2 1.459318E+04 1.351140E+01 + 3.640002E+01 4 4 2.706373E+05 4.358760E+01 + 3.640002E+01 5 1 -1.038452E+04 3.933470E+01 + 3.640002E+01 5 5 8.269940E+05 4.189568E+02 + 3.640002E+01 6 6 9.085887E+05 5.776129E+00 + 3.650002E+01 1 1 2.013779E+03 3.678185E+00 + 3.650002E+01 1 5 -1.036697E+04 3.920206E+01 + 3.650002E+01 2 2 2.284505E+03 4.148209E+00 + 3.650002E+01 2 4 1.457640E+04 1.337872E+01 + 3.650002E+01 3 3 2.301379E+03 2.089395E+02 + 3.650002E+01 4 2 1.459278E+04 1.342655E+01 + 3.650002E+01 4 4 2.706354E+05 4.330577E+01 + 3.650002E+01 5 1 -1.038458E+04 3.911081E+01 + 3.650002E+01 5 5 8.269932E+05 4.167011E+02 + 3.650002E+01 6 6 9.085653E+05 5.710447E+00 + 3.660001E+01 1 1 2.013702E+03 3.655786E+00 + 3.660001E+01 1 5 -1.036700E+04 3.897875E+01 + 3.660001E+01 2 2 2.284407E+03 4.122929E+00 + 3.660001E+01 2 4 1.457599E+04 1.329549E+01 + 3.660001E+01 3 3 2.301822E+03 2.089806E+02 + 3.660001E+01 4 2 1.459241E+04 1.334303E+01 + 3.660001E+01 4 4 2.706338E+05 4.303092E+01 + 3.660001E+01 5 1 -1.038457E+04 3.888433E+01 + 3.660001E+01 5 5 8.269909E+05 4.144677E+02 + 3.660001E+01 6 6 9.085432E+05 5.643402E+00 + 3.670001E+01 1 1 2.013626E+03 3.633783E+00 + 3.670001E+01 1 5 -1.036702E+04 3.875596E+01 + 3.670001E+01 2 2 2.284314E+03 4.097974E+00 + 3.670001E+01 2 4 1.457557E+04 1.321278E+01 + 3.670001E+01 3 3 2.302231E+03 2.090245E+02 + 3.670001E+01 4 2 1.459203E+04 1.326114E+01 + 3.670001E+01 4 4 2.706321E+05 4.275087E+01 + 3.670001E+01 5 1 -1.038457E+04 3.866187E+01 + 3.670001E+01 5 5 8.269919E+05 4.121606E+02 + 3.670001E+01 6 6 9.085218E+05 5.589066E+00 + 3.680001E+01 1 1 2.013556E+03 3.612016E+00 + 3.680001E+01 1 5 -1.036702E+04 3.853417E+01 + 3.680001E+01 2 2 2.284221E+03 4.073206E+00 + 3.680001E+01 2 4 1.457519E+04 1.313062E+01 + 3.680001E+01 3 3 2.302670E+03 2.090670E+02 + 3.680001E+01 4 2 1.459163E+04 1.317922E+01 + 3.680001E+01 4 4 2.706300E+05 4.247728E+01 + 3.680001E+01 5 1 -1.038457E+04 3.844415E+01 + 3.680001E+01 5 5 8.269908E+05 4.100852E+02 + 3.680001E+01 6 6 9.084987E+05 5.498926E+00 + 3.690001E+01 1 1 2.013482E+03 3.590358E+00 + 3.690001E+01 1 5 -1.036704E+04 3.831614E+01 + 3.690001E+01 2 2 2.284130E+03 4.048556E+00 + 3.690001E+01 2 4 1.457481E+04 1.305051E+01 + 3.690001E+01 3 3 2.303093E+03 2.091085E+02 + 3.690001E+01 4 2 1.459121E+04 1.309833E+01 + 3.690001E+01 4 4 2.706278E+05 4.222427E+01 + 3.690001E+01 5 1 -1.038462E+04 3.822642E+01 + 3.690001E+01 5 5 8.269888E+05 4.077679E+02 + 3.690001E+01 6 6 9.084771E+05 5.438470E+00 + 3.700001E+01 1 1 2.013411E+03 3.568935E+00 + 3.700001E+01 1 5 -1.036705E+04 3.809861E+01 + 3.700001E+01 2 2 2.284034E+03 4.024170E+00 + 3.700001E+01 2 4 1.457443E+04 1.296999E+01 + 3.700001E+01 3 3 2.303524E+03 2.091532E+02 + 3.700001E+01 4 2 1.459083E+04 1.301700E+01 + 3.700001E+01 4 4 2.706268E+05 4.195294E+01 + 3.700001E+01 5 1 -1.038460E+04 3.800803E+01 + 3.700001E+01 5 5 8.269881E+05 4.056193E+02 + 3.700001E+01 6 6 9.084576E+05 5.370837E+00 + 3.710001E+01 1 1 2.013341E+03 3.547757E+00 + 3.710001E+01 1 5 -1.036708E+04 3.788406E+01 + 3.710001E+01 2 2 2.283948E+03 3.999992E+00 + 3.710001E+01 2 4 1.457402E+04 1.289058E+01 + 3.710001E+01 3 3 2.303947E+03 2.091963E+02 + 3.710001E+01 4 2 1.459046E+04 1.293688E+01 + 3.710001E+01 4 4 2.706248E+05 4.168304E+01 + 3.710001E+01 5 1 -1.038466E+04 3.779264E+01 + 3.710001E+01 5 5 8.269868E+05 4.035041E+02 + 3.710001E+01 6 6 9.084366E+05 5.309042E+00 + 3.720000E+01 1 1 2.013268E+03 3.526645E+00 + 3.720000E+01 1 5 -1.036708E+04 3.767033E+01 + 3.720000E+01 2 2 2.283854E+03 3.976116E+00 + 3.720000E+01 2 4 1.457367E+04 1.281155E+01 + 3.720000E+01 3 3 2.304385E+03 2.092408E+02 + 3.720000E+01 4 2 1.459005E+04 1.285758E+01 + 3.720000E+01 4 4 2.706232E+05 4.142688E+01 + 3.720000E+01 5 1 -1.038470E+04 3.758187E+01 + 3.720000E+01 5 5 8.269874E+05 4.013394E+02 + 3.720000E+01 6 6 9.084147E+05 5.268166E+00 + 3.730000E+01 1 1 2.013203E+03 3.505867E+00 + 3.730000E+01 1 5 -1.036710E+04 3.745911E+01 + 3.730000E+01 2 2 2.283767E+03 3.952397E+00 + 3.730000E+01 2 4 1.457329E+04 1.273373E+01 + 3.730000E+01 3 3 2.304789E+03 2.092828E+02 + 3.730000E+01 4 2 1.458973E+04 1.277789E+01 + 3.730000E+01 4 4 2.706211E+05 4.117779E+01 + 3.730000E+01 5 1 -1.038467E+04 3.736903E+01 + 3.730000E+01 5 5 8.269850E+05 3.992006E+02 + 3.730000E+01 6 6 9.083945E+05 5.198104E+00 + 3.740000E+01 1 1 2.013130E+03 3.485213E+00 + 3.740000E+01 1 5 -1.036711E+04 3.724977E+01 + 3.740000E+01 2 2 2.283678E+03 3.928882E+00 + 3.740000E+01 2 4 1.457293E+04 1.265645E+01 + 3.740000E+01 3 3 2.305208E+03 2.093207E+02 + 3.740000E+01 4 2 1.458937E+04 1.270025E+01 + 3.740000E+01 4 4 2.706199E+05 4.090831E+01 + 3.740000E+01 5 1 -1.038471E+04 3.716008E+01 + 3.740000E+01 5 5 8.269840E+05 3.971006E+02 + 3.740000E+01 6 6 9.083726E+05 5.127429E+00 + 3.750000E+01 1 1 2.013062E+03 3.464626E+00 + 3.750000E+01 1 5 -1.036713E+04 3.704184E+01 + 3.750000E+01 2 2 2.283589E+03 3.905577E+00 + 3.750000E+01 2 4 1.457256E+04 1.257989E+01 + 3.750000E+01 3 3 2.305638E+03 2.093643E+02 + 3.750000E+01 4 2 1.458899E+04 1.262277E+01 + 3.750000E+01 4 4 2.706178E+05 4.067010E+01 + 3.750000E+01 5 1 -1.038468E+04 3.695582E+01 + 3.750000E+01 5 5 8.269815E+05 3.950205E+02 + 3.750000E+01 6 6 9.083530E+05 5.055467E+00 + 3.760000E+01 1 1 2.012994E+03 3.444397E+00 + 3.760000E+01 1 5 -1.036714E+04 3.683575E+01 + 3.760000E+01 2 2 2.283505E+03 3.882526E+00 + 3.760000E+01 2 4 1.457218E+04 1.250433E+01 + 3.760000E+01 3 3 2.306049E+03 2.094059E+02 + 3.760000E+01 4 2 1.458862E+04 1.254721E+01 + 3.760000E+01 4 4 2.706166E+05 4.042308E+01 + 3.760000E+01 5 1 -1.038471E+04 3.674814E+01 + 3.760000E+01 5 5 8.269804E+05 3.929808E+02 + 3.760000E+01 6 6 9.083321E+05 5.009821E+00 + 3.770000E+01 1 1 2.012924E+03 3.424435E+00 + 3.770000E+01 1 5 -1.036716E+04 3.663164E+01 + 3.770000E+01 2 2 2.283417E+03 3.859690E+00 + 3.770000E+01 2 4 1.457186E+04 1.242942E+01 + 3.770000E+01 3 3 2.306469E+03 2.094432E+02 + 3.770000E+01 4 2 1.458825E+04 1.247189E+01 + 3.770000E+01 4 4 2.706153E+05 4.017995E+01 + 3.770000E+01 5 1 -1.038473E+04 3.654385E+01 + 3.770000E+01 5 5 8.269794E+05 3.909111E+02 + 3.770000E+01 6 6 9.083129E+05 4.935872E+00 + 3.780000E+01 1 1 2.012855E+03 3.404402E+00 + 3.780000E+01 1 5 -1.036719E+04 3.642873E+01 + 3.780000E+01 2 2 2.283328E+03 3.837123E+00 + 3.780000E+01 2 4 1.457149E+04 1.235525E+01 + 3.780000E+01 3 3 2.306896E+03 2.094768E+02 + 3.780000E+01 4 2 1.458791E+04 1.239871E+01 + 3.780000E+01 4 4 2.706136E+05 3.994192E+01 + 3.780000E+01 5 1 -1.038474E+04 3.633950E+01 + 3.780000E+01 5 5 8.269797E+05 3.887933E+02 + 3.780000E+01 6 6 9.082928E+05 4.908989E+00 + 3.789999E+01 1 1 2.012790E+03 3.384700E+00 + 3.789999E+01 1 5 -1.036722E+04 3.622715E+01 + 3.789999E+01 2 2 2.283242E+03 3.814688E+00 + 3.789999E+01 2 4 1.457112E+04 1.228125E+01 + 3.789999E+01 3 3 2.307300E+03 2.095214E+02 + 3.789999E+01 4 2 1.458755E+04 1.232306E+01 + 3.789999E+01 4 4 2.706118E+05 3.969556E+01 + 3.789999E+01 5 1 -1.038474E+04 3.613874E+01 + 3.789999E+01 5 5 8.269791E+05 3.867734E+02 + 3.789999E+01 6 6 9.082722E+05 4.846871E+00 + 3.799999E+01 1 1 2.012723E+03 3.365166E+00 + 3.799999E+01 1 5 -1.036720E+04 3.602869E+01 + 3.799999E+01 2 2 2.283159E+03 3.792426E+00 + 3.799999E+01 2 4 1.457075E+04 1.220757E+01 + 3.799999E+01 3 3 2.307712E+03 2.095591E+02 + 3.799999E+01 4 2 1.458715E+04 1.225121E+01 + 3.799999E+01 4 4 2.706106E+05 3.944532E+01 + 3.799999E+01 5 1 -1.038480E+04 3.594152E+01 + 3.799999E+01 5 5 8.269774E+05 3.848085E+02 + 3.799999E+01 6 6 9.082527E+05 4.783886E+00 + 3.809999E+01 1 1 2.012658E+03 3.345552E+00 + 3.809999E+01 1 5 -1.036724E+04 3.583174E+01 + 3.809999E+01 2 2 2.283075E+03 3.770509E+00 + 3.809999E+01 2 4 1.457042E+04 1.213552E+01 + 3.809999E+01 3 3 2.308125E+03 2.095937E+02 + 3.809999E+01 4 2 1.458683E+04 1.217951E+01 + 3.809999E+01 4 4 2.706095E+05 3.921399E+01 + 3.809999E+01 5 1 -1.038483E+04 3.574688E+01 + 3.809999E+01 5 5 8.269768E+05 3.828458E+02 + 3.809999E+01 6 6 9.082335E+05 4.741799E+00 + 3.819999E+01 1 1 2.012592E+03 3.326407E+00 + 3.819999E+01 1 5 -1.036726E+04 3.563541E+01 + 3.819999E+01 2 2 2.282995E+03 3.748651E+00 + 3.819999E+01 2 4 1.457009E+04 1.206382E+01 + 3.819999E+01 3 3 2.308525E+03 2.096333E+02 + 3.819999E+01 4 2 1.458648E+04 1.210816E+01 + 3.819999E+01 4 4 2.706083E+05 3.897776E+01 + 3.819999E+01 5 1 -1.038485E+04 3.555049E+01 + 3.819999E+01 5 5 8.269772E+05 3.807567E+02 + 3.819999E+01 6 6 9.082136E+05 4.687849E+00 + 3.829999E+01 1 1 2.012526E+03 3.307404E+00 + 3.829999E+01 1 5 -1.036724E+04 3.544145E+01 + 3.829999E+01 2 2 2.282908E+03 3.726984E+00 + 3.829999E+01 2 4 1.456975E+04 1.199241E+01 + 3.829999E+01 3 3 2.308938E+03 2.096743E+02 + 3.829999E+01 4 2 1.458615E+04 1.203561E+01 + 3.829999E+01 4 4 2.706067E+05 3.873753E+01 + 3.829999E+01 5 1 -1.038487E+04 3.535653E+01 + 3.829999E+01 5 5 8.269764E+05 3.789005E+02 + 3.829999E+01 6 6 9.081937E+05 4.622365E+00 + 3.839999E+01 1 1 2.012460E+03 3.288520E+00 + 3.839999E+01 1 5 -1.036725E+04 3.524835E+01 + 3.839999E+01 2 2 2.282827E+03 3.705519E+00 + 3.839999E+01 2 4 1.456940E+04 1.192247E+01 + 3.839999E+01 3 3 2.309349E+03 2.097117E+02 + 3.839999E+01 4 2 1.458581E+04 1.196471E+01 + 3.839999E+01 4 4 2.706051E+05 3.850977E+01 + 3.839999E+01 5 1 -1.038487E+04 3.516337E+01 + 3.839999E+01 5 5 8.269758E+05 3.769133E+02 + 3.839999E+01 6 6 9.081760E+05 4.576396E+00 + 3.849998E+01 1 1 2.012400E+03 3.269788E+00 + 3.849998E+01 1 5 -1.036728E+04 3.505717E+01 + 3.849998E+01 2 2 2.282749E+03 3.684276E+00 + 3.849998E+01 2 4 1.456908E+04 1.185255E+01 + 3.849998E+01 3 3 2.309770E+03 2.097465E+02 + 3.849998E+01 4 2 1.458546E+04 1.189483E+01 + 3.849998E+01 4 4 2.706033E+05 3.826764E+01 + 3.849998E+01 5 1 -1.038490E+04 3.497512E+01 + 3.849998E+01 5 5 8.269746E+05 3.749321E+02 + 3.849998E+01 6 6 9.081566E+05 4.542968E+00 + 3.859998E+01 1 1 2.012333E+03 3.251281E+00 + 3.859998E+01 1 5 -1.036730E+04 3.486726E+01 + 3.859998E+01 2 2 2.282667E+03 3.663255E+00 + 3.859998E+01 2 4 1.456875E+04 1.178283E+01 + 3.859998E+01 3 3 2.310175E+03 2.097849E+02 + 3.859998E+01 4 2 1.458510E+04 1.182453E+01 + 3.859998E+01 4 4 2.706021E+05 3.803108E+01 + 3.859998E+01 5 1 -1.038491E+04 3.478324E+01 + 3.859998E+01 5 5 8.269734E+05 3.729440E+02 + 3.859998E+01 6 6 9.081362E+05 4.490300E+00 + 3.869998E+01 1 1 2.012272E+03 3.232926E+00 + 3.869998E+01 1 5 -1.036729E+04 3.467992E+01 + 3.869998E+01 2 2 2.282588E+03 3.642359E+00 + 3.869998E+01 2 4 1.456842E+04 1.171539E+01 + 3.869998E+01 3 3 2.310576E+03 2.098226E+02 + 3.869998E+01 4 2 1.458475E+04 1.175802E+01 + 3.869998E+01 4 4 2.706006E+05 3.779966E+01 + 3.869998E+01 5 1 -1.038495E+04 3.459625E+01 + 3.869998E+01 5 5 8.269721E+05 3.711460E+02 + 3.869998E+01 6 6 9.081186E+05 4.421749E+00 + 3.879998E+01 1 1 2.012209E+03 3.214651E+00 + 3.879998E+01 1 5 -1.036732E+04 3.449369E+01 + 3.879998E+01 2 2 2.282503E+03 3.621585E+00 + 3.879998E+01 2 4 1.456807E+04 1.164711E+01 + 3.879998E+01 3 3 2.310982E+03 2.098570E+02 + 3.879998E+01 4 2 1.458442E+04 1.168894E+01 + 3.879998E+01 4 4 2.705990E+05 3.758459E+01 + 3.879998E+01 5 1 -1.038493E+04 3.441256E+01 + 3.879998E+01 5 5 8.269718E+05 3.691244E+02 + 3.879998E+01 6 6 9.081011E+05 4.378713E+00 + 3.889998E+01 1 1 2.012145E+03 3.196586E+00 + 3.889998E+01 1 5 -1.036732E+04 3.430721E+01 + 3.889998E+01 2 2 2.282424E+03 3.601162E+00 + 3.889998E+01 2 4 1.456774E+04 1.157895E+01 + 3.889998E+01 3 3 2.311388E+03 2.098934E+02 + 3.889998E+01 4 2 1.458407E+04 1.162211E+01 + 3.889998E+01 4 4 2.705974E+05 3.737069E+01 + 3.889998E+01 5 1 -1.038494E+04 3.422789E+01 + 3.889998E+01 5 5 8.269711E+05 3.673767E+02 + 3.889998E+01 6 6 9.080827E+05 4.334402E+00 + 3.899998E+01 1 1 2.012087E+03 3.178778E+00 + 3.899998E+01 1 5 -1.036735E+04 3.412605E+01 + 3.899998E+01 2 2 2.282347E+03 3.580716E+00 + 3.899998E+01 2 4 1.456744E+04 1.151269E+01 + 3.899998E+01 3 3 2.311785E+03 2.099304E+02 + 3.899998E+01 4 2 1.458380E+04 1.155437E+01 + 3.899998E+01 4 4 2.705961E+05 3.714309E+01 + 3.899998E+01 5 1 -1.038495E+04 3.404263E+01 + 3.899998E+01 5 5 8.269695E+05 3.653286E+02 + 3.899998E+01 6 6 9.080644E+05 4.290007E+00 + 3.909998E+01 1 1 2.012023E+03 3.160982E+00 + 3.909998E+01 1 5 -1.036734E+04 3.394199E+01 + 3.909998E+01 2 2 2.282269E+03 3.560430E+00 + 3.909998E+01 2 4 1.456711E+04 1.144674E+01 + 3.909998E+01 3 3 2.312187E+03 2.099666E+02 + 3.909998E+01 4 2 1.458347E+04 1.148686E+01 + 3.909998E+01 4 4 2.705946E+05 3.693652E+01 + 3.909998E+01 5 1 -1.038495E+04 3.386298E+01 + 3.909998E+01 5 5 8.269674E+05 3.635599E+02 + 3.909998E+01 6 6 9.080466E+05 4.254579E+00 + 3.919997E+01 1 1 2.011962E+03 3.143251E+00 + 3.919997E+01 1 5 -1.036736E+04 3.376207E+01 + 3.919997E+01 2 2 2.282194E+03 3.540502E+00 + 3.919997E+01 2 4 1.456678E+04 1.138097E+01 + 3.919997E+01 3 3 2.312580E+03 2.099987E+02 + 3.919997E+01 4 2 1.458313E+04 1.141975E+01 + 3.919997E+01 4 4 2.705932E+05 3.670096E+01 + 3.919997E+01 5 1 -1.038498E+04 3.368402E+01 + 3.919997E+01 5 5 8.269670E+05 3.616775E+02 + 3.919997E+01 6 6 9.080277E+05 4.215195E+00 + 3.929997E+01 1 1 2.011903E+03 3.125883E+00 + 3.929997E+01 1 5 -1.036737E+04 3.358359E+01 + 3.929997E+01 2 2 2.282120E+03 3.520800E+00 + 3.929997E+01 2 4 1.456644E+04 1.131631E+01 + 3.929997E+01 3 3 2.312969E+03 2.100336E+02 + 3.929997E+01 4 2 1.458281E+04 1.135574E+01 + 3.929997E+01 4 4 2.705918E+05 3.649755E+01 + 3.929997E+01 5 1 -1.038500E+04 3.350385E+01 + 3.929997E+01 5 5 8.269663E+05 3.599503E+02 + 3.929997E+01 6 6 9.080109E+05 4.157808E+00 + 3.939997E+01 1 1 2.011847E+03 3.108540E+00 + 3.939997E+01 1 5 -1.036739E+04 3.340415E+01 + 3.939997E+01 2 2 2.282038E+03 3.501162E+00 + 3.939997E+01 2 4 1.456614E+04 1.125108E+01 + 3.939997E+01 3 3 2.313376E+03 2.100708E+02 + 3.939997E+01 4 2 1.458250E+04 1.129232E+01 + 3.939997E+01 4 4 2.705904E+05 3.627639E+01 + 3.939997E+01 5 1 -1.038502E+04 3.332632E+01 + 3.939997E+01 5 5 8.269655E+05 3.581561E+02 + 3.939997E+01 6 6 9.079923E+05 4.111275E+00 + 3.949997E+01 1 1 2.011782E+03 3.091426E+00 + 3.949997E+01 1 5 -1.036741E+04 3.322937E+01 + 3.949997E+01 2 2 2.281966E+03 3.481546E+00 + 3.949997E+01 2 4 1.456584E+04 1.118835E+01 + 3.949997E+01 3 3 2.313766E+03 2.101021E+02 + 3.949997E+01 4 2 1.458219E+04 1.122677E+01 + 3.949997E+01 4 4 2.705893E+05 3.608713E+01 + 3.949997E+01 5 1 -1.038504E+04 3.315043E+01 + 3.949997E+01 5 5 8.269635E+05 3.563717E+02 + 3.949997E+01 6 6 9.079751E+05 4.073586E+00 + 3.959997E+01 1 1 2.011724E+03 3.074402E+00 + 3.959997E+01 1 5 -1.036742E+04 3.305470E+01 + 3.959997E+01 2 2 2.281890E+03 3.462407E+00 + 3.959997E+01 2 4 1.456552E+04 1.112596E+01 + 3.959997E+01 3 3 2.314161E+03 2.101375E+02 + 3.959997E+01 4 2 1.458187E+04 1.116395E+01 + 3.959997E+01 4 4 2.705877E+05 3.588458E+01 + 3.959997E+01 5 1 -1.038506E+04 3.297411E+01 + 3.959997E+01 5 5 8.269639E+05 3.546119E+02 + 3.959997E+01 6 6 9.079575E+05 4.041151E+00 + 3.969997E+01 1 1 2.011666E+03 3.057555E+00 + 3.969997E+01 1 5 -1.036745E+04 3.288111E+01 + 3.969997E+01 2 2 2.281816E+03 3.443227E+00 + 3.969997E+01 2 4 1.456520E+04 1.106171E+01 + 3.969997E+01 3 3 2.314552E+03 2.101746E+02 + 3.969997E+01 4 2 1.458156E+04 1.110115E+01 + 3.969997E+01 4 4 2.705866E+05 3.565243E+01 + 3.969997E+01 5 1 -1.038508E+04 3.280614E+01 + 3.969997E+01 5 5 8.269627E+05 3.527347E+02 + 3.969997E+01 6 6 9.079406E+05 3.996453E+00 + 3.979996E+01 1 1 2.011607E+03 3.040918E+00 + 3.979996E+01 1 5 -1.036748E+04 3.270905E+01 + 3.979996E+01 2 2 2.281746E+03 3.424165E+00 + 3.979996E+01 2 4 1.456488E+04 1.100041E+01 + 3.979996E+01 3 3 2.314941E+03 2.102100E+02 + 3.979996E+01 4 2 1.458128E+04 1.103920E+01 + 3.979996E+01 4 4 2.705856E+05 3.546384E+01 + 3.979996E+01 5 1 -1.038511E+04 3.263005E+01 + 3.979996E+01 5 5 8.269610E+05 3.510912E+02 + 3.979996E+01 6 6 9.079243E+05 3.931697E+00 + 3.989996E+01 1 1 2.011553E+03 3.024139E+00 + 3.989996E+01 1 5 -1.036750E+04 3.253902E+01 + 3.989996E+01 2 2 2.281671E+03 3.405334E+00 + 3.989996E+01 2 4 1.456459E+04 1.093907E+01 + 3.989996E+01 3 3 2.315334E+03 2.102411E+02 + 3.989996E+01 4 2 1.458096E+04 1.097808E+01 + 3.989996E+01 4 4 2.705842E+05 3.526117E+01 + 3.989996E+01 5 1 -1.038511E+04 3.246190E+01 + 3.989996E+01 5 5 8.269589E+05 3.492199E+02 + 3.989996E+01 6 6 9.079063E+05 3.901466E+00 + 3.999996E+01 1 1 2.011493E+03 3.007740E+00 + 3.999996E+01 1 5 -1.036752E+04 3.236941E+01 + 3.999996E+01 2 2 2.281596E+03 3.386753E+00 + 3.999996E+01 2 4 1.456432E+04 1.087715E+01 + 3.999996E+01 3 3 2.315724E+03 2.102723E+02 + 3.999996E+01 4 2 1.458065E+04 1.091650E+01 + 3.999996E+01 4 4 2.705826E+05 3.505007E+01 + 3.999996E+01 5 1 -1.038512E+04 3.229579E+01 + 3.999996E+01 5 5 8.269584E+05 3.475764E+02 + 3.999996E+01 6 6 9.078898E+05 3.849471E+00 + 4.009996E+01 1 1 2.011437E+03 2.991410E+00 + 4.009996E+01 1 5 -1.036753E+04 3.220149E+01 + 4.009996E+01 2 2 2.281525E+03 3.368227E+00 + 4.009996E+01 2 4 1.456400E+04 1.081634E+01 + 4.009996E+01 3 3 2.316114E+03 2.103059E+02 + 4.009996E+01 4 2 1.458038E+04 1.085643E+01 + 4.009996E+01 4 4 2.705809E+05 3.484414E+01 + 4.009996E+01 5 1 -1.038514E+04 3.212786E+01 + 4.009996E+01 5 5 8.269564E+05 3.458421E+02 + 4.009996E+01 6 6 9.078736E+05 3.824381E+00 + 4.019996E+01 1 1 2.011378E+03 2.975131E+00 + 4.019996E+01 1 5 -1.036755E+04 3.203527E+01 + 4.019996E+01 2 2 2.281455E+03 3.349832E+00 + 4.019996E+01 2 4 1.456370E+04 1.075585E+01 + 4.019996E+01 3 3 2.316508E+03 2.103378E+02 + 4.019996E+01 4 2 1.458008E+04 1.079508E+01 + 4.019996E+01 4 4 2.705806E+05 3.464214E+01 + 4.019996E+01 5 1 -1.038515E+04 3.195966E+01 + 4.019996E+01 5 5 8.269543E+05 3.441451E+02 + 4.019996E+01 6 6 9.078556E+05 3.771292E+00 + 4.029996E+01 1 1 2.011323E+03 2.959233E+00 + 4.029996E+01 1 5 -1.036756E+04 3.186870E+01 + 4.029996E+01 2 2 2.281383E+03 3.331590E+00 + 4.029996E+01 2 4 1.456340E+04 1.069608E+01 + 4.029996E+01 3 3 2.316894E+03 2.103727E+02 + 4.029996E+01 4 2 1.457977E+04 1.073504E+01 + 4.029996E+01 4 4 2.705788E+05 3.445746E+01 + 4.029996E+01 5 1 -1.038517E+04 3.179680E+01 + 4.029996E+01 5 5 8.269531E+05 3.424527E+02 + 4.029996E+01 6 6 9.078409E+05 3.741815E+00 + 4.039996E+01 1 1 2.011270E+03 2.943222E+00 + 4.039996E+01 1 5 -1.036760E+04 3.170504E+01 + 4.039996E+01 2 2 2.281312E+03 3.313582E+00 + 4.039996E+01 2 4 1.456310E+04 1.063782E+01 + 4.039996E+01 3 3 2.317275E+03 2.104019E+02 + 4.039996E+01 4 2 1.457948E+04 1.067604E+01 + 4.039996E+01 4 4 2.705776E+05 3.426579E+01 + 4.039996E+01 5 1 -1.038520E+04 3.163220E+01 + 4.039996E+01 5 5 8.269516E+05 3.407807E+02 + 4.039996E+01 6 6 9.078230E+05 3.692379E+00 + 4.049995E+01 1 1 2.011215E+03 2.927410E+00 + 4.049995E+01 1 5 -1.036761E+04 3.154235E+01 + 4.049995E+01 2 2 2.281241E+03 3.295801E+00 + 4.049995E+01 2 4 1.456282E+04 1.057935E+01 + 4.049995E+01 3 3 2.317661E+03 2.104317E+02 + 4.049995E+01 4 2 1.457920E+04 1.061816E+01 + 4.049995E+01 4 4 2.705764E+05 3.407467E+01 + 4.049995E+01 5 1 -1.038521E+04 3.146976E+01 + 4.049995E+01 5 5 8.269507E+05 3.390747E+02 + 4.049995E+01 6 6 9.078081E+05 3.641167E+00 + 4.059995E+01 1 1 2.011161E+03 2.911773E+00 + 4.059995E+01 1 5 -1.036765E+04 3.138105E+01 + 4.059995E+01 2 2 2.281172E+03 3.278031E+00 + 4.059995E+01 2 4 1.456253E+04 1.052094E+01 + 4.059995E+01 3 3 2.318038E+03 2.104649E+02 + 4.059995E+01 4 2 1.457890E+04 1.056202E+01 + 4.059995E+01 4 4 2.705752E+05 3.388414E+01 + 4.059995E+01 5 1 -1.038523E+04 3.130933E+01 + 4.059995E+01 5 5 8.269500E+05 3.374234E+02 + 4.059995E+01 6 6 9.077920E+05 3.624387E+00 + 4.069995E+01 1 1 2.011105E+03 2.896175E+00 + 4.069995E+01 1 5 -1.036766E+04 3.122051E+01 + 4.069995E+01 2 2 2.281105E+03 3.260370E+00 + 4.069995E+01 2 4 1.456222E+04 1.046322E+01 + 4.069995E+01 3 3 2.318431E+03 2.104967E+02 + 4.069995E+01 4 2 1.457862E+04 1.050220E+01 + 4.069995E+01 4 4 2.705737E+05 3.368925E+01 + 4.069995E+01 5 1 -1.038527E+04 3.115114E+01 + 4.069995E+01 5 5 8.269492E+05 3.357729E+02 + 4.069995E+01 6 6 9.077761E+05 3.580951E+00 + 4.079995E+01 1 1 2.011051E+03 2.880900E+00 + 4.079995E+01 1 5 -1.036768E+04 3.106174E+01 + 4.079995E+01 2 2 2.281037E+03 3.242859E+00 + 4.079995E+01 2 4 1.456197E+04 1.040636E+01 + 4.079995E+01 3 3 2.318805E+03 2.105277E+02 + 4.079995E+01 4 2 1.457835E+04 1.044448E+01 + 4.079995E+01 4 4 2.705726E+05 3.350297E+01 + 4.079995E+01 5 1 -1.038528E+04 3.099028E+01 + 4.079995E+01 5 5 8.269483E+05 3.340829E+02 + 4.079995E+01 6 6 9.077611E+05 3.535315E+00 + 4.089995E+01 1 1 2.010996E+03 2.865503E+00 + 4.089995E+01 1 5 -1.036770E+04 3.090385E+01 + 4.089995E+01 2 2 2.280970E+03 3.225686E+00 + 4.089995E+01 2 4 1.456167E+04 1.035017E+01 + 4.089995E+01 3 3 2.319184E+03 2.105570E+02 + 4.089995E+01 4 2 1.457807E+04 1.038748E+01 + 4.089995E+01 4 4 2.705714E+05 3.332624E+01 + 4.089995E+01 5 1 -1.038528E+04 3.082990E+01 + 4.089995E+01 5 5 8.269490E+05 3.325596E+02 + 4.089995E+01 6 6 9.077447E+05 3.518167E+00 + 4.099995E+01 1 1 2.010943E+03 2.850343E+00 + 4.099995E+01 1 5 -1.036770E+04 3.074819E+01 + 4.099995E+01 2 2 2.280899E+03 3.208411E+00 + 4.099995E+01 2 4 1.456140E+04 1.029359E+01 + 4.099995E+01 3 3 2.319558E+03 2.105878E+02 + 4.099995E+01 4 2 1.457776E+04 1.033150E+01 + 4.099995E+01 4 4 2.705698E+05 3.313728E+01 + 4.099995E+01 5 1 -1.038530E+04 3.067612E+01 + 4.099995E+01 5 5 8.269471E+05 3.307766E+02 + 4.099995E+01 6 6 9.077286E+05 3.497452E+00 + 4.109995E+01 1 1 2.010892E+03 2.835345E+00 + 4.109995E+01 1 5 -1.036773E+04 3.059193E+01 + 4.109995E+01 2 2 2.280834E+03 3.191469E+00 + 4.109995E+01 2 4 1.456115E+04 1.023820E+01 + 4.109995E+01 3 3 2.319937E+03 2.106193E+02 + 4.109995E+01 4 2 1.457750E+04 1.027547E+01 + 4.109995E+01 4 4 2.705685E+05 3.296493E+01 + 4.109995E+01 5 1 -1.038534E+04 3.052301E+01 + 4.109995E+01 5 5 8.269469E+05 3.293317E+02 + 4.109995E+01 6 6 9.077132E+05 3.431105E+00 + 4.119994E+01 1 1 2.010840E+03 2.820436E+00 + 4.119994E+01 1 5 -1.036777E+04 3.043818E+01 + 4.119994E+01 2 2 2.280764E+03 3.174535E+00 + 4.119994E+01 2 4 1.456088E+04 1.018240E+01 + 4.119994E+01 3 3 2.320303E+03 2.106497E+02 + 4.119994E+01 4 2 1.457721E+04 1.022033E+01 + 4.119994E+01 4 4 2.705678E+05 3.277423E+01 + 4.119994E+01 5 1 -1.038538E+04 3.036722E+01 + 4.119994E+01 5 5 8.269467E+05 3.276874E+02 + 4.119994E+01 6 6 9.076984E+05 3.423158E+00 + 4.129994E+01 1 1 2.010787E+03 2.805636E+00 + 4.129994E+01 1 5 -1.036778E+04 3.028543E+01 + 4.129994E+01 2 2 2.280697E+03 3.157800E+00 + 4.129994E+01 2 4 1.456059E+04 1.012721E+01 + 4.129994E+01 3 3 2.320671E+03 2.106786E+02 + 4.129994E+01 4 2 1.457696E+04 1.016713E+01 + 4.129994E+01 4 4 2.705668E+05 3.258274E+01 + 4.129994E+01 5 1 -1.038539E+04 3.021600E+01 + 4.129994E+01 5 5 8.269446E+05 3.261401E+02 + 4.129994E+01 6 6 9.076834E+05 3.391908E+00 + 4.139994E+01 1 1 2.010738E+03 2.790935E+00 + 4.139994E+01 1 5 -1.036780E+04 3.013216E+01 + 4.139994E+01 2 2 2.280635E+03 3.140967E+00 + 4.139994E+01 2 4 1.456034E+04 1.007382E+01 + 4.139994E+01 3 3 2.321048E+03 2.107092E+02 + 4.139994E+01 4 2 1.457667E+04 1.010970E+01 + 4.139994E+01 4 4 2.705659E+05 3.242693E+01 + 4.139994E+01 5 1 -1.038540E+04 3.006433E+01 + 4.139994E+01 5 5 8.269430E+05 3.246499E+02 + 4.139994E+01 6 6 9.076686E+05 3.320487E+00 + 4.149994E+01 1 1 2.010685E+03 2.776349E+00 + 4.149994E+01 1 5 -1.036781E+04 2.998286E+01 + 4.149994E+01 2 2 2.280570E+03 3.124676E+00 + 4.149994E+01 2 4 1.456005E+04 1.001935E+01 + 4.149994E+01 3 3 2.321431E+03 2.107393E+02 + 4.149994E+01 4 2 1.457639E+04 1.005757E+01 + 4.149994E+01 4 4 2.705651E+05 3.223020E+01 + 4.149994E+01 5 1 -1.038540E+04 2.991556E+01 + 4.149994E+01 5 5 8.269421E+05 3.229818E+02 + 4.149994E+01 6 6 9.076525E+05 3.292625E+00 + 4.159994E+01 1 1 2.010633E+03 2.761979E+00 + 4.159994E+01 1 5 -1.036784E+04 2.983413E+01 + 4.159994E+01 2 2 2.280502E+03 3.108115E+00 + 4.159994E+01 2 4 1.455977E+04 9.966230E+00 + 4.159994E+01 3 3 2.321802E+03 2.107699E+02 + 4.159994E+01 4 2 1.457613E+04 1.000151E+01 + 4.159994E+01 4 4 2.705635E+05 3.205392E+01 + 4.159994E+01 5 1 -1.038544E+04 2.976593E+01 + 4.159994E+01 5 5 8.269400E+05 3.214334E+02 + 4.159994E+01 6 6 9.076379E+05 3.296375E+00 + 4.169994E+01 1 1 2.010583E+03 2.747638E+00 + 4.169994E+01 1 5 -1.036785E+04 2.968378E+01 + 4.169994E+01 2 2 2.280436E+03 3.091906E+00 + 4.169994E+01 2 4 1.455952E+04 9.914182E+00 + 4.169994E+01 3 3 2.322174E+03 2.108015E+02 + 4.169994E+01 4 2 1.457589E+04 9.948250E+00 + 4.169994E+01 4 4 2.705623E+05 3.190782E+01 + 4.169994E+01 5 1 -1.038545E+04 2.961996E+01 + 4.169994E+01 5 5 8.269397E+05 3.200453E+02 + 4.169994E+01 6 6 9.076232E+05 3.239015E+00 + 4.179993E+01 1 1 2.010532E+03 2.733359E+00 + 4.179993E+01 1 5 -1.036787E+04 2.953878E+01 + 4.179993E+01 2 2 2.280375E+03 3.075854E+00 + 4.179993E+01 2 4 1.455924E+04 9.861310E+00 + 4.179993E+01 3 3 2.322546E+03 2.108277E+02 + 4.179993E+01 4 2 1.457561E+04 9.894742E+00 + 4.179993E+01 4 4 2.705612E+05 3.172332E+01 + 4.179993E+01 5 1 -1.038547E+04 2.947310E+01 + 4.179993E+01 5 5 8.269386E+05 3.183591E+02 + 4.179993E+01 6 6 9.076082E+05 3.194246E+00 + 4.189993E+01 1 1 2.010479E+03 2.719279E+00 + 4.189993E+01 1 5 -1.036789E+04 2.939155E+01 + 4.189993E+01 2 2 2.280311E+03 3.059813E+00 + 4.189993E+01 2 4 1.455897E+04 9.809370E+00 + 4.189993E+01 3 3 2.322901E+03 2.108558E+02 + 4.189993E+01 4 2 1.457534E+04 9.842846E+00 + 4.189993E+01 4 4 2.705602E+05 3.155300E+01 + 4.189993E+01 5 1 -1.038547E+04 2.932571E+01 + 4.189993E+01 5 5 8.269378E+05 3.168844E+02 + 4.189993E+01 6 6 9.075934E+05 3.168942E+00 + 4.199993E+01 1 1 2.010434E+03 2.705281E+00 + 4.199993E+01 1 5 -1.036793E+04 2.924620E+01 + 4.199993E+01 2 2 2.280251E+03 3.044036E+00 + 4.199993E+01 2 4 1.455869E+04 9.758191E+00 + 4.199993E+01 3 3 2.323268E+03 2.108832E+02 + 4.199993E+01 4 2 1.457507E+04 9.791515E+00 + 4.199993E+01 4 4 2.705584E+05 3.139161E+01 + 4.199993E+01 5 1 -1.038549E+04 2.918254E+01 + 4.199993E+01 5 5 8.269366E+05 3.153878E+02 + 4.199993E+01 6 6 9.075792E+05 3.160925E+00 \ No newline at end of file diff --git a/Test_Cases/MHK_RM1/MHK_RM1_Floating.3 b/Test_Cases/MHK_RM1/MHK_RM1_Floating.3 new file mode 100644 index 00000000..2bfe7b48 --- /dev/null +++ b/Test_Cases/MHK_RM1/MHK_RM1_Floating.3 @@ -0,0 +1,10080 @@ + 1.000000E-01 0.000000E+00 1 3.928387E-05 9.000026E+01 -1.752301E-10 3.928387E-05 + 1.000000E-01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.000000E-01 0.000000E+00 3 5.096992E-06 2.330833E-04 5.096992E-06 2.073492E-11 + 1.000000E-01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.000000E-01 0.000000E+00 5 2.129045E-05 -8.999974E+01 9.931642E-11 -2.129045E-05 + 1.000000E-01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.000000E-01 3.000000E+01 1 2.479953E-05 9.000016E+01 -6.785025E-11 2.479953E-05 + 1.000000E-01 3.000000E+01 2 1.030077E-05 9.000000E+01 -3.776052E-13 1.030077E-05 + 1.000000E-01 3.000000E+01 3 6.027945E-06 2.529555E-05 6.027945E-06 2.661282E-12 + 1.000000E-01 3.000000E+01 4 4.842914E-05 -8.999998E+01 1.348501E-11 -4.842914E-05 + 1.000000E-01 3.000000E+01 5 1.310311E-05 -8.999985E+01 3.597847E-11 -1.310311E-05 + 1.000000E-01 3.000000E+01 6 1.316677E-04 -1.799997E+02 -1.316677E-04 -7.396868E-10 + 1.000000E-01 6.000000E+01 1 2.777314E-05 9.000978E+01 -4.741620E-09 2.777314E-05 + 1.000000E-01 6.000000E+01 2 3.752036E-06 9.000040E+01 -2.665548E-11 3.752036E-06 + 1.000000E-01 6.000000E+01 3 4.212014E-06 1.799998E+02 -4.212014E-06 1.676656E-11 + 1.000000E-01 6.000000E+01 4 1.801150E-05 -8.999966E+01 1.074628E-10 -1.801150E-05 + 1.000000E-01 6.000000E+01 5 1.438257E-05 -8.998517E+01 3.722973E-09 -1.438257E-05 + 1.000000E-01 6.000000E+01 6 2.408331E-04 2.416988E-04 2.408331E-04 1.015940E-09 + 1.000000E-01 9.000000E+01 1 3.569052E-10 9.000000E+01 -3.883185E-16 3.569052E-10 + 1.000000E-01 9.000000E+01 2 6.679657E-06 -8.999947E+01 6.145705E-11 -6.679657E-06 + 1.000000E-01 9.000000E+01 3 8.607126E-07 1.438843E-03 8.607126E-07 2.161469E-11 + 1.000000E-01 9.000000E+01 4 3.630382E-05 9.000039E+01 -2.475569E-10 3.630382E-05 + 1.000000E-01 9.000000E+01 5 1.129626E-10 9.000000E+01 -7.992531E-17 1.129626E-10 + 1.000000E-01 9.000000E+01 6 2.390679E-10 1.799993E+02 -2.390679E-10 2.915754E-15 + 2.000000E-01 0.000000E+00 1 4.794502E-03 -7.108732E+01 1.554026E-03 -4.535664E-03 + 2.000000E-01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.000000E-01 0.000000E+00 3 5.115628E-03 1.557186E+01 4.927857E-03 1.373273E-03 + 2.000000E-01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.000000E-01 0.000000E+00 5 3.931623E-04 -1.080528E+02 -1.218386E-04 -3.738074E-04 + 2.000000E-01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.000000E-01 3.000000E+01 1 7.095869E-03 -7.712666E+01 1.580935E-03 -6.917514E-03 + 2.000000E-01 3.000000E+01 2 4.226396E-03 1.086416E+02 -1.350958E-03 4.004665E-03 + 2.000000E-01 3.000000E+01 3 3.649259E-03 1.847425E+01 3.461199E-03 1.156371E-03 + 2.000000E-01 3.000000E+01 4 2.471381E-02 -7.209129E+01 7.599527E-03 -2.351637E-02 + 2.000000E-01 3.000000E+01 5 4.199853E-04 8.719241E+01 2.057174E-05 4.194811E-04 + 2.000000E-01 3.000000E+01 6 2.909344E-02 -1.673242E+02 -2.838435E-02 -6.384108E-03 + 2.000000E-01 6.000000E+01 1 2.047991E-03 -7.983326E+01 3.614978E-04 -2.015834E-03 + 2.000000E-01 6.000000E+01 2 1.384893E-03 -1.384165E+01 1.344677E-03 -3.313209E-04 + 2.000000E-01 6.000000E+01 3 3.288509E-03 -1.597656E+02 -3.085559E-03 -1.137370E-03 + 2.000000E-01 6.000000E+01 4 7.811303E-03 1.663535E+02 -7.590788E-03 1.842930E-03 + 2.000000E-01 6.000000E+01 5 7.411336E-04 -8.593498E+01 5.253779E-05 -7.392691E-04 + 2.000000E-01 6.000000E+01 6 3.474759E-02 6.111718E+00 3.455009E-02 3.699487E-03 + 2.000000E-01 9.000000E+01 1 1.420143E-08 -8.680801E+01 7.907613E-10 -1.417940E-08 + 2.000000E-01 9.000000E+01 2 1.406377E-02 1.025577E+02 -3.057782E-03 1.372733E-02 + 2.000000E-01 9.000000E+01 3 7.963536E-04 -1.482715E+02 -6.773379E-04 -4.187988E-04 + 2.000000E-01 9.000000E+01 4 7.866052E-02 -7.677493E+01 1.799571E-02 -7.657436E-02 + 2.000000E-01 9.000000E+01 5 2.518591E-09 9.854890E+01 -3.743971E-10 2.490607E-09 + 2.000000E-01 9.000000E+01 6 5.488987E-08 5.854488E+01 2.864320E-08 4.682376E-08 + 3.000000E-01 0.000000E+00 1 3.888490E-02 -9.719932E+01 -4.873109E-03 -3.857834E-02 + 3.000000E-01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.000000E-01 0.000000E+00 3 1.602358E-02 1.495198E+02 -1.380919E-02 8.127803E-03 + 3.000000E-01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.000000E-01 0.000000E+00 5 4.695172E-04 -3.361153E+01 3.910186E-04 -2.599056E-04 + 3.000000E-01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.000000E-01 3.000000E+01 1 4.646594E-03 5.454666E+01 2.695209E-03 3.785060E-03 + 3.000000E-01 3.000000E+01 2 7.563305E-03 1.047204E+01 7.437328E-03 1.374674E-03 + 3.000000E-01 3.000000E+01 3 1.330938E-02 -8.915330E+01 1.966758E-04 -1.330793E-02 + 3.000000E-01 3.000000E+01 4 4.322376E-02 -1.644875E+02 -4.164920E-02 -1.156016E-02 + 3.000000E-01 3.000000E+01 5 2.016536E-03 -1.208179E+02 -1.033095E-03 -1.731801E-03 + 3.000000E-01 3.000000E+01 6 8.285185E-02 7.853923E+01 1.646241E-02 8.119986E-02 + 3.000000E-01 6.000000E+01 1 2.509840E-02 -1.168346E+02 -1.132984E-02 -2.239563E-02 + 3.000000E-01 6.000000E+01 2 7.971748E-03 -4.328616E+01 5.802942E-03 -5.465769E-03 + 3.000000E-01 6.000000E+01 3 1.678508E-02 3.530571E+01 1.369797E-02 9.700751E-03 + 3.000000E-01 6.000000E+01 4 3.282496E-02 1.413052E+02 -2.561945E-02 2.052126E-02 + 3.000000E-01 6.000000E+01 5 5.603014E-04 1.154969E+02 -2.411888E-04 5.057327E-04 + 3.000000E-01 6.000000E+01 6 1.670086E-01 -1.458209E+02 -1.381638E-01 -9.382232E-02 + 3.000000E-01 9.000000E+01 1 2.949139E-07 -9.067712E+01 -3.485205E-09 -2.948933E-07 + 3.000000E-01 9.000000E+01 2 4.167762E-02 1.074692E+02 -1.251132E-02 3.975539E-02 + 3.000000E-01 9.000000E+01 3 2.107524E-02 1.002967E+02 -3.767119E-03 2.073582E-02 + 3.000000E-01 9.000000E+01 4 2.493339E-01 -7.362067E+01 7.031103E-02 -2.392149E-01 + 3.000000E-01 9.000000E+01 5 5.106316E-08 -9.276367E+01 -2.462081E-09 -5.100377E-08 + 3.000000E-01 9.000000E+01 6 3.944706E-07 3.112561E+01 3.376811E-07 2.039081E-07 + 4.000000E-01 0.000000E+00 1 1.307384E-01 -5.282935E+01 7.899095E-02 -1.041775E-01 + 4.000000E-01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 4.000000E-01 0.000000E+00 3 2.012498E-02 5.517360E+01 1.149321E-02 1.652032E-02 + 4.000000E-01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 4.000000E-01 0.000000E+00 5 6.834955E-03 1.047795E+02 -1.743601E-03 6.608818E-03 + 4.000000E-01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 4.000000E-01 3.000000E+01 1 5.314526E-02 -1.338230E+02 -3.679949E-02 -3.834339E-02 + 4.000000E-01 3.000000E+01 2 4.128766E-02 -9.884937E+01 -6.351586E-03 -4.079618E-02 + 4.000000E-01 3.000000E+01 3 2.686598E-02 -1.495038E+02 -2.314942E-02 -1.363397E-02 + 4.000000E-01 3.000000E+01 4 1.264045E-01 1.048542E+02 -3.240515E-02 1.221802E-01 + 4.000000E-01 3.000000E+01 5 4.001336E-03 7.631565E+01 9.466071E-04 3.887753E-03 + 4.000000E-01 3.000000E+01 6 5.532191E-01 -1.786506E+02 -5.530657E-01 -1.302844E-02 + 4.000000E-01 6.000000E+01 1 3.044731E-02 1.381135E+02 -2.266707E-02 2.032837E-02 + 4.000000E-01 6.000000E+01 2 7.044896E-02 8.796443E+01 2.502343E-03 7.040451E-02 + 4.000000E-01 6.000000E+01 3 6.615130E-02 -1.709194E+02 -6.532224E-02 -1.044024E-02 + 4.000000E-01 6.000000E+01 4 3.611451E-01 -8.312469E+01 4.323230E-02 -3.585481E-01 + 4.000000E-01 6.000000E+01 5 6.043765E-03 5.819611E+01 3.185145E-03 5.136336E-03 + 4.000000E-01 6.000000E+01 6 3.507415E-01 -1.755146E+02 -3.496673E-01 -2.742958E-02 + 4.000000E-01 9.000000E+01 1 5.332167E-07 -9.304235E+01 -2.829999E-08 -5.324652E-07 + 4.000000E-01 9.000000E+01 2 3.888678E-02 1.746534E+02 -3.871759E-02 3.623477E-03 + 4.000000E-01 9.000000E+01 3 5.207599E-02 1.688102E+02 -5.108601E-02 1.010584E-02 + 4.000000E-01 9.000000E+01 4 1.950537E-01 1.483926E+01 1.885483E-01 4.995484E-02 + 4.000000E-01 9.000000E+01 5 2.097070E-07 8.940276E+01 2.185888E-09 2.096956E-07 + 4.000000E-01 9.000000E+01 6 5.884815E-07 -8.653599E+00 5.817823E-07 -8.854307E-08 + 5.000000E-01 0.000000E+00 1 3.081082E-01 8.983705E+01 8.762858E-04 3.081069E-01 + 5.000000E-01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 5.000000E-01 0.000000E+00 3 2.407918E-02 2.501227E+01 2.182096E-02 1.018097E-02 + 5.000000E-01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 5.000000E-01 0.000000E+00 5 4.103291E-02 -9.531126E+01 -3.798261E-03 -4.085674E-02 + 5.000000E-01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 5.000000E-01 3.000000E+01 1 9.193930E-02 1.028800E+02 -2.049419E-02 8.962601E-02 + 5.000000E-01 3.000000E+01 2 1.244288E-02 1.155199E+02 -5.360694E-03 1.122890E-02 + 5.000000E-01 3.000000E+01 3 5.293012E-02 9.640726E+01 -5.906723E-03 5.259950E-02 + 5.000000E-01 3.000000E+01 4 3.355523E-01 -5.319021E+01 2.010497E-01 -2.686529E-01 + 5.000000E-01 3.000000E+01 5 3.948701E-03 6.551472E+01 1.636576E-03 3.593585E-03 + 5.000000E-01 3.000000E+01 6 1.075385E+00 2.140287E+01 1.001224E+00 3.924331E-01 + 5.000000E-01 6.000000E+01 1 1.267945E-01 1.144335E+02 -5.244690E-02 1.154391E-01 + 5.000000E-01 6.000000E+01 2 8.339784E-02 1.031805E+02 -1.901636E-02 8.120085E-02 + 5.000000E-01 6.000000E+01 3 6.141623E-02 -1.751663E+02 -6.119780E-02 -5.175158E-03 + 5.000000E-01 6.000000E+01 4 4.040240E-01 -6.234457E+01 1.875290E-01 -3.578662E-01 + 5.000000E-01 6.000000E+01 5 1.285017E-02 4.696736E+01 8.769150E-03 9.393029E-03 + 5.000000E-01 6.000000E+01 6 1.832786E+00 1.790019E+02 -1.832507E+00 3.192545E-02 + 5.000000E-01 9.000000E+01 1 1.766503E-06 8.096854E+01 2.773000E-07 1.744602E-06 + 5.000000E-01 9.000000E+01 2 2.347312E-01 6.647649E+01 9.368712E-02 2.152242E-01 + 5.000000E-01 9.000000E+01 3 3.180214E-02 1.300939E+02 -2.048190E-02 2.432833E-02 + 5.000000E-01 9.000000E+01 4 4.249727E-01 -8.168529E+01 6.145542E-02 -4.205057E-01 + 5.000000E-01 9.000000E+01 5 1.556368E-07 9.600702E+01 -1.628744E-08 1.547822E-07 + 5.000000E-01 9.000000E+01 6 7.300903E-05 1.775445E+02 -7.294200E-05 3.127902E-06 + 6.000000E-01 0.000000E+00 1 1.872266E-01 -1.771957E+02 -1.870024E-01 -9.159982E-03 + 6.000000E-01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 6.000000E-01 0.000000E+00 3 2.174157E-02 1.385365E+02 -1.629265E-02 1.439602E-02 + 6.000000E-01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 6.000000E-01 0.000000E+00 5 7.292495E-03 -1.096383E+02 -2.450872E-03 -6.868312E-03 + 6.000000E-01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 6.000000E-01 3.000000E+01 1 2.012022E-01 1.017873E+02 -4.110143E-02 1.969594E-01 + 6.000000E-01 3.000000E+01 2 9.185858E-02 1.075576E+02 -2.771054E-02 8.757925E-02 + 6.000000E-01 3.000000E+01 3 5.708990E-02 -1.741342E+02 -5.679097E-02 -5.834544E-03 + 6.000000E-01 3.000000E+01 4 3.475970E-01 -7.517700E+01 8.892706E-02 -3.360293E-01 + 6.000000E-01 3.000000E+01 5 3.762222E-02 -8.768892E+01 1.517118E-03 -3.759162E-02 + 6.000000E-01 3.000000E+01 6 5.433523E-01 -8.032565E+01 9.130932E-02 -5.356252E-01 + 6.000000E-01 6.000000E+01 1 6.134738E-02 -6.685158E+01 2.411654E-02 -5.640827E-02 + 6.000000E-01 6.000000E+01 2 2.838711E-01 -5.865669E+01 1.476598E-01 -2.424446E-01 + 6.000000E-01 6.000000E+01 3 7.000349E-02 3.677592E+01 5.607161E-02 4.191018E-02 + 6.000000E-01 6.000000E+01 4 8.238294E-01 1.504999E+02 -7.170240E-01 4.056741E-01 + 6.000000E-01 6.000000E+01 5 1.140813E-02 -4.424509E+01 8.172348E-03 -7.959786E-03 + 6.000000E-01 6.000000E+01 6 9.150789E-01 3.374132E+01 7.609373E-01 5.082753E-01 + 6.000000E-01 9.000000E+01 1 7.724071E-07 6.753969E+01 2.950931E-07 7.138157E-07 + 6.000000E-01 9.000000E+01 2 2.032647E-01 9.344522E+01 -1.221503E-02 2.028973E-01 + 6.000000E-01 9.000000E+01 3 5.020192E-02 6.025718E+01 2.490556E-02 4.358836E-02 + 6.000000E-01 9.000000E+01 4 9.899581E-01 -8.339436E+01 1.138798E-01 -9.833862E-01 + 6.000000E-01 9.000000E+01 5 4.465225E-07 -1.031010E+02 -1.012124E-07 -4.349005E-07 + 6.000000E-01 9.000000E+01 6 9.935205E-06 -1.697474E+02 -9.776565E-06 -1.768350E-06 + 7.000000E-01 0.000000E+00 1 8.027183E-01 6.060232E+01 3.940291E-01 6.993552E-01 + 7.000000E-01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 7.000000E-01 0.000000E+00 3 1.692642E-01 3.964836E+01 1.303292E-01 1.080031E-01 + 7.000000E-01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 7.000000E-01 0.000000E+00 5 1.808603E-01 -1.052378E+02 -4.753476E-02 -1.745018E-01 + 7.000000E-01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 7.000000E-01 3.000000E+01 1 1.148481E-01 -1.690576E+02 -1.127600E-01 -2.180065E-02 + 7.000000E-01 3.000000E+01 2 1.608283E-01 4.394753E+00 1.603555E-01 1.232391E-02 + 7.000000E-01 3.000000E+01 3 7.954486E-03 -1.564072E+02 -7.289595E-03 -3.183652E-03 + 7.000000E-01 3.000000E+01 4 8.603882E-01 8.365328E+01 9.511141E-02 8.551151E-01 + 7.000000E-01 3.000000E+01 5 7.463598E-02 -6.266520E+01 3.427203E-02 -6.630202E-02 + 7.000000E-01 3.000000E+01 6 9.527321E+00 1.384091E+02 -7.125519E+00 6.324304E+00 + 7.000000E-01 6.000000E+01 1 4.940590E-01 -1.497921E+02 -4.269682E-01 -2.485807E-01 + 7.000000E-01 6.000000E+01 2 4.148615E-01 -1.045590E+02 -1.042866E-01 -4.015400E-01 + 7.000000E-01 6.000000E+01 3 1.437976E-01 2.332423E+01 1.320463E-01 5.693434E-02 + 7.000000E-01 6.000000E+01 4 1.464140E+00 -7.177795E+01 4.578373E-01 -1.390716E+00 + 7.000000E-01 6.000000E+01 5 6.378181E-02 7.214042E+01 1.956094E-02 6.070822E-02 + 7.000000E-01 6.000000E+01 6 1.511462E+01 -1.530150E+01 1.457881E+01 -3.988723E+00 + 7.000000E-01 9.000000E+01 1 1.589562E-06 -5.732171E+01 8.582388E-07 -1.337959E-06 + 7.000000E-01 9.000000E+01 2 6.702136E-01 5.452286E+01 3.889773E-01 5.457866E-01 + 7.000000E-01 9.000000E+01 3 1.072043E-01 8.414521E+01 1.093565E-02 1.066451E-01 + 7.000000E-01 9.000000E+01 4 1.161876E+00 -5.514134E+01 6.640748E-01 -9.533941E-01 + 7.000000E-01 9.000000E+01 5 3.845822E-07 -1.378897E+02 -2.853046E-07 -2.578852E-07 + 7.000000E-01 9.000000E+01 6 2.159800E-04 1.604690E+02 -2.035527E-04 7.220576E-05 + 8.000001E-01 0.000000E+00 1 4.028370E+00 -5.588440E+01 2.259370E+00 -3.335119E+00 + 8.000001E-01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 8.000001E-01 0.000000E+00 3 2.095643E-01 -3.923662E+00 2.090731E-01 -1.433992E-02 + 8.000001E-01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 8.000001E-01 0.000000E+00 5 7.912704E-01 1.254263E+02 -4.586639E-01 6.447762E-01 + 8.000001E-01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 8.000001E-01 3.000000E+01 1 5.347347E-01 -7.389597E+01 1.483259E-01 -5.137515E-01 + 8.000001E-01 3.000000E+01 2 3.749571E-01 4.094019E+01 2.832404E-01 2.456985E-01 + 8.000001E-01 3.000000E+01 3 2.190640E-01 -1.435698E+02 -1.762548E-01 -1.300895E-01 + 8.000001E-01 3.000000E+01 4 1.997968E+00 -5.941833E+01 1.016498E+00 -1.720060E+00 + 8.000001E-01 3.000000E+01 5 1.540143E-01 1.044117E+02 -3.833220E-02 1.491678E-01 + 8.000001E-01 3.000000E+01 6 1.853185E+01 -1.581446E+02 -1.719990E+01 -6.898758E+00 + 8.000001E-01 6.000000E+01 1 2.647785E-01 -9.986835E+00 2.607664E-01 -4.591838E-02 + 8.000001E-01 6.000000E+01 2 3.127118E-02 -1.723142E+02 -3.099025E-02 -4.182242E-03 + 8.000001E-01 6.000000E+01 3 2.191740E-01 -1.447901E+02 -1.790750E-01 -1.263701E-01 + 8.000001E-01 6.000000E+01 4 1.036278E+00 -4.005235E+01 7.932259E-01 -6.668315E-01 + 8.000001E-01 6.000000E+01 5 1.151183E-01 -1.673150E+02 -1.123085E-01 -2.527882E-02 + 8.000001E-01 6.000000E+01 6 2.461483E+00 -1.095917E+01 2.416592E+00 -4.679509E-01 + 8.000001E-01 9.000000E+01 1 1.617859E-06 1.135123E+02 -6.454394E-07 1.483535E-06 + 8.000001E-01 9.000000E+01 2 1.755162E+00 -7.329680E+01 5.044584E-01 -1.681106E+00 + 8.000001E-01 9.000000E+01 3 8.098494E-02 6.427621E+01 3.515016E-02 7.295907E-02 + 8.000001E-01 9.000000E+01 4 1.641137E+00 -6.077317E+01 8.013152E-01 -1.432210E+00 + 8.000001E-01 9.000000E+01 5 5.084881E-07 -8.231286E+01 6.801734E-08 -5.039184E-07 + 8.000001E-01 9.000000E+01 6 2.693365E-04 2.322025E+01 2.475192E-04 1.061904E-04 + 9.000001E-01 0.000000E+00 1 1.068581E+00 6.843844E+01 3.927042E-01 9.938048E-01 + 9.000001E-01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 9.000001E-01 0.000000E+00 3 5.909093E-02 -1.017197E+02 -1.200281E-02 -5.785906E-02 + 9.000001E-01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 9.000001E-01 0.000000E+00 5 2.806859E-01 -1.200122E+02 -1.403947E-01 -2.430512E-01 + 9.000001E-01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 9.000001E-01 3.000000E+01 1 6.341945E-01 -6.897472E+01 2.275362E-01 -5.919712E-01 + 9.000001E-01 3.000000E+01 2 2.360800E-01 1.247190E+02 -1.344599E-01 1.940472E-01 + 9.000001E-01 3.000000E+01 3 3.962129E-02 -6.630566E+00 3.935628E-02 -4.574955E-03 + 9.000001E-01 3.000000E+01 4 1.353328E+00 2.196399E+01 1.255102E+00 5.061766E-01 + 9.000001E-01 3.000000E+01 5 1.222350E-01 1.242814E+02 -6.884973E-02 1.010005E-01 + 9.000001E-01 3.000000E+01 6 3.158235E+01 -3.682267E+01 2.528149E+01 -1.892858E+01 + 9.000001E-01 6.000000E+01 1 1.149328E+00 7.111678E+01 3.719688E-01 1.087471E+00 + 9.000001E-01 6.000000E+01 2 1.495766E+00 5.134853E+01 9.342274E-01 1.168133E+00 + 9.000001E-01 6.000000E+01 3 1.335133E-01 1.577747E+02 -1.235937E-01 5.050145E-02 + 9.000001E-01 6.000000E+01 4 6.085460E-01 -1.030611E+02 -1.375258E-01 -5.928026E-01 + 9.000001E-01 6.000000E+01 5 1.975831E-01 -1.385824E+02 -1.481691E-01 -1.307095E-01 + 9.000001E-01 6.000000E+01 6 3.867049E+00 -6.315012E+01 1.746570E+00 -3.450154E+00 + 9.000001E-01 9.000000E+01 1 2.148013E-06 -3.934335E+01 1.661189E-06 -1.361768E-06 + 9.000001E-01 9.000000E+01 2 5.254689E-01 6.716647E+01 2.039109E-01 4.842912E-01 + 9.000001E-01 9.000000E+01 3 2.646114E-01 -2.418865E+01 2.413789E-01 -1.084225E-01 + 9.000001E-01 9.000000E+01 4 1.538332E+00 9.886794E+01 -2.371452E-01 1.519943E+00 + 9.000001E-01 9.000000E+01 5 5.961102E-07 -1.758145E+02 -5.945204E-07 -4.350777E-08 + 9.000001E-01 9.000000E+01 6 2.369981E-04 1.465884E+02 -1.978308E-04 1.305030E-04 + 1.000000E+00 0.000000E+00 1 4.498790E+00 1.417020E+02 -3.530643E+00 2.788131E+00 + 1.000000E+00 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.000000E+00 0.000000E+00 3 4.891869E-01 1.280575E+02 -3.015603E-01 3.851821E-01 + 1.000000E+00 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.000000E+00 0.000000E+00 5 1.111608E+00 -4.117408E+01 8.367217E-01 -7.318260E-01 + 1.000000E+00 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.000000E+00 3.000000E+01 1 9.384710E-01 6.006435E+01 4.683224E-01 8.132662E-01 + 1.000000E+00 3.000000E+01 2 5.688173E-01 6.984396E+01 1.960020E-01 5.339816E-01 + 1.000000E+00 3.000000E+01 3 3.170465E-01 1.560125E+02 -2.896644E-01 1.288915E-01 + 1.000000E+00 3.000000E+01 4 2.548091E+00 -1.309901E+02 -1.671366E+00 -1.923358E+00 + 1.000000E+00 3.000000E+01 5 2.532068E-01 -1.020614E+02 -5.291017E-02 -2.476170E-01 + 1.000000E+00 3.000000E+01 6 1.370568E+01 8.000809E+01 2.378060E+00 1.349780E+01 + 1.000000E+00 6.000000E+01 1 1.063347E+00 1.199143E+02 -5.302954E-01 9.216798E-01 + 1.000000E+00 6.000000E+01 2 9.221056E-01 -1.749147E+02 -9.184759E-01 -8.173476E-02 + 1.000000E+00 6.000000E+01 3 5.232720E-01 -1.733326E+02 -5.197331E-01 -6.075449E-02 + 1.000000E+00 6.000000E+01 4 5.569331E-01 -2.655671E+01 4.981723E-01 -2.489956E-01 + 1.000000E+00 6.000000E+01 5 4.033430E-01 -6.104259E+01 1.952823E-01 -3.529170E-01 + 1.000000E+00 6.000000E+01 6 9.770492E+00 4.874333E+01 6.442988E+00 7.345094E+00 + 1.000000E+00 9.000000E+01 1 3.758858E-06 3.555691E+01 3.057976E-06 2.185818E-06 + 1.000000E+00 9.000000E+01 2 2.487580E+00 1.172793E+02 -1.140129E+00 2.210919E+00 + 1.000000E+00 9.000000E+01 3 9.679143E-02 8.315680E+00 9.577379E-02 1.399865E-02 + 1.000000E+00 9.000000E+01 4 2.912810E+00 -1.650378E+02 -2.814055E+00 -7.520341E-01 + 1.000000E+00 9.000000E+01 5 6.350767E-07 -1.537991E+02 -5.698235E-07 -2.803990E-07 + 1.000000E+00 9.000000E+01 6 3.296134E-04 -1.187178E+02 -1.583778E-04 -2.890700E-04 + 1.100000E+00 0.000000E+00 1 2.409579E+00 1.689714E+02 -2.365078E+00 4.609488E-01 + 1.100000E+00 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.100000E+00 0.000000E+00 3 7.349316E-01 -1.583984E+02 -6.833147E-01 -2.705651E-01 + 1.100000E+00 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.100000E+00 0.000000E+00 5 6.515889E-01 2.371388E+00 6.510308E-01 2.696060E-02 + 1.100000E+00 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.100000E+00 3.000000E+01 1 1.383384E+00 -2.329154E+01 1.270645E+00 -5.470040E-01 + 1.100000E+00 3.000000E+01 2 7.300221E-01 -7.040385E+01 2.448408E-01 -6.877392E-01 + 1.100000E+00 3.000000E+01 3 2.772623E-01 -6.642005E+01 1.109128E-01 -2.541117E-01 + 1.100000E+00 3.000000E+01 4 2.365005E+00 1.220531E+02 -1.255120E+00 2.004475E+00 + 1.100000E+00 3.000000E+01 5 1.840076E-01 1.413332E+02 -1.436718E-01 1.149662E-01 + 1.100000E+00 3.000000E+01 6 1.300902E+01 -7.074613E+00 1.290998E+01 -1.602214E+00 + 1.100000E+00 6.000000E+01 1 6.888239E-01 1.965264E+01 6.486992E-01 2.316631E-01 + 1.100000E+00 6.000000E+01 2 1.274021E+00 7.086687E+01 4.175786E-01 1.203644E+00 + 1.100000E+00 6.000000E+01 3 3.023910E-01 -1.388350E+02 -2.276452E-01 -1.990427E-01 + 1.100000E+00 6.000000E+01 4 4.212014E+00 1.605077E+02 -3.970607E+00 1.405468E+00 + 1.100000E+00 6.000000E+01 5 6.740979E-02 1.239330E+02 -3.762972E-02 5.592928E-02 + 1.100000E+00 6.000000E+01 6 6.277072E+00 -1.779185E+02 -6.272930E+00 -2.279956E-01 + 1.100000E+00 9.000000E+01 1 9.634122E-07 1.621139E+02 -9.168493E-07 2.958890E-07 + 1.100000E+00 9.000000E+01 2 3.993272E-01 -1.672850E+02 -3.895345E-01 -8.789238E-02 + 1.100000E+00 9.000000E+01 3 3.142914E-01 1.432106E+02 -2.516979E-01 1.882212E-01 + 1.100000E+00 9.000000E+01 4 3.689179E+00 -3.181832E+01 3.134784E+00 -1.945037E+00 + 1.100000E+00 9.000000E+01 5 4.653694E-07 -5.811555E+01 2.458118E-07 -3.951522E-07 + 1.100000E+00 9.000000E+01 6 6.607713E-05 2.584140E-01 6.607646E-05 2.980184E-07 + 1.200000E+00 0.000000E+00 1 1.443482E+00 -1.671270E+02 -1.407202E+00 -3.215949E-01 + 1.200000E+00 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.200000E+00 0.000000E+00 3 4.628122E-01 -1.645647E+02 -4.461193E-01 -1.231774E-01 + 1.200000E+00 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.200000E+00 0.000000E+00 5 5.352653E-01 4.020810E+01 4.087847E-01 3.455489E-01 + 1.200000E+00 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.200000E+00 3.000000E+01 1 2.075541E+00 1.748229E+02 -2.067074E+00 1.872850E-01 + 1.200000E+00 3.000000E+01 2 1.362046E+00 1.108371E+02 -4.844972E-01 1.272962E+00 + 1.200000E+00 3.000000E+01 3 8.534918E-01 -1.128969E+02 -3.320719E-01 -7.862421E-01 + 1.200000E+00 3.000000E+01 4 2.205437E+00 1.177562E+01 2.159022E+00 4.500845E-01 + 1.200000E+00 3.000000E+01 5 6.961068E-01 -5.783009E+00 6.925641E-01 -7.014059E-02 + 1.200000E+00 3.000000E+01 6 1.774967E+01 -7.653576E+01 4.132805E+00 -1.726183E+01 + 1.200000E+00 6.000000E+01 1 2.512922E+00 1.082590E+02 -7.873306E-01 2.386397E+00 + 1.200000E+00 6.000000E+01 2 4.185233E+00 8.515934E+01 3.531708E-01 4.170305E+00 + 1.200000E+00 6.000000E+01 3 3.349589E-01 5.579454E+01 1.883012E-01 2.770200E-01 + 1.200000E+00 6.000000E+01 4 1.705958E+00 2.558417E+01 1.538692E+00 7.366951E-01 + 1.200000E+00 6.000000E+01 5 9.582613E-01 -7.502637E+01 2.475901E-01 -9.257234E-01 + 1.200000E+00 6.000000E+01 6 1.168844E+02 1.558077E+02 -1.066191E+02 4.789923E+01 + 1.200000E+00 9.000000E+01 1 3.344430E-06 -1.190675E+02 -1.624855E-06 -2.923193E-06 + 1.200000E+00 9.000000E+01 2 3.579329E+00 -7.162445E+01 1.128362E+00 -3.396821E+00 + 1.200000E+00 9.000000E+01 3 5.534689E-01 1.540251E+02 -4.975608E-01 2.424069E-01 + 1.200000E+00 9.000000E+01 4 1.741812E+00 1.029711E+02 -3.909655E-01 1.697367E+00 + 1.200000E+00 9.000000E+01 5 1.616718E-06 8.714442E+01 8.054281E-08 1.614711E-06 + 1.200000E+00 9.000000E+01 6 4.290794E-04 -2.489748E+01 3.892018E-04 -1.806407E-04 + 1.300000E+00 0.000000E+00 1 7.003986E+00 1.314920E+02 -4.640247E+00 5.246325E+00 + 1.300000E+00 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.300000E+00 0.000000E+00 3 6.571900E-01 -1.645828E+02 -6.335413E-01 -1.747112E-01 + 1.300000E+00 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.300000E+00 0.000000E+00 5 2.849876E+00 -4.921009E+01 1.861788E+00 -2.157670E+00 + 1.300000E+00 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.300000E+00 3.000000E+01 1 2.263089E+00 1.555407E+02 -2.059990E+00 9.370242E-01 + 1.300000E+00 3.000000E+01 2 2.027119E+00 1.166973E+02 -9.107381E-01 1.811013E+00 + 1.300000E+00 3.000000E+01 3 5.080034E-01 6.292294E+01 2.312373E-01 4.523238E-01 + 1.300000E+00 3.000000E+01 4 4.724977E+00 -4.095230E+01 3.568564E+00 -3.096894E+00 + 1.300000E+00 3.000000E+01 5 6.495391E-01 -1.060814E+01 6.384380E-01 -1.195743E-01 + 1.300000E+00 3.000000E+01 6 3.506529E+01 7.157618E+01 1.108216E+01 3.326801E+01 + 1.300000E+00 6.000000E+01 1 9.093643E-01 8.503635E+01 7.868150E-02 9.059540E-01 + 1.300000E+00 6.000000E+01 2 2.073938E+00 1.441509E+02 -1.681056E+00 1.214607E+00 + 1.300000E+00 6.000000E+01 3 1.249524E+00 2.353761E+00 1.248470E+00 5.131713E-02 + 1.300000E+00 6.000000E+01 4 1.618520E+00 -1.168375E+02 -7.307007E-01 -1.444189E+00 + 1.300000E+00 6.000000E+01 5 5.895178E-01 -1.037552E+02 -1.401722E-01 -5.726107E-01 + 1.300000E+00 6.000000E+01 6 1.155252E+02 4.325387E+01 8.413983E+01 7.916157E+01 + 1.300000E+00 9.000000E+01 1 7.389086E-06 3.724580E+01 5.882055E-06 4.472139E-06 + 1.300000E+00 9.000000E+01 2 2.336719E+00 -1.787105E+02 -2.336127E+00 -5.258447E-02 + 1.300000E+00 9.000000E+01 3 4.543476E-01 -1.128423E+02 -1.763758E-01 -4.187163E-01 + 1.300000E+00 9.000000E+01 4 2.450729E+00 1.110250E+02 -8.792601E-01 2.287569E+00 + 1.300000E+00 9.000000E+01 5 3.034535E-06 -1.440656E+02 -2.457031E-06 -1.780843E-06 + 1.300000E+00 9.000000E+01 6 4.249371E-04 -1.246016E+02 -2.413078E-04 -3.497743E-04 + 1.400000E+00 0.000000E+00 1 1.171565E+01 7.347941E+01 3.331463E+00 1.123200E+01 + 1.400000E+00 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.400000E+00 0.000000E+00 3 2.655761E-01 -3.997689E+01 2.035120E-01 -1.706269E-01 + 1.400000E+00 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.400000E+00 0.000000E+00 5 5.973072E+00 -1.114528E+02 -2.184563E+00 -5.559251E+00 + 1.400000E+00 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.400000E+00 3.000000E+01 1 1.173266E+01 7.165550E+01 3.692616E+00 1.113642E+01 + 1.400000E+00 3.000000E+01 2 4.782632E+00 5.907642E+01 2.457768E+00 4.102797E+00 + 1.400000E+00 3.000000E+01 3 1.455644E+00 6.325904E+01 6.549782E-01 1.299963E+00 + 1.400000E+00 3.000000E+01 4 5.447604E+00 1.608448E+02 -5.145986E+00 1.787515E+00 + 1.400000E+00 3.000000E+01 5 5.153780E+00 -1.096298E+02 -1.731364E+00 -4.854259E+00 + 1.400000E+00 3.000000E+01 6 2.281675E+01 9.611151E+01 -2.429159E+00 2.268707E+01 + 1.400000E+00 6.000000E+01 1 1.157303E+01 -1.016479E+02 -2.336565E+00 -1.133470E+01 + 1.400000E+00 6.000000E+01 2 1.292264E+01 -9.645769E+01 -1.453401E+00 -1.284064E+01 + 1.400000E+00 6.000000E+01 3 6.924345E-01 1.279500E+02 -4.258292E-01 5.460174E-01 + 1.400000E+00 6.000000E+01 4 5.056304E+00 1.624172E+02 -4.820082E+00 1.527424E+00 + 1.400000E+00 6.000000E+01 5 5.463288E+00 7.882168E+01 1.059131E+00 5.359642E+00 + 1.400000E+00 6.000000E+01 6 1.273826E+02 1.634732E+02 -1.221200E+02 3.623571E+01 + 1.400000E+00 9.000000E+01 1 7.535232E-06 1.578394E+02 -6.978606E-06 2.842320E-06 + 1.400000E+00 9.000000E+01 2 1.086191E+01 6.206549E+01 5.088391E+00 9.596318E+00 + 1.400000E+00 9.000000E+01 3 9.402484E-02 -1.133706E+02 -3.729743E-02 -8.631090E-02 + 1.400000E+00 9.000000E+01 4 3.135868E+00 1.319860E+01 3.053032E+00 7.160037E-01 + 1.400000E+00 9.000000E+01 5 4.244722E-06 -2.349240E+01 3.892890E-06 -1.692062E-06 + 1.400000E+00 9.000000E+01 6 4.178208E-04 1.586816E+02 -3.892313E-04 1.518986E-04 + 1.500000E+00 0.000000E+00 1 2.253690E+01 2.170131E+01 2.093958E+01 8.333425E+00 + 1.500000E+00 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.500000E+00 0.000000E+00 3 8.662427E-01 1.083845E+02 -2.732056E-01 8.220311E-01 + 1.500000E+00 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.500000E+00 0.000000E+00 5 1.326415E+01 -1.582939E+02 -1.232364E+01 -4.905677E+00 + 1.500000E+00 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.500000E+00 3.000000E+01 1 3.378882E+00 9.253078E+00 3.334915E+00 5.433093E-01 + 1.500000E+00 3.000000E+01 2 7.914361E+00 2.474301E+01 7.187777E+00 3.312547E+00 + 1.500000E+00 3.000000E+01 3 5.950861E-01 -3.377501E+01 4.946517E-01 -3.308280E-01 + 1.500000E+00 3.000000E+01 4 8.162408E+00 -1.378921E+02 -6.055557E+00 -5.473128E+00 + 1.500000E+00 3.000000E+01 5 1.556425E+00 1.701120E+02 -1.533305E+00 2.672737E-01 + 1.500000E+00 3.000000E+01 6 3.121408E+01 -1.125936E+02 -1.199218E+01 -2.881851E+01 + 1.500000E+00 6.000000E+01 1 8.058857E+00 1.511977E+01 7.779881E+00 2.102053E+00 + 1.500000E+00 6.000000E+01 2 1.575511E+01 2.624129E+01 1.413138E+01 6.966158E+00 + 1.500000E+00 6.000000E+01 3 1.023166E+00 1.520826E+02 -9.040931E-01 4.790444E-01 + 1.500000E+00 6.000000E+01 4 3.840172E+00 5.642629E+01 2.123651E+00 3.199536E+00 + 1.500000E+00 6.000000E+01 5 5.091404E+00 -1.611259E+02 -4.817647E+00 -1.647017E+00 + 1.500000E+00 6.000000E+01 6 1.822460E+01 1.319307E+02 -1.217826E+01 1.355825E+01 + 1.500000E+00 9.000000E+01 1 7.987765E-06 1.628710E+02 -7.633459E-06 2.352590E-06 + 1.500000E+00 9.000000E+01 2 5.198710E+00 1.088665E+02 -1.681076E+00 4.919408E+00 + 1.500000E+00 9.000000E+01 3 6.865063E-01 4.361718E+01 4.970066E-01 4.735772E-01 + 1.500000E+00 9.000000E+01 4 7.910254E+00 1.620439E+01 7.595998E+00 2.207472E+00 + 1.500000E+00 9.000000E+01 5 4.914498E-06 -2.147218E+01 4.573409E-06 -1.798949E-06 + 1.500000E+00 9.000000E+01 6 5.152921E-04 1.271103E+02 -3.109023E-04 4.109327E-04 + 1.600000E+00 0.000000E+00 1 2.117395E+01 -6.286393E+01 9.657549E+00 -1.884324E+01 + 1.600000E+00 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.600000E+00 0.000000E+00 3 6.416135E-02 1.035933E+02 -1.507976E-02 6.236409E-02 + 1.600000E+00 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.600000E+00 0.000000E+00 5 1.372208E+01 1.168204E+02 -6.191330E+00 1.224594E+01 + 1.600000E+00 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.600000E+00 3.000000E+01 1 1.415636E+00 3.696273E+01 1.131131E+00 8.512152E-01 + 1.600000E+00 3.000000E+01 2 2.140322E+00 3.397316E+01 1.774968E+00 1.196021E+00 + 1.600000E+00 3.000000E+01 3 2.697981E+00 -4.465592E+01 1.919183E+00 -1.896270E+00 + 1.600000E+00 3.000000E+01 4 3.825750E+00 1.541572E+02 -3.443149E+00 1.667660E+00 + 1.600000E+00 3.000000E+01 5 3.813242E-01 -1.302608E+02 -2.464376E-01 -2.909925E-01 + 1.600000E+00 3.000000E+01 6 5.789972E+01 -1.640426E+02 -5.566863E+01 -1.591795E+01 + 1.600000E+00 6.000000E+01 1 6.619334E+00 1.283833E+02 -4.110074E+00 5.188725E+00 + 1.600000E+00 6.000000E+01 2 1.838614E+01 1.424945E+02 -1.458563E+01 1.119418E+01 + 1.600000E+00 6.000000E+01 3 2.027168E+00 -1.594750E+02 -1.898481E+00 -7.107591E-01 + 1.600000E+00 6.000000E+01 4 9.656239E+00 1.708991E+02 -9.534679E+00 1.527363E+00 + 1.600000E+00 6.000000E+01 5 4.125096E+00 -4.624290E+01 2.852927E+00 -2.979468E+00 + 1.600000E+00 6.000000E+01 6 2.767762E+01 -1.623947E+02 -2.638127E+01 -8.371320E+00 + 1.600000E+00 9.000000E+01 1 1.362756E-06 -1.219808E+02 -7.217633E-07 -1.155925E-06 + 1.600000E+00 9.000000E+01 2 1.583243E+01 -3.573277E+01 1.285197E+01 -9.246226E+00 + 1.600000E+00 9.000000E+01 3 6.111758E-01 6.304171E+01 2.770716E-01 5.447634E-01 + 1.600000E+00 9.000000E+01 4 4.628506E+00 -3.940343E+01 3.576426E+00 -2.938068E+00 + 1.600000E+00 9.000000E+01 5 9.186458E-07 1.975923E+01 8.645574E-07 3.105651E-07 + 1.600000E+00 9.000000E+01 6 4.913512E-04 5.417681E+01 2.875809E-04 3.984009E-04 + 1.700000E+00 0.000000E+00 1 1.530682E+01 -5.350866E+01 9.102983E+00 -1.230587E+01 + 1.700000E+00 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.700000E+00 0.000000E+00 3 5.826858E-01 4.770614E+01 3.921086E-01 4.310145E-01 + 1.700000E+00 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.700000E+00 0.000000E+00 5 1.124916E+01 1.277608E+02 -6.888609E+00 8.893294E+00 + 1.700000E+00 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.700000E+00 3.000000E+01 1 5.635712E+00 8.176098E+01 8.076141E-01 5.577545E+00 + 1.700000E+00 3.000000E+01 2 7.947534E+00 8.021186E+01 1.351125E+00 7.831843E+00 + 1.700000E+00 3.000000E+01 3 1.510188E+00 -3.053736E+01 1.300722E+00 -7.673268E-01 + 1.700000E+00 3.000000E+01 4 1.109124E+01 6.744710E+01 4.253893E+00 1.024305E+01 + 1.700000E+00 3.000000E+01 5 4.486289E+00 -9.376264E+01 -2.944054E-01 -4.476618E+00 + 1.700000E+00 3.000000E+01 6 3.115220E+01 1.183897E+02 -1.481183E+01 2.740564E+01 + 1.700000E+00 6.000000E+01 1 3.911623E+00 -7.028982E+00 3.882225E+00 -4.786707E-01 + 1.700000E+00 6.000000E+01 2 4.845512E+00 -4.624642E+01 3.350954E+00 -3.500014E+00 + 1.700000E+00 6.000000E+01 3 1.029428E+00 -5.107076E+00 1.025342E+00 -9.163695E-02 + 1.700000E+00 6.000000E+01 4 1.075074E+01 -9.466867E+01 -8.750406E-01 -1.071507E+01 + 1.700000E+00 6.000000E+01 5 3.100899E+00 1.428822E+02 -2.472644E+00 1.871257E+00 + 1.700000E+00 6.000000E+01 6 9.706261E+01 1.629150E+02 -9.277924E+01 2.851603E+01 + 1.700000E+00 9.000000E+01 1 7.440038E-06 -3.070845E+01 6.396773E-06 -3.799403E-06 + 1.700000E+00 9.000000E+01 2 1.270294E+01 -8.442886E+01 1.233221E+00 -1.264294E+01 + 1.700000E+00 9.000000E+01 3 4.901777E-01 -1.579370E+02 -4.542825E-01 -1.841238E-01 + 1.700000E+00 9.000000E+01 4 8.660085E+00 -1.339957E+02 -6.015331E+00 -6.229998E+00 + 1.700000E+00 9.000000E+01 5 6.433670E-06 1.572520E+02 -5.933221E-06 2.487768E-06 + 1.700000E+00 9.000000E+01 6 6.261227E-04 1.977188E+01 5.892108E-04 2.118024E-04 + 1.800000E+00 0.000000E+00 1 1.563779E+01 -2.521997E+01 1.414717E+01 -6.663180E+00 + 1.800000E+00 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.800000E+00 0.000000E+00 3 8.863202E-01 8.969315E+00 8.754823E-01 1.381822E-01 + 1.800000E+00 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.800000E+00 0.000000E+00 5 1.281577E+01 1.564779E+02 -1.175086E+01 5.114805E+00 + 1.800000E+00 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.800000E+00 3.000000E+01 1 2.043249E+01 -1.258618E+02 -1.197001E+01 -1.655915E+01 + 1.800000E+00 3.000000E+01 2 1.070184E+01 -1.181437E+02 -5.047898E+00 -9.436531E+00 + 1.800000E+00 3.000000E+01 3 1.688774E+00 -5.875546E+01 8.759534E-01 -1.443837E+00 + 1.800000E+00 3.000000E+01 4 9.695031E+00 7.104430E+01 3.149306E+00 9.169270E+00 + 1.800000E+00 3.000000E+01 5 1.565632E+01 5.198190E+01 9.642890E+00 1.233430E+01 + 1.800000E+00 3.000000E+01 6 2.845789E+02 -2.323301E+01 2.615019E+02 -1.122582E+02 + 1.800000E+00 6.000000E+01 1 1.510823E+01 -1.385775E+02 -1.132893E+01 -9.995703E+00 + 1.800000E+00 6.000000E+01 2 1.004253E+01 -8.650637E+01 6.119674E-01 -1.002386E+01 + 1.800000E+00 6.000000E+01 3 1.388990E+00 6.042284E+00 1.381273E+00 1.462084E-01 + 1.800000E+00 6.000000E+01 4 1.351580E+01 -1.059756E+02 -3.719937E+00 -1.299381E+01 + 1.800000E+00 6.000000E+01 5 1.413674E+01 4.748552E+01 9.553273E+00 1.042028E+01 + 1.800000E+00 6.000000E+01 6 3.829813E+02 -1.331674E+01 3.726835E+02 -8.821362E+01 + 1.800000E+00 9.000000E+01 1 5.628297E-06 1.162374E+02 -2.488218E-06 5.048415E-06 + 1.800000E+00 9.000000E+01 2 6.767492E+00 -4.651331E+01 4.657294E+00 -4.910047E+00 + 1.800000E+00 9.000000E+01 3 1.506869E+00 -6.931219E+01 5.323405E-01 -1.409705E+00 + 1.800000E+00 9.000000E+01 4 1.066799E+01 -9.853442E+01 -1.583167E+00 -1.054986E+01 + 1.800000E+00 9.000000E+01 5 4.086576E-06 -6.425894E+01 1.774819E-06 -3.681049E-06 + 1.800000E+00 9.000000E+01 6 6.607128E-04 -2.933037E+01 5.760159E-04 -3.236466E-04 + 1.900000E+00 0.000000E+00 1 2.451026E+01 -1.332121E+02 -1.678221E+01 -1.786365E+01 + 1.900000E+00 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.900000E+00 0.000000E+00 3 1.532402E+00 2.599337E+01 1.377392E+00 6.716014E-01 + 1.900000E+00 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.900000E+00 0.000000E+00 5 2.241921E+01 4.611429E+01 1.554149E+01 1.615807E+01 + 1.900000E+00 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.900000E+00 3.000000E+01 1 1.175581E+01 -9.466068E+01 -9.552123E-01 -1.171694E+01 + 1.900000E+00 3.000000E+01 2 9.560308E+00 -9.428857E+01 -7.149178E-01 -9.533540E+00 + 1.900000E+00 3.000000E+01 3 1.041836E+00 -5.468043E+01 6.023233E-01 -8.500760E-01 + 1.900000E+00 3.000000E+01 4 8.651684E+00 7.486741E+01 2.258555E+00 8.351681E+00 + 1.900000E+00 3.000000E+01 5 8.733264E+00 8.609362E+01 5.949658E-01 8.712974E+00 + 1.900000E+00 3.000000E+01 6 1.218528E+02 1.527181E+02 -1.082982E+02 5.585350E+01 + 1.900000E+00 6.000000E+01 1 4.766725E+00 1.457030E+02 -3.937923E+00 2.685968E+00 + 1.900000E+00 6.000000E+01 2 7.627123E+00 6.175206E+01 3.609826E+00 6.718791E+00 + 1.900000E+00 6.000000E+01 3 1.806216E+00 -1.179529E+00 1.805833E+00 -3.718132E-02 + 1.900000E+00 6.000000E+01 4 2.338598E+00 5.864749E+01 1.216777E+00 1.997122E+00 + 1.900000E+00 6.000000E+01 5 4.262382E+00 -1.407905E+01 4.134345E+00 -1.036868E+00 + 1.900000E+00 6.000000E+01 6 1.326395E+02 -1.746618E+02 -1.320642E+02 -1.234013E+01 + 1.900000E+00 9.000000E+01 1 5.604497E-06 6.239099E+00 5.571302E-06 6.090841E-07 + 1.900000E+00 9.000000E+01 2 1.889650E+01 -1.268181E+02 -1.132423E+01 -1.512744E+01 + 1.900000E+00 9.000000E+01 3 1.551565E+00 -1.180688E+02 -7.300589E-01 -1.369075E+00 + 1.900000E+00 9.000000E+01 4 2.209306E+01 -1.472831E+02 -1.858802E+01 -1.194106E+01 + 1.900000E+00 9.000000E+01 5 6.493098E-06 -1.682033E+02 -6.355958E-06 -1.327448E-06 + 1.900000E+00 9.000000E+01 6 5.750424E-04 -4.119217E+01 4.327223E-04 -3.787153E-04 + 2.000000E+00 0.000000E+00 1 5.821302E+00 -6.600632E+01 2.367150E+00 -5.318286E+00 + 2.000000E+00 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.000000E+00 0.000000E+00 3 8.212474E-01 -5.246426E+00 8.178069E-01 -7.509445E-02 + 2.000000E+00 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.000000E+00 0.000000E+00 5 5.942253E+00 1.149928E+02 -2.510632E+00 5.385824E+00 + 2.000000E+00 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.000000E+00 3.000000E+01 1 2.971290E+01 1.648385E+02 -2.867867E+01 7.771135E+00 + 2.000000E+00 3.000000E+01 2 2.109365E+01 -1.544192E+02 -1.902600E+01 -9.107873E+00 + 2.000000E+00 3.000000E+01 3 1.116087E+00 1.449782E+02 -9.140012E-01 6.405092E-01 + 2.000000E+00 3.000000E+01 4 1.737694E+01 1.613567E+02 -1.646511E+01 5.554991E+00 + 2.000000E+00 3.000000E+01 5 3.115120E+01 -2.130091E+01 2.902312E+01 -1.131617E+01 + 2.000000E+00 3.000000E+01 6 1.132266E+02 -9.659354E+01 -1.300126E+01 -1.124777E+02 + 2.000000E+00 6.000000E+01 1 1.129384E+01 -7.250443E+01 3.395290E+00 -1.077139E+01 + 2.000000E+00 6.000000E+01 2 8.313642E+00 1.825148E+01 7.895391E+00 2.603735E+00 + 2.000000E+00 6.000000E+01 3 3.279949E+00 -2.767537E+01 2.904701E+00 -1.523410E+00 + 2.000000E+00 6.000000E+01 4 1.487036E+01 1.412784E+01 1.442059E+01 3.629652E+00 + 2.000000E+00 6.000000E+01 5 1.104694E+01 1.092108E+02 -3.634940E+00 1.043178E+01 + 2.000000E+00 6.000000E+01 6 5.640735E+02 1.091309E+02 -1.848626E+02 5.329210E+02 + 2.000000E+00 9.000000E+01 1 1.187785E-05 8.651313E+01 7.224082E-07 1.185586E-05 + 2.000000E+00 9.000000E+01 2 3.749706E+01 -1.751489E+02 -3.736274E+01 -3.170978E+00 + 2.000000E+00 9.000000E+01 3 1.734941E+00 -6.733071E+01 6.686662E-01 -1.600908E+00 + 2.000000E+00 9.000000E+01 4 3.541190E+01 -1.760981E+02 -3.532981E+01 -2.409709E+00 + 2.000000E+00 9.000000E+01 5 1.130888E-05 -8.963467E+01 7.210677E-08 -1.130865E-05 + 2.000000E+00 9.000000E+01 6 7.684740E-04 -6.270164E+01 3.524407E-04 -6.828893E-04 + 2.100000E+00 0.000000E+00 1 3.469384E+01 -1.632826E+02 -3.322751E+01 -9.979723E+00 + 2.100000E+00 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.100000E+00 0.000000E+00 3 3.800893E-01 1.574097E+02 -3.509271E-01 1.460069E-01 + 2.100000E+00 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.100000E+00 0.000000E+00 5 3.752528E+01 1.653084E+01 3.597424E+01 1.067712E+01 + 2.100000E+00 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.100000E+00 3.000000E+01 1 3.390757E+00 4.897110E+01 2.225828E+00 2.557914E+00 + 2.100000E+00 3.000000E+01 2 8.254489E+00 -9.804829E+01 -1.155693E+00 -8.173185E+00 + 2.100000E+00 3.000000E+01 3 2.355528E+00 1.350706E+02 -1.667662E+00 1.663556E+00 + 2.100000E+00 3.000000E+01 4 4.972169E+00 2.617470E+01 4.462290E+00 2.193272E+00 + 2.100000E+00 3.000000E+01 5 8.047062E+00 -1.089703E+02 -2.615923E+00 -7.610003E+00 + 2.100000E+00 3.000000E+01 6 1.375585E+02 1.384727E+02 -1.029817E+02 9.119812E+01 + 2.100000E+00 6.000000E+01 1 9.750317E+00 -1.259258E+02 -5.720868E+00 -7.895591E+00 + 2.100000E+00 6.000000E+01 2 3.188938E+00 4.149963E+01 2.388387E+00 2.113039E+00 + 2.100000E+00 6.000000E+01 3 2.481020E+00 -4.064047E+01 1.882626E+00 -1.615914E+00 + 2.100000E+00 6.000000E+01 4 1.363382E+01 6.727907E+01 5.265969E+00 1.257579E+01 + 2.100000E+00 6.000000E+01 5 1.113503E+01 5.728171E+01 6.018582E+00 9.368325E+00 + 2.100000E+00 6.000000E+01 6 1.587328E+02 1.919057E+01 1.499120E+02 5.217724E+01 + 2.100000E+00 9.000000E+01 1 7.526227E-06 -6.560124E+01 3.108969E-06 -6.854080E-06 + 2.100000E+00 9.000000E+01 2 2.984016E+01 1.745603E+02 -2.970577E+01 2.828802E+00 + 2.100000E+00 9.000000E+01 3 2.147939E+00 -1.599565E+02 -2.017844E+00 -7.361711E-01 + 2.100000E+00 9.000000E+01 4 2.823634E+01 1.683424E+02 -2.765389E+01 5.705529E+00 + 2.100000E+00 9.000000E+01 5 8.384823E-06 1.164150E+02 -3.730158E-06 7.509405E-06 + 2.100000E+00 9.000000E+01 6 6.949179E-04 -1.031911E+02 -1.585795E-04 -6.765822E-04 + 2.200000E+00 0.000000E+00 1 1.840914E+01 1.246068E+02 -1.045532E+01 1.515199E+01 + 2.200000E+00 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.200000E+00 0.000000E+00 3 3.016562E+00 7.359667E+01 8.518687E-01 2.893780E+00 + 2.200000E+00 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.200000E+00 0.000000E+00 5 2.189817E+01 -5.459550E+01 1.268660E+01 -1.784881E+01 + 2.200000E+00 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.200000E+00 3.000000E+01 1 1.003793E+01 1.687380E+02 -9.844638E+00 1.960372E+00 + 2.200000E+00 3.000000E+01 2 7.348200E+00 -1.333114E+02 -5.040593E+00 -5.346819E+00 + 2.200000E+00 3.000000E+01 3 3.990573E+00 1.612579E+02 -3.778970E+00 1.282207E+00 + 2.200000E+00 3.000000E+01 4 2.769185E+00 1.150331E+02 -1.171758E+00 2.509058E+00 + 2.200000E+00 3.000000E+01 5 1.299058E+01 -2.709982E+01 1.156440E+01 -5.917757E+00 + 2.200000E+00 3.000000E+01 6 4.706312E+02 6.546182E+01 1.954529E+02 4.281260E+02 + 2.200000E+00 6.000000E+01 1 9.554170E+00 -5.325864E+01 5.715340E+00 -7.656177E+00 + 2.200000E+00 6.000000E+01 2 5.871254E+00 -1.696238E+02 -5.775238E+00 -1.057474E+00 + 2.200000E+00 6.000000E+01 3 4.580588E+00 -6.968203E+00 4.546754E+00 -5.557101E-01 + 2.200000E+00 6.000000E+01 4 9.044420E+00 9.761833E+01 -1.199051E+00 8.964586E+00 + 2.200000E+00 6.000000E+01 5 1.148960E+01 1.325676E+02 -7.772250E+00 8.461858E+00 + 2.200000E+00 6.000000E+01 6 4.873628E+02 -1.109005E+02 -1.738651E+02 -4.552949E+02 + 2.200000E+00 9.000000E+01 1 6.787387E-06 2.305665E+01 6.245197E-06 2.658220E-06 + 2.200000E+00 9.000000E+01 2 1.074581E+01 1.732706E+02 -1.067178E+01 1.259205E+00 + 2.200000E+00 9.000000E+01 3 4.149904E+00 -1.095534E+02 -1.388911E+00 -3.910579E+00 + 2.200000E+00 9.000000E+01 4 6.907977E+00 1.615725E+02 -6.553764E+00 2.183648E+00 + 2.200000E+00 9.000000E+01 5 8.732525E-06 -1.405445E+02 -6.742548E-06 -5.549329E-06 + 2.200000E+00 9.000000E+01 6 7.234850E-04 -1.137432E+02 -2.913027E-04 -6.622486E-04 + 2.300000E+00 0.000000E+00 1 6.652022E+00 1.714180E+02 -6.577542E+00 9.926440E-01 + 2.300000E+00 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.300000E+00 0.000000E+00 3 3.341569E+00 9.958330E+01 -5.563088E-01 3.294936E+00 + 2.300000E+00 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.300000E+00 0.000000E+00 5 8.600190E+00 -1.346889E+01 8.363655E+00 -2.003134E+00 + 2.300000E+00 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.300000E+00 3.000000E+01 1 2.813330E+01 1.017791E+02 -5.743085E+00 2.754087E+01 + 2.300000E+00 3.000000E+01 2 1.331318E+01 1.719806E+02 -1.318299E+01 1.857306E+00 + 2.300000E+00 3.000000E+01 3 5.697778E+00 1.764393E+02 -5.686778E+00 3.538708E-01 + 2.300000E+00 3.000000E+01 4 1.458461E+01 1.343526E+02 -1.019570E+01 1.042874E+01 + 2.300000E+00 3.000000E+01 5 4.251502E+01 -7.939967E+01 7.820933E+00 -4.178947E+01 + 2.300000E+00 3.000000E+01 6 2.409720E+02 1.194129E+01 2.357574E+02 4.985936E+01 + 2.300000E+00 6.000000E+01 1 8.122261E+00 -2.673362E+00 8.113421E+00 -3.788389E-01 + 2.300000E+00 6.000000E+01 2 1.754300E+01 -7.681292E+01 4.002109E+00 -1.708040E+01 + 2.300000E+00 6.000000E+01 3 3.457100E+00 6.086721E+01 1.683038E+00 3.019755E+00 + 2.300000E+00 6.000000E+01 4 1.385956E+01 -4.006794E+01 1.060647E+01 -8.921338E+00 + 2.300000E+00 6.000000E+01 5 1.238480E+01 -1.746265E+02 -1.233038E+01 -1.159803E+00 + 2.300000E+00 6.000000E+01 6 8.567575E+02 -1.341973E+02 -5.972726E+02 -6.142466E+02 + 2.300000E+00 9.000000E+01 1 8.110849E-06 5.452580E+01 4.707020E-06 6.605288E-06 + 2.300000E+00 9.000000E+01 2 1.484728E+01 -1.770321E+02 -1.482736E+01 -7.687485E-01 + 2.300000E+00 9.000000E+01 3 3.613738E+00 -4.756544E+01 2.438361E+00 -2.667114E+00 + 2.300000E+00 9.000000E+01 4 1.042713E+01 -1.320228E+02 -6.980190E+00 -7.746091E+00 + 2.300000E+00 9.000000E+01 5 1.129052E-05 -1.152556E+02 -4.817187E-06 -1.021129E-05 + 2.300000E+00 9.000000E+01 6 6.935667E-04 -1.311100E+02 -4.560248E-04 -5.225670E-04 + 2.400000E+00 0.000000E+00 1 6.691988E+01 1.437616E+02 -5.397520E+01 3.955941E+01 + 2.400000E+00 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.400000E+00 0.000000E+00 3 2.040703E+00 1.177941E+02 -9.515707E-01 1.805265E+00 + 2.400000E+00 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.400000E+00 0.000000E+00 5 9.895098E+01 -3.651546E+01 7.952654E+01 -5.887976E+01 + 2.400000E+00 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.400000E+00 3.000000E+01 1 2.056048E+01 -7.887166E+01 3.968325E+00 -2.017389E+01 + 2.400000E+00 3.000000E+01 2 1.794580E+01 -6.599496E+01 7.300655E+00 -1.639366E+01 + 2.400000E+00 3.000000E+01 3 4.279415E+00 -1.772949E+02 -4.274646E+00 -2.019664E-01 + 2.400000E+00 3.000000E+01 4 2.314850E+01 -5.315101E+01 1.388234E+01 -1.852386E+01 + 2.400000E+00 3.000000E+01 5 2.366356E+01 1.133196E+02 -9.367453E+00 2.173051E+01 + 2.400000E+00 3.000000E+01 6 2.629239E+01 1.162468E+02 -1.162751E+01 2.358158E+01 + 2.400000E+00 6.000000E+01 1 1.101585E+01 -7.089606E+01 3.605299E+00 -1.040917E+01 + 2.400000E+00 6.000000E+01 2 2.194420E+01 -7.073899E+01 7.238779E+00 -2.071589E+01 + 2.400000E+00 6.000000E+01 3 2.151742E+00 1.444439E+02 -1.750542E+00 1.251238E+00 + 2.400000E+00 6.000000E+01 4 2.502406E+01 -4.151780E+01 1.873676E+01 -1.658726E+01 + 2.400000E+00 6.000000E+01 5 1.221794E+01 1.362352E+02 -8.823617E+00 8.451142E+00 + 2.400000E+00 6.000000E+01 6 5.474531E+02 -1.368706E+02 -3.995377E+02 -3.742652E+02 + 2.400000E+00 9.000000E+01 1 1.443677E-05 1.781123E+02 -1.442893E-05 4.755645E-07 + 2.400000E+00 9.000000E+01 2 2.785631E+01 -1.771170E+02 -2.782105E+01 -1.401092E+00 + 2.400000E+00 9.000000E+01 3 1.413268E+00 2.660327E+01 1.263643E+00 6.328756E-01 + 2.400000E+00 9.000000E+01 4 1.771157E+01 -1.481608E+02 -1.504654E+01 -9.343523E+00 + 2.400000E+00 9.000000E+01 5 2.027583E-05 -8.507624E+00 2.005272E-05 -2.999627E-06 + 2.400000E+00 9.000000E+01 6 9.715804E-04 -1.369534E+02 -7.100300E-04 -6.631936E-04 + 2.500000E+00 0.000000E+00 1 5.129078E+01 1.138478E+02 -2.073730E+01 4.691171E+01 + 2.500000E+00 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.500000E+00 0.000000E+00 3 1.529491E+00 1.225288E+02 -8.224432E-01 1.289546E+00 + 2.500000E+00 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.500000E+00 0.000000E+00 5 8.451809E+01 -6.702504E+01 3.298985E+01 -7.781374E+01 + 2.500000E+00 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.500000E+00 3.000000E+01 1 4.145443E+01 -4.538499E+01 2.911509E+01 -2.950900E+01 + 2.500000E+00 3.000000E+01 2 3.950846E+01 -6.894279E+01 1.419539E+01 -3.687017E+01 + 2.500000E+00 3.000000E+01 3 3.751704E+00 1.699554E+02 -3.694198E+00 6.543530E-01 + 2.500000E+00 3.000000E+01 4 6.341410E+01 -6.394818E+01 2.785045E+01 -5.697105E+01 + 2.500000E+00 3.000000E+01 5 6.103278E+01 1.379704E+02 -4.533508E+01 4.086234E+01 + 2.500000E+00 3.000000E+01 6 2.903393E+02 5.470456E+01 1.677559E+02 2.369702E+02 + 2.500000E+00 6.000000E+01 1 4.370257E+00 1.419348E+02 -3.440747E+00 2.694514E+00 + 2.500000E+00 6.000000E+01 2 1.341662E+01 -6.668523E+01 5.310061E+00 -1.232108E+01 + 2.500000E+00 6.000000E+01 3 1.843527E+00 1.454165E+02 -1.517775E+00 1.046398E+00 + 2.500000E+00 6.000000E+01 4 2.508925E+01 1.343679E+01 2.440248E+01 5.830053E+00 + 2.500000E+00 6.000000E+01 5 1.784713E+01 -8.089987E+01 2.822708E+00 -1.762249E+01 + 2.500000E+00 6.000000E+01 6 2.772294E+02 3.482975E+01 2.275645E+02 1.583367E+02 + 2.500000E+00 9.000000E+01 1 4.373749E-06 -8.041764E+01 7.280764E-07 -4.312723E-06 + 2.500000E+00 9.000000E+01 2 3.571795E+01 1.595034E+02 -3.345677E+01 1.250667E+01 + 2.500000E+00 9.000000E+01 3 1.586350E+00 9.202799E+01 -5.613745E-02 1.585356E+00 + 2.500000E+00 9.000000E+01 4 3.055895E+01 1.481671E+02 -2.596258E+01 1.611813E+01 + 2.500000E+00 9.000000E+01 5 2.473950E-06 1.016150E+02 -4.980903E-07 2.423290E-06 + 2.500000E+00 9.000000E+01 6 8.151199E-04 -1.394990E+02 -6.198129E-04 -5.293887E-04 + 2.600000E+00 0.000000E+00 1 2.374993E+01 8.941797E+01 2.412556E-01 2.374870E+01 + 2.600000E+00 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.600000E+00 0.000000E+00 3 1.379885E+00 1.207559E+02 -7.056479E-01 1.185809E+00 + 2.600000E+00 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.600000E+00 0.000000E+00 5 3.882188E+01 -9.195899E+01 -1.327094E+00 -3.879919E+01 + 2.600000E+00 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.600000E+00 3.000000E+01 1 2.512787E+01 -7.338380E+01 7.185550E+00 -2.407857E+01 + 2.600000E+00 3.000000E+01 2 3.913450E+01 -7.277780E+01 1.158687E+01 -3.737986E+01 + 2.600000E+00 3.000000E+01 3 4.915434E+00 1.651986E+02 -4.752327E+00 1.255740E+00 + 2.600000E+00 3.000000E+01 4 7.238557E+01 -6.670432E+01 2.862678E+01 -6.648442E+01 + 2.600000E+00 3.000000E+01 5 3.821024E+01 9.774843E+01 -5.151649E+00 3.786136E+01 + 2.600000E+00 3.000000E+01 6 7.005328E+02 1.571709E+01 6.743406E+02 1.897657E+02 + 2.600000E+00 6.000000E+01 1 1.314660E+01 1.011741E+02 -2.547699E+00 1.289738E+01 + 2.600000E+00 6.000000E+01 2 1.136843E+01 9.581977E+01 -1.152753E+00 1.130984E+01 + 2.600000E+00 6.000000E+01 3 2.856414E+00 1.617910E+02 -2.713374E+00 8.925833E-01 + 2.600000E+00 6.000000E+01 4 6.483476E+01 8.739442E+01 2.947407E+00 6.476773E+01 + 2.600000E+00 6.000000E+01 5 4.451958E+01 -7.846105E+01 8.905430E+00 -4.361979E+01 + 2.600000E+00 6.000000E+01 6 9.317444E+02 2.763584E+01 8.254451E+02 4.321898E+02 + 2.600000E+00 9.000000E+01 1 4.715702E-06 -1.099771E+02 -1.611092E-06 -4.431955E-06 + 2.600000E+00 9.000000E+01 2 4.229353E+01 1.186479E+02 -2.027663E+01 3.711604E+01 + 2.600000E+00 9.000000E+01 3 1.893995E+00 1.071196E+02 -5.575296E-01 1.810077E+00 + 2.600000E+00 9.000000E+01 4 5.444688E+01 9.005308E+01 -5.043561E-02 5.444685E+01 + 2.600000E+00 9.000000E+01 5 4.799822E-06 -1.704821E+00 4.797698E-06 -1.427964E-07 + 2.600000E+00 9.000000E+01 6 8.340525E-04 -1.562957E+02 -7.636857E-04 -3.353025E-04 + 2.700000E+00 0.000000E+00 1 1.285704E+01 1.376649E+02 -9.504169E+00 8.658763E+00 + 2.700000E+00 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.700000E+00 0.000000E+00 3 1.071230E+00 1.054962E+02 -2.862057E-01 1.032289E+00 + 2.700000E+00 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.700000E+00 0.000000E+00 5 2.219130E+01 -2.058312E+01 2.077468E+01 -7.801703E+00 + 2.700000E+00 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.700000E+00 3.000000E+01 1 1.246238E+01 -1.406525E+02 -9.637338E+00 -7.901432E+00 + 2.700000E+00 3.000000E+01 2 1.873427E+01 -5.288271E+01 1.130517E+01 -1.493874E+01 + 2.700000E+00 3.000000E+01 3 5.321106E+00 1.741083E+02 -5.292998E+00 5.462034E-01 + 2.700000E+00 3.000000E+01 4 4.667109E+01 -3.742222E+01 3.706520E+01 -2.836127E+01 + 2.700000E+00 3.000000E+01 5 2.527288E+01 2.607484E+01 2.270062E+01 1.110856E+01 + 2.700000E+00 3.000000E+01 6 7.275867E+02 4.028961E+00 7.257886E+02 5.112075E+01 + 2.700000E+00 6.000000E+01 1 3.480887E+01 1.156737E+02 -1.508077E+01 3.137241E+01 + 2.700000E+00 6.000000E+01 2 3.563494E+01 1.025745E+02 -7.758019E+00 3.478020E+01 + 2.700000E+00 6.000000E+01 3 3.903898E+00 1.766144E+02 -3.897084E+00 2.305482E-01 + 2.700000E+00 6.000000E+01 4 1.007721E+02 1.107006E+02 -3.562133E+01 9.426632E+01 + 2.700000E+00 6.000000E+01 5 7.932731E+01 -6.428683E+01 3.441743E+01 -7.147211E+01 + 2.700000E+00 6.000000E+01 6 1.200961E+03 1.413786E+01 1.164585E+03 2.933418E+02 + 2.700000E+00 9.000000E+01 1 1.373922E-05 -5.906470E+01 7.062917E-06 -1.178479E-05 + 2.700000E+00 9.000000E+01 2 8.003942E+01 8.975844E+01 3.374447E-01 8.003871E+01 + 2.700000E+00 9.000000E+01 3 1.309628E+00 1.092766E+02 -4.323460E-01 1.236205E+00 + 2.700000E+00 9.000000E+01 4 1.853950E+02 7.520155E+01 4.735352E+01 1.792455E+02 + 2.700000E+00 9.000000E+01 5 1.659808E-05 1.194172E+02 -8.152405E-06 1.445803E-05 + 2.700000E+00 9.000000E+01 6 8.618580E-04 -1.684376E+02 -8.443682E-04 -1.727471E-04 + 2.799999E+00 0.000000E+00 1 3.084495E+01 1.363763E+02 -2.232826E+01 2.128050E+01 + 2.799999E+00 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.799999E+00 0.000000E+00 3 1.018026E+00 4.981052E+01 6.569498E-01 7.776847E-01 + 2.799999E+00 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.799999E+00 0.000000E+00 5 6.890652E+01 -3.809226E+01 5.423070E+01 -4.251048E+01 + 2.799999E+00 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.799999E+00 3.000000E+01 1 7.436464E+00 6.883179E+01 2.685361E+00 6.934684E+00 + 2.799999E+00 3.000000E+01 2 4.692299E+00 1.573202E+01 4.516528E+00 1.272262E+00 + 2.799999E+00 3.000000E+01 3 5.127012E+00 1.705119E+02 -5.056873E+00 8.451540E-01 + 2.799999E+00 3.000000E+01 4 1.385750E+01 2.200511E+01 1.284799E+01 5.192256E+00 + 2.799999E+00 3.000000E+01 5 2.142159E+01 -1.054122E+02 -5.693040E+00 -2.065124E+01 + 2.799999E+00 3.000000E+01 6 1.663048E+02 3.039669E+01 1.434450E+02 8.414754E+01 + 2.799999E+00 6.000000E+01 1 4.148475E+01 1.089419E+02 -1.346630E+01 3.923829E+01 + 2.799999E+00 6.000000E+01 2 4.794329E+01 9.155702E+01 -1.302705E+00 4.792559E+01 + 2.799999E+00 6.000000E+01 3 4.497569E+00 1.653757E+02 -4.351856E+00 1.135548E+00 + 2.799999E+00 6.000000E+01 4 1.051302E+02 9.357171E+01 -6.549361E+00 1.049260E+02 + 2.799999E+00 6.000000E+01 5 9.666524E+01 -7.074407E+01 3.187907E+01 -9.125729E+01 + 2.799999E+00 6.000000E+01 6 1.340882E+03 3.476051E+00 1.338415E+03 8.129942E+01 + 2.799999E+00 9.000000E+01 1 1.634091E-05 -2.739770E+01 1.450801E-05 -7.519499E-06 + 2.799999E+00 9.000000E+01 2 1.083563E+02 9.151974E+01 -2.873775E+00 1.083182E+02 + 2.799999E+00 9.000000E+01 3 3.234695E+00 7.527977E+01 8.219343E-01 3.128526E+00 + 2.799999E+00 9.000000E+01 4 2.391108E+02 9.031908E+01 -1.331573E+00 2.391071E+02 + 2.799999E+00 9.000000E+01 5 2.194817E-05 1.451231E+02 -1.800589E-05 1.255030E-05 + 2.799999E+00 9.000000E+01 6 1.012854E-03 -1.762982E+02 -1.010741E-03 -6.539427E-05 + 2.899999E+00 0.000000E+00 1 5.913933E+01 7.511961E+01 1.518710E+01 5.715604E+01 + 2.899999E+00 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.899999E+00 0.000000E+00 3 1.474937E+00 3.119394E+01 1.261689E+00 7.639238E-01 + 2.899999E+00 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.899999E+00 0.000000E+00 5 1.361311E+02 -9.472819E+01 -1.122113E+01 -1.356678E+02 + 2.899999E+00 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.899999E+00 3.000000E+01 1 1.404502E+01 7.505493E+01 3.622111E+00 1.356993E+01 + 2.899999E+00 3.000000E+01 2 1.182106E+01 -9.669734E+01 -1.378627E+00 -1.174040E+01 + 2.899999E+00 3.000000E+01 3 6.231650E+00 1.707256E+02 -6.150188E+00 1.004316E+00 + 2.899999E+00 3.000000E+01 4 2.915959E+01 -1.004853E+02 -5.306571E+00 -2.867267E+01 + 2.899999E+00 3.000000E+01 5 3.683768E+01 -1.315670E+02 -2.444164E+01 -2.756121E+01 + 2.899999E+00 3.000000E+01 6 8.204958E+02 1.632954E+02 -7.858704E+02 2.358412E+02 + 2.899999E+00 6.000000E+01 1 5.087309E+01 1.082702E+02 -1.594861E+01 4.830852E+01 + 2.899999E+00 6.000000E+01 2 5.881094E+01 8.293089E+01 7.237651E+00 5.836389E+01 + 2.899999E+00 6.000000E+01 3 6.112622E+00 1.666014E+02 -5.946246E+00 1.416439E+00 + 2.899999E+00 6.000000E+01 4 1.303272E+02 8.085902E+01 2.070435E+01 1.286721E+02 + 2.899999E+00 6.000000E+01 5 1.126831E+02 -7.312285E+01 3.271422E+01 -1.078298E+02 + 2.899999E+00 6.000000E+01 6 1.045594E+03 7.533033E+00 1.036570E+03 1.370750E+02 + 2.899999E+00 9.000000E+01 1 2.153102E-05 2.575455E+01 1.939221E-05 9.355592E-06 + 2.899999E+00 9.000000E+01 2 1.126526E+02 8.799042E+01 3.950352E+00 1.125833E+02 + 2.899999E+00 9.000000E+01 3 4.730039E+00 9.452670E+01 -3.733119E-01 4.715284E+00 + 2.899999E+00 9.000000E+01 4 2.431560E+02 8.754437E+01 1.041817E+01 2.429327E+02 + 2.899999E+00 9.000000E+01 5 3.590472E-05 -1.538434E+02 -3.222781E-05 -1.582773E-05 + 2.899999E+00 9.000000E+01 6 1.082301E-03 -1.765180E+02 -1.080303E-03 -6.573328E-05 + 2.999999E+00 0.000000E+00 1 1.535824E+02 7.256065E+01 4.602804E+01 1.465229E+02 + 2.999999E+00 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.999999E+00 0.000000E+00 3 1.969451E+00 5.637770E+01 1.090516E+00 1.639974E+00 + 2.999999E+00 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.999999E+00 0.000000E+00 5 3.425206E+02 -1.060463E+02 -9.467750E+01 -3.291755E+02 + 2.999999E+00 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.999999E+00 3.000000E+01 1 5.881850E+01 -1.358674E+02 -4.221578E+01 -4.095662E+01 + 2.999999E+00 3.000000E+01 2 3.964449E+01 -9.267473E+01 -1.850040E+00 -3.960130E+01 + 2.999999E+00 3.000000E+01 3 6.848557E+00 1.763287E+02 -6.834503E+00 4.385305E-01 + 2.999999E+00 3.000000E+01 4 9.575523E+01 -9.607970E+01 -1.014161E+01 -9.521666E+01 + 2.999999E+00 3.000000E+01 5 1.050537E+02 5.814314E+01 5.544724E+01 8.922939E+01 + 2.999999E+00 3.000000E+01 6 1.311709E+03 1.717300E+02 -1.298069E+03 1.886731E+02 + 2.999999E+00 6.000000E+01 1 4.004496E+01 1.390207E+02 -3.023180E+01 2.626094E+01 + 2.999999E+00 6.000000E+01 2 5.293253E+01 8.055581E+01 8.685534E+00 5.221508E+01 + 2.999999E+00 6.000000E+01 3 7.548622E+00 1.712188E+02 -7.460140E+00 1.152391E+00 + 2.999999E+00 6.000000E+01 4 1.187431E+02 7.564075E+01 2.944842E+01 1.150335E+02 + 2.999999E+00 6.000000E+01 5 8.239848E+01 -4.672632E+01 5.648284E+01 -5.999332E+01 + 2.999999E+00 6.000000E+01 6 2.921517E+02 2.838828E+01 2.570193E+02 1.389019E+02 + 2.999999E+00 9.000000E+01 1 2.870632E-05 1.225683E+02 -1.545275E-05 2.419226E-05 + 2.999999E+00 9.000000E+01 2 1.085063E+02 8.412341E+01 1.110955E+01 1.079361E+02 + 2.999999E+00 9.000000E+01 3 6.175937E+00 1.148498E+02 -2.595377E+00 5.604125E+00 + 2.999999E+00 9.000000E+01 4 2.412059E+02 8.263962E+01 3.090086E+01 2.392184E+02 + 2.999999E+00 9.000000E+01 5 7.033809E-05 -5.379518E+01 4.154685E-05 -5.675655E-05 + 2.999999E+00 9.000000E+01 6 1.061258E-03 -1.797259E+02 -1.061246E-03 -5.077388E-06 + 3.099999E+00 0.000000E+00 1 1.352772E+02 7.965231E+01 2.429864E+01 1.330770E+02 + 3.099999E+00 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.099999E+00 0.000000E+00 3 4.043180E+00 9.310086E+01 -2.187111E-01 4.037260E+00 + 3.099999E+00 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.099999E+00 0.000000E+00 5 3.204205E+02 -1.041802E+02 -7.849390E+01 -3.106574E+02 + 3.099999E+00 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.099999E+00 3.000000E+01 1 1.023205E+02 -1.063303E+02 -2.876989E+01 -9.819260E+01 + 3.099999E+00 3.000000E+01 2 5.650270E+01 -9.243196E+01 -2.397580E+00 -5.645181E+01 + 3.099999E+00 3.000000E+01 3 5.845279E+00 -1.780309E+02 -5.841827E+00 -2.008460E-01 + 3.099999E+00 3.000000E+01 4 1.438770E+02 -9.665790E+01 -1.668124E+01 -1.429067E+02 + 3.099999E+00 3.000000E+01 5 2.320557E+02 8.034755E+01 3.890910E+01 2.287705E+02 + 3.099999E+00 3.000000E+01 6 1.158180E+03 1.715860E+02 -1.145714E+03 1.694695E+02 + 3.099999E+00 6.000000E+01 1 1.398031E+01 1.693249E+02 -1.373836E+01 2.589702E+00 + 3.099999E+00 6.000000E+01 2 3.398200E+01 6.586255E+01 1.389616E+01 3.101085E+01 + 3.099999E+00 6.000000E+01 3 7.300803E+00 -1.706796E+02 -7.204419E+00 -1.182402E+00 + 3.099999E+00 6.000000E+01 4 7.537634E+01 5.599914E+01 4.215086E+01 6.248919E+01 + 3.099999E+00 6.000000E+01 5 2.412563E+01 2.367664E+01 2.209489E+01 9.688235E+00 + 3.099999E+00 6.000000E+01 6 5.216992E+02 1.745547E+02 -5.193450E+02 4.950640E+01 + 3.099999E+00 9.000000E+01 1 2.174027E-05 -1.530094E+02 -1.937235E-05 -9.866681E-06 + 3.099999E+00 9.000000E+01 2 9.793117E+01 7.983202E+01 1.728826E+01 9.639310E+01 + 3.099999E+00 9.000000E+01 3 6.437273E+00 1.435798E+02 -5.179974E+00 3.821827E+00 + 3.099999E+00 9.000000E+01 4 2.273067E+02 7.777940E+01 4.811544E+01 2.221559E+02 + 3.099999E+00 9.000000E+01 5 6.417438E-05 1.557107E+01 6.181907E-05 1.722655E-05 + 3.099999E+00 9.000000E+01 6 1.061670E-03 1.746794E+02 -1.057096E-03 9.844666E-05 + 3.199999E+00 0.000000E+00 1 9.313126E+01 7.703487E+01 2.089476E+01 9.075704E+01 + 3.199999E+00 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.199999E+00 0.000000E+00 3 6.376946E+00 1.272288E+02 -3.858049E+00 5.077490E+00 + 3.199999E+00 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.199999E+00 0.000000E+00 5 2.207682E+02 -1.136822E+02 -8.867440E+01 -2.021768E+02 + 3.199999E+00 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.199999E+00 3.000000E+01 1 1.148556E+02 -1.046191E+02 -2.898855E+01 -1.111372E+02 + 3.199999E+00 3.000000E+01 2 6.264732E+01 -1.008677E+02 -1.181164E+01 -6.152375E+01 + 3.199999E+00 3.000000E+01 3 4.421484E+00 -1.709751E+02 -4.366747E+00 -6.935720E-01 + 3.199999E+00 3.000000E+01 4 1.708979E+02 -1.044649E+02 -4.268807E+01 -1.654806E+02 + 3.199999E+00 3.000000E+01 5 2.763033E+02 7.809556E+01 5.699586E+01 2.703609E+02 + 3.199999E+00 3.000000E+01 6 7.071581E+02 1.658765E+02 -6.857822E+02 1.725552E+02 + 3.199999E+00 6.000000E+01 1 1.593430E+01 -1.136228E+02 -6.385092E+00 -1.459906E+01 + 3.199999E+00 6.000000E+01 2 1.738074E+01 2.798335E+01 1.534865E+01 8.155304E+00 + 3.199999E+00 6.000000E+01 3 4.390622E+00 1.773398E+02 -4.385890E+00 2.037780E-01 + 3.199999E+00 6.000000E+01 4 4.314693E+01 -5.031633E+00 4.298066E+01 -3.784233E+00 + 3.199999E+00 6.000000E+01 5 8.151366E+01 8.811880E+01 2.675864E+00 8.146973E+01 + 3.199999E+00 6.000000E+01 6 1.115759E+03 1.776656E+02 -1.114833E+03 4.544571E+01 + 3.199999E+00 9.000000E+01 1 1.641946E-05 -1.242221E+02 -9.234337E-06 -1.357666E-05 + 3.199999E+00 9.000000E+01 2 8.466059E+01 7.749667E+01 1.832870E+01 8.265273E+01 + 3.199999E+00 9.000000E+01 3 5.032353E+00 1.462475E+02 -4.184126E+00 2.796008E+00 + 3.199999E+00 9.000000E+01 4 2.031117E+02 7.519678E+01 5.189503E+01 1.963702E+02 + 3.199999E+00 9.000000E+01 5 4.495156E-05 3.121729E+01 3.844293E-05 2.329773E-05 + 3.199999E+00 9.000000E+01 6 1.099406E-03 1.695473E+02 -1.081162E-03 1.994592E-04 + 3.299999E+00 0.000000E+00 1 4.678250E+01 8.237811E+01 6.204999E+00 4.636917E+01 + 3.299999E+00 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.299999E+00 0.000000E+00 3 7.054717E+00 1.426483E+02 -5.607983E+00 4.280135E+00 + 3.299999E+00 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.299999E+00 0.000000E+00 5 1.004503E+02 -1.286896E+02 -6.279161E+01 -7.840590E+01 + 3.299999E+00 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.299999E+00 3.000000E+01 1 1.055210E+02 -1.072739E+02 -3.133335E+01 -1.007616E+02 + 3.299999E+00 3.000000E+01 2 6.150303E+01 -1.091924E+02 -2.021861E+01 -5.808468E+01 + 3.299999E+00 3.000000E+01 3 2.173652E+00 -1.587816E+02 -2.026295E+00 -7.866974E-01 + 3.299999E+00 3.000000E+01 4 1.770257E+02 -1.119721E+02 -6.623500E+01 -1.641676E+02 + 3.299999E+00 3.000000E+01 5 2.544291E+02 7.011642E+01 8.653385E+01 2.392614E+02 + 3.299999E+00 3.000000E+01 6 2.318566E+02 1.571164E+02 -2.136087E+02 9.015990E+01 + 3.299999E+00 6.000000E+01 1 3.435871E+01 -9.594345E+01 -3.557737E+00 -3.417402E+01 + 3.299999E+00 6.000000E+01 2 2.065511E+01 -6.633234E+01 8.291598E+00 -1.891780E+01 + 3.299999E+00 6.000000E+01 3 3.711243E+00 1.619598E+02 -3.528796E+00 1.149315E+00 + 3.299999E+00 6.000000E+01 4 9.041335E+01 -7.612052E+01 2.168839E+01 -8.777351E+01 + 3.299999E+00 6.000000E+01 5 1.689747E+02 9.353695E+01 -1.042441E+01 1.686529E+02 + 3.299999E+00 6.000000E+01 6 1.552885E+03 1.734821E+02 -1.542848E+03 1.762744E+02 + 3.299999E+00 9.000000E+01 1 1.429221E-05 -1.106028E+02 -5.029259E-06 -1.337811E-05 + 3.299999E+00 9.000000E+01 2 6.621753E+01 7.656819E+01 1.538153E+01 6.440629E+01 + 3.299999E+00 9.000000E+01 3 5.661932E+00 1.466332E+02 -4.728658E+00 3.114044E+00 + 3.299999E+00 9.000000E+01 4 1.632255E+02 7.372087E+01 4.575491E+01 1.566814E+02 + 3.299999E+00 9.000000E+01 5 3.369616E-05 3.174554E+01 2.865498E-05 1.772915E-05 + 3.299999E+00 9.000000E+01 6 1.156401E-03 1.667464E+02 -1.125600E-03 2.651193E-04 + 3.399999E+00 0.000000E+00 1 1.361654E+01 1.252903E+02 -7.866537E+00 1.111431E+01 + 3.399999E+00 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.399999E+00 0.000000E+00 3 6.630826E+00 1.534148E+02 -5.929750E+00 2.967477E+00 + 3.399999E+00 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.399999E+00 0.000000E+00 5 3.057225E+01 1.626662E+02 -2.918381E+01 9.108666E+00 + 3.399999E+00 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.399999E+00 3.000000E+01 1 7.400742E+01 -1.119290E+02 -2.763857E+01 -6.865280E+01 + 3.399999E+00 3.000000E+01 2 5.104679E+01 -1.168010E+02 -2.301664E+01 -4.556325E+01 + 3.399999E+00 3.000000E+01 3 1.701708E-01 1.513890E+02 -1.493914E-01 8.148818E-02 + 3.399999E+00 3.000000E+01 4 1.543932E+02 -1.191935E+02 -7.530685E+01 -1.347819E+02 + 3.399999E+00 3.000000E+01 5 1.754636E+02 5.171851E+01 1.087042E+02 1.377348E+02 + 3.399999E+00 3.000000E+01 6 1.745534E+02 -3.068357E+01 1.501157E+02 -8.907393E+01 + 3.399999E+00 6.000000E+01 1 5.649395E+01 -9.294634E+01 -2.903829E+00 -5.641927E+01 + 3.399999E+00 6.000000E+01 2 4.890638E+01 -9.335667E+01 -2.863540E+00 -4.882248E+01 + 3.399999E+00 6.000000E+01 3 1.974456E+00 1.499715E+02 -1.709438E+00 9.880779E-01 + 3.399999E+00 6.000000E+01 4 1.835228E+02 -9.412207E+01 -1.319192E+01 -1.830480E+02 + 3.399999E+00 6.000000E+01 5 2.654980E+02 9.541576E+01 -2.505829E+01 2.643128E+02 + 3.399999E+00 6.000000E+01 6 1.884565E+03 1.682920E+02 -1.845355E+03 3.824237E+02 + 3.399999E+00 9.000000E+01 1 1.524115E-05 -9.668856E+01 -1.775174E-06 -1.513742E-05 + 3.399999E+00 9.000000E+01 2 4.834594E+01 7.256494E+01 1.448564E+01 4.612479E+01 + 3.399999E+00 9.000000E+01 3 6.366030E+00 1.568401E+02 -5.852995E+00 2.503754E+00 + 3.399999E+00 9.000000E+01 4 1.239776E+02 6.965963E+01 4.309418E+01 1.162469E+02 + 3.399999E+00 9.000000E+01 5 2.766623E-05 2.271446E+01 2.552046E-05 1.068301E-05 + 3.399999E+00 9.000000E+01 6 1.139374E-03 1.668813E+02 -1.109638E-03 2.586038E-04 + 3.499999E+00 0.000000E+00 1 8.050917E+00 1.672397E+02 -7.852081E+00 1.778225E+00 + 3.499999E+00 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.499999E+00 0.000000E+00 3 5.365941E+00 1.646354E+02 -5.174159E+00 1.421762E+00 + 3.499999E+00 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.499999E+00 0.000000E+00 5 2.002238E+01 1.748561E+02 -1.994174E+01 1.795141E+00 + 3.499999E+00 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.499999E+00 3.000000E+01 1 3.266153E+01 -1.400336E+02 -2.503250E+01 -2.097973E+01 + 3.499999E+00 3.000000E+01 2 3.473077E+01 -1.264799E+02 -2.064885E+01 -2.792581E+01 + 3.499999E+00 3.000000E+01 3 1.774829E+00 8.915792E+01 2.608388E-02 1.774637E+00 + 3.499999E+00 3.000000E+01 4 1.095299E+02 -1.286510E+02 -6.840970E+01 -8.553900E+01 + 3.499999E+00 3.000000E+01 5 1.383809E+02 -1.414545E+00 1.383387E+02 -3.416065E+00 + 3.499999E+00 3.000000E+01 6 4.447607E+02 -3.494680E+01 3.645633E+02 -2.547658E+02 + 3.499999E+00 6.000000E+01 1 7.875937E+01 -8.723781E+01 3.795474E+00 -7.866786E+01 + 3.499999E+00 6.000000E+01 2 7.877679E+01 -1.023097E+02 -1.679493E+01 -7.696567E+01 + 3.499999E+00 6.000000E+01 3 2.027775E+00 3.002265E+01 1.755703E+00 1.014581E+00 + 3.499999E+00 6.000000E+01 4 2.833362E+02 -1.022665E+02 -6.019749E+01 -2.768676E+02 + 3.499999E+00 6.000000E+01 5 3.520478E+02 9.965697E+01 -5.905570E+01 3.470592E+02 + 3.499999E+00 6.000000E+01 6 2.114968E+03 1.639057E+02 -2.032075E+03 5.863102E+02 + 3.499999E+00 9.000000E+01 1 1.697149E-05 -7.374596E+01 4.750265E-06 -1.629314E-05 + 3.499999E+00 9.000000E+01 2 3.708871E+01 6.821251E+01 1.376604E+01 3.443935E+01 + 3.499999E+00 9.000000E+01 3 6.407467E+00 1.718145E+02 -6.342189E+00 9.122886E-01 + 3.499999E+00 9.000000E+01 4 9.978592E+01 6.746081E+01 3.824947E+01 9.216402E+01 + 3.499999E+00 9.000000E+01 5 2.805061E-05 1.040976E+01 2.758892E-05 5.068373E-06 + 3.499999E+00 9.000000E+01 6 1.127239E-03 1.654328E+02 -1.091002E-03 2.835178E-04 + 3.599999E+00 0.000000E+00 1 2.577330E+01 9.237114E+01 -1.066301E+00 2.575124E+01 + 3.599999E+00 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.599999E+00 0.000000E+00 3 4.057404E+00 1.715391E+02 -4.013245E+00 5.969842E-01 + 3.599999E+00 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.599999E+00 0.000000E+00 5 1.168028E+02 -9.787395E+01 -1.600130E+01 -1.157016E+02 + 3.599999E+00 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.599999E+00 3.000000E+01 1 3.466184E+01 1.459034E+02 -2.870325E+01 1.943107E+01 + 3.599999E+00 3.000000E+01 2 1.695292E+01 -1.442497E+02 -1.375849E+01 -9.904814E+00 + 3.599999E+00 3.000000E+01 3 3.636840E+00 1.338848E+02 -2.521097E+00 2.621197E+00 + 3.599999E+00 3.000000E+01 4 5.423851E+01 -1.489744E+02 -4.647898E+01 -2.795567E+01 + 3.599999E+00 3.000000E+01 5 2.045745E+02 -3.209956E+01 1.733004E+02 -1.087093E+02 + 3.599999E+00 3.000000E+01 6 4.912776E+02 -3.812108E+01 3.864920E+02 -3.032781E+02 + 3.599999E+00 6.000000E+01 1 8.862406E+01 -8.002473E+01 1.535174E+01 -8.728429E+01 + 3.599999E+00 6.000000E+01 2 1.076934E+02 -1.082558E+02 -3.373612E+01 -1.022729E+02 + 3.599999E+00 6.000000E+01 3 6.449351E+00 2.759315E+01 5.715795E+00 2.987276E+00 + 3.599999E+00 6.000000E+01 4 3.844471E+02 -1.080811E+02 -1.193178E+02 -3.654625E+02 + 3.599999E+00 6.000000E+01 5 3.885133E+02 1.044001E+02 -9.662006E+01 3.763072E+02 + 3.599999E+00 6.000000E+01 6 2.230641E+03 1.606511E+02 -2.104650E+03 7.390564E+02 + 3.599999E+00 9.000000E+01 1 1.746707E-05 -4.613996E+01 1.210292E-05 -1.259436E-05 + 3.599999E+00 9.000000E+01 2 3.031299E+01 7.251962E+01 9.105392E+00 2.891313E+01 + 3.599999E+00 9.000000E+01 3 5.550235E+00 -1.756765E+02 -5.534440E+00 -4.184227E-01 + 3.599999E+00 9.000000E+01 4 8.694468E+01 7.543147E+01 2.186988E+01 8.414919E+01 + 3.599999E+00 9.000000E+01 5 2.958998E-05 1.050274E+01 2.909423E-05 5.393735E-06 + 3.599999E+00 9.000000E+01 6 1.111655E-03 1.640854E+02 -1.069047E-03 3.048207E-04 + 3.699999E+00 0.000000E+00 1 6.448834E+01 8.812731E+01 2.107403E+00 6.445390E+01 + 3.699999E+00 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.699999E+00 0.000000E+00 3 4.135828E+00 1.736109E+02 -4.110141E+00 4.602304E-01 + 3.699999E+00 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.699999E+00 0.000000E+00 5 2.780600E+02 -8.937009E+01 3.056895E+00 -2.780432E+02 + 3.699999E+00 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.699999E+00 3.000000E+01 1 4.616284E+01 1.214222E+02 -2.406658E+01 3.939299E+01 + 3.699999E+00 3.000000E+01 2 6.240627E+00 1.255741E+02 -3.630517E+00 5.075901E+00 + 3.699999E+00 3.000000E+01 3 5.365453E+00 1.765769E+02 -5.355880E+00 3.203621E-01 + 3.699999E+00 3.000000E+01 4 3.015887E+01 1.169264E+02 -1.365729E+01 2.688932E+01 + 3.699999E+00 3.000000E+01 5 2.150159E+02 -4.157241E+01 1.608572E+02 -1.426772E+02 + 3.699999E+00 3.000000E+01 6 2.990040E+02 -4.463598E+01 2.127668E+02 -2.100802E+02 + 3.699999E+00 6.000000E+01 1 8.421621E+01 -7.756512E+01 1.813427E+01 -8.224061E+01 + 3.699999E+00 6.000000E+01 2 1.357168E+02 -1.126557E+02 -5.227703E+01 -1.252444E+02 + 3.699999E+00 6.000000E+01 3 9.447015E+00 4.043707E+01 7.190301E+00 6.127451E+00 + 3.699999E+00 6.000000E+01 4 4.851443E+02 -1.124662E+02 -1.853927E+02 -4.483242E+02 + 3.699999E+00 6.000000E+01 5 3.718708E+02 1.051254E+02 -9.703284E+01 3.589882E+02 + 3.699999E+00 6.000000E+01 6 2.221244E+03 1.585461E+02 -2.067339E+03 8.124263E+02 + 3.699999E+00 9.000000E+01 1 1.675151E-05 -1.914058E+01 1.582543E-05 -5.492601E-06 + 3.699999E+00 9.000000E+01 2 2.606002E+01 9.104572E+01 -4.755977E-01 2.605568E+01 + 3.699999E+00 9.000000E+01 3 4.797679E+00 -1.754465E+02 -4.782536E+00 -3.808895E-01 + 3.699999E+00 9.000000E+01 4 8.483791E+01 9.507306E+01 -7.501873E+00 8.450558E+01 + 3.699999E+00 9.000000E+01 5 2.136629E-05 2.694220E+01 1.904728E-05 9.680883E-06 + 3.699999E+00 9.000000E+01 6 1.095377E-03 1.630527E+02 -1.047808E-03 3.192936E-04 + 3.799999E+00 0.000000E+00 1 9.680605E+01 8.504037E+01 8.369260E+00 9.644360E+01 + 3.799999E+00 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.799999E+00 0.000000E+00 3 5.284828E+00 -1.749997E+02 -5.264716E+00 -4.606299E-01 + 3.799999E+00 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.799999E+00 0.000000E+00 5 4.108856E+02 -8.898692E+01 7.264781E+00 -4.108213E+02 + 3.799999E+00 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.799999E+00 3.000000E+01 1 4.886696E+01 9.373832E+01 -3.186108E+00 4.876299E+01 + 3.799999E+00 3.000000E+01 2 1.746278E+01 5.889301E+01 9.021933E+00 1.495170E+01 + 3.799999E+00 3.000000E+01 3 6.057806E+00 -1.521841E+02 -5.357835E+00 -2.826767E+00 + 3.799999E+00 3.000000E+01 4 7.572858E+01 6.843237E+01 2.783778E+01 7.042639E+01 + 3.799999E+00 3.000000E+01 5 1.618238E+02 -6.106374E+01 7.829624E+01 -1.416215E+02 + 3.799999E+00 3.000000E+01 6 1.136665E+02 1.716626E+02 -1.124651E+02 1.648192E+01 + 3.799999E+00 6.000000E+01 1 7.506390E+01 -8.244417E+01 9.870318E+00 -7.441214E+01 + 3.799999E+00 6.000000E+01 2 1.623081E+02 -1.157113E+02 -7.041512E+01 -1.462383E+02 + 3.799999E+00 6.000000E+01 3 9.810149E+00 4.842605E+01 6.509879E+00 7.338972E+00 + 3.799999E+00 6.000000E+01 4 5.820505E+02 -1.156258E+02 -2.517319E+02 -5.247988E+02 + 3.799999E+00 6.000000E+01 5 3.351341E+02 1.002252E+02 -5.949224E+01 3.298113E+02 + 3.799999E+00 6.000000E+01 6 2.078295E+03 1.573983E+02 -1.918680E+03 7.987352E+02 + 3.799999E+00 9.000000E+01 1 1.561437E-05 5.050616E+00 1.555374E-05 1.374623E-06 + 3.799999E+00 9.000000E+01 2 2.564585E+01 1.215206E+02 -1.340777E+01 2.186187E+01 + 3.799999E+00 9.000000E+01 3 5.158154E+00 -1.783746E+02 -5.156078E+00 -1.463055E-01 + 3.799999E+00 9.000000E+01 4 9.451308E+01 1.181360E+02 -4.456914E+01 8.334455E+01 + 3.799999E+00 9.000000E+01 5 5.694140E-06 -1.429422E+02 -4.544086E-06 -3.431402E-06 + 3.799999E+00 9.000000E+01 6 1.075892E-03 1.624064E+02 -1.025566E-03 3.252031E-04 + 3.899998E+00 0.000000E+00 1 1.199427E+02 7.651603E+01 2.796745E+01 1.166365E+02 + 3.899998E+00 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.899998E+00 0.000000E+00 3 6.305821E+00 -1.622106E+02 -6.004313E+00 -1.926551E+00 + 3.899998E+00 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.899998E+00 0.000000E+00 5 4.949913E+02 -9.490263E+01 -4.230329E+01 -4.931804E+02 + 3.899998E+00 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.899998E+00 3.000000E+01 1 6.339765E+01 6.585059E+01 2.593709E+01 5.784919E+01 + 3.899998E+00 3.000000E+01 2 3.166013E+01 3.966199E+01 2.437271E+01 2.020731E+01 + 3.899998E+00 3.000000E+01 3 5.663646E+00 -1.308824E+02 -3.706906E+00 -4.282024E+00 + 3.899998E+00 3.000000E+01 4 1.285910E+02 5.258181E+01 7.813549E+01 1.021298E+02 + 3.899998E+00 3.000000E+01 5 1.490516E+02 -1.063731E+02 -4.201637E+01 -1.430070E+02 + 3.899998E+00 3.000000E+01 6 6.498409E+02 1.471119E+02 -5.456924E+02 3.528640E+02 + 3.899998E+00 6.000000E+01 1 6.852900E+01 -9.329747E+01 -3.941782E+00 -6.841554E+01 + 3.899998E+00 6.000000E+01 2 1.866383E+02 -1.175325E+02 -8.627378E+01 -1.655013E+02 + 3.899998E+00 6.000000E+01 3 8.832902E+00 4.766920E+01 5.948164E+00 6.529892E+00 + 3.899998E+00 6.000000E+01 4 6.714777E+02 -1.176640E+02 -3.117577E+02 -5.947179E+02 + 3.899998E+00 6.000000E+01 5 3.008390E+02 9.106235E+01 -5.577679E+00 3.007873E+02 + 3.899998E+00 6.000000E+01 6 1.807456E+03 1.565780E+02 -1.658525E+03 7.184641E+02 + 3.899998E+00 9.000000E+01 1 1.434072E-05 2.640816E+01 1.284425E-05 6.378219E-06 + 3.899998E+00 9.000000E+01 2 2.865577E+01 1.522909E+02 -2.536953E+01 1.332442E+01 + 3.899998E+00 9.000000E+01 3 5.945359E+00 -1.762351E+02 -5.932528E+00 -3.903839E-01 + 3.899998E+00 9.000000E+01 4 1.056488E+02 1.360561E+02 -7.606926E+01 7.331535E+01 + 3.899998E+00 9.000000E+01 5 3.824207E-05 -1.125429E+02 -1.466106E-05 -3.532010E-05 + 3.899998E+00 9.000000E+01 6 1.051411E-03 1.620507E+02 -1.000238E-03 3.240192E-04 + 3.999998E+00 0.000000E+00 1 1.436809E+02 6.415221E+01 6.264229E+01 1.293064E+02 + 3.999998E+00 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.999998E+00 0.000000E+00 3 6.736756E+00 -1.539550E+02 -6.052634E+00 -2.957956E+00 + 3.999998E+00 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.999998E+00 0.000000E+00 5 5.601800E+02 -1.058728E+02 -1.532105E+02 -5.388211E+02 + 3.999998E+00 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.999998E+00 3.000000E+01 1 8.682338E+01 5.205758E+01 5.338503E+01 6.847144E+01 + 3.999998E+00 3.000000E+01 2 4.819812E+01 2.988014E+01 4.179112E+01 2.401169E+01 + 3.999998E+00 3.000000E+01 3 4.733355E+00 -1.156061E+02 -2.045673E+00 -4.268475E+00 + 3.999998E+00 3.000000E+01 4 1.867685E+02 4.412656E+01 1.340631E+02 1.300368E+02 + 3.999998E+00 3.000000E+01 5 2.228042E+02 -1.358351E+02 -1.598257E+02 -1.552336E+02 + 3.999998E+00 3.000000E+01 6 1.290208E+03 1.445139E+02 -1.050561E+03 7.489717E+02 + 3.999998E+00 6.000000E+01 1 6.732007E+01 -1.073700E+02 -2.009781E+01 -6.425006E+01 + 3.999998E+00 6.000000E+01 2 2.078974E+02 -1.181541E+02 -9.809530E+01 -1.832993E+02 + 3.999998E+00 6.000000E+01 3 7.912072E+00 3.934391E+01 6.118838E+00 5.016046E+00 + 3.999998E+00 6.000000E+01 4 7.497960E+02 -1.185743E+02 -3.586257E+02 -6.584692E+02 + 3.999998E+00 6.000000E+01 5 2.748507E+02 7.875133E+01 5.361447E+01 2.695708E+02 + 3.999998E+00 6.000000E+01 6 1.442472E+03 1.549349E+02 -1.306630E+03 6.110990E+02 + 3.999998E+00 9.000000E+01 1 1.314687E-05 4.594492E+01 9.141666E-06 9.448280E-06 + 3.999998E+00 9.000000E+01 2 3.048443E+01 1.780125E+02 -3.046609E+01 1.057267E+00 + 3.999998E+00 9.000000E+01 3 6.787580E+00 -1.731823E+02 -6.739584E+00 -8.057644E-01 + 3.999998E+00 9.000000E+01 4 1.024031E+02 1.458316E+02 -8.472736E+01 5.751231E+01 + 3.999998E+00 9.000000E+01 5 6.856214E-05 -9.788301E+01 -9.403356E-06 -6.791424E-05 + 3.999998E+00 9.000000E+01 6 1.022519E-03 1.618751E+02 -9.717822E-04 3.180952E-04 + 4.099998E+00 0.000000E+00 1 1.769769E+02 5.216186E+01 1.085635E+02 1.397670E+02 + 4.099998E+00 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 4.099998E+00 0.000000E+00 3 6.656598E+00 -1.504145E+02 -5.788711E+00 -3.286505E+00 + 4.099998E+00 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 4.099998E+00 0.000000E+00 5 6.470839E+02 -1.186960E+02 -3.107056E+02 -5.676087E+02 + 4.099998E+00 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 4.099998E+00 3.000000E+01 1 1.083780E+02 4.710453E+01 7.376889E+01 7.939737E+01 + 4.099998E+00 3.000000E+01 2 6.552439E+01 2.731570E+01 5.821786E+01 3.006869E+01 + 4.099998E+00 3.000000E+01 3 3.793626E+00 -1.018131E+02 -7.766338E-01 -3.713279E+00 + 4.099998E+00 3.000000E+01 4 2.468741E+02 4.157050E+01 1.846964E+02 1.638111E+02 + 4.099998E+00 3.000000E+01 5 3.059917E+02 -1.451601E+02 -2.511432E+02 -1.748085E+02 + 4.099998E+00 3.000000E+01 6 1.953405E+03 1.440962E+02 -1.582263E+03 1.145528E+03 + 4.099998E+00 6.000000E+01 1 7.278704E+01 -1.211571E+02 -3.765905E+01 -6.228763E+01 + 4.099998E+00 6.000000E+01 2 2.250607E+02 -1.174773E+02 -1.038424E+02 -1.996724E+02 + 4.099998E+00 6.000000E+01 3 7.562171E+00 2.844657E+01 6.649127E+00 3.602157E+00 + 4.099998E+00 6.000000E+01 4 8.121299E+02 -1.182283E+02 -3.841263E+02 -7.155431E+02 + 4.099998E+00 6.000000E+01 5 2.641593E+02 6.395090E+01 1.160033E+02 2.373255E+02 + 4.099998E+00 6.000000E+01 6 1.038762E+03 1.507644E+02 -9.064431E+02 5.073342E+02 + 4.099998E+00 9.000000E+01 1 1.218451E-05 6.544556E+01 5.063365E-06 1.108262E-05 + 4.099998E+00 9.000000E+01 2 2.692613E+01 -1.580917E+02 -2.498158E+01 -1.004675E+01 + 4.099998E+00 9.000000E+01 3 7.728706E+00 -1.708995E+02 -7.631421E+00 -1.222420E+00 + 4.099998E+00 9.000000E+01 4 7.902838E+01 1.398593E+02 -6.041432E+01 5.094698E+01 + 4.099998E+00 9.000000E+01 5 9.701904E-05 -8.663662E+01 5.691952E-06 -9.685192E-05 + 4.099998E+00 9.000000E+01 6 9.907717E-04 1.618420E+02 -9.414321E-04 3.087624E-04 + 4.199998E+00 0.000000E+00 1 2.222129E+02 4.372376E+01 1.605889E+02 1.535896E+02 + 4.199998E+00 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 4.199998E+00 0.000000E+00 3 6.272953E+00 -1.497196E+02 -5.417120E+00 -3.163029E+00 + 4.199998E+00 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 4.199998E+00 0.000000E+00 5 7.777079E+02 -1.293957E+02 -4.935896E+02 -6.009982E+02 + 4.199998E+00 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 4.199998E+00 3.000000E+01 1 1.235069E+02 4.672363E+01 8.466619E+01 8.991985E+01 + 4.199998E+00 3.000000E+01 2 7.948988E+01 2.993484E+01 6.888541E+01 3.966662E+01 + 4.199998E+00 3.000000E+01 3 3.152623E+00 -8.481982E+01 2.846442E-01 -3.139747E+00 + 4.199998E+00 3.000000E+01 4 2.969751E+02 4.384402E+01 2.141868E+02 2.057139E+02 + 4.199998E+00 3.000000E+01 5 3.638582E+02 -1.468557E+02 -3.046570E+02 -1.989394E+02 + 4.199998E+00 3.000000E+01 6 2.577388E+03 1.443839E+02 -2.095253E+03 1.500947E+03 + 4.199998E+00 6.000000E+01 1 8.496262E+01 -1.310437E+02 -5.578941E+01 -6.407954E+01 + 4.199998E+00 6.000000E+01 2 2.361464E+02 -1.153644E+02 -1.011588E+02 -2.133824E+02 + 4.199998E+00 6.000000E+01 3 7.540276E+00 1.941462E+01 7.111519E+00 2.506401E+00 + 4.199998E+00 6.000000E+01 4 8.499861E+02 -1.165007E+02 -3.792712E+02 -7.606771E+02 + 4.199998E+00 6.000000E+01 5 2.771346E+02 4.957950E+01 1.796919E+02 2.109843E+02 + 4.199998E+00 6.000000E+01 6 6.496003E+02 1.407102E+02 -5.027601E+02 4.113549E+02 + 4.199998E+00 9.000000E+01 1 1.162693E-05 8.708602E+01 5.910740E-07 1.161190E-05 + 4.199998E+00 9.000000E+01 2 1.717420E+01 -1.257395E+02 -1.003147E+01 -1.393998E+01 + 4.199998E+00 9.000000E+01 3 8.776693E+00 -1.691979E+02 -8.621174E+00 -1.644905E+00 + 4.199998E+00 9.000000E+01 4 7.172317E+01 9.604378E+01 -7.551608E+00 7.132451E+01 + 4.199998E+00 9.000000E+01 5 1.239009E-04 -7.636890E+01 2.919967E-05 -1.204110E-04 + 4.199998E+00 9.000000E+01 6 9.571696E-04 1.619692E+02 -9.101634E-04 2.962704E-04 + 4.299998E+00 0.000000E+00 1 2.769825E+02 4.001219E+01 2.121430E+02 1.780860E+02 + 4.299998E+00 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 4.299998E+00 0.000000E+00 3 5.694993E+00 -1.497345E+02 -4.918758E+00 -2.870323E+00 + 4.299998E+00 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 4.299998E+00 0.000000E+00 5 9.487909E+02 -1.354382E+02 -6.760075E+02 -6.657462E+02 + 4.299998E+00 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 4.299998E+00 3.000000E+01 1 1.304576E+02 4.986138E+01 8.409808E+01 9.973315E+01 + 4.299998E+00 3.000000E+01 2 8.628721E+01 3.583747E+01 6.995141E+01 5.052013E+01 + 4.299998E+00 3.000000E+01 3 2.998477E+00 -6.388546E+01 1.319831E+00 -2.692380E+00 + 4.299998E+00 3.000000E+01 4 3.243755E+02 4.959517E+01 2.102551E+02 2.470067E+02 + 4.299998E+00 3.000000E+01 5 3.863448E+02 -1.441945E+02 -3.133285E+02 -2.260256E+02 + 4.299998E+00 3.000000E+01 6 3.126312E+03 1.450128E+02 -2.561323E+03 1.792609E+03 + 4.299998E+00 6.000000E+01 1 1.021343E+02 -1.351964E+02 -7.246703E+01 -7.197182E+01 + 4.299998E+00 6.000000E+01 2 2.381832E+02 -1.119180E+02 -8.890878E+01 -2.209671E+02 + 4.299998E+00 6.000000E+01 3 7.493745E+00 1.328287E+01 7.293269E+00 1.721753E+00 + 4.299998E+00 6.000000E+01 4 8.518859E+02 -1.135350E+02 -3.401663E+02 -7.810228E+02 + 4.299998E+00 6.000000E+01 5 3.114526E+02 4.011540E+01 2.381828E+02 2.006780E+02 + 4.299998E+00 6.000000E+01 6 3.336525E+02 1.111197E+02 -1.202209E+02 3.112410E+02 + 4.299998E+00 9.000000E+01 1 1.169914E-05 1.126883E+02 -4.512574E-06 1.079382E-05 + 4.299998E+00 9.000000E+01 2 1.171045E+01 -3.668459E+01 9.391036E+00 -6.995934E+00 + 4.299998E+00 9.000000E+01 3 9.869135E+00 -1.678559E+02 -9.648279E+00 -2.076180E+00 + 4.299998E+00 9.000000E+01 4 1.410076E+02 6.587157E+01 5.764157E+01 1.286880E+02 + 4.299998E+00 9.000000E+01 5 1.475130E-04 -6.556328E+01 6.102437E-05 -1.342986E-04 + 4.299998E+00 9.000000E+01 6 9.218401E-04 1.622708E+02 -8.780588E-04 2.807167E-04 + 4.399998E+00 0.000000E+00 1 3.343017E+02 4.143633E+01 2.506232E+02 2.212366E+02 + 4.399998E+00 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 4.399998E+00 0.000000E+00 3 4.950696E+00 -1.486069E+02 -4.225980E+00 -2.578854E+00 + 4.399998E+00 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 4.399998E+00 0.000000E+00 5 1.134238E+03 -1.358509E+02 -8.138492E+02 -7.900288E+02 + 4.399998E+00 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 4.399998E+00 3.000000E+01 1 1.271773E+02 5.689435E+01 6.946230E+01 1.065320E+02 + 4.399998E+00 3.000000E+01 2 8.429147E+01 4.361216E+01 6.102916E+01 5.814200E+01 + 4.399998E+00 3.000000E+01 3 3.361035E+00 -4.464866E+01 2.391139E+00 -2.361993E+00 + 4.399998E+00 3.000000E+01 4 3.224410E+02 5.764745E+01 1.725470E+02 2.723889E+02 + 4.399998E+00 3.000000E+01 5 3.667534E+02 -1.374053E+02 -2.699893E+02 -2.482214E+02 + 4.399998E+00 3.000000E+01 6 3.582413E+03 1.460116E+02 -2.970361E+03 2.002658E+03 + 4.399998E+00 6.000000E+01 1 1.208290E+02 -1.332758E+02 -8.282953E+01 -8.797112E+01 + 4.399998E+00 6.000000E+01 2 2.289413E+02 -1.076797E+02 -6.952862E+01 -2.181281E+02 + 4.399998E+00 6.000000E+01 3 7.232306E+00 9.682171E+00 7.129288E+00 1.216348E+00 + 4.399998E+00 6.000000E+01 4 8.101049E+02 -1.099217E+02 -2.760321E+02 -7.616274E+02 + 4.399998E+00 6.000000E+01 5 3.493807E+02 3.800619E+01 2.752925E+02 2.151300E+02 + 4.399998E+00 6.000000E+01 6 3.082111E+02 3.977768E+01 2.368704E+02 1.971967E+02 + 4.399998E+00 9.000000E+01 1 9.736978E-06 -1.223660E+02 -5.212446E-06 -8.224301E-06 + 4.399998E+00 9.000000E+01 2 2.901769E+01 2.097297E+01 2.709525E+01 1.038623E+01 + 4.399998E+00 9.000000E+01 3 1.092908E+01 -1.668187E+02 -1.064114E+01 -2.492191E+00 + 4.399998E+00 9.000000E+01 4 2.484756E+02 6.239579E+01 1.151340E+02 2.201915E+02 + 4.399998E+00 9.000000E+01 5 1.173416E-04 -7.779848E+01 2.480024E-05 -1.146909E-04 + 4.399998E+00 9.000000E+01 6 8.845504E-04 1.627181E+02 -8.446172E-04 2.627760E-04 + 4.499998E+00 0.000000E+00 1 3.779098E+02 4.799015E+01 2.529193E+02 2.807982E+02 + 4.499998E+00 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 4.499998E+00 0.000000E+00 3 4.052723E+00 -1.444656E+02 -3.297972E+00 -2.355407E+00 + 4.499998E+00 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 4.499998E+00 0.000000E+00 5 1.275649E+03 -1.306416E+02 -8.308618E+02 -9.679617E+02 + 4.499998E+00 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 4.499998E+00 3.000000E+01 1 1.105494E+02 6.842512E+01 4.065087E+01 1.028040E+02 + 4.499998E+00 3.000000E+01 2 7.465453E+01 5.225248E+01 4.570224E+01 5.903053E+01 + 4.499998E+00 3.000000E+01 3 4.060913E+00 -3.087147E+01 3.485565E+00 -2.083710E+00 + 4.499998E+00 3.000000E+01 4 2.938735E+02 6.712950E+01 1.142138E+02 2.707708E+02 + 4.499998E+00 3.000000E+01 5 2.988004E+02 -1.262189E+02 -1.765529E+02 -2.410618E+02 + 4.499998E+00 3.000000E+01 6 3.932096E+03 1.475261E+02 -3.317257E+03 2.111204E+03 + 4.499998E+00 6.000000E+01 1 1.344396E+02 -1.256581E+02 -7.837117E+01 -1.092335E+02 + 4.499998E+00 6.000000E+01 2 2.091497E+02 -1.035040E+02 -4.883919E+01 -2.033674E+02 + 4.499998E+00 6.000000E+01 3 6.686349E+00 8.363100E+00 6.615248E+00 9.725019E-01 + 4.499998E+00 6.000000E+01 4 7.285418E+02 -1.065712E+02 -2.077849E+02 -6.982826E+02 + 4.499998E+00 6.000000E+01 5 3.606620E+02 4.315837E+01 2.630906E+02 2.466990E+02 + 4.499998E+00 6.000000E+01 6 5.779142E+02 6.874489E+00 5.737595E+02 6.917333E+01 + 4.499998E+00 9.000000E+01 1 1.015033E-05 -1.126452E+02 -3.908118E-06 -9.367806E-06 + 4.499998E+00 9.000000E+01 2 5.162467E+01 4.145635E+01 3.869064E+01 3.417807E+01 + 4.499998E+00 9.000000E+01 3 1.188245E+01 -1.660739E+02 -1.153318E+01 -2.859762E+00 + 4.499998E+00 9.000000E+01 4 3.639225E+02 6.548040E+01 1.510294E+02 3.311037E+02 + 4.499998E+00 9.000000E+01 5 1.262468E-04 -7.941154E+01 2.319828E-05 -1.240971E-04 + 4.499998E+00 9.000000E+01 6 8.453398E-04 1.632377E+02 -8.094208E-04 2.437979E-04 + 4.599998E+00 0.000000E+00 1 3.841077E+02 5.818426E+01 2.024975E+02 3.263947E+02 + 4.599998E+00 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 4.599998E+00 0.000000E+00 3 3.049386E+00 -1.344309E+02 -2.134718E+00 -2.177552E+00 + 4.599998E+00 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 4.599998E+00 0.000000E+00 5 1.292093E+03 -1.214620E+02 -6.743853E+02 -1.102138E+03 + 4.599998E+00 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 4.599998E+00 3.000000E+01 1 8.041452E+01 8.405013E+01 8.335629E+00 7.998132E+01 + 4.599998E+00 3.000000E+01 2 6.048987E+01 6.132509E+01 2.902542E+01 5.307118E+01 + 4.599998E+00 3.000000E+01 3 4.875956E+00 -2.113382E+01 4.548004E+00 -1.758014E+00 + 4.599998E+00 3.000000E+01 4 2.488913E+02 7.771290E+01 5.296669E+01 2.431901E+02 + 4.599998E+00 3.000000E+01 5 1.903443E+02 -1.115959E+02 -7.005787E+01 -1.769826E+02 + 4.599998E+00 3.000000E+01 6 4.159670E+03 1.496618E+02 -3.590040E+03 2.101063E+03 + 4.599998E+00 6.000000E+01 1 1.341561E+02 -1.141581E+02 -5.490426E+01 -1.224067E+02 + 4.599998E+00 6.000000E+01 2 1.825358E+02 -1.001821E+02 -3.226822E+01 -1.796610E+02 + 4.599998E+00 6.000000E+01 3 5.846311E+00 9.632482E+00 5.763885E+00 9.782497E-01 + 4.599998E+00 6.000000E+01 4 6.221777E+02 -1.043536E+02 -1.542407E+02 -6.027560E+02 + 4.599998E+00 6.000000E+01 5 3.155230E+02 5.339978E+01 1.881236E+02 2.533066E+02 + 4.599998E+00 6.000000E+01 6 8.984623E+02 -4.113700E+00 8.961475E+02 -6.445203E+01 + 4.599998E+00 9.000000E+01 1 1.011548E-05 -1.062156E+02 -2.824781E-06 -9.713065E-06 + 4.599998E+00 9.000000E+01 2 7.347574E+01 5.378092E+01 4.341493E+01 5.927755E+01 + 4.599998E+00 9.000000E+01 3 1.265103E+01 -1.656356E+02 -1.225552E+01 -3.138562E+00 + 4.599998E+00 9.000000E+01 4 4.728514E+02 6.973167E+01 1.638038E+02 4.435728E+02 + 4.599998E+00 9.000000E+01 5 1.366691E-04 -8.105184E+01 2.125763E-05 -1.350058E-04 + 4.599998E+00 9.000000E+01 6 8.048025E-04 1.637364E+02 -7.725970E-04 2.253906E-04 + 4.699998E+00 0.000000E+00 1 3.460417E+02 6.870765E+01 1.256570E+02 3.224208E+02 + 4.699998E+00 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 4.699998E+00 0.000000E+00 3 2.093747E+00 -1.122938E+02 -7.942743E-01 -1.937241E+00 + 4.699998E+00 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 4.699998E+00 0.000000E+00 5 1.162250E+03 -1.118040E+02 -4.316968E+02 -1.079103E+03 + 4.699998E+00 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 4.699998E+00 3.000000E+01 1 4.541433E+01 1.033159E+02 -1.045981E+01 4.419337E+01 + 4.699998E+00 3.000000E+01 2 4.515564E+01 7.131896E+01 1.446332E+01 4.277667E+01 + 4.699998E+00 3.000000E+01 3 5.617669E+00 -1.294745E+01 5.474845E+00 -1.258679E+00 + 4.699998E+00 3.000000E+01 4 1.996091E+02 8.985918E+01 4.906016E-01 1.996085E+02 + 4.699998E+00 3.000000E+01 5 7.648222E+01 -9.556819E+01 -7.421094E+00 -7.612133E+01 + 4.699998E+00 3.000000E+01 6 4.250005E+03 1.524145E+02 -3.766867E+03 1.968059E+03 + 4.699998E+00 6.000000E+01 1 1.177873E+02 -1.023044E+02 -2.510108E+01 -1.150816E+02 + 4.699998E+00 6.000000E+01 2 1.535583E+02 -9.816393E+01 -2.180615E+01 -1.520021E+02 + 4.699998E+00 6.000000E+01 3 4.744053E+00 1.478502E+01 4.586978E+00 1.210649E+00 + 4.699998E+00 6.000000E+01 4 5.082306E+02 -1.038524E+02 -1.216815E+02 -4.934490E+02 + 4.699998E+00 6.000000E+01 5 2.164927E+02 6.491900E+01 9.177108E+01 1.960795E+02 + 4.699998E+00 6.000000E+01 6 1.220451E+03 -9.020590E+00 1.205357E+03 -1.913538E+02 + 4.699998E+00 9.000000E+01 1 9.939735E-06 -1.026334E+02 -2.173937E-06 -9.699089E-06 + 4.699998E+00 9.000000E+01 2 9.290768E+01 6.229543E+01 4.319396E+01 8.225642E+01 + 4.699998E+00 9.000000E+01 3 1.314444E+01 -1.656420E+02 -1.273388E+01 -3.259555E+00 + 4.699998E+00 9.000000E+01 4 5.692185E+02 7.359039E+01 1.608055E+02 5.460323E+02 + 4.699998E+00 9.000000E+01 5 1.475656E-04 -8.213509E+01 2.019256E-05 -1.461775E-04 + 4.699998E+00 9.000000E+01 6 7.639885E-04 1.641319E+02 -7.348755E-04 2.088932E-04 + 4.799998E+00 0.000000E+00 1 2.851581E+02 7.683483E+01 6.494731E+01 2.776635E+02 + 4.799998E+00 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 4.799998E+00 0.000000E+00 3 1.573121E+00 -6.936901E+01 5.542859E-01 -1.472236E+00 + 4.799998E+00 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 4.799998E+00 0.000000E+00 5 9.603394E+02 -1.045776E+02 -2.417084E+02 -9.294238E+02 + 4.799998E+00 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 4.799998E+00 3.000000E+01 1 1.800440E+01 1.379652E+02 -1.337255E+01 1.205543E+01 + 4.799998E+00 3.000000E+01 2 3.116061E+01 8.419940E+01 3.149298E+00 3.100105E+01 + 4.799998E+00 3.000000E+01 3 6.096856E+00 -4.478701E+00 6.078238E+00 -4.760943E-01 + 4.799998E+00 3.000000E+01 4 1.558646E+02 1.047826E+02 -3.976906E+01 1.507056E+02 + 4.799998E+00 3.000000E+01 5 8.520231E+00 7.131519E+01 2.729558E+00 8.071175E+00 + 4.799998E+00 3.000000E+01 6 4.196128E+03 1.556629E+02 -3.823245E+03 1.729244E+03 + 4.799998E+00 6.000000E+01 1 9.337648E+01 -9.295598E+01 -4.815296E+00 -9.325224E+01 + 4.799998E+00 6.000000E+01 2 1.254169E+02 -9.756944E+01 -1.652089E+01 -1.243240E+02 + 4.799998E+00 6.000000E+01 3 3.493744E+00 2.757178E+01 3.096965E+00 1.617113E+00 + 4.799998E+00 6.000000E+01 4 3.988786E+02 -1.054398E+02 -1.061915E+02 -3.844834E+02 + 4.799998E+00 6.000000E+01 5 9.889384E+01 7.518446E+01 2.528795E+01 9.560602E+01 + 4.799998E+00 6.000000E+01 6 1.526965E+03 -1.134167E+01 1.497147E+03 -3.002918E+02 + 4.799998E+00 9.000000E+01 1 9.805247E-06 -1.010645E+02 -1.881760E-06 -9.622985E-06 + 4.799998E+00 9.000000E+01 2 1.096895E+02 6.836515E+01 4.044143E+01 1.019621E+02 + 4.799998E+00 9.000000E+01 3 1.328537E+01 -1.665575E+02 -1.292139E+01 -3.088449E+00 + 4.799998E+00 9.000000E+01 4 6.525575E+02 7.666199E+01 1.505419E+02 6.349554E+02 + 4.799998E+00 9.000000E+01 5 1.578573E-04 -8.271859E+01 2.000726E-05 -1.565842E-04 + 4.799998E+00 9.000000E+01 6 7.240947E-04 1.643738E+02 -6.973319E-04 1.950419E-04 + 4.899998E+00 0.000000E+00 1 2.242526E+02 8.205466E+01 3.099806E+01 2.220998E+02 + 4.899998E+00 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 4.899998E+00 0.000000E+00 3 1.730230E+00 -2.364791E+01 1.584938E+00 -6.940214E-01 + 4.899998E+00 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 4.899998E+00 0.000000E+00 5 7.637006E+02 -1.005024E+02 -1.392053E+02 -7.509065E+02 + 4.899998E+00 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 4.899998E+00 3.000000E+01 1 1.331560E+01 -1.353097E+02 -9.466311E+00 -9.364521E+00 + 4.899998E+00 3.000000E+01 2 2.033665E+01 1.046555E+02 -5.145310E+00 1.967499E+01 + 4.899998E+00 3.000000E+01 3 6.114715E+00 5.298188E+00 6.088590E+00 5.646272E-01 + 4.899998E+00 3.000000E+01 4 1.244294E+02 1.236556E+02 -6.895877E+01 1.035730E+02 + 4.899998E+00 3.000000E+01 5 5.477603E+01 1.016458E+02 -1.105713E+01 5.364843E+01 + 4.899998E+00 3.000000E+01 6 4.006181E+03 1.592074E+02 -3.745264E+03 1.422142E+03 + 4.899998E+00 6.000000E+01 1 6.913773E+01 -8.669994E+01 3.979922E+00 -6.902308E+01 + 4.899998E+00 6.000000E+01 2 9.966670E+01 -9.837323E+01 -1.451354E+01 -9.860430E+01 + 4.899998E+00 6.000000E+01 3 2.494493E+00 5.765803E+01 1.334482E+00 2.107523E+00 + 4.899998E+00 6.000000E+01 4 3.002386E+02 -1.096119E+02 -1.007742E+02 -2.828211E+02 + 4.899998E+00 6.000000E+01 5 9.884706E+00 -1.214070E+02 -5.151062E+00 -8.436466E+00 + 4.899998E+00 6.000000E+01 6 1.805199E+03 -1.231811E+01 1.763640E+03 -3.851199E+02 + 4.899998E+00 9.000000E+01 1 9.782155E-06 -1.006720E+02 -1.811526E-06 -9.612956E-06 + 4.899998E+00 9.000000E+01 2 1.241622E+02 7.274443E+01 3.683076E+01 1.185738E+02 + 4.899998E+00 9.000000E+01 3 1.312218E+01 -1.693184E+02 -1.289481E+01 -2.432216E+00 + 4.899998E+00 9.000000E+01 4 7.247023E+02 7.897560E+01 1.385827E+02 7.113286E+02 + 4.899998E+00 9.000000E+01 5 1.670554E-04 -8.305560E+01 2.019804E-05 -1.658299E-04 + 4.899998E+00 9.000000E+01 6 6.861564E-04 1.644506E+02 -6.610429E-04 1.839371E-04 + 4.999998E+00 0.000000E+00 1 1.726201E+02 8.508228E+01 1.479787E+01 1.719847E+02 + 4.999998E+00 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 4.999998E+00 0.000000E+00 3 1.957078E+00 6.319008E+00 1.945188E+00 2.154040E-01 + 4.999998E+00 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 4.999998E+00 0.000000E+00 5 6.035105E+02 -9.911384E+01 -9.559399E+01 -5.958915E+02 + 4.999998E+00 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 4.999998E+00 3.000000E+01 1 2.238787E+01 -1.032164E+02 -5.118547E+00 -2.179489E+01 + 4.999998E+00 3.000000E+01 2 1.473204E+01 1.385222E+02 -1.103742E+01 9.757474E+00 + 4.999998E+00 3.000000E+01 3 5.556369E+00 1.667700E+01 5.322656E+00 1.594544E+00 + 4.999998E+00 3.000000E+01 4 1.086218E+02 1.453653E+02 -8.937321E+01 6.173428E+01 + 4.999998E+00 3.000000E+01 5 7.309184E+01 1.132108E+02 -2.880659E+01 6.717587E+01 + 4.999998E+00 3.000000E+01 6 3.704331E+03 1.628360E+02 -3.539354E+03 1.093178E+03 + 4.999998E+00 6.000000E+01 1 4.828257E+01 -8.284464E+01 6.014091E+00 -4.790655E+01 + 4.999998E+00 6.000000E+01 2 7.673846E+01 -1.006174E+02 -1.413899E+01 -7.542466E+01 + 4.999998E+00 6.000000E+01 3 2.660417E+00 1.029868E+02 -5.978680E-01 2.592368E+00 + 4.999998E+00 6.000000E+01 4 2.149162E+02 -1.176101E+02 -9.960352E+01 -1.904419E+02 + 4.999998E+00 6.000000E+01 5 9.926028E+01 -9.857103E+01 -1.479330E+01 -9.815173E+01 + 4.999998E+00 6.000000E+01 6 2.046443E+03 -1.259009E+01 1.997236E+03 -4.460722E+02 + 4.999998E+00 9.000000E+01 1 9.873493E-06 -1.008077E+02 -1.851404E-06 -9.698359E-06 + 4.999998E+00 9.000000E+01 2 1.367568E+02 7.594843E+01 3.320388E+01 1.326647E+02 + 4.999998E+00 9.000000E+01 3 1.298596E+01 -1.747427E+02 -1.293134E+01 -1.189889E+00 + 4.999998E+00 9.000000E+01 4 7.877038E+02 8.068748E+01 1.274659E+02 7.773221E+02 + 4.999998E+00 9.000000E+01 5 1.751611E-04 -8.334624E+01 2.029577E-05 -1.739813E-04 + 4.999998E+00 9.000000E+01 6 6.508722E-04 1.643833E+02 -6.268446E-04 1.752157E-04 + 5.099998E+00 0.000000E+00 1 1.312804E+02 8.677015E+01 7.396552E+00 1.310719E+02 + 5.099998E+00 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 5.099998E+00 0.000000E+00 3 1.801020E+00 2.839039E+01 1.584408E+00 8.563427E-01 + 5.099998E+00 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 5.099998E+00 0.000000E+00 5 4.830936E+02 -9.984545E+01 -8.260476E+01 -4.759789E+02 + 5.099998E+00 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 5.099998E+00 3.000000E+01 1 2.846573E+01 -9.460564E+01 -2.285713E+00 -2.837381E+01 + 5.099998E+00 3.000000E+01 2 1.517342E+01 1.739700E+02 -1.508947E+01 1.593953E+00 + 5.099998E+00 3.000000E+01 3 4.530262E+00 2.998076E+01 3.924082E+00 2.263813E+00 + 5.099998E+00 3.000000E+01 4 1.063378E+02 1.655567E+02 -1.029770E+02 2.652286E+01 + 5.099998E+00 3.000000E+01 5 7.443301E+01 1.267481E+02 -4.453309E+01 5.964124E+01 + 5.099998E+00 3.000000E+01 6 3.324823E+03 1.663876E+02 -3.231429E+03 7.825051E+02 + 5.099998E+00 6.000000E+01 1 3.106172E+01 -8.046489E+01 5.145436E+00 -3.063258E+01 + 5.099998E+00 6.000000E+01 2 5.653857E+01 -1.046741E+02 -1.432239E+01 -5.469442E+01 + 5.099998E+00 6.000000E+01 3 3.987724E+00 1.300531E+02 -2.566091E+00 3.052396E+00 + 5.099998E+00 6.000000E+01 4 1.457803E+02 -1.327872E+02 -9.902529E+01 -1.069855E+02 + 5.099998E+00 6.000000E+01 5 1.720107E+02 -9.528493E+01 -1.584369E+01 -1.712795E+02 + 5.099998E+00 6.000000E+01 6 2.247497E+03 -1.253841E+01 2.193896E+03 -4.879184E+02 + 5.099998E+00 9.000000E+01 1 1.005404E-05 -1.010651E+02 -1.929613E-06 -9.867133E-06 + 5.099998E+00 9.000000E+01 2 1.478123E+02 7.833849E+01 2.987723E+01 1.447613E+02 + 5.099998E+00 9.000000E+01 3 1.335400E+01 1.780605E+02 -1.334635E+01 4.519591E-01 + 5.099998E+00 9.000000E+01 4 8.430808E+02 8.196151E+01 1.178951E+02 8.347970E+02 + 5.099998E+00 9.000000E+01 5 1.824164E-04 -8.369120E+01 2.004519E-05 -1.813117E-04 + 5.099998E+00 9.000000E+01 6 6.185627E-04 1.642137E+02 -5.952326E-04 1.682797E-04 + 5.199997E+00 0.000000E+00 1 9.872353E+01 8.776910E+01 3.842977E+00 9.864870E+01 + 5.199997E+00 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 5.199997E+00 0.000000E+00 3 1.284143E+00 5.091521E+01 8.096135E-01 9.967697E-01 + 5.199997E+00 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 5.199997E+00 0.000000E+00 5 3.974545E+02 -1.023061E+02 -8.471117E+01 -3.883222E+02 + 5.199997E+00 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 5.199997E+00 3.000000E+01 1 3.130427E+01 -9.179281E+01 -9.793614E-01 -3.128895E+01 + 5.199997E+00 3.000000E+01 2 1.834637E+01 -1.649215E+02 -1.771471E+01 -4.772676E+00 + 5.199997E+00 3.000000E+01 3 3.355320E+00 4.752442E+01 2.265767E+00 2.474767E+00 + 5.199997E+00 3.000000E+01 4 1.111701E+02 -1.790739E+02 -1.111556E+02 -1.796929E+00 + 5.199997E+00 3.000000E+01 5 6.993764E+01 1.462886E+02 -5.817718E+01 3.881610E+01 + 5.199997E+00 3.000000E+01 6 2.903145E+03 1.697889E+02 -2.857164E+03 5.146542E+02 + 5.199997E+00 6.000000E+01 1 1.686113E+01 -7.846501E+01 3.371660E+00 -1.652059E+01 + 5.199997E+00 6.000000E+01 2 3.889046E+01 -1.118502E+02 -1.447432E+01 -3.609656E+01 + 5.199997E+00 6.000000E+01 3 5.714093E+00 1.418495E+02 -4.493509E+00 3.529765E+00 + 5.199997E+00 6.000000E+01 4 1.021020E+02 -1.621298E+02 -9.717603E+01 -3.133125E+01 + 5.199997E+00 6.000000E+01 5 2.306090E+02 -9.358036E+01 -1.440116E+01 -2.301589E+02 + 5.199997E+00 6.000000E+01 6 2.410101E+03 -1.237994E+01 2.354060E+03 -5.167098E+02 + 5.199997E+00 9.000000E+01 1 1.029325E-05 -1.012334E+02 -2.005185E-06 -1.009605E-05 + 5.199997E+00 9.000000E+01 2 1.575495E+02 8.016237E+01 2.691839E+01 1.552329E+02 + 5.199997E+00 9.000000E+01 3 1.436696E+01 1.714826E+02 -1.420850E+01 2.127890E+00 + 5.199997E+00 9.000000E+01 4 8.917733E+02 8.292913E+01 1.097745E+02 8.849910E+02 + 5.199997E+00 9.000000E+01 5 1.891061E-04 -8.411414E+01 1.939230E-05 -1.881092E-04 + 5.199997E+00 9.000000E+01 6 5.892388E-04 1.639931E+02 -5.663932E-04 1.624843E-04 + 5.299997E+00 0.000000E+00 1 7.318203E+01 8.851676E+01 1.894282E+00 7.315751E+01 + 5.299997E+00 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 5.299997E+00 0.000000E+00 3 7.291105E-01 9.409160E+01 -5.202293E-02 7.272522E-01 + 5.299997E+00 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 5.299997E+00 0.000000E+00 5 3.408557E+02 -1.061450E+02 -9.478160E+01 -3.274127E+02 + 5.299997E+00 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 5.299997E+00 3.000000E+01 1 3.183023E+01 -9.126304E+01 -7.016137E-01 -3.182250E+01 + 5.299997E+00 3.000000E+01 2 2.139673E+01 -1.538552E+02 -1.920749E+01 -9.428274E+00 + 5.299997E+00 3.000000E+01 3 2.469082E+00 7.542561E+01 6.213123E-01 2.389631E+00 + 5.299997E+00 3.000000E+01 4 1.172394E+02 -1.684819E+02 -1.148783E+02 -2.341015E+01 + 5.299997E+00 3.000000E+01 5 7.161636E+01 1.724431E+02 -7.099435E+01 9.418367E+00 + 5.299997E+00 3.000000E+01 6 2.469182E+03 1.730642E+02 -2.451113E+03 2.981705E+02 + 5.299997E+00 6.000000E+01 1 5.029590E+00 -7.181719E+01 1.569483E+00 -4.778441E+00 + 5.299997E+00 6.000000E+01 2 2.403101E+01 -1.265989E+02 -1.432751E+01 -1.929280E+01 + 5.299997E+00 6.000000E+01 3 7.550153E+00 1.475927E+02 -6.374292E+00 4.046382E+00 + 5.299997E+00 6.000000E+01 4 1.006784E+02 1.580147E+02 -9.335703E+01 3.769087E+01 + 5.299997E+00 6.000000E+01 5 2.778275E+02 -9.266583E+01 -1.292196E+01 -2.775269E+02 + 5.299997E+00 6.000000E+01 6 2.538895E+03 -1.221761E+01 2.481391E+03 -5.372943E+02 + 5.299997E+00 9.000000E+01 1 1.056448E-05 -1.012218E+02 -2.055921E-06 -1.036250E-05 + 5.299997E+00 9.000000E+01 2 1.661043E+02 8.158524E+01 2.430735E+01 1.643162E+02 + 5.299997E+00 9.000000E+01 3 1.576545E+01 1.668751E+02 -1.535362E+01 3.579932E+00 + 5.299997E+00 9.000000E+01 4 9.343185E+02 8.368379E+01 1.027895E+02 9.286471E+02 + 5.299997E+00 9.000000E+01 5 1.954692E-04 -8.459381E+01 1.841629E-05 -1.945997E-04 + 5.299997E+00 9.000000E+01 6 5.626847E-04 1.637713E+02 -5.402638E-04 1.572549E-04 + 5.399997E+00 0.000000E+00 1 5.320681E+01 8.927164E+01 6.763632E-01 5.320251E+01 + 5.399997E+00 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 5.399997E+00 0.000000E+00 3 8.946602E-01 1.628443E+02 -8.548536E-01 2.638978E-01 + 5.399997E+00 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 5.399997E+00 0.000000E+00 5 3.084848E+02 -1.108280E+02 -1.096860E+02 -2.883259E+02 + 5.399997E+00 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 5.399997E+00 3.000000E+01 1 3.072328E+01 -9.174631E+01 -9.362619E-01 -3.070901E+01 + 5.399997E+00 3.000000E+01 2 2.341204E+01 -1.477095E+02 -1.979138E+01 -1.250700E+01 + 5.399997E+00 3.000000E+01 3 2.390580E+00 1.128374E+02 -9.278246E-01 2.203183E+00 + 5.399997E+00 3.000000E+01 4 1.212354E+02 -1.613960E+02 -1.149004E+02 -3.867727E+01 + 5.399997E+00 3.000000E+01 5 8.786434E+01 -1.629816E+02 -8.401685E+01 -2.571596E+01 + 5.399997E+00 3.000000E+01 6 2.044515E+03 1.763336E+02 -2.040331E+03 1.307424E+02 + 5.399997E+00 6.000000E+01 1 5.211673E+00 8.915567E+01 7.679845E-02 5.211107E+00 + 5.399997E+00 6.000000E+01 2 1.436965E+01 -1.638569E+02 -1.380306E+01 -3.995303E+00 + 5.399997E+00 6.000000E+01 3 9.404319E+00 1.508960E+02 -8.216909E+00 4.574233E+00 + 5.399997E+00 6.000000E+01 4 1.336929E+02 1.309017E+02 -8.753727E+01 1.010495E+02 + 5.399997E+00 6.000000E+01 5 3.157938E+02 -9.220214E+01 -1.213439E+01 -3.155605E+02 + 5.399997E+00 6.000000E+01 6 2.639307E+03 -1.208229E+01 2.580841E+03 -5.524499E+02 + 5.399997E+00 9.000000E+01 1 1.084641E-05 -1.010023E+02 -2.070025E-06 -1.064705E-05 + 5.399997E+00 9.000000E+01 2 1.735647E+02 8.271427E+01 2.201106E+01 1.721633E+02 + 5.399997E+00 9.000000E+01 3 1.724582E+01 1.640994E+02 -1.658596E+01 4.724835E+00 + 5.399997E+00 9.000000E+01 4 9.710290E+02 8.428634E+01 9.667275E+01 9.662048E+02 + 5.399997E+00 9.000000E+01 5 2.016459E-04 -8.508926E+01 1.726162E-05 -2.009057E-04 + 5.399997E+00 9.000000E+01 6 5.385648E-04 1.635914E+02 -5.166297E-04 1.521372E-04 + 5.499997E+00 0.000000E+00 1 3.771612E+01 9.009675E+01 -6.368235E-02 3.771607E+01 + 5.499997E+00 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 5.499997E+00 0.000000E+00 3 1.600938E+00 -1.721058E+02 -1.585767E+00 -2.198788E-01 + 5.499997E+00 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 5.499997E+00 0.000000E+00 5 2.962563E+02 -1.155710E+02 -1.278731E+02 -2.672382E+02 + 5.499997E+00 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 5.499997E+00 3.000000E+01 1 2.840397E+01 -9.256886E+01 -1.273066E+00 -2.837543E+01 + 5.499997E+00 3.000000E+01 2 2.422392E+01 -1.442243E+02 -1.965315E+01 -1.416163E+01 + 5.499997E+00 3.000000E+01 3 3.138138E+00 1.397190E+02 -2.394031E+00 2.028922E+00 + 5.499997E+00 3.000000E+01 4 1.217762E+02 -1.567622E+02 -1.118971E+02 -4.804665E+01 + 5.499997E+00 3.000000E+01 5 1.172373E+02 -1.464309E+02 -9.768437E+01 -6.482551E+01 + 5.499997E+00 3.000000E+01 6 1.642951E+03 1.798269E+02 -1.642944E+03 4.963988E+00 + 5.499997E+00 6.000000E+01 1 1.392469E+01 9.416711E+01 -1.011847E+00 1.388788E+01 + 5.499997E+00 6.000000E+01 2 1.634966E+01 1.422125E+02 -1.292094E+01 1.001801E+01 + 5.499997E+00 6.000000E+01 3 1.121547E+01 1.531807E+02 -1.000906E+01 5.060182E+00 + 5.499997E+00 6.000000E+01 4 1.784242E+02 1.166464E+02 -8.002017E+01 1.594741E+02 + 5.499997E+00 6.000000E+01 5 3.460588E+02 -9.198971E+01 -1.201513E+01 -3.458501E+02 + 5.499997E+00 6.000000E+01 6 2.716236E+03 -1.196644E+01 2.657210E+03 -5.631809E+02 + 5.499997E+00 9.000000E+01 1 1.112227E-05 -1.005776E+02 -2.041689E-06 -1.093327E-05 + 5.499997E+00 9.000000E+01 2 1.800022E+02 8.361764E+01 2.000959E+01 1.788865E+02 + 5.499997E+00 9.000000E+01 3 1.862189E+01 1.626125E+02 -1.777097E+01 5.564838E+00 + 5.499997E+00 9.000000E+01 4 1.002173E+03 8.477409E+01 9.128094E+01 9.980078E+02 + 5.499997E+00 9.000000E+01 5 2.076841E-04 -8.555885E+01 1.608203E-05 -2.070605E-04 + 5.499997E+00 9.000000E+01 6 5.164861E-04 1.634863E+02 -4.951819E-04 1.468086E-04 + 5.599997E+00 0.000000E+00 1 2.592664E+01 9.071744E+01 -3.246363E-01 2.592461E+01 + 5.599997E+00 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 5.599997E+00 0.000000E+00 3 2.360951E+00 -1.646193E+02 -2.276394E+00 -6.261969E-01 + 5.599997E+00 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 5.599997E+00 0.000000E+00 5 3.003529E+02 -1.195644E+02 -1.481948E+02 -2.612473E+02 + 5.599997E+00 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 5.599997E+00 3.000000E+01 1 2.511107E+01 -9.324791E+01 -1.422701E+00 -2.507073E+01 + 5.599997E+00 3.000000E+01 2 2.390110E+01 -1.424890E+02 -1.895922E+01 -1.455372E+01 + 5.599997E+00 3.000000E+01 3 4.252658E+00 1.533592E+02 -3.801176E+00 1.906873E+00 + 5.599997E+00 3.000000E+01 4 1.185494E+02 -1.539626E+02 -1.065176E+02 -5.203813E+01 + 5.599997E+00 3.000000E+01 5 1.546024E+02 -1.363390E+02 -1.118452E+02 -1.067360E+02 + 5.599997E+00 3.000000E+01 6 1.272583E+03 -1.760506E+02 -1.269561E+03 -8.764964E+01 + 5.599997E+00 6.000000E+01 1 2.162773E+01 9.453346E+01 -1.709483E+00 2.156006E+01 + 5.599997E+00 6.000000E+01 2 2.574589E+01 1.171429E+02 -1.174558E+01 2.291052E+01 + 5.599997E+00 6.000000E+01 3 1.292267E+01 1.550454E+02 -1.171624E+01 5.452082E+00 + 5.599997E+00 6.000000E+01 4 2.250487E+02 1.084547E+02 -7.124017E+01 2.134754E+02 + 5.599997E+00 6.000000E+01 5 3.697420E+02 -9.189798E+01 -1.224580E+01 -3.695392E+02 + 5.599997E+00 6.000000E+01 6 2.773529E+03 -1.184790E+01 2.714442E+03 -5.694453E+02 + 5.599997E+00 9.000000E+01 1 1.137850E-05 -9.996614E+01 -1.969235E-06 -1.120680E-05 + 5.599997E+00 9.000000E+01 2 1.854883E+02 8.433888E+01 1.829739E+01 1.845836E+02 + 5.599997E+00 9.000000E+01 3 1.979555E+01 1.619875E+02 -1.882535E+01 6.121271E+00 + 5.599997E+00 9.000000E+01 4 1.028038E+03 8.516866E+01 8.658434E+01 1.024386E+03 + 5.599997E+00 9.000000E+01 5 2.135555E-04 -8.597174E+01 1.500195E-05 -2.130279E-04 + 5.599997E+00 9.000000E+01 6 5.334870E-04 1.735302E+02 -5.300895E-04 6.011270E-05 + 5.699997E+00 0.000000E+00 1 1.728198E+01 9.010542E+01 -3.179745E-02 1.728195E+01 + 5.699997E+00 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 5.699997E+00 0.000000E+00 3 3.096178E+00 -1.628466E+02 -2.958456E+00 -9.131567E-01 + 5.699997E+00 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 5.699997E+00 0.000000E+00 5 3.170832E+02 -1.222886E+02 -1.693808E+02 -2.680520E+02 + 5.699997E+00 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 5.699997E+00 3.000000E+01 1 2.096853E+01 -9.330057E+01 -1.207242E+00 -2.093375E+01 + 5.699997E+00 3.000000E+01 2 2.260131E+01 -1.422039E+02 -1.785948E+01 -1.385128E+01 + 5.699997E+00 3.000000E+01 3 5.475793E+00 1.603896E+02 -5.158177E+00 1.837805E+00 + 5.699997E+00 3.000000E+01 4 1.118138E+02 -1.527302E+02 -9.938672E+01 -5.123090E+01 + 5.699997E+00 3.000000E+01 5 1.962200E+02 -1.298908E+02 -1.258410E+02 -1.505534E+02 + 5.699997E+00 3.000000E+01 6 9.383300E+02 -1.705120E+02 -9.254937E+02 -1.546758E+02 + 5.699997E+00 6.000000E+01 1 2.851969E+01 9.417486E+01 -2.076246E+00 2.844401E+01 + 5.699997E+00 6.000000E+01 2 3.630803E+01 1.065696E+02 -1.035434E+01 3.480030E+01 + 5.699997E+00 6.000000E+01 3 1.446616E+01 1.567466E+02 -1.329104E+01 5.711210E+00 + 5.699997E+00 6.000000E+01 4 2.705252E+02 1.031721E+02 -6.164660E+01 2.634077E+02 + 5.699997E+00 6.000000E+01 5 3.876318E+02 -9.183718E+01 -1.242720E+01 -3.874325E+02 + 5.699997E+00 6.000000E+01 6 2.813971E+03 -1.170341E+01 2.755471E+03 -5.708015E+02 + 5.699997E+00 9.000000E+01 1 1.160414E-05 -9.919559E+01 -1.854404E-06 -1.145501E-05 + 5.699997E+00 9.000000E+01 2 1.901039E+02 8.490704E+01 1.687589E+01 1.893534E+02 + 5.699997E+00 9.000000E+01 3 2.071064E+01 1.619549E+02 -1.969195E+01 6.415437E+00 + 5.699997E+00 9.000000E+01 4 1.048984E+03 8.548279E+01 8.261642E+01 1.045725E+03 + 5.699997E+00 9.000000E+01 5 2.191727E-04 -8.631281E+01 1.409480E-05 -2.187190E-04 + 5.699997E+00 9.000000E+01 6 5.074404E-04 1.735952E+02 -5.042733E-04 5.660590E-05 + 5.799997E+00 0.000000E+00 1 1.144484E+01 8.563708E+01 8.706529E-01 1.141168E+01 + 5.799997E+00 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 5.799997E+00 0.000000E+00 3 3.805194E+00 -1.636273E+02 -3.650888E+00 -1.072621E+00 + 5.799997E+00 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 5.799997E+00 0.000000E+00 5 3.429525E+02 -1.236140E+02 -1.898565E+02 -2.856062E+02 + 5.799997E+00 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 5.799997E+00 3.000000E+01 1 1.604464E+01 -9.196248E+01 -5.494484E-01 -1.603523E+01 + 5.799997E+00 3.000000E+01 2 2.052374E+01 -1.434422E+02 -1.648582E+01 -1.222463E+01 + 5.799997E+00 3.000000E+01 3 6.704503E+00 1.643690E+02 -6.456552E+00 1.806462E+00 + 5.799997E+00 3.000000E+01 4 1.021577E+02 -1.530744E+02 -9.108334E+01 -4.626033E+01 + 5.799997E+00 3.000000E+01 5 2.396104E+02 -1.253522E+02 -1.386386E+02 -1.954289E+02 + 5.799997E+00 3.000000E+01 6 6.452072E+02 -1.617413E+02 -6.127220E+02 -2.021487E+02 + 5.799997E+00 6.000000E+01 1 3.476017E+01 9.361497E+01 -2.191678E+00 3.469101E+01 + 5.799997E+00 6.000000E+01 2 4.661618E+01 1.009082E+02 -8.821434E+00 4.577390E+01 + 5.799997E+00 6.000000E+01 3 1.579199E+01 1.583885E+02 -1.468185E+01 5.816370E+00 + 5.799997E+00 6.000000E+01 4 3.137964E+02 9.947241E+01 -5.164229E+01 3.095178E+02 + 5.799997E+00 6.000000E+01 5 4.002642E+02 -9.174596E+01 -1.219529E+01 -4.000784E+02 + 5.799997E+00 6.000000E+01 6 2.839525E+03 -1.151507E+01 2.782372E+03 -5.668420E+02 + 5.799997E+00 9.000000E+01 1 1.179089E-05 -9.829910E+01 -1.701904E-06 -1.166742E-05 + 5.799997E+00 9.000000E+01 2 1.939394E+02 8.534341E+01 1.574466E+01 1.932993E+02 + 5.799997E+00 9.000000E+01 3 2.133052E+01 1.623423E+02 -2.032555E+01 6.470180E+00 + 5.799997E+00 9.000000E+01 4 1.065437E+03 8.572481E+01 7.942514E+01 1.062473E+03 + 5.799997E+00 9.000000E+01 5 2.244461E-04 -8.658265E+01 1.337895E-05 -2.240470E-04 + 5.799997E+00 9.000000E+01 6 4.829921E-04 1.736989E+02 -4.800743E-04 5.300975E-05 + 5.899997E+00 0.000000E+00 1 8.392694E+00 7.358714E+01 2.371412E+00 8.050696E+00 + 5.899997E+00 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 5.899997E+00 0.000000E+00 3 4.499769E+00 -1.656466E+02 -4.359310E+00 -1.115499E+00 + 5.899997E+00 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 5.899997E+00 0.000000E+00 5 3.747024E+02 -1.236756E+02 -2.077689E+02 -3.118236E+02 + 5.899997E+00 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 5.899997E+00 3.000000E+01 1 1.042408E+01 -8.704988E+01 5.364913E-01 -1.041026E+01 + 5.899997E+00 3.000000E+01 2 1.789810E+01 -1.466397E+02 -1.494902E+01 -9.842196E+00 + 5.899997E+00 3.000000E+01 3 7.883803E+00 1.668464E+02 -7.676961E+00 1.794051E+00 + 5.899997E+00 3.000000E+01 4 9.039412E+01 -1.552851E+02 -8.211400E+01 -3.779402E+01 + 5.899997E+00 3.000000E+01 5 2.828014E+02 -1.217937E+02 -1.489974E+02 -2.403673E+02 + 5.899997E+00 3.000000E+01 6 4.059503E+02 -1.446949E+02 -3.312903E+02 -2.346111E+02 + 5.899997E+00 6.000000E+01 1 4.046095E+01 9.303251E+01 -2.140489E+00 4.040429E+01 + 5.899997E+00 6.000000E+01 2 5.636086E+01 9.735036E+01 -7.210611E+00 5.589771E+01 + 5.899997E+00 6.000000E+01 3 1.685619E+01 1.600059E+02 -1.584023E+01 5.763529E+00 + 5.899997E+00 6.000000E+01 4 3.544296E+02 9.673380E+01 -4.155926E+01 3.519846E+02 + 5.899997E+00 6.000000E+01 5 4.080023E+02 -9.158569E+01 -1.129021E+01 -4.078460E+02 + 5.899997E+00 6.000000E+01 6 2.851611E+03 -1.127238E+01 2.796601E+03 -5.574141E+02 + 5.899997E+00 9.000000E+01 1 1.193312E-05 -9.731239E+01 -1.518836E-06 -1.183606E-05 + 5.899997E+00 9.000000E+01 2 1.970907E+02 8.566570E+01 1.489529E+01 1.965271E+02 + 5.899997E+00 9.000000E+01 3 2.163098E+01 1.630303E+02 -2.068915E+01 6.313335E+00 + 5.899997E+00 9.000000E+01 4 1.077874E+03 8.590173E+01 7.703280E+01 1.075118E+03 + 5.899997E+00 9.000000E+01 5 2.292903E-04 -8.679324E+01 1.282634E-05 -2.289313E-04 + 5.899997E+00 9.000000E+01 6 4.599442E-04 1.738406E+02 -4.572890E-04 4.934994E-05 + 5.999997E+00 0.000000E+00 1 8.249591E+00 5.801945E+01 4.369242E+00 6.997534E+00 + 5.999997E+00 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 5.999997E+00 0.000000E+00 3 5.187577E+00 -1.681797E+02 -5.077574E+00 -1.062639E+00 + 5.999997E+00 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 5.999997E+00 0.000000E+00 5 4.092494E+02 -1.227191E+02 -2.212080E+02 -3.443139E+02 + 5.999997E+00 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 5.999997E+00 3.000000E+01 1 4.531404E+00 -6.442155E+01 1.956418E+00 -4.087304E+00 + 5.999997E+00 3.000000E+01 2 1.500057E+01 -1.527637E+02 -1.333741E+01 -6.865170E+00 + 5.999997E+00 3.000000E+01 3 8.973127E+00 1.685330E+02 -8.794018E+00 1.783891E+00 + 5.999997E+00 3.000000E+01 4 7.756216E+01 -1.600227E+02 -7.289507E+01 -2.649899E+01 + 5.999997E+00 3.000000E+01 5 3.239916E+02 -1.187229E+02 -1.557018E+02 -2.841259E+02 + 5.999997E+00 3.000000E+01 6 2.677123E+02 -1.074318E+02 -8.019846E+01 -2.554175E+02 + 5.999997E+00 6.000000E+01 1 4.569069E+01 9.251271E+01 -2.003130E+00 4.564676E+01 + 5.999997E+00 6.000000E+01 2 6.546344E+01 9.488390E+01 -5.573354E+00 6.522576E+01 + 5.999997E+00 6.000000E+01 3 1.762659E+01 1.616013E+02 -1.672557E+01 5.563430E+00 + 5.999997E+00 6.000000E+01 4 3.922416E+02 9.462893E+01 -3.165479E+01 3.909622E+02 + 5.999997E+00 6.000000E+01 5 4.110932E+02 -9.133858E+01 -9.603373E+00 -4.109810E+02 + 5.999997E+00 6.000000E+01 6 2.851342E+03 -1.097183E+01 2.799222E+03 -5.426855E+02 + 5.999997E+00 9.000000E+01 1 1.202753E-05 -9.627190E+01 -1.313971E-06 -1.195555E-05 + 5.999997E+00 9.000000E+01 2 1.996523E+02 8.589021E+01 1.430868E+01 1.991389E+02 + 5.999997E+00 9.000000E+01 3 2.159931E+01 1.639290E+02 -2.075520E+01 5.979290E+00 + 5.999997E+00 9.000000E+01 4 1.086781E+03 8.602073E+01 7.541784E+01 1.084161E+03 + 5.999997E+00 9.000000E+01 5 2.336553E-04 -8.696281E+01 1.238002E-05 -2.333271E-04 + 5.999997E+00 9.000000E+01 6 4.381380E-04 1.740168E+02 -4.357513E-04 4.567037E-05 + 6.099997E+00 0.000000E+00 1 1.046364E+01 5.035596E+01 6.675972E+00 8.057245E+00 + 6.099997E+00 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 6.099997E+00 0.000000E+00 3 5.866732E+00 -1.707883E+02 -5.791072E+00 -9.391614E-01 + 6.099997E+00 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 6.099997E+00 0.000000E+00 5 4.436782E+02 -1.210020E+02 -2.285244E+02 -3.802985E+02 + 6.099997E+00 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 6.099997E+00 3.000000E+01 1 4.574429E+00 3.900104E+01 3.554947E+00 2.878845E+00 + 6.099997E+00 3.000000E+01 2 1.221256E+01 -1.636316E+02 -1.171758E+01 -3.441653E+00 + 6.099997E+00 3.000000E+01 3 9.939134E+00 1.697807E+02 -9.781460E+00 1.763356E+00 + 6.099997E+00 3.000000E+01 4 6.506376E+01 -1.684614E+02 -6.374884E+01 -1.301454E+01 + 6.099997E+00 3.000000E+01 5 3.614323E+02 -1.158878E+02 -1.578053E+02 -3.251627E+02 + 6.099997E+00 3.000000E+01 6 3.025023E+02 -6.198606E+01 1.420812E+02 -2.670591E+02 + 6.099997E+00 6.000000E+01 1 5.048534E+01 9.209763E+01 -1.847879E+00 5.045151E+01 + 6.099997E+00 6.000000E+01 2 7.391103E+01 9.306325E+01 -3.949679E+00 7.380543E+01 + 6.099997E+00 6.000000E+01 3 1.808422E+01 1.631641E+02 -1.730909E+01 5.237776E+00 + 6.099997E+00 6.000000E+01 4 4.271609E+02 9.296829E+01 -2.211983E+01 4.265879E+02 + 6.099997E+00 6.000000E+01 5 4.097423E+02 -9.100600E+01 -7.193880E+00 -4.096792E+02 + 6.099997E+00 6.000000E+01 6 2.839707E+03 -1.061555E+01 2.791107E+03 -5.231253E+02 + 6.099997E+00 9.000000E+01 1 1.207376E-05 -9.521217E+01 -1.096832E-06 -1.202384E-05 + 6.099997E+00 9.000000E+01 2 2.017121E+02 8.603269E+01 1.395591E+01 2.012287E+02 + 6.099997E+00 9.000000E+01 3 2.123364E+01 1.649668E+02 -2.050693E+01 5.507566E+00 + 6.099997E+00 9.000000E+01 4 1.092631E+03 8.608970E+01 7.451158E+01 1.090088E+03 + 6.099997E+00 9.000000E+01 5 2.375192E-04 -8.711062E+01 1.197284E-05 -2.372173E-04 + 6.099997E+00 9.000000E+01 6 4.174509E-04 1.742228E+02 -4.153306E-04 4.202110E-05 + 6.199996E+00 0.000000E+00 1 1.423732E+01 5.055992E+01 9.044558E+00 1.099533E+01 + 6.199996E+00 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 6.199996E+00 0.000000E+00 3 6.524652E+00 -1.732178E+02 -6.478994E+00 -7.705297E-01 + 6.199996E+00 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 6.199996E+00 0.000000E+00 5 4.753039E+02 -1.187623E+02 -2.287052E+02 -4.166626E+02 + 6.199996E+00 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 6.199996E+00 3.000000E+01 1 1.159182E+01 6.364566E+01 5.145857E+00 1.038704E+01 + 6.199996E+00 3.000000E+01 2 1.014111E+01 1.783265E+02 -1.013678E+01 2.961683E-01 + 6.199996E+00 3.000000E+01 3 1.075400E+01 1.707731E+02 -1.061486E+01 1.724348E+00 + 6.199996E+00 3.000000E+01 4 5.494801E+01 1.778411E+02 -5.490900E+01 2.069896E+00 + 6.199996E+00 3.000000E+01 5 3.935418E+02 -1.131767E+02 -1.548857E+02 -3.617812E+02 + 6.199996E+00 3.000000E+01 6 4.329815E+02 -3.882263E+01 3.373317E+02 -2.714411E+02 + 6.199996E+00 6.000000E+01 1 5.485495E+01 9.180088E+01 -1.723876E+00 5.482785E+01 + 6.199996E+00 6.000000E+01 2 8.171471E+01 9.166198E+01 -2.369965E+00 8.168033E+01 + 6.199996E+00 6.000000E+01 3 1.822185E+01 1.646790E+02 -1.757425E+01 4.814692E+00 + 6.199996E+00 6.000000E+01 4 4.591909E+02 9.163345E+01 -1.308932E+01 4.590043E+02 + 6.199996E+00 6.000000E+01 5 4.041983E+02 -9.060629E+01 -4.277046E+00 -4.041757E+02 + 6.199996E+00 6.000000E+01 6 2.817646E+03 -1.020965E+01 2.773031E+03 -4.994294E+02 + 6.199996E+00 9.000000E+01 1 1.207343E-05 -9.416452E+01 -8.767791E-07 -1.204155E-05 + 6.199996E+00 9.000000E+01 2 2.033479E+02 8.610851E+01 1.380067E+01 2.028790E+02 + 6.199996E+00 9.000000E+01 3 2.054312E+01 1.660861E+02 -1.994034E+01 4.939880E+00 + 6.199996E+00 9.000000E+01 4 1.095863E+03 8.611726E+01 7.420622E+01 1.093347E+03 + 6.199996E+00 9.000000E+01 5 2.409031E-04 -8.725345E+01 1.154361E-05 -2.406263E-04 + 6.199996E+00 9.000000E+01 6 3.977880E-04 1.744530E+02 -3.959252E-04 3.845130E-05 + 6.299996E+00 0.000000E+00 1 1.914362E+01 5.413163E+01 1.121673E+01 1.551332E+01 + 6.299996E+00 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 6.299996E+00 0.000000E+00 3 7.141086E+00 -1.753409E+02 -7.117488E+00 -5.800562E-01 + 6.299996E+00 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 6.299996E+00 0.000000E+00 5 5.019013E+02 -1.162051E+02 -2.216324E+02 -4.503155E+02 + 6.299996E+00 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 6.299996E+00 3.000000E+01 1 1.941873E+01 7.028712E+01 6.550072E+00 1.828069E+01 + 6.299996E+00 3.000000E+01 2 9.609566E+00 1.538569E+02 -8.626476E+00 4.234107E+00 + 6.299996E+00 3.000000E+01 3 1.139540E+01 1.716096E+02 -1.127343E+01 1.662793E+00 + 6.299996E+00 3.000000E+01 4 4.997646E+01 1.586054E+02 -4.653260E+01 1.823085E+01 + 6.299996E+00 3.000000E+01 5 4.190488E+02 -1.105592E+02 -1.471591E+02 -3.923597E+02 + 6.299996E+00 3.000000E+01 6 5.748251E+02 -2.802354E+01 5.074295E+02 -2.700725E+02 + 6.299996E+00 6.000000E+01 1 5.879642E+01 9.161513E+01 -1.657208E+00 5.877306E+01 + 6.299996E+00 6.000000E+01 2 8.889552E+01 9.055240E+01 -8.570521E-01 8.889138E+01 + 6.299996E+00 6.000000E+01 3 1.804291E+01 1.661316E+02 -1.751694E+01 4.324758E+00 + 6.299996E+00 6.000000E+01 4 4.883799E+02 9.054623E+01 -4.655920E+00 4.883577E+02 + 6.299996E+00 6.000000E+01 5 3.947912E+02 -9.016973E+01 -1.169526E+00 -3.947895E+02 + 6.299996E+00 6.000000E+01 6 2.786145E+03 -9.762721E+00 2.745798E+03 -4.724420E+02 + 6.299996E+00 9.000000E+01 1 1.203010E-05 -9.315540E+01 -6.621877E-07 -1.201186E-05 + 6.299996E+00 9.000000E+01 2 2.046265E+02 8.613224E+01 1.380285E+01 2.041604E+02 + 6.299996E+00 9.000000E+01 3 1.954493E+01 1.672406E+02 -1.906229E+01 4.316647E+00 + 6.299996E+00 9.000000E+01 4 1.096852E+03 8.611218E+01 7.436994E+01 1.094328E+03 + 6.299996E+00 9.000000E+01 5 2.438480E-04 -8.740331E+01 1.104761E-05 -2.435977E-04 + 6.299996E+00 9.000000E+01 6 3.790760E-04 1.747016E+02 -3.774563E-04 3.500461E-05 + 6.399996E+00 0.000000E+00 1 2.490040E+01 5.859365E+01 1.297570E+01 2.125232E+01 + 6.399996E+00 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 6.399996E+00 0.000000E+00 3 7.690893E+00 -1.771123E+02 -7.681128E+00 -3.874537E-01 + 6.399996E+00 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 6.399996E+00 0.000000E+00 5 5.218397E+02 -1.135057E+02 -2.081304E+02 -4.785378E+02 + 6.399996E+00 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 6.399996E+00 3.000000E+01 1 2.744187E+01 7.385473E+01 7.630864E+00 2.635955E+01 + 6.399996E+00 3.000000E+01 2 1.097380E+01 1.310448E+02 -7.205935E+00 8.276397E+00 + 6.399996E+00 3.000000E+01 3 1.184639E+01 1.723465E+02 -1.174086E+01 1.577718E+00 + 6.399996E+00 3.000000E+01 4 5.220620E+01 1.378680E+02 -3.871618E+01 3.502207E+01 + 6.399996E+00 3.000000E+01 5 4.371505E+02 -1.080518E+02 -1.354627E+02 -4.156325E+02 + 6.399996E+00 3.000000E+01 6 7.056147E+02 -2.198862E+01 6.542870E+02 -2.641980E+02 + 6.399996E+00 6.000000E+01 1 6.230491E+01 9.151879E+01 -1.651382E+00 6.228302E+01 + 6.399996E+00 6.000000E+01 2 9.548029E+01 8.965668E+01 5.721323E-01 9.547857E+01 + 6.399996E+00 6.000000E+01 3 1.755966E+01 1.675099E+02 -1.714409E+01 3.797630E+00 + 6.399996E+00 6.000000E+01 4 5.148070E+02 8.965267E+01 3.120712E+00 5.147975E+02 + 6.399996E+00 6.000000E+01 5 3.819733E+02 -8.973202E+01 1.786511E+00 -3.819691E+02 + 6.399996E+00 6.000000E+01 6 2.746226E+03 -9.284508E+00 2.710248E+03 -4.430677E+02 + 6.399996E+00 9.000000E+01 1 1.194856E-05 -9.220567E+01 -4.598603E-07 -1.193971E-05 + 6.399996E+00 9.000000E+01 2 2.056012E+02 8.611742E+01 1.392169E+01 2.051293E+02 + 6.399996E+00 9.000000E+01 3 1.826296E+01 1.683928E+02 -1.788948E+01 3.674524E+00 + 6.399996E+00 9.000000E+01 4 1.095928E+03 8.608315E+01 7.486142E+01 1.093369E+03 + 6.399996E+00 9.000000E+01 5 2.464013E-04 -8.756695E+01 1.046024E-05 -2.461792E-04 + 6.399996E+00 9.000000E+01 6 3.612580E-04 1.749633E+02 -3.598631E-04 3.171640E-05 + 6.499996E+00 0.000000E+00 1 3.122998E+01 6.298394E+01 1.418592E+01 2.782214E+01 + 6.499996E+00 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 6.499996E+00 0.000000E+00 3 8.148113E+00 -1.785369E+02 -8.145456E+00 -2.080519E-01 + 6.499996E+00 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 6.499996E+00 0.000000E+00 5 5.342173E+02 -1.108041E+02 -1.897402E+02 -4.993865E+02 + 6.499996E+00 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 6.499996E+00 3.000000E+01 1 3.539780E+01 7.641184E+01 8.316403E+00 3.440700E+01 + 6.499996E+00 3.000000E+01 2 1.367614E+01 1.154904E+02 -5.885651E+00 1.234487E+01 + 6.499996E+00 3.000000E+01 3 1.209567E+01 1.730168E+02 -1.200595E+01 1.470577E+00 + 6.499996E+00 3.000000E+01 4 6.085913E+01 1.211826E+02 -3.151083E+01 5.206631E+01 + 6.499996E+00 3.000000E+01 5 4.475864E+02 -1.056898E+02 -1.210405E+02 -4.309092E+02 + 6.499996E+00 3.000000E+01 6 8.204029E+02 -1.809916E+01 7.798096E+02 -2.548684E+02 + 6.499996E+00 6.000000E+01 1 6.538300E+01 9.148339E+01 -1.692576E+00 6.536109E+01 + 6.499996E+00 6.000000E+01 2 1.014976E+02 8.892442E+01 1.905245E+00 1.014797E+02 + 6.499996E+00 6.000000E+01 3 1.678957E+01 1.688050E+02 -1.647010E+01 3.259687E+00 + 6.499996E+00 6.000000E+01 4 5.385770E+02 8.891418E+01 1.020595E+01 5.384803E+02 + 6.499996E+00 6.000000E+01 5 3.662848E+02 -8.932704E+01 4.302074E+00 -3.662596E+02 + 6.499996E+00 6.000000E+01 6 2.698946E+03 -8.785026E+00 2.667282E+03 -4.122033E+02 + 6.499996E+00 9.000000E+01 1 1.183456E-05 -9.133024E+01 -2.747390E-07 -1.183137E-05 + 6.499996E+00 9.000000E+01 2 2.063142E+02 8.607605E+01 1.411855E+01 2.058306E+02 + 6.499996E+00 9.000000E+01 3 1.672458E+01 1.695131E+02 -1.644522E+01 3.044042E+00 + 6.499996E+00 9.000000E+01 4 1.093365E+03 8.603822E+01 7.554176E+01 1.090752E+03 + 6.499996E+00 9.000000E+01 5 2.486224E-04 -8.774632E+01 9.776836E-06 -2.484300E-04 + 6.499996E+00 9.000000E+01 6 3.442881E-04 1.752327E+02 -3.430970E-04 2.861344E-05 + 6.599996E+00 0.000000E+00 1 3.786176E+01 6.697951E+01 1.480623E+01 3.484664E+01 + 6.599996E+00 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 6.599996E+00 0.000000E+00 3 8.487835E+00 -1.796442E+02 -8.487671E+00 -5.270457E-02 + 6.599996E+00 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 6.599996E+00 0.000000E+00 5 5.388351E+02 -1.082077E+02 -1.683661E+02 -5.118555E+02 + 6.599996E+00 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 6.599996E+00 3.000000E+01 1 4.308966E+01 7.848481E+01 8.601892E+00 4.222235E+01 + 6.599996E+00 3.000000E+01 2 1.702968E+01 1.059161E+02 -4.670047E+00 1.637683E+01 + 6.599996E+00 3.000000E+01 3 1.213597E+01 1.736402E+02 -1.206129E+01 1.344316E+00 + 6.599996E+00 3.000000E+01 4 7.342095E+01 1.098535E+02 -2.493490E+01 6.905713E+01 + 6.599996E+00 3.000000E+01 5 4.506039E+02 -1.035107E+02 -1.052731E+02 -4.381340E+02 + 6.599996E+00 3.000000E+01 6 9.185867E+02 -1.533850E+01 8.858665E+02 -2.429855E+02 + 6.599996E+00 6.000000E+01 1 6.804441E+01 9.148019E+01 -1.757680E+00 6.802171E+01 + 6.599996E+00 6.000000E+01 2 1.069763E+02 8.832145E+01 3.133549E+00 1.069304E+02 + 6.599996E+00 6.000000E+01 3 1.575467E+01 1.700105E+02 -1.551582E+01 2.732924E+00 + 6.599996E+00 6.000000E+01 4 5.598049E+02 8.830235E+01 1.658437E+01 5.595591E+02 + 6.599996E+00 6.000000E+01 5 3.483130E+02 -8.898127E+01 6.192752E+00 -3.482580E+02 + 6.599996E+00 6.000000E+01 6 2.645371E+03 -8.273825E+00 2.617837E+03 -3.806798E+02 + 6.599996E+00 9.000000E+01 1 1.169387E-05 -9.053847E+01 -1.098983E-07 -1.169335E-05 + 6.599996E+00 9.000000E+01 2 2.067984E+02 8.601857E+01 1.435866E+01 2.062993E+02 + 6.599996E+00 9.000000E+01 3 1.495983E+01 1.705767E+02 -1.475796E+01 2.449327E+00 + 6.599996E+00 9.000000E+01 4 1.089383E+03 8.598453E+01 7.628492E+01 1.086709E+03 + 6.599996E+00 9.000000E+01 5 2.505603E-04 -8.793982E+01 9.007451E-06 -2.503984E-04 + 6.599996E+00 9.000000E+01 6 3.281282E-04 1.755054E+02 -3.271191E-04 2.571375E-05 + 6.699996E+00 0.000000E+00 1 4.455798E+01 7.049490E+01 1.487750E+01 4.200088E+01 + 6.699996E+00 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 6.699996E+00 0.000000E+00 3 8.688542E+00 1.795257E+02 -8.688245E+00 7.192025E-02 + 6.699996E+00 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 6.699996E+00 0.000000E+00 5 5.360759E+02 -1.057896E+02 -1.458690E+02 -5.158484E+02 + 6.699996E+00 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 6.699996E+00 3.000000E+01 1 5.037367E+01 8.024486E+01 8.535211E+00 4.964531E+01 + 6.699996E+00 3.000000E+01 2 2.063268E+01 9.993425E+01 -3.559507E+00 2.032333E+01 + 6.699996E+00 3.000000E+01 3 1.196493E+01 1.742294E+02 -1.190430E+01 1.203019E+00 + 6.699996E+00 3.000000E+01 4 8.782640E+01 1.024838E+02 -1.898485E+01 8.574994E+01 + 6.699996E+00 3.000000E+01 5 4.468409E+02 -1.015424E+02 -8.940945E+01 -4.378044E+02 + 6.699996E+00 3.000000E+01 6 1.000911E+03 -1.324486E+01 9.742869E+02 -2.293219E+02 + 6.699996E+00 6.000000E+01 1 7.031628E+01 9.148508E+01 -1.822360E+00 7.029266E+01 + 6.699996E+00 6.000000E+01 2 1.119460E+02 8.782357E+01 4.251348E+00 1.118652E+02 + 6.699996E+00 6.000000E+01 3 1.447888E+01 1.711226E+02 -1.430544E+01 2.234383E+00 + 6.699996E+00 6.000000E+01 4 5.786184E+02 8.779576E+01 2.225468E+01 5.781902E+02 + 6.699996E+00 6.000000E+01 5 3.286430E+02 -8.871101E+01 7.392869E+00 -3.285598E+02 + 6.699996E+00 6.000000E+01 6 2.586569E+03 -7.759521E+00 2.562885E+03 -3.492271E+02 + 6.699996E+00 9.000000E+01 1 1.153209E-05 -8.983506E+01 3.319838E-08 -1.153204E-05 + 6.699996E+00 9.000000E+01 2 2.070776E+02 8.595363E+01 1.461220E+01 2.065614E+02 + 6.699996E+00 9.000000E+01 3 1.299832E+01 1.715605E+02 -1.285757E+01 1.907696E+00 + 6.699996E+00 9.000000E+01 4 1.084159E+03 8.592821E+01 7.698219E+01 1.081422E+03 + 6.699996E+00 9.000000E+01 5 2.522556E-04 -8.814351E+01 8.172125E-06 -2.521232E-04 + 6.699996E+00 9.000000E+01 6 3.127473E-04 1.757775E+02 -3.118984E-04 2.302751E-05 + 6.799996E+00 0.000000E+00 1 5.113235E+01 7.353231E+01 1.449473E+01 4.903489E+01 + 6.799996E+00 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 6.799996E+00 0.000000E+00 3 8.732897E+00 1.789313E+02 -8.731378E+00 1.628813E-01 + 6.799996E+00 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 6.799996E+00 0.000000E+00 5 5.266843E+02 -1.035937E+02 -1.237892E+02 -5.119302E+02 + 6.799996E+00 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 6.799996E+00 3.000000E+01 1 5.715731E+01 8.175683E+01 8.194915E+00 5.656678E+01 + 6.799996E+00 3.000000E+01 2 2.428172E+01 9.603278E+01 -2.551944E+00 2.414725E+01 + 6.799996E+00 3.000000E+01 3 1.158336E+01 1.747928E+02 -1.153555E+01 1.051281E+00 + 6.799996E+00 3.000000E+01 4 1.028631E+02 9.762134E+01 -1.364228E+01 1.019544E+02 + 6.799996E+00 3.000000E+01 5 4.371751E+02 -9.979926E+01 -7.440577E+01 -4.307968E+02 + 6.799996E+00 3.000000E+01 6 1.068589E+03 -1.158160E+01 1.046832E+03 -2.145334E+02 + 6.799996E+00 6.000000E+01 1 7.223330E+01 9.148089E+01 -1.866762E+00 7.220918E+01 + 6.799996E+00 6.000000E+01 2 1.164352E+02 8.741300E+01 5.255457E+00 1.163165E+02 + 6.799996E+00 6.000000E+01 3 1.298696E+01 1.721374E+02 -1.286487E+01 1.776593E+00 + 6.799996E+00 6.000000E+01 4 5.951456E+02 8.737786E+01 2.722735E+01 5.945225E+02 + 6.799996E+00 6.000000E+01 5 3.077865E+02 -8.852185E+01 7.939594E+00 -3.076841E+02 + 6.799996E+00 6.000000E+01 6 2.523560E+03 -7.249585E+00 2.503386E+03 -3.184525E+02 + 6.799996E+00 9.000000E+01 1 1.135437E-05 -8.922071E+01 1.544279E-07 -1.135332E-05 + 6.799996E+00 9.000000E+01 2 2.071705E+02 8.588818E+01 1.485480E+01 2.066373E+02 + 6.799996E+00 9.000000E+01 3 1.086942E+01 1.724371E+02 -1.077487E+01 1.430578E+00 + 6.799996E+00 9.000000E+01 4 1.077842E+03 8.587426E+01 7.754592E+01 1.075049E+03 + 6.799996E+00 9.000000E+01 5 2.537453E-04 -8.835240E+01 7.295710E-06 -2.536403E-04 + 6.799996E+00 9.000000E+01 6 2.981145E-04 1.760457E+02 -2.974048E-04 2.055814E-05 + 6.899996E+00 0.000000E+00 1 5.745194E+01 7.612595E+01 1.377632E+01 5.577579E+01 + 6.899996E+00 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 6.899996E+00 0.000000E+00 3 8.607684E+00 1.785334E+02 -8.604864E+00 2.203111E-01 + 6.899996E+00 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 6.899996E+00 0.000000E+00 5 5.116173E+02 -1.016391E+02 -1.032173E+02 -5.010972E+02 + 6.899996E+00 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 6.899996E+00 3.000000E+01 1 6.339461E+01 8.305264E+01 7.668045E+00 6.292915E+01 + 6.899996E+00 3.000000E+01 2 2.786877E+01 9.338131E+01 -1.643719E+00 2.782025E+01 + 6.899996E+00 3.000000E+01 3 1.099518E+01 1.753356E+02 -1.095876E+01 8.941151E-01 + 6.899996E+00 3.000000E+01 4 1.178615E+02 9.432112E+01 -8.880433E+00 1.175264E+02 + 6.899996E+00 3.000000E+01 5 4.225779E+02 -9.828252E+01 -6.087412E+01 -4.181703E+02 + 6.899996E+00 3.000000E+01 6 1.122989E+03 -1.021568E+01 1.105186E+03 -1.991666E+02 + 6.899996E+00 6.000000E+01 1 7.383486E+01 9.145753E+01 -1.878057E+00 7.381097E+01 + 6.899996E+00 6.000000E+01 2 1.204713E+02 8.707623E+01 6.144914E+00 1.203145E+02 + 6.899996E+00 6.000000E+01 3 1.130301E+01 1.730492E+02 -1.121993E+01 1.367863E+00 + 6.899996E+00 6.000000E+01 4 6.095179E+02 8.703556E+01 3.152198E+01 6.087022E+02 + 6.899996E+00 6.000000E+01 5 2.861794E+02 -8.841126E+01 7.934399E+00 -2.860694E+02 + 6.899996E+00 6.000000E+01 6 2.457310E+03 -6.750232E+00 2.440276E+03 -2.888357E+02 + 6.899996E+00 9.000000E+01 1 1.116526E-05 -8.869334E+01 2.546057E-07 -1.116236E-05 + 6.899996E+00 9.000000E+01 2 2.070912E+02 8.582763E+01 1.506740E+01 2.065423E+02 + 6.899996E+00 9.000000E+01 3 8.599986E+00 1.731607E+02 -8.538789E+00 1.024133E+00 + 6.899996E+00 9.000000E+01 4 1.070553E+03 8.582662E+01 7.790929E+01 1.067714E+03 + 6.899996E+00 9.000000E+01 5 2.550481E-04 -8.856126E+01 6.403743E-06 -2.549677E-04 + 6.899996E+00 9.000000E+01 6 2.842032E-04 1.763074E+02 -2.836132E-04 1.830359E-05 + 6.999996E+00 0.000000E+00 1 6.343251E+01 7.832144E+01 1.284006E+01 6.211937E+01 + 6.999996E+00 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 6.999996E+00 0.000000E+00 3 8.304324E+00 1.782966E+02 -8.300654E+00 2.468486E-01 + 6.999996E+00 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 6.999996E+00 0.000000E+00 5 4.918595E+02 -9.992722E+01 -8.479517E+01 -4.844952E+02 + 6.999996E+00 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 6.999996E+00 3.000000E+01 1 6.907496E+01 8.415459E+01 7.034931E+00 6.871579E+01 + 6.999996E+00 3.000000E+01 2 3.133360E+01 9.151859E+01 -8.303803E-01 3.132260E+01 + 6.999996E+00 3.000000E+01 3 1.020716E+01 1.758622E+02 -1.018056E+01 7.364960E-01 + 6.999996E+00 3.000000E+01 4 1.324410E+02 9.201951E+01 -4.667178E+00 1.323587E+02 + 6.999996E+00 3.000000E+01 5 4.039922E+02 -9.698272E+01 -4.911329E+01 -4.009958E+02 + 6.999996E+00 3.000000E+01 6 1.165503E+03 -9.066772E+00 1.150941E+03 -1.836663E+02 + 6.999996E+00 6.000000E+01 1 7.516010E+01 9.141090E+01 -1.850616E+00 7.513731E+01 + 6.999996E+00 6.000000E+01 2 1.240806E+02 8.680267E+01 6.920580E+00 1.238875E+02 + 6.999996E+00 6.000000E+01 3 9.450929E+00 1.738460E+02 -9.396466E+00 1.013153E+00 + 6.999996E+00 6.000000E+01 4 6.218619E+02 8.675819E+01 3.516629E+01 6.208668E+02 + 6.999996E+00 6.000000E+01 5 2.641574E+02 -8.837112E+01 7.508770E+00 -2.640507E+02 + 6.999996E+00 6.000000E+01 6 2.388713E+03 -6.266428E+00 2.374440E+03 -2.607325E+02 + 6.999996E+00 9.000000E+01 1 1.096863E-05 -8.824891E+01 3.351755E-07 -1.096351E-05 + 6.999996E+00 9.000000E+01 2 2.068489E+02 8.577593E+01 1.523589E+01 2.062870E+02 + 6.999996E+00 9.000000E+01 3 6.214508E+00 1.736199E+02 -6.176019E+00 6.905746E-01 + 6.999996E+00 9.000000E+01 4 1.062390E+03 8.578819E+01 7.802592E+01 1.059521E+03 + 6.999996E+00 9.000000E+01 5 2.561845E-04 -8.876540E+01 5.519805E-06 -2.561250E-04 + 6.999996E+00 9.000000E+01 6 2.709863E-04 1.765605E+02 -2.704981E-04 1.625756E-05 + 7.099996E+00 0.000000E+00 1 6.902799E+01 8.016754E+01 1.178775E+01 6.801406E+01 + 7.099996E+00 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 7.099996E+00 0.000000E+00 3 7.818867E+00 1.781913E+02 -7.814971E+00 2.467834E-01 + 7.099996E+00 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 7.099996E+00 0.000000E+00 5 4.683553E+02 -9.844705E+01 -6.879926E+01 -4.632746E+02 + 7.099996E+00 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 7.099996E+00 3.000000E+01 1 7.421140E+01 8.508284E+01 6.361053E+00 7.393828E+01 + 7.099996E+00 3.000000E+01 2 3.464056E+01 9.017688E+01 -1.069370E-01 3.464040E+01 + 7.099996E+00 3.000000E+01 3 9.228217E+00 1.763761E+02 -9.209764E+00 5.832899E-01 + 7.099996E+00 3.000000E+01 4 1.463782E+02 9.037870E+01 -9.674802E-01 1.463750E+02 + 7.099996E+00 3.000000E+01 5 3.822705E+02 -9.588326E+01 -3.918346E+01 -3.802570E+02 + 7.099996E+00 3.000000E+01 6 1.197489E+03 -8.083371E+00 1.185591E+03 -1.683836E+02 + 7.099996E+00 6.000000E+01 1 7.624609E+01 9.134110E+01 -1.784504E+00 7.622520E+01 + 7.099996E+00 6.000000E+01 2 1.272887E+02 8.658373E+01 7.585104E+00 1.270625E+02 + 7.099996E+00 6.000000E+01 3 7.452615E+00 1.744976E+02 -7.418275E+00 7.146100E-01 + 7.099996E+00 6.000000E+01 4 6.323093E+02 8.653707E+01 3.819326E+01 6.311547E+02 + 7.099996E+00 6.000000E+01 5 2.420005E+02 -8.839009E+01 6.798873E+00 -2.419050E+02 + 7.099996E+00 6.000000E+01 6 2.318564E+03 -5.801970E+00 2.306687E+03 -2.343848E+02 + 7.099996E+00 9.000000E+01 1 1.076766E-05 -8.788194E+01 3.979592E-07 -1.076031E-05 + 7.099996E+00 9.000000E+01 2 2.064532E+02 8.573586E+01 1.535073E+01 2.058817E+02 + 7.099996E+00 9.000000E+01 3 3.737227E+00 1.734104E+02 -3.712537E+00 4.288726E-01 + 7.099996E+00 9.000000E+01 4 1.053439E+03 8.576096E+01 7.786783E+01 1.050557E+03 + 7.099996E+00 9.000000E+01 5 2.571575E-04 -8.896078E+01 4.663993E-06 -2.571152E-04 + 7.099996E+00 9.000000E+01 6 2.584371E-04 1.768035E+02 -2.580350E-04 1.441059E-05 + 7.199996E+00 0.000000E+00 1 7.421930E+01 8.171126E+01 1.069959E+01 7.344402E+01 + 7.199996E+00 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 7.199996E+00 0.000000E+00 3 7.150705E+00 1.781928E+02 -7.147148E+00 2.255081E-01 + 7.199996E+00 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 7.199996E+00 0.000000E+00 5 4.419293E+02 -9.717999E+01 -5.523533E+01 -4.384639E+02 + 7.199996E+00 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 7.199996E+00 3.000000E+01 1 7.883245E+01 8.585766E+01 5.694427E+00 7.862652E+01 + 7.199996E+00 3.000000E+01 2 3.776899E+01 8.919318E+01 5.318334E-01 3.776524E+01 + 7.199996E+00 3.000000E+01 3 8.068378E+00 1.768814E+02 -8.056430E+00 4.389446E-01 + 7.199996E+00 3.000000E+01 4 1.595447E+02 8.919025E+01 2.254713E+00 1.595288E+02 + 7.199996E+00 3.000000E+01 5 3.581570E+02 -9.496335E+01 -3.098722E+01 -3.568139E+02 + 7.199996E+00 3.000000E+01 6 1.220220E+03 -7.230842E+00 1.210516E+03 -1.535857E+02 + 7.199996E+00 6.000000E+01 1 7.712525E+01 9.125092E+01 -1.683711E+00 7.710687E+01 + 7.199996E+00 6.000000E+01 2 1.301200E+02 8.641229E+01 8.142446E+00 1.298650E+02 + 7.199996E+00 6.000000E+01 3 5.329028E+00 1.749167E+02 -5.308068E+00 4.721779E-01 + 7.199996E+00 6.000000E+01 4 6.409879E+02 8.636476E+01 4.064141E+01 6.396981E+02 + 7.199996E+00 6.000000E+01 5 2.198767E+02 -8.845608E+01 5.924181E+00 -2.197969E+02 + 7.199996E+00 6.000000E+01 6 2.247585E+03 -5.359552E+00 2.237759E+03 -2.099368E+02 + 7.199996E+00 9.000000E+01 1 1.056503E-05 -8.758630E+01 4.449422E-07 -1.055565E-05 + 7.199996E+00 9.000000E+01 2 2.059109E+02 8.570915E+01 1.540616E+01 2.053338E+02 + 7.199996E+00 9.000000E+01 3 1.192611E+00 1.686046E+02 -1.169101E+00 2.356335E-01 + 7.199996E+00 9.000000E+01 4 1.043784E+03 8.574621E+01 7.742220E+01 1.040909E+03 + 7.199996E+00 9.000000E+01 5 2.579798E-04 -8.914448E+01 3.851947E-06 -2.579511E-04 + 7.199996E+00 9.000000E+01 6 2.465296E-04 1.770352E+02 -2.461996E-04 1.275104E-05 + 7.299995E+00 0.000000E+00 1 7.900702E+01 8.299664E+01 9.633142E+00 7.841755E+01 + 7.299995E+00 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 7.299995E+00 0.000000E+00 3 6.303385E+00 1.782814E+02 -6.300550E+00 1.890387E-01 + 7.299995E+00 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 7.299995E+00 0.000000E+00 5 4.132928E+02 -9.610378E+01 -4.394532E+01 -4.109499E+02 + 7.299995E+00 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 7.299995E+00 3.000000E+01 1 8.297503E+01 8.649887E+01 5.067137E+00 8.282017E+01 + 7.299995E+00 3.000000E+01 2 4.070684E+01 8.846386E+01 1.091247E+00 4.069221E+01 + 7.299995E+00 3.000000E+01 3 6.739426E+00 1.773851E+02 -6.732409E+00 3.074704E-01 + 7.299995E+00 3.000000E+01 4 1.718642E+02 8.832094E+01 5.035780E+00 1.717904E+02 + 7.299995E+00 3.000000E+01 5 3.322572E+02 -9.420104E+01 -2.433993E+01 -3.313644E+02 + 7.299995E+00 3.000000E+01 6 1.234887E+03 -6.484753E+00 1.226986E+03 -1.394666E+02 + 7.299995E+00 6.000000E+01 1 7.782559E+01 9.114442E+01 -1.554368E+00 7.781007E+01 + 7.299995E+00 6.000000E+01 2 1.325970E+02 8.628230E+01 8.597677E+00 1.323180E+02 + 7.299995E+00 6.000000E+01 3 3.099323E+00 1.747380E+02 -3.086262E+00 2.842379E-01 + 7.299995E+00 6.000000E+01 4 6.480093E+02 8.623495E+01 4.255168E+01 6.466107E+02 + 7.299995E+00 6.000000E+01 5 1.979331E+02 -8.855743E+01 4.982943E+00 -1.978704E+02 + 7.299995E+00 6.000000E+01 6 2.176386E+03 -4.941000E+00 2.168298E+03 -1.874518E+02 + 7.299995E+00 9.000000E+01 1 1.036275E-05 -8.735548E+01 4.781286E-07 -1.035171E-05 + 7.299995E+00 9.000000E+01 2 2.052295E+02 8.569668E+01 1.539971E+01 2.046509E+02 + 7.299995E+00 9.000000E+01 3 1.438498E+00 4.225457E+00 1.434588E+00 1.059904E-01 + 7.299995E+00 9.000000E+01 4 1.033485E+03 8.574448E+01 7.668940E+01 1.030635E+03 + 7.299995E+00 9.000000E+01 5 2.586495E-04 -8.931433E+01 3.095230E-06 -2.586310E-04 + 7.299995E+00 9.000000E+01 6 2.352377E-04 1.772550E+02 -2.349678E-04 1.126597E-05 + 7.399995E+00 0.000000E+00 1 8.340108E+01 8.406290E+01 8.626729E+00 8.295373E+01 + 7.399995E+00 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 7.399995E+00 0.000000E+00 3 5.281970E+00 1.784444E+02 -5.280023E+00 1.433921E-01 + 7.399995E+00 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 7.399995E+00 0.000000E+00 5 3.830153E+02 -9.519530E+01 -3.468234E+01 -3.814418E+02 + 7.399995E+00 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 7.399995E+00 3.000000E+01 1 8.667696E+01 8.702539E+01 4.497969E+00 8.656017E+01 + 7.399995E+00 3.000000E+01 2 4.344891E+01 8.792039E+01 1.576675E+00 4.342029E+01 + 7.399995E+00 3.000000E+01 3 5.253987E+00 1.779033E+02 -5.250469E+00 1.922214E-01 + 7.399995E+00 3.000000E+01 4 1.832959E+02 8.768266E+01 7.411419E+00 1.831460E+02 + 7.399995E+00 3.000000E+01 5 3.050693E+02 -9.357434E+01 -1.901909E+01 -3.044759E+02 + 7.399995E+00 3.000000E+01 6 1.242579E+03 -5.827247E+00 1.236158E+03 -1.261583E+02 + 7.399995E+00 6.000000E+01 1 7.837060E+01 9.102612E+01 -1.403471E+00 7.835803E+01 + 7.399995E+00 6.000000E+01 2 1.347433E+02 8.618854E+01 8.956859E+00 1.344453E+02 + 7.399995E+00 6.000000E+01 3 7.860215E-01 1.691552E+02 -7.719834E-01 1.478894E-01 + 7.399995E+00 6.000000E+01 4 6.535016E+02 8.614218E+01 4.396807E+01 6.520209E+02 + 7.399995E+00 6.000000E+01 5 1.762595E+02 -8.868392E+01 4.048314E+00 -1.762130E+02 + 7.399995E+00 6.000000E+01 6 2.105494E+03 -4.547356E+00 2.098867E+03 -1.669300E+02 + 7.399995E+00 9.000000E+01 1 1.016247E-05 -8.718291E+01 4.994621E-07 -1.015019E-05 + 7.399995E+00 9.000000E+01 2 2.044150E+02 8.569868E+01 1.533145E+01 2.038392E+02 + 7.399995E+00 9.000000E+01 3 4.082258E+00 4.759538E-01 4.082117E+00 3.391077E-02 + 7.399995E+00 9.000000E+01 4 1.022605E+03 8.575587E+01 7.567914E+01 1.019801E+03 + 7.399995E+00 9.000000E+01 5 2.591698E-04 -8.946914E+01 2.401235E-06 -2.591586E-04 + 7.399995E+00 9.000000E+01 6 2.245352E-04 1.774623E+02 -2.243150E-04 9.941742E-06 + 7.499995E+00 0.000000E+00 1 8.742158E+01 8.494504E+01 7.702832E+00 8.708157E+01 + 7.499995E+00 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 7.499995E+00 0.000000E+00 3 4.095227E+00 1.786794E+02 -4.094140E+00 9.438183E-02 + 7.499995E+00 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 7.499995E+00 0.000000E+00 5 3.515769E+02 -9.443193E+01 -2.716799E+01 -3.505256E+02 + 7.499995E+00 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 7.499995E+00 3.000000E+01 1 8.997755E+01 8.745473E+01 3.995785E+00 8.988879E+01 + 7.499995E+00 3.000000E+01 2 4.599360E+01 8.751589E+01 1.993469E+00 4.595038E+01 + 7.499995E+00 3.000000E+01 3 3.625280E+00 1.784841E+02 -3.624011E+00 9.590188E-02 + 7.499995E+00 3.000000E+01 4 1.938288E+02 8.721533E+01 9.416683E+00 1.935999E+02 + 7.499995E+00 3.000000E+01 5 2.769919E+02 -9.306342E+01 -1.480279E+01 -2.765961E+02 + 7.499995E+00 3.000000E+01 6 1.244277E+03 -5.244829E+00 1.239067E+03 -1.137415E+02 + 7.499995E+00 6.000000E+01 1 7.877998E+01 9.090032E+01 -1.237872E+00 7.877025E+01 + 7.499995E+00 6.000000E+01 2 1.365795E+02 8.612640E+01 9.226720E+00 1.362675E+02 + 7.499995E+00 6.000000E+01 3 1.619560E+00 2.104268E+00 1.618468E+00 5.946723E-02 + 7.499995E+00 6.000000E+01 4 6.575726E+02 8.608166E+01 4.493509E+01 6.560355E+02 + 7.499995E+00 6.000000E+01 5 1.549301E+02 -8.882681E+01 3.172145E+00 -1.548976E+02 + 7.499995E+00 6.000000E+01 6 2.035356E+03 -4.178991E+00 2.029945E+03 -1.483215E+02 + 7.499995E+00 9.000000E+01 1 9.965480E-06 -8.706212E+01 5.107633E-07 -9.952382E-06 + 7.499995E+00 9.000000E+01 2 2.034739E+02 8.571490E+01 1.520344E+01 2.029051E+02 + 7.499995E+00 9.000000E+01 3 6.759169E+00 1.113236E-01 6.759156E+00 1.313281E-02 + 7.499995E+00 9.000000E+01 4 1.011207E+03 8.578003E+01 7.441042E+01 1.008466E+03 + 7.499995E+00 9.000000E+01 5 2.595411E-04 -8.960838E+01 1.773960E-06 -2.595350E-04 + 7.499995E+00 9.000000E+01 6 2.143955E-04 1.776571E+02 -2.142163E-04 8.764559E-06 + 7.599995E+00 0.000000E+00 1 9.108731E+01 8.567310E+01 6.872245E+00 9.082770E+01 + 7.599995E+00 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 7.599995E+00 0.000000E+00 3 2.753061E+00 1.790195E+02 -2.752658E+00 4.711146E-02 + 7.599995E+00 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 7.599995E+00 0.000000E+00 5 3.193669E+02 -9.379190E+01 -2.112063E+01 -3.186677E+02 + 7.599995E+00 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 7.599995E+00 3.000000E+01 1 9.291185E+01 8.780254E+01 3.562552E+00 9.284352E+01 + 7.599995E+00 3.000000E+01 2 4.834269E+01 8.721734E+01 2.346922E+00 4.828569E+01 + 7.599995E+00 3.000000E+01 3 1.866945E+00 1.793741E+02 -1.866833E+00 2.039605E-02 + 7.599995E+00 3.000000E+01 4 2.034649E+02 8.687680E+01 1.108542E+01 2.031627E+02 + 7.599995E+00 3.000000E+01 5 2.483542E+02 -9.264957E+01 -1.148071E+01 -2.480887E+02 + 7.599995E+00 3.000000E+01 6 1.240875E+03 -4.726879E+00 1.236654E+03 -1.022556E+02 + 7.599995E+00 6.000000E+01 1 7.907039E+01 9.077093E+01 -1.063876E+00 7.906323E+01 + 7.599995E+00 6.000000E+01 2 1.381267E+02 8.609180E+01 9.414437E+00 1.378055E+02 + 7.599995E+00 6.000000E+01 3 4.069374E+00 2.072948E-01 4.069347E+00 1.472287E-02 + 7.599995E+00 6.000000E+01 4 6.603373E+02 8.604908E+01 4.549854E+01 6.587679E+02 + 7.599995E+00 6.000000E+01 5 1.340043E+02 -8.897920E+01 2.387324E+00 -1.339831E+02 + 7.599995E+00 6.000000E+01 6 1.966332E+03 -3.835799E+00 1.961927E+03 -1.315424E+02 + 7.599995E+00 9.000000E+01 1 9.772629E-06 -8.698692E+01 5.136886E-07 -9.759118E-06 + 7.599995E+00 9.000000E+01 2 2.024144E+02 8.574466E+01 1.501944E+01 2.018564E+02 + 7.599995E+00 9.000000E+01 3 9.453634E+00 2.233773E-01 9.453563E+00 3.685650E-02 + 7.599995E+00 9.000000E+01 4 9.993538E+02 8.581632E+01 7.290702E+01 9.966908E+02 + 7.599995E+00 9.000000E+01 5 2.597687E-04 -8.973209E+01 1.214688E-06 -2.597658E-04 + 7.599995E+00 9.000000E+01 6 2.047929E-04 1.778394E+02 -2.046473E-04 7.720900E-06 + 7.699995E+00 0.000000E+00 1 9.442255E+01 8.627306E+01 6.137610E+00 9.422286E+01 + 7.699995E+00 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 7.699995E+00 0.000000E+00 3 1.266463E+00 1.797298E+02 -1.266448E+00 5.973011E-03 + 7.699995E+00 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 7.699995E+00 0.000000E+00 5 2.866823E+02 -9.325626E+01 -1.628411E+01 -2.862195E+02 + 7.699995E+00 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 7.699995E+00 3.000000E+01 1 9.551472E+01 8.808272E+01 3.195601E+00 9.546125E+01 + 7.699995E+00 3.000000E+01 2 5.050034E+01 8.700081E+01 2.642276E+00 5.043117E+01 + 7.699995E+00 3.000000E+01 3 3.403573E-02 -7.708894E+01 7.604886E-03 -3.317524E-02 + 7.699995E+00 3.000000E+01 4 2.122245E+02 8.663680E+01 1.245017E+01 2.118590E+02 + 7.699995E+00 3.000000E+01 5 2.194090E+02 -9.231698E+01 -8.870259E+00 -2.192297E+02 + 7.699995E+00 3.000000E+01 6 1.233160E+03 -4.264926E+00 1.229745E+03 -9.170797E+01 + 7.699995E+00 6.000000E+01 1 7.925520E+01 9.064118E+01 -8.868990E-01 7.925024E+01 + 7.699995E+00 6.000000E+01 2 1.394051E+02 8.608114E+01 9.527458E+00 1.390791E+02 + 7.699995E+00 6.000000E+01 3 6.567874E+00 7.875823E-02 6.567868E+00 9.028135E-03 + 7.699995E+00 6.000000E+01 4 6.618986E+02 8.604070E+01 4.570275E+01 6.603188E+02 + 7.699995E+00 6.000000E+01 5 1.135088E+02 -8.913577E+01 1.712074E+00 -1.134959E+02 + 7.699995E+00 6.000000E+01 6 1.898716E+03 -3.517265E+00 1.895140E+03 -1.164849E+02 + 7.699995E+00 9.000000E+01 1 9.584668E-06 -8.695145E+01 5.097324E-07 -9.571104E-06 + 7.699995E+00 9.000000E+01 2 2.012424E+02 8.578704E+01 1.478404E+01 2.006986E+02 + 7.699995E+00 9.000000E+01 3 1.215646E+01 4.643328E-01 1.215606E+01 9.851649E-02 + 7.699995E+00 9.000000E+01 4 9.870933E+02 8.586389E+01 7.119507E+01 9.845224E+02 + 7.699995E+00 9.000000E+01 5 2.598501E-04 -8.984074E+01 7.222630E-07 -2.598492E-04 + 7.699995E+00 9.000000E+01 6 1.957017E-04 1.780094E+02 -1.955836E-04 6.797717E-06 + 7.799995E+00 0.000000E+00 1 9.744762E+01 8.676672E+01 5.496192E+00 9.729250E+01 + 7.799995E+00 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 7.799995E+00 0.000000E+00 3 3.533028E-01 -4.133177E+00 3.523839E-01 -2.546430E-02 + 7.799995E+00 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 7.799995E+00 0.000000E+00 5 2.537789E+02 -9.280707E+01 -1.242832E+01 -2.534744E+02 + 7.799995E+00 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 7.799995E+00 3.000000E+01 1 9.781522E+01 8.830712E+01 2.889658E+00 9.777252E+01 + 7.799995E+00 3.000000E+01 2 5.247171E+01 8.684859E+01 2.884618E+00 5.239236E+01 + 7.799995E+00 3.000000E+01 3 1.986412E+00 -1.854771E+00 1.985371E+00 -6.429262E-02 + 7.799995E+00 3.000000E+01 4 2.201274E+02 8.647298E+01 1.354209E+01 2.197104E+02 + 7.799995E+00 3.000000E+01 5 1.903563E+02 -9.205275E+01 -6.818476E+00 -1.902341E+02 + 7.799995E+00 3.000000E+01 6 1.221833E+03 -3.851990E+00 1.219072E+03 -8.208183E+01 + 7.799995E+00 6.000000E+01 1 7.934649E+01 9.051372E+01 -7.114094E-01 7.934330E+01 + 7.799995E+00 6.000000E+01 2 1.404336E+02 8.609111E+01 9.573378E+00 1.401069E+02 + 7.799995E+00 6.000000E+01 3 9.102118E+00 2.380052E-01 9.102040E+00 3.780986E-02 + 7.799995E+00 6.000000E+01 4 6.623581E+02 8.605309E+01 4.559156E+01 6.607872E+02 + 7.799995E+00 6.000000E+01 5 9.347800E+01 -8.929327E+01 1.153013E+00 -9.347089E+01 + 7.799995E+00 6.000000E+01 6 1.832736E+03 -3.222579E+00 1.829838E+03 -1.030272E+02 + 7.799995E+00 9.000000E+01 1 9.401953E-06 -8.695017E+01 5.002249E-07 -9.388636E-06 + 7.799995E+00 9.000000E+01 2 1.999665E+02 8.584091E+01 1.450279E+01 1.994399E+02 + 7.799995E+00 9.000000E+01 3 1.485886E+01 7.400206E-01 1.485762E+01 1.919087E-01 + 7.799995E+00 9.000000E+01 4 9.744837E+02 8.592172E+01 6.930460E+01 9.720161E+02 + 7.799995E+00 9.000000E+01 5 2.597919E-04 -8.993514E+01 2.940749E-07 -2.597917E-04 + 7.799995E+00 9.000000E+01 6 1.870968E-04 1.781676E+02 -1.870011E-04 5.982688E-06 + 7.899995E+00 0.000000E+00 1 1.001835E+02 8.717259E+01 4.941816E+00 1.000616E+02 + 7.899995E+00 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 7.899995E+00 0.000000E+00 3 2.091449E+00 -1.222346E+00 2.090973E+00 -4.461550E-02 + 7.899995E+00 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 7.899995E+00 0.000000E+00 5 2.208600E+02 -9.242885E+01 -9.359738E+00 -2.206615E+02 + 7.899995E+00 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 7.899995E+00 3.000000E+01 1 9.984132E+01 8.848597E+01 2.637978E+00 9.980646E+01 + 7.899995E+00 3.000000E+01 2 5.426383E+01 8.674731E+01 3.078921E+00 5.417641E+01 + 7.899995E+00 3.000000E+01 3 4.054196E+00 -1.035074E+00 4.053535E+00 -7.323688E-02 + 7.899995E+00 3.000000E+01 4 2.272098E+02 8.636868E+01 1.439062E+01 2.267536E+02 + 7.899995E+00 3.000000E+01 5 1.613735E+02 -9.184579E+01 -5.197766E+00 -1.612898E+02 + 7.899995E+00 3.000000E+01 6 1.207513E+03 -3.482229E+00 1.205284E+03 -7.334307E+01 + 7.899995E+00 6.000000E+01 1 7.935417E+01 9.039056E+01 -5.409049E-01 7.935233E+01 + 7.899995E+00 6.000000E+01 2 1.412311E+02 8.611877E+01 9.559717E+00 1.409072E+02 + 7.899995E+00 6.000000E+01 3 1.166198E+01 4.730663E-01 1.166158E+01 9.628679E-02 + 7.899995E+00 6.000000E+01 4 6.618198E+02 8.608330E+01 4.520630E+01 6.602740E+02 + 7.899995E+00 6.000000E+01 5 7.393465E+01 -8.944995E+01 7.097710E-01 -7.393124E+01 + 7.899995E+00 6.000000E+01 6 1.768568E+03 -2.950732E+00 1.766223E+03 -9.104096E+01 + 7.899995E+00 9.000000E+01 1 9.224881E-06 -8.697808E+01 4.863176E-07 -9.212054E-06 + 7.899995E+00 9.000000E+01 2 1.985938E+02 8.590507E+01 1.418145E+01 1.980869E+02 + 7.899995E+00 9.000000E+01 3 1.755438E+01 1.015346E+00 1.755162E+01 3.110671E-01 + 7.899995E+00 9.000000E+01 4 9.615761E+02 8.598869E+01 6.726544E+01 9.592205E+02 + 7.899995E+00 9.000000E+01 5 2.595977E-04 -9.001629E+01 -7.377717E-08 -2.595977E-04 + 7.899995E+00 9.000000E+01 6 1.789530E-04 1.783143E+02 -1.788755E-04 5.264333E-06 + 7.999995E+00 0.000000E+00 1 1.026511E+02 8.750613E+01 4.466602E+00 1.025539E+02 + 7.999995E+00 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 7.999995E+00 0.000000E+00 3 3.937476E+00 -7.238156E-01 3.937161E+00 -4.974067E-02 + 7.999995E+00 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 7.999995E+00 0.000000E+00 5 1.880801E+02 -9.210726E+01 -6.915757E+00 -1.879529E+02 + 7.999995E+00 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 7.999995E+00 3.000000E+01 1 1.016173E+02 8.862783E+01 2.433381E+00 1.015881E+02 + 7.999995E+00 3.000000E+01 2 5.588414E+01 8.668661E+01 3.229963E+00 5.579073E+01 + 7.999995E+00 3.000000E+01 3 6.199816E+00 -5.616584E-01 6.199518E+00 -6.077451E-02 + 7.999995E+00 3.000000E+01 4 2.335099E+02 8.631115E+01 1.502359E+01 2.330261E+02 + 7.999995E+00 3.000000E+01 5 1.325916E+02 -9.168777E+01 -3.905201E+00 -1.325341E+02 + 7.999995E+00 3.000000E+01 6 1.190741E+03 -3.150677E+00 1.188941E+03 -6.544550E+01 + 7.999995E+00 6.000000E+01 1 7.928681E+01 9.027322E+01 -3.780780E-01 7.928591E+01 + 7.999995E+00 6.000000E+01 2 1.418152E+02 8.616150E+01 9.493734E+00 1.414971E+02 + 7.999995E+00 6.000000E+01 3 1.423871E+01 7.244696E-01 1.423757E+01 1.800348E-01 + 7.999995E+00 6.000000E+01 4 6.603688E+02 8.612856E+01 4.458681E+01 6.588619E+02 + 7.999995E+00 6.000000E+01 5 5.490401E+01 -8.960667E+01 3.769139E-01 -5.490271E+01 + 7.999995E+00 6.000000E+01 6 1.706345E+03 -2.700556E+00 1.704450E+03 -8.039639E+01 + 7.999995E+00 9.000000E+01 1 9.053556E-06 -8.703043E+01 4.690244E-07 -9.041399E-06 + 7.999995E+00 9.000000E+01 2 1.971333E+02 8.597823E+01 1.382605E+01 1.966479E+02 + 7.999995E+00 9.000000E+01 3 2.023759E+01 1.275899E+00 2.023257E+01 4.506261E-01 + 7.999995E+00 9.000000E+01 4 9.484269E+02 8.606368E+01 6.510731E+01 9.461896E+02 + 7.999995E+00 9.000000E+01 5 2.592711E-04 -9.008528E+01 -3.859052E-07 -2.592708E-04 + 7.999995E+00 9.000000E+01 6 1.712471E-04 1.784500E+02 -1.711845E-04 4.632054E-06 + 8.099995E+00 0.000000E+00 1 1.048676E+02 8.778030E+01 4.061672E+00 1.047889E+02 + 8.099995E+00 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 8.099995E+00 0.000000E+00 3 5.878958E+00 -3.878740E-01 5.878823E+00 -3.979835E-02 + 8.099995E+00 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 8.099995E+00 0.000000E+00 5 1.555692E+02 -9.182758E+01 -4.961399E+00 -1.554901E+02 + 8.099995E+00 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 8.099995E+00 3.000000E+01 1 1.031647E+02 8.873989E+01 2.268725E+00 1.031398E+02 + 8.099995E+00 3.000000E+01 2 5.734096E+01 8.665842E+01 3.342315E+00 5.724347E+01 + 8.099995E+00 3.000000E+01 3 8.412326E+00 -1.913998E-01 8.412279E+00 -2.810179E-02 + 8.099995E+00 3.000000E+01 4 2.390619E+02 8.629047E+01 1.546689E+01 2.385610E+02 + 8.099995E+00 3.000000E+01 5 1.041119E+02 -9.157516E+01 -2.861869E+00 -1.040726E+02 + 8.099995E+00 3.000000E+01 6 1.171987E+03 -2.853062E+00 1.170535E+03 -5.833537E+01 + 8.099995E+00 6.000000E+01 1 7.915191E+01 9.016277E+01 -2.248562E-01 7.915159E+01 + 8.099995E+00 6.000000E+01 2 1.422033E+02 8.621691E+01 9.382489E+00 1.418934E+02 + 8.099995E+00 6.000000E+01 3 1.682552E+01 9.696588E-01 1.682311E+01 2.847371E-01 + 8.099995E+00 6.000000E+01 4 6.580927E+02 8.618642E+01 4.376996E+01 6.566354E+02 + 8.099995E+00 6.000000E+01 5 3.638227E+01 -8.977335E+01 1.439245E-01 -3.638198E+01 + 8.099995E+00 6.000000E+01 6 1.646148E+03 -2.470806E+00 1.644618E+03 -7.096602E+01 + 8.099995E+00 9.000000E+01 1 8.888026E-06 -8.710305E+01 4.491992E-07 -8.876667E-06 + 8.099995E+00 9.000000E+01 2 1.955928E+02 8.605914E+01 1.344249E+01 1.951303E+02 + 8.099995E+00 9.000000E+01 3 2.290479E+01 1.515339E+00 2.289677E+01 6.057073E-01 + 8.099995E+00 9.000000E+01 4 9.350745E+02 8.614549E+01 6.285859E+01 9.329593E+02 + 8.099995E+00 9.000000E+01 5 2.588207E-04 -9.014330E+01 -6.473321E-07 -2.588199E-04 + 8.099995E+00 9.000000E+01 6 1.639552E-04 1.785754E+02 -1.639046E-04 4.076145E-06 + 8.199995E+00 0.000000E+00 1 1.068520E+02 8.800578E+01 3.718322E+00 1.067873E+02 + 8.199995E+00 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 8.199995E+00 0.000000E+00 3 7.902928E+00 -1.063022E-01 7.902915E+00 -1.466247E-02 + 8.199995E+00 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 8.199995E+00 0.000000E+00 5 1.234563E+02 -9.157329E+01 -3.389571E+00 -1.234097E+02 + 8.199995E+00 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 8.199995E+00 3.000000E+01 1 1.045033E+02 8.882807E+01 2.137357E+00 1.044814E+02 + 8.199995E+00 3.000000E+01 2 5.864267E+01 8.665630E+01 3.420366E+00 5.854284E+01 + 8.199995E+00 3.000000E+01 3 1.068015E+01 1.240289E-01 1.068013E+01 2.311945E-02 + 8.199995E+00 3.000000E+01 4 2.439129E+02 8.629896E+01 1.574469E+01 2.434042E+02 + 8.199995E+00 3.000000E+01 5 7.604199E+01 -9.151055E+01 -2.004550E+00 -7.601556E+01 + 8.199995E+00 3.000000E+01 6 1.151663E+03 -2.585664E+00 1.150490E+03 -5.195500E+01 + 8.199995E+00 6.000000E+01 1 7.895687E+01 9.005986E+01 -8.249161E-02 7.895683E+01 + 8.199995E+00 6.000000E+01 2 1.424118E+02 8.628288E+01 9.232624E+00 1.421122E+02 + 8.199995E+00 6.000000E+01 3 1.941458E+01 1.199059E+00 1.941032E+01 4.062694E-01 + 8.199995E+00 6.000000E+01 4 6.550826E+02 8.625477E+01 4.279003E+01 6.536836E+02 + 8.199995E+00 6.000000E+01 5 1.840337E+01 -8.999612E+01 1.248352E-03 -1.840337E+01 + 8.199995E+00 6.000000E+01 6 1.588037E+03 -2.260185E+00 1.586802E+03 -6.262812E+01 + 8.199995E+00 9.000000E+01 1 8.728281E-06 -8.719205E+01 4.275842E-07 -8.717801E-06 + 8.199995E+00 9.000000E+01 2 1.939802E+02 8.614654E+01 1.303642E+01 1.935417E+02 + 8.199995E+00 9.000000E+01 3 2.555106E+01 1.731206E+00 2.553940E+01 7.719142E-01 + 8.199995E+00 9.000000E+01 4 9.215750E+02 8.623306E+01 6.054570E+01 9.195839E+02 + 8.199995E+00 9.000000E+01 5 2.582526E-04 -9.019151E+01 -8.632314E-07 -2.582512E-04 + 8.199995E+00 9.000000E+01 6 1.570556E-04 1.786910E+02 -1.570146E-04 3.587820E-06 + 8.299995E+00 0.000000E+00 1 1.086188E+02 8.819144E+01 3.428026E+00 1.085647E+02 + 8.299995E+00 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 8.299995E+00 0.000000E+00 3 9.999021E+00 1.456736E-01 9.998988E+00 2.542233E-02 + 8.299995E+00 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 8.299995E+00 0.000000E+00 5 9.182286E+01 -9.132073E+01 -2.116430E+00 -9.179847E+01 + 8.299995E+00 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 8.299995E+00 3.000000E+01 1 1.056509E+02 8.889730E+01 2.033197E+00 1.056313E+02 + 8.299995E+00 3.000000E+01 2 5.979816E+01 8.667507E+01 3.468193E+00 5.969751E+01 + 8.299995E+00 3.000000E+01 3 1.299342E+01 4.014685E-01 1.299310E+01 9.104348E-02 + 8.299995E+00 3.000000E+01 4 2.481039E+02 8.633039E+01 1.587941E+01 2.475952E+02 + 8.299995E+00 3.000000E+01 5 4.845108E+01 -9.152054E+01 -1.285665E+00 -4.843402E+01 + 8.299995E+00 3.000000E+01 6 1.130121E+03 -2.345234E+00 1.129175E+03 -4.624528E+01 + 8.299995E+00 6.000000E+01 1 7.870705E+01 8.996489E+01 4.823263E-02 7.870704E+01 + 8.299995E+00 6.000000E+01 2 1.424557E+02 8.635747E+01 9.050406E+00 1.421679E+02 + 8.299995E+00 6.000000E+01 3 2.200033E+01 1.409368E+00 2.199367E+01 5.411121E-01 + 8.299995E+00 6.000000E+01 4 6.514143E+02 8.633164E+01 4.167820E+01 6.500797E+02 + 8.299995E+00 6.000000E+01 5 9.643353E-01 -9.382101E+01 -6.426318E-02 -9.621917E-01 + 8.299995E+00 6.000000E+01 6 1.532040E+03 -2.067390E+00 1.531042E+03 -5.526822E+01 + 8.299995E+00 9.000000E+01 1 8.574210E-06 -8.729401E+01 4.047953E-07 -8.564650E-06 + 8.299995E+00 9.000000E+01 2 1.923042E+02 8.623924E+01 1.261333E+01 1.918901E+02 + 8.299995E+00 9.000000E+01 3 2.817375E+01 1.923349E+00 2.815788E+01 9.455803E-01 + 8.299995E+00 9.000000E+01 4 9.079691E+02 8.632528E+01 5.819356E+01 9.061024E+02 + 8.299995E+00 9.000000E+01 5 2.575735E-04 -9.023106E+01 -1.038740E-06 -2.575714E-04 + 8.299995E+00 9.000000E+01 6 1.505263E-04 1.787974E+02 -1.504932E-04 3.159157E-06 + 8.399996E+00 0.000000E+00 1 1.101842E+02 8.834463E+01 3.182974E+00 1.101382E+02 + 8.399996E+00 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 8.399996E+00 0.000000E+00 3 1.215627E+01 3.754811E-01 1.215601E+01 7.966411E-02 + 8.399996E+00 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 8.399996E+00 0.000000E+00 5 6.073744E+01 -9.101222E+01 -1.072971E+00 -6.072796E+01 + 8.399996E+00 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 8.399996E+00 3.000000E+01 1 1.066237E+02 8.895159E+01 1.950916E+00 1.066059E+02 + 8.399996E+00 3.000000E+01 2 6.081600E+01 8.671054E+01 3.489645E+00 6.071580E+01 + 8.399996E+00 3.000000E+01 3 1.534336E+01 6.485831E-01 1.534238E+01 1.736817E-01 + 8.399996E+00 3.000000E+01 4 2.516782E+02 8.637983E+01 1.589144E+01 2.511760E+02 + 8.399996E+00 3.000000E+01 5 2.139992E+01 -9.179913E+01 -6.718618E-01 -2.138937E+01 + 8.399996E+00 3.000000E+01 6 1.107667E+03 -2.128899E+00 1.106903E+03 -4.114735E+01 + 8.399996E+00 6.000000E+01 1 7.840784E+01 8.987799E+01 1.669732E-01 7.840767E+01 + 8.399996E+00 6.000000E+01 2 1.423499E+02 8.643902E+01 8.841481E+00 1.420750E+02 + 8.399996E+00 6.000000E+01 3 2.457878E+01 1.598849E+00 2.456922E+01 6.857862E-01 + 8.399996E+00 6.000000E+01 4 6.471569E+02 8.641531E+01 4.046268E+01 6.458907E+02 + 8.399996E+00 6.000000E+01 5 1.593196E+01 9.023058E+01 -6.411661E-02 1.593184E+01 + 8.399996E+00 6.000000E+01 6 1.478153E+03 -1.891146E+00 1.477348E+03 -4.878013E+01 + 8.399996E+00 9.000000E+01 1 8.425674E-06 -8.740590E+01 3.813477E-07 -8.417040E-06 + 8.399996E+00 9.000000E+01 2 1.905720E+02 8.633611E+01 1.217818E+01 1.901825E+02 + 8.399996E+00 9.000000E+01 3 3.077169E+01 2.092187E+00 3.075118E+01 1.123396E+00 + 8.399996E+00 9.000000E+01 4 8.942975E+02 8.642114E+01 5.582407E+01 8.925535E+02 + 8.399996E+00 9.000000E+01 5 2.567888E-04 -9.026302E+01 -1.178763E-06 -2.567861E-04 + 8.399996E+00 9.000000E+01 6 1.443470E-04 1.788952E+02 -1.443201E-04 2.783047E-06 + 8.499996E+00 0.000000E+00 1 1.115610E+02 8.847137E+01 2.976067E+00 1.115213E+02 + 8.499996E+00 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 8.499996E+00 0.000000E+00 3 1.436424E+01 5.859408E-01 1.436349E+01 1.468947E-01 + 8.499996E+00 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 8.499996E+00 0.000000E+00 5 3.026838E+01 -9.039252E+01 -2.073547E-01 -3.026767E+01 + 8.499996E+00 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 8.499996E+00 3.000000E+01 1 1.074365E+02 8.899419E+01 1.885903E+00 1.074199E+02 + 8.499996E+00 3.000000E+01 2 6.170529E+01 8.675925E+01 3.488291E+00 6.160661E+01 + 8.499996E+00 3.000000E+01 3 1.772121E+01 8.693196E-01 1.771917E+01 2.688645E-01 + 8.499996E+00 3.000000E+01 4 2.546799E+02 8.644330E+01 1.579940E+01 2.541894E+02 + 8.499996E+00 3.000000E+01 5 5.062679E+00 9.151420E+01 -1.337793E-01 5.060912E+00 + 8.499996E+00 3.000000E+01 6 1.084562E+03 -1.934128E+00 1.083944E+03 -3.660450E+01 + 8.499996E+00 6.000000E+01 1 7.806481E+01 8.979910E+01 2.737343E-01 7.806433E+01 + 8.499996E+00 6.000000E+01 2 1.421089E+02 8.652599E+01 8.611196E+00 1.418477E+02 + 8.499996E+00 6.000000E+01 3 2.714522E+01 1.767649E+00 2.713231E+01 8.373327E-01 + 8.499996E+00 6.000000E+01 4 6.423845E+02 8.650430E+01 3.916857E+01 6.411893E+02 + 8.499996E+00 6.000000E+01 5 3.227318E+01 9.001779E+01 -1.001967E-02 3.227318E+01 + 8.499996E+00 6.000000E+01 6 1.426372E+03 -1.730191E+00 1.425722E+03 -4.306636E+01 + 8.499996E+00 9.000000E+01 1 1.042746E-05 -8.652386E+01 6.322487E-07 -1.040828E-05 + 8.499996E+00 9.000000E+01 2 1.887924E+02 8.643615E+01 1.173549E+01 1.884273E+02 + 8.499996E+00 9.000000E+01 3 3.334180E+01 2.238865E+00 3.331635E+01 1.302519E+00 + 8.499996E+00 9.000000E+01 4 8.806016E+02 8.651970E+01 5.345721E+01 8.789775E+02 + 8.499996E+00 9.000000E+01 5 3.221859E-04 -8.928722E+01 4.007965E-06 -3.221609E-04 + 8.499996E+00 9.000000E+01 6 1.384979E-04 1.789851E+02 -1.384762E-04 2.453158E-06 + 8.599997E+00 0.000000E+00 1 1.127633E+02 8.857661E+01 2.801085E+00 1.127285E+02 + 8.599997E+00 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 8.599997E+00 0.000000E+00 3 1.661392E+01 7.786490E-01 1.661238E+01 2.257760E-01 + 8.599997E+00 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 8.599997E+00 0.000000E+00 5 7.083997E-01 -4.257503E+01 5.216599E-01 -4.792714E-01 + 8.599997E+00 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 8.599997E+00 3.000000E+01 1 1.081019E+02 8.902776E+01 1.834273E+00 1.080864E+02 + 8.599997E+00 3.000000E+01 2 6.247464E+01 8.681840E+01 3.467401E+00 6.237835E+01 + 8.599997E+00 3.000000E+01 3 2.011938E+01 1.066583E+00 2.011590E+01 3.745086E-01 + 8.599997E+00 3.000000E+01 4 2.571511E+02 8.651755E+01 1.562009E+01 2.566763E+02 + 8.599997E+00 3.000000E+01 5 3.088075E+01 8.935660E+01 3.467661E-01 3.087881E+01 + 8.599997E+00 3.000000E+01 6 1.061029E+03 -1.758672E+00 1.060529E+03 -3.256275E+01 + 8.599997E+00 6.000000E+01 1 7.768225E+01 8.972802E+01 3.687541E-01 7.768137E+01 + 8.599997E+00 6.000000E+01 2 1.417454E+02 8.661707E+01 8.364246E+00 1.414984E+02 + 8.599997E+00 6.000000E+01 3 2.969547E+01 1.916534E+00 2.967886E+01 9.931231E-01 + 8.599997E+00 6.000000E+01 4 6.371637E+02 8.659726E+01 3.781829E+01 6.360403E+02 + 8.599997E+00 6.000000E+01 5 4.805872E+01 8.989476E+01 8.827934E-02 4.805864E+01 + 8.599997E+00 6.000000E+01 6 1.376663E+03 -1.583330E+00 1.376137E+03 -3.803830E+01 + 8.599997E+00 9.000000E+01 1 1.023129E-05 -8.663912E+01 5.998070E-07 -1.021369E-05 + 8.599997E+00 9.000000E+01 2 1.869718E+02 8.653838E+01 1.128936E+01 1.866306E+02 + 8.599997E+00 9.000000E+01 3 3.588227E+01 2.364943E+00 3.585170E+01 1.480657E+00 + 8.599997E+00 9.000000E+01 4 8.669142E+02 8.662012E+01 5.110961E+01 8.654063E+02 + 8.599997E+00 9.000000E+01 5 3.202662E-04 -8.929819E+01 3.922801E-06 -3.202422E-04 + 8.599997E+00 9.000000E+01 6 1.329601E-04 1.790675E+02 -1.329425E-04 2.163852E-06 + 8.699997E+00 0.000000E+00 1 1.138037E+02 8.866444E+01 2.652522E+00 1.137728E+02 + 8.699997E+00 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 8.699997E+00 0.000000E+00 3 1.889723E+01 9.544963E-01 1.889460E+01 3.147963E-01 + 8.699997E+00 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 8.699997E+00 0.000000E+00 5 2.862950E+01 8.771075E+01 1.143582E+00 2.860665E+01 + 8.699997E+00 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 8.699997E+00 3.000000E+01 1 1.086335E+02 8.905442E+01 1.792759E+00 1.086187E+02 + 8.699997E+00 3.000000E+01 2 6.313221E+01 8.688560E+01 3.429956E+00 6.303897E+01 + 8.699997E+00 3.000000E+01 3 2.253175E+01 1.242531E+00 2.252645E+01 4.885909E-01 + 8.699997E+00 3.000000E+01 4 2.591305E+02 8.659990E+01 1.536855E+01 2.586743E+02 + 8.699997E+00 3.000000E+01 5 5.604251E+01 8.920014E+01 7.823366E-01 5.603704E+01 + 8.699997E+00 3.000000E+01 6 1.037252E+03 -1.600515E+00 1.036847E+03 -2.897108E+01 + 8.699997E+00 6.000000E+01 1 7.726470E+01 8.966447E+01 4.524664E-01 7.726337E+01 + 8.699997E+00 6.000000E+01 2 1.412723E+02 8.671111E+01 8.104875E+00 1.410396E+02 + 8.699997E+00 6.000000E+01 3 3.222758E+01 2.046584E+00 3.220703E+01 1.150913E+00 + 8.699997E+00 6.000000E+01 4 6.315511E+02 8.669302E+01 3.643149E+01 6.304995E+02 + 8.699997E+00 6.000000E+01 5 6.329416E+01 8.980098E+01 2.198613E-01 6.329378E+01 + 8.699997E+00 6.000000E+01 6 1.328988E+03 -1.449415E+00 1.328563E+03 -3.361591E+01 + 8.699997E+00 9.000000E+01 1 1.004328E-05 -8.676299E+01 5.671095E-07 -1.002725E-05 + 8.699997E+00 9.000000E+01 2 1.851176E+02 8.664194E+01 1.084338E+01 1.847998E+02 + 8.699997E+00 9.000000E+01 3 3.839290E+01 2.472024E+00 3.835717E+01 1.655946E+00 + 8.699997E+00 9.000000E+01 4 8.532695E+02 8.672157E+01 4.879702E+01 8.518731E+02 + 8.699997E+00 9.000000E+01 5 3.182887E-04 -8.931004E+01 3.832783E-06 -3.182656E-04 + 8.699997E+00 9.000000E+01 6 1.277159E-04 1.791430E+02 -1.277016E-04 1.910145E-06 + 8.799997E+00 0.000000E+00 1 1.146925E+02 8.873815E+01 2.525715E+00 1.146646E+02 + 8.799997E+00 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 8.799997E+00 0.000000E+00 3 2.120618E+01 1.114105E+00 2.120217E+01 4.123240E-01 + 8.799997E+00 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 8.799997E+00 0.000000E+00 5 5.696907E+01 8.830740E+01 1.682705E+00 5.694421E+01 + 8.799997E+00 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 8.799997E+00 3.000000E+01 1 1.090416E+02 8.907587E+01 1.758680E+00 1.090274E+02 + 8.799997E+00 3.000000E+01 2 6.368653E+01 8.695892E+01 3.378690E+00 6.359685E+01 + 8.799997E+00 3.000000E+01 3 2.495154E+01 1.398870E+00 2.494411E+01 6.091287E-01 + 8.799997E+00 3.000000E+01 4 2.606603E+02 8.668817E+01 1.505839E+01 2.602250E+02 + 8.799997E+00 3.000000E+01 5 8.050187E+01 8.915780E+01 1.183269E+00 8.049317E+01 + 8.799997E+00 3.000000E+01 6 1.013393E+03 -1.457878E+00 1.013065E+03 -2.578277E+01 + 8.799997E+00 6.000000E+01 1 7.681592E+01 8.960807E+01 5.254475E-01 7.681412E+01 + 8.799997E+00 6.000000E+01 2 1.407009E+02 8.680706E+01 7.836827E+00 1.404825E+02 + 8.799997E+00 6.000000E+01 3 3.473800E+01 2.159020E+00 3.471334E+01 1.308688E+00 + 8.799997E+00 6.000000E+01 4 6.256008E+02 8.679055E+01 3.502496E+01 6.246196E+02 + 8.799997E+00 6.000000E+01 5 7.797361E+01 8.972295E+01 3.770394E-01 7.797270E+01 + 8.799997E+00 6.000000E+01 6 1.283291E+03 -1.327380E+00 1.282947E+03 -2.972753E+01 + 8.799997E+00 9.000000E+01 1 9.863033E-06 -8.689292E+01 5.345981E-07 -9.848533E-06 + 8.799997E+00 9.000000E+01 2 1.832373E+02 8.674611E+01 1.040067E+01 1.829419E+02 + 8.799997E+00 9.000000E+01 3 4.087251E+01 2.561725E+00 4.083166E+01 1.826823E+00 + 8.799997E+00 9.000000E+01 4 8.397040E+02 8.682341E+01 4.653093E+01 8.384138E+02 + 8.799997E+00 9.000000E+01 5 3.162640E-04 -8.932271E+01 3.738477E-06 -3.162420E-04 + 8.799997E+00 9.000000E+01 6 1.227483E-04 1.792122E+02 -1.227367E-04 1.687626E-06 + 8.899998E+00 0.000000E+00 1 1.154415E+02 8.880047E+01 2.416671E+00 1.154162E+02 + 8.899998E+00 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 8.899998E+00 0.000000E+00 3 2.353365E+01 1.258228E+00 2.352797E+01 5.167626E-01 + 8.899998E+00 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 8.899998E+00 0.000000E+00 5 8.453156E+01 8.853838E+01 2.156168E+00 8.450405E+01 + 8.899998E+00 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 8.899998E+00 3.000000E+01 1 1.093369E+02 8.909344E+01 1.729911E+00 1.093232E+02 + 8.899998E+00 3.000000E+01 2 6.414483E+01 8.703671E+01 3.316039E+00 6.405906E+01 + 8.899998E+00 3.000000E+01 3 2.737386E+01 1.537138E+00 2.736401E+01 7.343010E-01 + 8.899998E+00 3.000000E+01 4 2.617768E+02 8.678060E+01 1.470127E+01 2.613637E+02 + 8.899998E+00 3.000000E+01 5 1.042432E+02 8.914483E+01 1.555832E+00 1.042316E+02 + 8.899998E+00 3.000000E+01 6 9.895847E+02 -1.329165E+00 9.893184E+02 -2.295463E+01 + 8.899998E+00 6.000000E+01 1 7.633929E+01 8.955841E+01 5.883585E-01 7.633702E+01 + 8.899998E+00 6.000000E+01 2 1.400420E+02 8.690406E+01 7.563385E+00 1.398376E+02 + 8.899998E+00 6.000000E+01 3 3.722475E+01 2.255234E+00 3.719592E+01 1.464835E+00 + 8.899998E+00 6.000000E+01 4 6.193709E+02 8.688903E+01 3.361327E+01 6.184581E+02 + 8.899998E+00 6.000000E+01 5 9.210502E+01 8.965668E+01 5.518961E-01 9.210336E+01 + 8.899998E+00 6.000000E+01 6 1.239524E+03 -1.216205E+00 1.239245E+03 -2.630914E+01 + 8.899998E+00 9.000000E+01 1 9.690153E-06 -8.702674E+01 5.026269E-07 -9.677109E-06 + 8.899998E+00 9.000000E+01 2 1.813369E+02 8.685020E+01 9.963889E+00 1.810629E+02 + 8.899998E+00 9.000000E+01 3 4.331962E+01 2.635539E+00 4.327380E+01 1.991950E+00 + 8.899998E+00 9.000000E+01 4 8.262416E+02 8.692502E+01 4.432195E+01 8.250520E+02 + 8.899998E+00 9.000000E+01 5 3.141985E-04 -8.933611E+01 3.640586E-06 -3.141774E-04 + 8.899998E+00 9.000000E+01 6 1.180415E-04 1.792756E+02 -1.180320E-04 1.492417E-06 + 8.999998E+00 0.000000E+00 1 1.160606E+02 8.885361E+01 2.322023E+00 1.160374E+02 + 8.999998E+00 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 8.999998E+00 0.000000E+00 3 2.587355E+01 1.387605E+00 2.586596E+01 6.265516E-01 + 8.999998E+00 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 8.999998E+00 0.000000E+00 5 1.113087E+02 8.867339E+01 2.576969E+00 1.112789E+02 + 8.999998E+00 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 8.999998E+00 3.000000E+01 1 1.095290E+02 8.910822E+01 1.704707E+00 1.095157E+02 + 8.999998E+00 3.000000E+01 2 6.451524E+01 8.711766E+01 3.244162E+00 6.443362E+01 + 8.999998E+00 3.000000E+01 3 2.979382E+01 1.658782E+00 2.978134E+01 8.624467E-01 + 8.999998E+00 3.000000E+01 4 2.625165E+02 8.687570E+01 1.430773E+01 2.621263E+02 + 8.999998E+00 3.000000E+01 5 1.272618E+02 8.914267E+01 1.904178E+00 1.272476E+02 + 8.999998E+00 3.000000E+01 6 9.659369E+02 -1.212944E+00 9.657205E+02 -2.044723E+01 + 8.999998E+00 6.000000E+01 1 7.583825E+01 8.951503E+01 6.419079E-01 7.583553E+01 + 8.999998E+00 6.000000E+01 2 1.393056E+02 8.700136E+01 7.287399E+00 1.391148E+02 + 8.999998E+00 6.000000E+01 3 3.968670E+01 2.336427E+00 3.965370E+01 1.617909E+00 + 8.999998E+00 6.000000E+01 4 6.129016E+02 8.698767E+01 3.220852E+01 6.120547E+02 + 8.999998E+00 6.000000E+01 5 1.056942E+02 8.959994E+01 7.379875E-01 1.056916E+02 + 8.999998E+00 6.000000E+01 6 1.197618E+03 -1.114954E+00 1.197392E+03 -2.330372E+01 + 8.999998E+00 9.000000E+01 1 9.524249E-06 -8.716258E+01 4.714704E-07 -9.512573E-06 + 8.999998E+00 9.000000E+01 2 1.794218E+02 8.695363E+01 9.535217E+00 1.791683E+02 + 8.999998E+00 9.000000E+01 3 4.573512E+01 2.695062E+00 4.568454E+01 2.150482E+00 + 8.999998E+00 9.000000E+01 4 8.129009E+02 8.702586E+01 4.217762E+01 8.118060E+02 + 8.999998E+00 9.000000E+01 5 3.121020E-04 -8.935016E+01 3.539742E-06 -3.120819E-04 + 8.999998E+00 9.000000E+01 6 1.135800E-04 1.793336E+02 -1.135724E-04 1.321103E-06 + 9.099998E+00 0.000000E+00 1 1.165594E+02 8.889934E+01 2.238990E+00 1.165379E+02 + 9.099998E+00 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 9.099998E+00 0.000000E+00 3 2.822002E+01 1.503054E+00 2.821031E+01 7.402175E-01 + 9.099998E+00 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 9.099998E+00 0.000000E+00 5 1.372598E+02 8.876658E+01 2.954594E+00 1.372280E+02 + 9.099998E+00 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 9.099998E+00 3.000000E+01 1 1.096270E+02 8.912101E+01 1.681753E+00 1.096141E+02 + 9.099998E+00 3.000000E+01 2 6.480476E+01 8.720060E+01 3.165014E+00 6.472742E+01 + 9.099998E+00 3.000000E+01 3 3.220694E+01 1.765186E+00 3.219166E+01 9.920846E-01 + 9.099998E+00 3.000000E+01 4 2.629136E+02 8.697227E+01 1.388687E+01 2.625466E+02 + 9.099998E+00 3.000000E+01 5 1.495354E+02 8.914532E+01 2.230549E+00 1.495188E+02 + 9.099998E+00 3.000000E+01 6 9.425421E+02 -1.107938E+00 9.423659E+02 -1.822496E+01 + 9.099998E+00 6.000000E+01 1 7.531596E+01 8.947748E+01 6.868495E-01 7.531282E+01 + 9.099998E+00 6.000000E+01 2 1.385013E+02 8.709830E+01 7.011276E+00 1.383237E+02 + 9.099998E+00 6.000000E+01 3 4.212157E+01 2.404099E+00 4.208450E+01 1.766879E+00 + 9.099998E+00 6.000000E+01 4 6.062382E+02 8.708585E+01 3.082088E+01 6.054542E+02 + 9.099998E+00 6.000000E+01 5 1.187472E+02 8.955143E+01 9.296626E-01 1.187436E+02 + 9.099998E+00 6.000000E+01 6 1.157509E+03 -1.022758E+00 1.157325E+03 -2.066101E+01 + 9.099998E+00 9.000000E+01 1 9.364927E-06 -8.729887E+01 4.413322E-07 -9.354522E-06 + 9.099998E+00 9.000000E+01 2 1.774974E+02 8.705589E+01 9.116605E+00 1.772631E+02 + 9.099998E+00 9.000000E+01 3 4.811776E+01 2.741782E+00 4.806268E+01 2.301706E+00 + 9.099998E+00 9.000000E+01 4 7.997100E+02 8.712547E+01 4.010474E+01 7.987038E+02 + 9.099998E+00 9.000000E+01 5 3.099794E-04 -8.936478E+01 3.436606E-06 -3.099604E-04 + 9.099998E+00 9.000000E+01 6 1.093497E-04 1.793866E+02 -1.093434E-04 1.170687E-06 + 9.199999E+00 0.000000E+00 1 1.169471E+02 8.893913E+01 2.165245E+00 1.169271E+02 + 9.199999E+00 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 9.199999E+00 0.000000E+00 3 3.056842E+01 1.605399E+00 3.055642E+01 8.563998E-01 + 9.199999E+00 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 9.199999E+00 0.000000E+00 5 1.623999E+02 8.883729E+01 3.295392E+00 1.623665E+02 + 9.199999E+00 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 9.199999E+00 3.000000E+01 1 1.096390E+02 8.913246E+01 1.660030E+00 1.096264E+02 + 9.199999E+00 3.000000E+01 2 6.502007E+01 8.728464E+01 3.080281E+00 6.494707E+01 + 9.199999E+00 3.000000E+01 3 3.460962E+01 1.857570E+00 3.459143E+01 1.121872E+00 + 9.199999E+00 3.000000E+01 4 2.629997E+02 8.706934E+01 1.344649E+01 2.626557E+02 + 9.199999E+00 3.000000E+01 5 1.710542E+02 8.915020E+01 2.536954E+00 1.710354E+02 + 9.199999E+00 3.000000E+01 6 9.194749E+02 -1.013012E+00 9.193312E+02 -1.625583E+01 + 9.199999E+00 6.000000E+01 1 7.477536E+01 8.944529E+01 7.239272E-01 7.477186E+01 + 9.199999E+00 6.000000E+01 2 1.376372E+02 8.719436E+01 6.737082E+00 1.374722E+02 + 9.199999E+00 6.000000E+01 3 4.452791E+01 2.459471E+00 4.448689E+01 1.910812E+00 + 9.199999E+00 6.000000E+01 4 5.994178E+02 8.718303E+01 2.945880E+01 5.986935E+02 + 9.199999E+00 6.000000E+01 5 1.312729E+02 8.951003E+01 1.122579E+00 1.312681E+02 + 9.199999E+00 6.000000E+01 6 1.119135E+03 -9.388041E-01 1.118985E+03 -1.833646E+01 + 9.199999E+00 9.000000E+01 1 9.211790E-06 -8.743430E+01 4.123651E-07 -9.202556E-06 + 9.199999E+00 9.000000E+01 2 1.755691E+02 8.715659E+01 8.709388E+00 1.753530E+02 + 9.199999E+00 9.000000E+01 3 5.046645E+01 2.777081E+00 5.040718E+01 2.445111E+00 + 9.199999E+00 9.000000E+01 4 7.866900E+02 8.722346E+01 3.810787E+01 7.857665E+02 + 9.199999E+00 9.000000E+01 5 3.078333E-04 -8.937985E+01 3.331829E-06 -3.078153E-04 + 9.199999E+00 9.000000E+01 6 1.053368E-04 1.794351E+02 -1.053317E-04 1.038555E-06 + 9.299999E+00 0.000000E+00 1 1.172321E+02 8.897412E+01 2.098919E+00 1.172133E+02 + 9.299999E+00 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 9.299999E+00 0.000000E+00 3 3.291422E+01 1.695353E+00 3.289981E+01 9.737731E-01 + 9.299999E+00 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 9.299999E+00 0.000000E+00 5 1.867091E+02 8.889349E+01 3.605545E+00 1.866742E+02 + 9.299999E+00 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 9.299999E+00 3.000000E+01 1 1.095727E+02 8.914307E+01 1.638749E+00 1.095604E+02 + 9.299999E+00 3.000000E+01 2 6.516769E+01 8.736900E+01 2.991433E+00 6.509899E+01 + 9.299999E+00 3.000000E+01 3 3.699881E+01 1.936981E+00 3.697767E+01 1.250569E+00 + 9.299999E+00 3.000000E+01 4 2.628047E+02 8.716611E+01 1.299326E+01 2.624833E+02 + 9.299999E+00 3.000000E+01 5 1.918302E+02 8.915633E+01 2.824592E+00 1.918094E+02 + 9.299999E+00 3.000000E+01 6 8.967960E+02 -9.271351E-01 8.966786E+02 -1.451092E+01 + 9.299999E+00 6.000000E+01 1 7.421921E+01 8.941801E+01 7.538694E-01 7.421538E+01 + 9.299999E+00 6.000000E+01 2 1.367218E+02 8.728908E+01 6.466522E+00 1.365688E+02 + 9.299999E+00 6.000000E+01 3 4.690530E+01 2.503586E+00 4.686052E+01 2.048913E+00 + 9.299999E+00 6.000000E+01 4 5.924759E+02 8.727876E+01 2.812886E+01 5.918078E+02 + 9.299999E+00 6.000000E+01 5 1.432829E+02 8.947479E+01 1.313416E+00 1.432769E+02 + 9.299999E+00 6.000000E+01 6 1.082423E+03 -8.623536E-01 1.082300E+03 -1.629083E+01 + 9.299999E+00 9.000000E+01 1 9.064471E-06 -8.756777E+01 3.846747E-07 -9.056304E-06 + 9.299999E+00 9.000000E+01 2 1.736416E+02 8.725536E+01 8.314786E+00 1.734424E+02 + 9.299999E+00 9.000000E+01 3 5.278285E+01 2.802060E+00 5.271974E+01 2.580326E+00 + 9.299999E+00 9.000000E+01 4 7.738512E+02 8.731953E+01 3.618996E+01 7.730045E+02 + 9.299999E+00 9.000000E+01 5 3.056753E-04 -8.939530E+01 3.226063E-06 -3.056583E-04 + 9.299999E+00 9.000000E+01 6 1.015288E-04 1.794794E+02 -1.015247E-04 9.224037E-07 + 9.400000E+00 0.000000E+00 1 1.174227E+02 8.900529E+01 2.038470E+00 1.174050E+02 + 9.400000E+00 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 9.400000E+00 0.000000E+00 3 3.525301E+01 1.773938E+00 3.523611E+01 1.091296E+00 + 9.400000E+00 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 9.400000E+00 0.000000E+00 5 2.101871E+02 8.893999E+01 3.888407E+00 2.101512E+02 + 9.400000E+00 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 9.400000E+00 3.000000E+01 1 1.094354E+02 8.915318E+01 1.617389E+00 1.094234E+02 + 9.400000E+00 3.000000E+01 2 6.525328E+01 8.745300E+01 2.899776E+00 6.518882E+01 + 9.400000E+00 3.000000E+01 3 3.937164E+01 2.004708E+00 3.934754E+01 1.377283E+00 + 9.400000E+00 3.000000E+01 4 2.623578E+02 8.726190E+01 1.253300E+01 2.620582E+02 + 9.400000E+00 3.000000E+01 5 2.118597E+02 8.916341E+01 3.093292E+00 2.118371E+02 + 9.400000E+00 3.000000E+01 6 8.745499E+02 -8.493958E-01 8.744538E+02 -1.296451E+01 + 9.400000E+00 6.000000E+01 1 7.364943E+01 8.939521E+01 7.774000E-01 7.364532E+01 + 9.400000E+00 6.000000E+01 2 1.357621E+02 8.738207E+01 6.201006E+00 1.356204E+02 + 9.400000E+00 6.000000E+01 3 4.925246E+01 2.537764E+00 4.920415E+01 2.180793E+00 + 9.400000E+00 6.000000E+01 4 5.854478E+02 8.737270E+01 2.683640E+01 5.848324E+02 + 9.400000E+00 6.000000E+01 5 1.547827E+02 8.944517E+01 1.498852E+00 1.547754E+02 + 9.400000E+00 6.000000E+01 6 1.047306E+03 -7.927245E-01 1.047206E+03 -1.448970E+01 + 9.400000E+00 9.000000E+01 1 8.922653E-06 -8.769844E+01 3.583247E-07 -8.915456E-06 + 9.400000E+00 9.000000E+01 2 1.717189E+02 8.735191E+01 7.933661E+00 1.715355E+02 + 9.400000E+00 9.000000E+01 3 5.506533E+01 2.818021E+00 5.499874E+01 2.707227E+00 + 9.400000E+00 9.000000E+01 4 7.612180E+02 8.741341E+01 3.435312E+01 7.604424E+02 + 9.400000E+00 9.000000E+01 5 3.035088E-04 -8.941103E+01 3.119849E-06 -3.034928E-04 + 9.400000E+00 9.000000E+01 6 9.791365E-05 1.795200E+02 -9.791021E-05 8.202282E-07 + 9.500000E+00 0.000000E+00 1 1.175263E+02 8.903337E+01 1.982663E+00 1.175095E+02 + 9.500000E+00 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 9.500000E+00 0.000000E+00 3 3.758219E+01 1.841845E+00 3.756277E+01 1.207919E+00 + 9.500000E+00 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 9.500000E+00 0.000000E+00 5 2.328416E+02 8.897963E+01 4.146432E+00 2.328046E+02 + 9.500000E+00 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 9.500000E+00 3.000000E+01 1 1.092334E+02 8.916306E+01 1.595552E+00 1.092217E+02 + 9.500000E+00 3.000000E+01 2 6.528275E+01 8.753620E+01 2.806384E+00 6.522240E+01 + 9.500000E+00 3.000000E+01 3 4.172578E+01 2.061700E+00 4.169877E+01 1.501114E+00 + 9.500000E+00 3.000000E+01 4 2.616840E+02 8.735624E+01 1.207042E+01 2.614055E+02 + 9.500000E+00 3.000000E+01 5 2.311435E+02 8.917111E+01 3.343805E+00 2.311194E+02 + 9.500000E+00 3.000000E+01 6 8.527784E+02 -7.789711E-01 8.526996E+02 -1.159369E+01 + 9.500000E+00 6.000000E+01 1 7.306854E+01 8.937646E+01 7.951841E-01 7.306422E+01 + 9.500000E+00 6.000000E+01 2 1.347647E+02 8.747308E+01 5.941638E+00 1.346337E+02 + 9.500000E+00 6.000000E+01 3 5.156913E+01 2.562895E+00 5.151755E+01 2.305967E+00 + 9.500000E+00 6.000000E+01 4 5.783568E+02 8.746452E+01 2.558543E+01 5.777906E+02 + 9.500000E+00 6.000000E+01 5 1.657898E+02 8.942056E+01 1.676633E+00 1.657813E+02 + 9.500000E+00 6.000000E+01 6 1.013714E+03 -7.292941E-01 1.013632E+03 -1.290279E+01 + 9.500000E+00 9.000000E+01 1 8.785993E-06 -8.782562E+01 3.333497E-07 -8.779667E-06 + 9.500000E+00 9.000000E+01 2 1.698040E+02 8.744601E+01 7.566580E+00 1.696353E+02 + 9.500000E+00 9.000000E+01 3 5.731452E+01 2.825916E+00 5.724482E+01 2.825694E+00 + 9.500000E+00 9.000000E+01 4 7.487892E+02 8.750488E+01 3.259814E+01 7.480793E+02 + 9.500000E+00 9.000000E+01 5 3.013330E-04 -8.942694E+01 3.013811E-06 -3.013179E-04 + 9.500000E+00 9.000000E+01 6 9.447982E-05 1.795571E+02 -9.447700E-05 7.302739E-07 + 9.600000E+00 0.000000E+00 1 1.175499E+02 8.905898E+01 1.930542E+00 1.175340E+02 + 9.600000E+00 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 9.600000E+00 0.000000E+00 3 3.989761E+01 1.899998E+00 3.987568E+01 1.322811E+00 + 9.600000E+00 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 9.600000E+00 0.000000E+00 5 2.546638E+02 8.901414E+01 4.381640E+00 2.546261E+02 + 9.600000E+00 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 9.600000E+00 3.000000E+01 1 1.089727E+02 8.917290E+01 1.573015E+00 1.089613E+02 + 9.600000E+00 3.000000E+01 2 6.526106E+01 8.761814E+01 2.712210E+00 6.520468E+01 + 9.600000E+00 3.000000E+01 3 4.405827E+01 2.109046E+00 4.402843E+01 1.621410E+00 + 9.600000E+00 3.000000E+01 4 2.608084E+02 8.744871E+01 1.160957E+01 2.605499E+02 + 9.600000E+00 3.000000E+01 5 2.496811E+02 8.917929E+01 3.576336E+00 2.496555E+02 + 9.600000E+00 3.000000E+01 6 8.315068E+02 -7.151269E-01 8.314421E+02 -1.037803E+01 + 9.600000E+00 6.000000E+01 1 7.247884E+01 8.936135E+01 8.078730E-01 7.247433E+01 + 9.600000E+00 6.000000E+01 2 1.337359E+02 8.756182E+01 5.689329E+00 1.336148E+02 + 9.600000E+00 6.000000E+01 3 5.385368E+01 2.580039E+00 5.379909E+01 2.424221E+00 + 9.600000E+00 6.000000E+01 4 5.712331E+02 8.755403E+01 2.437869E+01 5.707126E+02 + 9.600000E+00 6.000000E+01 5 1.763068E+02 8.940032E+01 1.845266E+00 1.762971E+02 + 9.600000E+00 6.000000E+01 6 9.815810E+02 -6.714934E-01 9.815136E+02 -1.150364E+01 + 9.600000E+00 9.000000E+01 1 8.654189E-06 -8.794876E+01 3.097618E-07 -8.648643E-06 + 9.600000E+00 9.000000E+01 2 1.679009E+02 8.753750E+01 7.213941E+00 1.677458E+02 + 9.600000E+00 9.000000E+01 3 5.952987E+01 2.826792E+00 5.945744E+01 2.935823E+00 + 9.600000E+00 9.000000E+01 4 7.365856E+02 8.759377E+01 3.092498E+01 7.359361E+02 + 9.600000E+00 9.000000E+01 5 2.991584E-04 -8.944297E+01 2.908380E-06 -2.991442E-04 + 9.600000E+00 9.000000E+01 6 9.121706E-05 1.795911E+02 -9.121474E-05 6.510139E-07 + 9.700001E+00 0.000000E+00 1 1.175001E+02 8.908259E+01 1.881315E+00 1.174850E+02 + 9.700001E+00 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 9.700001E+00 0.000000E+00 3 4.219749E+01 1.949078E+00 4.217308E+01 1.435190E+00 + 9.700001E+00 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 9.700001E+00 0.000000E+00 5 2.756729E+02 8.904470E+01 4.596128E+00 2.756346E+02 + 9.700001E+00 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 9.700001E+00 3.000000E+01 1 1.086600E+02 8.918287E+01 1.549620E+00 1.086490E+02 + 9.700001E+00 3.000000E+01 2 6.519335E+01 8.769851E+01 2.618025E+00 6.514076E+01 + 9.700001E+00 3.000000E+01 3 4.636815E+01 2.147478E+00 4.633559E+01 1.737497E+00 + 9.700001E+00 3.000000E+01 4 2.597520E+02 8.753899E+01 1.115364E+01 2.595125E+02 + 9.700001E+00 3.000000E+01 5 2.675006E+02 8.918803E+01 3.790771E+00 2.674738E+02 + 9.700001E+00 3.000000E+01 6 8.107560E+02 -6.572052E-01 8.107027E+02 -9.299488E+00 + 9.700001E+00 6.000000E+01 1 7.188165E+01 8.934953E+01 8.160516E-01 7.187702E+01 + 9.700001E+00 6.000000E+01 2 1.326802E+02 8.764812E+01 5.444745E+00 1.325684E+02 + 9.700001E+00 6.000000E+01 3 5.610655E+01 2.589999E+00 5.604924E+01 2.535378E+00 + 9.700001E+00 6.000000E+01 4 5.640962E+02 8.764104E+01 2.321823E+01 5.636182E+02 + 9.700001E+00 6.000000E+01 5 1.863526E+02 8.938400E+01 2.003495E+00 1.863418E+02 + 9.700001E+00 6.000000E+01 6 9.508435E+02 -6.188014E-01 9.507880E+02 -1.026903E+01 + 9.700001E+00 9.000000E+01 1 8.526941E-06 -8.806748E+01 2.875491E-07 -8.522092E-06 + 9.700001E+00 9.000000E+01 2 1.660127E+02 8.762624E+01 6.875925E+00 1.658703E+02 + 9.700001E+00 9.000000E+01 3 6.171202E+01 2.821412E+00 6.163721E+01 3.037653E+00 + 9.700001E+00 9.000000E+01 4 7.246121E+02 8.767999E+01 2.933279E+01 7.240182E+02 + 9.700001E+00 9.000000E+01 5 2.969830E-04 -8.945903E+01 2.803997E-06 -2.969697E-04 + 9.700001E+00 9.000000E+01 6 8.811515E-05 1.796221E+02 -8.811324E-05 5.811088E-07 + 9.800001E+00 0.000000E+00 1 1.173830E+02 8.910458E+01 1.834391E+00 1.173687E+02 + 9.800001E+00 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 9.800001E+00 0.000000E+00 3 4.447944E+01 1.989984E+00 4.445261E+01 1.544539E+00 + 9.800001E+00 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 9.800001E+00 0.000000E+00 5 2.958734E+02 8.907237E+01 4.790026E+00 2.958347E+02 + 9.800001E+00 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 9.800001E+00 3.000000E+01 1 1.082990E+02 8.919299E+01 1.525331E+00 1.082883E+02 + 9.800001E+00 3.000000E+01 2 6.508414E+01 8.777704E+01 2.524505E+00 6.503516E+01 + 9.800001E+00 3.000000E+01 3 4.865367E+01 2.177999E+00 4.861852E+01 1.849039E+00 + 9.800001E+00 3.000000E+01 4 2.585378E+02 8.762685E+01 1.070539E+01 2.583160E+02 + 9.800001E+00 3.000000E+01 5 2.846022E+02 8.919722E+01 3.987484E+00 2.845743E+02 + 9.800001E+00 3.000000E+01 6 7.905407E+02 -6.046118E-01 7.904967E+02 -8.342000E+00 + 9.800001E+00 6.000000E+01 1 7.127917E+01 8.934064E+01 8.202709E-01 7.127444E+01 + 9.800001E+00 6.000000E+01 2 1.316037E+02 8.773186E+01 5.208350E+00 1.315005E+02 + 9.800001E+00 6.000000E+01 3 5.832739E+01 2.593717E+00 5.826764E+01 2.639515E+00 + 9.800001E+00 6.000000E+01 4 5.569635E+02 8.772540E+01 2.210526E+01 5.565247E+02 + 9.800001E+00 6.000000E+01 5 1.959448E+02 8.937125E+01 2.150185E+00 1.959330E+02 + 9.800001E+00 6.000000E+01 6 9.214333E+02 -5.707465E-01 9.213876E+02 -9.178619E+00 + 9.800001E+00 9.000000E+01 1 8.404029E-06 -8.818153E+01 2.666843E-07 -8.399797E-06 + 9.800001E+00 9.000000E+01 2 1.641413E+02 8.771213E+01 6.552562E+00 1.640104E+02 + 9.800001E+00 9.000000E+01 3 6.386058E+01 2.810702E+00 6.378376E+01 3.131488E+00 + 9.800001E+00 9.000000E+01 4 7.128737E+02 8.776344E+01 2.782015E+01 7.123307E+02 + 9.800001E+00 9.000000E+01 5 2.948142E-04 -8.947506E+01 2.701058E-06 -2.948018E-04 + 9.800001E+00 9.000000E+01 6 8.516476E-05 1.796506E+02 -8.516318E-05 5.193963E-07 + 9.900002E+00 0.000000E+00 1 1.172050E+02 8.912526E+01 1.789311E+00 1.171914E+02 + 9.900002E+00 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 9.900002E+00 0.000000E+00 3 4.674041E+01 2.023381E+00 4.671127E+01 1.650278E+00 + 9.900002E+00 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 9.900002E+00 0.000000E+00 5 3.152844E+02 8.909766E+01 4.965184E+00 3.152453E+02 + 9.900002E+00 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 9.900002E+00 3.000000E+01 1 1.078954E+02 8.920335E+01 1.500136E+00 1.078849E+02 + 9.900002E+00 3.000000E+01 2 6.493745E+01 8.785353E+01 2.432174E+00 6.489188E+01 + 9.900002E+00 3.000000E+01 3 5.091317E+01 2.201357E+00 5.087559E+01 1.955649E+00 + 9.900002E+00 3.000000E+01 4 2.571832E+02 8.771211E+01 1.026689E+01 2.569782E+02 + 9.900002E+00 3.000000E+01 5 3.009960E+02 8.920689E+01 4.166389E+00 3.009671E+02 + 9.900002E+00 3.000000E+01 6 7.708690E+02 -5.568187E-01 7.708326E+02 -7.491434E+00 + 9.900002E+00 6.000000E+01 1 7.067269E+01 8.933435E+01 8.210385E-01 7.066792E+01 + 9.900002E+00 6.000000E+01 2 1.305102E+02 8.781295E+01 4.980528E+00 1.304152E+02 + 9.900002E+00 6.000000E+01 3 6.051537E+01 2.591830E+00 6.045346E+01 2.736538E+00 + 9.900002E+00 6.000000E+01 4 5.498582E+02 8.780705E+01 2.104022E+01 5.494555E+02 + 9.900002E+00 6.000000E+01 5 2.050883E+02 8.936155E+01 2.285264E+00 2.050755E+02 + 9.900002E+00 6.000000E+01 6 8.932906E+02 -5.268963E-01 8.932528E+02 -8.214651E+00 + 9.900002E+00 9.000000E+01 1 8.285133E-06 -8.829071E+01 2.471319E-07 -8.281447E-06 + 9.900002E+00 9.000000E+01 2 1.622894E+02 8.779511E+01 6.243764E+00 1.621692E+02 + 9.900002E+00 9.000000E+01 3 6.597607E+01 2.795250E+00 6.589757E+01 3.217452E+00 + 9.900002E+00 9.000000E+01 4 7.013761E+02 8.784407E+01 2.638522E+01 7.008796E+02 + 9.900002E+00 9.000000E+01 5 2.926507E-04 -8.949097E+01 2.599930E-06 -2.926391E-04 + 9.900002E+00 9.000000E+01 6 8.235678E-05 1.796766E+02 -8.235547E-05 4.648591E-07 + 1.000000E+01 0.000000E+00 1 1.169712E+02 8.914487E+01 1.745720E+00 1.169581E+02 + 1.000000E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.000000E+01 0.000000E+00 3 4.897959E+01 2.049965E+00 4.894825E+01 1.752050E+00 + 1.000000E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.000000E+01 0.000000E+00 5 3.339042E+02 8.912106E+01 5.122027E+00 3.338649E+02 + 1.000000E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.000000E+01 3.000000E+01 1 1.074541E+02 8.921397E+01 1.474098E+00 1.074440E+02 + 1.000000E+01 3.000000E+01 2 6.475717E+01 8.792786E+01 2.341482E+00 6.471483E+01 + 1.000000E+01 3.000000E+01 3 5.314511E+01 2.218310E+00 5.310529E+01 2.057096E+00 + 1.000000E+01 3.000000E+01 4 2.557055E+02 8.779467E+01 9.839749E+00 2.555161E+02 + 1.000000E+01 3.000000E+01 5 3.167002E+02 8.921693E+01 4.328268E+00 3.166707E+02 + 1.000000E+01 3.000000E+01 6 7.517448E+02 -5.133530E-01 7.517147E+02 -6.735319E+00 + 1.000000E+01 6.000000E+01 1 7.006360E+01 8.933038E+01 8.188215E-01 7.005882E+01 + 1.000000E+01 6.000000E+01 2 1.294039E+02 8.789131E+01 4.761447E+00 1.293162E+02 + 1.000000E+01 6.000000E+01 3 6.267030E+01 2.585020E+00 6.260653E+01 2.826543E+00 + 1.000000E+01 6.000000E+01 4 5.427922E+02 8.788593E+01 2.002315E+01 5.424228E+02 + 1.000000E+01 6.000000E+01 5 2.138007E+02 8.935457E+01 2.408391E+00 2.137871E+02 + 1.000000E+01 6.000000E+01 6 8.663563E+02 -4.868632E-01 8.663251E+02 -7.361658E+00 + 1.000000E+01 9.000000E+01 1 8.170079E-06 -8.839492E+01 2.288456E-07 -8.166873E-06 + 1.000000E+01 9.000000E+01 2 1.604586E+02 8.787517E+01 5.949301E+00 1.603483E+02 + 1.000000E+01 9.000000E+01 3 6.805760E+01 2.775809E+00 6.797775E+01 3.295897E+00 + 1.000000E+01 9.000000E+01 4 6.901216E+02 8.792185E+01 2.502566E+01 6.896677E+02 + 1.000000E+01 9.000000E+01 5 2.904943E-04 -8.950674E+01 2.500847E-06 -2.904835E-04 + 1.000000E+01 9.000000E+01 6 7.968334E-05 1.797004E+02 -7.968225E-05 4.166122E-07 + 1.010000E+01 0.000000E+00 1 1.166864E+02 8.916358E+01 1.703356E+00 1.166740E+02 + 1.010000E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.010000E+01 0.000000E+00 3 5.119496E+01 2.070443E+00 5.116154E+01 1.849581E+00 + 1.010000E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.010000E+01 0.000000E+00 5 3.517633E+02 8.914294E+01 5.261702E+00 3.517239E+02 + 1.010000E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.010000E+01 3.000000E+01 1 1.069780E+02 8.922484E+01 1.447280E+00 1.069682E+02 + 1.010000E+01 3.000000E+01 2 6.454665E+01 8.799989E+01 2.252775E+00 6.450732E+01 + 1.010000E+01 3.000000E+01 3 5.534990E+01 2.229496E+00 5.530801E+01 2.153234E+00 + 1.010000E+01 3.000000E+01 4 2.541205E+02 8.787442E+01 9.425289E+00 2.539457E+02 + 1.010000E+01 3.000000E+01 5 3.317360E+02 8.922735E+01 4.473430E+00 3.317058E+02 + 1.010000E+01 3.000000E+01 6 7.331686E+02 -4.737875E-01 7.331436E+02 -6.062614E+00 + 1.010000E+01 6.000000E+01 1 6.945335E+01 8.932846E+01 8.140199E-01 6.944859E+01 + 1.010000E+01 6.000000E+01 2 1.282881E+02 8.796692E+01 4.551222E+00 1.282073E+02 + 1.010000E+01 6.000000E+01 3 6.479252E+01 2.573969E+00 6.472715E+01 2.909775E+00 + 1.010000E+01 6.000000E+01 4 5.357795E+02 8.796202E+01 1.905341E+01 5.354407E+02 + 1.010000E+01 6.000000E+01 5 2.220971E+02 8.935001E+01 2.519507E+00 2.220828E+02 + 1.010000E+01 6.000000E+01 6 8.405726E+02 -4.502915E-01 8.405467E+02 -6.606051E+00 + 1.010000E+01 9.000000E+01 1 8.058648E-06 -8.849416E+01 2.117711E-07 -8.055865E-06 + 1.010000E+01 9.000000E+01 2 1.586507E+02 8.795229E+01 5.668875E+00 1.585494E+02 + 1.010000E+01 9.000000E+01 3 7.010595E+01 2.752871E+00 7.002505E+01 3.367061E+00 + 1.010000E+01 9.000000E+01 4 6.791106E+02 8.799677E+01 2.373888E+01 6.786956E+02 + 1.010000E+01 9.000000E+01 5 2.883523E-04 -8.952231E+01 2.404073E-06 -2.883423E-04 + 1.010000E+01 9.000000E+01 6 7.713650E-05 1.797223E+02 -7.713559E-05 3.738827E-07 + 1.020000E+01 0.000000E+00 1 1.163559E+02 8.918156E+01 1.662029E+00 1.163440E+02 + 1.020000E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.020000E+01 0.000000E+00 3 5.338578E+01 2.085252E+00 5.335043E+01 1.942520E+00 + 1.020000E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.020000E+01 0.000000E+00 5 3.688779E+02 8.916357E+01 5.384873E+00 3.688386E+02 + 1.020000E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.020000E+01 3.000000E+01 1 1.064719E+02 8.923595E+01 1.419788E+00 1.064624E+02 + 1.020000E+01 3.000000E+01 2 6.430946E+01 8.806957E+01 2.166323E+00 6.427296E+01 + 1.020000E+01 3.000000E+01 3 5.752578E+01 2.235494E+00 5.748199E+01 2.243899E+00 + 1.020000E+01 3.000000E+01 4 2.524415E+02 8.795133E+01 9.024391E+00 2.522802E+02 + 1.020000E+01 3.000000E+01 5 3.461152E+02 8.923814E+01 4.602109E+00 3.460846E+02 + 1.020000E+01 3.000000E+01 6 7.151368E+02 -4.377417E-01 7.151159E+02 -5.463615E+00 + 1.020000E+01 6.000000E+01 1 6.884287E+01 8.932832E+01 8.070253E-01 6.883814E+01 + 1.020000E+01 6.000000E+01 2 1.271661E+02 8.803976E+01 4.349825E+00 1.270917E+02 + 1.020000E+01 6.000000E+01 3 6.688241E+01 2.559122E+00 6.681570E+01 2.986316E+00 + 1.020000E+01 6.000000E+01 4 5.288314E+02 8.803529E+01 1.813049E+01 5.285204E+02 + 1.020000E+01 6.000000E+01 5 2.299881E+02 8.934759E+01 2.618761E+00 2.299732E+02 + 1.020000E+01 6.000000E+01 6 8.158806E+02 -4.168615E-01 8.158589E+02 -5.935972E+00 + 1.020000E+01 9.000000E+01 1 7.950614E-06 -8.858845E+01 1.958533E-07 -7.948202E-06 + 1.020000E+01 9.000000E+01 2 1.568666E+02 8.802647E+01 5.402133E+00 1.567735E+02 + 1.020000E+01 9.000000E+01 3 7.212234E+01 2.726942E+00 7.204066E+01 3.431303E+00 + 1.020000E+01 9.000000E+01 4 6.683471E+02 8.806887E+01 2.252207E+01 6.679675E+02 + 1.020000E+01 9.000000E+01 5 2.862214E-04 -8.953762E+01 2.309812E-06 -2.862121E-04 + 1.020000E+01 9.000000E+01 6 7.470902E-05 1.797423E+02 -7.470826E-05 3.359954E-07 + 1.030000E+01 0.000000E+00 1 1.159833E+02 8.919891E+01 1.621601E+00 1.159719E+02 + 1.030000E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.030000E+01 0.000000E+00 3 5.555044E+01 2.095102E+00 5.551330E+01 2.030828E+00 + 1.030000E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.030000E+01 0.000000E+00 5 3.852576E+02 8.918316E+01 5.492260E+00 3.852184E+02 + 1.030000E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.030000E+01 3.000000E+01 1 1.059390E+02 8.924728E+01 1.391723E+00 1.059299E+02 + 1.030000E+01 3.000000E+01 2 6.404846E+01 8.813687E+01 2.082344E+00 6.401460E+01 + 1.030000E+01 3.000000E+01 3 5.967226E+01 2.236973E+00 5.962678E+01 2.329164E+00 + 1.030000E+01 3.000000E+01 4 2.506837E+02 8.802541E+01 8.637652E+00 2.505348E+02 + 1.030000E+01 3.000000E+01 5 3.598548E+02 8.924917E+01 4.715608E+00 3.598239E+02 + 1.030000E+01 3.000000E+01 6 6.976420E+02 -4.048707E-01 6.976246E+02 -4.929726E+00 + 1.030000E+01 6.000000E+01 1 6.823340E+01 8.932977E+01 7.981609E-01 6.822873E+01 + 1.030000E+01 6.000000E+01 2 1.260409E+02 8.810987E+01 4.157207E+00 1.259723E+02 + 1.030000E+01 6.000000E+01 3 6.893880E+01 2.541027E+00 6.887101E+01 3.056384E+00 + 1.030000E+01 6.000000E+01 4 5.219585E+02 8.810577E+01 1.725308E+01 5.216733E+02 + 1.030000E+01 6.000000E+01 5 2.374935E+02 8.934695E+01 2.706846E+00 2.374780E+02 + 1.030000E+01 6.000000E+01 6 7.922292E+02 -3.862822E-01 7.922112E+02 -5.341087E+00 + 1.030000E+01 9.000000E+01 1 7.845823E-06 -8.867785E+01 1.810329E-07 -7.843734E-06 + 1.030000E+01 9.000000E+01 2 1.551079E+02 8.809779E+01 5.148639E+00 1.550224E+02 + 1.030000E+01 9.000000E+01 3 7.410574E+01 2.698485E+00 7.402357E+01 3.488901E+00 + 1.030000E+01 9.000000E+01 4 6.578296E+02 8.813818E+01 2.137241E+01 6.574823E+02 + 1.030000E+01 9.000000E+01 5 2.841064E-04 -8.955265E+01 2.218179E-06 -2.840977E-04 + 1.030000E+01 9.000000E+01 6 7.239411E-05 1.797607E+02 -7.239348E-05 3.023628E-07 + 1.040000E+01 0.000000E+00 1 1.155735E+02 8.921570E+01 1.581993E+00 1.155627E+02 + 1.040000E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.040000E+01 0.000000E+00 3 5.768827E+01 2.100430E+00 5.764951E+01 2.114344E+00 + 1.040000E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.040000E+01 0.000000E+00 5 4.009281E+02 8.920187E+01 5.584766E+00 4.008892E+02 + 1.040000E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.040000E+01 3.000000E+01 1 1.053823E+02 8.925881E+01 1.363213E+00 1.053735E+02 + 1.040000E+01 3.000000E+01 2 6.376615E+01 8.820177E+01 2.000984E+00 6.373475E+01 + 1.040000E+01 3.000000E+01 3 6.178837E+01 2.234376E+00 6.174139E+01 2.408964E+00 + 1.040000E+01 3.000000E+01 4 2.488582E+02 8.809665E+01 8.265490E+00 2.487209E+02 + 1.040000E+01 3.000000E+01 5 3.729734E+02 8.926048E+01 4.813849E+00 3.729423E+02 + 1.040000E+01 3.000000E+01 6 6.806799E+02 -3.748697E-01 6.806653E+02 -4.453459E+00 + 1.040000E+01 6.000000E+01 1 6.762556E+01 8.933258E+01 7.877367E-01 6.762097E+01 + 1.040000E+01 6.000000E+01 2 1.249154E+02 8.817728E+01 3.973207E+00 1.248521E+02 + 1.040000E+01 6.000000E+01 3 7.096295E+01 2.520146E+00 7.089432E+01 3.120288E+00 + 1.040000E+01 6.000000E+01 4 5.151669E+02 8.817352E+01 1.641975E+01 5.149052E+02 + 1.040000E+01 6.000000E+01 5 2.446202E+02 8.934795E+01 2.783833E+00 2.446044E+02 + 1.040000E+01 6.000000E+01 6 7.695685E+02 -3.582901E-01 7.695535E+02 -4.812344E+00 + 1.040000E+01 9.000000E+01 1 7.744115E-06 -8.876249E+01 1.672494E-07 -7.742309E-06 + 1.040000E+01 9.000000E+01 2 1.533754E+02 8.816624E+01 4.907936E+00 1.532968E+02 + 1.040000E+01 9.000000E+01 3 7.605679E+01 2.667913E+00 7.597435E+01 3.540219E+00 + 1.040000E+01 9.000000E+01 4 6.475590E+02 8.820473E+01 2.028681E+01 6.472411E+02 + 1.040000E+01 9.000000E+01 5 2.820044E-04 -8.956738E+01 2.129336E-06 -2.819964E-04 + 1.040000E+01 9.000000E+01 6 7.018534E-05 1.797776E+02 -7.018481E-05 2.724718E-07 + 1.050000E+01 0.000000E+00 1 1.151296E+02 8.923202E+01 1.543128E+00 1.151192E+02 + 1.050000E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.050000E+01 0.000000E+00 3 5.979835E+01 2.101754E+00 5.975812E+01 2.193062E+00 + 1.050000E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.050000E+01 0.000000E+00 5 4.159096E+02 8.921983E+01 5.663044E+00 4.158711E+02 + 1.050000E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.050000E+01 3.000000E+01 1 1.048050E+02 8.927050E+01 1.334369E+00 1.047966E+02 + 1.050000E+01 3.000000E+01 2 6.346526E+01 8.826427E+01 1.922339E+00 6.343614E+01 + 1.050000E+01 3.000000E+01 3 6.387455E+01 2.228186E+00 6.382626E+01 2.483403E+00 + 1.050000E+01 3.000000E+01 4 2.469748E+02 8.816509E+01 7.908054E+00 2.468482E+02 + 1.050000E+01 3.000000E+01 5 3.854914E+02 8.927195E+01 4.898271E+00 3.854603E+02 + 1.050000E+01 3.000000E+01 6 6.642385E+02 -3.474618E-01 6.642263E+02 -4.028152E+00 + 1.050000E+01 6.000000E+01 1 6.702032E+01 8.933657E+01 7.760142E-01 6.701583E+01 + 1.050000E+01 6.000000E+01 2 1.237905E+02 8.824201E+01 3.797640E+00 1.237323E+02 + 1.050000E+01 6.000000E+01 3 7.295372E+01 2.496862E+00 7.288446E+01 3.178205E+00 + 1.050000E+01 6.000000E+01 4 5.084659E+02 8.823856E+01 1.562921E+01 5.082257E+02 + 1.050000E+01 6.000000E+01 5 2.513903E+02 8.935038E+01 2.850223E+00 2.513742E+02 + 1.050000E+01 6.000000E+01 6 7.478476E+02 -3.326485E-01 7.478350E+02 -4.341838E+00 + 1.050000E+01 9.000000E+01 1 7.645333E-06 -8.884250E+01 1.544425E-07 -7.643774E-06 + 1.050000E+01 9.000000E+01 2 1.516699E+02 8.823196E+01 4.679524E+00 1.515977E+02 + 1.050000E+01 9.000000E+01 3 7.797541E+01 2.635607E+00 7.789293E+01 3.585605E+00 + 1.050000E+01 9.000000E+01 4 6.375266E+02 8.826861E+01 1.926221E+01 6.372355E+02 + 1.050000E+01 9.000000E+01 5 2.799223E-04 -8.958176E+01 2.043348E-06 -2.799149E-04 + 1.050000E+01 9.000000E+01 6 6.807659E-05 1.797931E+02 -6.807614E-05 2.458727E-07 + 1.060000E+01 0.000000E+00 1 1.146553E+02 8.924791E+01 1.504978E+00 1.146454E+02 + 1.060000E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.060000E+01 0.000000E+00 3 6.187998E+01 2.099505E+00 6.183844E+01 2.266978E+00 + 1.060000E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.060000E+01 0.000000E+00 5 4.302150E+02 8.923714E+01 5.727894E+00 4.301769E+02 + 1.060000E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.060000E+01 3.000000E+01 1 1.042095E+02 8.928232E+01 1.305299E+00 1.042013E+02 + 1.060000E+01 3.000000E+01 2 6.314794E+01 8.832440E+01 1.846480E+00 6.312094E+01 + 1.060000E+01 3.000000E+01 3 6.592982E+01 2.218868E+00 6.588039E+01 2.552597E+00 + 1.060000E+01 3.000000E+01 4 2.450438E+02 8.823080E+01 7.565379E+00 2.449270E+02 + 1.060000E+01 3.000000E+01 5 3.974218E+02 8.928361E+01 4.969038E+00 3.973907E+02 + 1.060000E+01 3.000000E+01 6 6.483076E+02 -3.223989E-01 6.482973E+02 -3.647957E+00 + 1.060000E+01 6.000000E+01 1 6.641848E+01 8.934158E+01 7.632339E-01 6.641409E+01 + 1.060000E+01 6.000000E+01 2 1.226696E+02 8.830415E+01 3.630279E+00 1.226159E+02 + 1.060000E+01 6.000000E+01 3 7.491222E+01 2.471537E+00 7.484253E+01 3.230445E+00 + 1.060000E+01 6.000000E+01 4 5.018592E+02 8.830099E+01 1.487966E+01 5.016385E+02 + 1.060000E+01 6.000000E+01 5 2.578091E+02 8.935396E+01 2.906878E+00 2.577927E+02 + 1.060000E+01 6.000000E+01 6 7.270218E+02 -3.091397E-01 7.270112E+02 -3.922631E+00 + 1.060000E+01 9.000000E+01 1 7.549281E-06 -8.891802E+01 1.425530E-07 -7.547935E-06 + 1.060000E+01 9.000000E+01 2 1.499921E+02 8.829495E+01 4.462903E+00 1.499257E+02 + 1.060000E+01 9.000000E+01 3 7.986166E+01 2.601855E+00 7.977934E+01 3.625347E+00 + 1.060000E+01 9.000000E+01 4 6.277375E+02 8.832988E+01 1.829544E+01 6.274709E+02 + 1.060000E+01 9.000000E+01 5 2.778549E-04 -8.959577E+01 1.960276E-06 -2.778480E-04 + 1.060000E+01 9.000000E+01 6 6.606242E-05 1.798073E+02 -6.606205E-05 2.221744E-07 + 1.070000E+01 0.000000E+00 1 1.141537E+02 8.926340E+01 1.467511E+00 1.141442E+02 + 1.070000E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.070000E+01 0.000000E+00 3 6.393304E+01 2.094086E+00 6.389034E+01 2.336149E+00 + 1.070000E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.070000E+01 0.000000E+00 5 4.438734E+02 8.925386E+01 5.780247E+00 4.438358E+02 + 1.070000E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.070000E+01 3.000000E+01 1 1.035983E+02 8.929422E+01 1.276119E+00 1.035905E+02 + 1.070000E+01 3.000000E+01 2 6.281622E+01 8.838221E+01 1.773431E+00 6.279118E+01 + 1.070000E+01 3.000000E+01 3 6.795429E+01 2.206761E+00 6.790389E+01 2.616629E+00 + 1.070000E+01 3.000000E+01 4 2.430734E+02 8.829381E+01 7.237322E+00 2.429656E+02 + 1.070000E+01 3.000000E+01 5 4.087933E+02 8.929536E+01 5.027290E+00 4.087624E+02 + 1.070000E+01 3.000000E+01 6 6.328757E+02 -2.994595E-01 6.328670E+02 -3.307744E+00 + 1.070000E+01 6.000000E+01 1 6.582057E+01 8.934747E+01 7.495978E-01 6.581631E+01 + 1.070000E+01 6.000000E+01 2 1.215535E+02 8.836374E+01 3.470883E+00 1.215040E+02 + 1.070000E+01 6.000000E+01 3 7.683866E+01 2.444463E+00 7.676874E+01 3.277245E+00 + 1.070000E+01 6.000000E+01 4 4.953550E+02 8.836084E+01 1.416955E+01 4.951523E+02 + 1.070000E+01 6.000000E+01 5 2.638965E+02 8.935859E+01 2.954202E+00 2.638800E+02 + 1.070000E+01 6.000000E+01 6 7.070473E+02 -2.875706E-01 7.070384E+02 -3.548694E+00 + 1.070000E+01 9.000000E+01 1 7.455899E-06 -8.898923E+01 1.315240E-07 -7.454739E-06 + 1.070000E+01 9.000000E+01 2 1.483416E+02 8.835533E+01 4.257556E+00 1.482805E+02 + 1.070000E+01 9.000000E+01 3 8.171694E+01 2.566934E+00 8.163495E+01 3.659813E+00 + 1.070000E+01 9.000000E+01 4 6.181830E+02 8.838859E+01 1.738377E+01 6.179386E+02 + 1.070000E+01 9.000000E+01 5 2.758073E-04 -8.960943E+01 1.880126E-06 -2.758008E-04 + 1.070000E+01 9.000000E+01 6 6.413752E-05 1.798204E+02 -6.413721E-05 2.010338E-07 + 1.080000E+01 0.000000E+00 1 1.136280E+02 8.927855E+01 1.430734E+00 1.136190E+02 + 1.080000E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.080000E+01 0.000000E+00 3 6.595620E+01 2.085848E+00 6.591250E+01 2.400599E+00 + 1.080000E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.080000E+01 0.000000E+00 5 4.568948E+02 8.927005E+01 5.820706E+00 4.568578E+02 + 1.080000E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.080000E+01 3.000000E+01 1 1.029741E+02 8.930618E+01 1.246922E+00 1.029666E+02 + 1.080000E+01 3.000000E+01 2 6.247221E+01 8.843774E+01 1.703198E+00 6.244899E+01 + 1.080000E+01 3.000000E+01 3 6.994787E+01 2.192204E+00 6.989668E+01 2.675635E+00 + 1.080000E+01 3.000000E+01 4 2.410707E+02 8.835420E+01 6.923707E+00 2.409713E+02 + 1.080000E+01 3.000000E+01 5 4.196074E+02 8.930720E+01 5.073658E+00 4.195768E+02 + 1.080000E+01 3.000000E+01 6 6.179302E+02 -2.784428E-01 6.179229E+02 -3.002970E+00 + 1.080000E+01 6.000000E+01 1 6.522710E+01 8.935410E+01 7.352954E-01 6.522296E+01 + 1.080000E+01 6.000000E+01 2 1.204439E+02 8.842086E+01 3.319156E+00 1.203982E+02 + 1.080000E+01 6.000000E+01 3 7.873296E+01 2.415946E+00 7.866298E+01 3.318888E+00 + 1.080000E+01 6.000000E+01 4 4.889547E+02 8.841821E+01 1.349714E+01 4.887684E+02 + 1.080000E+01 6.000000E+01 5 2.696635E+02 8.936408E+01 2.992888E+00 2.696469E+02 + 1.080000E+01 6.000000E+01 6 6.878823E+02 -2.677642E-01 6.878748E+02 -3.214714E+00 + 1.080000E+01 9.000000E+01 1 7.365016E-06 -8.905633E+01 1.212971E-07 -7.364017E-06 + 1.080000E+01 9.000000E+01 2 1.467195E+02 8.841316E+01 4.062960E+00 1.466632E+02 + 1.080000E+01 9.000000E+01 3 8.354046E+01 2.531108E+00 8.345895E+01 3.689297E+00 + 1.080000E+01 9.000000E+01 4 6.088626E+02 8.844485E+01 1.652410E+01 6.086384E+02 + 1.080000E+01 9.000000E+01 5 2.737784E-04 -8.962268E+01 1.802924E-06 -2.737724E-04 + 1.080000E+01 9.000000E+01 6 6.229666E-05 1.798325E+02 -6.229639E-05 1.821510E-07 + 1.090001E+01 0.000000E+00 1 1.130809E+02 8.929334E+01 1.394639E+00 1.130723E+02 + 1.090001E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.090001E+01 0.000000E+00 3 6.795072E+01 2.075143E+00 6.790616E+01 2.460506E+00 + 1.090001E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.090001E+01 0.000000E+00 5 4.693108E+02 8.928577E+01 5.850070E+00 4.692743E+02 + 1.090001E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.090001E+01 3.000000E+01 1 1.023384E+02 8.931818E+01 1.217809E+00 1.023312E+02 + 1.090001E+01 3.000000E+01 2 6.211732E+01 8.849104E+01 1.635760E+00 6.209578E+01 + 1.090001E+01 3.000000E+01 3 7.191013E+01 2.175603E+00 7.185829E+01 2.729875E+00 + 1.090001E+01 3.000000E+01 4 2.390453E+02 8.841207E+01 6.624189E+00 2.389535E+02 + 1.090001E+01 3.000000E+01 5 4.299111E+02 8.931908E+01 5.109051E+00 4.298808E+02 + 1.090001E+01 3.000000E+01 6 6.034572E+02 -2.591694E-01 6.034510E+02 -2.729645E+00 + 1.090001E+01 6.000000E+01 1 6.463866E+01 8.936135E+01 7.204774E-01 6.463465E+01 + 1.090001E+01 6.000000E+01 2 1.193423E+02 8.847560E+01 3.174819E+00 1.193001E+02 + 1.090001E+01 6.000000E+01 3 8.059480E+01 2.386306E+00 8.052491E+01 3.355714E+00 + 1.090001E+01 6.000000E+01 4 4.826599E+02 8.847315E+01 1.286060E+01 4.824885E+02 + 1.090001E+01 6.000000E+01 5 2.751201E+02 8.937035E+01 3.023324E+00 2.751035E+02 + 1.090001E+01 6.000000E+01 6 6.694854E+02 -2.495624E-01 6.694791E+02 -2.916059E+00 + 1.090001E+01 9.000000E+01 1 7.276533E-06 -8.911949E+01 1.118204E-07 -7.275674E-06 + 1.090001E+01 9.000000E+01 2 1.451256E+02 8.846854E+01 3.878605E+00 1.450737E+02 + 1.090001E+01 9.000000E+01 3 8.533361E+01 2.494587E+00 8.525275E+01 3.714146E+00 + 1.090001E+01 9.000000E+01 4 5.997737E+02 8.849873E+01 1.571356E+01 5.995679E+02 + 1.090001E+01 9.000000E+01 5 2.717693E-04 -8.963556E+01 1.728637E-06 -2.717638E-04 + 1.090001E+01 9.000000E+01 6 6.053559E-05 1.798436E+02 -6.053536E-05 1.652639E-07 + 1.100001E+01 0.000000E+00 1 1.125144E+02 8.930782E+01 1.359243E+00 1.125062E+02 + 1.100001E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.100001E+01 0.000000E+00 3 6.991489E+01 2.062274E+00 6.986961E+01 2.515937E+00 + 1.100001E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.100001E+01 0.000000E+00 5 4.811365E+02 8.930108E+01 5.869034E+00 4.811007E+02 + 1.100001E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.100001E+01 3.000000E+01 1 1.016928E+02 8.933015E+01 1.188864E+00 1.016858E+02 + 1.100001E+01 3.000000E+01 2 6.175324E+01 8.854217E+01 1.571076E+00 6.173325E+01 + 1.100001E+01 3.000000E+01 3 7.384133E+01 2.157180E+00 7.378900E+01 2.779461E+00 + 1.100001E+01 3.000000E+01 4 2.370016E+02 8.846749E+01 6.338412E+00 2.369169E+02 + 1.100001E+01 3.000000E+01 5 4.396971E+02 8.933101E+01 5.133879E+00 4.396672E+02 + 1.100001E+01 3.000000E+01 6 5.894427E+02 -2.414777E-01 5.894375E+02 -2.484246E+00 + 1.100001E+01 6.000000E+01 1 6.405579E+01 8.936913E+01 7.052865E-01 6.405190E+01 + 1.100001E+01 6.000000E+01 2 1.182499E+02 8.852805E+01 3.037569E+00 1.182109E+02 + 1.100001E+01 6.000000E+01 3 8.242564E+01 2.355674E+00 8.235598E+01 3.387915E+00 + 1.100001E+01 6.000000E+01 4 4.764743E+02 8.852579E+01 1.225823E+01 4.763166E+02 + 1.100001E+01 6.000000E+01 5 2.802826E+02 8.937723E+01 3.046450E+00 2.802660E+02 + 1.100001E+01 6.000000E+01 6 6.518202E+02 -2.328204E-01 6.518148E+02 -2.648653E+00 + 1.100001E+01 9.000000E+01 1 7.190376E-06 -8.917889E+01 1.030418E-07 -7.189638E-06 + 1.100001E+01 9.000000E+01 2 1.435599E+02 8.852155E+01 3.703973E+00 1.435121E+02 + 1.100001E+01 9.000000E+01 3 8.709569E+01 2.457584E+00 8.701558E+01 3.734643E+00 + 1.100001E+01 9.000000E+01 4 5.909086E+02 8.855032E+01 1.494944E+01 5.907194E+02 + 1.100001E+01 9.000000E+01 5 2.697787E-04 -8.964803E+01 1.657267E-06 -2.697736E-04 + 1.100001E+01 9.000000E+01 6 5.884979E-05 1.798538E+02 -5.884960E-05 1.501424E-07 + 1.110001E+01 0.000000E+00 1 1.119316E+02 8.932198E+01 1.324538E+00 1.119238E+02 + 1.110001E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.110001E+01 0.000000E+00 3 7.184986E+01 2.047471E+00 7.180399E+01 2.567016E+00 + 1.110001E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.110001E+01 0.000000E+00 5 4.924015E+02 8.931596E+01 5.878577E+00 4.923664E+02 + 1.110001E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.110001E+01 3.000000E+01 1 1.010397E+02 8.934211E+01 1.160147E+00 1.010330E+02 + 1.110001E+01 3.000000E+01 2 6.138131E+01 8.859121E+01 1.509093E+00 6.136276E+01 + 1.110001E+01 3.000000E+01 3 7.574242E+01 2.137134E+00 7.568974E+01 2.824539E+00 + 1.110001E+01 3.000000E+01 4 2.349445E+02 8.852053E+01 6.065991E+00 2.348662E+02 + 1.110001E+01 3.000000E+01 5 4.489980E+02 8.934286E+01 5.149603E+00 4.489685E+02 + 1.110001E+01 3.000000E+01 6 5.758735E+02 -2.252217E-01 5.758691E+02 -2.263673E+00 + 1.110001E+01 6.000000E+01 1 6.347852E+01 8.937733E+01 6.898419E-01 6.347477E+01 + 1.110001E+01 6.000000E+01 2 1.171672E+02 8.857825E+01 2.907109E+00 1.171311E+02 + 1.110001E+01 6.000000E+01 3 8.422581E+01 2.324244E+00 8.415652E+01 3.415742E+00 + 1.110001E+01 6.000000E+01 4 4.703987E+02 8.857618E+01 1.168838E+01 4.702535E+02 + 1.110001E+01 6.000000E+01 5 2.851645E+02 8.938467E+01 3.062518E+00 2.851480E+02 + 1.110001E+01 6.000000E+01 6 6.348505E+02 -2.174072E-01 6.348459E+02 -2.408916E+00 + 1.110001E+01 9.000000E+01 1 7.106396E-06 -8.923474E+01 9.491247E-08 -7.105763E-06 + 1.110001E+01 9.000000E+01 2 1.420220E+02 8.857228E+01 3.538598E+00 1.419779E+02 + 1.110001E+01 9.000000E+01 3 8.882748E+01 2.420229E+00 8.874824E+01 3.751043E+00 + 1.110001E+01 9.000000E+01 4 5.822624E+02 8.859971E+01 1.422893E+01 5.820885E+02 + 1.110001E+01 9.000000E+01 5 2.678100E-04 -8.966010E+01 1.588743E-06 -2.678053E-04 + 1.110001E+01 9.000000E+01 6 5.723511E-05 1.798633E+02 -5.723494E-05 1.365836E-07 + 1.120001E+01 0.000000E+00 1 1.113342E+02 8.933583E+01 1.290555E+00 1.113267E+02 + 1.120001E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.120001E+01 0.000000E+00 3 7.375426E+01 2.031043E+00 7.370792E+01 2.613922E+00 + 1.120001E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.120001E+01 0.000000E+00 5 5.031029E+02 8.933041E+01 5.879393E+00 5.030686E+02 + 1.120001E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.120001E+01 3.000000E+01 1 1.003808E+02 8.935400E+01 1.131748E+00 1.003744E+02 + 1.120001E+01 3.000000E+01 2 6.100290E+01 8.863823E+01 1.449747E+00 6.098566E+01 + 1.120001E+01 3.000000E+01 3 7.761174E+01 2.115768E+00 7.755883E+01 2.865326E+00 + 1.120001E+01 3.000000E+01 4 2.328806E+02 8.857130E+01 5.806410E+00 2.328082E+02 + 1.120001E+01 3.000000E+01 5 4.578250E+02 8.935469E+01 5.156323E+00 4.577959E+02 + 1.120001E+01 3.000000E+01 6 5.627352E+02 -2.102707E-01 5.627314E+02 -2.065186E+00 + 1.120001E+01 6.000000E+01 1 6.290738E+01 8.938589E+01 6.742471E-01 6.290377E+01 + 1.120001E+01 6.000000E+01 2 1.160951E+02 8.862632E+01 2.783134E+00 1.160617E+02 + 1.120001E+01 6.000000E+01 3 8.599400E+01 2.292254E+00 8.592519E+01 3.439478E+00 + 1.120001E+01 6.000000E+01 4 4.644374E+02 8.862442E+01 1.114933E+01 4.643036E+02 + 1.120001E+01 6.000000E+01 5 2.897723E+02 8.939249E+01 3.072418E+00 2.897560E+02 + 1.120001E+01 6.000000E+01 6 6.185414E+02 -2.032062E-01 6.185375E+02 -2.193725E+00 + 1.120001E+01 9.000000E+01 1 7.024513E-06 -8.928721E+01 8.738753E-08 -7.023969E-06 + 1.120001E+01 9.000000E+01 2 1.405123E+02 8.862083E+01 3.381952E+00 1.404716E+02 + 1.120001E+01 9.000000E+01 3 9.052944E+01 2.382656E+00 9.045117E+01 3.763600E+00 + 1.120001E+01 9.000000E+01 4 5.738329E+02 8.864698E+01 1.354965E+01 5.736729E+02 + 1.120001E+01 9.000000E+01 5 2.658614E-04 -8.967177E+01 1.523023E-06 -2.658571E-04 + 1.120001E+01 9.000000E+01 6 5.568777E-05 1.798720E+02 -5.568763E-05 1.244114E-07 + 1.130001E+01 0.000000E+00 1 1.107238E+02 8.934938E+01 1.257293E+00 1.107167E+02 + 1.130001E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.130001E+01 0.000000E+00 3 7.562865E+01 2.013171E+00 7.558198E+01 2.656777E+00 + 1.130001E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.130001E+01 0.000000E+00 5 5.132776E+02 8.934452E+01 5.871973E+00 5.132441E+02 + 1.130001E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.130001E+01 3.000000E+01 1 9.971642E+01 8.936581E+01 1.103706E+00 9.971030E+01 + 1.130001E+01 3.000000E+01 2 6.061891E+01 8.868329E+01 1.392957E+00 6.060290E+01 + 1.130001E+01 3.000000E+01 3 7.945041E+01 2.093302E+00 7.939739E+01 2.902076E+00 + 1.130001E+01 3.000000E+01 4 2.308129E+02 8.861987E+01 5.559219E+00 2.307459E+02 + 1.130001E+01 3.000000E+01 5 4.662014E+02 8.936644E+01 5.154998E+00 4.661729E+02 + 1.130001E+01 3.000000E+01 6 5.500144E+02 -1.965068E-01 5.500112E+02 -1.886376E+00 + 1.130001E+01 6.000000E+01 1 6.234248E+01 8.939471E+01 6.585937E-01 6.233900E+01 + 1.130001E+01 6.000000E+01 2 1.150346E+02 8.867235E+01 2.665341E+00 1.150037E+02 + 1.130001E+01 6.000000E+01 3 8.773208E+01 2.259831E+00 8.766385E+01 3.459388E+00 + 1.130001E+01 6.000000E+01 4 4.585868E+02 8.867059E+01 1.063947E+01 4.584634E+02 + 1.130001E+01 6.000000E+01 5 2.941199E+02 8.940067E+01 3.076541E+00 2.941038E+02 + 1.130001E+01 6.000000E+01 6 6.028621E+02 -1.901099E-01 6.028588E+02 -2.000319E+00 + 1.130001E+01 9.000000E+01 1 6.944631E-06 -8.933647E+01 8.042228E-08 -6.944166E-06 + 1.130001E+01 9.000000E+01 2 1.390304E+02 8.866728E+01 3.233606E+00 1.389928E+02 + 1.130001E+01 9.000000E+01 3 9.220133E+01 2.345079E+00 9.212411E+01 3.772687E+00 + 1.130001E+01 9.000000E+01 4 5.656148E+02 8.869221E+01 1.290913E+01 5.654675E+02 + 1.130001E+01 9.000000E+01 5 2.639317E-04 -8.968305E+01 1.460027E-06 -2.639277E-04 + 1.130001E+01 9.000000E+01 6 5.420435E-05 1.798801E+02 -5.420423E-05 1.134699E-07 + 1.140001E+01 0.000000E+00 1 1.101025E+02 8.936264E+01 1.224765E+00 1.100957E+02 + 1.140001E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.140001E+01 0.000000E+00 3 7.747333E+01 1.994088E+00 7.742641E+01 2.695791E+00 + 1.140001E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.140001E+01 0.000000E+00 5 5.229449E+02 8.935825E+01 5.857249E+00 5.229121E+02 + 1.140001E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.140001E+01 3.000000E+01 1 9.904882E+01 8.937751E+01 1.076087E+00 9.904298E+01 + 1.140001E+01 3.000000E+01 2 6.023065E+01 8.872647E+01 1.338648E+00 6.021577E+01 + 1.140001E+01 3.000000E+01 3 8.125858E+01 2.069893E+00 8.120556E+01 2.934945E+00 + 1.140001E+01 3.000000E+01 4 2.287463E+02 8.866636E+01 5.323910E+00 2.286843E+02 + 1.140001E+01 3.000000E+01 5 4.741358E+02 8.937807E+01 5.146564E+00 4.741078E+02 + 1.140001E+01 3.000000E+01 6 5.376979E+02 -1.838224E-01 5.376951E+02 -1.725097E+00 + 1.140001E+01 6.000000E+01 1 6.178437E+01 8.940375E+01 6.429548E-01 6.178102E+01 + 1.140001E+01 6.000000E+01 2 1.139862E+02 8.871640E+01 2.553433E+00 1.139576E+02 + 1.140001E+01 6.000000E+01 3 8.943973E+01 2.227108E+00 8.937217E+01 3.475679E+00 + 1.140001E+01 6.000000E+01 4 4.528462E+02 8.871477E+01 1.015718E+01 4.527323E+02 + 1.140001E+01 6.000000E+01 5 2.982212E+02 8.940913E+01 3.075377E+00 2.982053E+02 + 1.140001E+01 6.000000E+01 6 5.877830E+02 -1.780215E-01 5.877802E+02 -1.826275E+00 + 1.140001E+01 9.000000E+01 1 6.866730E-06 -8.938273E+01 7.397684E-08 -6.866332E-06 + 1.140001E+01 9.000000E+01 2 1.375760E+02 8.871172E+01 3.093096E+00 1.375413E+02 + 1.140001E+01 9.000000E+01 3 9.384401E+01 2.307541E+00 9.376791E+01 3.778470E+00 + 1.140001E+01 9.000000E+01 4 5.576008E+02 8.873551E+01 1.230498E+01 5.574650E+02 + 1.140001E+01 9.000000E+01 5 2.620240E-04 -8.969394E+01 1.399698E-06 -2.620202E-04 + 1.140001E+01 9.000000E+01 6 5.278120E-05 1.798875E+02 -5.278110E-05 1.036221E-07 + 1.150001E+01 0.000000E+00 1 1.094725E+02 8.937561E+01 1.192975E+00 1.094660E+02 + 1.150001E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.150001E+01 0.000000E+00 3 7.928864E+01 1.973968E+00 7.924158E+01 2.731131E+00 + 1.150001E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.150001E+01 0.000000E+00 5 5.321284E+02 8.937166E+01 5.835532E+00 5.320964E+02 + 1.150001E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.150001E+01 3.000000E+01 1 9.837859E+01 8.938910E+01 1.048917E+00 9.837300E+01 + 1.150001E+01 3.000000E+01 2 5.983892E+01 8.876785E+01 1.286740E+00 5.982508E+01 + 1.150001E+01 3.000000E+01 3 8.303709E+01 2.045689E+00 8.298417E+01 2.964127E+00 + 1.150001E+01 3.000000E+01 4 2.266836E+02 8.871083E+01 5.100006E+00 2.266263E+02 + 1.150001E+01 3.000000E+01 5 4.816543E+02 8.938961E+01 5.131142E+00 4.816269E+02 + 1.150001E+01 3.000000E+01 6 5.257704E+02 -1.721227E-01 5.257680E+02 -1.579469E+00 + 1.150001E+01 6.000000E+01 1 6.123268E+01 8.941293E+01 6.273907E-01 6.122946E+01 + 1.150001E+01 6.000000E+01 2 1.129500E+02 8.875856E+01 2.447115E+00 1.129235E+02 + 1.150001E+01 6.000000E+01 3 9.111797E+01 2.194224E+00 9.105116E+01 3.488640E+00 + 1.150001E+01 6.000000E+01 4 4.472183E+02 8.875706E+01 9.700960E+00 4.471131E+02 + 1.150001E+01 6.000000E+01 5 3.020876E+02 8.941781E+01 3.069503E+00 3.020721E+02 + 1.150001E+01 6.000000E+01 6 5.732735E+02 -1.668540E-01 5.732711E+02 -1.669457E+00 + 1.150001E+01 9.000000E+01 1 6.790643E-06 -8.942614E+01 6.801285E-08 -6.790302E-06 + 1.150001E+01 9.000000E+01 2 1.361487E+02 8.875424E+01 2.959986E+00 1.361165E+02 + 1.150001E+01 9.000000E+01 3 9.545879E+01 2.270139E+00 9.538387E+01 3.781222E+00 + 1.150001E+01 9.000000E+01 4 5.497868E+02 8.877695E+01 1.173502E+01 5.496616E+02 + 1.150001E+01 9.000000E+01 5 2.601389E-04 -8.970444E+01 1.341961E-06 -2.601354E-04 + 1.150001E+01 9.000000E+01 6 5.141528E-05 1.798944E+02 -5.141519E-05 9.474749E-08 + 1.160001E+01 0.000000E+00 1 1.088344E+02 8.938829E+01 1.161933E+00 1.088281E+02 + 1.160001E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.160001E+01 0.000000E+00 3 8.107460E+01 1.952964E+00 8.102750E+01 2.762945E+00 + 1.160001E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.160001E+01 0.000000E+00 5 5.408304E+02 8.938472E+01 5.807692E+00 5.407993E+02 + 1.160001E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.160001E+01 3.000000E+01 1 9.770663E+01 8.940054E+01 1.022247E+00 9.770128E+01 + 1.160001E+01 3.000000E+01 2 5.944448E+01 8.880750E+01 1.237135E+00 5.943161E+01 + 1.160001E+01 3.000000E+01 3 8.478502E+01 2.020885E+00 8.473228E+01 2.989840E+00 + 1.160001E+01 3.000000E+01 4 2.246288E+02 8.875339E+01 4.886991E+00 2.245756E+02 + 1.160001E+01 3.000000E+01 5 4.887805E+02 8.940102E+01 5.109688E+00 4.887538E+02 + 1.160001E+01 3.000000E+01 6 5.142203E+02 -1.613197E-01 5.142183E+02 -1.447816E+00 + 1.160001E+01 6.000000E+01 1 6.068818E+01 8.942224E+01 6.119623E-01 6.068510E+01 + 1.160001E+01 6.000000E+01 2 1.119269E+02 8.879893E+01 2.346122E+00 1.119023E+02 + 1.160001E+01 6.000000E+01 3 9.276630E+01 2.161283E+00 9.270030E+01 3.498454E+00 + 1.160001E+01 6.000000E+01 4 4.417021E+02 8.879754E+01 9.269327E+00 4.416049E+02 + 1.160001E+01 6.000000E+01 5 3.057259E+02 8.942667E+01 3.059182E+00 3.057105E+02 + 1.160001E+01 6.000000E+01 6 5.593065E+02 -1.565280E-01 5.593044E+02 -1.527984E+00 + 1.160001E+01 9.000000E+01 1 6.716354E-06 -8.946687E+01 6.249444E-08 -6.716063E-06 + 1.160001E+01 9.000000E+01 2 1.347481E+02 8.879493E+01 2.833873E+00 1.347183E+02 + 1.160001E+01 9.000000E+01 3 9.704471E+01 2.232968E+00 9.697102E+01 3.781131E+00 + 1.160001E+01 9.000000E+01 4 5.421680E+02 8.881660E+01 1.119728E+01 5.420523E+02 + 1.160001E+01 9.000000E+01 5 2.582736E-04 -8.971455E+01 1.286725E-06 -2.582704E-04 + 1.160001E+01 9.000000E+01 6 5.010374E-05 1.799008E+02 -5.010366E-05 8.673994E-08 + 1.170001E+01 0.000000E+00 1 1.081895E+02 8.940069E+01 1.131644E+00 1.081836E+02 + 1.170001E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.170001E+01 0.000000E+00 3 8.283031E+01 1.931236E+00 8.278326E+01 2.791385E+00 + 1.170001E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.170001E+01 0.000000E+00 5 5.490875E+02 8.939746E+01 5.774291E+00 5.490571E+02 + 1.170001E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.170001E+01 3.000000E+01 1 9.703459E+01 8.941183E+01 9.961008E-01 9.702948E+01 + 1.170001E+01 3.000000E+01 2 5.904829E+01 8.884548E+01 1.189748E+00 5.903631E+01 + 1.170001E+01 3.000000E+01 3 8.650333E+01 1.995570E+00 8.645087E+01 3.012239E+00 + 1.170001E+01 3.000000E+01 4 2.225845E+02 8.879410E+01 4.684371E+00 2.225352E+02 + 1.170001E+01 3.000000E+01 5 4.955051E+02 8.941225E+01 5.082895E+00 4.954790E+02 + 1.170001E+01 3.000000E+01 6 5.030318E+02 -1.513360E-01 5.030301E+02 -1.328662E+00 + 1.170001E+01 6.000000E+01 1 6.015052E+01 8.943160E+01 5.967079E-01 6.014756E+01 + 1.170001E+01 6.000000E+01 2 1.109169E+02 8.883756E+01 2.250171E+00 1.108940E+02 + 1.170001E+01 6.000000E+01 3 9.438599E+01 2.128350E+00 9.432087E+01 3.505323E+00 + 1.170001E+01 6.000000E+01 4 4.362974E+02 8.883627E+01 8.860934E+00 4.362074E+02 + 1.170001E+01 6.000000E+01 5 3.091421E+02 8.943562E+01 3.045091E+00 3.091271E+02 + 1.170001E+01 6.000000E+01 6 5.458569E+02 -1.469714E-01 5.458551E+02 -1.400195E+00 + 1.170001E+01 9.000000E+01 1 6.643791E-06 -8.950507E+01 5.738891E-08 -6.643544E-06 + 1.170001E+01 9.000000E+01 2 1.333739E+02 8.883386E+01 2.714365E+00 1.333463E+02 + 1.170001E+01 9.000000E+01 3 9.860223E+01 2.196118E+00 9.852982E+01 3.778448E+00 + 1.170001E+01 9.000000E+01 4 5.347398E+02 8.885456E+01 1.068966E+01 5.346329E+02 + 1.170001E+01 9.000000E+01 5 2.564288E-04 -8.972430E+01 1.233911E-06 -2.564258E-04 + 1.170001E+01 9.000000E+01 6 4.884357E-05 1.799067E+02 -4.884350E-05 7.950538E-08 + 1.180001E+01 0.000000E+00 1 1.075397E+02 8.941280E+01 1.102103E+00 1.075341E+02 + 1.180001E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.180001E+01 0.000000E+00 3 8.455796E+01 1.908912E+00 8.451103E+01 2.816679E+00 + 1.180001E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.180001E+01 0.000000E+00 5 5.569067E+02 8.940990E+01 5.735585E+00 5.568771E+02 + 1.180001E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.180001E+01 3.000000E+01 1 9.636280E+01 8.942295E+01 9.705013E-01 9.635791E+01 + 1.180001E+01 3.000000E+01 2 5.865092E+01 8.888188E+01 1.144490E+00 5.863975E+01 + 1.180001E+01 3.000000E+01 3 8.819274E+01 1.969882E+00 8.814062E+01 3.031551E+00 + 1.180001E+01 3.000000E+01 4 2.205512E+02 8.883305E+01 4.491670E+00 2.205054E+02 + 1.180001E+01 3.000000E+01 5 5.018663E+02 8.942335E+01 5.050970E+00 5.018409E+02 + 1.180001E+01 3.000000E+01 6 4.921938E+02 -1.421004E-01 4.921923E+02 -1.220698E+00 + 1.180001E+01 6.000000E+01 1 5.961980E+01 8.944099E+01 5.816728E-01 5.961696E+01 + 1.180001E+01 6.000000E+01 2 1.099202E+02 8.887455E+01 2.159002E+00 1.098990E+02 + 1.180001E+01 6.000000E+01 3 9.597688E+01 2.095549E+00 9.591269E+01 3.509498E+00 + 1.180001E+01 6.000000E+01 4 4.309995E+02 8.887337E+01 8.474439E+00 4.309162E+02 + 1.180001E+01 6.000000E+01 5 3.123563E+02 8.944466E+01 3.027450E+00 3.123416E+02 + 1.180001E+01 6.000000E+01 6 5.328994E+02 -1.381192E-01 5.328979E+02 -1.284625E+00 + 1.180001E+01 9.000000E+01 1 6.572867E-06 -8.954091E+01 5.266531E-08 -6.572656E-06 + 1.180001E+01 9.000000E+01 2 1.320260E+02 8.887112E+01 2.601086E+00 1.320003E+02 + 1.180001E+01 9.000000E+01 3 1.001325E+02 2.159629E+00 1.000614E+02 3.773364E+00 + 1.180001E+01 9.000000E+01 4 5.274958E+02 8.889090E+01 1.021038E+01 5.273970E+02 + 1.180001E+01 9.000000E+01 5 2.546061E-04 -8.973369E+01 1.183421E-06 -2.546033E-04 + 1.180001E+01 9.000000E+01 6 4.763217E-05 1.799122E+02 -4.763211E-05 7.296139E-08 + 1.190001E+01 0.000000E+00 1 1.068864E+02 8.942465E+01 1.073315E+00 1.068810E+02 + 1.190001E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.190001E+01 0.000000E+00 3 8.625607E+01 1.886070E+00 8.620934E+01 2.838876E+00 + 1.190001E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.190001E+01 0.000000E+00 5 5.643052E+02 8.942200E+01 5.692641E+00 5.642765E+02 + 1.190001E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.190001E+01 3.000000E+01 1 9.569206E+01 8.943389E+01 9.454651E-01 9.568739E+01 + 1.190001E+01 3.000000E+01 2 5.825286E+01 8.891676E+01 1.101272E+00 5.824245E+01 + 1.190001E+01 3.000000E+01 3 8.985291E+01 1.943876E+00 8.980120E+01 3.047858E+00 + 1.190001E+01 3.000000E+01 4 2.185332E+02 8.887034E+01 4.308407E+00 2.184907E+02 + 1.190001E+01 3.000000E+01 5 5.078765E+02 8.943426E+01 5.014700E+00 5.078517E+02 + 1.190001E+01 3.000000E+01 6 4.816945E+02 -1.335487E-01 4.816932E+02 -1.122764E+00 + 1.190001E+01 6.000000E+01 1 5.909634E+01 8.945039E+01 5.668811E-01 5.909362E+01 + 1.190001E+01 6.000000E+01 2 1.089371E+02 8.890997E+01 2.072361E+00 1.089174E+02 + 1.190001E+01 6.000000E+01 3 9.754016E+01 2.062865E+00 9.747695E+01 3.511057E+00 + 1.190001E+01 6.000000E+01 4 4.258096E+02 8.890886E+01 8.108605E+00 4.257324E+02 + 1.190001E+01 6.000000E+01 5 3.153695E+02 8.945371E+01 3.006876E+00 3.153551E+02 + 1.190001E+01 6.000000E+01 6 5.204125E+02 -1.299123E-01 5.204112E+02 -1.179981E+00 + 1.190001E+01 9.000000E+01 1 6.503536E-06 -8.957452E+01 4.829484E-08 -6.503357E-06 + 1.190001E+01 9.000000E+01 2 1.307033E+02 8.890679E+01 2.493684E+00 1.306795E+02 + 1.190001E+01 9.000000E+01 3 1.016361E+02 2.123506E+00 1.015663E+02 3.765992E+00 + 1.190001E+01 9.000000E+01 4 5.204306E+02 8.892568E+01 9.757710E+00 5.203391E+02 + 1.190001E+01 9.000000E+01 5 2.528031E-04 -8.974271E+01 1.135188E-06 -2.528005E-04 + 1.190001E+01 9.000000E+01 6 4.646727E-05 1.799173E+02 -4.646722E-05 6.703487E-08 + 1.200001E+01 0.000000E+00 1 1.062292E+02 8.943621E+01 1.045279E+00 1.062241E+02 + 1.200001E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.200001E+01 0.000000E+00 3 8.792551E+01 1.862878E+00 8.787904E+01 2.858249E+00 + 1.200001E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.200001E+01 0.000000E+00 5 5.713010E+02 8.943381E+01 5.645458E+00 5.712731E+02 + 1.200001E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.200001E+01 3.000000E+01 1 9.502312E+01 8.944466E+01 9.210083E-01 9.501866E+01 + 1.200001E+01 3.000000E+01 2 5.785476E+01 8.895018E+01 1.059999E+00 5.784505E+01 + 1.200001E+01 3.000000E+01 3 9.148434E+01 1.917713E+00 9.143310E+01 3.061446E+00 + 1.200001E+01 3.000000E+01 4 2.165313E+02 8.890603E+01 4.134084E+00 2.164918E+02 + 1.200001E+01 3.000000E+01 5 5.135402E+02 8.944498E+01 4.974524E+00 5.135161E+02 + 1.200001E+01 3.000000E+01 6 4.715199E+02 -1.256225E-01 4.715188E+02 -1.033819E+00 + 1.200001E+01 6.000000E+01 1 5.857990E+01 8.945974E+01 5.523602E-01 5.857729E+01 + 1.200001E+01 6.000000E+01 2 1.079678E+02 8.894389E+01 1.990017E+00 1.079494E+02 + 1.200001E+01 6.000000E+01 3 9.907504E+01 2.030438E+00 9.901284E+01 3.510269E+00 + 1.200001E+01 6.000000E+01 4 4.207267E+02 8.894286E+01 7.762195E+00 4.206550E+02 + 1.200001E+01 6.000000E+01 5 3.181928E+02 8.946277E+01 2.983491E+00 3.181788E+02 + 1.200001E+01 6.000000E+01 6 5.083714E+02 -1.222968E-01 5.083702E+02 -1.085109E+00 + 1.200001E+01 9.000000E+01 1 6.435780E-06 -8.960605E+01 4.425109E-08 -6.435627E-06 + 1.200001E+01 9.000000E+01 2 1.294058E+02 8.894093E+01 2.391825E+00 1.293837E+02 + 1.200001E+01 9.000000E+01 3 1.031123E+02 2.087878E+00 1.030439E+02 3.756617E+00 + 1.200001E+01 9.000000E+01 4 5.135405E+02 8.895899E+01 9.330029E+00 5.134557E+02 + 1.200001E+01 9.000000E+01 5 2.510214E-04 -8.975141E+01 1.089106E-06 -2.510191E-04 + 1.200001E+01 9.000000E+01 6 4.534634E-05 1.799221E+02 -4.534630E-05 6.166076E-08 + 1.210001E+01 0.000000E+00 1 1.055706E+02 8.944751E+01 1.017983E+00 1.055657E+02 + 1.210001E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.210001E+01 0.000000E+00 3 8.956721E+01 1.839370E+00 8.952106E+01 2.874888E+00 + 1.210001E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.210001E+01 0.000000E+00 5 5.779141E+02 8.944532E+01 5.594736E+00 5.778870E+02 + 1.210001E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.210001E+01 3.000000E+01 1 9.435610E+01 8.945523E+01 8.971375E-01 9.435184E+01 + 1.210001E+01 3.000000E+01 2 5.745713E+01 8.898222E+01 1.020595E+00 5.744807E+01 + 1.210001E+01 3.000000E+01 3 9.308748E+01 1.891421E+00 9.303676E+01 3.072401E+00 + 1.210001E+01 3.000000E+01 4 2.145465E+02 8.894019E+01 3.968291E+00 2.145098E+02 + 1.210001E+01 3.000000E+01 5 5.188732E+02 8.945552E+01 4.930748E+00 5.188497E+02 + 1.210001E+01 3.000000E+01 6 4.616594E+02 -1.182696E-01 4.616584E+02 -9.529539E-01 + 1.210001E+01 6.000000E+01 1 5.807073E+01 8.946905E+01 5.381309E-01 5.806824E+01 + 1.210001E+01 6.000000E+01 2 1.070119E+02 8.897638E+01 1.911727E+00 1.069948E+02 + 1.210001E+01 6.000000E+01 3 1.005827E+02 1.998309E+00 1.005216E+02 3.507320E+00 + 1.210001E+01 6.000000E+01 4 4.157474E+02 8.897543E+01 7.434075E+00 4.156809E+02 + 1.210001E+01 6.000000E+01 5 3.208337E+02 8.947179E+01 2.957735E+00 3.208201E+02 + 1.210001E+01 6.000000E+01 6 4.967585E+02 -1.152239E-01 4.967575E+02 -9.989983E-01 + 1.210001E+01 9.000000E+01 1 6.369472E-06 -8.963560E+01 4.050915E-08 -6.369344E-06 + 1.210001E+01 9.000000E+01 2 1.281328E+02 8.897363E+01 2.295185E+00 1.281122E+02 + 1.210001E+01 9.000000E+01 3 1.045628E+02 2.052713E+00 1.044957E+02 3.745329E+00 + 1.210001E+01 9.000000E+01 4 5.068209E+02 8.899091E+01 8.925686E+00 5.067423E+02 + 1.210001E+01 9.000000E+01 5 2.492595E-04 -8.975977E+01 1.045091E-06 -2.492573E-04 + 1.210001E+01 9.000000E+01 6 4.426733E-05 1.799265E+02 -4.426729E-05 5.678195E-08 + 1.220001E+01 0.000000E+00 1 1.049102E+02 8.945853E+01 9.914271E-01 1.049055E+02 + 1.220001E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.220001E+01 0.000000E+00 3 9.118073E+01 1.815689E+00 9.113495E+01 2.889012E+00 + 1.220001E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.220001E+01 0.000000E+00 5 5.841580E+02 8.945654E+01 5.540733E+00 5.841317E+02 + 1.220001E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.220001E+01 3.000000E+01 1 9.369230E+01 8.946560E+01 8.738610E-01 9.368822E+01 + 1.220001E+01 3.000000E+01 2 5.706032E+01 8.901293E+01 9.829652E-01 5.705185E+01 + 1.220001E+01 3.000000E+01 3 9.466312E+01 1.865110E+00 9.461298E+01 3.080958E+00 + 1.220001E+01 3.000000E+01 4 2.125812E+02 8.897290E+01 3.810581E+00 2.125471E+02 + 1.220001E+01 3.000000E+01 5 5.239091E+02 8.946588E+01 4.883858E+00 5.238863E+02 + 1.220001E+01 3.000000E+01 6 4.521007E+02 -1.114424E-01 4.520999E+02 -8.793516E-01 + 1.220001E+01 6.000000E+01 1 5.756867E+01 8.947827E+01 5.242051E-01 5.756628E+01 + 1.220001E+01 6.000000E+01 2 1.060700E+02 8.900750E+01 1.837288E+00 1.060541E+02 + 1.220001E+01 6.000000E+01 3 1.020632E+02 1.966529E+00 1.020031E+02 3.502366E+00 + 1.220001E+01 6.000000E+01 4 4.108702E+02 8.900661E+01 7.123251E+00 4.108085E+02 + 1.220001E+01 6.000000E+01 5 3.233058E+02 8.948078E+01 2.929794E+00 3.232925E+02 + 1.220001E+01 6.000000E+01 6 4.855527E+02 -1.086493E-01 4.855518E+02 -9.207476E-01 + 1.220001E+01 9.000000E+01 1 6.304601E-06 -8.966332E+01 3.704645E-08 -6.304493E-06 + 1.220001E+01 9.000000E+01 2 1.268837E+02 8.900494E+01 2.203476E+00 1.268646E+02 + 1.220001E+01 9.000000E+01 3 1.059868E+02 2.018099E+00 1.059210E+02 3.732344E+00 + 1.220001E+01 9.000000E+01 4 5.002638E+02 8.902147E+01 8.543369E+00 5.001908E+02 + 1.220001E+01 9.000000E+01 5 2.475191E-04 -8.976781E+01 1.003075E-06 -2.475171E-04 + 1.220001E+01 9.000000E+01 6 4.322813E-05 1.799306E+02 -4.322810E-05 5.234746E-08 + 1.230001E+01 0.000000E+00 1 1.042497E+02 8.946930E+01 9.655973E-01 1.042452E+02 + 1.230001E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.230001E+01 0.000000E+00 3 9.276642E+01 1.791852E+00 9.272105E+01 2.900677E+00 + 1.230001E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.230001E+01 0.000000E+00 5 5.900499E+02 8.946748E+01 5.483995E+00 5.900244E+02 + 1.230001E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.230001E+01 3.000000E+01 1 9.303152E+01 8.947578E+01 8.511832E-01 9.302763E+01 + 1.230001E+01 3.000000E+01 2 5.666471E+01 8.904237E+01 9.470353E-01 5.665679E+01 + 1.230001E+01 3.000000E+01 3 9.621081E+01 1.838820E+00 9.616126E+01 3.087209E+00 + 1.230001E+01 3.000000E+01 4 2.106349E+02 8.900423E+01 3.660543E+00 2.106031E+02 + 1.230001E+01 3.000000E+01 5 5.286344E+02 8.947604E+01 4.834286E+00 5.286123E+02 + 1.230001E+01 3.000000E+01 6 4.428337E+02 -1.050971E-01 4.428329E+02 -8.122854E-01 + 1.230001E+01 6.000000E+01 1 5.707371E+01 8.948741E+01 5.105975E-01 5.707143E+01 + 1.230001E+01 6.000000E+01 2 1.051417E+02 8.903733E+01 1.766484E+00 1.051268E+02 + 1.230001E+01 6.000000E+01 3 1.035178E+02 1.935063E+00 1.034588E+02 3.495465E+00 + 1.230001E+01 6.000000E+01 4 4.060948E+02 8.903651E+01 6.828631E+00 4.060374E+02 + 1.230001E+01 6.000000E+01 5 3.256099E+02 8.948969E+01 2.900049E+00 3.255970E+02 + 1.230001E+01 6.000000E+01 6 4.747352E+02 -1.025328E-01 4.747344E+02 -8.495545E-01 + 1.230001E+01 9.000000E+01 1 6.241133E-06 -8.968932E+01 3.384201E-08 -6.241041E-06 + 1.230001E+01 9.000000E+01 2 1.256580E+02 8.903494E+01 2.116406E+00 1.256402E+02 + 1.230001E+01 9.000000E+01 3 1.073860E+02 1.983983E+00 1.073217E+02 3.717717E+00 + 1.230001E+01 9.000000E+01 4 4.938672E+02 8.905077E+01 8.181700E+00 4.937994E+02 + 1.230001E+01 9.000000E+01 5 2.457996E-04 -8.977554E+01 9.629482E-07 -2.457977E-04 + 1.230001E+01 9.000000E+01 6 4.222679E-05 1.799344E+02 -4.222676E-05 4.831198E-08 + 1.240001E+01 0.000000E+00 1 1.035895E+02 8.947980E+01 9.404937E-01 1.035852E+02 + 1.240001E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.240001E+01 0.000000E+00 3 9.432555E+01 1.767963E+00 9.428065E+01 2.910121E+00 + 1.240001E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.240001E+01 0.000000E+00 5 5.956002E+02 8.947814E+01 5.424707E+00 5.955754E+02 + 1.240001E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.240001E+01 3.000000E+01 1 9.237492E+01 8.948574E+01 8.291031E-01 9.237119E+01 + 1.240001E+01 3.000000E+01 2 5.627071E+01 8.907061E+01 9.127184E-01 5.626330E+01 + 1.240001E+01 3.000000E+01 3 9.773093E+01 1.812637E+00 9.768202E+01 3.091347E+00 + 1.240001E+01 3.000000E+01 4 2.087110E+02 8.903425E+01 3.517780E+00 2.086814E+02 + 1.240001E+01 3.000000E+01 5 5.330732E+02 8.948598E+01 4.782290E+00 5.330518E+02 + 1.240001E+01 3.000000E+01 6 4.338464E+02 -9.919482E-02 4.338457E+02 -7.511076E-01 + 1.240001E+01 6.000000E+01 1 5.658599E+01 8.949644E+01 4.973158E-01 5.658380E+01 + 1.240001E+01 6.000000E+01 2 1.042272E+02 8.906592E+01 1.699119E+00 1.042134E+02 + 1.240001E+01 6.000000E+01 3 1.049463E+02 1.904029E+00 1.048884E+02 3.486890E+00 + 1.240001E+01 6.000000E+01 4 4.014172E+02 8.906515E+01 6.549312E+00 4.013638E+02 + 1.240001E+01 6.000000E+01 5 3.277592E+02 8.949853E+01 2.868647E+00 3.277467E+02 + 1.240001E+01 6.000000E+01 6 4.642887E+02 -9.683754E-02 4.642880E+02 -7.847096E-01 + 1.240001E+01 9.000000E+01 1 6.179006E-06 -8.971370E+01 3.087587E-08 -6.178929E-06 + 1.240001E+01 9.000000E+01 2 1.244558E+02 8.906370E+01 2.033714E+00 1.244392E+02 + 1.240001E+01 9.000000E+01 3 1.087600E+02 1.950470E+00 1.086970E+02 3.701705E+00 + 1.240001E+01 9.000000E+01 4 4.876261E+02 8.907884E+01 7.839365E+00 4.875630E+02 + 1.240001E+01 9.000000E+01 5 2.440982E-04 -8.978297E+01 9.246425E-07 -2.440964E-04 + 1.240001E+01 9.000000E+01 6 4.126145E-05 1.799380E+02 -4.126142E-05 4.463558E-08 + 1.250001E+01 0.000000E+00 1 1.029296E+02 8.949005E+01 9.160917E-01 1.029255E+02 + 1.250001E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.250001E+01 0.000000E+00 3 9.585702E+01 1.744084E+00 9.581261E+01 2.917438E+00 + 1.250001E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.250001E+01 0.000000E+00 5 6.008287E+02 8.948854E+01 5.363334E+00 6.008048E+02 + 1.250001E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.250001E+01 3.000000E+01 1 9.172245E+01 8.949551E+01 8.076090E-01 9.171889E+01 + 1.250001E+01 3.000000E+01 2 5.587859E+01 8.909771E+01 8.799407E-01 5.587166E+01 + 1.250001E+01 3.000000E+01 3 9.922520E+01 1.786535E+00 9.917697E+01 3.093431E+00 + 1.250001E+01 3.000000E+01 4 2.068085E+02 8.906302E+01 3.381885E+00 2.067808E+02 + 1.250001E+01 3.000000E+01 5 5.372525E+02 8.949575E+01 4.728209E+00 5.372317E+02 + 1.250001E+01 3.000000E+01 6 4.251291E+02 -9.369939E-02 4.251285E+02 -6.952400E-01 + 1.250001E+01 6.000000E+01 1 5.610529E+01 8.950536E+01 4.843614E-01 5.610320E+01 + 1.250001E+01 6.000000E+01 2 1.033262E+02 8.909333E+01 1.635004E+00 1.033132E+02 + 1.250001E+01 6.000000E+01 3 1.063493E+02 1.873419E+00 1.062925E+02 3.476720E+00 + 1.250001E+01 6.000000E+01 4 3.968362E+02 8.909261E+01 6.284411E+00 3.967865E+02 + 1.250001E+01 6.000000E+01 5 3.297563E+02 8.950726E+01 2.835852E+00 3.297441E+02 + 1.250001E+01 6.000000E+01 6 4.541964E+02 -9.152967E-02 4.541958E+02 -7.255757E-01 + 1.250001E+01 9.000000E+01 1 6.118162E-06 -8.973656E+01 2.813067E-08 -6.118098E-06 + 1.250001E+01 9.000000E+01 2 1.232759E+02 8.909126E+01 1.955142E+00 1.232604E+02 + 1.250001E+01 9.000000E+01 3 1.101094E+02 1.917527E+00 1.100478E+02 3.684362E+00 + 1.250001E+01 9.000000E+01 4 4.815327E+02 8.910576E+01 7.515173E+00 4.814741E+02 + 1.250001E+01 9.000000E+01 5 2.424188E-04 -8.979011E+01 8.880730E-07 -2.424172E-04 + 1.250001E+01 9.000000E+01 6 4.033050E-05 1.799413E+02 -4.033048E-05 4.128229E-08 + 1.260001E+01 0.000000E+00 1 1.022716E+02 8.950005E+01 8.923918E-01 1.022678E+02 + 1.260001E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.260001E+01 0.000000E+00 3 9.736290E+01 1.720210E+00 9.731902E+01 2.922719E+00 + 1.260001E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.260001E+01 0.000000E+00 5 6.057446E+02 8.949866E+01 5.300231E+00 6.057214E+02 + 1.260001E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.260001E+01 3.000000E+01 1 9.107421E+01 8.950507E+01 7.867076E-01 9.107082E+01 + 1.260001E+01 3.000000E+01 2 5.548875E+01 8.912370E+01 8.486320E-01 5.548226E+01 + 1.260001E+01 3.000000E+01 3 1.006928E+02 1.760619E+00 1.006452E+02 3.093660E+00 + 1.260001E+01 3.000000E+01 4 2.049292E+02 8.909059E+01 3.252542E+00 2.049034E+02 + 1.260001E+01 3.000000E+01 5 5.411503E+02 8.950527E+01 4.672566E+00 5.411301E+02 + 1.260001E+01 3.000000E+01 6 4.166722E+02 -8.857828E-02 4.166717E+02 -6.441677E-01 + 1.260001E+01 6.000000E+01 1 5.563151E+01 8.951414E+01 4.717415E-01 5.562951E+01 + 1.260001E+01 6.000000E+01 2 1.024386E+02 8.911962E+01 1.573968E+00 1.024265E+02 + 1.260001E+01 6.000000E+01 3 1.077271E+02 1.843222E+00 1.076713E+02 3.465012E+00 + 1.260001E+01 6.000000E+01 4 3.923490E+02 8.911895E+01 6.033013E+00 3.923026E+02 + 1.260001E+01 6.000000E+01 5 3.316088E+02 8.951587E+01 2.801925E+00 3.315970E+02 + 1.260001E+01 6.000000E+01 6 4.444436E+02 -8.657908E-02 4.444431E+02 -6.715940E-01 + 1.260001E+01 9.000000E+01 1 6.058593E-06 -8.975800E+01 2.558908E-08 -6.058538E-06 + 1.260001E+01 9.000000E+01 2 1.221181E+02 8.911768E+01 1.880469E+00 1.221036E+02 + 1.260001E+01 9.000000E+01 3 1.114346E+02 1.885134E+00 1.113743E+02 3.665738E+00 + 1.260001E+01 9.000000E+01 4 4.755874E+02 8.913158E+01 7.208121E+00 4.755328E+02 + 1.260001E+01 9.000000E+01 5 2.407573E-04 -8.979696E+01 8.531620E-07 -2.407558E-04 + 1.260001E+01 9.000000E+01 6 3.943224E-05 1.799445E+02 -3.943222E-05 3.822041E-08 + 1.270001E+01 0.000000E+00 1 1.016153E+02 8.950980E+01 8.693728E-01 1.016116E+02 + 1.270001E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.270001E+01 0.000000E+00 3 9.884223E+01 1.696432E+00 9.879891E+01 2.926125E+00 + 1.270001E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.270001E+01 0.000000E+00 5 6.103551E+02 8.950853E+01 5.235420E+00 6.103326E+02 + 1.270001E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.270001E+01 3.000000E+01 1 9.043067E+01 8.951442E+01 7.663884E-01 9.042742E+01 + 1.270001E+01 3.000000E+01 2 5.510102E+01 8.914865E+01 8.187144E-01 5.509494E+01 + 1.270001E+01 3.000000E+01 3 1.021355E+02 1.734906E+00 1.020887E+02 3.092173E+00 + 1.270001E+01 3.000000E+01 4 2.030723E+02 8.911703E+01 3.129369E+00 2.030482E+02 + 1.270001E+01 3.000000E+01 5 5.448085E+02 8.951463E+01 4.615272E+00 5.447889E+02 + 1.270001E+01 3.000000E+01 6 4.084662E+02 -8.380222E-02 4.084658E+02 -5.974325E-01 + 1.270001E+01 6.000000E+01 1 5.516476E+01 8.952279E+01 4.594568E-01 5.516285E+01 + 1.270001E+01 6.000000E+01 2 1.015644E+02 8.914484E+01 1.515838E+00 1.015531E+02 + 1.270001E+01 6.000000E+01 3 1.090804E+02 1.813513E+00 1.090258E+02 3.452014E+00 + 1.270001E+01 6.000000E+01 4 3.879556E+02 8.914421E+01 5.794427E+00 3.879123E+02 + 1.270001E+01 6.000000E+01 5 3.333284E+02 8.952438E+01 2.766979E+00 3.333169E+02 + 1.270001E+01 6.000000E+01 6 4.350145E+02 -8.195766E-02 4.350140E+02 -6.222580E-01 + 1.270001E+01 9.000000E+01 1 6.000205E-06 -8.977811E+01 2.323623E-08 -6.000160E-06 + 1.270001E+01 9.000000E+01 2 1.209816E+02 8.914303E+01 1.809454E+00 1.209680E+02 + 1.270001E+01 9.000000E+01 3 1.127366E+02 1.853378E+00 1.126776E+02 3.646115E+00 + 1.270001E+01 9.000000E+01 4 4.697818E+02 8.915635E+01 6.917041E+00 4.697309E+02 + 1.270001E+01 9.000000E+01 5 2.391163E-04 -8.980356E+01 8.198295E-07 -2.391149E-04 + 1.270001E+01 9.000000E+01 6 3.856514E-05 1.799474E+02 -3.856512E-05 3.542146E-08 + 1.280001E+01 0.000000E+00 1 1.009614E+02 8.951931E+01 8.470231E-01 1.009578E+02 + 1.280001E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.280001E+01 0.000000E+00 3 1.002962E+02 1.672778E+00 1.002535E+02 2.927781E+00 + 1.280001E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.280001E+01 0.000000E+00 5 6.146942E+02 8.951814E+01 5.169532E+00 6.146724E+02 + 1.280001E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.280001E+01 3.000000E+01 1 8.979245E+01 8.952357E+01 7.466415E-01 8.978934E+01 + 1.280001E+01 3.000000E+01 2 5.471620E+01 8.917259E+01 7.901255E-01 5.471049E+01 + 1.280001E+01 3.000000E+01 3 1.035522E+02 1.709448E+00 1.035061E+02 3.089072E+00 + 1.280001E+01 3.000000E+01 4 2.012382E+02 8.914239E+01 3.012062E+00 2.012156E+02 + 1.280001E+01 3.000000E+01 5 5.482299E+02 8.952376E+01 4.556846E+00 5.482110E+02 + 1.280001E+01 3.000000E+01 6 4.005014E+02 -7.934381E-02 4.005010E+02 -5.546184E-01 + 1.280001E+01 6.000000E+01 1 5.470491E+01 8.953130E+01 4.475023E-01 5.470308E+01 + 1.280001E+01 6.000000E+01 2 1.007037E+02 8.916904E+01 1.460459E+00 1.006931E+02 + 1.280001E+01 6.000000E+01 3 1.104098E+02 1.784248E+00 1.103563E+02 3.437717E+00 + 1.280001E+01 6.000000E+01 4 3.836539E+02 8.916846E+01 5.567841E+00 3.836135E+02 + 1.280001E+01 6.000000E+01 5 3.349163E+02 8.953274E+01 2.731304E+00 3.349051E+02 + 1.280001E+01 6.000000E+01 6 4.258942E+02 -7.764024E-02 4.258938E+02 -5.771196E-01 + 1.280001E+01 9.000000E+01 1 5.943022E-06 -8.979699E+01 2.105765E-08 -5.942984E-06 + 1.280001E+01 9.000000E+01 2 1.198662E+02 8.916734E+01 1.741907E+00 1.198535E+02 + 1.280001E+01 9.000000E+01 3 1.140152E+02 1.822179E+00 1.139576E+02 3.625418E+00 + 1.280001E+01 9.000000E+01 4 4.641135E+02 8.918012E+01 6.641050E+00 4.640660E+02 + 1.280001E+01 9.000000E+01 5 2.374954E-04 -8.980989E+01 7.880111E-07 -2.374941E-04 + 1.280001E+01 9.000000E+01 6 3.772786E-05 1.799501E+02 -3.772785E-05 3.286006E-08 + 1.290001E+01 0.000000E+00 1 1.003103E+02 8.952858E+01 8.253285E-01 1.003070E+02 + 1.290001E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.290001E+01 0.000000E+00 3 1.017248E+02 1.649289E+00 1.016827E+02 2.927798E+00 + 1.290001E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.290001E+01 0.000000E+00 5 6.187474E+02 8.952752E+01 5.102357E+00 6.187264E+02 + 1.290001E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.290001E+01 3.000000E+01 1 8.915935E+01 8.953251E+01 7.274616E-01 8.915638E+01 + 1.290001E+01 3.000000E+01 2 5.433393E+01 8.919559E+01 7.627972E-01 5.432858E+01 + 1.290001E+01 3.000000E+01 3 1.049436E+02 1.684247E+00 1.048983E+02 3.084443E+00 + 1.290001E+01 3.000000E+01 4 1.994283E+02 8.916672E+01 2.900286E+00 1.994072E+02 + 1.290001E+01 3.000000E+01 5 5.514082E+02 8.953268E+01 4.497407E+00 5.513898E+02 + 1.290001E+01 3.000000E+01 6 3.927689E+02 -7.517843E-02 3.927686E+02 -5.153563E-01 + 1.290001E+01 6.000000E+01 1 5.425166E+01 8.953966E+01 4.358831E-01 5.424991E+01 + 1.290001E+01 6.000000E+01 2 9.985564E+01 8.919227E+01 1.407678E+00 9.984572E+01 + 1.290001E+01 6.000000E+01 3 1.117153E+02 1.755491E+00 1.116628E+02 3.422320E+00 + 1.290001E+01 6.000000E+01 4 3.794368E+02 8.919173E+01 5.352582E+00 3.793991E+02 + 1.290001E+01 6.000000E+01 5 3.363806E+02 8.954098E+01 2.694847E+00 3.363698E+02 + 1.290001E+01 6.000000E+01 6 4.170709E+02 -7.360327E-02 4.170705E+02 -5.357772E-01 + 1.290001E+01 9.000000E+01 1 5.886964E-06 -8.981469E+01 1.904019E-08 -5.886933E-06 + 1.290001E+01 9.000000E+01 2 1.187717E+02 8.919069E+01 1.677620E+00 1.187598E+02 + 1.290001E+01 9.000000E+01 3 1.152706E+02 1.791620E+00 1.152143E+02 3.603888E+00 + 1.290001E+01 9.000000E+01 4 4.585769E+02 8.920294E+01 6.379220E+00 4.585326E+02 + 1.290001E+01 9.000000E+01 5 2.358923E-04 -8.981598E+01 7.576314E-07 -2.358911E-04 + 1.290001E+01 9.000000E+01 6 3.691895E-05 1.799527E+02 -3.691894E-05 3.051355E-08 + 1.300001E+01 0.000000E+00 1 9.966228E+01 8.953762E+01 8.042725E-01 9.965904E+01 + 1.300001E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.300001E+01 0.000000E+00 3 1.031288E+02 1.625988E+00 1.030872E+02 2.926281E+00 + 1.300001E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.300001E+01 0.000000E+00 5 6.225383E+02 8.953664E+01 5.034557E+00 6.225179E+02 + 1.300001E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.300001E+01 3.000000E+01 1 8.853170E+01 8.954125E+01 7.088355E-01 8.852886E+01 + 1.300001E+01 3.000000E+01 2 5.395467E+01 8.921769E+01 7.366695E-01 5.394965E+01 + 1.300001E+01 3.000000E+01 3 1.063111E+02 1.659326E+00 1.062665E+02 3.078414E+00 + 1.300001E+01 3.000000E+01 4 1.976420E+02 8.919007E+01 2.793766E+00 1.976223E+02 + 1.300001E+01 3.000000E+01 5 5.543762E+02 8.954140E+01 4.437195E+00 5.543584E+02 + 1.300001E+01 3.000000E+01 6 3.852600E+02 -7.128378E-02 3.852597E+02 -4.793159E-01 + 1.300001E+01 6.000000E+01 1 5.380541E+01 8.954787E+01 4.245897E-01 5.380374E+01 + 1.300001E+01 6.000000E+01 2 9.902090E+01 8.921458E+01 1.357359E+00 9.901160E+01 + 1.300001E+01 6.000000E+01 3 1.129971E+02 1.727234E+00 1.129457E+02 3.405884E+00 + 1.300001E+01 6.000000E+01 4 3.753094E+02 8.921407E+01 5.148009E+00 3.752740E+02 + 1.300001E+01 6.000000E+01 5 3.377252E+02 8.954906E+01 2.657947E+00 3.377147E+02 + 1.300001E+01 6.000000E+01 6 4.085299E+02 -6.982595E-02 4.085296E+02 -4.978722E-01 + 1.300001E+01 9.000000E+01 1 5.832023E-06 -8.983130E+01 1.717203E-08 -5.831997E-06 + 1.300001E+01 9.000000E+01 2 1.176967E+02 8.921309E+01 1.616412E+00 1.176856E+02 + 1.300001E+01 9.000000E+01 3 1.165038E+02 1.761626E+00 1.164487E+02 3.581482E+00 + 1.300001E+01 9.000000E+01 4 4.531705E+02 8.922485E+01 6.130694E+00 4.531290E+02 + 1.300001E+01 9.000000E+01 5 2.343102E-04 -8.982183E+01 7.286212E-07 -2.343090E-04 + 1.300001E+01 9.000000E+01 6 3.613716E-05 1.799550E+02 -3.613715E-05 2.836163E-08 + 1.310001E+01 0.000000E+00 1 9.901750E+01 8.954643E+01 7.838416E-01 9.901440E+01 + 1.310001E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.310001E+01 0.000000E+00 3 1.045077E+02 1.602922E+00 1.044668E+02 2.923352E+00 + 1.310001E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.310001E+01 0.000000E+00 5 6.260788E+02 8.954553E+01 4.966015E+00 6.260591E+02 + 1.310001E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.310001E+01 3.000000E+01 1 8.790895E+01 8.954979E+01 6.907496E-01 8.790623E+01 + 1.310001E+01 3.000000E+01 2 5.357861E+01 8.923892E+01 7.116803E-01 5.357389E+01 + 1.310001E+01 3.000000E+01 3 1.076543E+02 1.634723E+00 1.076105E+02 3.071101E+00 + 1.310001E+01 3.000000E+01 4 1.958805E+02 8.921249E+01 2.692211E+00 1.958620E+02 + 1.310001E+01 3.000000E+01 5 5.571302E+02 8.954993E+01 4.376284E+00 5.571130E+02 + 1.310001E+01 3.000000E+01 6 3.779671E+02 -6.763905E-02 3.779669E+02 -4.461991E-01 + 1.310001E+01 6.000000E+01 1 5.336574E+01 8.955592E+01 4.136202E-01 5.336414E+01 + 1.310001E+01 6.000000E+01 2 9.819876E+01 8.923601E+01 1.309368E+00 9.819003E+01 + 1.310001E+01 6.000000E+01 3 1.142560E+02 1.699478E+00 1.142057E+02 3.388506E+00 + 1.310001E+01 6.000000E+01 4 3.712650E+02 8.923553E+01 4.953495E+00 3.712319E+02 + 1.310001E+01 6.000000E+01 5 3.389550E+02 8.955701E+01 2.620605E+00 3.389448E+02 + 1.310001E+01 6.000000E+01 6 4.002613E+02 -6.628826E-02 4.002610E+02 -4.630815E-01 + 1.310001E+01 9.000000E+01 1 5.778136E-06 -8.984689E+01 1.544170E-08 -5.778116E-06 + 1.310001E+01 9.000000E+01 2 1.166413E+02 8.923461E+01 1.558110E+00 1.166309E+02 + 1.310001E+01 9.000000E+01 3 1.177151E+02 1.732256E+00 1.176613E+02 3.558406E+00 + 1.310001E+01 9.000000E+01 4 4.478879E+02 8.924590E+01 5.894688E+00 4.478491E+02 + 1.310001E+01 9.000000E+01 5 2.327449E-04 -8.982745E+01 7.009148E-07 -2.327438E-04 + 1.310001E+01 9.000000E+01 6 3.538123E-05 1.799573E+02 -3.538122E-05 2.638610E-08 + 1.320001E+01 0.000000E+00 1 9.837684E+01 8.955502E+01 7.640185E-01 9.837387E+01 + 1.320001E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.320001E+01 0.000000E+00 3 1.058633E+02 1.580071E+00 1.058230E+02 2.919067E+00 + 1.320001E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.320001E+01 0.000000E+00 5 6.293903E+02 8.955421E+01 4.897017E+00 6.293712E+02 + 1.320001E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.320001E+01 3.000000E+01 1 8.729283E+01 8.955813E+01 6.731992E-01 8.729024E+01 + 1.320001E+01 3.000000E+01 2 5.320554E+01 8.925933E+01 6.877763E-01 5.320110E+01 + 1.320001E+01 3.000000E+01 3 1.089736E+02 1.610426E+00 1.089306E+02 3.062545E+00 + 1.320001E+01 3.000000E+01 4 1.941425E+02 8.923402E+01 2.595366E+00 1.941252E+02 + 1.320001E+01 3.000000E+01 5 5.596900E+02 8.955827E+01 4.314929E+00 5.596733E+02 + 1.320001E+01 3.000000E+01 6 3.708825E+02 -6.422561E-02 3.708823E+02 -4.157401E-01 + 1.320001E+01 6.000000E+01 1 5.293261E+01 8.956381E+01 4.029681E-01 5.293108E+01 + 1.320001E+01 6.000000E+01 2 9.738930E+01 8.925660E+01 1.263577E+00 9.738110E+01 + 1.320001E+01 6.000000E+01 3 1.154934E+02 1.672202E+00 1.154442E+02 3.370245E+00 + 1.320001E+01 6.000000E+01 4 3.673029E+02 8.925615E+01 4.768451E+00 3.672720E+02 + 1.320001E+01 6.000000E+01 5 3.400790E+02 8.956483E+01 2.582965E+00 3.400692E+02 + 1.320001E+01 6.000000E+01 6 3.922525E+02 -6.297272E-02 3.922523E+02 -4.311173E-01 + 1.320001E+01 9.000000E+01 1 5.725295E-06 -8.986151E+01 1.383912E-08 -5.725278E-06 + 1.320001E+01 9.000000E+01 2 1.156054E+02 8.925529E+01 1.502553E+00 1.155956E+02 + 1.320001E+01 9.000000E+01 3 1.189044E+02 1.703483E+00 1.188518E+02 3.534670E+00 + 1.320001E+01 9.000000E+01 4 4.427265E+02 8.926614E+01 5.670448E+00 4.426902E+02 + 1.320001E+01 9.000000E+01 5 2.311977E-04 -8.983286E+01 6.744531E-07 -2.311967E-04 + 1.320001E+01 9.000000E+01 6 3.465001E-05 1.799594E+02 -3.465001E-05 2.457063E-08 + 1.330001E+01 0.000000E+00 1 9.774033E+01 8.956340E+01 7.447913E-01 9.773750E+01 + 1.330001E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.330001E+01 0.000000E+00 3 1.071949E+02 1.557480E+00 1.071553E+02 2.913537E+00 + 1.330001E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.330001E+01 0.000000E+00 5 6.324617E+02 8.956264E+01 4.827824E+00 6.324432E+02 + 1.330001E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.330001E+01 3.000000E+01 1 8.668199E+01 8.956628E+01 6.561638E-01 8.667950E+01 + 1.330001E+01 3.000000E+01 2 5.283584E+01 8.927895E+01 6.649019E-01 5.283165E+01 + 1.330001E+01 3.000000E+01 3 1.102699E+02 1.586484E+00 1.102276E+02 3.052914E+00 + 1.330001E+01 3.000000E+01 4 1.924293E+02 8.925472E+01 2.502980E+00 1.924130E+02 + 1.330001E+01 3.000000E+01 5 5.620496E+02 8.956641E+01 4.253352E+00 5.620335E+02 + 1.330001E+01 3.000000E+01 6 3.639974E+02 -6.102650E-02 3.639972E+02 -3.876984E-01 + 1.330001E+01 6.000000E+01 1 5.250566E+01 8.957155E+01 3.926283E-01 5.250420E+01 + 1.330001E+01 6.000000E+01 2 9.659223E+01 8.927639E+01 1.219870E+00 9.658453E+01 + 1.330001E+01 6.000000E+01 3 1.167076E+02 1.645454E+00 1.166595E+02 3.351216E+00 + 1.330001E+01 6.000000E+01 4 3.634221E+02 8.927597E+01 4.592340E+00 3.633930E+02 + 1.330001E+01 6.000000E+01 5 3.411006E+02 8.957249E+01 2.545118E+00 3.410912E+02 + 1.330001E+01 6.000000E+01 6 3.844919E+02 -5.986314E-02 3.844917E+02 -4.017205E-01 + 1.330001E+01 9.000000E+01 1 5.673464E-06 -8.987523E+01 1.235477E-08 -5.673451E-06 + 1.330001E+01 9.000000E+01 2 1.145877E+02 8.927516E+01 1.449587E+00 1.145785E+02 + 1.330001E+01 9.000000E+01 3 1.200731E+02 1.675291E+00 1.200218E+02 3.510358E+00 + 1.330001E+01 9.000000E+01 4 4.376828E+02 8.928558E+01 5.457304E+00 4.376488E+02 + 1.330001E+01 9.000000E+01 5 2.296706E-04 -8.983805E+01 6.491774E-07 -2.296697E-04 + 1.330001E+01 9.000000E+01 6 3.394248E-05 1.799613E+02 -3.394248E-05 2.290062E-08 + 1.340001E+01 0.000000E+00 1 9.710779E+01 8.957156E+01 7.261354E-01 9.710507E+01 + 1.340001E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.340001E+01 0.000000E+00 3 1.085035E+02 1.535164E+00 1.084645E+02 2.906857E+00 + 1.340001E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.340001E+01 0.000000E+00 5 6.353191E+02 8.957086E+01 4.758424E+00 6.353013E+02 + 1.340001E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.340001E+01 3.000000E+01 1 8.607747E+01 8.957423E+01 6.396378E-01 8.607509E+01 + 1.340001E+01 3.000000E+01 2 5.246952E+01 8.929783E+01 6.430091E-01 5.246558E+01 + 1.340001E+01 3.000000E+01 3 1.115434E+02 1.562870E+00 1.115019E+02 3.042217E+00 + 1.340001E+01 3.000000E+01 4 1.907394E+02 8.927460E+01 2.414806E+00 1.907242E+02 + 1.340001E+01 3.000000E+01 5 5.642354E+02 8.957436E+01 4.191593E+00 5.642198E+02 + 1.340001E+01 3.000000E+01 6 3.573062E+02 -5.802537E-02 3.573061E+02 -3.618560E-01 + 1.340001E+01 6.000000E+01 1 5.208547E+01 8.957913E+01 3.825932E-01 5.208406E+01 + 1.340001E+01 6.000000E+01 2 9.580726E+01 8.929543E+01 1.178136E+00 9.580002E+01 + 1.340001E+01 6.000000E+01 3 1.179009E+02 1.619188E+00 1.178538E+02 3.331455E+00 + 1.340001E+01 6.000000E+01 4 3.596194E+02 8.929503E+01 4.424686E+00 3.595922E+02 + 1.340001E+01 6.000000E+01 5 3.420238E+02 8.957999E+01 2.507203E+00 3.420146E+02 + 1.340001E+01 6.000000E+01 6 3.769714E+02 -5.694431E-02 3.769712E+02 -3.746589E-01 + 1.340001E+01 9.000000E+01 1 5.622613E-06 -8.988811E+01 1.097981E-08 -5.622602E-06 + 1.340001E+01 9.000000E+01 2 1.135885E+02 8.929427E+01 1.399070E+00 1.135799E+02 + 1.340001E+01 9.000000E+01 3 1.212212E+02 1.647668E+00 1.211711E+02 3.485506E+00 + 1.340001E+01 9.000000E+01 4 4.327518E+02 8.930429E+01 5.254560E+00 4.327199E+02 + 1.340001E+01 9.000000E+01 5 2.281604E-04 -8.984305E+01 6.250299E-07 -2.281596E-04 + 1.340001E+01 9.000000E+01 6 3.325758E-05 1.799632E+02 -3.325758E-05 2.136287E-08 + 1.350002E+01 0.000000E+00 1 9.647980E+01 8.957951E+01 7.080393E-01 9.647720E+01 + 1.350002E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.350002E+01 0.000000E+00 3 1.097896E+02 1.513120E+00 1.097513E+02 2.899089E+00 + 1.350002E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.350002E+01 0.000000E+00 5 6.379564E+02 8.957887E+01 4.689035E+00 6.379391E+02 + 1.350002E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.350002E+01 3.000000E+01 1 8.547876E+01 8.958200E+01 6.236005E-01 8.547649E+01 + 1.350002E+01 3.000000E+01 2 5.210656E+01 8.931599E+01 6.220471E-01 5.210284E+01 + 1.350002E+01 3.000000E+01 3 1.127945E+02 1.539611E+00 1.127538E+02 3.030568E+00 + 1.350002E+01 3.000000E+01 4 1.890742E+02 8.929372E+01 2.330631E+00 1.890598E+02 + 1.350002E+01 3.000000E+01 5 5.662357E+02 8.958212E+01 4.129840E+00 5.662206E+02 + 1.350002E+01 3.000000E+01 6 3.508008E+02 -5.520827E-02 3.508006E+02 -3.380197E-01 + 1.350002E+01 6.000000E+01 1 5.167117E+01 8.958656E+01 3.728577E-01 5.166982E+01 + 1.350002E+01 6.000000E+01 2 9.503458E+01 8.931373E+01 1.138269E+00 9.502776E+01 + 1.350002E+01 6.000000E+01 3 1.190729E+02 1.593426E+00 1.190269E+02 3.311053E+00 + 1.350002E+01 6.000000E+01 4 3.558934E+02 8.931335E+01 4.264977E+00 3.558679E+02 + 1.350002E+01 6.000000E+01 5 3.428521E+02 8.958733E+01 2.469314E+00 3.428432E+02 + 1.350002E+01 6.000000E+01 6 3.696781E+02 -5.420265E-02 3.696780E+02 -3.497209E-01 + 1.350002E+01 9.000000E+01 1 5.572710E-06 -8.990021E+01 9.706190E-09 -5.572701E-06 + 1.350002E+01 9.000000E+01 2 1.126070E+02 8.931264E+01 1.350871E+00 1.125989E+02 + 1.350002E+01 9.000000E+01 3 1.223481E+02 1.620644E+00 1.222992E+02 3.460225E+00 + 1.350002E+01 9.000000E+01 4 4.279327E+02 8.932228E+01 5.061672E+00 4.279028E+02 + 1.350002E+01 9.000000E+01 5 2.266682E-04 -8.984784E+01 6.019519E-07 -2.266674E-04 + 1.350002E+01 9.000000E+01 6 3.259435E-05 1.799649E+02 -3.259435E-05 1.994554E-08 + 1.360002E+01 0.000000E+00 1 9.585638E+01 8.958727E+01 6.904913E-01 9.585390E+01 + 1.360002E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.360002E+01 0.000000E+00 3 1.110531E+02 1.491375E+00 1.110155E+02 2.890318E+00 + 1.360002E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.360002E+01 0.000000E+00 5 6.404005E+02 8.958669E+01 4.619687E+00 6.403839E+02 + 1.360002E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.360002E+01 3.000000E+01 1 8.488598E+01 8.958958E+01 6.080474E-01 8.488380E+01 + 1.360002E+01 3.000000E+01 2 5.174720E+01 8.933347E+01 6.019685E-01 5.174369E+01 + 1.360002E+01 3.000000E+01 3 1.140237E+02 1.516720E+00 1.139837E+02 3.018055E+00 + 1.360002E+01 3.000000E+01 4 1.874324E+02 8.931211E+01 2.250251E+00 1.874189E+02 + 1.360002E+01 3.000000E+01 5 5.680785E+02 8.958969E+01 4.068121E+00 5.680639E+02 + 1.360002E+01 3.000000E+01 6 3.444746E+02 -5.256160E-02 3.444745E+02 -3.160116E-01 + 1.360002E+01 6.000000E+01 1 5.126316E+01 8.959382E+01 3.634132E-01 5.126187E+01 + 1.360002E+01 6.000000E+01 2 9.427340E+01 8.933135E+01 1.100167E+00 9.426698E+01 + 1.360002E+01 6.000000E+01 3 1.202243E+02 1.568163E+00 1.201793E+02 3.290081E+00 + 1.360002E+01 6.000000E+01 4 3.522416E+02 8.933100E+01 4.112770E+00 3.522176E+02 + 1.360002E+01 6.000000E+01 5 3.435918E+02 8.959454E+01 2.431463E+00 3.435832E+02 + 1.360002E+01 6.000000E+01 6 3.626053E+02 -5.162517E-02 3.626052E+02 -3.267179E-01 + 1.360002E+01 9.000000E+01 1 5.523750E-06 -8.991156E+01 8.526428E-09 -5.523743E-06 + 1.360002E+01 9.000000E+01 2 1.116428E+02 8.933032E+01 1.304857E+00 1.116352E+02 + 1.360002E+01 9.000000E+01 3 1.234563E+02 1.594159E+00 1.234086E+02 3.434522E+00 + 1.360002E+01 9.000000E+01 4 4.232200E+02 8.933959E+01 4.878055E+00 4.231919E+02 + 1.360002E+01 9.000000E+01 5 2.251913E-04 -8.985246E+01 5.798990E-07 -2.251906E-04 + 1.360002E+01 9.000000E+01 6 3.195180E-05 1.799666E+02 -3.195180E-05 1.863791E-08 + 1.370002E+01 0.000000E+00 1 9.523803E+01 8.959483E+01 6.734699E-01 9.523565E+01 + 1.370002E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.370002E+01 0.000000E+00 3 1.122953E+02 1.469924E+00 1.122583E+02 2.880620E+00 + 1.370002E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.370002E+01 0.000000E+00 5 6.426550E+02 8.959429E+01 4.550618E+00 6.426389E+02 + 1.370002E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.370002E+01 3.000000E+01 1 8.429946E+01 8.959698E+01 5.929583E-01 8.429738E+01 + 1.370002E+01 3.000000E+01 2 5.139131E+01 8.935030E+01 5.827336E-01 5.138801E+01 + 1.370002E+01 3.000000E+01 3 1.152318E+02 1.494177E+00 1.151926E+02 3.004710E+00 + 1.370002E+01 3.000000E+01 4 1.858150E+02 8.932980E+01 2.173457E+00 1.858023E+02 + 1.370002E+01 3.000000E+01 5 5.697527E+02 8.959708E+01 4.006640E+00 5.697386E+02 + 1.370002E+01 3.000000E+01 6 3.383217E+02 -5.007343E-02 3.383216E+02 -2.956749E-01 + 1.370002E+01 6.000000E+01 1 5.086125E+01 8.960093E+01 3.542526E-01 5.086002E+01 + 1.370002E+01 6.000000E+01 2 9.352402E+01 8.934830E+01 1.063745E+00 9.351797E+01 + 1.370002E+01 6.000000E+01 3 1.213550E+02 1.543401E+00 1.213110E+02 3.268597E+00 + 1.370002E+01 6.000000E+01 4 3.486605E+02 8.934798E+01 3.967686E+00 3.486379E+02 + 1.370002E+01 6.000000E+01 5 3.442470E+02 8.960159E+01 2.393731E+00 3.442386E+02 + 1.370002E+01 6.000000E+01 6 3.557429E+02 -4.920064E-02 3.557427E+02 -3.054811E-01 + 1.370002E+01 9.000000E+01 1 5.475670E-06 -8.992222E+01 7.433633E-09 -5.475665E-06 + 1.370002E+01 9.000000E+01 2 1.106953E+02 8.934734E+01 1.260907E+00 1.106881E+02 + 1.370002E+01 9.000000E+01 3 1.245441E+02 1.568268E+00 1.244974E+02 3.408525E+00 + 1.370002E+01 9.000000E+01 4 4.186085E+02 8.935625E+01 4.703158E+00 4.185821E+02 + 1.370002E+01 9.000000E+01 5 2.237349E-04 -8.985690E+01 5.588086E-07 -2.237342E-04 + 1.370002E+01 9.000000E+01 6 3.132915E-05 1.799681E+02 -3.132915E-05 1.743039E-08 + 1.380002E+01 0.000000E+00 1 9.462417E+01 8.960220E+01 6.569591E-01 9.462189E+01 + 1.380002E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.380002E+01 0.000000E+00 3 1.135152E+02 1.448807E+00 1.134789E+02 2.870092E+00 + 1.380002E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.380002E+01 0.000000E+00 5 6.447154E+02 8.960169E+01 4.481882E+00 6.446998E+02 + 1.380002E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.380002E+01 3.000000E+01 1 8.371916E+01 8.960421E+01 5.783236E-01 8.371716E+01 + 1.380002E+01 3.000000E+01 2 5.103907E+01 8.936652E+01 5.642987E-01 5.103595E+01 + 1.380002E+01 3.000000E+01 3 1.164179E+02 1.472036E+00 1.163795E+02 2.990666E+00 + 1.380002E+01 3.000000E+01 4 1.842216E+02 8.934684E+01 2.100059E+00 1.842097E+02 + 1.380002E+01 3.000000E+01 5 5.712762E+02 8.960429E+01 3.945374E+00 5.712626E+02 + 1.380002E+01 3.000000E+01 6 3.323361E+02 -4.773237E-02 3.323359E+02 -2.768648E-01 + 1.380002E+01 6.000000E+01 1 5.046520E+01 8.960788E+01 3.453674E-01 5.046402E+01 + 1.380002E+01 6.000000E+01 2 9.278586E+01 8.936463E+01 1.028909E+00 9.278015E+01 + 1.380002E+01 6.000000E+01 3 1.224657E+02 1.519127E+00 1.224227E+02 3.246646E+00 + 1.380002E+01 6.000000E+01 4 3.451521E+02 8.936433E+01 3.829268E+00 3.451308E+02 + 1.380002E+01 6.000000E+01 5 3.448199E+02 8.960848E+01 2.356209E+00 3.448118E+02 + 1.380002E+01 6.000000E+01 6 3.490835E+02 -4.691823E-02 3.490834E+02 -2.858566E-01 + 1.380002E+01 9.000000E+01 1 5.428473E-06 -8.993223E+01 6.421432E-09 -5.428470E-06 + 1.380002E+01 9.000000E+01 2 1.097644E+02 8.936373E+01 1.218917E+00 1.097577E+02 + 1.380002E+01 9.000000E+01 3 1.256127E+02 1.542922E+00 1.255671E+02 3.382223E+00 + 1.380002E+01 9.000000E+01 4 4.140994E+02 8.937231E+01 4.536509E+00 4.140746E+02 + 1.380002E+01 9.000000E+01 5 2.222941E-04 -8.986117E+01 5.386522E-07 -2.222934E-04 + 1.380002E+01 9.000000E+01 6 3.072555E-05 1.799696E+02 -3.072555E-05 1.631426E-08 + 1.390002E+01 0.000000E+00 1 9.401585E+01 8.960938E+01 6.409466E-01 9.401367E+01 + 1.390002E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.390002E+01 0.000000E+00 3 1.147139E+02 1.428002E+00 1.146783E+02 2.858756E+00 + 1.390002E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.390002E+01 0.000000E+00 5 6.466078E+02 8.960892E+01 4.413477E+00 6.465928E+02 + 1.390002E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.390002E+01 3.000000E+01 1 8.314499E+01 8.961125E+01 5.641295E-01 8.314307E+01 + 1.390002E+01 3.000000E+01 2 5.069037E+01 8.938213E+01 5.466266E-01 5.068742E+01 + 1.390002E+01 3.000000E+01 3 1.175835E+02 1.450251E+00 1.175459E+02 2.975916E+00 + 1.390002E+01 3.000000E+01 4 1.826507E+02 8.936324E+01 2.029879E+00 1.826394E+02 + 1.390002E+01 3.000000E+01 5 5.726527E+02 8.961134E+01 3.884524E+00 5.726395E+02 + 1.390002E+01 3.000000E+01 6 3.265115E+02 -4.552826E-02 3.265114E+02 -2.594519E-01 + 1.390002E+01 6.000000E+01 1 5.007525E+01 8.961469E+01 3.367526E-01 5.007412E+01 + 1.390002E+01 6.000000E+01 2 9.205920E+01 8.938036E+01 9.955786E-01 9.205381E+01 + 1.390002E+01 6.000000E+01 3 1.235569E+02 1.495332E+00 1.235148E+02 3.224281E+00 + 1.390002E+01 6.000000E+01 4 3.417121E+02 8.938007E+01 3.697199E+00 3.416921E+02 + 1.390002E+01 6.000000E+01 5 3.453161E+02 8.961524E+01 2.318897E+00 3.453083E+02 + 1.390002E+01 6.000000E+01 6 3.426181E+02 -4.476813E-02 3.426180E+02 -2.677051E-01 + 1.390002E+01 9.000000E+01 1 5.382105E-06 -8.994162E+01 5.483923E-09 -5.382103E-06 + 1.390002E+01 9.000000E+01 2 1.088496E+02 8.937951E+01 1.178782E+00 1.088432E+02 + 1.390002E+01 9.000000E+01 3 1.266628E+02 1.518117E+00 1.266184E+02 3.355685E+00 + 1.390002E+01 9.000000E+01 4 4.096870E+02 8.938776E+01 4.377617E+00 4.096636E+02 + 1.390002E+01 9.000000E+01 5 2.208703E-04 -8.986527E+01 5.193689E-07 -2.208697E-04 + 1.390002E+01 9.000000E+01 6 3.014010E-05 1.799709E+02 -3.014010E-05 1.528172E-08 + 1.400002E+01 0.000000E+00 1 9.341292E+01 8.961639E+01 6.254156E-01 9.341083E+01 + 1.400002E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.400002E+01 0.000000E+00 3 1.158918E+02 1.407507E+00 1.158568E+02 2.846669E+00 + 1.400002E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.400002E+01 0.000000E+00 5 6.483340E+02 8.961596E+01 4.345604E+00 6.483194E+02 + 1.400002E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.400002E+01 3.000000E+01 1 8.257697E+01 8.961813E+01 5.503611E-01 8.257514E+01 + 1.400002E+01 3.000000E+01 2 5.034540E+01 8.939719E+01 5.296783E-01 5.034261E+01 + 1.400002E+01 3.000000E+01 3 1.187293E+02 1.428819E+00 1.186924E+02 2.960516E+00 + 1.400002E+01 3.000000E+01 4 1.811027E+02 8.937902E+01 1.962768E+00 1.810921E+02 + 1.400002E+01 3.000000E+01 5 5.738928E+02 8.961822E+01 3.824070E+00 5.738800E+02 + 1.400002E+01 3.000000E+01 6 3.208421E+02 -4.345161E-02 3.208420E+02 -2.433182E-01 + 1.400002E+01 6.000000E+01 1 4.969078E+01 8.962134E+01 3.283996E-01 4.968969E+01 + 1.400002E+01 6.000000E+01 2 9.134313E+01 8.939552E+01 9.636754E-01 9.133805E+01 + 1.400002E+01 6.000000E+01 3 1.246293E+02 1.472011E+00 1.245882E+02 3.201554E+00 + 1.400002E+01 6.000000E+01 4 3.383389E+02 8.939524E+01 3.571121E+00 3.383200E+02 + 1.400002E+01 6.000000E+01 5 3.457374E+02 8.962184E+01 2.281882E+00 3.457299E+02 + 1.400002E+01 6.000000E+01 6 3.363388E+02 -4.274136E-02 3.363387E+02 -2.509011E-01 + 1.400002E+01 9.000000E+01 1 5.336591E-06 -8.995045E+01 4.615730E-09 -5.336589E-06 + 1.400002E+01 9.000000E+01 2 1.079504E+02 8.939471E+01 1.140400E+00 1.079444E+02 + 1.400002E+01 9.000000E+01 3 1.276943E+02 1.493816E+00 1.276509E+02 3.328869E+00 + 1.400002E+01 9.000000E+01 4 4.053708E+02 8.940267E+01 4.226071E+00 4.053488E+02 + 1.400002E+01 9.000000E+01 5 2.194629E-04 -8.986922E+01 5.009261E-07 -2.194623E-04 + 1.400002E+01 9.000000E+01 6 2.957223E-05 1.799722E+02 -2.957222E-05 1.432562E-08 + 1.410002E+01 0.000000E+00 1 9.281465E+01 8.962321E+01 6.103522E-01 9.281264E+01 + 1.410002E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.410002E+01 0.000000E+00 3 1.170500E+02 1.387336E+00 1.170157E+02 2.833923E+00 + 1.410002E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.410002E+01 0.000000E+00 5 6.498899E+02 8.962283E+01 4.278166E+00 6.498758E+02 + 1.410002E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.410002E+01 3.000000E+01 1 8.201529E+01 8.962485E+01 5.370075E-01 8.201353E+01 + 1.410002E+01 3.000000E+01 2 5.000404E+01 8.941170E+01 5.134202E-01 5.000141E+01 + 1.410002E+01 3.000000E+01 3 1.198546E+02 1.407775E+00 1.198184E+02 2.944569E+00 + 1.410002E+01 3.000000E+01 4 1.795791E+02 8.939424E+01 1.898557E+00 1.795691E+02 + 1.410002E+01 3.000000E+01 5 5.749977E+02 8.962492E+01 3.764142E+00 5.749854E+02 + 1.410002E+01 3.000000E+01 6 3.153224E+02 -4.149376E-02 3.153224E+02 -2.283574E-01 + 1.410002E+01 6.000000E+01 1 4.931218E+01 8.962784E+01 3.202994E-01 4.931113E+01 + 1.410002E+01 6.000000E+01 2 9.063799E+01 8.941013E+01 9.331260E-01 9.063319E+01 + 1.410002E+01 6.000000E+01 3 1.256827E+02 1.449176E+00 1.256425E+02 3.178539E+00 + 1.410002E+01 6.000000E+01 4 3.350314E+02 8.940987E+01 3.450684E+00 3.350136E+02 + 1.410002E+01 6.000000E+01 5 3.460934E+02 8.962830E+01 2.245189E+00 3.460861E+02 + 1.410002E+01 6.000000E+01 6 3.302390E+02 -4.082947E-02 3.302389E+02 -2.353311E-01 + 1.410002E+01 9.000000E+01 1 5.291866E-06 -8.995872E+01 3.811751E-09 -5.291865E-06 + 1.410002E+01 9.000000E+01 2 1.070666E+02 8.940937E+01 1.103676E+00 1.070609E+02 + 1.410002E+01 9.000000E+01 3 1.287075E+02 1.470075E+00 1.286651E+02 3.301970E+00 + 1.410002E+01 9.000000E+01 4 4.011458E+02 8.941704E+01 4.081447E+00 4.011251E+02 + 1.410002E+01 9.000000E+01 5 2.180719E-04 -8.987302E+01 4.832769E-07 -2.180714E-04 + 1.410002E+01 9.000000E+01 6 2.902108E-05 1.799735E+02 -2.902108E-05 1.343956E-08 + 1.420002E+01 0.000000E+00 1 9.222209E+01 8.962988E+01 5.957394E-01 9.222017E+01 + 1.420002E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.420002E+01 0.000000E+00 3 1.181887E+02 1.367490E+00 1.181551E+02 2.820566E+00 + 1.420002E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.420002E+01 0.000000E+00 5 6.512989E+02 8.962952E+01 4.211454E+00 6.512853E+02 + 1.420002E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.420002E+01 3.000000E+01 1 8.145914E+01 8.963139E+01 5.240567E-01 8.145745E+01 + 1.420002E+01 3.000000E+01 2 4.966637E+01 8.942570E+01 4.978178E-01 4.966388E+01 + 1.420002E+01 3.000000E+01 3 1.209608E+02 1.387103E+00 1.209254E+02 2.928117E+00 + 1.420002E+01 3.000000E+01 4 1.780764E+02 8.940891E+01 1.837086E+00 1.780669E+02 + 1.420002E+01 3.000000E+01 5 5.759803E+02 8.963148E+01 3.704710E+00 5.759684E+02 + 1.420002E+01 3.000000E+01 6 3.099483E+02 -3.964655E-02 3.099482E+02 -2.144727E-01 + 1.420002E+01 6.000000E+01 1 4.893873E+01 8.963420E+01 3.124456E-01 4.893773E+01 + 1.420002E+01 6.000000E+01 2 8.994339E+01 8.942421E+01 9.038602E-01 8.993885E+01 + 1.420002E+01 6.000000E+01 3 1.267177E+02 1.426796E+00 1.266785E+02 3.155236E+00 + 1.420002E+01 6.000000E+01 4 3.317870E+02 8.942397E+01 3.335597E+00 3.317702E+02 + 1.420002E+01 6.000000E+01 5 3.463760E+02 8.963463E+01 2.208806E+00 3.463690E+02 + 1.420002E+01 6.000000E+01 6 3.243127E+02 -3.902475E-02 3.243127E+02 -2.208927E-01 + 1.420002E+01 9.000000E+01 1 5.247934E-06 -8.996651E+01 3.067469E-09 -5.247933E-06 + 1.420002E+01 9.000000E+01 2 1.061972E+02 8.942349E+01 1.068530E+00 1.061918E+02 + 1.420002E+01 9.000000E+01 3 1.297040E+02 1.446820E+00 1.296626E+02 3.274906E+00 + 1.420002E+01 9.000000E+01 4 3.970090E+02 8.943089E+01 3.943370E+00 3.969894E+02 + 1.420002E+01 9.000000E+01 5 2.166960E-04 -8.987669E+01 4.663885E-07 -2.166955E-04 + 1.420002E+01 9.000000E+01 6 2.848610E-05 1.799746E+02 -2.848610E-05 1.261768E-08 + 1.430002E+01 0.000000E+00 1 9.163473E+01 8.963637E+01 5.815630E-01 9.163288E+01 + 1.430002E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.430002E+01 0.000000E+00 3 1.193063E+02 1.347985E+00 1.192732E+02 2.806632E+00 + 1.430002E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.430002E+01 0.000000E+00 5 6.525556E+02 8.963602E+01 4.145412E+00 6.525424E+02 + 1.430002E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.430002E+01 3.000000E+01 1 8.090956E+01 8.963779E+01 5.114934E-01 8.090794E+01 + 1.430002E+01 3.000000E+01 2 4.933223E+01 8.943921E+01 4.828393E-01 4.932987E+01 + 1.430002E+01 3.000000E+01 3 1.220479E+02 1.366797E+00 1.220132E+02 2.911189E+00 + 1.430002E+01 3.000000E+01 4 1.765970E+02 8.942306E+01 1.778233E+00 1.765881E+02 + 1.430002E+01 3.000000E+01 5 5.768289E+02 8.963786E+01 3.645904E+00 5.768173E+02 + 1.430002E+01 3.000000E+01 6 3.047135E+02 -3.790264E-02 3.047134E+02 -2.015758E-01 + 1.430002E+01 6.000000E+01 1 4.857093E+01 8.964041E+01 3.048303E-01 4.856997E+01 + 1.430002E+01 6.000000E+01 2 8.925934E+01 8.943781E+01 8.758137E-01 8.925504E+01 + 1.430002E+01 6.000000E+01 3 1.277345E+02 1.404871E+00 1.276961E+02 3.131686E+00 + 1.430002E+01 6.000000E+01 4 3.286065E+02 8.943757E+01 3.225616E+00 3.285907E+02 + 1.430002E+01 6.000000E+01 5 3.465981E+02 8.964080E+01 2.172868E+00 3.465913E+02 + 1.430002E+01 6.000000E+01 6 3.185517E+02 -3.732009E-02 3.185517E+02 -2.074914E-01 + 1.430002E+01 9.000000E+01 1 5.204746E-06 -8.997382E+01 2.378467E-09 -5.204746E-06 + 1.430002E+01 9.000000E+01 2 1.053429E+02 8.943713E+01 1.034876E+00 1.053378E+02 + 1.430002E+01 9.000000E+01 3 1.306822E+02 1.424090E+00 1.306419E+02 3.247781E+00 + 1.430002E+01 9.000000E+01 4 3.929597E+02 8.944426E+01 3.811475E+00 3.929412E+02 + 1.430002E+01 9.000000E+01 5 2.153368E-04 -8.988021E+01 4.502167E-07 -2.153363E-04 + 1.430002E+01 9.000000E+01 6 2.796662E-05 1.799757E+02 -2.796661E-05 1.185471E-08 + 1.440002E+01 0.000000E+00 1 9.105280E+01 8.964269E+01 5.678107E-01 9.105103E+01 + 1.440002E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.440002E+01 0.000000E+00 3 1.204055E+02 1.328791E+00 1.203731E+02 2.792167E+00 + 1.440002E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.440002E+01 0.000000E+00 5 6.536740E+02 8.964238E+01 4.079990E+00 6.536613E+02 + 1.440002E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.440002E+01 3.000000E+01 1 8.036610E+01 8.964403E+01 4.993050E-01 8.036456E+01 + 1.440002E+01 3.000000E+01 2 4.900182E+01 8.945224E+01 4.684564E-01 4.899958E+01 + 1.440002E+01 3.000000E+01 3 1.231159E+02 1.346855E+00 1.230819E+02 2.893824E+00 + 1.440002E+01 3.000000E+01 4 1.751390E+02 8.943670E+01 1.721862E+00 1.751306E+02 + 1.440002E+01 3.000000E+01 5 5.775671E+02 8.964409E+01 3.587728E+00 5.775560E+02 + 1.440002E+01 3.000000E+01 6 2.996143E+02 -3.625504E-02 2.996142E+02 -1.895868E-01 + 1.440002E+01 6.000000E+01 1 4.820866E+01 8.964648E+01 2.974450E-01 4.820774E+01 + 1.440002E+01 6.000000E+01 2 8.858540E+01 8.945092E+01 8.489271E-01 8.858134E+01 + 1.440002E+01 6.000000E+01 3 1.287342E+02 1.383388E+00 1.286967E+02 3.107944E+00 + 1.440002E+01 6.000000E+01 4 3.254849E+02 8.945070E+01 3.120404E+00 3.254700E+02 + 1.440002E+01 6.000000E+01 5 3.467580E+02 8.964685E+01 2.137307E+00 3.467514E+02 + 1.440002E+01 6.000000E+01 6 3.129503E+02 -3.570894E-02 3.129503E+02 -1.950427E-01 + 1.440002E+01 9.000000E+01 1 5.162310E-06 -8.998068E+01 1.740849E-09 -5.162309E-06 + 1.440002E+01 9.000000E+01 2 1.045026E+02 8.945028E+01 1.002634E+00 1.044978E+02 + 1.440002E+01 9.000000E+01 3 1.316441E+02 1.401820E+00 1.316047E+02 3.220534E+00 + 1.440002E+01 9.000000E+01 4 3.889918E+02 8.945715E+01 3.685435E+00 3.889743E+02 + 1.440002E+01 9.000000E+01 5 2.139940E-04 -8.988361E+01 4.347340E-07 -2.139936E-04 + 1.440002E+01 9.000000E+01 6 2.746197E-05 1.799767E+02 -2.746197E-05 1.114580E-08 + 1.450002E+01 0.000000E+00 1 9.047619E+01 8.964887E+01 5.544686E-01 9.047449E+01 + 1.450002E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.450002E+01 0.000000E+00 3 1.214867E+02 1.309920E+00 1.214549E+02 2.777238E+00 + 1.450002E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.450002E+01 0.000000E+00 5 6.546560E+02 8.964857E+01 4.015304E+00 6.546437E+02 + 1.450002E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.450002E+01 3.000000E+01 1 7.982861E+01 8.965012E+01 4.874841E-01 7.982712E+01 + 1.450002E+01 3.000000E+01 2 4.867495E+01 8.946483E+01 4.546393E-01 4.867282E+01 + 1.450002E+01 3.000000E+01 3 1.241655E+02 1.327266E+00 1.241322E+02 2.876056E+00 + 1.450002E+01 3.000000E+01 4 1.737033E+02 8.944986E+01 1.667834E+00 1.736953E+02 + 1.450002E+01 3.000000E+01 5 5.781986E+02 8.965018E+01 3.530241E+00 5.781878E+02 + 1.450002E+01 3.000000E+01 6 2.946451E+02 -3.469753E-02 2.946450E+02 -1.784330E-01 + 1.450002E+01 6.000000E+01 1 4.785126E+01 8.965242E+01 2.902845E-01 4.785038E+01 + 1.450002E+01 6.000000E+01 2 8.792124E+01 8.946358E+01 8.231394E-01 8.791739E+01 + 1.450002E+01 6.000000E+01 3 1.297157E+02 1.362360E+00 1.296790E+02 3.084047E+00 + 1.450002E+01 6.000000E+01 4 3.224222E+02 8.946337E+01 3.019745E+00 3.224081E+02 + 1.450002E+01 6.000000E+01 5 3.468647E+02 8.965275E+01 2.102222E+00 3.468583E+02 + 1.450002E+01 6.000000E+01 6 3.075024E+02 -3.418531E-02 3.075024E+02 -1.834701E-01 + 1.450002E+01 9.000000E+01 1 5.120589E-06 -8.998712E+01 1.150930E-09 -5.120589E-06 + 1.450002E+01 9.000000E+01 2 1.036764E+02 8.946297E+01 9.717385E-01 1.036719E+02 + 1.450002E+01 9.000000E+01 3 1.325885E+02 1.380049E+00 1.325500E+02 3.193270E+00 + 1.450002E+01 9.000000E+01 4 3.851090E+02 8.946960E+01 3.564947E+00 3.850925E+02 + 1.450002E+01 9.000000E+01 5 2.126657E-04 -8.988687E+01 4.199055E-07 -2.126653E-04 + 1.450002E+01 9.000000E+01 6 2.697163E-05 1.799777E+02 -2.697163E-05 1.048662E-08 + 1.460002E+01 0.000000E+00 1 8.990534E+01 8.965489E+01 5.415218E-01 8.990371E+01 + 1.460002E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.460002E+01 0.000000E+00 3 1.225487E+02 1.291372E+00 1.225176E+02 2.761854E+00 + 1.460002E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.460002E+01 0.000000E+00 5 6.555183E+02 8.965462E+01 3.951430E+00 6.555064E+02 + 1.460002E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.460002E+01 3.000000E+01 1 7.929740E+01 8.965606E+01 4.760134E-01 7.929597E+01 + 1.460002E+01 3.000000E+01 2 4.835192E+01 8.947699E+01 4.413630E-01 4.834990E+01 + 1.460002E+01 3.000000E+01 3 1.251974E+02 1.308041E+00 1.251648E+02 2.857962E+00 + 1.460002E+01 3.000000E+01 4 1.722886E+02 8.946256E+01 1.616053E+00 1.722810E+02 + 1.460002E+01 3.000000E+01 5 5.787271E+02 8.965612E+01 3.473412E+00 5.787167E+02 + 1.460002E+01 3.000000E+01 6 2.898024E+02 -3.322428E-02 2.898023E+02 -1.680486E-01 + 1.460002E+01 6.000000E+01 1 4.749929E+01 8.965822E+01 2.833395E-01 4.749844E+01 + 1.460002E+01 6.000000E+01 2 8.726714E+01 8.947580E+01 7.983971E-01 8.726349E+01 + 1.460002E+01 6.000000E+01 3 1.306810E+02 1.341744E+00 1.306452E+02 3.059990E+00 + 1.460002E+01 6.000000E+01 4 3.194173E+02 8.947560E+01 2.923404E+00 3.194039E+02 + 1.460002E+01 6.000000E+01 5 3.469147E+02 8.965853E+01 2.067532E+00 3.469086E+02 + 1.460002E+01 6.000000E+01 6 3.022028E+02 -3.274328E-02 3.022027E+02 -1.727022E-01 + 1.460002E+01 9.000000E+01 1 5.079569E-06 -8.999317E+01 6.052689E-10 -5.079569E-06 + 1.460002E+01 9.000000E+01 2 1.028633E+02 8.947523E+01 9.421161E-01 1.028589E+02 + 1.460002E+01 9.000000E+01 3 1.335172E+02 1.358744E+00 1.334797E+02 3.166005E+00 + 1.460002E+01 9.000000E+01 4 3.813017E+02 8.948164E+01 3.449689E+00 3.812861E+02 + 1.460002E+01 9.000000E+01 5 2.113527E-04 -8.989001E+01 4.056980E-07 -2.113523E-04 + 1.460002E+01 9.000000E+01 6 2.649499E-05 1.799787E+02 -2.649499E-05 9.873189E-09 + 1.470002E+01 0.000000E+00 1 8.934002E+01 8.966077E+01 5.289591E-01 8.933846E+01 + 1.470002E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.470002E+01 0.000000E+00 3 1.235926E+02 1.273147E+00 1.235621E+02 2.746077E+00 + 1.470002E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.470002E+01 0.000000E+00 5 6.562511E+02 8.966051E+01 3.888381E+00 6.562396E+02 + 1.470002E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.470002E+01 3.000000E+01 1 7.877178E+01 8.966186E+01 4.648857E-01 7.877041E+01 + 1.470002E+01 3.000000E+01 2 4.803225E+01 8.948874E+01 4.285992E-01 4.803034E+01 + 1.470002E+01 3.000000E+01 3 1.262114E+02 1.289177E+00 1.261794E+02 2.839566E+00 + 1.470002E+01 3.000000E+01 4 1.708953E+02 8.947484E+01 1.566375E+00 1.708882E+02 + 1.470002E+01 3.000000E+01 5 5.791414E+02 8.966192E+01 3.417307E+00 5.791313E+02 + 1.470002E+01 3.000000E+01 6 2.850809E+02 -3.182985E-02 2.850809E+02 -1.583726E-01 + 1.470002E+01 6.000000E+01 1 4.715218E+01 8.966389E+01 2.766046E-01 4.715137E+01 + 1.470002E+01 6.000000E+01 2 8.662259E+01 8.948761E+01 7.746499E-01 8.661913E+01 + 1.470002E+01 6.000000E+01 3 1.316294E+02 1.321567E+00 1.315944E+02 3.035854E+00 + 1.470002E+01 6.000000E+01 4 3.164691E+02 8.948743E+01 2.831140E+00 3.164564E+02 + 1.470002E+01 6.000000E+01 5 3.469092E+02 8.966417E+01 2.033355E+00 3.469033E+02 + 1.470002E+01 6.000000E+01 6 2.970460E+02 -3.137781E-02 2.970460E+02 -1.626761E-01 + 1.470002E+01 9.000000E+01 1 5.039243E-06 -8.999886E+01 1.007715E-10 -5.039243E-06 + 1.470002E+01 9.000000E+01 2 1.020634E+02 8.948706E+01 9.137036E-01 1.020593E+02 + 1.470002E+01 9.000000E+01 3 1.344297E+02 1.337892E+00 1.343931E+02 3.138733E+00 + 1.470002E+01 9.000000E+01 4 3.775727E+02 8.949325E+01 3.339386E+00 3.775579E+02 + 1.470002E+01 9.000000E+01 5 2.100547E-04 -8.989306E+01 3.920825E-07 -2.100543E-04 + 1.470002E+01 9.000000E+01 6 2.603161E-05 1.799795E+02 -2.603161E-05 9.301885E-09 + 1.480002E+01 0.000000E+00 1 8.877970E+01 8.966649E+01 5.167668E-01 8.877820E+01 + 1.480002E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.480002E+01 0.000000E+00 3 1.246186E+02 1.255260E+00 1.245887E+02 2.729977E+00 + 1.480002E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.480002E+01 0.000000E+00 5 6.568660E+02 8.966626E+01 3.826134E+00 6.568548E+02 + 1.480002E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.480002E+01 3.000000E+01 1 7.825255E+01 8.966753E+01 4.540872E-01 7.825123E+01 + 1.480002E+01 3.000000E+01 2 4.771630E+01 8.950009E+01 4.163271E-01 4.771449E+01 + 1.480002E+01 3.000000E+01 3 1.272083E+02 1.270658E+00 1.271770E+02 2.820889E+00 + 1.480002E+01 3.000000E+01 4 1.695220E+02 8.948669E+01 1.518737E+00 1.695152E+02 + 1.480002E+01 3.000000E+01 5 5.794677E+02 8.966758E+01 3.361999E+00 5.794579E+02 + 1.480002E+01 3.000000E+01 6 2.804776E+02 -3.050905E-02 2.804776E+02 -1.493496E-01 + 1.480002E+01 6.000000E+01 1 4.681024E+01 8.966943E+01 2.700717E-01 4.680946E+01 + 1.480002E+01 6.000000E+01 2 8.598749E+01 8.949902E+01 7.518459E-01 8.598420E+01 + 1.480002E+01 6.000000E+01 3 1.325615E+02 1.301795E+00 1.325273E+02 3.011619E+00 + 1.480002E+01 6.000000E+01 4 3.135744E+02 8.949885E+01 2.742731E+00 3.135624E+02 + 1.480002E+01 6.000000E+01 5 3.468528E+02 8.966969E+01 1.999662E+00 3.468470E+02 + 1.480002E+01 6.000000E+01 6 2.920262E+02 -3.008408E-02 2.920262E+02 -1.533331E-01 + 1.480002E+01 9.000000E+01 1 4.999580E-06 -9.000419E+01 -3.654768E-10 -4.999580E-06 + 1.480002E+01 9.000000E+01 2 1.012766E+02 8.949850E+01 8.864421E-01 1.012727E+02 + 1.480002E+01 9.000000E+01 3 1.353274E+02 1.317483E+00 1.352916E+02 3.111501E+00 + 1.480002E+01 9.000000E+01 4 3.739180E+02 8.950448E+01 3.233794E+00 3.739040E+02 + 1.480002E+01 9.000000E+01 5 2.087706E-04 -8.989598E+01 3.790296E-07 -2.087702E-04 + 1.480002E+01 9.000000E+01 6 2.558093E-05 1.799804E+02 -2.558093E-05 8.769400E-09 + 1.490002E+01 0.000000E+00 1 8.822519E+01 8.967208E+01 5.049328E-01 8.822375E+01 + 1.490002E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.490002E+01 0.000000E+00 3 1.256275E+02 1.237665E+00 1.255981E+02 2.713509E+00 + 1.490002E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.490002E+01 0.000000E+00 5 6.573676E+02 8.967187E+01 3.764722E+00 6.573568E+02 + 1.490002E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.490002E+01 3.000000E+01 1 7.773914E+01 8.967305E+01 4.436097E-01 7.773788E+01 + 1.490002E+01 3.000000E+01 2 4.740380E+01 8.951105E+01 4.045225E-01 4.740208E+01 + 1.490002E+01 3.000000E+01 3 1.281878E+02 1.252486E+00 1.281572E+02 2.801964E+00 + 1.490002E+01 3.000000E+01 4 1.681700E+02 8.949814E+01 1.473014E+00 1.681635E+02 + 1.490002E+01 3.000000E+01 5 5.797009E+02 8.967310E+01 3.307492E+00 5.796915E+02 + 1.490002E+01 3.000000E+01 6 2.759885E+02 -2.925755E-02 2.759884E+02 -1.409309E-01 + 1.490002E+01 6.000000E+01 1 4.647306E+01 8.967484E+01 2.637374E-01 4.647231E+01 + 1.490002E+01 6.000000E+01 2 8.536143E+01 8.951005E+01 7.299417E-01 8.535831E+01 + 1.490002E+01 6.000000E+01 3 1.334781E+02 1.282427E+00 1.334447E+02 2.987334E+00 + 1.490002E+01 6.000000E+01 4 3.107328E+02 8.950988E+01 2.658035E+00 3.107214E+02 + 1.490002E+01 6.000000E+01 5 3.467537E+02 8.967508E+01 1.966433E+00 3.467481E+02 + 1.490002E+01 6.000000E+01 6 2.871392E+02 -2.885762E-02 2.871392E+02 -1.446207E-01 + 1.490002E+01 9.000000E+01 1 4.960578E-06 -9.000919E+01 -7.961881E-10 -4.960578E-06 + 1.490002E+01 9.000000E+01 2 1.005024E+02 8.950956E+01 8.602720E-01 1.004988E+02 + 1.490002E+01 9.000000E+01 3 1.362085E+02 1.297531E+00 1.361736E+02 3.084341E+00 + 1.490002E+01 9.000000E+01 4 3.703365E+02 8.951534E+01 3.132666E+00 3.703233E+02 + 1.490002E+01 9.000000E+01 5 2.075021E-04 -8.989880E+01 3.665159E-07 -2.075017E-04 + 1.490002E+01 9.000000E+01 6 2.514250E-05 1.799812E+02 -2.514250E-05 8.272731E-09 + 1.500002E+01 0.000000E+00 1 8.767646E+01 8.967754E+01 4.934455E-01 8.767507E+01 + 1.500002E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.500002E+01 0.000000E+00 3 1.266190E+02 1.220399E+00 1.265903E+02 2.696779E+00 + 1.500002E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.500002E+01 0.000000E+00 5 6.577644E+02 8.967734E+01 3.704196E+00 6.577540E+02 + 1.500002E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.500002E+01 3.000000E+01 1 7.723136E+01 8.967844E+01 4.334382E-01 7.723015E+01 + 1.500002E+01 3.000000E+01 2 4.709496E+01 8.952168E+01 3.931641E-01 4.709332E+01 + 1.500002E+01 3.000000E+01 3 1.291510E+02 1.234663E+00 1.291210E+02 2.782850E+00 + 1.500002E+01 3.000000E+01 4 1.668384E+02 8.950921E+01 1.429110E+00 1.668323E+02 + 1.500002E+01 3.000000E+01 5 5.798446E+02 8.967849E+01 3.253777E+00 5.798354E+02 + 1.500002E+01 3.000000E+01 6 2.716092E+02 -2.807072E-02 2.716092E+02 -1.330685E-01 + 1.500002E+01 6.000000E+01 1 4.614055E+01 8.968013E+01 2.575900E-01 4.613984E+01 + 1.500002E+01 6.000000E+01 2 8.474454E+01 8.952071E+01 7.088934E-01 8.474157E+01 + 1.500002E+01 6.000000E+01 3 1.343785E+02 1.263469E+00 1.343458E+02 2.963034E+00 + 1.500002E+01 6.000000E+01 4 3.079449E+02 8.952056E+01 2.576803E+00 3.079342E+02 + 1.500002E+01 6.000000E+01 5 3.466065E+02 8.968035E+01 1.933706E+00 3.466011E+02 + 1.500002E+01 6.000000E+01 6 2.823795E+02 -2.769420E-02 2.823794E+02 -1.364895E-01 + 1.500002E+01 9.000000E+01 1 4.922194E-06 -9.001389E+01 -1.193877E-09 -4.922194E-06 + 1.500002E+01 9.000000E+01 2 9.974036E+01 8.952024E+01 8.351440E-01 9.973687E+01 + 1.500002E+01 9.000000E+01 3 1.370753E+02 1.277996E+00 1.370412E+02 3.057245E+00 + 1.500002E+01 9.000000E+01 4 3.668237E+02 8.952583E+01 3.035752E+00 3.668111E+02 + 1.500002E+01 9.000000E+01 5 2.062474E-04 -8.990152E+01 3.545141E-07 -2.062470E-04 + 1.500002E+01 9.000000E+01 6 2.471590E-05 1.799819E+02 -2.471590E-05 7.809119E-09 + 1.510002E+01 0.000000E+00 1 8.713300E+01 8.968285E+01 4.822934E-01 8.713167E+01 + 1.510002E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.510002E+01 0.000000E+00 3 1.275944E+02 1.203435E+00 1.275662E+02 2.679784E+00 + 1.510002E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.510002E+01 0.000000E+00 5 6.580576E+02 8.968267E+01 3.644553E+00 6.580475E+02 + 1.510002E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.510002E+01 3.000000E+01 1 7.672961E+01 8.968371E+01 4.235687E-01 7.672844E+01 + 1.510002E+01 3.000000E+01 2 4.678942E+01 8.953194E+01 3.822304E-01 4.678786E+01 + 1.510002E+01 3.000000E+01 3 1.300972E+02 1.217184E+00 1.300678E+02 2.763560E+00 + 1.510002E+01 3.000000E+01 4 1.655255E+02 8.951991E+01 1.386959E+00 1.655197E+02 + 1.510002E+01 3.000000E+01 5 5.799040E+02 8.968375E+01 3.200826E+00 5.798951E+02 + 1.510002E+01 3.000000E+01 6 2.673363E+02 -2.694475E-02 2.673362E+02 -1.257215E-01 + 1.510002E+01 6.000000E+01 1 4.581274E+01 8.968530E+01 2.516267E-01 4.581205E+01 + 1.510002E+01 6.000000E+01 2 8.413657E+01 8.953103E+01 6.886593E-01 8.413375E+01 + 1.510002E+01 6.000000E+01 3 1.352637E+02 1.244908E+00 1.352318E+02 2.938744E+00 + 1.510002E+01 6.000000E+01 4 3.052050E+02 8.953088E+01 2.498896E+00 3.051948E+02 + 1.510002E+01 6.000000E+01 5 3.464147E+02 8.968550E+01 1.901496E+00 3.464095E+02 + 1.510002E+01 6.000000E+01 6 2.777427E+02 -2.658994E-02 2.777427E+02 -1.288954E-01 + 1.510002E+01 9.000000E+01 1 4.884440E-06 -9.001831E+01 -1.560826E-09 -4.884439E-06 + 1.510002E+01 9.000000E+01 2 9.899045E+01 8.953059E+01 8.110016E-01 9.898713E+01 + 1.510002E+01 9.000000E+01 3 1.379266E+02 1.258885E+00 1.378933E+02 3.030236E+00 + 1.510002E+01 9.000000E+01 4 3.633807E+02 8.953598E+01 2.942872E+00 3.633688E+02 + 1.510002E+01 9.000000E+01 5 2.050074E-04 -8.990414E+01 3.429994E-07 -2.050071E-04 + 1.510002E+01 9.000000E+01 6 2.430062E-05 1.799826E+02 -2.430062E-05 7.376046E-09 + 1.520002E+01 0.000000E+00 1 8.659521E+01 8.968806E+01 4.714664E-01 8.659393E+01 + 1.520002E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.520002E+01 0.000000E+00 3 1.285534E+02 1.186760E+00 1.285259E+02 2.662521E+00 + 1.520002E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.520002E+01 0.000000E+00 5 6.582505E+02 8.968787E+01 3.585832E+00 6.582408E+02 + 1.520002E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.520002E+01 3.000000E+01 1 7.623369E+01 8.968886E+01 4.139851E-01 7.623257E+01 + 1.520002E+01 3.000000E+01 2 4.648751E+01 8.954188E+01 3.717035E-01 4.648602E+01 + 1.520002E+01 3.000000E+01 3 1.310284E+02 1.199995E+00 1.309997E+02 2.744039E+00 + 1.520002E+01 3.000000E+01 4 1.642324E+02 8.953027E+01 1.346447E+00 1.642269E+02 + 1.520002E+01 3.000000E+01 5 5.798818E+02 8.968889E+01 3.148697E+00 5.798732E+02 + 1.520002E+01 3.000000E+01 6 2.631668E+02 -2.587582E-02 2.631667E+02 -1.188509E-01 + 1.520002E+01 6.000000E+01 1 4.548966E+01 8.969035E+01 2.458408E-01 4.548900E+01 + 1.520002E+01 6.000000E+01 2 8.353723E+01 8.954101E+01 6.692020E-01 8.353455E+01 + 1.520002E+01 6.000000E+01 3 1.361334E+02 1.226707E+00 1.361022E+02 2.914402E+00 + 1.520002E+01 6.000000E+01 4 3.025162E+02 8.954087E+01 2.424147E+00 3.025065E+02 + 1.520002E+01 6.000000E+01 5 3.461852E+02 8.969054E+01 1.869825E+00 3.461802E+02 + 1.520002E+01 6.000000E+01 6 2.732248E+02 -2.554131E-02 2.732248E+02 -1.217982E-01 + 1.520002E+01 9.000000E+01 1 4.847285E-06 -9.002245E+01 -1.899215E-09 -4.847284E-06 + 1.520002E+01 9.000000E+01 2 9.825237E+01 8.954059E+01 7.878018E-01 9.824921E+01 + 1.520002E+01 9.000000E+01 3 1.387645E+02 1.240151E+00 1.387320E+02 3.003283E+00 + 1.520002E+01 9.000000E+01 4 3.600040E+02 8.954581E+01 2.853787E+00 3.599927E+02 + 1.520002E+01 9.000000E+01 5 2.037803E-04 -8.990667E+01 3.319499E-07 -2.037801E-04 + 1.520002E+01 9.000000E+01 6 2.389628E-05 1.799833E+02 -2.389628E-05 6.971225E-09 + 1.530002E+01 0.000000E+00 1 8.606243E+01 8.969312E+01 4.609525E-01 8.606120E+01 + 1.530002E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.530002E+01 0.000000E+00 3 1.294955E+02 1.170427E+00 1.294685E+02 2.645124E+00 + 1.530002E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.530002E+01 0.000000E+00 5 6.583472E+02 8.969296E+01 3.527977E+00 6.583377E+02 + 1.530002E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.530002E+01 3.000000E+01 1 7.574323E+01 8.969388E+01 4.046807E-01 7.574215E+01 + 1.530002E+01 3.000000E+01 2 4.618900E+01 8.955148E+01 3.615649E-01 4.618759E+01 + 1.530002E+01 3.000000E+01 3 1.319434E+02 1.183168E+00 1.319152E+02 2.724460E+00 + 1.530002E+01 3.000000E+01 4 1.629589E+02 8.954028E+01 1.307519E+00 1.629536E+02 + 1.530002E+01 3.000000E+01 5 5.797832E+02 8.969391E+01 3.097349E+00 5.797749E+02 + 1.530002E+01 3.000000E+01 6 2.590969E+02 -2.486056E-02 2.590969E+02 -1.124218E-01 + 1.530002E+01 6.000000E+01 1 4.517104E+01 8.969530E+01 2.402260E-01 4.517040E+01 + 1.530002E+01 6.000000E+01 2 8.294641E+01 8.955067E+01 6.504865E-01 8.294386E+01 + 1.530002E+01 6.000000E+01 3 1.369893E+02 1.208894E+00 1.369588E+02 2.890149E+00 + 1.530002E+01 6.000000E+01 4 2.998741E+02 8.955054E+01 2.352382E+00 2.998648E+02 + 1.530002E+01 6.000000E+01 5 3.459137E+02 8.969545E+01 1.838653E+00 3.459088E+02 + 1.530002E+01 6.000000E+01 6 2.688218E+02 -2.454494E-02 2.688217E+02 -1.151606E-01 + 1.530002E+01 9.000000E+01 1 4.810727E-06 -9.002634E+01 -2.211027E-09 -4.810727E-06 + 1.530002E+01 9.000000E+01 2 9.752534E+01 8.955027E+01 7.654933E-01 9.752234E+01 + 1.530002E+01 9.000000E+01 3 1.395885E+02 1.221842E+00 1.395568E+02 2.976523E+00 + 1.530002E+01 9.000000E+01 4 3.566913E+02 8.955532E+01 2.768331E+00 3.566806E+02 + 1.530002E+01 9.000000E+01 5 2.025673E-04 -8.990911E+01 3.213458E-07 -2.025671E-04 + 1.530002E+01 9.000000E+01 6 2.350250E-05 1.799839E+02 -2.350250E-05 6.592542E-09 + 1.540002E+01 0.000000E+00 1 8.553530E+01 8.969807E+01 4.507416E-01 8.553411E+01 + 1.540002E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.540002E+01 0.000000E+00 3 1.304226E+02 1.154364E+00 1.303961E+02 2.627505E+00 + 1.540002E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.540002E+01 0.000000E+00 5 6.583620E+02 8.969792E+01 3.470994E+00 6.583528E+02 + 1.540002E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.540002E+01 3.000000E+01 1 7.525835E+01 8.969878E+01 3.956480E-01 7.525731E+01 + 1.540002E+01 3.000000E+01 2 4.589386E+01 8.956080E+01 3.517953E-01 4.589251E+01 + 1.540002E+01 3.000000E+01 3 1.328431E+02 1.166649E+00 1.328155E+02 2.704745E+00 + 1.540002E+01 3.000000E+01 4 1.617028E+02 8.954997E+01 1.270088E+00 1.616978E+02 + 1.540002E+01 3.000000E+01 5 5.796142E+02 8.969881E+01 3.046833E+00 5.796062E+02 + 1.540002E+01 3.000000E+01 6 2.551239E+02 -2.389564E-02 2.551238E+02 -1.064014E-01 + 1.540002E+01 6.000000E+01 1 4.485680E+01 8.970012E+01 2.347775E-01 4.485618E+01 + 1.540002E+01 6.000000E+01 2 8.236400E+01 8.956002E+01 6.324736E-01 8.236157E+01 + 1.540002E+01 6.000000E+01 3 1.378305E+02 1.191440E+00 1.378007E+02 2.865917E+00 + 1.540002E+01 6.000000E+01 4 2.972792E+02 8.955989E+01 2.283461E+00 2.972704E+02 + 1.540002E+01 6.000000E+01 5 3.456057E+02 8.970026E+01 1.807986E+00 3.456010E+02 + 1.540002E+01 6.000000E+01 6 2.645298E+02 -2.359766E-02 2.645297E+02 -1.089484E-01 + 1.540002E+01 9.000000E+01 1 4.774732E-06 -9.002998E+01 -2.498079E-09 -4.774731E-06 + 1.540002E+01 9.000000E+01 2 9.680955E+01 8.955964E+01 7.440415E-01 9.680669E+01 + 1.540002E+01 9.000000E+01 3 1.403971E+02 1.203922E+00 1.403661E+02 2.949863E+00 + 1.540002E+01 9.000000E+01 4 3.534423E+02 8.956452E+01 2.686297E+00 3.534321E+02 + 1.540002E+01 9.000000E+01 5 2.013682E-04 -8.991146E+01 3.111631E-07 -2.013679E-04 + 1.540002E+01 9.000000E+01 6 2.311891E-05 1.799845E+02 -2.311891E-05 6.238065E-09 + 1.550002E+01 0.000000E+00 1 8.501358E+01 8.970290E+01 4.408222E-01 8.501244E+01 + 1.550002E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.550002E+01 0.000000E+00 3 1.313343E+02 1.138597E+00 1.313084E+02 2.609739E+00 + 1.550002E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.550002E+01 0.000000E+00 5 6.582881E+02 8.970277E+01 3.414966E+00 6.582793E+02 + 1.550002E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.550002E+01 3.000000E+01 1 7.477923E+01 8.970358E+01 3.868747E-01 7.477823E+01 + 1.550002E+01 3.000000E+01 2 4.560212E+01 8.956982E+01 3.423804E-01 4.560084E+01 + 1.550002E+01 3.000000E+01 3 1.337283E+02 1.150445E+00 1.337013E+02 2.684956E+00 + 1.550002E+01 3.000000E+01 4 1.604662E+02 8.955936E+01 1.234099E+00 1.604614E+02 + 1.550002E+01 3.000000E+01 5 5.793742E+02 8.970361E+01 2.997118E+00 5.793665E+02 + 1.550002E+01 3.000000E+01 6 2.512444E+02 -2.297812E-02 2.512443E+02 -1.007600E-01 + 1.550002E+01 6.000000E+01 1 4.454686E+01 8.970483E+01 2.294877E-01 4.454627E+01 + 1.550002E+01 6.000000E+01 2 8.178957E+01 8.956908E+01 6.151325E-01 8.178726E+01 + 1.550002E+01 6.000000E+01 3 1.386578E+02 1.174335E+00 1.386287E+02 2.841734E+00 + 1.550002E+01 6.000000E+01 4 2.947299E+02 8.956896E+01 2.217250E+00 2.947216E+02 + 1.550002E+01 6.000000E+01 5 3.452635E+02 8.970497E+01 1.777822E+00 3.452590E+02 + 1.550002E+01 6.000000E+01 6 2.603443E+02 -2.269665E-02 2.603442E+02 -1.031305E-01 + 1.550002E+01 9.000000E+01 1 4.739297E-06 -9.003339E+01 -2.762163E-09 -4.739296E-06 + 1.550002E+01 9.000000E+01 2 9.610486E+01 8.956872E+01 7.234001E-01 9.610213E+01 + 1.550002E+01 9.000000E+01 3 1.411937E+02 1.186374E+00 1.411634E+02 2.923365E+00 + 1.550002E+01 9.000000E+01 4 3.502533E+02 8.957345E+01 2.607532E+00 3.502436E+02 + 1.550002E+01 9.000000E+01 5 2.001821E-04 -8.991374E+01 3.013827E-07 -2.001819E-04 + 1.550002E+01 9.000000E+01 6 2.274516E-05 1.799851E+02 -2.274516E-05 5.906017E-09 + 1.560002E+01 0.000000E+00 1 8.449736E+01 8.970763E+01 4.311863E-01 8.449626E+01 + 1.560002E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.560002E+01 0.000000E+00 3 1.322307E+02 1.123103E+00 1.322053E+02 2.591802E+00 + 1.560002E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.560002E+01 0.000000E+00 5 6.581295E+02 8.970750E+01 3.359847E+00 6.581208E+02 + 1.560002E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.560002E+01 3.000000E+01 1 7.430541E+01 8.970826E+01 3.783545E-01 7.430445E+01 + 1.560002E+01 3.000000E+01 2 4.531374E+01 8.957856E+01 3.333023E-01 4.531251E+01 + 1.560002E+01 3.000000E+01 3 1.345982E+02 1.134543E+00 1.345718E+02 2.665074E+00 + 1.560002E+01 3.000000E+01 4 1.592472E+02 8.956844E+01 1.199459E+00 1.592427E+02 + 1.560002E+01 3.000000E+01 5 5.790646E+02 8.970828E+01 2.948259E+00 5.790571E+02 + 1.560002E+01 3.000000E+01 6 2.474553E+02 -2.210524E-02 2.474553E+02 -9.547052E-02 + 1.560002E+01 6.000000E+01 1 4.424113E+01 8.970945E+01 2.243525E-01 4.424057E+01 + 1.560002E+01 6.000000E+01 2 8.122330E+01 8.957786E+01 5.984322E-01 8.122110E+01 + 1.560002E+01 6.000000E+01 3 1.394710E+02 1.157583E+00 1.394425E+02 2.817630E+00 + 1.560002E+01 6.000000E+01 4 2.922254E+02 8.957774E+01 2.153616E+00 2.922175E+02 + 1.560002E+01 6.000000E+01 5 3.448848E+02 8.970957E+01 1.748207E+00 3.448803E+02 + 1.560002E+01 6.000000E+01 6 2.562623E+02 -2.183915E-02 2.562622E+02 -9.767821E-02 + 1.560002E+01 9.000000E+01 1 4.704414E-06 -9.003660E+01 -3.004812E-09 -4.704413E-06 + 1.560002E+01 9.000000E+01 2 9.541071E+01 8.957751E+01 7.035336E-01 9.540811E+01 + 1.560002E+01 9.000000E+01 3 1.419765E+02 1.169180E+00 1.419470E+02 2.896977E+00 + 1.560002E+01 9.000000E+01 4 3.471267E+02 8.958209E+01 2.531875E+00 3.471174E+02 + 1.560002E+01 9.000000E+01 5 1.990087E-04 -8.991594E+01 2.919870E-07 -1.990085E-04 + 1.560002E+01 9.000000E+01 6 2.238082E-05 1.799857E+02 -2.238082E-05 5.594784E-09 + 1.570002E+01 0.000000E+00 1 8.398630E+01 8.971223E+01 4.218252E-01 8.398524E+01 + 1.570002E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.570002E+01 0.000000E+00 3 1.331126E+02 1.107914E+00 1.330877E+02 2.573803E+00 + 1.570002E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.570002E+01 0.000000E+00 5 6.578960E+02 8.971211E+01 3.305639E+00 6.578877E+02 + 1.570002E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.570002E+01 3.000000E+01 1 7.383731E+01 8.971283E+01 3.700774E-01 7.383638E+01 + 1.570002E+01 3.000000E+01 2 4.502851E+01 8.958703E+01 3.245486E-01 4.502734E+01 + 1.570002E+01 3.000000E+01 3 1.354543E+02 1.118935E+00 1.354284E+02 2.645133E+00 + 1.570002E+01 3.000000E+01 4 1.580459E+02 8.957725E+01 1.166122E+00 1.580416E+02 + 1.570002E+01 3.000000E+01 5 5.786974E+02 8.971285E+01 2.900206E+00 5.786901E+02 + 1.570002E+01 3.000000E+01 6 2.437544E+02 -2.127433E-02 2.437544E+02 -9.050775E-02 + 1.570002E+01 6.000000E+01 1 4.393958E+01 8.971396E+01 2.193666E-01 4.393903E+01 + 1.570002E+01 6.000000E+01 2 8.066491E+01 8.958636E+01 5.823464E-01 8.066280E+01 + 1.570002E+01 6.000000E+01 3 1.402710E+02 1.141168E+00 1.402432E+02 2.793614E+00 + 1.570002E+01 6.000000E+01 4 2.897626E+02 8.958625E+01 2.092440E+00 2.897550E+02 + 1.570002E+01 6.000000E+01 5 3.444773E+02 8.971407E+01 1.719118E+00 3.444730E+02 + 1.570002E+01 6.000000E+01 6 2.522802E+02 -2.102265E-02 2.522801E+02 -9.256525E-02 + 1.570002E+01 9.000000E+01 1 4.670068E-06 -9.003960E+01 -3.227515E-09 -4.670067E-06 + 1.570002E+01 9.000000E+01 2 9.472731E+01 8.958603E+01 6.844041E-01 9.472484E+01 + 1.570002E+01 9.000000E+01 3 1.427458E+02 1.152369E+00 1.427170E+02 2.870800E+00 + 1.570002E+01 9.000000E+01 4 3.440529E+02 8.959046E+01 2.459167E+00 3.440441E+02 + 1.570002E+01 9.000000E+01 5 1.978478E-04 -8.991805E+01 2.829585E-07 -1.978476E-04 + 1.570002E+01 9.000000E+01 6 2.202568E-05 1.799862E+02 -2.202568E-05 5.302874E-09 + 1.580002E+01 0.000000E+00 1 8.348027E+01 8.971673E+01 4.127260E-01 8.347925E+01 + 1.580002E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.580002E+01 0.000000E+00 3 1.339804E+02 1.092994E+00 1.339560E+02 2.555701E+00 + 1.580002E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.580002E+01 0.000000E+00 5 6.575893E+02 8.971663E+01 3.252314E+00 6.575812E+02 + 1.580002E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.580002E+01 3.000000E+01 1 7.337444E+01 8.971729E+01 3.620350E-01 7.337354E+01 + 1.580002E+01 3.000000E+01 2 4.474663E+01 8.959525E+01 3.161027E-01 4.474551E+01 + 1.580002E+01 3.000000E+01 3 1.362958E+02 1.103642E+00 1.362705E+02 2.625192E+00 + 1.580002E+01 3.000000E+01 4 1.568627E+02 8.958578E+01 1.134036E+00 1.568586E+02 + 1.580002E+01 3.000000E+01 5 5.782645E+02 8.971732E+01 2.852954E+00 5.782575E+02 + 1.580002E+01 3.000000E+01 6 2.401385E+02 -2.048301E-02 2.401385E+02 -8.584853E-02 + 1.580002E+01 6.000000E+01 1 4.364219E+01 8.971836E+01 2.145253E-01 4.364167E+01 + 1.580002E+01 6.000000E+01 2 8.011423E+01 8.959460E+01 5.668424E-01 8.011222E+01 + 1.580002E+01 6.000000E+01 3 1.410566E+02 1.125105E+00 1.410294E+02 2.769721E+00 + 1.580002E+01 6.000000E+01 4 2.873427E+02 8.959451E+01 2.033598E+00 2.873354E+02 + 1.580002E+01 6.000000E+01 5 3.440365E+02 8.971846E+01 1.690512E+00 3.440323E+02 + 1.580002E+01 6.000000E+01 6 2.483942E+02 -2.024484E-02 2.483942E+02 -8.776741E-02 + 1.580002E+01 9.000000E+01 1 4.636241E-06 -9.004241E+01 -3.431655E-09 -4.636240E-06 + 1.580002E+01 9.000000E+01 2 9.405357E+01 8.959430E+01 6.659787E-01 9.405122E+01 + 1.580002E+01 9.000000E+01 3 1.435032E+02 1.135892E+00 1.434750E+02 2.844773E+00 + 1.580002E+01 9.000000E+01 4 3.410387E+02 8.959859E+01 2.389280E+00 3.410303E+02 + 1.580002E+01 9.000000E+01 5 1.967006E-04 -8.992011E+01 2.742790E-07 -1.967004E-04 + 1.580002E+01 9.000000E+01 6 2.167934E-05 1.799867E+02 -2.167934E-05 5.028896E-09 + 1.590002E+01 0.000000E+00 1 8.298023E+01 8.972113E+01 4.038826E-01 8.297925E+01 + 1.590002E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.590002E+01 0.000000E+00 3 1.348329E+02 1.078353E+00 1.348090E+02 2.537514E+00 + 1.590002E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.590002E+01 0.000000E+00 5 6.572054E+02 8.972102E+01 3.199937E+00 6.571976E+02 + 1.590002E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.590002E+01 3.000000E+01 1 7.291677E+01 8.972166E+01 3.542206E-01 7.291591E+01 + 1.590002E+01 3.000000E+01 2 4.446796E+01 8.960321E+01 3.079539E-01 4.446689E+01 + 1.590002E+01 3.000000E+01 3 1.371233E+02 1.088633E+00 1.370986E+02 2.605219E+00 + 1.590002E+01 3.000000E+01 4 1.556960E+02 8.959405E+01 1.103129E+00 1.556920E+02 + 1.590002E+01 3.000000E+01 5 5.777761E+02 8.972169E+01 2.806556E+00 5.777693E+02 + 1.590002E+01 3.000000E+01 6 2.366047E+02 -1.972905E-02 2.366047E+02 -8.147172E-02 + 1.590002E+01 6.000000E+01 1 4.334882E+01 8.972267E+01 2.098231E-01 4.334831E+01 + 1.590002E+01 6.000000E+01 2 7.957107E+01 8.960260E+01 5.518972E-01 7.956915E+01 + 1.590002E+01 6.000000E+01 3 1.418307E+02 1.109341E+00 1.418042E+02 2.745907E+00 + 1.590002E+01 6.000000E+01 4 2.849661E+02 8.960250E+01 1.976981E+00 2.849593E+02 + 1.590002E+01 6.000000E+01 5 3.435679E+02 8.972276E+01 1.662444E+00 3.435639E+02 + 1.590002E+01 6.000000E+01 6 2.446023E+02 -1.950350E-02 2.446022E+02 -8.326268E-02 + 1.590002E+01 9.000000E+01 1 4.602926E-06 -9.004504E+01 -3.618515E-09 -4.602924E-06 + 1.590002E+01 9.000000E+01 2 9.338999E+01 8.960230E+01 6.482276E-01 9.338774E+01 + 1.590002E+01 9.000000E+01 3 1.442480E+02 1.119761E+00 1.442204E+02 2.818933E+00 + 1.590002E+01 9.000000E+01 4 3.380776E+02 8.960646E+01 2.322075E+00 3.380696E+02 + 1.590002E+01 9.000000E+01 5 1.955658E-04 -8.992209E+01 2.659353E-07 -1.955656E-04 + 1.590002E+01 9.000000E+01 6 2.134156E-05 1.799872E+02 -2.134156E-05 4.771601E-09 + 1.600002E+01 0.000000E+00 1 8.248469E+01 8.972543E+01 3.952885E-01 8.248374E+01 + 1.600002E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.600002E+01 0.000000E+00 3 1.356718E+02 1.063973E+00 1.356484E+02 2.519257E+00 + 1.600002E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.600002E+01 0.000000E+00 5 6.567580E+02 8.972533E+01 3.148412E+00 6.567504E+02 + 1.600002E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.600002E+01 3.000000E+01 1 7.246449E+01 8.972593E+01 3.466277E-01 7.246365E+01 + 1.600002E+01 3.000000E+01 2 4.419244E+01 8.961094E+01 3.000866E-01 4.419143E+01 + 1.600002E+01 3.000000E+01 3 1.379379E+02 1.073897E+00 1.379137E+02 2.585224E+00 + 1.600002E+01 3.000000E+01 4 1.545462E+02 8.960207E+01 1.073349E+00 1.545425E+02 + 1.600002E+01 3.000000E+01 5 5.772315E+02 8.972595E+01 2.760939E+00 5.772249E+02 + 1.600002E+01 3.000000E+01 6 2.331511E+02 -1.901023E-02 2.331510E+02 -7.735745E-02 + 1.600002E+01 6.000000E+01 1 4.305938E+01 8.972688E+01 2.052545E-01 4.305889E+01 + 1.600002E+01 6.000000E+01 2 7.903542E+01 8.961035E+01 5.374856E-01 7.903358E+01 + 1.600002E+01 6.000000E+01 3 1.425912E+02 1.093902E+00 1.425652E+02 2.722215E+00 + 1.600002E+01 6.000000E+01 4 2.826280E+02 8.961026E+01 1.922494E+00 2.826215E+02 + 1.600002E+01 6.000000E+01 5 3.430718E+02 8.972696E+01 1.634872E+00 3.430679E+02 + 1.600002E+01 6.000000E+01 6 2.409003E+02 -1.879655E-02 2.409003E+02 -7.903018E-02 + 1.600002E+01 9.000000E+01 1 4.570110E-06 -9.004751E+01 -3.789268E-09 -4.570109E-06 + 1.600002E+01 9.000000E+01 2 9.273631E+01 8.961008E+01 6.311160E-01 9.273416E+01 + 1.600002E+01 9.000000E+01 3 1.449802E+02 1.103963E+00 1.449532E+02 2.793275E+00 + 1.600002E+01 9.000000E+01 4 3.351709E+02 8.961411E+01 2.257408E+00 3.351633E+02 + 1.600002E+01 9.000000E+01 5 1.944421E-04 -8.992400E+01 2.579107E-07 -1.944419E-04 + 1.600002E+01 9.000000E+01 6 2.101203E-05 1.799876E+02 -2.101203E-05 4.529813E-09 + 1.610003E+01 0.000000E+00 1 8.199458E+01 8.972961E+01 3.869341E-01 8.199367E+01 + 1.610003E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.610003E+01 0.000000E+00 3 1.364973E+02 1.049858E+00 1.364744E+02 2.500965E+00 + 1.610003E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.610003E+01 0.000000E+00 5 6.562446E+02 8.972954E+01 3.097819E+00 6.562373E+02 + 1.610003E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.610003E+01 3.000000E+01 1 7.201734E+01 8.973010E+01 3.392474E-01 7.201654E+01 + 1.610003E+01 3.000000E+01 2 4.392006E+01 8.961843E+01 2.924908E-01 4.391909E+01 + 1.610003E+01 3.000000E+01 3 1.387381E+02 1.059451E+00 1.387144E+02 2.565246E+00 + 1.610003E+01 3.000000E+01 4 1.534126E+02 8.960985E+01 1.044645E+00 1.534091E+02 + 1.610003E+01 3.000000E+01 5 5.766322E+02 8.973013E+01 2.716109E+00 5.766258E+02 + 1.610003E+01 3.000000E+01 6 2.297751E+02 -1.832469E-02 2.297751E+02 -7.348808E-02 + 1.610003E+01 6.000000E+01 1 4.277364E+01 8.973100E+01 2.008175E-01 4.277316E+01 + 1.610003E+01 6.000000E+01 2 7.850677E+01 8.961787E+01 5.235832E-01 7.850502E+01 + 1.610003E+01 6.000000E+01 3 1.433391E+02 1.078775E+00 1.433137E+02 2.698655E+00 + 1.610003E+01 6.000000E+01 4 2.803295E+02 8.961778E+01 1.870026E+00 2.803232E+02 + 1.610003E+01 6.000000E+01 5 3.425508E+02 8.973108E+01 1.607805E+00 3.425470E+02 + 1.610003E+01 6.000000E+01 6 2.372856E+02 -1.812215E-02 2.372856E+02 -7.505134E-02 + 1.610003E+01 9.000000E+01 1 4.537772E-06 -9.004981E+01 -3.945039E-09 -4.537770E-06 + 1.610003E+01 9.000000E+01 2 9.209183E+01 8.961761E+01 6.146173E-01 9.208978E+01 + 1.610003E+01 9.000000E+01 3 1.457000E+02 1.088498E+00 1.456738E+02 2.767825E+00 + 1.610003E+01 9.000000E+01 4 3.323153E+02 8.962151E+01 2.195188E+00 3.323080E+02 + 1.610003E+01 9.000000E+01 5 1.933317E-04 -8.992586E+01 2.501906E-07 -1.933316E-04 + 1.610003E+01 9.000000E+01 6 2.069044E-05 1.799881E+02 -2.069044E-05 4.302473E-09 + 1.620003E+01 0.000000E+00 1 8.150962E+01 8.973372E+01 3.788093E-01 8.150874E+01 + 1.620003E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.620003E+01 0.000000E+00 3 1.373093E+02 1.036007E+00 1.372869E+02 2.482654E+00 + 1.620003E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.620003E+01 0.000000E+00 5 6.556716E+02 8.973365E+01 3.048084E+00 6.556645E+02 + 1.620003E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.620003E+01 3.000000E+01 1 7.157527E+01 8.973418E+01 3.320727E-01 7.157450E+01 + 1.620003E+01 3.000000E+01 2 4.365086E+01 8.962571E+01 2.851542E-01 4.364993E+01 + 1.620003E+01 3.000000E+01 3 1.395263E+02 1.045278E+00 1.395030E+02 2.545311E+00 + 1.620003E+01 3.000000E+01 4 1.522952E+02 8.961739E+01 1.016979E+00 1.522918E+02 + 1.620003E+01 3.000000E+01 5 5.759805E+02 8.973420E+01 2.672055E+00 5.759743E+02 + 1.620003E+01 3.000000E+01 6 2.264742E+02 -1.767052E-02 2.264742E+02 -6.984662E-02 + 1.620003E+01 6.000000E+01 1 4.249178E+01 8.973503E+01 1.965063E-01 4.249132E+01 + 1.620003E+01 6.000000E+01 2 7.798560E+01 8.962518E+01 5.101681E-01 7.798392E+01 + 1.620003E+01 6.000000E+01 3 1.440754E+02 1.063956E+00 1.440506E+02 2.675261E+00 + 1.620003E+01 6.000000E+01 4 2.780690E+02 8.962509E+01 1.819491E+00 2.780630E+02 + 1.620003E+01 6.000000E+01 5 3.420031E+02 8.973509E+01 1.581232E+00 3.419995E+02 + 1.620003E+01 6.000000E+01 6 2.337555E+02 -1.747839E-02 2.337555E+02 -7.130837E-02 + 1.620003E+01 9.000000E+01 1 4.505927E-06 -9.005197E+01 -4.086868E-09 -4.505926E-06 + 1.620003E+01 9.000000E+01 2 9.145695E+01 8.962492E+01 5.987044E-01 9.145499E+01 + 1.620003E+01 9.000000E+01 3 1.464088E+02 1.073344E+00 1.463831E+02 2.742572E+00 + 1.620003E+01 9.000000E+01 4 3.295114E+02 8.962872E+01 2.135277E+00 3.295044E+02 + 1.620003E+01 9.000000E+01 5 1.922324E-04 -8.992764E+01 2.427637E-07 -1.922322E-04 + 1.620003E+01 9.000000E+01 6 2.037656E-05 1.799885E+02 -2.037656E-05 4.088583E-09 + 1.630003E+01 0.000000E+00 1 8.102962E+01 8.973773E+01 3.709082E-01 8.102878E+01 + 1.630003E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.630003E+01 0.000000E+00 3 1.381084E+02 1.022408E+00 1.380864E+02 2.464328E+00 + 1.630003E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.630003E+01 0.000000E+00 5 6.550367E+02 8.973766E+01 2.999223E+00 6.550299E+02 + 1.630003E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.630003E+01 3.000000E+01 1 7.113800E+01 8.973816E+01 3.250960E-01 7.113726E+01 + 1.630003E+01 3.000000E+01 2 4.338460E+01 8.963277E+01 2.780656E-01 4.338371E+01 + 1.630003E+01 3.000000E+01 3 1.403013E+02 1.031371E+00 1.402785E+02 2.525403E+00 + 1.630003E+01 3.000000E+01 4 1.511939E+02 8.962472E+01 9.902994E-01 1.511906E+02 + 1.630003E+01 3.000000E+01 5 5.752880E+02 8.973818E+01 2.628852E+00 5.752820E+02 + 1.630003E+01 3.000000E+01 6 2.232461E+02 -1.704601E-02 2.232461E+02 -6.641772E-02 + 1.630003E+01 6.000000E+01 1 4.221375E+01 8.973898E+01 1.923163E-01 4.221331E+01 + 1.630003E+01 6.000000E+01 2 7.747129E+01 8.963226E+01 4.972187E-01 7.746970E+01 + 1.630003E+01 6.000000E+01 3 1.448003E+02 1.049418E+00 1.447760E+02 2.651986E+00 + 1.630003E+01 6.000000E+01 4 2.758463E+02 8.963219E+01 1.770804E+00 2.758407E+02 + 1.630003E+01 6.000000E+01 5 3.414315E+02 8.973903E+01 1.555139E+00 3.414279E+02 + 1.630003E+01 6.000000E+01 6 2.303071E+02 -1.686371E-02 2.303071E+02 -6.778567E-02 + 1.630003E+01 9.000000E+01 1 4.474533E-06 -9.005399E+01 -4.215642E-09 -4.474531E-06 + 1.630003E+01 9.000000E+01 2 9.083119E+01 8.963202E+01 5.833520E-01 9.082932E+01 + 1.630003E+01 9.000000E+01 3 1.471063E+02 1.058501E+00 1.470812E+02 2.717536E+00 + 1.630003E+01 9.000000E+01 4 3.267547E+02 8.963570E+01 2.077567E+00 3.267481E+02 + 1.630003E+01 9.000000E+01 5 1.911456E-04 -8.992938E+01 2.356130E-07 -1.911455E-04 + 1.630003E+01 9.000000E+01 6 2.007018E-05 1.799889E+02 -2.007018E-05 3.887227E-09 + 1.640003E+01 0.000000E+00 1 8.055461E+01 8.974165E+01 3.632233E-01 8.055379E+01 + 1.640003E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.640003E+01 0.000000E+00 3 1.388940E+02 1.009062E+00 1.388724E+02 2.445999E+00 + 1.640003E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.640003E+01 0.000000E+00 5 6.543459E+02 8.974158E+01 2.951299E+00 6.543393E+02 + 1.640003E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.640003E+01 3.000000E+01 1 7.070606E+01 8.974206E+01 3.183130E-01 7.070535E+01 + 1.640003E+01 3.000000E+01 2 4.312134E+01 8.963963E+01 2.712153E-01 4.312048E+01 + 1.640003E+01 3.000000E+01 3 1.410633E+02 1.017727E+00 1.410411E+02 2.505533E+00 + 1.640003E+01 3.000000E+01 4 1.501079E+02 8.963183E+01 9.645554E-01 1.501048E+02 + 1.640003E+01 3.000000E+01 5 5.745479E+02 8.974207E+01 2.586395E+00 5.745421E+02 + 1.640003E+01 3.000000E+01 6 2.200888E+02 -1.644952E-02 2.200888E+02 -6.318712E-02 + 1.640003E+01 6.000000E+01 1 4.193920E+01 8.974283E+01 1.882436E-01 4.193877E+01 + 1.640003E+01 6.000000E+01 2 7.696369E+01 8.963915E+01 4.847154E-01 7.696217E+01 + 1.640003E+01 6.000000E+01 3 1.455114E+02 1.035188E+00 1.454877E+02 2.628876E+00 + 1.640003E+01 6.000000E+01 4 2.736604E+02 8.963908E+01 1.723872E+00 2.736549E+02 + 1.640003E+01 6.000000E+01 5 3.408386E+02 8.974288E+01 1.529532E+00 3.408352E+02 + 1.640003E+01 6.000000E+01 6 2.269384E+02 -1.627640E-02 2.269384E+02 -6.446794E-02 + 1.640003E+01 9.000000E+01 1 4.443601E-06 -9.005586E+01 -4.332325E-09 -4.443599E-06 + 1.640003E+01 9.000000E+01 2 9.021398E+01 8.963892E+01 5.685329E-01 9.021219E+01 + 1.640003E+01 9.000000E+01 3 1.477919E+02 1.043959E+00 1.477673E+02 2.692695E+00 + 1.640003E+01 9.000000E+01 4 3.240478E+02 8.964249E+01 2.021979E+00 3.240415E+02 + 1.640003E+01 9.000000E+01 5 1.900700E-04 -8.993105E+01 2.287292E-07 -1.900699E-04 + 1.640003E+01 9.000000E+01 6 1.977098E-05 1.799893E+02 -1.977098E-05 3.697572E-09 + 1.650003E+01 0.000000E+00 1 8.008446E+01 8.974548E+01 3.557478E-01 8.008366E+01 + 1.650003E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.650003E+01 0.000000E+00 3 1.396676E+02 9.959418E-01 1.396465E+02 2.427645E+00 + 1.650003E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.650003E+01 0.000000E+00 5 6.536002E+02 8.974541E+01 2.904176E+00 6.535938E+02 + 1.650003E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.650003E+01 3.000000E+01 1 7.027889E+01 8.974587E+01 3.117142E-01 7.027820E+01 + 1.650003E+01 3.000000E+01 2 4.286112E+01 8.964629E+01 2.645930E-01 4.286031E+01 + 1.650003E+01 3.000000E+01 3 1.418136E+02 1.004334E+00 1.417918E+02 2.485714E+00 + 1.650003E+01 3.000000E+01 4 1.490375E+02 8.963873E+01 9.397214E-01 1.490346E+02 + 1.650003E+01 3.000000E+01 5 5.737659E+02 8.974589E+01 2.544692E+00 5.737603E+02 + 1.650003E+01 3.000000E+01 6 2.170004E+02 -1.587954E-02 2.170004E+02 -6.014171E-02 + 1.650003E+01 6.000000E+01 1 4.166819E+01 8.974660E+01 1.842842E-01 4.166778E+01 + 1.650003E+01 6.000000E+01 2 7.646296E+01 8.964584E+01 4.726377E-01 7.646150E+01 + 1.650003E+01 6.000000E+01 3 1.462129E+02 1.021221E+00 1.461897E+02 2.605911E+00 + 1.650003E+01 6.000000E+01 4 2.715097E+02 8.964576E+01 1.678620E+00 2.715045E+02 + 1.650003E+01 6.000000E+01 5 3.402256E+02 8.974664E+01 1.504421E+00 3.402223E+02 + 1.650003E+01 6.000000E+01 6 2.236460E+02 -1.571510E-02 2.236460E+02 -6.134169E-02 + 1.650003E+01 9.000000E+01 1 4.413116E-06 -9.005762E+01 -4.437728E-09 -4.413114E-06 + 1.650003E+01 9.000000E+01 2 8.960568E+01 8.964561E+01 5.542263E-01 8.960397E+01 + 1.650003E+01 9.000000E+01 3 1.484664E+02 1.029708E+00 1.484424E+02 2.668064E+00 + 1.650003E+01 9.000000E+01 4 3.213871E+02 8.964908E+01 1.968395E+00 3.213810E+02 + 1.650003E+01 9.000000E+01 5 1.890061E-04 -8.993267E+01 2.220995E-07 -1.890059E-04 + 1.650003E+01 9.000000E+01 6 1.947877E-05 1.799897E+02 -1.947877E-05 3.518819E-09 + 1.660003E+01 0.000000E+00 1 7.961937E+01 8.974923E+01 3.484754E-01 7.961861E+01 + 1.660003E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.660003E+01 0.000000E+00 3 1.404284E+02 9.830716E-01 1.404077E+02 2.409329E+00 + 1.660003E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.660003E+01 0.000000E+00 5 6.528055E+02 8.974917E+01 2.857936E+00 6.527993E+02 + 1.660003E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.660003E+01 3.000000E+01 1 6.985648E+01 8.974960E+01 3.052970E-01 6.985582E+01 + 1.660003E+01 3.000000E+01 2 4.260384E+01 8.965277E+01 2.581891E-01 4.260305E+01 + 1.660003E+01 3.000000E+01 3 1.425518E+02 9.911868E-01 1.425305E+02 2.465948E+00 + 1.660003E+01 3.000000E+01 4 1.479819E+02 8.964544E+01 9.157410E-01 1.479791E+02 + 1.660003E+01 3.000000E+01 5 5.729396E+02 8.974961E+01 2.503804E+00 5.729341E+02 + 1.660003E+01 3.000000E+01 6 2.139779E+02 -1.533474E-02 2.139779E+02 -5.726939E-02 + 1.660003E+01 6.000000E+01 1 4.140081E+01 8.975029E+01 1.804350E-01 4.140041E+01 + 1.660003E+01 6.000000E+01 2 7.596867E+01 8.965234E+01 4.609694E-01 7.596728E+01 + 1.660003E+01 6.000000E+01 3 1.469029E+02 1.007521E+00 1.468802E+02 2.583089E+00 + 1.660003E+01 6.000000E+01 4 2.693941E+02 8.965227E+01 1.634977E+00 2.693891E+02 + 1.660003E+01 6.000000E+01 5 3.395906E+02 8.975034E+01 1.479773E+00 3.395873E+02 + 1.660003E+01 6.000000E+01 6 2.204283E+02 -1.517843E-02 2.204282E+02 -5.839444E-02 + 1.660003E+01 9.000000E+01 1 4.383061E-06 -9.005925E+01 -4.532602E-09 -4.383058E-06 + 1.660003E+01 9.000000E+01 2 8.900592E+01 8.965212E+01 5.404093E-01 8.900428E+01 + 1.660003E+01 9.000000E+01 3 1.491305E+02 1.015738E+00 1.491071E+02 2.643642E+00 + 1.660003E+01 9.000000E+01 4 3.187715E+02 8.965548E+01 1.916744E+00 3.187658E+02 + 1.660003E+01 9.000000E+01 5 1.879531E-04 -8.993424E+01 2.157135E-07 -1.879529E-04 + 1.660003E+01 9.000000E+01 6 1.919333E-05 1.799900E+02 -1.919333E-05 3.350276E-09 + 1.670003E+01 0.000000E+00 1 7.915928E+01 8.975289E+01 3.413980E-01 7.915855E+01 + 1.670003E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.670003E+01 0.000000E+00 3 1.411773E+02 9.704314E-01 1.411570E+02 2.391037E+00 + 1.670003E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.670003E+01 0.000000E+00 5 6.519617E+02 8.975283E+01 2.812466E+00 6.519557E+02 + 1.670003E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.670003E+01 3.000000E+01 1 6.943875E+01 8.975324E+01 2.990534E-01 6.943811E+01 + 1.670003E+01 3.000000E+01 2 4.234944E+01 8.965907E+01 2.519954E-01 4.234869E+01 + 1.670003E+01 3.000000E+01 3 1.432779E+02 9.782935E-01 1.432570E+02 2.446272E+00 + 1.670003E+01 3.000000E+01 4 1.469415E+02 8.965195E+01 8.925918E-01 1.469388E+02 + 1.670003E+01 3.000000E+01 5 5.720788E+02 8.975326E+01 2.463653E+00 5.720735E+02 + 1.670003E+01 3.000000E+01 6 2.110209E+02 -1.481364E-02 2.110209E+02 -5.455877E-02 + 1.670003E+01 6.000000E+01 1 4.113696E+01 8.975391E+01 1.766920E-01 4.113658E+01 + 1.670003E+01 6.000000E+01 2 7.548108E+01 8.965865E+01 4.496918E-01 7.547974E+01 + 1.670003E+01 6.000000E+01 3 1.475816E+02 9.941030E-01 1.475593E+02 2.560466E+00 + 1.670003E+01 6.000000E+01 4 2.673114E+02 8.965858E+01 1.592865E+00 2.673066E+02 + 1.670003E+01 6.000000E+01 5 3.389381E+02 8.975394E+01 1.455589E+00 3.389350E+02 + 1.670003E+01 6.000000E+01 6 2.172823E+02 -1.466502E-02 2.172823E+02 -5.561403E-02 + 1.670003E+01 9.000000E+01 1 4.353434E-06 -9.006077E+01 -4.617680E-09 -4.353431E-06 + 1.670003E+01 9.000000E+01 2 8.841442E+01 8.965845E+01 5.270610E-01 8.841285E+01 + 1.670003E+01 9.000000E+01 3 1.497841E+02 1.002045E+00 1.497612E+02 2.619438E+00 + 1.670003E+01 9.000000E+01 4 3.162005E+02 8.966171E+01 1.866930E+00 3.161950E+02 + 1.670003E+01 9.000000E+01 5 1.869116E-04 -8.993577E+01 2.095604E-07 -1.869115E-04 + 1.670003E+01 9.000000E+01 6 1.891439E-05 1.799903E+02 -1.891439E-05 3.191249E-09 + 1.680003E+01 0.000000E+00 1 7.870379E+01 8.975648E+01 3.345112E-01 7.870308E+01 + 1.680003E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.680003E+01 0.000000E+00 3 1.419147E+02 9.580268E-01 1.418949E+02 2.372806E+00 + 1.680003E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.680003E+01 0.000000E+00 5 6.510717E+02 8.975642E+01 2.767807E+00 6.510659E+02 + 1.680003E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.680003E+01 3.000000E+01 1 6.902589E+01 8.975681E+01 2.929785E-01 6.902527E+01 + 1.680003E+01 3.000000E+01 2 4.209784E+01 8.966518E+01 2.460019E-01 4.209712E+01 + 1.680003E+01 3.000000E+01 3 1.439933E+02 9.656351E-01 1.439729E+02 2.426679E+00 + 1.680003E+01 3.000000E+01 4 1.459150E+02 8.965829E+01 8.702304E-01 1.459124E+02 + 1.680003E+01 3.000000E+01 5 5.711770E+02 8.975683E+01 2.424177E+00 5.711719E+02 + 1.680003E+01 3.000000E+01 6 2.081268E+02 -1.431505E-02 2.081268E+02 -5.199940E-02 + 1.680003E+01 6.000000E+01 1 4.087637E+01 8.975744E+01 1.730514E-01 4.087600E+01 + 1.680003E+01 6.000000E+01 2 7.499953E+01 8.966479E+01 4.387893E-01 7.499825E+01 + 1.680003E+01 6.000000E+01 3 1.482493E+02 9.809484E-01 1.482275E+02 2.538019E+00 + 1.680003E+01 6.000000E+01 4 2.652624E+02 8.966473E+01 1.552231E+00 2.652578E+02 + 1.680003E+01 6.000000E+01 5 3.382650E+02 8.975747E+01 1.431869E+00 3.382619E+02 + 1.680003E+01 6.000000E+01 6 2.142068E+02 -1.417367E-02 2.142068E+02 -5.298986E-02 + 1.680003E+01 9.000000E+01 1 4.324208E-06 -9.006219E+01 -4.693642E-09 -4.324205E-06 + 1.680003E+01 9.000000E+01 2 8.783129E+01 8.966460E+01 5.141620E-01 8.782979E+01 + 1.680003E+01 9.000000E+01 3 1.504268E+02 9.886392E-01 1.504044E+02 2.595487E+00 + 1.680003E+01 9.000000E+01 4 3.136725E+02 8.966776E+01 1.818861E+00 3.136672E+02 + 1.680003E+01 9.000000E+01 5 1.858807E-04 -8.993723E+01 2.036307E-07 -1.858806E-04 + 1.680003E+01 9.000000E+01 6 1.864179E-05 1.799906E+02 -1.864179E-05 3.041129E-09 + 1.690003E+01 0.000000E+00 1 7.825299E+01 8.975999E+01 3.278065E-01 7.825230E+01 + 1.690003E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.690003E+01 0.000000E+00 3 1.426401E+02 9.458489E-01 1.426206E+02 2.354621E+00 + 1.690003E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.690003E+01 0.000000E+00 5 6.501360E+02 8.975993E+01 2.724063E+00 6.501302E+02 + 1.690003E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.690003E+01 3.000000E+01 1 6.861776E+01 8.976030E+01 2.870665E-01 6.861716E+01 + 1.690003E+01 3.000000E+01 2 4.184914E+01 8.967113E+01 2.402019E-01 4.184845E+01 + 1.690003E+01 3.000000E+01 3 1.446970E+02 9.532170E-01 1.446770E+02 2.407180E+00 + 1.690003E+01 3.000000E+01 4 1.449025E+02 8.966444E+01 8.486223E-01 1.449000E+02 + 1.690003E+01 3.000000E+01 5 5.702377E+02 8.976031E+01 2.385506E+00 5.702327E+02 + 1.690003E+01 3.000000E+01 6 2.052938E+02 -1.383781E-02 2.052938E+02 -4.958160E-02 + 1.690003E+01 6.000000E+01 1 4.061907E+01 8.976090E+01 1.695097E-01 4.061872E+01 + 1.690003E+01 6.000000E+01 2 7.452441E+01 8.967075E+01 4.282461E-01 7.452318E+01 + 1.690003E+01 6.000000E+01 3 1.489065E+02 9.680391E-01 1.488852E+02 2.515725E+00 + 1.690003E+01 6.000000E+01 4 2.632462E+02 8.967069E+01 1.512990E+00 2.632419E+02 + 1.690003E+01 6.000000E+01 5 3.375758E+02 8.976092E+01 1.408611E+00 3.375729E+02 + 1.690003E+01 6.000000E+01 6 2.111987E+02 -1.370325E-02 2.111987E+02 -5.051173E-02 + 1.690003E+01 9.000000E+01 1 4.295412E-06 -9.006351E+01 -4.761101E-09 -4.295409E-06 + 1.690003E+01 9.000000E+01 2 8.725597E+01 8.967057E+01 5.016919E-01 8.725453E+01 + 1.690003E+01 9.000000E+01 3 1.510592E+02 9.754964E-01 1.510374E+02 2.571754E+00 + 1.690003E+01 9.000000E+01 4 3.111864E+02 8.967365E+01 1.772481E+00 3.111813E+02 + 1.690003E+01 9.000000E+01 5 1.848607E-04 -8.993866E+01 1.979136E-07 -1.848606E-04 + 1.690003E+01 9.000000E+01 6 1.837537E-05 1.799910E+02 -1.837537E-05 2.899343E-09 + 1.700003E+01 0.000000E+00 1 7.780700E+01 8.976341E+01 3.212808E-01 7.780634E+01 + 1.700003E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.700003E+01 0.000000E+00 3 1.433537E+02 9.338885E-01 1.433346E+02 2.336479E+00 + 1.700003E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.700003E+01 0.000000E+00 5 6.491511E+02 8.976337E+01 2.681012E+00 6.491456E+02 + 1.700003E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.700003E+01 3.000000E+01 1 6.821416E+01 8.976371E+01 2.813120E-01 6.821358E+01 + 1.700003E+01 3.000000E+01 2 4.160308E+01 8.967693E+01 2.345867E-01 4.160242E+01 + 1.700003E+01 3.000000E+01 3 1.453886E+02 9.410301E-01 1.453690E+02 2.387765E+00 + 1.700003E+01 3.000000E+01 4 1.439045E+02 8.967043E+01 8.277432E-01 1.439021E+02 + 1.700003E+01 3.000000E+01 5 5.692606E+02 8.976373E+01 2.347507E+00 5.692558E+02 + 1.700003E+01 3.000000E+01 6 2.025197E+02 -1.338084E-02 2.025197E+02 -4.729638E-02 + 1.700003E+01 6.000000E+01 1 4.036497E+01 8.976428E+01 1.660650E-01 4.036462E+01 + 1.700003E+01 6.000000E+01 2 7.405534E+01 8.967656E+01 4.180475E-01 7.405415E+01 + 1.700003E+01 6.000000E+01 3 1.495526E+02 9.553865E-01 1.495318E+02 2.493621E+00 + 1.700003E+01 6.000000E+01 4 2.612618E+02 8.967651E+01 1.475102E+00 2.612577E+02 + 1.700003E+01 6.000000E+01 5 3.368707E+02 8.976430E+01 1.385798E+00 3.368678E+02 + 1.700003E+01 6.000000E+01 6 2.082564E+02 -1.325271E-02 2.082564E+02 -4.817042E-02 + 1.700003E+01 9.000000E+01 1 4.267002E-06 -9.006474E+01 -4.820654E-09 -4.266999E-06 + 1.700003E+01 9.000000E+01 2 8.668875E+01 8.967638E+01 4.896342E-01 8.668737E+01 + 1.700003E+01 9.000000E+01 3 1.516819E+02 9.626111E-01 1.516604E+02 2.548246E+00 + 1.700003E+01 9.000000E+01 4 3.087421E+02 8.967937E+01 1.727703E+00 3.087373E+02 + 1.700003E+01 9.000000E+01 5 1.838514E-04 -8.994004E+01 1.924002E-07 -1.838513E-04 + 1.700003E+01 9.000000E+01 6 1.811487E-05 1.799913E+02 -1.811487E-05 2.765362E-09 + 1.710003E+01 0.000000E+00 1 7.736562E+01 8.976677E+01 3.149246E-01 7.736497E+01 + 1.710003E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.710003E+01 0.000000E+00 3 1.440564E+02 9.221410E-01 1.440378E+02 2.318401E+00 + 1.710003E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.710003E+01 0.000000E+00 5 6.481404E+02 8.976672E+01 2.638818E+00 6.481351E+02 + 1.710003E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.710003E+01 3.000000E+01 1 6.781467E+01 8.976705E+01 2.757103E-01 6.781411E+01 + 1.710003E+01 3.000000E+01 2 4.135986E+01 8.968256E+01 2.291498E-01 4.135922E+01 + 1.710003E+01 3.000000E+01 3 1.460704E+02 9.290562E-01 1.460512E+02 2.368441E+00 + 1.710003E+01 3.000000E+01 4 1.429198E+02 8.967625E+01 8.075590E-01 1.429175E+02 + 1.710003E+01 3.000000E+01 5 5.682650E+02 8.976707E+01 2.310235E+00 5.682603E+02 + 1.710003E+01 3.000000E+01 6 1.998033E+02 -1.294307E-02 1.998033E+02 -4.513539E-02 + 1.710003E+01 6.000000E+01 1 4.011433E+01 8.976760E+01 1.627119E-01 4.011400E+01 + 1.710003E+01 6.000000E+01 2 7.359230E+01 8.968221E+01 4.081792E-01 7.359117E+01 + 1.710003E+01 6.000000E+01 3 1.501896E+02 9.429771E-01 1.501692E+02 2.471717E+00 + 1.710003E+01 6.000000E+01 4 2.593072E+02 8.968215E+01 1.438494E+00 2.593032E+02 + 1.710003E+01 6.000000E+01 5 3.361512E+02 8.976762E+01 1.363393E+00 3.361484E+02 + 1.710003E+01 6.000000E+01 6 2.053779E+02 -1.282100E-02 2.053779E+02 -4.595713E-02 + 1.710003E+01 9.000000E+01 1 4.238977E-06 -9.006586E+01 -4.872835E-09 -4.238974E-06 + 1.710003E+01 9.000000E+01 2 8.612893E+01 8.968204E+01 4.779708E-01 8.612760E+01 + 1.710003E+01 9.000000E+01 3 1.522950E+02 9.499663E-01 1.522740E+02 2.524941E+00 + 1.710003E+01 9.000000E+01 4 3.063377E+02 8.968494E+01 1.684460E+00 3.063331E+02 + 1.710003E+01 9.000000E+01 5 1.828522E-04 -8.994138E+01 1.870827E-07 -1.828521E-04 + 1.710003E+01 9.000000E+01 6 1.786016E-05 1.799915E+02 -1.786016E-05 2.638687E-09 + 1.720003E+01 0.000000E+00 1 7.692882E+01 8.977006E+01 3.087362E-01 7.692820E+01 + 1.720003E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.720003E+01 0.000000E+00 3 1.447481E+02 9.106072E-01 1.447298E+02 2.300398E+00 + 1.720003E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.720003E+01 0.000000E+00 5 6.470827E+02 8.977002E+01 2.597396E+00 6.470775E+02 + 1.720003E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.720003E+01 3.000000E+01 1 6.742007E+01 8.977033E+01 2.702556E-01 6.741953E+01 + 1.720003E+01 3.000000E+01 2 4.111934E+01 8.968804E+01 2.238836E-01 4.111873E+01 + 1.720003E+01 3.000000E+01 3 1.467415E+02 9.173130E-01 1.467227E+02 2.349250E+00 + 1.720003E+01 3.000000E+01 4 1.419483E+02 8.968192E+01 7.880372E-01 1.419461E+02 + 1.720003E+01 3.000000E+01 5 5.672308E+02 8.977034E+01 2.273669E+00 5.672262E+02 + 1.720003E+01 3.000000E+01 6 1.971432E+02 -1.252353E-02 1.971432E+02 -4.309093E-02 + 1.720003E+01 6.000000E+01 1 3.986652E+01 8.977084E+01 1.594489E-01 3.986620E+01 + 1.720003E+01 6.000000E+01 2 7.313503E+01 8.968771E+01 3.986283E-01 7.313394E+01 + 1.720003E+01 6.000000E+01 3 1.508159E+02 9.308029E-01 1.507961E+02 2.449984E+00 + 1.720003E+01 6.000000E+01 4 2.573831E+02 8.968765E+01 1.403127E+00 2.573793E+02 + 1.720003E+01 6.000000E+01 5 3.354142E+02 8.977086E+01 1.341441E+00 3.354116E+02 + 1.720003E+01 6.000000E+01 6 2.025613E+02 -1.240717E-02 2.025613E+02 -4.386384E-02 + 1.720003E+01 9.000000E+01 1 4.211352E-06 -9.006691E+01 -4.918130E-09 -4.211350E-06 + 1.720003E+01 9.000000E+01 2 8.557645E+01 8.968754E+01 4.666883E-01 8.557518E+01 + 1.720003E+01 9.000000E+01 3 1.528981E+02 9.375727E-01 1.528776E+02 2.501872E+00 + 1.720003E+01 9.000000E+01 4 3.039721E+02 8.969037E+01 1.642692E+00 3.039677E+02 + 1.720003E+01 9.000000E+01 5 1.818636E-04 -8.994268E+01 1.819528E-07 -1.818635E-04 + 1.720003E+01 9.000000E+01 6 1.761103E-05 1.799918E+02 -1.761103E-05 2.518862E-09 + 1.730003E+01 0.000000E+00 1 7.649648E+01 8.977328E+01 3.027084E-01 7.649587E+01 + 1.730003E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.730003E+01 0.000000E+00 3 1.454297E+02 8.992753E-01 1.454118E+02 2.282471E+00 + 1.730003E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.730003E+01 0.000000E+00 5 6.459941E+02 8.977323E+01 2.556705E+00 6.459890E+02 + 1.730003E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.730003E+01 3.000000E+01 1 6.702960E+01 8.977353E+01 2.649444E-01 6.702908E+01 + 1.730003E+01 3.000000E+01 2 4.088143E+01 8.969337E+01 2.187814E-01 4.088085E+01 + 1.730003E+01 3.000000E+01 3 1.474021E+02 9.057806E-01 1.473837E+02 2.330162E+00 + 1.730003E+01 3.000000E+01 4 1.409897E+02 8.968742E+01 7.691571E-01 1.409876E+02 + 1.730003E+01 3.000000E+01 5 5.661701E+02 8.977354E+01 2.237766E+00 5.661657E+02 + 1.730003E+01 3.000000E+01 6 1.945372E+02 -1.212130E-02 1.945372E+02 -4.115565E-02 + 1.730003E+01 6.000000E+01 1 3.962185E+01 8.977402E+01 1.562728E-01 3.962154E+01 + 1.730003E+01 6.000000E+01 2 7.268350E+01 8.969305E+01 3.893808E-01 7.268246E+01 + 1.730003E+01 6.000000E+01 3 1.514333E+02 9.188576E-01 1.514138E+02 2.428445E+00 + 1.730003E+01 6.000000E+01 4 2.554887E+02 8.969300E+01 1.368935E+00 2.554850E+02 + 1.730003E+01 6.000000E+01 5 3.346673E+02 8.977402E+01 1.319904E+00 3.346647E+02 + 1.730003E+01 6.000000E+01 6 1.998048E+02 -1.201034E-02 1.998048E+02 -4.188307E-02 + 1.730003E+01 9.000000E+01 1 4.184083E-06 -9.006788E+01 -4.957047E-09 -4.184080E-06 + 1.730003E+01 9.000000E+01 2 8.503168E+01 8.969289E+01 4.557677E-01 8.503046E+01 + 1.730003E+01 9.000000E+01 3 1.534927E+02 9.254283E-01 1.534726E+02 2.479070E+00 + 1.730003E+01 9.000000E+01 4 3.016447E+02 8.969564E+01 1.602325E+00 3.016405E+02 + 1.730003E+01 9.000000E+01 5 1.808851E-04 -8.994393E+01 1.770024E-07 -1.808850E-04 + 1.730003E+01 9.000000E+01 6 1.736735E-05 1.799921E+02 -1.736735E-05 2.405464E-09 + 1.740003E+01 0.000000E+00 1 7.606857E+01 8.977642E+01 2.968370E-01 7.606799E+01 + 1.740003E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.740003E+01 0.000000E+00 3 1.461000E+02 8.881522E-01 1.460824E+02 2.264631E+00 + 1.740003E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.740003E+01 0.000000E+00 5 6.448622E+02 8.977638E+01 2.516809E+00 6.448573E+02 + 1.740003E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.740003E+01 3.000000E+01 1 6.664342E+01 8.977666E+01 2.597717E-01 6.664291E+01 + 1.740003E+01 3.000000E+01 2 4.064622E+01 8.969857E+01 2.138377E-01 4.064566E+01 + 1.740003E+01 3.000000E+01 3 1.480520E+02 8.944587E-01 1.480340E+02 2.311183E+00 + 1.740003E+01 3.000000E+01 4 1.400447E+02 8.969279E+01 7.508884E-01 1.400427E+02 + 1.740003E+01 3.000000E+01 5 5.650781E+02 8.977668E+01 2.202544E+00 5.650739E+02 + 1.740003E+01 3.000000E+01 6 1.919844E+02 -1.173553E-02 1.919844E+02 -3.932295E-02 + 1.740003E+01 6.000000E+01 1 3.938031E+01 8.977714E+01 1.531806E-01 3.938001E+01 + 1.740003E+01 6.000000E+01 2 7.223764E+01 8.969826E+01 3.804266E-01 7.223664E+01 + 1.740003E+01 6.000000E+01 3 1.520408E+02 9.071378E-01 1.520217E+02 2.407091E+00 + 1.740003E+01 6.000000E+01 4 2.536234E+02 8.969821E+01 1.335878E+00 2.536199E+02 + 1.740003E+01 6.000000E+01 5 3.339070E+02 8.977714E+01 1.298781E+00 3.339045E+02 + 1.740003E+01 6.000000E+01 6 1.971064E+02 -1.162970E-02 1.971064E+02 -4.000797E-02 + 1.740003E+01 9.000000E+01 1 4.157188E-06 -9.006878E+01 -4.990004E-09 -4.157185E-06 + 1.740003E+01 9.000000E+01 2 8.449390E+01 8.969811E+01 4.451937E-01 8.449272E+01 + 1.740003E+01 9.000000E+01 3 1.540770E+02 9.135116E-01 1.540574E+02 2.456466E+00 + 1.740003E+01 9.000000E+01 4 2.993548E+02 8.970079E+01 1.563310E+00 2.993507E+02 + 1.740003E+01 9.000000E+01 5 1.799171E-04 -8.994516E+01 1.722229E-07 -1.799170E-04 + 1.740003E+01 9.000000E+01 6 1.712890E-05 1.799923E+02 -1.712890E-05 2.298087E-09 + 1.750003E+01 0.000000E+00 1 7.564523E+01 8.977950E+01 2.911168E-01 7.564468E+01 + 1.750003E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.750003E+01 0.000000E+00 3 1.467605E+02 8.772206E-01 1.467433E+02 2.246873E+00 + 1.750003E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.750003E+01 0.000000E+00 5 6.437031E+02 8.977946E+01 2.477639E+00 6.436983E+02 + 1.750003E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.750003E+01 3.000000E+01 1 6.626160E+01 8.977974E+01 2.547330E-01 6.626112E+01 + 1.750003E+01 3.000000E+01 2 4.041354E+01 8.970363E+01 2.090445E-01 4.041300E+01 + 1.750003E+01 3.000000E+01 3 1.486924E+02 8.833405E-01 1.486747E+02 2.292330E+00 + 1.750003E+01 3.000000E+01 4 1.391121E+02 8.969801E+01 7.332051E-01 1.391102E+02 + 1.750003E+01 3.000000E+01 5 5.639617E+02 8.977975E+01 2.167981E+00 5.639575E+02 + 1.750003E+01 3.000000E+01 6 1.894836E+02 -1.136537E-02 1.894836E+02 -3.758655E-02 + 1.750003E+01 6.000000E+01 1 3.914173E+01 8.978018E+01 1.501700E-01 3.914144E+01 + 1.750003E+01 6.000000E+01 2 7.179738E+01 8.970333E+01 3.717521E-01 7.179642E+01 + 1.750003E+01 6.000000E+01 3 1.526384E+02 8.956429E-01 1.526198E+02 2.385934E+00 + 1.750003E+01 6.000000E+01 4 2.517860E+02 8.970329E+01 1.303899E+00 2.517826E+02 + 1.750003E+01 6.000000E+01 5 3.331340E+02 8.978019E+01 1.278064E+00 3.331315E+02 + 1.750003E+01 6.000000E+01 6 1.944650E+02 -1.126439E-02 1.944650E+02 -3.823193E-02 + 1.750003E+01 9.000000E+01 1 4.130654E-06 -9.006960E+01 -5.017452E-09 -4.130651E-06 + 1.750003E+01 9.000000E+01 2 8.396326E+01 8.970319E+01 4.349561E-01 8.396214E+01 + 1.750003E+01 9.000000E+01 3 1.546528E+02 9.018231E-01 1.546337E+02 2.434101E+00 + 1.750003E+01 9.000000E+01 4 2.971018E+02 8.970580E+01 1.525586E+00 2.970979E+02 + 1.750003E+01 9.000000E+01 5 1.789581E-04 -8.994634E+01 1.676095E-07 -1.789580E-04 + 1.750003E+01 9.000000E+01 6 1.689559E-05 1.799926E+02 -1.689559E-05 2.196375E-09 + 1.760003E+01 0.000000E+00 1 7.522603E+01 8.978252E+01 2.855424E-01 7.522549E+01 + 1.760003E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.760003E+01 0.000000E+00 3 1.474105E+02 8.664895E-01 1.473936E+02 2.229218E+00 + 1.760003E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.760003E+01 0.000000E+00 5 6.425116E+02 8.978249E+01 2.439182E+00 6.425070E+02 + 1.760003E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.760003E+01 3.000000E+01 1 6.588400E+01 8.978275E+01 2.498240E-01 6.588353E+01 + 1.760003E+01 3.000000E+01 2 4.018336E+01 8.970856E+01 2.043981E-01 4.018284E+01 + 1.760003E+01 3.000000E+01 3 1.493228E+02 8.724263E-01 1.493055E+02 2.273607E+00 + 1.760003E+01 3.000000E+01 4 1.381915E+02 8.970310E+01 7.160906E-01 1.381896E+02 + 1.760003E+01 3.000000E+01 5 5.628223E+02 8.978275E+01 2.134067E+00 5.628182E+02 + 1.760003E+01 3.000000E+01 6 1.870322E+02 -1.101012E-02 1.870322E+02 -3.594062E-02 + 1.760003E+01 6.000000E+01 1 3.890599E+01 8.978316E+01 1.472380E-01 3.890571E+01 + 1.760003E+01 6.000000E+01 2 7.136261E+01 8.970827E+01 3.633476E-01 7.136169E+01 + 1.760003E+01 6.000000E+01 3 1.532270E+02 8.843609E-01 1.532087E+02 2.364966E+00 + 1.760003E+01 6.000000E+01 4 2.499757E+02 8.970823E+01 1.272962E+00 2.499725E+02 + 1.760003E+01 6.000000E+01 5 3.323467E+02 8.978316E+01 1.257752E+00 3.323443E+02 + 1.760003E+01 6.000000E+01 6 1.918781E+02 -1.091368E-02 1.918781E+02 -3.654889E-02 + 1.760003E+01 9.000000E+01 1 4.104470E-06 -9.007036E+01 -5.039729E-09 -4.104467E-06 + 1.760003E+01 9.000000E+01 2 8.343951E+01 8.970814E+01 4.250399E-01 8.343843E+01 + 1.760003E+01 9.000000E+01 3 1.552197E+02 8.903571E-01 1.552009E+02 2.411964E+00 + 1.760003E+01 9.000000E+01 4 2.948824E+02 8.971067E+01 1.489102E+00 2.948787E+02 + 1.760003E+01 9.000000E+01 5 1.780100E-04 -8.994749E+01 1.631530E-07 -1.780099E-04 + 1.760003E+01 9.000000E+01 6 1.666724E-05 1.799928E+02 -1.666724E-05 2.099976E-09 + 1.770003E+01 0.000000E+00 1 7.481139E+01 8.978548E+01 2.801100E-01 7.481087E+01 + 1.770003E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.770003E+01 0.000000E+00 3 1.480506E+02 8.559459E-01 1.480341E+02 2.211657E+00 + 1.770003E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.770003E+01 0.000000E+00 5 6.412889E+02 8.978545E+01 2.401450E+00 6.412844E+02 + 1.770003E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.770003E+01 3.000000E+01 1 6.551038E+01 8.978568E+01 2.450408E-01 6.550993E+01 + 1.770003E+01 3.000000E+01 2 3.995592E+01 8.971336E+01 1.998918E-01 3.995542E+01 + 1.770003E+01 3.000000E+01 3 1.499435E+02 8.617072E-01 1.499266E+02 2.255009E+00 + 1.770003E+01 3.000000E+01 4 1.372833E+02 8.970805E+01 6.995165E-01 1.372816E+02 + 1.770003E+01 3.000000E+01 5 5.616598E+02 8.978569E+01 2.100796E+00 5.616559E+02 + 1.770003E+01 3.000000E+01 6 1.846298E+02 -1.066901E-02 1.846298E+02 -3.437980E-02 + 1.770003E+01 6.000000E+01 1 3.867310E+01 8.978609E+01 1.443823E-01 3.867283E+01 + 1.770003E+01 6.000000E+01 2 7.093285E+01 8.971309E+01 3.552011E-01 7.093196E+01 + 1.770003E+01 6.000000E+01 3 1.538070E+02 8.732904E-01 1.537892E+02 2.344204E+00 + 1.770003E+01 6.000000E+01 4 2.481922E+02 8.971304E+01 1.243022E+00 2.481891E+02 + 1.770003E+01 6.000000E+01 5 3.315513E+02 8.978609E+01 1.237825E+00 3.315490E+02 + 1.770003E+01 6.000000E+01 6 1.893453E+02 -1.057689E-02 1.893453E+02 -3.495344E-02 + 1.770003E+01 9.000000E+01 1 4.078627E-06 -9.007104E+01 -5.057224E-09 -4.078624E-06 + 1.770003E+01 9.000000E+01 2 8.292255E+01 8.971296E+01 4.154316E-01 8.292151E+01 + 1.770003E+01 9.000000E+01 3 1.557786E+02 8.791062E-01 1.557602E+02 2.390063E+00 + 1.770003E+01 9.000000E+01 4 2.926987E+02 8.971542E+01 1.453803E+00 2.926951E+02 + 1.770003E+01 9.000000E+01 5 1.770701E-04 -8.994860E+01 1.588489E-07 -1.770701E-04 + 1.770003E+01 9.000000E+01 6 1.644369E-05 1.799930E+02 -1.644369E-05 2.008577E-09 + 1.780003E+01 0.000000E+00 1 7.440078E+01 8.978837E+01 2.748142E-01 7.440027E+01 + 1.780003E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.780003E+01 0.000000E+00 3 1.486817E+02 8.455824E-01 1.486656E+02 2.194195E+00 + 1.780003E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.780003E+01 0.000000E+00 5 6.400364E+02 8.978835E+01 2.364407E+00 6.400320E+02 + 1.780003E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.780003E+01 3.000000E+01 1 6.514104E+01 8.978857E+01 2.403791E-01 6.514060E+01 + 1.780003E+01 3.000000E+01 2 3.973069E+01 8.971804E+01 1.955202E-01 3.973021E+01 + 1.780003E+01 3.000000E+01 3 1.505547E+02 8.511811E-01 1.505381E+02 2.236545E+00 + 1.780003E+01 3.000000E+01 4 1.363872E+02 8.971288E+01 6.834597E-01 1.363855E+02 + 1.780003E+01 3.000000E+01 5 5.604759E+02 8.978858E+01 2.068119E+00 5.604720E+02 + 1.780003E+01 3.000000E+01 6 1.822750E+02 -1.034134E-02 1.822750E+02 -3.289888E-02 + 1.780003E+01 6.000000E+01 1 3.844302E+01 8.978896E+01 1.416005E-01 3.844276E+01 + 1.780003E+01 6.000000E+01 2 7.050869E+01 8.971778E+01 3.473049E-01 7.050784E+01 + 1.780003E+01 6.000000E+01 3 1.543772E+02 8.624300E-01 1.543597E+02 2.323635E+00 + 1.780003E+01 6.000000E+01 4 2.464359E+02 8.971774E+01 1.214041E+00 2.464330E+02 + 1.780003E+01 6.000000E+01 5 3.307463E+02 8.978896E+01 1.218282E+00 3.307440E+02 + 1.780003E+01 6.000000E+01 6 1.868641E+02 -1.025334E-02 1.868641E+02 -3.344018E-02 + 1.780003E+01 9.000000E+01 1 4.053125E-06 -9.007167E+01 -5.070256E-09 -4.053122E-06 + 1.780003E+01 9.000000E+01 2 8.241228E+01 8.971765E+01 4.061211E-01 8.241128E+01 + 1.780003E+01 9.000000E+01 3 1.563274E+02 8.680727E-01 1.563095E+02 2.368384E+00 + 1.780003E+01 9.000000E+01 4 2.905500E+02 8.972005E+01 1.419651E+00 2.905465E+02 + 1.780003E+01 9.000000E+01 5 1.761400E-04 -8.994968E+01 1.546902E-07 -1.761399E-04 + 1.780003E+01 9.000000E+01 6 1.622480E-05 1.799932E+02 -1.622480E-05 1.921874E-09 + 1.790003E+01 0.000000E+00 1 7.399467E+01 8.979121E+01 2.696534E-01 7.399419E+01 + 1.790003E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.790003E+01 0.000000E+00 3 1.493023E+02 8.354082E-01 1.492865E+02 2.176844E+00 + 1.790003E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.790003E+01 0.000000E+00 5 6.387642E+02 8.979118E+01 2.328068E+00 6.387599E+02 + 1.790003E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.790003E+01 3.000000E+01 1 6.477534E+01 8.979140E+01 2.358356E-01 6.477492E+01 + 1.790003E+01 3.000000E+01 2 3.950798E+01 8.972260E+01 1.912789E-01 3.950752E+01 + 1.790003E+01 3.000000E+01 3 1.511558E+02 8.408459E-01 1.511395E+02 2.218212E+00 + 1.790003E+01 3.000000E+01 4 1.355029E+02 8.971758E+01 6.679081E-01 1.355012E+02 + 1.790003E+01 3.000000E+01 5 5.592638E+02 8.979140E+01 2.036119E+00 5.592601E+02 + 1.790003E+01 3.000000E+01 6 1.799663E+02 -1.002654E-02 1.799663E+02 -3.149339E-02 + 1.790003E+01 6.000000E+01 1 3.821576E+01 8.979176E+01 1.388902E-01 3.821550E+01 + 1.790003E+01 6.000000E+01 2 7.008968E+01 8.972235E+01 3.396469E-01 7.008885E+01 + 1.790003E+01 6.000000E+01 3 1.549396E+02 8.517636E-01 1.549225E+02 2.303259E+00 + 1.790003E+01 6.000000E+01 4 2.447059E+02 8.972231E+01 1.185986E+00 2.447030E+02 + 1.790003E+01 6.000000E+01 5 3.299292E+02 8.979176E+01 1.199113E+00 3.299270E+02 + 1.790003E+01 6.000000E+01 6 1.844336E+02 -9.942386E-03 1.844336E+02 -3.200428E-02 + 1.790003E+01 9.000000E+01 1 4.027956E-06 -9.007224E+01 -5.079143E-09 -4.027953E-06 + 1.790003E+01 9.000000E+01 2 8.190853E+01 8.972223E+01 3.970944E-01 8.190757E+01 + 1.790003E+01 9.000000E+01 3 1.568689E+02 8.572463E-01 1.568513E+02 2.346948E+00 + 1.790003E+01 9.000000E+01 4 2.884336E+02 8.972456E+01 1.386583E+00 2.884302E+02 + 1.790003E+01 9.000000E+01 5 1.752189E-04 -8.995073E+01 1.506712E-07 -1.752189E-04 + 1.790003E+01 9.000000E+01 6 1.601048E-05 1.799934E+02 -1.601048E-05 1.839592E-09 + 1.800003E+01 0.000000E+00 1 7.359242E+01 8.979398E+01 2.646198E-01 7.359195E+01 + 1.800003E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.800003E+01 0.000000E+00 3 1.499134E+02 8.254050E-01 1.498979E+02 2.159583E+00 + 1.800003E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.800003E+01 0.000000E+00 5 6.374623E+02 8.979396E+01 2.292387E+00 6.374581E+02 + 1.800003E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.800003E+01 3.000000E+01 1 6.441399E+01 8.979417E+01 2.314064E-01 6.441357E+01 + 1.800003E+01 3.000000E+01 2 3.928770E+01 8.972705E+01 1.871628E-01 3.928726E+01 + 1.800003E+01 3.000000E+01 3 1.517487E+02 8.306831E-01 1.517327E+02 2.199999E+00 + 1.800003E+01 3.000000E+01 4 1.346301E+02 8.972217E+01 6.528330E-01 1.346285E+02 + 1.800003E+01 3.000000E+01 5 5.580375E+02 8.979417E+01 2.004682E+00 5.580339E+02 + 1.800003E+01 3.000000E+01 6 1.777027E+02 -9.723916E-03 1.777027E+02 -3.015869E-02 + 1.800003E+01 6.000000E+01 1 3.799120E+01 8.979452E+01 1.362488E-01 3.799096E+01 + 1.800003E+01 6.000000E+01 2 6.967571E+01 8.972681E+01 3.322195E-01 6.967492E+01 + 1.800003E+01 6.000000E+01 3 1.554927E+02 8.412932E-01 1.554759E+02 2.283069E+00 + 1.800003E+01 6.000000E+01 4 2.430007E+02 8.972678E+01 1.158802E+00 2.429979E+02 + 1.800003E+01 6.000000E+01 5 3.291052E+02 8.979451E+01 1.180315E+00 3.291031E+02 + 1.800003E+01 6.000000E+01 6 1.820520E+02 -9.643480E-03 1.820520E+02 -3.064126E-02 + 1.800003E+01 9.000000E+01 1 4.003104E-06 -9.007277E+01 -5.084192E-09 -4.003100E-06 + 1.800003E+01 9.000000E+01 2 8.141106E+01 8.972669E+01 3.883424E-01 8.141014E+01 + 1.800003E+01 9.000000E+01 3 1.574014E+02 8.466154E-01 1.573842E+02 2.325713E+00 + 1.800003E+01 9.000000E+01 4 2.863488E+02 8.972896E+01 1.354571E+00 2.863456E+02 + 1.800003E+01 9.000000E+01 5 1.743079E-04 -8.995175E+01 1.467860E-07 -1.743078E-04 + 1.800003E+01 9.000000E+01 6 1.580057E-05 1.799936E+02 -1.580057E-05 1.761472E-09 + 1.810003E+01 0.000000E+00 1 7.319434E+01 8.979670E+01 2.597115E-01 7.319389E+01 + 1.810003E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.810003E+01 0.000000E+00 3 1.505152E+02 8.155890E-01 1.505000E+02 2.142469E+00 + 1.810003E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.810003E+01 0.000000E+00 5 6.361327E+02 8.979668E+01 2.257386E+00 6.361287E+02 + 1.810003E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.810003E+01 3.000000E+01 1 6.405619E+01 8.979688E+01 2.270879E-01 6.405579E+01 + 1.810003E+01 3.000000E+01 2 3.906975E+01 8.973138E+01 1.831671E-01 3.906932E+01 + 1.810003E+01 3.000000E+01 3 1.523327E+02 8.207114E-01 1.523171E+02 2.181957E+00 + 1.810003E+01 3.000000E+01 4 1.337683E+02 8.972664E+01 6.382182E-01 1.337668E+02 + 1.810003E+01 3.000000E+01 5 5.567880E+02 8.979689E+01 1.973825E+00 5.567845E+02 + 1.810003E+01 3.000000E+01 6 1.754824E+02 -9.432958E-03 1.754824E+02 -2.889074E-02 + 1.810003E+01 6.000000E+01 1 3.776931E+01 8.979722E+01 1.336748E-01 3.776907E+01 + 1.810003E+01 6.000000E+01 2 6.926653E+01 8.973116E+01 3.250135E-01 6.926576E+01 + 1.810003E+01 6.000000E+01 3 1.560380E+02 8.310156E-01 1.560216E+02 2.263090E+00 + 1.810003E+01 6.000000E+01 4 2.413194E+02 8.973112E+01 1.132469E+00 2.413167E+02 + 1.810003E+01 6.000000E+01 5 3.282740E+02 8.979721E+01 1.161875E+00 3.282720E+02 + 1.810003E+01 6.000000E+01 6 1.797184E+02 -9.355979E-03 1.797184E+02 -2.934668E-02 + 1.810003E+01 9.000000E+01 1 3.978574E-06 -9.007323E+01 -5.085662E-09 -3.978570E-06 + 1.810003E+01 9.000000E+01 2 8.091991E+01 8.973104E+01 3.798544E-01 8.091902E+01 + 1.810003E+01 9.000000E+01 3 1.579263E+02 8.361931E-01 1.579095E+02 2.304746E+00 + 1.810003E+01 9.000000E+01 4 2.842980E+02 8.973326E+01 1.323563E+00 2.842949E+02 + 1.810003E+01 9.000000E+01 5 1.734056E-04 -8.995274E+01 1.430287E-07 -1.734055E-04 + 1.810003E+01 9.000000E+01 6 1.559493E-05 1.799938E+02 -1.559493E-05 1.687267E-09 + 1.820003E+01 0.000000E+00 1 7.280035E+01 8.979937E+01 2.549250E-01 7.279990E+01 + 1.820003E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.820003E+01 0.000000E+00 3 1.511089E+02 8.059275E-01 1.510940E+02 2.125441E+00 + 1.820003E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.820003E+01 0.000000E+00 5 6.347894E+02 8.979935E+01 2.223038E+00 6.347855E+02 + 1.820003E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.820003E+01 3.000000E+01 1 6.370239E+01 8.979954E+01 2.228774E-01 6.370200E+01 + 1.820003E+01 3.000000E+01 2 3.885412E+01 8.973561E+01 1.792869E-01 3.885371E+01 + 1.820003E+01 3.000000E+01 3 1.529076E+02 8.109112E-01 1.528923E+02 2.164040E+00 + 1.820003E+01 3.000000E+01 4 1.329179E+02 8.973100E+01 6.240516E-01 1.329165E+02 + 1.820003E+01 3.000000E+01 5 5.555248E+02 8.979955E+01 1.943584E+00 5.555214E+02 + 1.820003E+01 3.000000E+01 6 1.733053E+02 -9.153094E-03 1.733053E+02 -2.768579E-02 + 1.820003E+01 6.000000E+01 1 3.754996E+01 8.979986E+01 1.311652E-01 3.754973E+01 + 1.820003E+01 6.000000E+01 2 6.886234E+01 8.973540E+01 3.180218E-01 6.886160E+01 + 1.820003E+01 6.000000E+01 3 1.565751E+02 8.209197E-01 1.565590E+02 2.243292E+00 + 1.820003E+01 6.000000E+01 4 2.396626E+02 8.973536E+01 1.106960E+00 2.396601E+02 + 1.820003E+01 6.000000E+01 5 3.274324E+02 8.979985E+01 1.143814E+00 3.274304E+02 + 1.820003E+01 6.000000E+01 6 1.774308E+02 -9.079442E-03 1.774308E+02 -2.811678E-02 + 1.820003E+01 9.000000E+01 1 3.954354E-06 -9.007366E+01 -5.083816E-09 -3.954351E-06 + 1.820003E+01 9.000000E+01 2 8.043484E+01 8.973528E+01 3.716185E-01 8.043398E+01 + 1.820003E+01 9.000000E+01 3 1.584439E+02 8.259460E-01 1.584274E+02 2.283965E+00 + 1.820003E+01 9.000000E+01 4 2.822743E+02 8.973744E+01 1.293522E+00 2.822714E+02 + 1.820003E+01 9.000000E+01 5 1.725127E-04 -8.995370E+01 1.393963E-07 -1.725126E-04 + 1.820003E+01 9.000000E+01 6 1.539349E-05 1.799940E+02 -1.539349E-05 1.616758E-09 + 1.830003E+01 0.000000E+00 1 7.241020E+01 8.980198E+01 2.502557E-01 7.240977E+01 + 1.830003E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.830003E+01 0.000000E+00 3 1.516930E+02 7.964388E-01 1.516783E+02 2.108537E+00 + 1.830003E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.830003E+01 0.000000E+00 5 6.334097E+02 8.980196E+01 2.189332E+00 6.334059E+02 + 1.830003E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.830003E+01 3.000000E+01 1 6.335241E+01 8.980215E+01 2.187716E-01 6.335203E+01 + 1.830003E+01 3.000000E+01 2 3.864079E+01 8.973975E+01 1.755189E-01 3.864039E+01 + 1.830003E+01 3.000000E+01 3 1.534740E+02 8.012852E-01 1.534589E+02 2.146273E+00 + 1.830003E+01 3.000000E+01 4 1.320782E+02 8.973524E+01 6.103086E-01 1.320768E+02 + 1.830003E+01 3.000000E+01 5 5.542449E+02 8.980215E+01 1.913880E+00 5.542416E+02 + 1.830003E+01 3.000000E+01 6 1.711694E+02 -8.883815E-03 1.711694E+02 -2.654013E-02 + 1.830003E+01 6.000000E+01 1 3.733328E+01 8.980245E+01 1.287194E-01 3.733306E+01 + 1.830003E+01 6.000000E+01 2 6.846301E+01 8.973953E+01 3.112344E-01 6.846230E+01 + 1.830003E+01 6.000000E+01 3 1.571040E+02 8.110126E-01 1.570883E+02 2.223709E+00 + 1.830003E+01 6.000000E+01 4 2.380298E+02 8.973950E+01 1.082225E+00 2.380274E+02 + 1.830003E+01 6.000000E+01 5 3.265837E+02 8.980244E+01 1.126073E+00 3.265818E+02 + 1.830003E+01 6.000000E+01 6 1.751885E+02 -8.813322E-03 1.751885E+02 -2.694776E-02 + 1.830003E+01 9.000000E+01 1 3.930443E-06 -9.007404E+01 -5.078886E-09 -3.930440E-06 + 1.830003E+01 9.000000E+01 2 7.995577E+01 8.973943E+01 3.636277E-01 7.995495E+01 + 1.830003E+01 9.000000E+01 3 1.589527E+02 8.159044E-01 1.589366E+02 2.263445E+00 + 1.830003E+01 9.000000E+01 4 2.802824E+02 8.974153E+01 1.264404E+00 2.802796E+02 + 1.830003E+01 9.000000E+01 5 1.716281E-04 -8.995464E+01 1.358817E-07 -1.716281E-04 + 1.830003E+01 9.000000E+01 6 1.519608E-05 1.799942E+02 -1.519608E-05 1.549729E-09 + 1.840003E+01 0.000000E+00 1 7.202413E+01 8.980454E+01 2.457006E-01 7.202371E+01 + 1.840003E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.840003E+01 0.000000E+00 3 1.522688E+02 7.871171E-01 1.522544E+02 2.091770E+00 + 1.840003E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.840003E+01 0.000000E+00 5 6.320253E+02 8.980453E+01 2.156214E+00 6.320217E+02 + 1.840003E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.840003E+01 3.000000E+01 1 6.300617E+01 8.980470E+01 2.147653E-01 6.300580E+01 + 1.840003E+01 3.000000E+01 2 3.842981E+01 8.974377E+01 1.718586E-01 3.842942E+01 + 1.840003E+01 3.000000E+01 3 1.540321E+02 7.918285E-01 1.540174E+02 2.128659E+00 + 1.840003E+01 3.000000E+01 4 1.312489E+02 8.973939E+01 5.969814E-01 1.312476E+02 + 1.840003E+01 3.000000E+01 5 5.529463E+02 8.980471E+01 1.884742E+00 5.529431E+02 + 1.840003E+01 3.000000E+01 6 1.690739E+02 -8.624646E-03 1.690739E+02 -2.545044E-02 + 1.840003E+01 6.000000E+01 1 3.711906E+01 8.980499E+01 1.263339E-01 3.711884E+01 + 1.840003E+01 6.000000E+01 2 6.806809E+01 8.974357E+01 3.046451E-01 6.806741E+01 + 1.840003E+01 6.000000E+01 3 1.576254E+02 8.012876E-01 1.576100E+02 2.204337E+00 + 1.840003E+01 6.000000E+01 4 2.364193E+02 8.974354E+01 1.058241E+00 2.364169E+02 + 1.840003E+01 6.000000E+01 5 3.257329E+02 8.980498E+01 1.108688E+00 3.257310E+02 + 1.840003E+01 6.000000E+01 6 1.729902E+02 -8.557120E-03 1.729902E+02 -2.583607E-02 + 1.840003E+01 9.000000E+01 1 3.906815E-06 -9.007437E+01 -5.071096E-09 -3.906812E-06 + 1.840003E+01 9.000000E+01 2 7.948264E+01 8.974347E+01 3.558712E-01 7.948185E+01 + 1.840003E+01 9.000000E+01 3 1.594551E+02 8.060344E-01 1.594393E+02 2.243133E+00 + 1.840003E+01 9.000000E+01 4 2.783203E+02 8.974551E+01 1.236186E+00 2.783175E+02 + 1.840003E+01 9.000000E+01 5 1.707521E-04 -8.995554E+01 1.324810E-07 -1.707521E-04 + 1.840003E+01 9.000000E+01 6 1.500261E-05 1.799943E+02 -1.500261E-05 1.485979E-09 + 1.850003E+01 0.000000E+00 1 7.164205E+01 8.980706E+01 2.412556E-01 7.164165E+01 + 1.850003E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.850003E+01 0.000000E+00 3 1.528361E+02 7.779517E-01 1.528220E+02 2.075117E+00 + 1.850003E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.850003E+01 0.000000E+00 5 6.306125E+02 8.980704E+01 2.123773E+00 6.306089E+02 + 1.850003E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.850003E+01 3.000000E+01 1 6.266346E+01 8.980721E+01 2.108573E-01 6.266311E+01 + 1.850003E+01 3.000000E+01 2 3.822110E+01 8.974770E+01 1.683022E-01 3.822073E+01 + 1.850003E+01 3.000000E+01 3 1.545818E+02 7.825297E-01 1.545674E+02 2.111169E+00 + 1.850003E+01 3.000000E+01 4 1.304306E+02 8.974344E+01 5.840477E-01 1.304293E+02 + 1.850003E+01 3.000000E+01 5 5.516334E+02 8.980721E+01 1.856169E+00 5.516302E+02 + 1.850003E+01 3.000000E+01 6 1.670181E+02 -8.375099E-03 1.670181E+02 -2.441354E-02 + 1.850003E+01 6.000000E+01 1 3.690732E+01 8.980749E+01 1.240075E-01 3.690711E+01 + 1.850003E+01 6.000000E+01 2 6.767809E+01 8.974751E+01 2.982456E-01 6.767743E+01 + 1.850003E+01 6.000000E+01 3 1.581387E+02 7.917254E-01 1.581236E+02 2.185125E+00 + 1.850003E+01 6.000000E+01 4 2.348323E+02 8.974747E+01 1.034985E+00 2.348300E+02 + 1.850003E+01 6.000000E+01 5 3.248682E+02 8.980747E+01 1.091634E+00 3.248664E+02 + 1.850003E+01 6.000000E+01 6 1.708347E+02 -8.310426E-03 1.708347E+02 -2.477859E-02 + 1.850003E+01 9.000000E+01 1 3.883495E-06 -9.007466E+01 -5.060660E-09 -3.883492E-06 + 1.850003E+01 9.000000E+01 2 7.901544E+01 8.974741E+01 3.483408E-01 7.901467E+01 + 1.850003E+01 9.000000E+01 3 1.599494E+02 7.963436E-01 1.599340E+02 2.223036E+00 + 1.850003E+01 9.000000E+01 4 2.763865E+02 8.974940E+01 1.208826E+00 2.763838E+02 + 1.850003E+01 9.000000E+01 5 1.698839E-04 -8.995643E+01 1.291906E-07 -1.698839E-04 + 1.850003E+01 9.000000E+01 6 1.481295E-05 1.799945E+02 -1.481295E-05 1.425329E-09 + 1.860003E+01 0.000000E+00 1 7.126378E+01 8.980952E+01 2.369186E-01 7.126338E+01 + 1.860003E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.860003E+01 0.000000E+00 3 1.533943E+02 7.689454E-01 1.533805E+02 2.058587E+00 + 1.860003E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.860003E+01 0.000000E+00 5 6.291846E+02 8.980950E+01 2.091887E+00 6.291811E+02 + 1.860003E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.860003E+01 3.000000E+01 1 6.232437E+01 8.980966E+01 2.070444E-01 6.232403E+01 + 1.860003E+01 3.000000E+01 2 3.801441E+01 8.975154E+01 1.648460E-01 3.801405E+01 + 1.860003E+01 3.000000E+01 3 1.551238E+02 7.734011E-01 1.551096E+02 2.093859E+00 + 1.860003E+01 3.000000E+01 4 1.296225E+02 8.974739E+01 5.714963E-01 1.296213E+02 + 1.860003E+01 3.000000E+01 5 5.503102E+02 8.980967E+01 1.828118E+00 5.503071E+02 + 1.860003E+01 3.000000E+01 6 1.650007E+02 -8.134776E-03 1.650007E+02 -2.342656E-02 + 1.860003E+01 6.000000E+01 1 3.669810E+01 8.980994E+01 1.217389E-01 3.669790E+01 + 1.860003E+01 6.000000E+01 2 6.729265E+01 8.975135E+01 2.920308E-01 6.729202E+01 + 1.860003E+01 6.000000E+01 3 1.586445E+02 7.823420E-01 1.586297E+02 2.166135E+00 + 1.860003E+01 6.000000E+01 4 2.332667E+02 8.975132E+01 1.012429E+00 2.332645E+02 + 1.860003E+01 6.000000E+01 5 3.240025E+02 8.980992E+01 1.074895E+00 3.240008E+02 + 1.860003E+01 6.000000E+01 6 1.687207E+02 -8.072804E-03 1.687207E+02 -2.377225E-02 + 1.860003E+01 9.000000E+01 1 3.860472E-06 -9.007492E+01 -5.047793E-09 -3.860469E-06 + 1.860003E+01 9.000000E+01 2 7.855367E+01 8.975126E+01 3.410285E-01 7.855293E+01 + 1.860003E+01 9.000000E+01 3 1.604366E+02 7.868304E-01 1.604214E+02 2.203171E+00 + 1.860003E+01 9.000000E+01 4 2.744805E+02 8.975320E+01 1.182297E+00 2.744779E+02 + 1.860003E+01 9.000000E+01 5 1.690257E-04 -8.995729E+01 1.260047E-07 -1.690256E-04 + 1.860003E+01 9.000000E+01 6 1.462706E-05 1.799946E+02 -1.462706E-05 1.367605E-09 + 1.870004E+01 0.000000E+00 1 7.088927E+01 8.981194E+01 2.326851E-01 7.088889E+01 + 1.870004E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.870004E+01 0.000000E+00 3 1.539454E+02 7.600883E-01 1.539318E+02 2.042186E+00 + 1.870004E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.870004E+01 0.000000E+00 5 6.277385E+02 8.981192E+01 2.060601E+00 6.277351E+02 + 1.870004E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.870004E+01 3.000000E+01 1 6.198892E+01 8.981207E+01 2.033236E-01 6.198859E+01 + 1.870004E+01 3.000000E+01 2 3.780996E+01 8.975529E+01 1.614865E-01 3.780961E+01 + 1.870004E+01 3.000000E+01 3 1.556573E+02 7.644194E-01 1.556434E+02 2.076661E+00 + 1.870004E+01 3.000000E+01 4 1.288244E+02 8.975124E+01 5.593082E-01 1.288232E+02 + 1.870004E+01 3.000000E+01 5 5.489734E+02 8.981208E+01 1.800582E+00 5.489705E+02 + 1.870004E+01 3.000000E+01 6 1.630204E+02 -7.903268E-03 1.630204E+02 -2.248672E-02 + 1.870004E+01 6.000000E+01 1 3.649121E+01 8.981233E+01 1.195254E-01 3.649101E+01 + 1.870004E+01 6.000000E+01 2 6.691158E+01 8.975510E+01 2.859918E-01 6.691096E+01 + 1.870004E+01 6.000000E+01 3 1.591425E+02 7.731164E-01 1.591281E+02 2.147313E+00 + 1.870004E+01 6.000000E+01 4 2.317234E+02 8.975508E+01 9.905398E-01 2.317213E+02 + 1.870004E+01 6.000000E+01 5 3.231285E+02 8.981232E+01 1.058487E+00 3.231268E+02 + 1.870004E+01 6.000000E+01 6 1.666478E+02 -7.843827E-03 1.666478E+02 -2.281418E-02 + 1.870004E+01 9.000000E+01 1 3.837726E-06 -9.007513E+01 -5.032650E-09 -3.837723E-06 + 1.870004E+01 9.000000E+01 2 7.809767E+01 8.975502E+01 3.339256E-01 7.809695E+01 + 1.870004E+01 9.000000E+01 3 1.609160E+02 7.774919E-01 1.609012E+02 2.183530E+00 + 1.870004E+01 9.000000E+01 4 2.726035E+02 8.975692E+01 1.156559E+00 2.726011E+02 + 1.870004E+01 9.000000E+01 5 1.681753E-04 -8.995812E+01 1.229208E-07 -1.681752E-04 + 1.870004E+01 9.000000E+01 6 1.444477E-05 1.799948E+02 -1.444477E-05 1.312643E-09 + 1.880004E+01 0.000000E+00 1 7.051838E+01 8.981431E+01 2.285529E-01 7.051801E+01 + 1.880004E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.880004E+01 0.000000E+00 3 1.544878E+02 7.513816E-01 1.544745E+02 2.025908E+00 + 1.880004E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.880004E+01 0.000000E+00 5 6.262758E+02 8.981429E+01 2.029913E+00 6.262725E+02 + 1.880004E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.880004E+01 3.000000E+01 1 6.165702E+01 8.981444E+01 1.996926E-01 6.165670E+01 + 1.880004E+01 3.000000E+01 2 3.760765E+01 8.975895E+01 1.582202E-01 3.760732E+01 + 1.880004E+01 3.000000E+01 3 1.561836E+02 7.555948E-01 1.561700E+02 2.059630E+00 + 1.880004E+01 3.000000E+01 4 1.280360E+02 8.975500E+01 5.474756E-01 1.280349E+02 + 1.880004E+01 3.000000E+01 5 5.476246E+02 8.981444E+01 1.773582E+00 5.476217E+02 + 1.880004E+01 3.000000E+01 6 1.610770E+02 -7.680135E-03 1.610770E+02 -2.159135E-02 + 1.880004E+01 6.000000E+01 1 3.628674E+01 8.981468E+01 1.173662E-01 3.628654E+01 + 1.880004E+01 6.000000E+01 2 6.653476E+01 8.975877E+01 2.801238E-01 6.653417E+01 + 1.880004E+01 6.000000E+01 3 1.596335E+02 7.640691E-01 1.596193E+02 2.128733E+00 + 1.880004E+01 6.000000E+01 4 2.301998E+02 8.975875E+01 9.692938E-01 2.301978E+02 + 1.880004E+01 6.000000E+01 5 3.222533E+02 8.981467E+01 1.042398E+00 3.222516E+02 + 1.880004E+01 6.000000E+01 6 1.646141E+02 -7.623150E-03 1.646141E+02 -2.190175E-02 + 1.880004E+01 9.000000E+01 1 3.815251E-06 -9.007532E+01 -5.015422E-09 -3.815248E-06 + 1.880004E+01 9.000000E+01 2 7.764704E+01 8.975869E+01 3.270249E-01 7.764635E+01 + 1.880004E+01 9.000000E+01 3 1.613897E+02 7.683160E-01 1.613752E+02 2.164113E+00 + 1.880004E+01 9.000000E+01 4 2.707519E+02 8.976054E+01 1.131587E+00 2.707496E+02 + 1.880004E+01 9.000000E+01 5 1.673326E-04 -8.995893E+01 1.199335E-07 -1.673326E-04 + 1.880004E+01 9.000000E+01 6 1.426603E-05 1.799949E+02 -1.426603E-05 1.260288E-09 + 1.890004E+01 0.000000E+00 1 7.015113E+01 8.981663E+01 2.245188E-01 7.015077E+01 + 1.890004E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.890004E+01 0.000000E+00 3 1.550225E+02 7.428225E-01 1.550094E+02 2.009763E+00 + 1.890004E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.890004E+01 0.000000E+00 5 6.247957E+02 8.981661E+01 1.999770E+00 6.247925E+02 + 1.890004E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.890004E+01 3.000000E+01 1 6.132856E+01 8.981675E+01 1.961475E-01 6.132825E+01 + 1.890004E+01 3.000000E+01 2 3.740742E+01 8.976253E+01 1.550437E-01 3.740710E+01 + 1.890004E+01 3.000000E+01 3 1.567010E+02 7.469233E-01 1.566877E+02 2.042739E+00 + 1.890004E+01 3.000000E+01 4 1.272576E+02 8.975868E+01 5.359846E-01 1.272565E+02 + 1.890004E+01 3.000000E+01 5 5.462592E+02 8.981675E+01 1.747093E+00 5.462563E+02 + 1.890004E+01 3.000000E+01 6 1.591689E+02 -7.465058E-03 1.591689E+02 -2.073810E-02 + 1.890004E+01 6.000000E+01 1 3.608452E+01 8.981699E+01 1.152586E-01 3.608434E+01 + 1.890004E+01 6.000000E+01 2 6.616258E+01 8.976235E+01 2.744199E-01 6.616201E+01 + 1.890004E+01 6.000000E+01 3 1.601171E+02 7.551630E-01 1.601032E+02 2.110296E+00 + 1.890004E+01 6.000000E+01 4 2.286984E+02 8.976233E+01 9.486709E-01 2.286964E+02 + 1.890004E+01 6.000000E+01 5 3.213707E+02 8.981698E+01 1.026604E+00 3.213691E+02 + 1.890004E+01 6.000000E+01 6 1.626183E+02 -7.410386E-03 1.626183E+02 -2.103234E-02 + 1.890004E+01 9.000000E+01 1 3.793045E-06 -9.007547E+01 -4.996249E-09 -3.793042E-06 + 1.890004E+01 9.000000E+01 2 7.720198E+01 8.976228E+01 3.203201E-01 7.720132E+01 + 1.890004E+01 9.000000E+01 3 1.618545E+02 7.593017E-01 1.618403E+02 2.144884E+00 + 1.890004E+01 9.000000E+01 4 2.689290E+02 8.976408E+01 1.107348E+00 2.689268E+02 + 1.890004E+01 9.000000E+01 5 1.664985E-04 -8.995972E+01 1.170405E-07 -1.664984E-04 + 1.890004E+01 9.000000E+01 6 1.409072E-05 1.799951E+02 -1.409072E-05 1.210402E-09 + 1.900004E+01 0.000000E+00 1 6.978777E+01 8.981891E+01 2.205790E-01 6.978741E+01 + 1.900004E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.900004E+01 0.000000E+00 3 1.555495E+02 7.344062E-01 1.555367E+02 1.993748E+00 + 1.900004E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.900004E+01 0.000000E+00 5 6.233063E+02 8.981889E+01 1.970198E+00 6.233032E+02 + 1.900004E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.900004E+01 3.000000E+01 1 6.100338E+01 8.981902E+01 1.926873E-01 6.100307E+01 + 1.900004E+01 3.000000E+01 2 3.720937E+01 8.976602E+01 1.519540E-01 3.720906E+01 + 1.900004E+01 3.000000E+01 3 1.572115E+02 7.384052E-01 1.571984E+02 2.026023E+00 + 1.900004E+01 3.000000E+01 4 1.264887E+02 8.976228E+01 5.248197E-01 1.264876E+02 + 1.900004E+01 3.000000E+01 5 5.448878E+02 8.981903E+01 1.721063E+00 5.448850E+02 + 1.900004E+01 3.000000E+01 6 1.572953E+02 -7.257670E-03 1.572953E+02 -1.992464E-02 + 1.900004E+01 6.000000E+01 1 3.588451E+01 8.981926E+01 1.132025E-01 3.588433E+01 + 1.900004E+01 6.000000E+01 2 6.579439E+01 8.976586E+01 2.688755E-01 6.579384E+01 + 1.900004E+01 6.000000E+01 3 1.605941E+02 7.464270E-01 1.605805E+02 2.092098E+00 + 1.900004E+01 6.000000E+01 4 2.272180E+02 8.976583E+01 9.286466E-01 2.272161E+02 + 1.900004E+01 6.000000E+01 5 3.204846E+02 8.981924E+01 1.011113E+00 3.204830E+02 + 1.900004E+01 6.000000E+01 6 1.606605E+02 -7.205190E-03 1.606605E+02 -2.020374E-02 + 1.900004E+01 9.000000E+01 1 3.771110E-06 -9.007559E+01 -4.975303E-09 -3.771107E-06 + 1.900004E+01 9.000000E+01 2 7.676212E+01 8.976578E+01 3.138021E-01 7.676148E+01 + 1.900004E+01 9.000000E+01 3 1.623144E+02 7.504477E-01 1.623005E+02 2.125898E+00 + 1.900004E+01 9.000000E+01 4 2.671296E+02 8.976754E+01 1.083821E+00 2.671274E+02 + 1.900004E+01 9.000000E+01 5 1.656728E-04 -8.996049E+01 1.142378E-07 -1.656728E-04 + 1.900004E+01 9.000000E+01 6 1.391878E-05 1.799952E+02 -1.391878E-05 1.162848E-09 + 1.910004E+01 0.000000E+00 1 6.942786E+01 8.982114E+01 2.167330E-01 6.942752E+01 + 1.910004E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.910004E+01 0.000000E+00 3 1.560689E+02 7.261311E-01 1.560564E+02 1.977868E+00 + 1.910004E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.910004E+01 0.000000E+00 5 6.218000E+02 8.982114E+01 1.941159E+00 6.217969E+02 + 1.910004E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.910004E+01 3.000000E+01 1 6.068158E+01 8.982126E+01 1.893084E-01 6.068128E+01 + 1.910004E+01 3.000000E+01 2 3.701323E+01 8.976943E+01 1.489489E-01 3.701293E+01 + 1.910004E+01 3.000000E+01 3 1.577154E+02 7.300221E-01 1.577026E+02 2.009443E+00 + 1.910004E+01 3.000000E+01 4 1.257294E+02 8.976578E+01 5.139754E-01 1.257283E+02 + 1.910004E+01 3.000000E+01 5 5.435054E+02 8.982126E+01 1.695528E+00 5.435027E+02 + 1.910004E+01 3.000000E+01 6 1.554560E+02 -7.057612E-03 1.554560E+02 -1.914885E-02 + 1.910004E+01 6.000000E+01 1 3.568686E+01 8.982148E+01 1.111949E-01 3.568669E+01 + 1.910004E+01 6.000000E+01 2 6.543037E+01 8.976927E+01 2.634829E-01 6.542984E+01 + 1.910004E+01 6.000000E+01 3 1.610642E+02 7.378352E-01 1.610508E+02 2.074071E+00 + 1.910004E+01 6.000000E+01 4 2.257564E+02 8.976925E+01 9.091973E-01 2.257546E+02 + 1.910004E+01 6.000000E+01 5 3.195949E+02 8.982146E+01 9.959189E-01 3.195933E+02 + 1.910004E+01 6.000000E+01 6 1.587390E+02 -7.007251E-03 1.587390E+02 -1.941372E-02 + 1.910004E+01 9.000000E+01 1 3.749427E-06 -9.007568E+01 -4.952720E-09 -3.749424E-06 + 1.910004E+01 9.000000E+01 2 7.632726E+01 8.976920E+01 3.074666E-01 7.632664E+01 + 1.910004E+01 9.000000E+01 3 1.627665E+02 7.417550E-01 1.627528E+02 2.107127E+00 + 1.910004E+01 9.000000E+01 4 2.653554E+02 8.977091E+01 1.060974E+00 2.653533E+02 + 1.910004E+01 9.000000E+01 5 1.648544E-04 -8.996124E+01 1.115214E-07 -1.648543E-04 + 1.910004E+01 9.000000E+01 6 1.375006E-05 1.799953E+02 -1.375006E-05 1.117500E-09 + 1.920004E+01 0.000000E+00 1 6.907115E+01 8.982333E+01 2.129757E-01 6.907082E+01 + 1.920004E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.920004E+01 0.000000E+00 3 1.565803E+02 7.179950E-01 1.565680E+02 1.962116E+00 + 1.920004E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.920004E+01 0.000000E+00 5 6.202828E+02 8.982333E+01 1.912669E+00 6.202799E+02 + 1.920004E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.920004E+01 3.000000E+01 1 6.036312E+01 8.982344E+01 1.860089E-01 6.036284E+01 + 1.920004E+01 3.000000E+01 2 3.681923E+01 8.977277E+01 1.460243E-01 3.681894E+01 + 1.920004E+01 3.000000E+01 3 1.582106E+02 7.217817E-01 1.581981E+02 1.993000E+00 + 1.920004E+01 3.000000E+01 4 1.249795E+02 8.976920E+01 5.034329E-01 1.249784E+02 + 1.920004E+01 3.000000E+01 5 5.421082E+02 8.982345E+01 1.670478E+00 5.421056E+02 + 1.920004E+01 3.000000E+01 6 1.536496E+02 -6.864610E-03 1.536496E+02 -1.840876E-02 + 1.920004E+01 6.000000E+01 1 3.549138E+01 8.982365E+01 1.092358E-01 3.549121E+01 + 1.920004E+01 6.000000E+01 2 6.507050E+01 8.977261E+01 2.582391E-01 6.506998E+01 + 1.920004E+01 6.000000E+01 3 1.615269E+02 7.293875E-01 1.615138E+02 2.056216E+00 + 1.920004E+01 6.000000E+01 4 2.243149E+02 8.977259E+01 8.903069E-01 2.243131E+02 + 1.920004E+01 6.000000E+01 5 3.186985E+02 8.982363E+01 9.810125E-01 3.186970E+02 + 1.920004E+01 6.000000E+01 6 1.568531E+02 -6.816230E-03 1.568531E+02 -1.866014E-02 + 1.920004E+01 9.000000E+01 1 3.728017E-06 -9.007575E+01 -4.928615E-09 -3.728014E-06 + 1.920004E+01 9.000000E+01 2 7.589767E+01 8.977254E+01 3.013060E-01 7.589707E+01 + 1.920004E+01 9.000000E+01 3 1.632128E+02 7.332022E-01 1.631994E+02 2.088543E+00 + 1.920004E+01 9.000000E+01 4 2.636079E+02 8.977422E+01 1.038785E+00 2.636059E+02 + 1.920004E+01 9.000000E+01 5 1.640436E-04 -8.996197E+01 1.088889E-07 -1.640436E-04 + 1.920004E+01 9.000000E+01 6 1.358456E-05 1.799955E+02 -1.358456E-05 1.074242E-09 + 1.930004E+01 0.000000E+00 1 6.871840E+01 8.982549E+01 2.093058E-01 6.871808E+01 + 1.930004E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.930004E+01 0.000000E+00 3 1.570845E+02 7.099943E-01 1.570725E+02 1.946501E+00 + 1.930004E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.930004E+01 0.000000E+00 5 6.187471E+02 8.982548E+01 1.884677E+00 6.187443E+02 + 1.930004E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.930004E+01 3.000000E+01 1 6.004795E+01 8.982559E+01 1.827856E-01 6.004767E+01 + 1.930004E+01 3.000000E+01 2 3.662716E+01 8.977603E+01 1.431779E-01 3.662688E+01 + 1.930004E+01 3.000000E+01 3 1.586995E+02 7.136821E-01 1.586872E+02 1.976727E+00 + 1.930004E+01 3.000000E+01 4 1.242382E+02 8.977256E+01 4.931839E-01 1.242372E+02 + 1.930004E+01 3.000000E+01 5 5.407071E+02 8.982559E+01 1.645885E+00 5.407046E+02 + 1.930004E+01 3.000000E+01 6 1.518755E+02 -6.678335E-03 1.518755E+02 -1.770245E-02 + 1.930004E+01 6.000000E+01 1 3.529807E+01 8.982579E+01 1.073225E-01 3.529791E+01 + 1.930004E+01 6.000000E+01 2 6.471467E+01 8.977589E+01 2.531377E-01 6.471417E+01 + 1.930004E+01 6.000000E+01 3 1.619833E+02 7.210882E-01 1.619704E+02 2.038564E+00 + 1.930004E+01 6.000000E+01 4 2.228919E+02 8.977586E+01 8.719522E-01 2.228902E+02 + 1.930004E+01 6.000000E+01 5 3.178018E+02 8.982578E+01 9.663804E-01 3.178004E+02 + 1.930004E+01 6.000000E+01 6 1.550019E+02 -6.631880E-03 1.550019E+02 -1.794118E-02 + 1.930004E+01 9.000000E+01 1 3.706853E-06 -9.007578E+01 -4.903121E-09 -3.706850E-06 + 1.930004E+01 9.000000E+01 2 7.547302E+01 8.977581E+01 2.953140E-01 7.547244E+01 + 1.930004E+01 9.000000E+01 3 1.636519E+02 7.248065E-01 1.636389E+02 2.070184E+00 + 1.930004E+01 9.000000E+01 4 2.618840E+02 8.977745E+01 1.017237E+00 2.618820E+02 + 1.930004E+01 9.000000E+01 5 1.632413E-04 -8.996268E+01 1.063370E-07 -1.632413E-04 + 1.930004E+01 9.000000E+01 6 1.342214E-05 1.799956E+02 -1.342214E-05 1.032962E-09 + 1.940004E+01 0.000000E+00 1 6.836884E+01 8.982761E+01 2.057198E-01 6.836853E+01 + 1.940004E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.940004E+01 0.000000E+00 3 1.575827E+02 7.021175E-01 1.575708E+02 1.931011E+00 + 1.940004E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.940004E+01 0.000000E+00 5 6.172117E+02 8.982760E+01 1.857207E+00 6.172089E+02 + 1.940004E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.940004E+01 3.000000E+01 1 5.973589E+01 8.982770E+01 1.796385E-01 5.973562E+01 + 1.940004E+01 3.000000E+01 2 3.643702E+01 8.977922E+01 1.404070E-01 3.643675E+01 + 1.940004E+01 3.000000E+01 3 1.591822E+02 7.057143E-01 1.591701E+02 1.960603E+00 + 1.940004E+01 3.000000E+01 4 1.235057E+02 8.977583E+01 4.832211E-01 1.235048E+02 + 1.940004E+01 3.000000E+01 5 5.392993E+02 8.982771E+01 1.621748E+00 5.392968E+02 + 1.940004E+01 3.000000E+01 6 1.501328E+02 -6.498507E-03 1.501328E+02 -1.702811E-02 + 1.940004E+01 6.000000E+01 1 3.510679E+01 8.982790E+01 1.054539E-01 3.510663E+01 + 1.940004E+01 6.000000E+01 2 6.436284E+01 8.977908E+01 2.481732E-01 6.436236E+01 + 1.940004E+01 6.000000E+01 3 1.624339E+02 7.129310E-01 1.624213E+02 2.021111E+00 + 1.940004E+01 6.000000E+01 4 2.214881E+02 8.977905E+01 8.541104E-01 2.214865E+02 + 1.940004E+01 6.000000E+01 5 3.169031E+02 8.982787E+01 9.520346E-01 3.169017E+02 + 1.940004E+01 6.000000E+01 6 1.531846E+02 -6.453868E-03 1.531846E+02 -1.725490E-02 + 1.940004E+01 9.000000E+01 1 3.685946E-06 -9.007580E+01 -4.876348E-09 -3.685942E-06 + 1.940004E+01 9.000000E+01 2 7.505329E+01 8.977901E+01 2.894852E-01 7.505273E+01 + 1.940004E+01 9.000000E+01 3 1.640857E+02 7.165560E-01 1.640729E+02 2.052046E+00 + 1.940004E+01 9.000000E+01 4 2.601810E+02 8.978060E+01 9.962885E-01 2.601790E+02 + 1.940004E+01 9.000000E+01 5 1.624452E-04 -8.996336E+01 1.038618E-07 -1.624452E-04 + 1.940004E+01 9.000000E+01 6 1.326271E-05 1.799957E+02 -1.326271E-05 9.935558E-10 + 1.950004E+01 0.000000E+00 1 6.802279E+01 8.982967E+01 2.022174E-01 6.802249E+01 + 1.950004E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.950004E+01 0.000000E+00 3 1.580724E+02 6.943756E-01 1.580608E+02 1.915655E+00 + 1.950004E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.950004E+01 0.000000E+00 5 6.156529E+02 8.982967E+01 1.830267E+00 6.156501E+02 + 1.950004E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.950004E+01 3.000000E+01 1 5.942714E+01 8.982977E+01 1.765630E-01 5.942687E+01 + 1.950004E+01 3.000000E+01 2 3.624876E+01 8.978233E+01 1.377095E-01 3.624850E+01 + 1.950004E+01 3.000000E+01 3 1.596567E+02 6.978816E-01 1.596449E+02 1.944623E+00 + 1.950004E+01 3.000000E+01 4 1.227823E+02 8.977903E+01 4.735329E-01 1.227813E+02 + 1.950004E+01 3.000000E+01 5 5.378788E+02 8.982977E+01 1.598069E+00 5.378764E+02 + 1.950004E+01 3.000000E+01 6 1.484208E+02 -6.324852E-03 1.484208E+02 -1.638410E-02 + 1.950004E+01 6.000000E+01 1 3.491772E+01 8.982996E+01 1.036295E-01 3.491757E+01 + 1.950004E+01 6.000000E+01 2 6.401466E+01 8.978220E+01 2.433422E-01 6.401420E+01 + 1.950004E+01 6.000000E+01 3 1.628769E+02 7.049140E-01 1.628646E+02 2.003836E+00 + 1.950004E+01 6.000000E+01 4 2.201030E+02 8.978217E+01 8.367677E-01 2.201014E+02 + 1.950004E+01 6.000000E+01 5 3.159998E+02 8.982993E+01 9.379523E-01 3.159984E+02 + 1.950004E+01 6.000000E+01 6 1.514002E+02 -6.281951E-03 1.514002E+02 -1.659963E-02 + 1.950004E+01 9.000000E+01 1 3.665270E-06 -9.007579E+01 -4.848439E-09 -3.665266E-06 + 1.950004E+01 9.000000E+01 2 7.463833E+01 8.978214E+01 2.838138E-01 7.463779E+01 + 1.950004E+01 9.000000E+01 3 1.645125E+02 7.084419E-01 1.644999E+02 2.034086E+00 + 1.950004E+01 9.000000E+01 4 2.585056E+02 8.978369E+01 9.759369E-01 2.585038E+02 + 1.950004E+01 9.000000E+01 5 1.616570E-04 -8.996404E+01 1.014617E-07 -1.616569E-04 + 1.950004E+01 9.000000E+01 6 1.310622E-05 1.799958E+02 -1.310622E-05 9.559269E-10 + 1.960004E+01 0.000000E+00 1 6.768022E+01 8.983171E+01 1.987937E-01 6.767993E+01 + 1.960004E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.960004E+01 0.000000E+00 3 1.585559E+02 6.867648E-01 1.585445E+02 1.900454E+00 + 1.960004E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.960004E+01 0.000000E+00 5 6.140935E+02 8.983170E+01 1.803811E+00 6.140909E+02 + 1.960004E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.960004E+01 3.000000E+01 1 5.912159E+01 8.983180E+01 1.735587E-01 5.912133E+01 + 1.960004E+01 3.000000E+01 2 3.606258E+01 8.978539E+01 1.350825E-01 3.606233E+01 + 1.960004E+01 3.000000E+01 3 1.601251E+02 6.901776E-01 1.601135E+02 1.928800E+00 + 1.960004E+01 3.000000E+01 4 1.220670E+02 8.978216E+01 4.641080E-01 1.220661E+02 + 1.960004E+01 3.000000E+01 5 5.364617E+02 8.983181E+01 1.574792E+00 5.364594E+02 + 1.960004E+01 3.000000E+01 6 1.467386E+02 -6.157144E-03 1.467386E+02 -1.576889E-02 + 1.960004E+01 6.000000E+01 1 3.473074E+01 8.983198E+01 1.018475E-01 3.473059E+01 + 1.960004E+01 6.000000E+01 2 6.367042E+01 8.978526E+01 2.386403E-01 6.366998E+01 + 1.960004E+01 6.000000E+01 3 1.633143E+02 6.970323E-01 1.633022E+02 1.986753E+00 + 1.960004E+01 6.000000E+01 4 2.187356E+02 8.978523E+01 8.199068E-01 2.187341E+02 + 1.960004E+01 6.000000E+01 5 3.150946E+02 8.983196E+01 9.241250E-01 3.150932E+02 + 1.960004E+01 6.000000E+01 6 1.496480E+02 -6.115883E-03 1.496480E+02 -1.597377E-02 + 1.960004E+01 9.000000E+01 1 3.644839E-06 -9.007577E+01 -4.819454E-09 -3.644836E-06 + 1.960004E+01 9.000000E+01 2 7.422815E+01 8.978519E+01 2.782941E-01 7.422763E+01 + 1.960004E+01 9.000000E+01 3 1.649340E+02 7.004694E-01 1.649216E+02 2.016349E+00 + 1.960004E+01 9.000000E+01 4 2.568502E+02 8.978671E+01 9.561508E-01 2.568484E+02 + 1.960004E+01 9.000000E+01 5 1.608771E-04 -8.996470E+01 9.913363E-08 -1.608770E-04 + 1.960004E+01 9.000000E+01 6 1.295262E-05 1.799959E+02 -1.295262E-05 9.199813E-10 + 1.970004E+01 0.000000E+00 1 6.734092E+01 8.983371E+01 1.954481E-01 6.734064E+01 + 1.970004E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.970004E+01 0.000000E+00 3 1.590327E+02 6.792712E-01 1.590215E+02 1.885371E+00 + 1.970004E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.970004E+01 0.000000E+00 5 6.125246E+02 8.983370E+01 1.777803E+00 6.125220E+02 + 1.970004E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.970004E+01 3.000000E+01 1 5.881894E+01 8.983380E+01 1.706220E-01 5.881870E+01 + 1.970004E+01 3.000000E+01 2 3.587813E+01 8.978836E+01 1.325237E-01 3.587788E+01 + 1.970004E+01 3.000000E+01 3 1.605865E+02 6.826011E-01 1.605751E+02 1.913124E+00 + 1.970004E+01 3.000000E+01 4 1.213605E+02 8.978522E+01 4.549405E-01 1.213596E+02 + 1.970004E+01 3.000000E+01 5 5.350274E+02 8.983380E+01 1.551983E+00 5.350251E+02 + 1.970004E+01 3.000000E+01 6 1.450856E+02 -5.995097E-03 1.450856E+02 -1.518091E-02 + 1.970004E+01 6.000000E+01 1 3.454567E+01 8.983397E+01 1.001060E-01 3.454552E+01 + 1.970004E+01 6.000000E+01 2 6.332985E+01 8.978824E+01 2.340613E-01 6.332942E+01 + 1.970004E+01 6.000000E+01 3 1.637459E+02 6.892782E-01 1.637341E+02 1.969845E+00 + 1.970004E+01 6.000000E+01 4 2.173860E+02 8.978822E+01 8.035110E-01 2.173845E+02 + 1.970004E+01 6.000000E+01 5 3.141878E+02 8.983395E+01 9.105613E-01 3.141865E+02 + 1.970004E+01 6.000000E+01 6 1.479271E+02 -5.955416E-03 1.479271E+02 -1.537578E-02 + 1.970004E+01 9.000000E+01 1 3.624643E-06 -9.007571E+01 -4.789501E-09 -3.624640E-06 + 1.970004E+01 9.000000E+01 2 7.382257E+01 8.978818E+01 2.729210E-01 7.382207E+01 + 1.970004E+01 9.000000E+01 3 1.653496E+02 6.926309E-01 1.653375E+02 1.998811E+00 + 1.970004E+01 9.000000E+01 4 2.552161E+02 8.978967E+01 9.369106E-01 2.552144E+02 + 1.970004E+01 9.000000E+01 5 1.601036E-04 -8.996533E+01 9.687469E-08 -1.601036E-04 + 1.970004E+01 9.000000E+01 6 1.280180E-05 1.799960E+02 -1.280180E-05 8.856320E-10 + 1.980004E+01 0.000000E+00 1 6.700471E+01 8.983567E+01 1.921776E-01 6.700443E+01 + 1.980004E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.980004E+01 0.000000E+00 3 1.595020E+02 6.718988E-01 1.594910E+02 1.870412E+00 + 1.980004E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.980004E+01 0.000000E+00 5 6.109462E+02 8.983567E+01 1.752289E+00 6.109437E+02 + 1.980004E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.980004E+01 3.000000E+01 1 5.851933E+01 8.983575E+01 1.677530E-01 5.851908E+01 + 1.980004E+01 3.000000E+01 2 3.569559E+01 8.979129E+01 1.300312E-01 3.569535E+01 + 1.980004E+01 3.000000E+01 3 1.610419E+02 6.751460E-01 1.610307E+02 1.897596E+00 + 1.980004E+01 3.000000E+01 4 1.206626E+02 8.978822E+01 4.460172E-01 1.206618E+02 + 1.980004E+01 3.000000E+01 5 5.335878E+02 8.983575E+01 1.529572E+00 5.335856E+02 + 1.980004E+01 3.000000E+01 6 1.434617E+02 -5.838491E-03 1.434617E+02 -1.461887E-02 + 1.980004E+01 6.000000E+01 1 3.436272E+01 8.983592E+01 9.840482E-02 3.436258E+01 + 1.980004E+01 6.000000E+01 2 6.299330E+01 8.979116E+01 2.296038E-01 6.299288E+01 + 1.980004E+01 6.000000E+01 3 1.641703E+02 6.816542E-01 1.641586E+02 1.953106E+00 + 1.980004E+01 6.000000E+01 4 2.160534E+02 8.979115E+01 7.875615E-01 2.160520E+02 + 1.980004E+01 6.000000E+01 5 3.132790E+02 8.983590E+01 8.972627E-01 3.132777E+02 + 1.980004E+01 6.000000E+01 6 1.462366E+02 -5.800338E-03 1.462366E+02 -1.480426E-02 + 1.980004E+01 9.000000E+01 1 3.604679E-06 -9.007564E+01 -4.758652E-09 -3.604676E-06 + 1.980004E+01 9.000000E+01 2 7.342159E+01 8.979110E+01 2.676905E-01 7.342110E+01 + 1.980004E+01 9.000000E+01 3 1.657582E+02 6.849240E-01 1.657464E+02 1.981456E+00 + 1.980004E+01 9.000000E+01 4 2.536058E+02 8.979256E+01 9.182081E-01 2.536041E+02 + 1.980004E+01 9.000000E+01 5 1.593371E-04 -8.996596E+01 9.468278E-08 -1.593371E-04 + 1.980004E+01 9.000000E+01 6 1.265372E-05 1.799961E+02 -1.265372E-05 8.527974E-10 + 1.990004E+01 0.000000E+00 1 6.667184E+01 8.983759E+01 1.889807E-01 6.667157E+01 + 1.990004E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.990004E+01 0.000000E+00 3 1.599651E+02 6.646500E-01 1.599543E+02 1.855606E+00 + 1.990004E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.990004E+01 0.000000E+00 5 6.093580E+02 8.983759E+01 1.727242E+00 6.093556E+02 + 1.990004E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 1.990004E+01 3.000000E+01 1 5.822293E+01 8.983768E+01 1.649476E-01 5.822269E+01 + 1.990004E+01 3.000000E+01 2 3.551482E+01 8.979414E+01 1.276025E-01 3.551460E+01 + 1.990004E+01 3.000000E+01 3 1.614907E+02 6.678128E-01 1.614797E+02 1.882217E+00 + 1.990004E+01 3.000000E+01 4 1.199726E+02 8.979115E+01 4.373339E-01 1.199718E+02 + 1.990004E+01 3.000000E+01 5 5.321520E+02 8.983768E+01 1.507587E+00 5.321498E+02 + 1.990004E+01 3.000000E+01 6 1.418652E+02 -5.687098E-03 1.418652E+02 -1.408134E-02 + 1.990004E+01 6.000000E+01 1 3.418168E+01 8.983784E+01 9.674253E-02 3.418155E+01 + 1.990004E+01 6.000000E+01 2 6.266013E+01 8.979403E+01 2.252613E-01 6.265973E+01 + 1.990004E+01 6.000000E+01 3 1.645891E+02 6.741656E-01 1.645777E+02 1.936578E+00 + 1.990004E+01 6.000000E+01 4 2.147379E+02 8.979401E+01 7.720474E-01 2.147365E+02 + 1.990004E+01 6.000000E+01 5 3.123662E+02 8.983781E+01 8.842103E-01 3.123649E+02 + 1.990004E+01 6.000000E+01 6 1.445764E+02 -5.650376E-03 1.445764E+02 -1.425779E-02 + 1.990004E+01 9.000000E+01 1 3.584934E-06 -9.007555E+01 -4.727026E-09 -3.584930E-06 + 1.990004E+01 9.000000E+01 2 7.302515E+01 8.979396E+01 2.625970E-01 7.302467E+01 + 1.990004E+01 9.000000E+01 3 1.661619E+02 6.773497E-01 1.661503E+02 1.964318E+00 + 1.990004E+01 9.000000E+01 4 2.520165E+02 8.979539E+01 9.000081E-01 2.520149E+02 + 1.990004E+01 9.000000E+01 5 1.585784E-04 -8.996656E+01 9.255515E-08 -1.585784E-04 + 1.990004E+01 9.000000E+01 6 1.250827E-05 1.799962E+02 -1.250827E-05 8.214012E-10 + 2.000004E+01 0.000000E+00 1 6.634226E+01 8.983949E+01 1.858546E-01 6.634200E+01 + 2.000004E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.000004E+01 0.000000E+00 3 1.604220E+02 6.575137E-01 1.604115E+02 1.840927E+00 + 2.000004E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.000004E+01 0.000000E+00 5 6.077615E+02 8.983949E+01 1.702645E+00 6.077592E+02 + 2.000004E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.000004E+01 3.000000E+01 1 5.792927E+01 8.983957E+01 1.622059E-01 5.792904E+01 + 2.000004E+01 3.000000E+01 2 3.533589E+01 8.979694E+01 1.252355E-01 3.533567E+01 + 2.000004E+01 3.000000E+01 3 1.619333E+02 6.605989E-01 1.619226E+02 1.866989E+00 + 2.000004E+01 3.000000E+01 4 1.192906E+02 8.979401E+01 4.288814E-01 1.192898E+02 + 2.000004E+01 3.000000E+01 5 5.307010E+02 8.983957E+01 1.485988E+00 5.306990E+02 + 2.000004E+01 3.000000E+01 6 1.402961E+02 -5.540731E-03 1.402961E+02 -1.356720E-02 + 2.000004E+01 6.000000E+01 1 3.400243E+01 8.983972E+01 9.511802E-02 3.400230E+01 + 2.000004E+01 6.000000E+01 2 6.233058E+01 8.979683E+01 2.210312E-01 6.233019E+01 + 2.000004E+01 6.000000E+01 3 1.650017E+02 6.667956E-01 1.649906E+02 1.920210E+00 + 2.000004E+01 6.000000E+01 4 2.134400E+02 8.979681E+01 7.569461E-01 2.134387E+02 + 2.000004E+01 6.000000E+01 5 3.114556E+02 8.983970E+01 8.713866E-01 3.114543E+02 + 2.000004E+01 6.000000E+01 6 1.429450E+02 -5.505381E-03 1.429450E+02 -1.373516E-02 + 2.000004E+01 9.000000E+01 1 3.565423E-06 -9.007544E+01 -4.694682E-09 -3.565420E-06 + 2.000004E+01 9.000000E+01 2 7.263313E+01 8.979677E+01 2.576355E-01 7.263268E+01 + 2.000004E+01 9.000000E+01 3 1.665602E+02 6.698995E-01 1.665488E+02 1.947369E+00 + 2.000004E+01 9.000000E+01 4 2.504476E+02 8.979815E+01 8.823016E-01 2.504461E+02 + 2.000004E+01 9.000000E+01 5 1.578268E-04 -8.996715E+01 9.048949E-08 -1.578268E-04 + 2.000004E+01 9.000000E+01 6 1.236541E-05 1.799963E+02 -1.236541E-05 7.913703E-10 + 2.010004E+01 0.000000E+00 1 6.601561E+01 8.984135E+01 1.827983E-01 6.601536E+01 + 2.010004E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.010004E+01 0.000000E+00 3 1.608723E+02 6.504965E-01 1.608620E+02 1.826393E+00 + 2.010004E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.010004E+01 0.000000E+00 5 6.061603E+02 8.984135E+01 1.678491E+00 6.061580E+02 + 2.010004E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.010004E+01 3.000000E+01 1 5.763844E+01 8.984143E+01 1.595245E-01 5.763822E+01 + 2.010004E+01 3.000000E+01 2 3.515861E+01 8.979967E+01 1.229283E-01 3.515839E+01 + 2.010004E+01 3.000000E+01 3 1.623705E+02 6.535022E-01 1.623599E+02 1.851919E+00 + 2.010004E+01 3.000000E+01 4 1.186168E+02 8.979681E+01 4.206497E-01 1.186160E+02 + 2.010004E+01 3.000000E+01 5 5.292515E+02 8.984143E+01 1.464780E+00 5.292495E+02 + 2.010004E+01 3.000000E+01 6 1.387538E+02 -5.399149E-03 1.387538E+02 -1.307518E-02 + 2.010004E+01 6.000000E+01 1 3.382521E+01 8.984157E+01 9.352974E-02 3.382508E+01 + 2.010004E+01 6.000000E+01 2 6.200449E+01 8.979957E+01 2.169100E-01 6.200412E+01 + 2.010004E+01 6.000000E+01 3 1.654107E+02 6.595407E-01 1.653997E+02 1.904026E+00 + 2.010004E+01 6.000000E+01 4 2.121576E+02 8.979955E+01 7.422479E-01 2.121563E+02 + 2.010004E+01 6.000000E+01 5 3.105449E+02 8.984155E+01 8.588048E-01 3.105437E+02 + 2.010004E+01 6.000000E+01 6 1.413419E+02 -5.365128E-03 1.413419E+02 -1.323513E-02 + 2.010004E+01 9.000000E+01 1 3.546126E-06 -9.007532E+01 -4.661665E-09 -3.546123E-06 + 2.010004E+01 9.000000E+01 2 7.224520E+01 8.979951E+01 2.528028E-01 7.224476E+01 + 2.010004E+01 9.000000E+01 3 1.669528E+02 6.625724E-01 1.669416E+02 1.930611E+00 + 2.010004E+01 9.000000E+01 4 2.488997E+02 8.980087E+01 8.650754E-01 2.488982E+02 + 2.010004E+01 9.000000E+01 5 1.570815E-04 -8.996773E+01 8.848377E-08 -1.570815E-04 + 2.010004E+01 9.000000E+01 6 1.222509E-05 1.799964E+02 -1.222509E-05 7.626365E-10 + 2.020004E+01 0.000000E+00 1 6.569223E+01 8.984318E+01 1.798095E-01 6.569199E+01 + 2.020004E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.020004E+01 0.000000E+00 3 1.613166E+02 6.435845E-01 1.613064E+02 1.811978E+00 + 2.020004E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.020004E+01 0.000000E+00 5 6.045582E+02 8.984318E+01 1.654773E+00 6.045560E+02 + 2.020004E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.020004E+01 3.000000E+01 1 5.735064E+01 8.984325E+01 1.569035E-01 5.735043E+01 + 2.020004E+01 3.000000E+01 2 3.498322E+01 8.980235E+01 1.206792E-01 3.498301E+01 + 2.020004E+01 3.000000E+01 3 1.628003E+02 6.465209E-01 1.627899E+02 1.836986E+00 + 2.020004E+01 3.000000E+01 4 1.179500E+02 8.979956E+01 4.126361E-01 1.179493E+02 + 2.020004E+01 3.000000E+01 5 5.278019E+02 8.984325E+01 1.443964E+00 5.278000E+02 + 2.020004E+01 3.000000E+01 6 1.372371E+02 -5.262219E-03 1.372371E+02 -1.260427E-02 + 2.020004E+01 6.000000E+01 1 3.364986E+01 8.984338E+01 9.197762E-02 3.364973E+01 + 2.020004E+01 6.000000E+01 2 6.168205E+01 8.980224E+01 2.128942E-01 6.168168E+01 + 2.020004E+01 6.000000E+01 3 1.658120E+02 6.524107E-01 1.658013E+02 1.888013E+00 + 2.020004E+01 6.000000E+01 4 2.108919E+02 8.980223E+01 7.279456E-01 2.108907E+02 + 2.020004E+01 6.000000E+01 5 3.096325E+02 8.984337E+01 8.464613E-01 3.096313E+02 + 2.020004E+01 6.000000E+01 6 1.397670E+02 -5.229436E-03 1.397670E+02 -1.275665E-02 + 2.020004E+01 9.000000E+01 1 3.527041E-06 -9.007518E+01 -4.628080E-09 -3.527038E-06 + 2.020004E+01 9.000000E+01 2 7.186182E+01 8.980219E+01 2.480940E-01 7.186139E+01 + 2.020004E+01 9.000000E+01 3 1.673397E+02 6.553698E-01 1.673287E+02 1.914050E+00 + 2.020004E+01 9.000000E+01 4 2.473715E+02 8.980352E+01 8.483040E-01 2.473701E+02 + 2.020004E+01 9.000000E+01 5 1.563432E-04 -8.996829E+01 8.653625E-08 -1.563432E-04 + 2.020004E+01 9.000000E+01 6 1.208725E-05 1.799965E+02 -1.208725E-05 7.351357E-10 + 2.030004E+01 0.000000E+00 1 6.537163E+01 8.984496E+01 1.768856E-01 6.537139E+01 + 2.030004E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.030004E+01 0.000000E+00 3 1.617542E+02 6.367794E-01 1.617442E+02 1.797682E+00 + 2.030004E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.030004E+01 0.000000E+00 5 6.029449E+02 8.984496E+01 1.631472E+00 6.029427E+02 + 2.030004E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.030004E+01 3.000000E+01 1 5.706572E+01 8.984504E+01 1.543395E-01 5.706551E+01 + 2.030004E+01 3.000000E+01 2 3.480951E+01 8.980498E+01 1.184862E-01 3.480930E+01 + 2.030004E+01 3.000000E+01 3 1.632244E+02 6.396463E-01 1.632142E+02 1.822188E+00 + 2.030004E+01 3.000000E+01 4 1.172912E+02 8.980224E+01 4.048288E-01 1.172905E+02 + 2.030004E+01 3.000000E+01 5 5.263376E+02 8.984504E+01 1.423520E+00 5.263356E+02 + 2.030004E+01 3.000000E+01 6 1.357458E+02 -5.129692E-03 1.357458E+02 -1.215333E-02 + 2.030004E+01 6.000000E+01 1 3.347633E+01 8.984518E+01 9.046014E-02 3.347621E+01 + 2.030004E+01 6.000000E+01 2 6.136294E+01 8.980487E+01 2.089788E-01 6.136259E+01 + 2.030004E+01 6.000000E+01 3 1.662077E+02 6.453947E-01 1.661971E+02 1.872167E+00 + 2.030004E+01 6.000000E+01 4 2.096410E+02 8.980486E+01 7.140174E-01 2.096398E+02 + 2.030004E+01 6.000000E+01 5 3.087147E+02 8.984515E+01 8.343419E-01 3.087136E+02 + 2.030004E+01 6.000000E+01 6 1.382186E+02 -5.098135E-03 1.382186E+02 -1.229859E-02 + 2.030004E+01 9.000000E+01 1 3.508177E-06 -9.007504E+01 -4.593992E-09 -3.508174E-06 + 2.030004E+01 9.000000E+01 2 7.148273E+01 8.980482E+01 2.435053E-01 7.148232E+01 + 2.030004E+01 9.000000E+01 3 1.677212E+02 6.482777E-01 1.677105E+02 1.897655E+00 + 2.030004E+01 9.000000E+01 4 2.458635E+02 8.980611E+01 8.319848E-01 2.458621E+02 + 2.030004E+01 9.000000E+01 5 1.556109E-04 -8.996883E+01 8.464443E-08 -1.556108E-04 + 2.030004E+01 9.000000E+01 6 1.195181E-05 1.799966E+02 -1.195181E-05 7.088051E-10 + 2.040004E+01 0.000000E+00 1 6.505441E+01 8.984673E+01 1.740260E-01 6.505418E+01 + 2.040004E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.040004E+01 0.000000E+00 3 1.621866E+02 6.300892E-01 1.621768E+02 1.783551E+00 + 2.040004E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.040004E+01 0.000000E+00 5 6.013277E+02 8.984673E+01 1.608596E+00 6.013256E+02 + 2.040004E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.040004E+01 3.000000E+01 1 5.678340E+01 8.984679E+01 1.518325E-01 5.678320E+01 + 2.040004E+01 3.000000E+01 2 3.463754E+01 8.980754E+01 1.163479E-01 3.463734E+01 + 2.040004E+01 3.000000E+01 3 1.636433E+02 6.328843E-01 1.636333E+02 1.807553E+00 + 2.040004E+01 3.000000E+01 4 1.166399E+02 8.980488E+01 3.972221E-01 1.166392E+02 + 2.040004E+01 3.000000E+01 5 5.248781E+02 8.984680E+01 1.403457E+00 5.248762E+02 + 2.040004E+01 3.000000E+01 6 1.342797E+02 -5.001434E-03 1.342797E+02 -1.172147E-02 + 2.040004E+01 6.000000E+01 1 3.330465E+01 8.984693E+01 8.897616E-02 3.330453E+01 + 2.040004E+01 6.000000E+01 2 6.104716E+01 8.980745E+01 2.051624E-01 6.104681E+01 + 2.040004E+01 6.000000E+01 3 1.665987E+02 6.384989E-01 1.665884E+02 1.856522E+00 + 2.040004E+01 6.000000E+01 4 2.084066E+02 8.980743E+01 7.004500E-01 2.084054E+02 + 2.040004E+01 6.000000E+01 5 3.078017E+02 8.984691E+01 8.224401E-01 3.078006E+02 + 2.040004E+01 6.000000E+01 6 1.366971E+02 -4.971014E-03 1.366971E+02 -1.185991E-02 + 2.040004E+01 9.000000E+01 1 3.489508E-06 -9.007486E+01 -4.559416E-09 -3.489505E-06 + 2.040004E+01 9.000000E+01 2 7.110738E+01 8.980740E+01 2.390324E-01 7.110697E+01 + 2.040004E+01 9.000000E+01 3 1.680971E+02 6.413115E-01 1.680865E+02 1.881471E+00 + 2.040004E+01 9.000000E+01 4 2.443733E+02 8.980866E+01 8.160858E-01 2.443720E+02 + 2.040004E+01 9.000000E+01 5 1.548858E-04 -8.996937E+01 8.280615E-08 -1.548858E-04 + 2.040004E+01 9.000000E+01 6 1.181870E-05 1.799967E+02 -1.181870E-05 6.835885E-10 + 2.050004E+01 0.000000E+00 1 6.474009E+01 8.984846E+01 1.712274E-01 6.473986E+01 + 2.050004E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.050004E+01 0.000000E+00 3 1.626125E+02 6.234991E-01 1.626029E+02 1.769532E+00 + 2.050004E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.050004E+01 0.000000E+00 5 5.997079E+02 8.984846E+01 1.586125E+00 5.997059E+02 + 2.050004E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.050004E+01 3.000000E+01 1 5.650393E+01 8.984853E+01 1.493797E-01 5.650373E+01 + 2.050004E+01 3.000000E+01 2 3.446715E+01 8.981007E+01 1.142618E-01 3.446696E+01 + 2.050004E+01 3.000000E+01 3 1.640561E+02 6.262299E-01 1.640463E+02 1.793061E+00 + 2.050004E+01 3.000000E+01 4 1.159960E+02 8.980746E+01 3.898126E-01 1.159953E+02 + 2.050004E+01 3.000000E+01 5 5.234153E+02 8.984853E+01 1.383736E+00 5.234135E+02 + 2.050004E+01 3.000000E+01 6 1.328376E+02 -4.877278E-03 1.328376E+02 -1.130774E-02 + 2.050004E+01 6.000000E+01 1 3.313467E+01 8.984866E+01 8.752491E-02 3.313456E+01 + 2.050004E+01 6.000000E+01 2 6.073477E+01 8.980997E+01 2.014418E-01 6.073443E+01 + 2.050004E+01 6.000000E+01 3 1.669841E+02 6.317062E-01 1.669740E+02 1.841022E+00 + 2.050004E+01 6.000000E+01 4 2.071870E+02 8.980995E+01 6.872378E-01 2.071858E+02 + 2.050004E+01 6.000000E+01 5 3.068885E+02 8.984863E+01 8.107663E-01 3.068875E+02 + 2.050004E+01 6.000000E+01 6 1.352013E+02 -4.847961E-03 1.352013E+02 -1.143977E-02 + 2.050004E+01 9.000000E+01 1 3.471049E-06 -9.007468E+01 -4.524483E-09 -3.471046E-06 + 2.050004E+01 9.000000E+01 2 7.073632E+01 8.980992E+01 2.346719E-01 7.073593E+01 + 2.050004E+01 9.000000E+01 3 1.684690E+02 6.344550E-01 1.684587E+02 1.865475E+00 + 2.050004E+01 9.000000E+01 4 2.429040E+02 8.981116E+01 8.006036E-01 2.429027E+02 + 2.050004E+01 9.000000E+01 5 1.541678E-04 -8.996989E+01 8.102046E-08 -1.541678E-04 + 2.050004E+01 9.000000E+01 6 1.168791E-05 1.799968E+02 -1.168791E-05 6.594332E-10 + 2.060004E+01 0.000000E+00 1 6.442854E+01 8.985017E+01 1.684904E-01 6.442831E+01 + 2.060004E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.060004E+01 0.000000E+00 3 1.630331E+02 6.170130E-01 1.630237E+02 1.755655E+00 + 2.060004E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.060004E+01 0.000000E+00 5 5.980828E+02 8.985017E+01 1.564067E+00 5.980807E+02 + 2.060004E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.060004E+01 3.000000E+01 1 5.622699E+01 8.985023E+01 1.469798E-01 5.622680E+01 + 2.060004E+01 3.000000E+01 2 3.429849E+01 8.981253E+01 1.122268E-01 3.429831E+01 + 2.060004E+01 3.000000E+01 3 1.644636E+02 6.196801E-01 1.644540E+02 1.778714E+00 + 2.060004E+01 3.000000E+01 4 1.153591E+02 8.980998E+01 3.825918E-01 1.153585E+02 + 2.060004E+01 3.000000E+01 5 5.219458E+02 8.985023E+01 1.364384E+00 5.219440E+02 + 2.060004E+01 3.000000E+01 6 1.314194E+02 -4.757043E-03 1.314194E+02 -1.091124E-02 + 2.060004E+01 6.000000E+01 1 3.296656E+01 8.985035E+01 8.610546E-02 3.296645E+01 + 2.060004E+01 6.000000E+01 2 6.042552E+01 8.981243E+01 1.978129E-01 6.042519E+01 + 2.060004E+01 6.000000E+01 3 1.673642E+02 6.250291E-01 1.673542E+02 1.825709E+00 + 2.060004E+01 6.000000E+01 4 2.059819E+02 8.981242E+01 6.743651E-01 2.059808E+02 + 2.060004E+01 6.000000E+01 5 3.059727E+02 8.985033E+01 7.992912E-01 3.059717E+02 + 2.060004E+01 6.000000E+01 6 1.337309E+02 -4.728779E-03 1.337309E+02 -1.103718E-02 + 2.060004E+01 9.000000E+01 1 3.452798E-06 -9.007449E+01 -4.489176E-09 -3.452795E-06 + 2.060004E+01 9.000000E+01 2 7.036932E+01 8.981239E+01 2.304207E-01 7.036894E+01 + 2.060004E+01 9.000000E+01 3 1.688353E+02 6.277081E-01 1.688251E+02 1.849650E+00 + 2.060004E+01 9.000000E+01 4 2.414518E+02 8.981360E+01 7.855271E-01 2.414505E+02 + 2.060004E+01 9.000000E+01 5 1.534564E-04 -8.997040E+01 7.928448E-08 -1.534564E-04 + 2.060004E+01 9.000000E+01 6 1.155933E-05 1.799969E+02 -1.155933E-05 6.362832E-10 + 2.070004E+01 0.000000E+00 1 6.412022E+01 8.985184E+01 1.658124E-01 6.412000E+01 + 2.070004E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.070004E+01 0.000000E+00 3 1.634482E+02 6.106256E-01 1.634389E+02 1.741905E+00 + 2.070004E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.070004E+01 0.000000E+00 5 5.964514E+02 8.985184E+01 1.542398E+00 5.964493E+02 + 2.070004E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.070004E+01 3.000000E+01 1 5.595306E+01 8.985190E+01 1.446317E-01 5.595288E+01 + 2.070004E+01 3.000000E+01 2 3.413142E+01 8.981494E+01 1.102414E-01 3.413124E+01 + 2.070004E+01 3.000000E+01 3 1.648655E+02 6.132323E-01 1.648561E+02 1.764509E+00 + 2.070004E+01 3.000000E+01 4 1.147300E+02 8.981245E+01 3.755530E-01 1.147294E+02 + 2.070004E+01 3.000000E+01 5 5.204780E+02 8.985190E+01 1.345384E+00 5.204763E+02 + 2.070004E+01 3.000000E+01 6 1.300244E+02 -4.640601E-03 1.300244E+02 -1.053116E-02 + 2.070004E+01 6.000000E+01 1 3.280011E+01 8.985201E+01 8.471688E-02 3.280000E+01 + 2.070004E+01 6.000000E+01 2 6.011945E+01 8.981485E+01 1.942734E-01 6.011913E+01 + 2.070004E+01 6.000000E+01 3 1.677389E+02 6.184556E-01 1.677292E+02 1.810553E+00 + 2.070004E+01 6.000000E+01 4 2.047917E+02 8.981483E+01 6.618194E-01 2.047907E+02 + 2.070004E+01 6.000000E+01 5 3.050566E+02 8.985199E+01 7.880349E-01 3.050556E+02 + 2.070004E+01 6.000000E+01 6 1.322850E+02 -4.613339E-03 1.322850E+02 -1.065131E-02 + 2.070004E+01 9.000000E+01 1 3.434739E-06 -9.007429E+01 -4.453538E-09 -3.434736E-06 + 2.070004E+01 9.000000E+01 2 7.000589E+01 8.981481E+01 2.262746E-01 7.000552E+01 + 2.070004E+01 9.000000E+01 3 1.691965E+02 6.210708E-01 1.691866E+02 1.834009E+00 + 2.070004E+01 9.000000E+01 4 2.400188E+02 8.981599E+01 7.708381E-01 2.400176E+02 + 2.070004E+01 9.000000E+01 5 1.527502E-04 -8.997089E+01 7.759730E-08 -1.527502E-04 + 2.070004E+01 9.000000E+01 6 1.143296E-05 1.799969E+02 -1.143296E-05 6.140952E-10 + 2.080004E+01 0.000000E+00 1 6.381456E+01 8.985349E+01 1.631899E-01 6.381435E+01 + 2.080004E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.080004E+01 0.000000E+00 3 1.638572E+02 6.043389E-01 1.638481E+02 1.728285E+00 + 2.080004E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.080004E+01 0.000000E+00 5 5.948220E+02 8.985349E+01 1.521102E+00 5.948200E+02 + 2.080004E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.080004E+01 3.000000E+01 1 5.568153E+01 8.985354E+01 1.423347E-01 5.568134E+01 + 2.080004E+01 3.000000E+01 2 3.396597E+01 8.981731E+01 1.083039E-01 3.396580E+01 + 2.080004E+01 3.000000E+01 3 1.652620E+02 6.068804E-01 1.652527E+02 1.750433E+00 + 2.080004E+01 3.000000E+01 4 1.141076E+02 8.981487E+01 3.686909E-01 1.141070E+02 + 2.080004E+01 3.000000E+01 5 5.190084E+02 8.985354E+01 1.326702E+00 5.190067E+02 + 2.080004E+01 3.000000E+01 6 1.286520E+02 -4.527792E-03 1.286520E+02 -1.016671E-02 + 2.080004E+01 6.000000E+01 1 3.263537E+01 8.985365E+01 8.335859E-02 3.263527E+01 + 2.080004E+01 6.000000E+01 2 5.981660E+01 8.981722E+01 1.908207E-01 5.981630E+01 + 2.080004E+01 6.000000E+01 3 1.681095E+02 6.119814E-01 1.680999E+02 1.795558E+00 + 2.080004E+01 6.000000E+01 4 2.036151E+02 8.981721E+01 6.495958E-01 2.036141E+02 + 2.080004E+01 6.000000E+01 5 3.041458E+02 8.985363E+01 7.769811E-01 3.041448E+02 + 2.080004E+01 6.000000E+01 6 1.308632E+02 -4.501495E-03 1.308632E+02 -1.028139E-02 + 2.080004E+01 9.000000E+01 1 3.416880E-06 -9.007407E+01 -4.417677E-09 -3.416877E-06 + 2.080004E+01 9.000000E+01 2 6.964664E+01 8.981718E+01 2.222306E-01 6.964629E+01 + 2.080004E+01 9.000000E+01 3 1.695526E+02 6.145399E-01 1.695428E+02 1.818543E+00 + 2.080004E+01 9.000000E+01 4 2.386036E+02 8.981834E+01 7.565217E-01 2.386024E+02 + 2.080004E+01 9.000000E+01 5 1.520502E-04 -8.997137E+01 7.595667E-08 -1.520501E-04 + 2.080004E+01 9.000000E+01 6 1.130872E-05 1.799970E+02 -1.130872E-05 5.928200E-10 + 2.090004E+01 0.000000E+00 1 6.351139E+01 8.985509E+01 1.606237E-01 6.351119E+01 + 2.090004E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.090004E+01 0.000000E+00 3 1.642611E+02 5.981480E-01 1.642521E+02 1.714797E+00 + 2.090004E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.090004E+01 0.000000E+00 5 5.931834E+02 8.985510E+01 1.500171E+00 5.931815E+02 + 2.090004E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.090004E+01 3.000000E+01 1 5.541267E+01 8.985516E+01 1.400858E-01 5.541249E+01 + 2.090004E+01 3.000000E+01 2 3.380206E+01 8.981963E+01 1.064127E-01 3.380189E+01 + 2.090004E+01 3.000000E+01 3 1.656524E+02 6.006361E-01 1.656433E+02 1.736515E+00 + 2.090004E+01 3.000000E+01 4 1.134919E+02 8.981725E+01 3.619986E-01 1.134913E+02 + 2.090004E+01 3.000000E+01 5 5.175372E+02 8.985516E+01 1.308356E+00 5.175355E+02 + 2.090004E+01 3.000000E+01 6 1.273019E+02 -4.418476E-03 1.273019E+02 -9.817134E-03 + 2.090004E+01 6.000000E+01 1 3.247225E+01 8.985526E+01 8.202945E-02 3.247215E+01 + 2.090004E+01 6.000000E+01 2 5.951677E+01 8.981954E+01 1.874512E-01 5.951647E+01 + 2.090004E+01 6.000000E+01 3 1.684745E+02 6.056167E-01 1.684651E+02 1.780743E+00 + 2.090004E+01 6.000000E+01 4 2.024531E+02 8.981953E+01 6.376822E-01 2.024521E+02 + 2.090004E+01 6.000000E+01 5 3.032299E+02 8.985524E+01 7.661338E-01 3.032289E+02 + 2.090004E+01 6.000000E+01 6 1.294651E+02 -4.393109E-03 1.294651E+02 -9.926637E-03 + 2.090004E+01 9.000000E+01 1 3.399201E-06 -9.007386E+01 -4.381584E-09 -3.399198E-06 + 2.090004E+01 9.000000E+01 2 6.929110E+01 8.981950E+01 2.182860E-01 6.929076E+01 + 2.090004E+01 9.000000E+01 3 1.699045E+02 6.081139E-01 1.698949E+02 1.803263E+00 + 2.090004E+01 9.000000E+01 4 2.372046E+02 8.982063E+01 7.425726E-01 2.372035E+02 + 2.090004E+01 9.000000E+01 5 1.513574E-04 -8.997185E+01 7.436127E-08 -1.513574E-04 + 2.090004E+01 9.000000E+01 6 1.118656E-05 1.799971E+02 -1.118656E-05 5.724159E-10 + 2.100004E+01 0.000000E+00 1 6.321159E+01 8.985669E+01 1.581123E-01 6.321140E+01 + 2.100004E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.100004E+01 0.000000E+00 3 1.646583E+02 5.920571E-01 1.646495E+02 1.701441E+00 + 2.100004E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.100004E+01 0.000000E+00 5 5.915450E+02 8.985669E+01 1.479630E+00 5.915432E+02 + 2.100004E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.100004E+01 3.000000E+01 1 5.514629E+01 8.985674E+01 1.378856E-01 5.514612E+01 + 2.100004E+01 3.000000E+01 2 3.363964E+01 8.982190E+01 1.045666E-01 3.363948E+01 + 2.100004E+01 3.000000E+01 3 1.660384E+02 5.944797E-01 1.660295E+02 1.722722E+00 + 2.100004E+01 3.000000E+01 4 1.128829E+02 8.981958E+01 3.554713E-01 1.128823E+02 + 2.100004E+01 3.000000E+01 5 5.160685E+02 8.985674E+01 1.290331E+00 5.160669E+02 + 2.100004E+01 3.000000E+01 6 1.259733E+02 -4.312538E-03 1.259733E+02 -9.481760E-03 + 2.100004E+01 6.000000E+01 1 3.231078E+01 8.985685E+01 8.072911E-02 3.231068E+01 + 2.100004E+01 6.000000E+01 2 5.922005E+01 8.982182E+01 1.841640E-01 5.921976E+01 + 2.100004E+01 6.000000E+01 3 1.688344E+02 5.993465E-01 1.688251E+02 1.766071E+00 + 2.100004E+01 6.000000E+01 4 2.013048E+02 8.982181E+01 6.260641E-01 2.013038E+02 + 2.100004E+01 6.000000E+01 5 3.023165E+02 8.985682E+01 7.554740E-01 3.023156E+02 + 2.100004E+01 6.000000E+01 6 1.280900E+02 -4.288050E-03 1.280900E+02 -9.586333E-03 + 2.100004E+01 9.000000E+01 1 3.381708E-06 -9.007362E+01 -4.345329E-09 -3.381705E-06 + 2.100004E+01 9.000000E+01 2 6.893932E+01 8.982178E+01 2.144361E-01 6.893898E+01 + 2.100004E+01 9.000000E+01 3 1.702522E+02 6.017843E-01 1.702428E+02 1.788146E+00 + 2.100004E+01 9.000000E+01 4 2.358240E+02 8.982289E+01 7.289737E-01 2.358228E+02 + 2.100004E+01 9.000000E+01 5 1.506705E-04 -8.997231E+01 7.281010E-08 -1.506704E-04 + 2.100004E+01 9.000000E+01 6 1.106645E-05 1.799971E+02 -1.106645E-05 5.528405E-10 + 2.110004E+01 0.000000E+00 1 6.291412E+01 8.985825E+01 1.556526E-01 6.291393E+01 + 2.110004E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.110004E+01 0.000000E+00 3 1.650519E+02 5.860521E-01 1.650433E+02 1.688211E+00 + 2.110004E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.110004E+01 0.000000E+00 5 5.899127E+02 8.985825E+01 1.459441E+00 5.899108E+02 + 2.110004E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.110004E+01 3.000000E+01 1 5.488240E+01 8.985831E+01 1.357310E-01 5.488223E+01 + 2.110004E+01 3.000000E+01 2 3.347894E+01 8.982413E+01 1.027637E-01 3.347878E+01 + 2.110004E+01 3.000000E+01 3 1.664191E+02 5.884231E-01 1.664103E+02 1.709080E+00 + 2.110004E+01 3.000000E+01 4 1.122806E+02 8.982185E+01 3.491066E-01 1.122801E+02 + 2.110004E+01 3.000000E+01 5 5.145932E+02 8.985831E+01 1.272644E+00 5.145916E+02 + 2.110004E+01 3.000000E+01 6 1.246663E+02 -4.209812E-03 1.246663E+02 -9.159866E-03 + 2.110004E+01 6.000000E+01 1 3.215103E+01 8.985840E+01 7.945626E-02 3.215093E+01 + 2.110004E+01 6.000000E+01 2 5.892637E+01 8.982405E+01 1.809549E-01 5.892609E+01 + 2.110004E+01 6.000000E+01 3 1.691900E+02 5.931741E-01 1.691809E+02 1.751566E+00 + 2.110004E+01 6.000000E+01 4 2.001701E+02 8.982404E+01 6.147355E-01 2.001692E+02 + 2.110004E+01 6.000000E+01 5 3.014066E+02 8.985838E+01 7.450023E-01 3.014057E+02 + 2.110004E+01 6.000000E+01 6 1.267374E+02 -4.186208E-03 1.267374E+02 -9.259829E-03 + 2.110004E+01 9.000000E+01 1 3.364417E-06 -9.007338E+01 -4.308923E-09 -3.364414E-06 + 2.110004E+01 9.000000E+01 2 6.859097E+01 8.982402E+01 2.106795E-01 6.859065E+01 + 2.110004E+01 9.000000E+01 3 1.705944E+02 5.955566E-01 1.705852E+02 1.773198E+00 + 2.110004E+01 9.000000E+01 4 2.344595E+02 8.982510E+01 7.157160E-01 2.344584E+02 + 2.110004E+01 9.000000E+01 5 1.499893E-04 -8.997276E+01 7.130098E-08 -1.499893E-04 + 2.110004E+01 9.000000E+01 6 1.094833E-05 1.799972E+02 -1.094833E-05 5.340559E-10 + 2.120004E+01 0.000000E+00 1 6.261952E+01 8.985979E+01 1.532447E-01 6.261933E+01 + 2.120004E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.120004E+01 0.000000E+00 3 1.654395E+02 5.801370E-01 1.654310E+02 1.675096E+00 + 2.120004E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.120004E+01 0.000000E+00 5 5.882706E+02 8.985979E+01 1.439604E+00 5.882689E+02 + 2.120004E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.120004E+01 3.000000E+01 1 5.462117E+01 8.985983E+01 1.336218E-01 5.462101E+01 + 2.120004E+01 3.000000E+01 2 3.331966E+01 8.982632E+01 1.010039E-01 3.331951E+01 + 2.120004E+01 3.000000E+01 3 1.667948E+02 5.824519E-01 1.667862E+02 1.695557E+00 + 2.120004E+01 3.000000E+01 4 1.116853E+02 8.982409E+01 3.428971E-01 1.116847E+02 + 2.120004E+01 3.000000E+01 5 5.131204E+02 8.985983E+01 1.255259E+00 5.131188E+02 + 2.120004E+01 3.000000E+01 6 1.233801E+02 -4.110220E-03 1.233801E+02 -8.850900E-03 + 2.120004E+01 6.000000E+01 1 3.199291E+01 8.985994E+01 7.821047E-02 3.199281E+01 + 2.120004E+01 6.000000E+01 2 5.863548E+01 8.982624E+01 1.778218E-01 5.863521E+01 + 2.120004E+01 6.000000E+01 3 1.695406E+02 5.871015E-01 1.695318E+02 1.737228E+00 + 2.120004E+01 6.000000E+01 4 1.990490E+02 8.982623E+01 6.036870E-01 1.990481E+02 + 2.120004E+01 6.000000E+01 5 3.004943E+02 8.985991E+01 7.347198E-01 3.004934E+02 + 2.120004E+01 6.000000E+01 6 1.254070E+02 -4.087419E-03 1.254070E+02 -8.946401E-03 + 2.120004E+01 9.000000E+01 1 3.347297E-06 -9.007314E+01 -4.272425E-09 -3.347295E-06 + 2.120004E+01 9.000000E+01 2 6.824651E+01 8.982620E+01 2.070131E-01 6.824620E+01 + 2.120004E+01 9.000000E+01 3 1.709321E+02 5.894273E-01 1.709230E+02 1.758423E+00 + 2.120004E+01 9.000000E+01 4 2.331120E+02 8.982727E+01 7.027883E-01 2.331109E+02 + 2.120004E+01 9.000000E+01 5 1.493142E-04 -8.997321E+01 6.983249E-08 -1.493142E-04 + 2.120004E+01 9.000000E+01 6 1.083215E-05 1.799973E+02 -1.083215E-05 5.160244E-10 + 2.130005E+01 0.000000E+00 1 6.232783E+01 8.986130E+01 1.508870E-01 6.232764E+01 + 2.130005E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.130005E+01 0.000000E+00 3 1.658223E+02 5.743163E-01 1.658140E+02 1.662127E+00 + 2.130005E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.130005E+01 0.000000E+00 5 5.866271E+02 8.986130E+01 1.420107E+00 5.866254E+02 + 2.130005E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.130005E+01 3.000000E+01 1 5.436221E+01 8.986134E+01 1.315567E-01 5.436205E+01 + 2.130005E+01 3.000000E+01 2 3.316186E+01 8.982846E+01 9.928485E-02 3.316171E+01 + 2.130005E+01 3.000000E+01 3 1.671654E+02 5.765816E-01 1.671569E+02 1.682198E+00 + 2.130005E+01 3.000000E+01 4 1.110960E+02 8.982629E+01 3.368384E-01 1.110955E+02 + 2.130005E+01 3.000000E+01 5 5.116482E+02 8.986134E+01 1.238179E+00 5.116467E+02 + 2.130005E+01 3.000000E+01 6 1.221137E+02 -4.013660E-03 1.221137E+02 -8.554257E-03 + 2.130005E+01 6.000000E+01 1 3.183622E+01 8.986144E+01 7.699062E-02 3.183612E+01 + 2.130005E+01 6.000000E+01 2 5.834761E+01 8.982839E+01 1.747638E-01 5.834734E+01 + 2.130005E+01 6.000000E+01 3 1.698870E+02 5.811199E-01 1.698782E+02 1.723041E+00 + 2.130005E+01 6.000000E+01 4 1.979413E+02 8.982838E+01 5.929118E-01 1.979405E+02 + 2.130005E+01 6.000000E+01 5 2.995831E+02 8.986142E+01 7.246204E-01 2.995822E+02 + 2.130005E+01 6.000000E+01 6 1.240979E+02 -3.991625E-03 1.240979E+02 -8.645531E-03 + 2.130005E+01 9.000000E+01 1 3.330355E-06 -9.007288E+01 -4.235849E-09 -3.330353E-06 + 2.130005E+01 9.000000E+01 2 6.790550E+01 8.982835E+01 2.034333E-01 6.790520E+01 + 2.130005E+01 9.000000E+01 3 1.712655E+02 5.833960E-01 1.712566E+02 1.743826E+00 + 2.130005E+01 9.000000E+01 4 2.317809E+02 8.982939E+01 6.901794E-01 2.317798E+02 + 2.130005E+01 9.000000E+01 5 1.486448E-04 -8.997363E+01 6.840413E-08 -1.486447E-04 + 2.130005E+01 9.000000E+01 6 1.071788E-05 1.799973E+02 -1.071788E-05 4.987119E-10 + 2.140005E+01 0.000000E+00 1 6.203843E+01 8.986279E+01 1.485775E-01 6.203825E+01 + 2.140005E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.140005E+01 0.000000E+00 3 1.662000E+02 5.685813E-01 1.661918E+02 1.649278E+00 + 2.140005E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.140005E+01 0.000000E+00 5 5.849853E+02 8.986279E+01 1.400969E+00 5.849836E+02 + 2.140005E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.140005E+01 3.000000E+01 1 5.410566E+01 8.986282E+01 1.295345E-01 5.410550E+01 + 2.140005E+01 3.000000E+01 2 3.300554E+01 8.983056E+01 9.760576E-02 3.300539E+01 + 2.140005E+01 3.000000E+01 3 1.675312E+02 5.707949E-01 1.675228E+02 1.668960E+00 + 2.140005E+01 3.000000E+01 4 1.105131E+02 8.982843E+01 3.309246E-01 1.105126E+02 + 2.140005E+01 3.000000E+01 5 5.101770E+02 8.986283E+01 1.221408E+00 5.101755E+02 + 2.140005E+01 3.000000E+01 6 1.208675E+02 -3.919979E-03 1.208675E+02 -8.269336E-03 + 2.140005E+01 6.000000E+01 1 3.168116E+01 8.986292E+01 7.579711E-02 3.168107E+01 + 2.140005E+01 6.000000E+01 2 5.806268E+01 8.983049E+01 1.717770E-01 5.806242E+01 + 2.140005E+01 6.000000E+01 3 1.702287E+02 5.752325E-01 1.702201E+02 1.709016E+00 + 2.140005E+01 6.000000E+01 4 1.968455E+02 8.983048E+01 5.823973E-01 1.968446E+02 + 2.140005E+01 6.000000E+01 5 2.986749E+02 8.986290E+01 7.146987E-01 2.986740E+02 + 2.140005E+01 6.000000E+01 6 1.228098E+02 -3.898692E-03 1.228098E+02 -8.356597E-03 + 2.140005E+01 9.000000E+01 1 3.313598E-06 -9.007261E+01 -4.199223E-09 -3.313595E-06 + 2.140005E+01 9.000000E+01 2 6.756801E+01 8.983046E+01 1.999397E-01 6.756771E+01 + 2.140005E+01 9.000000E+01 3 1.715948E+02 5.774541E-01 1.715860E+02 1.729384E+00 + 2.140005E+01 9.000000E+01 4 2.304656E+02 8.983147E+01 6.778837E-01 2.304646E+02 + 2.140005E+01 9.000000E+01 5 1.479810E-04 -8.997405E+01 6.701373E-08 -1.479809E-04 + 2.140005E+01 9.000000E+01 6 1.060548E-05 1.799974E+02 -1.060548E-05 4.820866E-10 + 2.150005E+01 0.000000E+00 1 6.175196E+01 8.986425E+01 1.463160E-01 6.175179E+01 + 2.150005E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.150005E+01 0.000000E+00 3 1.665725E+02 5.629305E-01 1.665645E+02 1.636547E+00 + 2.150005E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.150005E+01 0.000000E+00 5 5.833430E+02 8.986425E+01 1.382147E+00 5.833413E+02 + 2.150005E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.150005E+01 3.000000E+01 1 5.385172E+01 8.986429E+01 1.275541E-01 5.385157E+01 + 2.150005E+01 3.000000E+01 2 3.285075E+01 8.983263E+01 9.596533E-02 3.285061E+01 + 2.150005E+01 3.000000E+01 3 1.678927E+02 5.650940E-01 1.678846E+02 1.655857E+00 + 2.150005E+01 3.000000E+01 4 1.099366E+02 8.983054E+01 3.251544E-01 1.099361E+02 + 2.150005E+01 3.000000E+01 5 5.087033E+02 8.986429E+01 1.204916E+00 5.087019E+02 + 2.150005E+01 3.000000E+01 6 1.196407E+02 -3.829093E-03 1.196407E+02 -7.995619E-03 + 2.150005E+01 6.000000E+01 1 3.152754E+01 8.986438E+01 7.462784E-02 3.152746E+01 + 2.150005E+01 6.000000E+01 2 5.778044E+01 8.983256E+01 1.688604E-01 5.778019E+01 + 2.150005E+01 6.000000E+01 3 1.705653E+02 5.694318E-01 1.705569E+02 1.695129E+00 + 2.150005E+01 6.000000E+01 4 1.957619E+02 8.983255E+01 5.721402E-01 1.957611E+02 + 2.150005E+01 6.000000E+01 5 2.977689E+02 8.986436E+01 7.049621E-01 2.977680E+02 + 2.150005E+01 6.000000E+01 6 1.215423E+02 -3.808532E-03 1.215423E+02 -8.079089E-03 + 2.150005E+01 9.000000E+01 1 3.297014E-06 -9.007234E+01 -4.162584E-09 -3.297011E-06 + 2.150005E+01 9.000000E+01 2 6.723403E+01 8.983252E+01 1.965273E-01 6.723374E+01 + 2.150005E+01 9.000000E+01 3 1.719196E+02 5.716041E-01 1.719111E+02 1.715106E+00 + 2.150005E+01 9.000000E+01 4 2.291658E+02 8.983352E+01 6.658836E-01 2.291648E+02 + 2.150005E+01 9.000000E+01 5 1.473238E-04 -8.997446E+01 6.566022E-08 -1.473238E-04 + 2.150005E+01 9.000000E+01 6 1.049490E-05 1.799975E+02 -1.049490E-05 4.661145E-10 + 2.160005E+01 0.000000E+00 1 6.146769E+01 8.986568E+01 1.441004E-01 6.146752E+01 + 2.160005E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.160005E+01 0.000000E+00 3 1.669404E+02 5.573655E-01 1.669325E+02 1.623948E+00 + 2.160005E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.160005E+01 0.000000E+00 5 5.816965E+02 8.986568E+01 1.363655E+00 5.816949E+02 + 2.160005E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.160005E+01 3.000000E+01 1 5.359994E+01 8.986572E+01 1.256144E-01 5.359979E+01 + 2.160005E+01 3.000000E+01 2 3.269737E+01 8.983465E+01 9.436276E-02 3.269723E+01 + 2.160005E+01 3.000000E+01 3 1.682483E+02 5.594834E-01 1.682403E+02 1.642890E+00 + 2.160005E+01 3.000000E+01 4 1.093665E+02 8.983261E+01 3.195192E-01 1.093660E+02 + 2.160005E+01 3.000000E+01 5 5.072311E+02 8.986572E+01 1.188723E+00 5.072297E+02 + 2.160005E+01 3.000000E+01 6 1.184330E+02 -3.740890E-03 1.184330E+02 -7.732589E-03 + 2.160005E+01 6.000000E+01 1 3.137555E+01 8.986581E+01 7.348310E-02 3.137546E+01 + 2.160005E+01 6.000000E+01 2 5.750114E+01 8.983458E+01 1.660112E-01 5.750090E+01 + 2.160005E+01 6.000000E+01 3 1.708976E+02 5.637235E-01 1.708893E+02 1.681405E+00 + 2.160005E+01 6.000000E+01 4 1.946926E+02 8.983457E+01 5.621283E-01 1.946917E+02 + 2.160005E+01 6.000000E+01 5 2.968618E+02 8.986579E+01 6.953874E-01 2.968609E+02 + 2.160005E+01 6.000000E+01 6 1.202948E+02 -3.721021E-03 1.202948E+02 -7.812435E-03 + 2.160005E+01 9.000000E+01 1 3.280595E-06 -9.007206E+01 -4.125944E-09 -3.280593E-06 + 2.160005E+01 9.000000E+01 2 6.690331E+01 8.983455E+01 1.931945E-01 6.690302E+01 + 2.160005E+01 9.000000E+01 3 1.722387E+02 5.658488E-01 1.722303E+02 1.700989E+00 + 2.160005E+01 9.000000E+01 4 2.278819E+02 8.983553E+01 6.541724E-01 2.278809E+02 + 2.160005E+01 9.000000E+01 5 1.466718E-04 -8.997487E+01 6.434252E-08 -1.466718E-04 + 2.160005E+01 9.000000E+01 6 1.038609E-05 1.799975E+02 -1.038609E-05 4.507669E-10 + 2.170005E+01 0.000000E+00 1 6.118621E+01 8.986710E+01 1.419300E-01 6.118605E+01 + 2.170005E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.170005E+01 0.000000E+00 3 1.673034E+02 5.518878E-01 1.672957E+02 1.611485E+00 + 2.170005E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.170005E+01 0.000000E+00 5 5.800552E+02 8.986710E+01 1.345487E+00 5.800536E+02 + 2.170005E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.170005E+01 3.000000E+01 1 5.335066E+01 8.986713E+01 1.237141E-01 5.335051E+01 + 2.170005E+01 3.000000E+01 2 3.254532E+01 8.983663E+01 9.279647E-02 3.254519E+01 + 2.170005E+01 3.000000E+01 3 1.686000E+02 5.539546E-01 1.685921E+02 1.630056E+00 + 2.170005E+01 3.000000E+01 4 1.088019E+02 8.983464E+01 3.140184E-01 1.088015E+02 + 2.170005E+01 3.000000E+01 5 5.057626E+02 8.986714E+01 1.172791E+00 5.057612E+02 + 2.170005E+01 3.000000E+01 6 1.172439E+02 -3.655281E-03 1.172439E+02 -7.479773E-03 + 2.170005E+01 6.000000E+01 1 3.122495E+01 8.986722E+01 7.236214E-02 3.122487E+01 + 2.170005E+01 6.000000E+01 2 5.722442E+01 8.983657E+01 1.632275E-01 5.722419E+01 + 2.170005E+01 6.000000E+01 3 1.712260E+02 5.581045E-01 1.712178E+02 1.667845E+00 + 2.170005E+01 6.000000E+01 4 1.936340E+02 8.983656E+01 5.523558E-01 1.936332E+02 + 2.170005E+01 6.000000E+01 5 2.959577E+02 8.986720E+01 6.859781E-01 2.959569E+02 + 2.170005E+01 6.000000E+01 6 1.190674E+02 -3.636078E-03 1.190674E+02 -7.556202E-03 + 2.170005E+01 9.000000E+01 1 3.264335E-06 -9.007178E+01 -4.089379E-09 -3.264332E-06 + 2.170005E+01 9.000000E+01 2 6.657600E+01 8.983654E+01 1.899386E-01 6.657572E+01 + 2.170005E+01 9.000000E+01 3 1.725552E+02 5.601832E-01 1.725470E+02 1.687053E+00 + 2.170005E+01 9.000000E+01 4 2.266125E+02 8.983749E+01 6.427448E-01 2.266116E+02 + 2.170005E+01 9.000000E+01 5 1.460258E-04 -8.997526E+01 6.305931E-08 -1.460258E-04 + 2.170005E+01 9.000000E+01 6 1.027902E-05 1.799976E+02 -1.027902E-05 4.360170E-10 + 2.180005E+01 0.000000E+00 1 6.090726E+01 8.986848E+01 1.398032E-01 6.090710E+01 + 2.180005E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.180005E+01 0.000000E+00 3 1.676612E+02 5.464816E-01 1.676535E+02 1.599112E+00 + 2.180005E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.180005E+01 0.000000E+00 5 5.784138E+02 8.986848E+01 1.327620E+00 5.784122E+02 + 2.180005E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.180005E+01 3.000000E+01 1 5.310334E+01 8.986853E+01 1.218527E-01 5.310320E+01 + 2.180005E+01 3.000000E+01 2 3.239473E+01 8.983858E+01 9.126551E-02 3.239460E+01 + 2.180005E+01 3.000000E+01 3 1.689474E+02 5.485032E-01 1.689396E+02 1.617340E+00 + 2.180005E+01 3.000000E+01 4 1.082436E+02 8.983662E+01 3.086476E-01 1.082431E+02 + 2.180005E+01 3.000000E+01 5 5.042939E+02 8.986853E+01 1.157151E+00 5.042926E+02 + 2.180005E+01 3.000000E+01 6 1.160730E+02 -3.572175E-03 1.160730E+02 -7.236714E-03 + 2.180005E+01 6.000000E+01 1 3.107590E+01 8.986861E+01 7.126382E-02 3.107582E+01 + 2.180005E+01 6.000000E+01 2 5.695058E+01 8.983852E+01 1.605081E-01 5.695035E+01 + 2.180005E+01 6.000000E+01 3 1.715500E+02 5.525618E-01 1.715420E+02 1.654407E+00 + 2.180005E+01 6.000000E+01 4 1.925879E+02 8.983851E+01 5.428147E-01 1.925871E+02 + 2.180005E+01 6.000000E+01 5 2.950564E+02 8.986858E+01 6.767493E-01 2.950557E+02 + 2.180005E+01 6.000000E+01 6 1.178590E+02 -3.553607E-03 1.178590E+02 -7.309865E-03 + 2.180005E+01 9.000000E+01 1 3.248258E-06 -9.007149E+01 -4.052839E-09 -3.248256E-06 + 2.180005E+01 9.000000E+01 2 6.625190E+01 8.983849E+01 1.867585E-01 6.625163E+01 + 2.180005E+01 9.000000E+01 3 1.728678E+02 5.545917E-01 1.728596E+02 1.673239E+00 + 2.180005E+01 9.000000E+01 4 2.253576E+02 8.983942E+01 6.315912E-01 2.253568E+02 + 2.180005E+01 9.000000E+01 5 1.453838E-04 -8.997564E+01 6.181024E-08 -1.453838E-04 + 2.180005E+01 9.000000E+01 6 1.017367E-05 1.799976E+02 -1.017367E-05 4.218362E-10 + 2.190005E+01 0.000000E+00 1 6.063079E+01 8.986986E+01 1.377197E-01 6.063063E+01 + 2.190005E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.190005E+01 0.000000E+00 3 1.680152E+02 5.411572E-01 1.680077E+02 1.586875E+00 + 2.190005E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.190005E+01 0.000000E+00 5 5.767661E+02 8.986986E+01 1.310061E+00 5.767646E+02 + 2.190005E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.190005E+01 3.000000E+01 1 5.285872E+01 8.986990E+01 1.200289E-01 5.285858E+01 + 2.190005E+01 3.000000E+01 2 3.224557E+01 8.984049E+01 8.976915E-02 3.224544E+01 + 2.190005E+01 3.000000E+01 3 1.692900E+02 5.431344E-01 1.692824E+02 1.604757E+00 + 2.190005E+01 3.000000E+01 4 1.076909E+02 8.983858E+01 3.034011E-01 1.076905E+02 + 2.190005E+01 3.000000E+01 5 5.028245E+02 8.986990E+01 1.141775E+00 5.028232E+02 + 2.190005E+01 3.000000E+01 6 1.149203E+02 -3.491472E-03 1.149203E+02 -7.002978E-03 + 2.190005E+01 6.000000E+01 1 3.092817E+01 8.986998E+01 7.018826E-02 3.092809E+01 + 2.190005E+01 6.000000E+01 2 5.667926E+01 8.984044E+01 1.578502E-01 5.667904E+01 + 2.190005E+01 6.000000E+01 3 1.718700E+02 5.471047E-01 1.718622E+02 1.641123E+00 + 2.190005E+01 6.000000E+01 4 1.915538E+02 8.984042E+01 5.335016E-01 1.915531E+02 + 2.190005E+01 6.000000E+01 5 2.941549E+02 8.986995E+01 6.676727E-01 2.941541E+02 + 2.190005E+01 6.000000E+01 6 1.166695E+02 -3.473520E-03 1.166695E+02 -7.073014E-03 + 2.190005E+01 9.000000E+01 1 3.232331E-06 -9.007120E+01 -4.016376E-09 -3.232328E-06 + 2.190005E+01 9.000000E+01 2 6.593121E+01 8.984040E+01 1.836506E-01 6.593095E+01 + 2.190005E+01 9.000000E+01 3 1.731751E+02 5.490936E-01 1.731672E+02 1.659597E+00 + 2.190005E+01 9.000000E+01 4 2.241180E+02 8.984132E+01 6.207018E-01 2.241171E+02 + 2.190005E+01 9.000000E+01 5 1.447487E-04 -8.997601E+01 6.059328E-08 -1.447486E-04 + 2.190005E+01 9.000000E+01 6 1.006997E-05 1.799977E+02 -1.006997E-05 4.081997E-10 + 2.200005E+01 0.000000E+00 1 6.035680E+01 8.987121E+01 1.356777E-01 6.035665E+01 + 2.200005E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.200005E+01 0.000000E+00 3 1.683641E+02 5.359118E-01 1.683568E+02 1.574758E+00 + 2.200005E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.200005E+01 0.000000E+00 5 5.751278E+02 8.987121E+01 1.292816E+00 5.751263E+02 + 2.200005E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.200005E+01 3.000000E+01 1 5.261614E+01 8.987124E+01 1.182418E-01 5.261601E+01 + 2.200005E+01 3.000000E+01 2 3.209763E+01 8.984237E+01 8.830625E-02 3.209751E+01 + 2.200005E+01 3.000000E+01 3 1.696278E+02 5.378510E-01 1.696203E+02 1.592319E+00 + 2.200005E+01 3.000000E+01 4 1.071438E+02 8.984050E+01 2.982757E-01 1.071434E+02 + 2.200005E+01 3.000000E+01 5 5.013560E+02 8.987124E+01 1.126672E+00 5.013547E+02 + 2.200005E+01 3.000000E+01 6 1.137848E+02 -3.413100E-03 1.137848E+02 -6.778141E-03 + 2.200005E+01 6.000000E+01 1 3.078190E+01 8.987132E+01 6.913461E-02 3.078182E+01 + 2.200005E+01 6.000000E+01 2 5.641064E+01 8.984232E+01 1.552524E-01 5.641043E+01 + 2.200005E+01 6.000000E+01 3 1.721860E+02 5.417319E-01 1.721783E+02 1.627995E+00 + 2.200005E+01 6.000000E+01 4 1.905308E+02 8.984230E+01 5.244043E-01 1.905301E+02 + 2.200005E+01 6.000000E+01 5 2.932545E+02 8.987129E+01 6.587522E-01 2.932538E+02 + 2.200005E+01 6.000000E+01 6 1.154984E+02 -3.395742E-03 1.154984E+02 -6.845228E-03 + 2.200005E+01 9.000000E+01 1 3.216569E-06 -9.007089E+01 -3.980032E-09 -3.216566E-06 + 2.200005E+01 9.000000E+01 2 6.561368E+01 8.984228E+01 1.806138E-01 6.561343E+01 + 2.200005E+01 9.000000E+01 3 1.734805E+02 5.436727E-01 1.734727E+02 1.646111E+00 + 2.200005E+01 9.000000E+01 4 2.228934E+02 8.984319E+01 6.100681E-01 2.228926E+02 + 2.200005E+01 9.000000E+01 5 1.441191E-04 -8.997639E+01 5.940745E-08 -1.441191E-04 + 2.200005E+01 9.000000E+01 6 9.967895E-06 1.799977E+02 -9.967895E-06 3.950835E-10 + 2.210005E+01 0.000000E+00 1 6.008511E+01 8.987253E+01 1.336762E-01 6.008496E+01 + 2.210005E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.210005E+01 0.000000E+00 3 1.687092E+02 5.307443E-01 1.687020E+02 1.562771E+00 + 2.210005E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.210005E+01 0.000000E+00 5 5.734885E+02 8.987254E+01 1.275833E+00 5.734871E+02 + 2.210005E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.210005E+01 3.000000E+01 1 5.237580E+01 8.987257E+01 1.164903E-01 5.237568E+01 + 2.210005E+01 3.000000E+01 2 3.195111E+01 8.984422E+01 8.687587E-02 3.195099E+01 + 2.210005E+01 3.000000E+01 3 1.699618E+02 5.326432E-01 1.699544E+02 1.580006E+00 + 2.210005E+01 3.000000E+01 4 1.066027E+02 8.984238E+01 2.932694E-01 1.066023E+02 + 2.210005E+01 3.000000E+01 5 4.998937E+02 8.987257E+01 1.111814E+00 4.998925E+02 + 2.210005E+01 3.000000E+01 6 1.126665E+02 -3.336977E-03 1.126665E+02 -6.561836E-03 + 2.210005E+01 6.000000E+01 1 3.063708E+01 8.987264E+01 6.810214E-02 3.063701E+01 + 2.210005E+01 6.000000E+01 2 5.614452E+01 8.984416E+01 1.527131E-01 5.614431E+01 + 2.210005E+01 6.000000E+01 3 1.724972E+02 5.364386E-01 1.724897E+02 1.615003E+00 + 2.210005E+01 6.000000E+01 4 1.895200E+02 8.984415E+01 5.155184E-01 1.895193E+02 + 2.210005E+01 6.000000E+01 5 2.923587E+02 8.987262E+01 6.499888E-01 2.923580E+02 + 2.210005E+01 6.000000E+01 6 1.143454E+02 -3.320177E-03 1.143454E+02 -6.626091E-03 + 2.210005E+01 9.000000E+01 1 3.200958E-06 -9.007059E+01 -3.943783E-09 -3.200955E-06 + 2.210005E+01 9.000000E+01 2 6.529917E+01 8.984413E+01 1.776451E-01 6.529893E+01 + 2.210005E+01 9.000000E+01 3 1.737801E+02 5.383422E-01 1.737724E+02 1.632786E+00 + 2.210005E+01 9.000000E+01 4 2.216816E+02 8.984501E+01 5.996847E-01 2.216808E+02 + 2.210005E+01 9.000000E+01 5 1.434940E-04 -8.997674E+01 5.825240E-08 -1.434940E-04 + 2.210005E+01 9.000000E+01 6 9.867438E-06 1.799978E+02 -9.867438E-06 3.824653E-10 + 2.220005E+01 0.000000E+00 1 5.981580E+01 8.987383E+01 1.317142E-01 5.981566E+01 + 2.220005E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.220005E+01 0.000000E+00 3 1.690494E+02 5.256490E-01 1.690423E+02 1.550889E+00 + 2.220005E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.220005E+01 0.000000E+00 5 5.718513E+02 8.987384E+01 1.259161E+00 5.718499E+02 + 2.220005E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.220005E+01 3.000000E+01 1 5.213771E+01 8.987387E+01 1.147740E-01 5.213758E+01 + 2.220005E+01 3.000000E+01 2 3.180588E+01 8.984602E+01 8.547690E-02 3.180576E+01 + 2.220005E+01 3.000000E+01 3 1.702915E+02 5.275040E-01 1.702843E+02 1.567797E+00 + 2.220005E+01 3.000000E+01 4 1.060671E+02 8.984422E+01 2.883778E-01 1.060667E+02 + 2.220005E+01 3.000000E+01 5 4.984298E+02 8.987387E+01 1.097223E+00 4.984286E+02 + 2.220005E+01 3.000000E+01 6 1.115650E+02 -3.263013E-03 1.115650E+02 -6.353665E-03 + 2.220005E+01 6.000000E+01 1 3.049358E+01 8.987394E+01 6.709035E-02 3.049351E+01 + 2.220005E+01 6.000000E+01 2 5.588098E+01 8.984597E+01 1.502306E-01 5.588078E+01 + 2.220005E+01 6.000000E+01 3 1.728050E+02 5.312185E-01 1.727976E+02 1.602141E+00 + 2.220005E+01 6.000000E+01 4 1.885188E+02 8.984595E+01 5.068418E-01 1.885181E+02 + 2.220005E+01 6.000000E+01 5 2.914639E+02 8.987392E+01 6.413736E-01 2.914632E+02 + 2.220005E+01 6.000000E+01 6 1.132102E+02 -3.246761E-03 1.132102E+02 -6.415244E-03 + 2.220005E+01 9.000000E+01 1 3.185517E-06 -9.007029E+01 -3.907673E-09 -3.185514E-06 + 2.220005E+01 9.000000E+01 2 6.498784E+01 8.984594E+01 1.747441E-01 6.498760E+01 + 2.220005E+01 9.000000E+01 3 1.740767E+02 5.330843E-01 1.740692E+02 1.619599E+00 + 2.220005E+01 9.000000E+01 4 2.204834E+02 8.984680E+01 5.895447E-01 2.204826E+02 + 2.220005E+01 9.000000E+01 5 1.428752E-04 -8.997710E+01 5.712690E-08 -1.428752E-04 + 2.220005E+01 9.000000E+01 6 9.768516E-06 1.799978E+02 -9.768516E-06 3.703224E-10 + 2.230005E+01 0.000000E+00 1 5.954891E+01 8.987512E+01 1.297910E-01 5.954877E+01 + 2.230005E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.230005E+01 0.000000E+00 3 1.693851E+02 5.206265E-01 1.693782E+02 1.539122E+00 + 2.230005E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.230005E+01 0.000000E+00 5 5.702155E+02 8.987513E+01 1.242772E+00 5.702141E+02 + 2.230005E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.230005E+01 3.000000E+01 1 5.190144E+01 8.987515E+01 1.130914E-01 5.190132E+01 + 2.230005E+01 3.000000E+01 2 3.166203E+01 8.984780E+01 8.410879E-02 3.166191E+01 + 2.230005E+01 3.000000E+01 3 1.706168E+02 5.224418E-01 1.706097E+02 1.555719E+00 + 2.230005E+01 3.000000E+01 4 1.055370E+02 8.984604E+01 2.835975E-01 1.055366E+02 + 2.230005E+01 3.000000E+01 5 4.969723E+02 8.987515E+01 1.082875E+00 4.969711E+02 + 2.230005E+01 3.000000E+01 6 1.104799E+02 -3.191143E-03 1.104799E+02 -6.153282E-03 + 2.230005E+01 6.000000E+01 1 3.035161E+01 8.987522E+01 6.609912E-02 3.035154E+01 + 2.230005E+01 6.000000E+01 2 5.561997E+01 8.984775E+01 1.478033E-01 5.561978E+01 + 2.230005E+01 6.000000E+01 3 1.731088E+02 5.260794E-01 1.731015E+02 1.589431E+00 + 2.230005E+01 6.000000E+01 4 1.875295E+02 8.984774E+01 4.983612E-01 1.875289E+02 + 2.230005E+01 6.000000E+01 5 2.905703E+02 8.987521E+01 6.329147E-01 2.905696E+02 + 2.230005E+01 6.000000E+01 6 1.120922E+02 -3.175411E-03 1.120922E+02 -6.212304E-03 + 2.230005E+01 9.000000E+01 1 3.170218E-06 -9.006997E+01 -3.871713E-09 -3.170216E-06 + 2.230005E+01 9.000000E+01 2 6.467928E+01 8.984772E+01 1.719072E-01 6.467905E+01 + 2.230005E+01 9.000000E+01 3 1.743694E+02 5.279021E-01 1.743620E+02 1.606552E+00 + 2.230005E+01 9.000000E+01 4 2.193003E+02 8.984856E+01 5.796371E-01 2.192995E+02 + 2.230005E+01 9.000000E+01 5 1.422606E-04 -8.997744E+01 5.602987E-08 -1.422606E-04 + 2.230005E+01 9.000000E+01 6 9.671127E-06 1.799979E+02 -9.671127E-06 3.586343E-10 + 2.240005E+01 0.000000E+00 1 5.928447E+01 8.987638E+01 1.279064E-01 5.928434E+01 + 2.240005E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.240005E+01 0.000000E+00 3 1.697171E+02 5.156795E-01 1.697102E+02 1.527485E+00 + 2.240005E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.240005E+01 0.000000E+00 5 5.685760E+02 8.987639E+01 1.226670E+00 5.685746E+02 + 2.240005E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.240005E+01 3.000000E+01 1 5.166759E+01 8.987642E+01 1.114418E-01 5.166747E+01 + 2.240005E+01 3.000000E+01 2 3.151941E+01 8.984954E+01 8.277039E-02 3.151930E+01 + 2.240005E+01 3.000000E+01 3 1.709379E+02 5.174570E-01 1.709310E+02 1.543776E+00 + 2.240005E+01 3.000000E+01 4 1.050123E+02 8.984782E+01 2.789247E-01 1.050119E+02 + 2.240005E+01 3.000000E+01 5 4.955127E+02 8.987642E+01 1.068766E+00 4.955115E+02 + 2.240005E+01 3.000000E+01 6 1.094111E+02 -3.121288E-03 1.094111E+02 -5.960361E-03 + 2.240005E+01 6.000000E+01 1 3.021082E+01 8.987649E+01 6.512718E-02 3.021075E+01 + 2.240005E+01 6.000000E+01 2 5.536131E+01 8.984949E+01 1.454293E-01 5.536111E+01 + 2.240005E+01 6.000000E+01 3 1.734088E+02 5.210173E-01 1.734016E+02 1.576865E+00 + 2.240005E+01 6.000000E+01 4 1.865516E+02 8.984948E+01 4.900765E-01 1.865509E+02 + 2.240005E+01 6.000000E+01 5 2.896793E+02 8.987646E+01 6.245902E-01 2.896786E+02 + 2.240005E+01 6.000000E+01 6 1.109913E+02 -3.106060E-03 1.109913E+02 -6.016947E-03 + 2.240005E+01 9.000000E+01 1 3.155059E-06 -9.006966E+01 -3.835916E-09 -3.155057E-06 + 2.240005E+01 9.000000E+01 2 6.437397E+01 8.984946E+01 1.691330E-01 6.437375E+01 + 2.240005E+01 9.000000E+01 3 1.746581E+02 5.228024E-01 1.746509E+02 1.593668E+00 + 2.240005E+01 9.000000E+01 4 2.181295E+02 8.985030E+01 5.699567E-01 2.181288E+02 + 2.240005E+01 9.000000E+01 5 1.416516E-04 -8.997777E+01 5.496045E-08 -1.416516E-04 + 2.240005E+01 9.000000E+01 6 9.575243E-06 1.799979E+02 -9.575243E-06 3.473817E-10 + 2.250005E+01 0.000000E+00 1 5.902221E+01 8.987763E+01 1.260573E-01 5.902208E+01 + 2.250005E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.250005E+01 0.000000E+00 3 1.700447E+02 5.108026E-01 1.700380E+02 1.515961E+00 + 2.250005E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.250005E+01 0.000000E+00 5 5.669478E+02 8.987763E+01 1.210813E+00 5.669465E+02 + 2.250005E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.250005E+01 3.000000E+01 1 5.143571E+01 8.987766E+01 1.098251E-01 5.143559E+01 + 2.250005E+01 3.000000E+01 2 3.137811E+01 8.985126E+01 8.146127E-02 3.137801E+01 + 2.250005E+01 3.000000E+01 3 1.712562E+02 5.125394E-01 1.712494E+02 1.531952E+00 + 2.250005E+01 3.000000E+01 4 1.044927E+02 8.984956E+01 2.743582E-01 1.044923E+02 + 2.250005E+01 3.000000E+01 5 4.940579E+02 8.987766E+01 1.054901E+00 4.940568E+02 + 2.250005E+01 3.000000E+01 6 1.083581E+02 -3.053386E-03 1.083581E+02 -5.774582E-03 + 2.250005E+01 6.000000E+01 1 3.007125E+01 8.987773E+01 6.417476E-02 3.007118E+01 + 2.250005E+01 6.000000E+01 2 5.510530E+01 8.985121E+01 1.431075E-01 5.510511E+01 + 2.250005E+01 6.000000E+01 3 1.737053E+02 5.160235E-01 1.736983E+02 1.564422E+00 + 2.250005E+01 6.000000E+01 4 1.855834E+02 8.985120E+01 4.819798E-01 1.855828E+02 + 2.250005E+01 6.000000E+01 5 2.887914E+02 8.987770E+01 6.164166E-01 2.887907E+02 + 2.250005E+01 6.000000E+01 6 1.099068E+02 -3.038650E-03 1.099068E+02 -5.828848E-03 + 2.250005E+01 9.000000E+01 1 3.140078E-06 -9.006934E+01 -3.800280E-09 -3.140075E-06 + 2.250005E+01 9.000000E+01 2 6.407160E+01 8.985118E+01 1.664205E-01 6.407139E+01 + 2.250005E+01 9.000000E+01 3 1.749439E+02 5.177726E-01 1.749368E+02 1.580918E+00 + 2.250005E+01 9.000000E+01 4 2.169711E+02 8.985199E+01 5.605000E-01 2.169704E+02 + 2.250005E+01 9.000000E+01 5 1.410474E-04 -8.997810E+01 5.391795E-08 -1.410474E-04 + 2.250005E+01 9.000000E+01 6 9.480822E-06 1.799980E+02 -9.480822E-06 3.365462E-10 + 2.260005E+01 0.000000E+00 1 5.876220E+01 8.987885E+01 1.242446E-01 5.876207E+01 + 2.260005E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.260005E+01 0.000000E+00 3 1.703676E+02 5.059933E-01 1.703610E+02 1.504540E+00 + 2.260005E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.260005E+01 0.000000E+00 5 5.653150E+02 8.987886E+01 1.195239E+00 5.653137E+02 + 2.260005E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.260005E+01 3.000000E+01 1 5.120598E+01 8.987889E+01 1.082396E-01 5.120586E+01 + 2.260005E+01 3.000000E+01 2 3.123807E+01 8.985294E+01 8.018006E-02 3.123797E+01 + 2.260005E+01 3.000000E+01 3 1.715686E+02 5.076953E-01 1.715618E+02 1.520242E+00 + 2.260005E+01 3.000000E+01 4 1.039790E+02 8.985128E+01 2.698922E-01 1.039787E+02 + 2.260005E+01 3.000000E+01 5 4.926046E+02 8.987889E+01 1.041268E+00 4.926035E+02 + 2.260005E+01 3.000000E+01 6 1.073204E+02 -2.987368E-03 1.073204E+02 -5.595624E-03 + 2.260005E+01 6.000000E+01 1 2.993316E+01 8.987895E+01 6.324082E-02 2.993309E+01 + 2.260005E+01 6.000000E+01 2 5.485150E+01 8.985289E+01 1.408364E-01 5.485132E+01 + 2.260005E+01 6.000000E+01 3 1.739983E+02 5.111058E-01 1.739913E+02 1.552127E+00 + 2.260005E+01 6.000000E+01 4 1.846258E+02 8.985288E+01 4.740637E-01 1.846252E+02 + 2.260005E+01 6.000000E+01 5 2.879061E+02 8.987892E+01 6.083838E-01 2.879054E+02 + 2.260005E+01 6.000000E+01 6 1.088388E+02 -2.973096E-03 1.088388E+02 -5.647680E-03 + 2.260005E+01 9.000000E+01 1 3.125226E-06 -9.006902E+01 -3.764844E-09 -3.125224E-06 + 2.260005E+01 9.000000E+01 2 6.377199E+01 8.985287E+01 1.637671E-01 6.377178E+01 + 2.260005E+01 9.000000E+01 3 1.752252E+02 5.128179E-01 1.752182E+02 1.568308E+00 + 2.260005E+01 9.000000E+01 4 2.158263E+02 8.985366E+01 5.512557E-01 2.158256E+02 + 2.260005E+01 9.000000E+01 5 1.404487E-04 -8.997842E+01 5.290142E-08 -1.404487E-04 + 2.260005E+01 9.000000E+01 6 9.387832E-06 1.799980E+02 -9.387832E-06 3.261088E-10 + 2.270005E+01 0.000000E+00 1 5.850466E+01 8.988007E+01 1.224671E-01 5.850453E+01 + 2.270005E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.270005E+01 0.000000E+00 3 1.706876E+02 5.012506E-01 1.706811E+02 1.493237E+00 + 2.270005E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.270005E+01 0.000000E+00 5 5.636855E+02 8.988007E+01 1.179917E+00 5.636843E+02 + 2.270005E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.270005E+01 3.000000E+01 1 5.097813E+01 8.988010E+01 1.066849E-01 5.097802E+01 + 2.270005E+01 3.000000E+01 2 3.109923E+01 8.985459E+01 7.892652E-02 3.109913E+01 + 2.270005E+01 3.000000E+01 3 1.718788E+02 5.029147E-01 1.718722E+02 1.508650E+00 + 2.270005E+01 3.000000E+01 4 1.034701E+02 8.985297E+01 2.655265E-01 1.034698E+02 + 2.270005E+01 3.000000E+01 5 4.911523E+02 8.988010E+01 1.027858E+00 4.911512E+02 + 2.270005E+01 3.000000E+01 6 1.062980E+02 -2.923173E-03 1.062980E+02 -5.423216E-03 + 2.270005E+01 6.000000E+01 1 2.979630E+01 8.988016E+01 6.232551E-02 2.979623E+01 + 2.270005E+01 6.000000E+01 2 5.460021E+01 8.985454E+01 1.386141E-01 5.460003E+01 + 2.270005E+01 6.000000E+01 3 1.742867E+02 5.062580E-01 1.742799E+02 1.539954E+00 + 2.270005E+01 6.000000E+01 4 1.836797E+02 8.985454E+01 4.663287E-01 1.836791E+02 + 2.270005E+01 6.000000E+01 5 2.870220E+02 8.988013E+01 6.004782E-01 2.870213E+02 + 2.270005E+01 6.000000E+01 6 1.077867E+02 -2.909345E-03 1.077867E+02 -5.473155E-03 + 2.270005E+01 9.000000E+01 1 3.110519E-06 -9.006870E+01 -3.729598E-09 -3.110516E-06 + 2.270005E+01 9.000000E+01 2 6.347538E+01 8.985452E+01 1.611714E-01 6.347517E+01 + 2.270005E+01 9.000000E+01 3 1.755040E+02 5.079331E-01 1.754971E+02 1.555841E+00 + 2.270005E+01 9.000000E+01 4 2.146954E+02 8.985530E+01 5.422186E-01 2.146947E+02 + 2.270005E+01 9.000000E+01 5 1.398552E-04 -8.997874E+01 5.191003E-08 -1.398552E-04 + 2.270005E+01 9.000000E+01 6 9.296253E-06 1.799980E+02 -9.296253E-06 3.160540E-10 + 2.280005E+01 0.000000E+00 1 5.824918E+01 8.988126E+01 1.207237E-01 5.824906E+01 + 2.280005E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.280005E+01 0.000000E+00 3 1.710032E+02 4.965749E-01 1.709967E+02 1.482043E+00 + 2.280005E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.280005E+01 0.000000E+00 5 5.620590E+02 8.988126E+01 1.164852E+00 5.620577E+02 + 2.280005E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.280005E+01 3.000000E+01 1 5.075246E+01 8.988128E+01 1.051603E-01 5.075235E+01 + 2.280005E+01 3.000000E+01 2 3.096159E+01 8.985622E+01 7.769980E-02 3.096150E+01 + 2.280005E+01 3.000000E+01 3 1.721832E+02 4.982095E-01 1.721766E+02 1.497182E+00 + 2.280005E+01 3.000000E+01 4 1.029662E+02 8.985462E+01 2.612569E-01 1.029658E+02 + 2.280005E+01 3.000000E+01 5 4.897064E+02 8.988128E+01 1.014680E+00 4.897053E+02 + 2.280005E+01 3.000000E+01 6 1.052905E+02 -2.860733E-03 1.052905E+02 -5.257073E-03 + 2.280005E+01 6.000000E+01 1 2.966075E+01 8.988134E+01 6.142784E-02 2.966069E+01 + 2.280005E+01 6.000000E+01 2 5.435117E+01 8.985616E+01 1.364400E-01 5.435100E+01 + 2.280005E+01 6.000000E+01 3 1.745713E+02 5.014826E-01 1.745646E+02 1.527920E+00 + 2.280005E+01 6.000000E+01 4 1.827427E+02 8.985616E+01 4.587638E-01 1.827421E+02 + 2.280005E+01 6.000000E+01 5 2.861421E+02 8.988132E+01 5.927127E-01 2.861415E+02 + 2.280005E+01 6.000000E+01 6 1.067502E+02 -2.847337E-03 1.067502E+02 -5.304995E-03 + 2.280005E+01 9.000000E+01 1 3.095955E-06 -9.006837E+01 -3.694568E-09 -3.095952E-06 + 2.280005E+01 9.000000E+01 2 6.318153E+01 8.985615E+01 1.586325E-01 6.318133E+01 + 2.280005E+01 9.000000E+01 3 1.757789E+02 5.031202E-01 1.757721E+02 1.543513E+00 + 2.280005E+01 9.000000E+01 4 2.135760E+02 8.985691E+01 5.333858E-01 2.135753E+02 + 2.280005E+01 9.000000E+01 5 1.392646E-04 -8.997904E+01 5.094318E-08 -1.392646E-04 + 2.280005E+01 9.000000E+01 6 9.206043E-06 1.799981E+02 -9.206043E-06 3.063649E-10 + 2.290005E+01 0.000000E+00 1 5.799576E+01 8.988242E+01 1.190134E-01 5.799564E+01 + 2.290005E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.290005E+01 0.000000E+00 3 1.713144E+02 4.919704E-01 1.713081E+02 1.470973E+00 + 2.290005E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.290005E+01 0.000000E+00 5 5.604406E+02 8.988243E+01 1.150034E+00 5.604395E+02 + 2.290005E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.290005E+01 3.000000E+01 1 5.052847E+01 8.988245E+01 1.036647E-01 5.052836E+01 + 2.290005E+01 3.000000E+01 2 3.082521E+01 8.985781E+01 7.649886E-02 3.082512E+01 + 2.290005E+01 3.000000E+01 3 1.724854E+02 4.935687E-01 1.724790E+02 1.485840E+00 + 2.290005E+01 3.000000E+01 4 1.024670E+02 8.985625E+01 2.570813E-01 1.024667E+02 + 2.290005E+01 3.000000E+01 5 4.882610E+02 8.988245E+01 1.001710E+00 4.882599E+02 + 2.290005E+01 3.000000E+01 6 1.042977E+02 -2.799999E-03 1.042977E+02 -5.096943E-03 + 2.290005E+01 6.000000E+01 1 2.952635E+01 8.988251E+01 6.054788E-02 2.952629E+01 + 2.290005E+01 6.000000E+01 2 5.410443E+01 8.985777E+01 1.343129E-01 5.410426E+01 + 2.290005E+01 6.000000E+01 3 1.748531E+02 4.967713E-01 1.748465E+02 1.516009E+00 + 2.290005E+01 6.000000E+01 4 1.818155E+02 8.985776E+01 4.513689E-01 1.818149E+02 + 2.290005E+01 6.000000E+01 5 2.852617E+02 8.988248E+01 5.850755E-01 2.852611E+02 + 2.290005E+01 6.000000E+01 6 1.057289E+02 -2.787019E-03 1.057289E+02 -5.142936E-03 + 2.290005E+01 9.000000E+01 1 3.081531E-06 -9.006805E+01 -3.659745E-09 -3.081529E-06 + 2.290005E+01 9.000000E+01 2 6.289063E+01 8.985774E+01 1.561481E-01 6.289043E+01 + 2.290005E+01 9.000000E+01 3 1.760497E+02 4.983768E-01 1.760430E+02 1.531317E+00 + 2.290005E+01 9.000000E+01 4 2.124675E+02 8.985850E+01 5.247492E-01 2.124668E+02 + 2.290005E+01 9.000000E+01 5 1.386812E-04 -8.997934E+01 5.000005E-08 -1.386812E-04 + 2.290005E+01 9.000000E+01 6 9.117193E-06 1.799981E+02 -9.117193E-06 2.970265E-10 + 2.300005E+01 0.000000E+00 1 5.774446E+01 8.988358E+01 1.173359E-01 5.774434E+01 + 2.300005E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.300005E+01 0.000000E+00 3 1.716221E+02 4.874241E-01 1.716158E+02 1.459998E+00 + 2.300005E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.300005E+01 0.000000E+00 5 5.588184E+02 8.988358E+01 1.135463E+00 5.588173E+02 + 2.300005E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.300005E+01 3.000000E+01 1 5.030678E+01 8.988361E+01 1.021980E-01 5.030668E+01 + 2.300005E+01 3.000000E+01 2 3.069005E+01 8.985938E+01 7.532332E-02 3.068996E+01 + 2.300005E+01 3.000000E+01 3 1.727834E+02 4.889895E-01 1.727771E+02 1.474598E+00 + 2.300005E+01 3.000000E+01 4 1.019732E+02 8.985785E+01 2.529953E-01 1.019728E+02 + 2.300005E+01 3.000000E+01 5 4.868222E+02 8.988361E+01 9.889663E-01 4.868212E+02 + 2.300005E+01 3.000000E+01 6 1.033190E+02 -2.740901E-03 1.033190E+02 -4.942546E-03 + 2.300005E+01 6.000000E+01 1 2.939326E+01 8.988366E+01 5.968458E-02 2.939320E+01 + 2.300005E+01 6.000000E+01 2 5.385995E+01 8.985934E+01 1.322304E-01 5.385979E+01 + 2.300005E+01 6.000000E+01 3 1.751313E+02 4.921286E-01 1.751248E+02 1.504230E+00 + 2.300005E+01 6.000000E+01 4 1.808982E+02 8.985933E+01 4.441353E-01 1.808977E+02 + 2.300005E+01 6.000000E+01 5 2.843881E+02 8.988364E+01 5.775701E-01 2.843875E+02 + 2.300005E+01 6.000000E+01 6 1.047226E+02 -2.728326E-03 1.047226E+02 -4.986711E-03 + 2.300005E+01 9.000000E+01 1 3.067234E-06 -9.006772E+01 -3.625147E-09 -3.067232E-06 + 2.300005E+01 9.000000E+01 2 6.260244E+01 8.985931E+01 1.537165E-01 6.260226E+01 + 2.300005E+01 9.000000E+01 3 1.763179E+02 4.936996E-01 1.763113E+02 1.519257E+00 + 2.300005E+01 9.000000E+01 4 2.113725E+02 8.986005E+01 5.163049E-01 2.113719E+02 + 2.300005E+01 9.000000E+01 5 1.381013E-04 -8.997964E+01 4.907984E-08 -1.381013E-04 + 2.300005E+01 9.000000E+01 6 9.029641E-06 1.799982E+02 -9.029641E-06 2.880232E-10 + 2.310005E+01 0.000000E+00 1 5.749552E+01 8.988471E+01 1.156901E-01 5.749540E+01 + 2.310005E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.310005E+01 0.000000E+00 3 1.719264E+02 4.829415E-01 1.719203E+02 1.449137E+00 + 2.310005E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.310005E+01 0.000000E+00 5 5.572003E+02 8.988472E+01 1.121129E+00 5.571992E+02 + 2.310005E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.310005E+01 3.000000E+01 1 5.008691E+01 8.988474E+01 1.007595E-01 5.008681E+01 + 2.310005E+01 3.000000E+01 2 3.055601E+01 8.986092E+01 7.417223E-02 3.055592E+01 + 2.310005E+01 3.000000E+01 3 1.730778E+02 4.844745E-01 1.730717E+02 1.463472E+00 + 2.310005E+01 3.000000E+01 4 1.014840E+02 8.985942E+01 2.489998E-01 1.014837E+02 + 2.310005E+01 3.000000E+01 5 4.853862E+02 8.988474E+01 9.764374E-01 4.853852E+02 + 2.310005E+01 3.000000E+01 6 1.023544E+02 -2.683394E-03 1.023544E+02 -4.793673E-03 + 2.310005E+01 6.000000E+01 1 2.926138E+01 8.988479E+01 5.883796E-02 2.926132E+01 + 2.310005E+01 6.000000E+01 2 5.361773E+01 8.986088E+01 1.301921E-01 5.361758E+01 + 2.310005E+01 6.000000E+01 3 1.754065E+02 4.875498E-01 1.754002E+02 1.492577E+00 + 2.310005E+01 6.000000E+01 4 1.799904E+02 8.986087E+01 4.370606E-01 1.799899E+02 + 2.310005E+01 6.000000E+01 5 2.835160E+02 8.988477E+01 5.701879E-01 2.835154E+02 + 2.310005E+01 6.000000E+01 6 1.037312E+02 -2.671204E-03 1.037312E+02 -4.836084E-03 + 2.310005E+01 9.000000E+01 1 3.053080E-06 -9.006739E+01 -3.590793E-09 -3.053078E-06 + 2.310005E+01 9.000000E+01 2 6.231676E+01 8.986086E+01 1.513368E-01 6.231658E+01 + 2.310005E+01 9.000000E+01 3 1.765828E+02 4.890909E-01 1.765764E+02 1.507336E+00 + 2.310005E+01 9.000000E+01 4 2.102881E+02 8.986158E+01 5.080464E-01 2.102875E+02 + 2.310005E+01 9.000000E+01 5 1.375266E-04 -8.997993E+01 4.818189E-08 -1.375266E-04 + 2.310005E+01 9.000000E+01 6 8.943385E-06 1.799982E+02 -8.943385E-06 2.793419E-10 + 2.320005E+01 0.000000E+00 1 5.724863E+01 8.988583E+01 1.140751E-01 5.724851E+01 + 2.320005E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.320005E+01 0.000000E+00 3 1.722262E+02 4.785225E-01 1.722202E+02 1.438381E+00 + 2.320005E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.320005E+01 0.000000E+00 5 5.555858E+02 8.988583E+01 1.107037E+00 5.555847E+02 + 2.320005E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.320005E+01 3.000000E+01 1 4.986903E+01 8.988586E+01 9.934754E-02 4.986893E+01 + 2.320005E+01 3.000000E+01 2 3.042311E+01 8.986243E+01 7.304538E-02 3.042302E+01 + 2.320005E+01 3.000000E+01 3 1.733679E+02 4.800298E-01 1.733618E+02 1.452477E+00 + 2.320005E+01 3.000000E+01 4 1.010003E+02 8.986097E+01 2.450888E-01 1.010000E+02 + 2.320005E+01 3.000000E+01 5 4.839494E+02 8.988586E+01 9.641139E-01 4.839485E+02 + 2.320005E+01 3.000000E+01 6 1.014036E+02 -2.627429E-03 1.014036E+02 -4.650094E-03 + 2.320005E+01 6.000000E+01 1 2.913063E+01 8.988590E+01 5.800764E-02 2.913058E+01 + 2.320005E+01 6.000000E+01 2 5.337780E+01 8.986240E+01 1.281967E-01 5.337764E+01 + 2.320005E+01 6.000000E+01 3 1.756773E+02 4.830391E-01 1.756711E+02 1.481052E+00 + 2.320005E+01 6.000000E+01 4 1.790919E+02 8.986239E+01 4.301402E-01 1.790914E+02 + 2.320005E+01 6.000000E+01 5 2.826436E+02 8.988589E+01 5.629311E-01 2.826431E+02 + 2.320005E+01 6.000000E+01 6 1.027541E+02 -2.615610E-03 1.027541E+02 -4.690829E-03 + 2.320005E+01 9.000000E+01 1 3.039066E-06 -9.006705E+01 -3.556683E-09 -3.039064E-06 + 2.320005E+01 9.000000E+01 2 6.203386E+01 8.986237E+01 1.490075E-01 6.203368E+01 + 2.320005E+01 9.000000E+01 3 1.768442E+02 4.845468E-01 1.768379E+02 1.495543E+00 + 2.320005E+01 9.000000E+01 4 2.092164E+02 8.986308E+01 4.999671E-01 2.092158E+02 + 2.320005E+01 9.000000E+01 5 1.369564E-04 -8.998021E+01 4.730575E-08 -1.369564E-04 + 2.320005E+01 9.000000E+01 6 8.858414E-06 1.799982E+02 -8.858414E-06 2.709699E-10 + 2.330005E+01 0.000000E+00 1 5.700379E+01 8.988694E+01 1.124909E-01 5.700368E+01 + 2.330005E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.330005E+01 0.000000E+00 3 1.725218E+02 4.741654E-01 1.725159E+02 1.427730E+00 + 2.330005E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.330005E+01 0.000000E+00 5 5.539759E+02 8.988694E+01 1.093164E+00 5.539748E+02 + 2.330005E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.330005E+01 3.000000E+01 1 4.965289E+01 8.988696E+01 9.796271E-02 4.965280E+01 + 2.330005E+01 3.000000E+01 2 3.029145E+01 8.986392E+01 7.194176E-02 3.029136E+01 + 2.330005E+01 3.000000E+01 3 1.736550E+02 4.756360E-01 1.736491E+02 1.441566E+00 + 2.330005E+01 3.000000E+01 4 1.005208E+02 8.986249E+01 2.412628E-01 1.005205E+02 + 2.330005E+01 3.000000E+01 5 4.825190E+02 8.988696E+01 9.519819E-01 4.825180E+02 + 2.330005E+01 3.000000E+01 6 1.004662E+02 -2.572953E-03 1.004662E+02 -4.511584E-03 + 2.330005E+01 6.000000E+01 1 2.900108E+01 8.988701E+01 5.719278E-02 2.900102E+01 + 2.330005E+01 6.000000E+01 2 5.314001E+01 8.986388E+01 1.262435E-01 5.313987E+01 + 2.330005E+01 6.000000E+01 3 1.759453E+02 4.785885E-01 1.759391E+02 1.469644E+00 + 2.330005E+01 6.000000E+01 4 1.782030E+02 8.986388E+01 4.233695E-01 1.782025E+02 + 2.330005E+01 6.000000E+01 5 2.817781E+02 8.988699E+01 5.557917E-01 2.817776E+02 + 2.330005E+01 6.000000E+01 6 1.017911E+02 -2.561494E-03 1.017911E+02 -4.550726E-03 + 2.330005E+01 9.000000E+01 1 3.025175E-06 -9.006672E+01 -3.522809E-09 -3.025173E-06 + 2.330005E+01 9.000000E+01 2 6.175347E+01 8.986386E+01 1.467271E-01 6.175330E+01 + 2.330005E+01 9.000000E+01 3 1.771024E+02 4.800657E-01 1.770962E+02 1.483875E+00 + 2.330005E+01 9.000000E+01 4 2.081564E+02 8.986456E+01 4.920636E-01 2.081558E+02 + 2.330005E+01 9.000000E+01 5 1.363912E-04 -8.998049E+01 4.645045E-08 -1.363912E-04 + 2.330005E+01 9.000000E+01 6 8.774668E-06 1.799983E+02 -8.774668E-06 2.628938E-10 + 2.340005E+01 0.000000E+00 1 5.676098E+01 8.988802E+01 1.109356E-01 5.676088E+01 + 2.340005E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.340005E+01 0.000000E+00 3 1.728155E+02 4.698642E-01 1.728097E+02 1.417188E+00 + 2.340005E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.340005E+01 0.000000E+00 5 5.523732E+02 8.988802E+01 1.079528E+00 5.523721E+02 + 2.340005E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.340005E+01 3.000000E+01 1 4.943872E+01 8.988805E+01 9.660371E-02 4.943862E+01 + 2.340005E+01 3.000000E+01 2 3.016082E+01 8.986539E+01 7.086073E-02 3.016074E+01 + 2.340005E+01 3.000000E+01 3 1.739397E+02 4.713049E-01 1.739338E+02 1.430781E+00 + 2.340005E+01 3.000000E+01 4 1.000457E+02 8.986398E+01 2.375182E-01 1.000454E+02 + 2.340005E+01 3.000000E+01 5 4.810920E+02 8.988805E+01 9.400615E-01 4.810911E+02 + 2.340005E+01 3.000000E+01 6 9.954193E+01 -2.519920E-03 9.954193E+01 -4.377943E-03 + 2.340005E+01 6.000000E+01 1 2.887272E+01 8.988809E+01 5.639353E-02 2.887266E+01 + 2.340005E+01 6.000000E+01 2 5.290430E+01 8.986536E+01 1.243302E-01 5.290416E+01 + 2.340005E+01 6.000000E+01 3 1.762097E+02 4.742000E-01 1.762036E+02 1.458357E+00 + 2.340005E+01 6.000000E+01 4 1.773237E+02 8.986535E+01 4.167439E-01 1.773232E+02 + 2.340005E+01 6.000000E+01 5 2.809125E+02 8.988807E+01 5.487711E-01 2.809119E+02 + 2.340005E+01 6.000000E+01 6 1.008419E+02 -2.508803E-03 1.008419E+02 -4.415549E-03 + 2.340005E+01 9.000000E+01 1 3.011427E-06 -9.006638E+01 -3.489197E-09 -3.011425E-06 + 2.340005E+01 9.000000E+01 2 6.147582E+01 8.986533E+01 1.444942E-01 6.147565E+01 + 2.340005E+01 9.000000E+01 3 1.773578E+02 4.756498E-01 1.773517E+02 1.472347E+00 + 2.340005E+01 9.000000E+01 4 2.071072E+02 8.986601E+01 4.843317E-01 2.071067E+02 + 2.340005E+01 9.000000E+01 5 1.358298E-04 -8.998076E+01 4.561563E-08 -1.358298E-04 + 2.340005E+01 9.000000E+01 6 8.692145E-06 1.799983E+02 -8.692145E-06 2.551012E-10 + 2.350005E+01 0.000000E+00 1 5.652029E+01 8.988909E+01 1.094099E-01 5.652018E+01 + 2.350005E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.350005E+01 0.000000E+00 3 1.731049E+02 4.656200E-01 1.730992E+02 1.406739E+00 + 2.350005E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.350005E+01 0.000000E+00 5 5.507627E+02 8.988909E+01 1.066108E+00 5.507617E+02 + 2.350005E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.350005E+01 3.000000E+01 1 4.922615E+01 8.988911E+01 9.526986E-02 4.922606E+01 + 2.350005E+01 3.000000E+01 2 3.003135E+01 8.986683E+01 6.980192E-02 3.003127E+01 + 2.350005E+01 3.000000E+01 3 1.742183E+02 4.670392E-01 1.742125E+02 1.420103E+00 + 2.350005E+01 3.000000E+01 4 9.957614E+01 8.986544E+01 2.338523E-01 9.957587E+01 + 2.350005E+01 3.000000E+01 5 4.796705E+02 8.988911E+01 9.283333E-01 4.796696E+02 + 2.350005E+01 3.000000E+01 6 9.863074E+01 -2.468276E-03 9.863074E+01 -4.248967E-03 + 2.350005E+01 6.000000E+01 1 2.874556E+01 8.988916E+01 5.560928E-02 2.874551E+01 + 2.350005E+01 6.000000E+01 2 5.267070E+01 8.986679E+01 1.224572E-01 5.267056E+01 + 2.350005E+01 6.000000E+01 3 1.764716E+02 4.698740E-01 1.764656E+02 1.447200E+00 + 2.350005E+01 6.000000E+01 4 1.764534E+02 8.986679E+01 4.102605E-01 1.764529E+02 + 2.350005E+01 6.000000E+01 5 2.800497E+02 8.988914E+01 5.418662E-01 2.800492E+02 + 2.350005E+01 6.000000E+01 6 9.990620E+01 -2.457497E-03 9.990620E+01 -4.285118E-03 + 2.350005E+01 9.000000E+01 1 2.997795E-06 -9.006606E+01 -3.455841E-09 -2.997793E-06 + 2.350005E+01 9.000000E+01 2 6.120066E+01 8.986678E+01 1.423084E-01 6.120050E+01 + 2.350005E+01 9.000000E+01 3 1.776091E+02 4.712927E-01 1.776031E+02 1.460926E+00 + 2.350005E+01 9.000000E+01 4 2.060689E+02 8.986745E+01 4.767658E-01 2.060684E+02 + 2.350005E+01 9.000000E+01 5 1.352738E-04 -8.998103E+01 4.480063E-08 -1.352738E-04 + 2.350005E+01 9.000000E+01 6 8.610819E-06 1.799984E+02 -8.610819E-06 2.475814E-10 + 2.360005E+01 0.000000E+00 1 5.628149E+01 8.989014E+01 1.079119E-01 5.628139E+01 + 2.360005E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.360005E+01 0.000000E+00 3 1.733906E+02 4.614415E-01 1.733849E+02 1.396416E+00 + 2.360005E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.360005E+01 0.000000E+00 5 5.491675E+02 8.989014E+01 1.052917E+00 5.491665E+02 + 2.360005E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.360005E+01 3.000000E+01 1 4.901573E+01 8.989017E+01 9.396078E-02 4.901564E+01 + 2.360005E+01 3.000000E+01 2 2.990297E+01 8.986824E+01 6.876475E-02 2.990289E+01 + 2.360005E+01 3.000000E+01 3 1.744954E+02 4.628298E-01 1.744897E+02 1.409542E+00 + 2.360005E+01 3.000000E+01 4 9.911015E+01 8.986688E+01 2.302644E-01 9.910988E+01 + 2.360005E+01 3.000000E+01 5 4.782509E+02 8.989017E+01 9.167892E-01 4.782500E+02 + 2.360005E+01 3.000000E+01 6 9.773241E+01 -2.417973E-03 9.773241E+01 -4.124463E-03 + 2.360005E+01 6.000000E+01 1 2.861949E+01 8.989021E+01 5.483994E-02 2.861944E+01 + 2.360005E+01 6.000000E+01 2 5.243935E+01 8.986821E+01 1.206222E-01 5.243922E+01 + 2.360005E+01 6.000000E+01 3 1.767299E+02 4.656098E-01 1.767241E+02 1.436167E+00 + 2.360005E+01 6.000000E+01 4 1.755913E+02 8.986820E+01 4.039136E-01 1.755909E+02 + 2.360005E+01 6.000000E+01 5 2.791902E+02 8.989020E+01 5.350783E-01 2.791897E+02 + 2.360005E+01 6.000000E+01 6 9.898397E+01 -2.407515E-03 9.898397E+01 -4.159214E-03 + 2.360005E+01 9.000000E+01 1 2.984292E-06 -9.006572E+01 -3.422742E-09 -2.984290E-06 + 2.360005E+01 9.000000E+01 2 6.092810E+01 8.986819E+01 1.401669E-01 6.092794E+01 + 2.360005E+01 9.000000E+01 3 1.778585E+02 4.669997E-01 1.778526E+02 1.449652E+00 + 2.360005E+01 9.000000E+01 4 2.050410E+02 8.986884E+01 4.693612E-01 2.050404E+02 + 2.360005E+01 9.000000E+01 5 1.347215E-04 -8.998129E+01 4.400496E-08 -1.347215E-04 + 2.360005E+01 9.000000E+01 6 8.530661E-06 1.799984E+02 -8.530661E-06 2.403228E-10 + 2.370005E+01 0.000000E+00 1 5.604475E+01 8.989118E+01 1.064415E-01 5.604465E+01 + 2.370005E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.370005E+01 0.000000E+00 3 1.736726E+02 4.573165E-01 1.736671E+02 1.386184E+00 + 2.370005E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.370005E+01 0.000000E+00 5 5.475739E+02 8.989118E+01 1.039919E+00 5.475729E+02 + 2.370005E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.370005E+01 3.000000E+01 1 4.880688E+01 8.989120E+01 9.267645E-02 4.880679E+01 + 2.370005E+01 3.000000E+01 2 2.977571E+01 8.986964E+01 6.774839E-02 2.977563E+01 + 2.370005E+01 3.000000E+01 3 1.747689E+02 4.586752E-01 1.747633E+02 1.399079E+00 + 2.370005E+01 3.000000E+01 4 9.864913E+01 8.986830E+01 2.267505E-01 9.864887E+01 + 2.370005E+01 3.000000E+01 5 4.768365E+02 8.989120E+01 9.054314E-01 4.768357E+02 + 2.370005E+01 3.000000E+01 6 9.684645E+01 -2.368985E-03 9.684645E+01 -4.004271E-03 + 2.370005E+01 6.000000E+01 1 2.849452E+01 8.989124E+01 5.408464E-02 2.849447E+01 + 2.370005E+01 6.000000E+01 2 5.220984E+01 8.986960E+01 1.188247E-01 5.220970E+01 + 2.370005E+01 6.000000E+01 3 1.769851E+02 4.614007E-01 1.769794E+02 1.425239E+00 + 2.370005E+01 6.000000E+01 4 1.747380E+02 8.986960E+01 3.977008E-01 1.747376E+02 + 2.370005E+01 6.000000E+01 5 2.783364E+02 8.989124E+01 5.283985E-01 2.783359E+02 + 2.370005E+01 6.000000E+01 6 9.807465E+01 -2.358844E-03 9.807465E+01 -4.037693E-03 + 2.370005E+01 9.000000E+01 1 2.970911E-06 -9.006538E+01 -3.389921E-09 -2.970909E-06 + 2.370005E+01 9.000000E+01 2 6.065782E+01 8.986958E+01 1.380700E-01 6.065766E+01 + 2.370005E+01 9.000000E+01 3 1.781040E+02 4.627653E-01 1.780982E+02 1.438491E+00 + 2.370005E+01 9.000000E+01 4 2.040250E+02 8.987022E+01 4.621148E-01 2.040245E+02 + 2.370005E+01 9.000000E+01 5 1.341733E-04 -8.998154E+01 4.322765E-08 -1.341733E-04 + 2.370005E+01 9.000000E+01 6 8.451640E-06 1.799984E+02 -8.451640E-06 2.333156E-10 + 2.380005E+01 0.000000E+00 1 5.580989E+01 8.989221E+01 1.049980E-01 5.580980E+01 + 2.380005E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.380005E+01 0.000000E+00 3 1.739525E+02 4.532427E-01 1.739470E+02 1.376050E+00 + 2.380005E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.380005E+01 0.000000E+00 5 5.459833E+02 8.989221E+01 1.027143E+00 5.459824E+02 + 2.380005E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.380005E+01 3.000000E+01 1 4.859989E+01 8.989223E+01 9.141497E-02 4.859980E+01 + 2.380005E+01 3.000000E+01 2 2.964947E+01 8.987101E+01 6.675254E-02 2.964939E+01 + 2.380005E+01 3.000000E+01 3 1.750398E+02 4.545767E-01 1.750343E+02 1.388727E+00 + 2.380005E+01 3.000000E+01 4 9.819201E+01 8.986970E+01 2.233101E-01 9.819176E+01 + 2.380005E+01 3.000000E+01 5 4.754251E+02 8.989223E+01 8.942596E-01 4.754243E+02 + 2.380005E+01 3.000000E+01 6 9.597267E+01 -2.321265E-03 9.597267E+01 -3.888210E-03 + 2.380005E+01 6.000000E+01 1 2.837053E+01 8.989227E+01 5.334353E-02 2.837048E+01 + 2.380005E+01 6.000000E+01 2 5.198251E+01 8.987097E+01 1.170637E-01 5.198238E+01 + 2.380005E+01 6.000000E+01 3 1.772378E+02 4.572474E-01 1.772321E+02 1.414426E+00 + 2.380005E+01 6.000000E+01 4 1.738934E+02 8.987096E+01 3.916194E-01 1.738930E+02 + 2.380005E+01 6.000000E+01 5 2.774833E+02 8.989225E+01 5.218289E-01 2.774828E+02 + 2.380005E+01 6.000000E+01 6 9.717832E+01 -2.311415E-03 9.717832E+01 -3.920348E-03 + 2.380005E+01 9.000000E+01 1 2.957657E-06 -9.006504E+01 -3.357362E-09 -2.957655E-06 + 2.380005E+01 9.000000E+01 2 6.039014E+01 8.987096E+01 1.360155E-01 6.038999E+01 + 2.380005E+01 9.000000E+01 3 1.783479E+02 4.585855E-01 1.783422E+02 1.427451E+00 + 2.380005E+01 9.000000E+01 4 2.030182E+02 8.987159E+01 4.550181E-01 2.030177E+02 + 2.380005E+01 9.000000E+01 5 1.336310E-04 -8.998180E+01 4.246865E-08 -1.336310E-04 + 2.380005E+01 9.000000E+01 6 8.373747E-06 1.799984E+02 -8.373747E-06 2.265489E-10 + 2.390005E+01 0.000000E+00 1 5.557702E+01 8.989321E+01 1.035810E-01 5.557692E+01 + 2.390005E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.390005E+01 0.000000E+00 3 1.742278E+02 4.492277E-01 1.742224E+02 1.366019E+00 + 2.390005E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.390005E+01 0.000000E+00 5 5.443948E+02 8.989322E+01 1.014572E+00 5.443939E+02 + 2.390005E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.390005E+01 3.000000E+01 1 4.839457E+01 8.989324E+01 9.017714E-02 4.839449E+01 + 2.390005E+01 3.000000E+01 2 2.952438E+01 8.987235E+01 6.577675E-02 2.952431E+01 + 2.390005E+01 3.000000E+01 3 1.753066E+02 4.505365E-01 1.753012E+02 1.378483E+00 + 2.390005E+01 3.000000E+01 4 9.773938E+01 8.987107E+01 2.199414E-01 9.773914E+01 + 2.390005E+01 3.000000E+01 5 4.740217E+02 8.989324E+01 8.832666E-01 4.740209E+02 + 2.390005E+01 3.000000E+01 6 9.511114E+01 -2.274766E-03 9.511114E+01 -3.776117E-03 + 2.390005E+01 6.000000E+01 1 2.824776E+01 8.989327E+01 5.261603E-02 2.824771E+01 + 2.390005E+01 6.000000E+01 2 5.175714E+01 8.987232E+01 1.153386E-01 5.175701E+01 + 2.390005E+01 6.000000E+01 3 1.774868E+02 4.531532E-01 1.774813E+02 1.403731E+00 + 2.390005E+01 6.000000E+01 4 1.730580E+02 8.987231E+01 3.856652E-01 1.730576E+02 + 2.390005E+01 6.000000E+01 5 2.766343E+02 8.989326E+01 5.153677E-01 2.766338E+02 + 2.390005E+01 6.000000E+01 6 9.629453E+01 -2.265204E-03 9.629453E+01 -3.807030E-03 + 2.390005E+01 9.000000E+01 1 2.944529E-06 -9.006470E+01 -3.325086E-09 -2.944527E-06 + 2.390005E+01 9.000000E+01 2 6.012493E+01 8.987231E+01 1.340033E-01 6.012478E+01 + 2.390005E+01 9.000000E+01 3 1.785874E+02 4.544663E-01 1.785818E+02 1.416529E+00 + 2.390005E+01 9.000000E+01 4 2.020221E+02 8.987292E+01 4.480752E-01 2.020216E+02 + 2.390005E+01 9.000000E+01 5 1.330919E-04 -8.998204E+01 4.172722E-08 -1.330919E-04 + 2.390005E+01 9.000000E+01 6 8.296965E-06 1.799985E+02 -8.296965E-06 2.200141E-10 + 2.400006E+01 0.000000E+00 1 5.534610E+01 8.989421E+01 1.021894E-01 5.534601E+01 + 2.400006E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.400006E+01 0.000000E+00 3 1.744997E+02 4.452660E-01 1.744944E+02 1.356086E+00 + 2.400006E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.400006E+01 0.000000E+00 5 5.428163E+02 8.989422E+01 1.002187E+00 5.428154E+02 + 2.400006E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.400006E+01 3.000000E+01 1 4.819088E+01 8.989423E+01 8.896141E-02 4.819080E+01 + 2.400006E+01 3.000000E+01 2 2.940030E+01 8.987368E+01 6.482036E-02 2.940022E+01 + 2.400006E+01 3.000000E+01 3 1.755704E+02 4.465468E-01 1.755651E+02 1.368332E+00 + 2.400006E+01 3.000000E+01 4 9.729131E+01 8.987241E+01 2.166428E-01 9.729107E+01 + 2.400006E+01 3.000000E+01 5 4.726164E+02 8.989423E+01 8.724545E-01 4.726156E+02 + 2.400006E+01 3.000000E+01 6 9.426125E+01 -2.229446E-03 9.426125E+01 -3.667816E-03 + 2.400006E+01 6.000000E+01 1 2.812609E+01 8.989427E+01 5.190174E-02 2.812604E+01 + 2.400006E+01 6.000000E+01 2 5.153378E+01 8.987364E+01 1.136480E-01 5.153366E+01 + 2.400006E+01 6.000000E+01 3 1.777336E+02 4.491123E-01 1.777282E+02 1.393149E+00 + 2.400006E+01 6.000000E+01 4 1.722303E+02 8.987364E+01 3.798343E-01 1.722299E+02 + 2.400006E+01 6.000000E+01 5 2.757869E+02 8.989425E+01 5.090078E-01 2.757864E+02 + 2.400006E+01 6.000000E+01 6 9.542294E+01 -2.220166E-03 9.542294E+01 -3.697563E-03 + 2.400006E+01 9.000000E+01 1 2.931508E-06 -9.006436E+01 -3.293080E-09 -2.931506E-06 + 2.400006E+01 9.000000E+01 2 5.986201E+01 8.987363E+01 1.320310E-01 5.986186E+01 + 2.400006E+01 9.000000E+01 3 1.788251E+02 4.504021E-01 1.788195E+02 1.405729E+00 + 2.400006E+01 9.000000E+01 4 2.010370E+02 8.987424E+01 4.412749E-01 2.010365E+02 + 2.400006E+01 9.000000E+01 5 1.325567E-04 -8.998228E+01 4.100292E-08 -1.325567E-04 + 2.400006E+01 9.000000E+01 6 8.221267E-06 1.799985E+02 -8.221267E-06 2.137008E-10 + 2.410006E+01 0.000000E+00 1 5.511711E+01 8.989520E+01 1.008234E-01 5.511702E+01 + 2.410006E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.410006E+01 0.000000E+00 3 1.747693E+02 4.413574E-01 1.747641E+02 1.346259E+00 + 2.410006E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.410006E+01 0.000000E+00 5 5.412387E+02 8.989520E+01 9.900017E-01 5.412378E+02 + 2.410006E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.410006E+01 3.000000E+01 1 4.798917E+01 8.989522E+01 8.776800E-02 4.798909E+01 + 2.410006E+01 3.000000E+01 2 2.927723E+01 8.987498E+01 6.388288E-02 2.927716E+01 + 2.410006E+01 3.000000E+01 3 1.758313E+02 4.426152E-01 1.758261E+02 1.358300E+00 + 2.410006E+01 3.000000E+01 4 9.684742E+01 8.987375E+01 2.134103E-01 9.684718E+01 + 2.410006E+01 3.000000E+01 5 4.712179E+02 8.989522E+01 8.618144E-01 4.712171E+02 + 2.410006E+01 3.000000E+01 6 9.342292E+01 -2.185286E-03 9.342292E+01 -3.563191E-03 + 2.410006E+01 6.000000E+01 1 2.800544E+01 8.989525E+01 5.120069E-02 2.800540E+01 + 2.410006E+01 6.000000E+01 2 5.131229E+01 8.987495E+01 1.119914E-01 5.131217E+01 + 2.410006E+01 6.000000E+01 3 1.779765E+02 4.451326E-01 1.779711E+02 1.382691E+00 + 2.410006E+01 6.000000E+01 4 1.714108E+02 8.987495E+01 3.741245E-01 1.714104E+02 + 2.410006E+01 6.000000E+01 5 2.749439E+02 8.989523E+01 5.027539E-01 2.749435E+02 + 2.410006E+01 6.000000E+01 6 9.456345E+01 -2.176280E-03 9.456345E+01 -3.591827E-03 + 2.410006E+01 9.000000E+01 1 2.918614E-06 -9.006403E+01 -3.261367E-09 -2.918612E-06 + 2.410006E+01 9.000000E+01 2 5.960152E+01 8.987494E+01 1.300989E-01 5.960138E+01 + 2.410006E+01 9.000000E+01 3 1.790594E+02 4.463964E-01 1.790540E+02 1.395054E+00 + 2.410006E+01 9.000000E+01 4 2.000620E+02 8.987553E+01 4.346154E-01 2.000615E+02 + 2.410006E+01 9.000000E+01 5 1.320264E-04 -8.998251E+01 4.029528E-08 -1.320264E-04 + 2.410006E+01 9.000000E+01 6 8.146621E-06 1.799986E+02 -8.146621E-06 2.076021E-10 + 2.420006E+01 0.000000E+00 1 5.488992E+01 8.989616E+01 9.948167E-02 5.488983E+01 + 2.420006E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.420006E+01 0.000000E+00 3 1.750341E+02 4.374979E-01 1.750291E+02 1.336509E+00 + 2.420006E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.420006E+01 0.000000E+00 5 5.396603E+02 8.989616E+01 9.780313E-01 5.396594E+02 + 2.420006E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.420006E+01 3.000000E+01 1 4.778897E+01 8.989618E+01 8.659603E-02 4.778889E+01 + 2.420006E+01 3.000000E+01 2 2.915520E+01 8.987626E+01 6.296390E-02 2.915514E+01 + 2.420006E+01 3.000000E+01 3 1.760889E+02 4.387318E-01 1.760838E+02 1.348355E+00 + 2.420006E+01 3.000000E+01 4 9.640749E+01 8.987505E+01 2.102454E-01 9.640726E+01 + 2.420006E+01 3.000000E+01 5 4.698246E+02 8.989618E+01 8.513460E-01 4.698238E+02 + 2.420006E+01 3.000000E+01 6 9.259603E+01 -2.142239E-03 9.259603E+01 -3.462085E-03 + 2.420006E+01 6.000000E+01 1 2.788586E+01 8.989622E+01 5.051244E-02 2.788581E+01 + 2.420006E+01 6.000000E+01 2 5.109282E+01 8.987624E+01 1.103676E-01 5.109270E+01 + 2.420006E+01 6.000000E+01 3 1.782167E+02 4.412003E-01 1.782114E+02 1.372326E+00 + 2.420006E+01 6.000000E+01 4 1.705998E+02 8.987624E+01 3.685305E-01 1.705994E+02 + 2.420006E+01 6.000000E+01 5 2.741026E+02 8.989620E+01 4.965967E-01 2.741021E+02 + 2.420006E+01 6.000000E+01 6 9.371589E+01 -2.133490E-03 9.371589E+01 -3.489644E-03 + 2.420006E+01 9.000000E+01 1 2.905833E-06 -9.006369E+01 -3.229919E-09 -2.905831E-06 + 2.420006E+01 9.000000E+01 2 5.934311E+01 8.987622E+01 1.282050E-01 5.934298E+01 + 2.420006E+01 9.000000E+01 3 1.792914E+02 4.424344E-01 1.792861E+02 1.384463E+00 + 2.420006E+01 9.000000E+01 4 1.990962E+02 8.987681E+01 4.280929E-01 1.990957E+02 + 2.420006E+01 9.000000E+01 5 1.314999E-04 -8.998274E+01 3.960369E-08 -1.314999E-04 + 2.420006E+01 9.000000E+01 6 8.073012E-06 1.799986E+02 -8.073012E-06 2.017078E-10 + 2.430006E+01 0.000000E+00 1 5.466449E+01 8.989711E+01 9.816404E-02 5.466441E+01 + 2.430006E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.430006E+01 0.000000E+00 3 1.752979E+02 4.336909E-01 1.752929E+02 1.326876E+00 + 2.430006E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.430006E+01 0.000000E+00 5 5.380936E+02 8.989712E+01 9.662327E-01 5.380928E+02 + 2.430006E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.430006E+01 3.000000E+01 1 4.759039E+01 8.989713E+01 8.544528E-02 4.759032E+01 + 2.430006E+01 3.000000E+01 2 2.903419E+01 8.987753E+01 6.206277E-02 2.903412E+01 + 2.430006E+01 3.000000E+01 3 1.763440E+02 4.348980E-01 1.763389E+02 1.338509E+00 + 2.430006E+01 3.000000E+01 4 9.597160E+01 8.987634E+01 2.071419E-01 9.597138E+01 + 2.430006E+01 3.000000E+01 5 4.684349E+02 8.989713E+01 8.410389E-01 4.684341E+02 + 2.430006E+01 3.000000E+01 6 9.178020E+01 -2.100270E-03 9.178020E+01 -3.364352E-03 + 2.430006E+01 6.000000E+01 1 2.776723E+01 8.989717E+01 4.983657E-02 2.776718E+01 + 2.430006E+01 6.000000E+01 2 5.087517E+01 8.987749E+01 1.087756E-01 5.087505E+01 + 2.430006E+01 6.000000E+01 3 1.784546E+02 4.373234E-01 1.784494E+02 1.362083E+00 + 2.430006E+01 6.000000E+01 4 1.697960E+02 8.987749E+01 3.630520E-01 1.697956E+02 + 2.430006E+01 6.000000E+01 5 2.732666E+02 8.989715E+01 4.905472E-01 2.732661E+02 + 2.430006E+01 6.000000E+01 6 9.287992E+01 -2.091775E-03 9.287992E+01 -3.390893E-03 + 2.430006E+01 9.000000E+01 1 2.893164E-06 -9.006335E+01 -3.198767E-09 -2.893162E-06 + 2.430006E+01 9.000000E+01 2 5.908727E+01 8.987749E+01 1.263492E-01 5.908714E+01 + 2.430006E+01 9.000000E+01 3 1.795202E+02 4.385376E-01 1.795150E+02 1.374021E+00 + 2.430006E+01 9.000000E+01 4 1.981402E+02 8.987806E+01 4.217054E-01 1.981397E+02 + 2.430006E+01 9.000000E+01 5 1.309774E-04 -8.998297E+01 3.892789E-08 -1.309774E-04 + 2.430006E+01 9.000000E+01 6 8.000432E-06 1.799986E+02 -8.000432E-06 1.960112E-10 + 2.440006E+01 0.000000E+00 1 5.444105E+01 8.989805E+01 9.686979E-02 5.444096E+01 + 2.440006E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.440006E+01 0.000000E+00 3 1.755571E+02 4.299337E-01 1.755522E+02 1.317326E+00 + 2.440006E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.440006E+01 0.000000E+00 5 5.365279E+02 8.989806E+01 9.546290E-01 5.365270E+02 + 2.440006E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.440006E+01 3.000000E+01 1 4.739366E+01 8.989807E+01 8.431499E-02 4.739359E+01 + 2.440006E+01 3.000000E+01 2 2.891417E+01 8.987877E+01 6.117931E-02 2.891411E+01 + 2.440006E+01 3.000000E+01 3 1.765949E+02 4.311201E-01 1.765899E+02 1.328769E+00 + 2.440006E+01 3.000000E+01 4 9.553999E+01 8.987760E+01 2.041023E-01 9.553976E+01 + 2.440006E+01 3.000000E+01 5 4.670530E+02 8.989807E+01 8.308989E-01 4.670522E+02 + 2.440006E+01 3.000000E+01 6 9.097534E+01 -2.059355E-03 9.097534E+01 -3.269884E-03 + 2.440006E+01 6.000000E+01 1 2.764974E+01 8.989810E+01 4.917292E-02 2.764970E+01 + 2.440006E+01 6.000000E+01 2 5.065941E+01 8.987874E+01 1.072153E-01 5.065929E+01 + 2.440006E+01 6.000000E+01 3 1.786896E+02 4.334970E-01 1.786844E+02 1.351943E+00 + 2.440006E+01 6.000000E+01 4 1.690008E+02 8.987873E+01 3.576838E-01 1.690005E+02 + 2.440006E+01 6.000000E+01 5 2.724322E+02 8.989809E+01 4.845830E-01 2.724317E+02 + 2.440006E+01 6.000000E+01 6 9.205544E+01 -2.051094E-03 9.205544E+01 -3.295432E-03 + 2.440006E+01 9.000000E+01 1 2.880607E-06 -9.006301E+01 -3.167894E-09 -2.880605E-06 + 2.440006E+01 9.000000E+01 2 5.883351E+01 8.987872E+01 1.245295E-01 5.883337E+01 + 2.440006E+01 9.000000E+01 3 1.797462E+02 4.346892E-01 1.797410E+02 1.363678E+00 + 2.440006E+01 9.000000E+01 4 1.971942E+02 8.987930E+01 4.154466E-01 1.971937E+02 + 2.440006E+01 9.000000E+01 5 1.304596E-04 -8.998319E+01 3.826728E-08 -1.304596E-04 + 2.440006E+01 9.000000E+01 6 7.928846E-06 1.799986E+02 -7.928846E-06 1.905042E-10 + 2.450006E+01 0.000000E+00 1 5.421926E+01 8.989898E+01 9.559872E-02 5.421917E+01 + 2.450006E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.450006E+01 0.000000E+00 3 1.758142E+02 4.262261E-01 1.758094E+02 1.307878E+00 + 2.450006E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.450006E+01 0.000000E+00 5 5.349677E+02 8.989899E+01 9.431933E-01 5.349668E+02 + 2.450006E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.450006E+01 3.000000E+01 1 4.719819E+01 8.989900E+01 8.320457E-02 4.719812E+01 + 2.450006E+01 3.000000E+01 2 2.879515E+01 8.987999E+01 6.031291E-02 2.879509E+01 + 2.450006E+01 3.000000E+01 3 1.768436E+02 4.273906E-01 1.768386E+02 1.319130E+00 + 2.450006E+01 3.000000E+01 4 9.511223E+01 8.987885E+01 2.011238E-01 9.511201E+01 + 2.450006E+01 3.000000E+01 5 4.656710E+02 8.989900E+01 8.209152E-01 4.656702E+02 + 2.450006E+01 3.000000E+01 6 9.018147E+01 -2.019447E-03 9.018147E+01 -3.178535E-03 + 2.450006E+01 6.000000E+01 1 2.753310E+01 8.989903E+01 4.852091E-02 2.753306E+01 + 2.450006E+01 6.000000E+01 2 5.044561E+01 8.987997E+01 1.056854E-01 5.044550E+01 + 2.450006E+01 6.000000E+01 3 1.789222E+02 4.297256E-01 1.789172E+02 1.341926E+00 + 2.450006E+01 6.000000E+01 4 1.682136E+02 8.987997E+01 3.524255E-01 1.682132E+02 + 2.450006E+01 6.000000E+01 5 2.716010E+02 8.989901E+01 4.787209E-01 2.716006E+02 + 2.450006E+01 6.000000E+01 6 9.124196E+01 -2.011430E-03 9.124196E+01 -3.203146E-03 + 2.450006E+01 9.000000E+01 1 2.868165E-06 -9.006267E+01 -3.137320E-09 -2.868163E-06 + 2.450006E+01 9.000000E+01 2 5.858204E+01 8.987995E+01 1.227459E-01 5.858191E+01 + 2.450006E+01 9.000000E+01 3 1.799697E+02 4.308933E-01 1.799646E+02 1.353451E+00 + 2.450006E+01 9.000000E+01 4 1.962583E+02 8.988050E+01 4.093162E-01 1.962579E+02 + 2.450006E+01 9.000000E+01 5 1.299453E-04 -8.998341E+01 3.762150E-08 -1.299453E-04 + 2.450006E+01 9.000000E+01 6 7.858253E-06 1.799987E+02 -7.858253E-06 1.851799E-10 + 2.460006E+01 0.000000E+00 1 5.399934E+01 8.989989E+01 9.434960E-02 5.399926E+01 + 2.460006E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.460006E+01 0.000000E+00 3 1.760677E+02 4.225669E-01 1.760629E+02 1.298520E+00 + 2.460006E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.460006E+01 0.000000E+00 5 5.334150E+02 8.989990E+01 9.319467E-01 5.334142E+02 + 2.460006E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.460006E+01 3.000000E+01 1 4.700480E+01 8.989991E+01 8.211408E-02 4.700473E+01 + 2.460006E+01 3.000000E+01 2 2.867704E+01 8.988120E+01 5.946324E-02 2.867698E+01 + 2.460006E+01 3.000000E+01 3 1.770899E+02 4.237058E-01 1.770851E+02 1.309579E+00 + 2.460006E+01 3.000000E+01 4 9.468811E+01 8.988007E+01 1.982032E-01 9.468790E+01 + 2.460006E+01 3.000000E+01 5 4.642968E+02 8.989991E+01 8.110967E-01 4.642961E+02 + 2.460006E+01 3.000000E+01 6 8.939787E+01 -1.980525E-03 8.939787E+01 -3.090188E-03 + 2.460006E+01 6.000000E+01 1 2.741760E+01 8.989994E+01 4.788094E-02 2.741756E+01 + 2.460006E+01 6.000000E+01 2 5.023351E+01 8.988116E+01 1.041852E-01 5.023340E+01 + 2.460006E+01 6.000000E+01 3 1.791508E+02 4.259996E-01 1.791459E+02 1.331991E+00 + 2.460006E+01 6.000000E+01 4 1.674326E+02 8.988116E+01 3.472713E-01 1.674323E+02 + 2.460006E+01 6.000000E+01 5 2.707739E+02 8.989993E+01 4.729458E-01 2.707735E+02 + 2.460006E+01 6.000000E+01 6 9.043964E+01 -1.972735E-03 9.043964E+01 -3.113902E-03 + 2.460006E+01 9.000000E+01 1 2.855832E-06 -9.006233E+01 -3.107019E-09 -2.855830E-06 + 2.460006E+01 9.000000E+01 2 5.833270E+01 8.988116E+01 1.209969E-01 5.833257E+01 + 2.460006E+01 9.000000E+01 3 1.801916E+02 4.271433E-01 1.801866E+02 1.343326E+00 + 2.460006E+01 9.000000E+01 4 1.953301E+02 8.988170E+01 4.033084E-01 1.953297E+02 + 2.460006E+01 9.000000E+01 5 1.294351E-04 -8.998363E+01 3.699022E-08 -1.294351E-04 + 2.460006E+01 9.000000E+01 6 7.788616E-06 1.799987E+02 -7.788616E-06 1.800306E-10 + 2.470006E+01 0.000000E+00 1 5.378117E+01 8.990079E+01 9.312256E-02 5.378109E+01 + 2.470006E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.470006E+01 0.000000E+00 3 1.763189E+02 4.189522E-01 1.763141E+02 1.289249E+00 + 2.470006E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.470006E+01 0.000000E+00 5 5.318651E+02 8.990079E+01 9.208829E-01 5.318643E+02 + 2.470006E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.470006E+01 3.000000E+01 1 4.681253E+01 8.990081E+01 8.104297E-02 4.681247E+01 + 2.470006E+01 3.000000E+01 2 2.856001E+01 8.988238E+01 5.862991E-02 2.855994E+01 + 2.470006E+01 3.000000E+01 3 1.773324E+02 4.200728E-01 1.773277E+02 1.300128E+00 + 2.470006E+01 3.000000E+01 4 9.426814E+01 8.988127E+01 1.953418E-01 9.426794E+01 + 2.470006E+01 3.000000E+01 5 4.629255E+02 8.990081E+01 8.014228E-01 4.629248E+02 + 2.470006E+01 3.000000E+01 6 8.862480E+01 -1.942562E-03 8.862480E+01 -3.004744E-03 + 2.470006E+01 6.000000E+01 1 2.730299E+01 8.990084E+01 4.725219E-02 2.730295E+01 + 2.470006E+01 6.000000E+01 2 5.002332E+01 8.988235E+01 1.027142E-01 5.002321E+01 + 2.470006E+01 6.000000E+01 3 1.793775E+02 4.223199E-01 1.793727E+02 1.322157E+00 + 2.470006E+01 6.000000E+01 4 1.666603E+02 8.988235E+01 3.422202E-01 1.666600E+02 + 2.470006E+01 6.000000E+01 5 2.699490E+02 8.990083E+01 4.672738E-01 2.699486E+02 + 2.470006E+01 6.000000E+01 6 8.964802E+01 -1.934987E-03 8.964802E+01 -3.027584E-03 + 2.470006E+01 9.000000E+01 1 2.843609E-06 -9.006200E+01 -3.077015E-09 -2.843607E-06 + 2.470006E+01 9.000000E+01 2 5.808551E+01 8.988234E+01 1.192822E-01 5.808539E+01 + 2.470006E+01 9.000000E+01 3 1.804100E+02 4.234435E-01 1.804051E+02 1.333305E+00 + 2.470006E+01 9.000000E+01 4 1.944115E+02 8.988287E+01 3.974206E-01 1.944111E+02 + 2.470006E+01 9.000000E+01 5 1.289278E-04 -8.998383E+01 3.637289E-08 -1.289278E-04 + 2.470006E+01 9.000000E+01 6 7.719932E-06 1.799987E+02 -7.719932E-06 1.750500E-10 + 2.480006E+01 0.000000E+00 1 5.356469E+01 8.990168E+01 9.191687E-02 5.356461E+01 + 2.480006E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.480006E+01 0.000000E+00 3 1.765668E+02 4.153858E-01 1.765622E+02 1.280072E+00 + 2.480006E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.480006E+01 0.000000E+00 5 5.303159E+02 8.990168E+01 9.099780E-01 5.303151E+02 + 2.480006E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.480006E+01 3.000000E+01 1 4.662207E+01 8.990170E+01 7.999029E-02 4.662200E+01 + 2.480006E+01 3.000000E+01 2 2.844382E+01 8.988355E+01 5.781246E-02 2.844377E+01 + 2.480006E+01 3.000000E+01 3 1.775724E+02 4.164839E-01 1.775677E+02 1.290765E+00 + 2.480006E+01 3.000000E+01 4 9.385210E+01 8.988245E+01 1.925367E-01 9.385190E+01 + 2.480006E+01 3.000000E+01 5 4.615573E+02 8.990170E+01 7.919074E-01 4.615566E+02 + 2.480006E+01 3.000000E+01 6 8.786177E+01 -1.905528E-03 8.786177E+01 -2.922084E-03 + 2.480006E+01 6.000000E+01 1 2.718941E+01 8.990173E+01 4.663461E-02 2.718937E+01 + 2.480006E+01 6.000000E+01 2 4.981487E+01 8.988352E+01 1.012714E-01 4.981477E+01 + 2.480006E+01 6.000000E+01 3 1.796018E+02 4.186890E-01 1.795970E+02 1.312429E+00 + 2.480006E+01 6.000000E+01 4 1.658963E+02 8.988352E+01 3.372680E-01 1.658959E+02 + 2.480006E+01 6.000000E+01 5 2.691268E+02 8.990171E+01 4.616813E-01 2.691264E+02 + 2.480006E+01 6.000000E+01 6 8.886719E+01 -1.898159E-03 8.886719E+01 -2.944092E-03 + 2.480006E+01 9.000000E+01 1 2.831491E-06 -9.006167E+01 -3.047292E-09 -2.831489E-06 + 2.480006E+01 9.000000E+01 2 5.784065E+01 8.988351E+01 1.176006E-01 5.784053E+01 + 2.480006E+01 9.000000E+01 3 1.806254E+02 4.197936E-01 1.806206E+02 1.323391E+00 + 2.480006E+01 9.000000E+01 4 1.935027E+02 8.988403E+01 3.916526E-01 1.935023E+02 + 2.480006E+01 9.000000E+01 5 1.284257E-04 -8.998404E+01 3.576919E-08 -1.284257E-04 + 2.480006E+01 9.000000E+01 6 7.652169E-06 1.799987E+02 -7.652169E-06 1.702321E-10 + 2.490006E+01 0.000000E+00 1 5.335005E+01 8.990256E+01 9.073237E-02 5.334998E+01 + 2.490006E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.490006E+01 0.000000E+00 3 1.768118E+02 4.118660E-01 1.768072E+02 1.270986E+00 + 2.490006E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.490006E+01 0.000000E+00 5 5.287761E+02 8.990257E+01 8.992478E-01 5.287753E+02 + 2.490006E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.490006E+01 3.000000E+01 1 4.643299E+01 8.990257E+01 7.895582E-02 4.643292E+01 + 2.490006E+01 3.000000E+01 2 2.832863E+01 8.988470E+01 5.701044E-02 2.832857E+01 + 2.490006E+01 3.000000E+01 3 1.778103E+02 4.129422E-01 1.778057E+02 1.281503E+00 + 2.490006E+01 3.000000E+01 4 9.343965E+01 8.988363E+01 1.897852E-01 9.343946E+01 + 2.490006E+01 3.000000E+01 5 4.601959E+02 8.990257E+01 7.825330E-01 4.601952E+02 + 2.490006E+01 3.000000E+01 6 8.710892E+01 -1.869385E-03 8.710892E+01 -2.842095E-03 + 2.490006E+01 6.000000E+01 1 2.707679E+01 8.990260E+01 4.602775E-02 2.707675E+01 + 2.490006E+01 6.000000E+01 2 4.960810E+01 8.988467E+01 9.985618E-02 4.960800E+01 + 2.490006E+01 6.000000E+01 3 1.798236E+02 4.151099E-01 1.798188E+02 1.302817E+00 + 2.490006E+01 6.000000E+01 4 1.651373E+02 8.988467E+01 3.324157E-01 1.651370E+02 + 2.490006E+01 6.000000E+01 5 2.683115E+02 8.990259E+01 4.561692E-01 2.683111E+02 + 2.490006E+01 6.000000E+01 6 8.809652E+01 -1.862227E-03 8.809652E+01 -2.863312E-03 + 2.490006E+01 9.000000E+01 1 2.819473E-06 -9.006133E+01 -3.017858E-09 -2.819471E-06 + 2.490006E+01 9.000000E+01 2 5.759768E+01 8.988466E+01 1.159510E-01 5.759756E+01 + 2.490006E+01 9.000000E+01 3 1.808393E+02 4.161923E-01 1.808345E+02 1.313591E+00 + 2.490006E+01 9.000000E+01 4 1.926020E+02 8.988518E+01 3.859954E-01 1.926016E+02 + 2.490006E+01 9.000000E+01 5 1.279273E-04 -8.998425E+01 3.517875E-08 -1.279273E-04 + 2.490006E+01 9.000000E+01 6 7.585311E-06 1.799987E+02 -7.585311E-06 1.655704E-10 + 2.500006E+01 0.000000E+00 1 5.313704E+01 8.990343E+01 8.956819E-02 5.313696E+01 + 2.500006E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.500006E+01 0.000000E+00 3 1.770543E+02 4.083896E-01 1.770498E+02 1.261987E+00 + 2.500006E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.500006E+01 0.000000E+00 5 5.272414E+02 8.990343E+01 8.886803E-01 5.272407E+02 + 2.500006E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.500006E+01 3.000000E+01 1 4.624553E+01 8.990343E+01 7.794006E-02 4.624546E+01 + 2.500006E+01 3.000000E+01 2 2.821434E+01 8.988583E+01 5.622368E-02 2.821428E+01 + 2.500006E+01 3.000000E+01 3 1.780443E+02 4.094484E-01 1.780397E+02 1.272333E+00 + 2.500006E+01 3.000000E+01 4 9.303102E+01 8.988478E+01 1.870886E-01 9.303083E+01 + 2.500006E+01 3.000000E+01 5 4.588366E+02 8.990343E+01 7.733034E-01 4.588360E+02 + 2.500006E+01 3.000000E+01 6 8.636576E+01 -1.834118E-03 8.636576E+01 -2.764689E-03 + 2.500006E+01 6.000000E+01 1 2.696503E+01 8.990347E+01 4.543158E-02 2.696499E+01 + 2.500006E+01 6.000000E+01 2 4.940303E+01 8.988580E+01 9.846783E-02 4.940293E+01 + 2.500006E+01 6.000000E+01 3 1.800412E+02 4.115758E-01 1.800365E+02 1.293288E+00 + 2.500006E+01 6.000000E+01 4 1.643874E+02 8.988580E+01 3.276581E-01 1.643871E+02 + 2.500006E+01 6.000000E+01 5 2.674931E+02 8.990345E+01 4.507528E-01 2.674927E+02 + 2.500006E+01 6.000000E+01 6 8.733630E+01 -1.827158E-03 8.733630E+01 -2.785148E-03 + 2.500006E+01 9.000000E+01 1 2.807568E-06 -9.006100E+01 -2.988725E-09 -2.807566E-06 + 2.500006E+01 9.000000E+01 2 5.735681E+01 8.988579E+01 1.143331E-01 5.735670E+01 + 2.500006E+01 9.000000E+01 3 1.810499E+02 4.126362E-01 1.810452E+02 1.303885E+00 + 2.500006E+01 9.000000E+01 4 1.917110E+02 8.988629E+01 3.804510E-01 1.917106E+02 + 2.500006E+01 9.000000E+01 5 1.274322E-04 -8.998444E+01 3.460135E-08 -1.274322E-04 + 2.500006E+01 9.000000E+01 6 7.519363E-06 1.799988E+02 -7.519363E-06 1.610591E-10 + 2.510006E+01 0.000000E+00 1 5.292557E+01 8.990427E+01 8.842468E-02 5.292550E+01 + 2.510006E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.510006E+01 0.000000E+00 3 1.772938E+02 4.049586E-01 1.772893E+02 1.253077E+00 + 2.510006E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.510006E+01 0.000000E+00 5 5.257103E+02 8.990428E+01 8.782778E-01 5.257095E+02 + 2.510006E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.510006E+01 3.000000E+01 1 4.605963E+01 8.990429E+01 7.694146E-02 4.605957E+01 + 2.510006E+01 3.000000E+01 2 2.810098E+01 8.988694E+01 5.545168E-02 2.810092E+01 + 2.510006E+01 3.000000E+01 3 1.782761E+02 4.060007E-01 1.782716E+02 1.263263E+00 + 2.510006E+01 3.000000E+01 4 9.262593E+01 8.988591E+01 1.844436E-01 9.262575E+01 + 2.510006E+01 3.000000E+01 5 4.574836E+02 8.990428E+01 7.642243E-01 4.574829E+02 + 2.510006E+01 3.000000E+01 6 8.563242E+01 -1.799699E-03 8.563242E+01 -2.689772E-03 + 2.510006E+01 6.000000E+01 1 2.685440E+01 8.990432E+01 4.484583E-02 2.685436E+01 + 2.510006E+01 6.000000E+01 2 4.919981E+01 8.988692E+01 9.710602E-02 4.919972E+01 + 2.510006E+01 6.000000E+01 3 1.802585E+02 4.080828E-01 1.802540E+02 1.283860E+00 + 2.510006E+01 6.000000E+01 4 1.636436E+02 8.988691E+01 3.229948E-01 1.636433E+02 + 2.510006E+01 6.000000E+01 5 2.666844E+02 8.990430E+01 4.454191E-01 2.666840E+02 + 2.510006E+01 6.000000E+01 6 8.658608E+01 -1.792929E-03 8.658608E+01 -2.709497E-03 + 2.510006E+01 9.000000E+01 1 2.795762E-06 -9.006066E+01 -2.959867E-09 -2.795760E-06 + 2.510006E+01 9.000000E+01 2 5.711811E+01 8.988690E+01 1.127463E-01 5.711800E+01 + 2.510006E+01 9.000000E+01 3 1.812591E+02 4.091276E-01 1.812544E+02 1.294292E+00 + 2.510006E+01 9.000000E+01 4 1.908277E+02 8.988740E+01 3.750165E-01 1.908274E+02 + 2.510006E+01 9.000000E+01 5 1.269409E-04 -8.998463E+01 3.403653E-08 -1.269409E-04 + 2.510006E+01 9.000000E+01 6 7.454297E-06 1.799988E+02 -7.454297E-06 1.566928E-10 + 2.520006E+01 0.000000E+00 1 5.271600E+01 8.990512E+01 8.730014E-02 5.271592E+01 + 2.520006E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.520006E+01 0.000000E+00 3 1.775309E+02 4.015695E-01 1.775265E+02 1.244252E+00 + 2.520006E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.520006E+01 0.000000E+00 5 5.241855E+02 8.990512E+01 8.680288E-01 5.241848E+02 + 2.520006E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.520006E+01 3.000000E+01 1 4.587526E+01 8.990513E+01 7.595998E-02 4.587519E+01 + 2.520006E+01 3.000000E+01 2 2.798850E+01 8.988804E+01 5.469400E-02 2.798845E+01 + 2.520006E+01 3.000000E+01 3 1.785062E+02 4.025902E-01 1.785018E+02 1.254268E+00 + 2.520006E+01 3.000000E+01 4 9.222443E+01 8.988702E+01 1.818499E-01 9.222426E+01 + 2.520006E+01 3.000000E+01 5 4.561398E+02 8.990513E+01 7.552798E-01 4.561392E+02 + 2.520006E+01 3.000000E+01 6 8.490846E+01 -1.766103E-03 8.490846E+01 -2.617246E-03 + 2.520006E+01 6.000000E+01 1 2.674450E+01 8.990516E+01 4.427037E-02 2.674446E+01 + 2.520006E+01 6.000000E+01 2 4.899820E+01 8.988802E+01 9.576986E-02 4.899810E+01 + 2.520006E+01 6.000000E+01 3 1.804727E+02 4.046407E-01 1.804682E+02 1.274544E+00 + 2.520006E+01 6.000000E+01 4 1.629073E+02 8.988801E+01 3.184209E-01 1.629070E+02 + 2.520006E+01 6.000000E+01 5 2.658757E+02 8.990514E+01 4.401714E-01 2.658753E+02 + 2.520006E+01 6.000000E+01 6 8.584565E+01 -1.759518E-03 8.584565E+01 -2.636266E-03 + 2.520006E+01 9.000000E+01 1 2.784061E-06 -9.006033E+01 -2.931307E-09 -2.784060E-06 + 2.520006E+01 9.000000E+01 2 5.688136E+01 8.988800E+01 1.111894E-01 5.688126E+01 + 2.520006E+01 9.000000E+01 3 1.814655E+02 4.056632E-01 1.814610E+02 1.284794E+00 + 2.520006E+01 9.000000E+01 4 1.899537E+02 8.988850E+01 3.696886E-01 1.899533E+02 + 2.520006E+01 9.000000E+01 5 1.264529E-04 -8.998483E+01 3.348378E-08 -1.264529E-04 + 2.520006E+01 9.000000E+01 6 7.390084E-06 1.799988E+02 -7.390084E-06 1.524657E-10 + 2.530006E+01 0.000000E+00 1 5.250806E+01 8.990594E+01 8.619491E-02 5.250799E+01 + 2.530006E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.530006E+01 0.000000E+00 3 1.777646E+02 3.982247E-01 1.777604E+02 1.235514E+00 + 2.530006E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.530006E+01 0.000000E+00 5 5.226671E+02 8.990595E+01 8.579420E-01 5.226663E+02 + 2.530006E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.530006E+01 3.000000E+01 1 4.569215E+01 8.990596E+01 7.499533E-02 4.569209E+01 + 2.530006E+01 3.000000E+01 2 2.787701E+01 8.988911E+01 5.395045E-02 2.787696E+01 + 2.530006E+01 3.000000E+01 3 1.787324E+02 3.992268E-01 1.787280E+02 1.245365E+00 + 2.530006E+01 3.000000E+01 4 9.182629E+01 8.988811E+01 1.793063E-01 9.182612E+01 + 2.530006E+01 3.000000E+01 5 4.547971E+02 8.990596E+01 7.464731E-01 4.547965E+02 + 2.530006E+01 3.000000E+01 6 8.419390E+01 -1.733304E-03 8.419390E+01 -2.547023E-03 + 2.530006E+01 6.000000E+01 1 2.663543E+01 8.990598E+01 4.370455E-02 2.663539E+01 + 2.530006E+01 6.000000E+01 2 4.879833E+01 8.988909E+01 9.445865E-02 4.879824E+01 + 2.530006E+01 6.000000E+01 3 1.806845E+02 4.012356E-01 1.806801E+02 1.265302E+00 + 2.530006E+01 6.000000E+01 4 1.621776E+02 8.988909E+01 3.139356E-01 1.621773E+02 + 2.530006E+01 6.000000E+01 5 2.650708E+02 8.990598E+01 4.350087E-01 2.650704E+02 + 2.530006E+01 6.000000E+01 6 8.511478E+01 -1.726902E-03 8.511478E+01 -2.565370E-03 + 2.530006E+01 9.000000E+01 1 2.772455E-06 -9.005999E+01 -2.903029E-09 -2.772453E-06 + 2.530006E+01 9.000000E+01 2 5.664659E+01 8.988908E+01 1.096615E-01 5.664648E+01 + 2.530006E+01 9.000000E+01 3 1.816694E+02 4.022422E-01 1.816649E+02 1.275391E+00 + 2.530006E+01 9.000000E+01 4 1.890861E+02 8.988956E+01 3.644627E-01 1.890857E+02 + 2.530006E+01 9.000000E+01 5 1.259696E-04 -8.998502E+01 3.294310E-08 -1.259696E-04 + 2.530006E+01 9.000000E+01 6 7.326716E-06 1.799988E+02 -7.326716E-06 1.483733E-10 + 2.540006E+01 0.000000E+00 1 5.230154E+01 8.990676E+01 8.510897E-02 5.230147E+01 + 2.540006E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.540006E+01 0.000000E+00 3 1.779963E+02 3.949230E-01 1.779921E+02 1.226866E+00 + 2.540006E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.540006E+01 0.000000E+00 5 5.211514E+02 8.990677E+01 8.480092E-01 5.211507E+02 + 2.540006E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.540006E+01 3.000000E+01 1 4.551067E+01 8.990678E+01 7.404727E-02 4.551060E+01 + 2.540006E+01 3.000000E+01 2 2.776632E+01 8.989018E+01 5.322068E-02 2.776627E+01 + 2.540006E+01 3.000000E+01 3 1.789560E+02 3.959090E-01 1.789518E+02 1.236561E+00 + 2.540006E+01 3.000000E+01 4 9.143183E+01 8.988921E+01 1.768100E-01 9.143166E+01 + 2.540006E+01 3.000000E+01 5 4.534624E+02 8.990678E+01 7.377992E-01 4.534618E+02 + 2.540006E+01 3.000000E+01 6 8.348849E+01 -1.701282E-03 8.348849E+01 -2.479021E-03 + 2.540006E+01 6.000000E+01 1 2.652739E+01 8.990681E+01 4.314886E-02 2.652736E+01 + 2.540006E+01 6.000000E+01 2 4.860004E+01 8.989016E+01 9.317198E-02 4.859996E+01 + 2.540006E+01 6.000000E+01 3 1.808939E+02 3.978804E-01 1.808895E+02 1.256175E+00 + 2.540006E+01 6.000000E+01 4 1.614544E+02 8.989015E+01 3.095352E-01 1.614541E+02 + 2.540006E+01 6.000000E+01 5 2.642698E+02 8.990679E+01 4.299184E-01 2.642694E+02 + 2.540006E+01 6.000000E+01 6 8.439370E+01 -1.695051E-03 8.439370E+01 -2.496722E-03 + 2.540006E+01 9.000000E+01 1 2.760949E-06 -9.005966E+01 -2.875039E-09 -2.760948E-06 + 2.540006E+01 9.000000E+01 2 5.641391E+01 8.989014E+01 1.081625E-01 5.641381E+01 + 2.540006E+01 9.000000E+01 3 1.818706E+02 3.988698E-01 1.818662E+02 1.266098E+00 + 2.540006E+01 9.000000E+01 4 1.882291E+02 8.989062E+01 3.593362E-01 1.882288E+02 + 2.540006E+01 9.000000E+01 5 1.254894E-04 -8.998520E+01 3.241390E-08 -1.254894E-04 + 2.540006E+01 9.000000E+01 6 7.264190E-06 1.799989E+02 -7.264190E-06 1.444104E-10 + 2.550006E+01 0.000000E+00 1 5.209661E+01 8.990757E+01 8.404067E-02 5.209655E+01 + 2.550006E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.550006E+01 0.000000E+00 3 1.782248E+02 3.916592E-01 1.782206E+02 1.218289E+00 + 2.550006E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.550006E+01 0.000000E+00 5 5.196445E+02 8.990758E+01 8.382323E-01 5.196438E+02 + 2.550006E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.550006E+01 3.000000E+01 1 4.533051E+01 8.990759E+01 7.311536E-02 4.533046E+01 + 2.550006E+01 3.000000E+01 2 2.765651E+01 8.989123E+01 5.250428E-02 2.765646E+01 + 2.550006E+01 3.000000E+01 3 1.791780E+02 3.926268E-01 1.791738E+02 1.227831E+00 + 2.550006E+01 3.000000E+01 4 9.104112E+01 8.989027E+01 1.743610E-01 9.104095E+01 + 2.550006E+01 3.000000E+01 5 4.521271E+02 8.990759E+01 7.292583E-01 4.521265E+02 + 2.550006E+01 3.000000E+01 6 8.279195E+01 -1.670009E-03 8.279195E+01 -2.413150E-03 + 2.550006E+01 6.000000E+01 1 2.642026E+01 8.990761E+01 4.260239E-02 2.642022E+01 + 2.550006E+01 6.000000E+01 2 4.840344E+01 8.989120E+01 9.190919E-02 4.840335E+01 + 2.550006E+01 6.000000E+01 3 1.811003E+02 3.945653E-01 1.810961E+02 1.247131E+00 + 2.550006E+01 6.000000E+01 4 1.607382E+02 8.989120E+01 3.052194E-01 1.607379E+02 + 2.550006E+01 6.000000E+01 5 2.634714E+02 8.990760E+01 4.249104E-01 2.634711E+02 + 2.550006E+01 6.000000E+01 6 8.368171E+01 -1.663949E-03 8.368171E+01 -2.430232E-03 + 2.550006E+01 9.000000E+01 1 2.749541E-06 -9.005933E+01 -2.847323E-09 -2.749540E-06 + 2.550006E+01 9.000000E+01 2 5.618304E+01 8.989120E+01 1.066911E-01 5.618293E+01 + 2.550006E+01 9.000000E+01 3 1.820701E+02 3.955380E-01 1.820657E+02 1.256900E+00 + 2.550006E+01 9.000000E+01 4 1.873790E+02 8.989166E+01 3.543107E-01 1.873787E+02 + 2.550006E+01 9.000000E+01 5 1.250131E-04 -8.998538E+01 3.189593E-08 -1.250131E-04 + 2.550006E+01 9.000000E+01 6 7.202465E-06 1.799989E+02 -7.202465E-06 1.405721E-10 + 2.560006E+01 0.000000E+00 1 5.189355E+01 8.990837E+01 8.299110E-02 5.189349E+01 + 2.560006E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.560006E+01 0.000000E+00 3 1.784516E+02 3.884348E-01 1.784475E+02 1.209798E+00 + 2.560006E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.560006E+01 0.000000E+00 5 5.181401E+02 8.990838E+01 8.285958E-01 5.181395E+02 + 2.560006E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.560006E+01 3.000000E+01 1 4.515197E+01 8.990839E+01 7.219904E-02 4.515192E+01 + 2.560006E+01 3.000000E+01 2 2.754763E+01 8.989227E+01 5.180098E-02 2.754758E+01 + 2.560006E+01 3.000000E+01 3 1.793979E+02 3.893873E-01 1.793937E+02 1.219195E+00 + 2.560006E+01 3.000000E+01 4 9.065352E+01 8.989131E+01 1.719588E-01 9.065336E+01 + 2.560006E+01 3.000000E+01 5 4.508022E+02 8.990839E+01 7.208501E-01 4.508016E+02 + 2.560006E+01 3.000000E+01 6 8.210437E+01 -1.639471E-03 8.210437E+01 -2.349349E-03 + 2.560006E+01 6.000000E+01 1 2.631397E+01 8.990841E+01 4.206533E-02 2.631394E+01 + 2.560006E+01 6.000000E+01 2 4.820838E+01 8.989223E+01 9.066956E-02 4.820830E+01 + 2.560006E+01 6.000000E+01 3 1.813056E+02 3.912900E-01 1.813014E+02 1.238181E+00 + 2.560006E+01 6.000000E+01 4 1.600283E+02 8.989223E+01 3.009848E-01 1.600280E+02 + 2.560006E+01 6.000000E+01 5 2.626792E+02 8.990839E+01 4.199771E-01 2.626789E+02 + 2.560006E+01 6.000000E+01 6 8.297894E+01 -1.633574E-03 8.297894E+01 -2.365833E-03 + 2.560006E+01 9.000000E+01 1 2.738228E-06 -9.005901E+01 -2.819910E-09 -2.738226E-06 + 2.560006E+01 9.000000E+01 2 5.595417E+01 8.989223E+01 1.052474E-01 5.595407E+01 + 2.560006E+01 9.000000E+01 3 1.822680E+02 3.922426E-01 1.822638E+02 1.247784E+00 + 2.560006E+01 9.000000E+01 4 1.865367E+02 8.989268E+01 3.493795E-01 1.865363E+02 + 2.560006E+01 9.000000E+01 5 1.245393E-04 -8.998556E+01 3.138911E-08 -1.245393E-04 + 2.560006E+01 9.000000E+01 6 7.141562E-06 1.799989E+02 -7.141562E-06 1.368536E-10 + 2.570006E+01 0.000000E+00 1 5.169181E+01 8.990916E+01 8.195859E-02 5.169174E+01 + 2.570006E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.570006E+01 0.000000E+00 3 1.786752E+02 3.852565E-01 1.786711E+02 1.201402E+00 + 2.570006E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.570006E+01 0.000000E+00 5 5.166389E+02 8.990916E+01 8.191053E-01 5.166382E+02 + 2.570006E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.570006E+01 3.000000E+01 1 4.497443E+01 8.990917E+01 7.129841E-02 4.497437E+01 + 2.570006E+01 3.000000E+01 2 2.743947E+01 8.989327E+01 5.111049E-02 2.743943E+01 + 2.570006E+01 3.000000E+01 3 1.796143E+02 3.861879E-01 1.796102E+02 1.210636E+00 + 2.570006E+01 3.000000E+01 4 9.026964E+01 8.989235E+01 1.696022E-01 9.026948E+01 + 2.570006E+01 3.000000E+01 5 4.494815E+02 8.990917E+01 7.125678E-01 4.494809E+02 + 2.570006E+01 3.000000E+01 6 8.142542E+01 -1.609643E-03 8.142542E+01 -2.287530E-03 + 2.570006E+01 6.000000E+01 1 2.620855E+01 8.990919E+01 4.153742E-02 2.620851E+01 + 2.570006E+01 6.000000E+01 2 4.801499E+01 8.989326E+01 8.945265E-02 4.801491E+01 + 2.570006E+01 6.000000E+01 3 1.815072E+02 3.880599E-01 1.815030E+02 1.229325E+00 + 2.570006E+01 6.000000E+01 4 1.593258E+02 8.989326E+01 2.968335E-01 1.593255E+02 + 2.570006E+01 6.000000E+01 5 2.618866E+02 8.990918E+01 4.151195E-01 2.618863E+02 + 2.570006E+01 6.000000E+01 6 8.228532E+01 -1.603900E-03 8.228532E+01 -2.303440E-03 + 2.570006E+01 9.000000E+01 1 2.727010E-06 -9.005869E+01 -2.792771E-09 -2.727008E-06 + 2.570006E+01 9.000000E+01 2 5.572707E+01 8.989325E+01 1.038303E-01 5.572697E+01 + 2.570006E+01 9.000000E+01 3 1.824620E+02 3.889971E-01 1.824578E+02 1.238776E+00 + 2.570006E+01 9.000000E+01 4 1.857030E+02 8.989370E+01 3.445441E-01 1.857027E+02 + 2.570006E+01 9.000000E+01 5 1.240707E-04 -8.998573E+01 3.089279E-08 -1.240707E-04 + 2.570006E+01 9.000000E+01 6 7.081438E-06 1.799989E+02 -7.081438E-06 1.332513E-10 + 2.580006E+01 0.000000E+00 1 5.149174E+01 8.990993E+01 8.094350E-02 5.149168E+01 + 2.580006E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.580006E+01 0.000000E+00 3 1.788970E+02 3.821118E-01 1.788931E+02 1.193075E+00 + 2.580006E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.580006E+01 0.000000E+00 5 5.151501E+02 8.990994E+01 8.097555E-01 5.151495E+02 + 2.580006E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.580006E+01 3.000000E+01 1 4.479865E+01 8.990995E+01 7.041294E-02 4.479859E+01 + 2.580006E+01 3.000000E+01 2 2.733228E+01 8.989428E+01 5.043266E-02 2.733224E+01 + 2.580006E+01 3.000000E+01 3 1.798286E+02 3.830300E-01 1.798246E+02 1.202170E+00 + 2.580006E+01 3.000000E+01 4 8.988863E+01 8.989337E+01 1.672889E-01 8.988848E+01 + 2.580006E+01 3.000000E+01 5 4.481632E+02 8.990995E+01 7.044100E-01 4.481627E+02 + 2.580006E+01 3.000000E+01 6 8.075513E+01 -1.580509E-03 8.075513E+01 -2.227637E-03 + 2.580006E+01 6.000000E+01 1 2.610392E+01 8.990997E+01 4.101842E-02 2.610389E+01 + 2.580006E+01 6.000000E+01 2 4.782318E+01 8.989426E+01 8.825807E-02 4.782310E+01 + 2.580006E+01 6.000000E+01 3 1.817074E+02 3.848689E-01 1.817033E+02 1.220561E+00 + 2.580006E+01 6.000000E+01 4 1.586282E+02 8.989426E+01 2.927581E-01 1.586279E+02 + 2.580006E+01 6.000000E+01 5 2.610994E+02 8.990996E+01 4.103387E-01 2.610991E+02 + 2.580006E+01 6.000000E+01 6 8.160052E+01 -1.574919E-03 8.160052E+01 -2.242996E-03 + 2.580006E+01 9.000000E+01 1 2.715886E-06 -9.005836E+01 -2.765918E-09 -2.715885E-06 + 2.580006E+01 9.000000E+01 2 5.550196E+01 8.989425E+01 1.024391E-01 5.550187E+01 + 2.580006E+01 9.000000E+01 3 1.826550E+02 3.857875E-01 1.826509E+02 1.229855E+00 + 2.580006E+01 9.000000E+01 4 1.848768E+02 8.989470E+01 3.397984E-01 1.848765E+02 + 2.580006E+01 9.000000E+01 5 1.236045E-04 -8.998591E+01 3.040703E-08 -1.236045E-04 + 2.580006E+01 9.000000E+01 6 7.022090E-06 1.799989E+02 -7.022090E-06 1.297610E-10 + 2.590006E+01 0.000000E+00 1 5.129295E+01 8.991070E+01 7.994528E-02 5.129289E+01 + 2.590006E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.590006E+01 0.000000E+00 3 1.791144E+02 3.790093E-01 1.791105E+02 1.184826E+00 + 2.590006E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.590006E+01 0.000000E+00 5 5.136596E+02 8.991071E+01 8.005537E-01 5.136590E+02 + 2.590006E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.590006E+01 3.000000E+01 1 4.462414E+01 8.991071E+01 6.954189E-02 4.462409E+01 + 2.590006E+01 3.000000E+01 2 2.722587E+01 8.989527E+01 4.976699E-02 2.722582E+01 + 2.590006E+01 3.000000E+01 3 1.800397E+02 3.799113E-01 1.800357E+02 1.193781E+00 + 2.590006E+01 3.000000E+01 4 8.951101E+01 8.989437E+01 1.650197E-01 8.951086E+01 + 2.590006E+01 3.000000E+01 5 4.468538E+02 8.991071E+01 6.963717E-01 4.468533E+02 + 2.590006E+01 3.000000E+01 6 8.009295E+01 -1.552043E-03 8.009295E+01 -2.169579E-03 + 2.590006E+01 6.000000E+01 1 2.600018E+01 8.991074E+01 4.050803E-02 2.600015E+01 + 2.590006E+01 6.000000E+01 2 4.763277E+01 8.989525E+01 8.708522E-02 4.763269E+01 + 2.590006E+01 6.000000E+01 3 1.819051E+02 3.817146E-01 1.819011E+02 1.211875E+00 + 2.590006E+01 6.000000E+01 4 1.579380E+02 8.989525E+01 2.887590E-01 1.579378E+02 + 2.590006E+01 6.000000E+01 5 2.603143E+02 8.991072E+01 4.056258E-01 2.603140E+02 + 2.590006E+01 6.000000E+01 6 8.092432E+01 -1.546603E-03 8.092432E+01 -2.184416E-03 + 2.590006E+01 9.000000E+01 1 2.704857E-06 -9.005803E+01 -2.739347E-09 -2.704856E-06 + 2.590006E+01 9.000000E+01 2 5.527861E+01 8.989524E+01 1.010732E-01 5.527851E+01 + 2.590006E+01 9.000000E+01 3 1.828451E+02 3.826203E-01 1.828410E+02 1.221027E+00 + 2.590006E+01 9.000000E+01 4 1.840587E+02 8.989568E+01 3.351416E-01 1.840584E+02 + 2.590006E+01 9.000000E+01 5 1.231414E-04 -8.998608E+01 2.993141E-08 -1.231414E-04 + 2.590006E+01 9.000000E+01 6 6.963511E-06 1.799990E+02 -6.963511E-06 1.263779E-10 + 2.600006E+01 0.000000E+00 1 5.109602E+01 8.991145E+01 7.896393E-02 5.109596E+01 + 2.600006E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.600006E+01 0.000000E+00 3 1.793311E+02 3.759445E-01 1.793272E+02 1.176667E+00 + 2.600006E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.600006E+01 0.000000E+00 5 5.121817E+02 8.991146E+01 7.914839E-01 5.121811E+02 + 2.600006E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.600006E+01 3.000000E+01 1 4.445098E+01 8.991147E+01 6.868564E-02 4.445093E+01 + 2.600006E+01 3.000000E+01 2 2.712029E+01 8.989624E+01 4.911324E-02 2.712024E+01 + 2.600006E+01 3.000000E+01 3 1.802490E+02 3.768303E-01 1.802451E+02 1.185476E+00 + 2.600006E+01 3.000000E+01 4 8.913700E+01 8.989536E+01 1.627916E-01 8.913686E+01 + 2.600006E+01 3.000000E+01 5 4.455464E+02 8.991146E+01 6.884615E-01 4.455459E+02 + 2.600006E+01 3.000000E+01 6 7.943929E+01 -1.524229E-03 7.943929E+01 -2.113309E-03 + 2.600006E+01 6.000000E+01 1 2.589724E+01 8.991149E+01 4.000637E-02 2.589721E+01 + 2.600006E+01 6.000000E+01 2 4.744403E+01 8.989622E+01 8.593361E-02 4.744396E+01 + 2.600006E+01 6.000000E+01 3 1.820998E+02 3.786066E-01 1.820958E+02 1.203294E+00 + 2.600006E+01 6.000000E+01 4 1.572541E+02 8.989622E+01 2.848348E-01 1.572538E+02 + 2.600006E+01 6.000000E+01 5 2.595318E+02 8.991148E+01 4.009877E-01 2.595315E+02 + 2.600006E+01 6.000000E+01 6 8.025684E+01 -1.518931E-03 8.025684E+01 -2.127636E-03 + 2.600006E+01 9.000000E+01 1 2.693912E-06 -9.005771E+01 -2.713053E-09 -2.693911E-06 + 2.600006E+01 9.000000E+01 2 5.505724E+01 8.989621E+01 9.973222E-02 5.505715E+01 + 2.600006E+01 9.000000E+01 3 1.830339E+02 3.794927E-01 1.830299E+02 1.212297E+00 + 2.600006E+01 9.000000E+01 4 1.832482E+02 8.989664E+01 3.305736E-01 1.832479E+02 + 2.600006E+01 9.000000E+01 5 1.226827E-04 -8.998624E+01 2.946566E-08 -1.226827E-04 + 2.600006E+01 9.000000E+01 6 6.905673E-06 1.799990E+02 -6.905673E-06 1.230990E-10 + 2.610006E+01 0.000000E+00 1 5.090041E+01 8.991220E+01 7.799821E-02 5.090035E+01 + 2.610006E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.610006E+01 0.000000E+00 3 1.795460E+02 3.729165E-01 1.795422E+02 1.168588E+00 + 2.610006E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.610006E+01 0.000000E+00 5 5.107065E+02 8.991221E+01 7.825466E-01 5.107059E+02 + 2.610006E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.610006E+01 3.000000E+01 1 4.427908E+01 8.991222E+01 6.784350E-02 4.427903E+01 + 2.610006E+01 3.000000E+01 2 2.701556E+01 8.989720E+01 4.847119E-02 2.701551E+01 + 2.610006E+01 3.000000E+01 3 1.804570E+02 3.737855E-01 1.804531E+02 1.177255E+00 + 2.610006E+01 3.000000E+01 4 8.876540E+01 8.989633E+01 1.606045E-01 8.876526E+01 + 2.610006E+01 3.000000E+01 5 4.442437E+02 8.991222E+01 6.806616E-01 4.442431E+02 + 2.610006E+01 3.000000E+01 6 7.879364E+01 -1.497048E-03 7.879364E+01 -2.058754E-03 + 2.610006E+01 6.000000E+01 1 2.579519E+01 8.991224E+01 3.951291E-02 2.579516E+01 + 2.610006E+01 6.000000E+01 2 4.725676E+01 8.989718E+01 8.480272E-02 4.725668E+01 + 2.610006E+01 6.000000E+01 3 1.822945E+02 3.755299E-01 1.822906E+02 1.194792E+00 + 2.610006E+01 6.000000E+01 4 1.565759E+02 8.989718E+01 2.809838E-01 1.565756E+02 + 2.610006E+01 6.000000E+01 5 2.587555E+02 8.991222E+01 3.964159E-01 2.587552E+02 + 2.610006E+01 6.000000E+01 6 7.959760E+01 -1.491891E-03 7.959760E+01 -2.072594E-03 + 2.610006E+01 9.000000E+01 1 2.683070E-06 -9.005738E+01 -2.687030E-09 -2.683068E-06 + 2.610006E+01 9.000000E+01 2 5.483751E+01 8.989718E+01 9.841555E-02 5.483743E+01 + 2.610006E+01 9.000000E+01 3 1.832212E+02 3.764021E-01 1.832172E+02 1.203655E+00 + 2.610006E+01 9.000000E+01 4 1.824440E+02 8.989759E+01 3.260891E-01 1.824437E+02 + 2.610006E+01 9.000000E+01 5 1.222264E-04 -8.998640E+01 2.900953E-08 -1.222264E-04 + 2.610006E+01 9.000000E+01 6 6.848570E-06 1.799990E+02 -6.848570E-06 1.199204E-10 + 2.620006E+01 0.000000E+00 1 5.070644E+01 8.991294E+01 7.704881E-02 5.070638E+01 + 2.620006E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.620006E+01 0.000000E+00 3 1.797571E+02 3.699245E-01 1.797534E+02 1.160576E+00 + 2.620006E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.620006E+01 0.000000E+00 5 5.092314E+02 8.991295E+01 7.737415E-01 5.092308E+02 + 2.620006E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.620006E+01 3.000000E+01 1 4.410872E+01 8.991296E+01 6.701516E-02 4.410867E+01 + 2.620006E+01 3.000000E+01 2 2.691160E+01 8.989815E+01 4.784046E-02 2.691155E+01 + 2.620006E+01 3.000000E+01 3 1.806618E+02 3.707798E-01 1.806580E+02 1.169114E+00 + 2.620006E+01 3.000000E+01 4 8.839765E+01 8.989730E+01 1.584572E-01 8.839751E+01 + 2.620006E+01 3.000000E+01 5 4.429486E+02 8.991296E+01 6.729875E-01 4.429481E+02 + 2.620006E+01 3.000000E+01 6 7.815615E+01 -1.470482E-03 7.815615E+01 -2.005859E-03 + 2.620006E+01 6.000000E+01 1 2.569386E+01 8.991297E+01 3.902771E-02 2.569383E+01 + 2.620006E+01 6.000000E+01 2 4.707100E+01 8.989813E+01 8.369195E-02 4.707092E+01 + 2.620006E+01 6.000000E+01 3 1.824854E+02 3.724924E-01 1.824815E+02 1.186369E+00 + 2.620006E+01 6.000000E+01 4 1.559037E+02 8.989812E+01 2.772022E-01 1.559034E+02 + 2.620006E+01 6.000000E+01 5 2.579809E+02 8.991296E+01 3.919181E-01 2.579806E+02 + 2.620006E+01 6.000000E+01 6 7.894678E+01 -1.465459E-03 7.894678E+01 -2.019228E-03 + 2.620006E+01 9.000000E+01 1 2.672306E-06 -9.005706E+01 -2.661287E-09 -2.672305E-06 + 2.620006E+01 9.000000E+01 2 5.461969E+01 8.989812E+01 9.712229E-02 5.461960E+01 + 2.620006E+01 9.000000E+01 3 1.834053E+02 3.733473E-01 1.834014E+02 1.195086E+00 + 2.620006E+01 9.000000E+01 4 1.816475E+02 8.989854E+01 3.216880E-01 1.816472E+02 + 2.620006E+01 9.000000E+01 5 1.217739E-04 -8.998656E+01 2.856275E-08 -1.217739E-04 + 2.620006E+01 9.000000E+01 6 6.792188E-06 1.799990E+02 -6.792188E-06 1.168381E-10 + 2.630006E+01 0.000000E+00 1 5.051381E+01 8.991367E+01 7.611477E-02 5.051376E+01 + 2.630006E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.630006E+01 0.000000E+00 3 1.799664E+02 3.669711E-01 1.799627E+02 1.152651E+00 + 2.630006E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.630006E+01 0.000000E+00 5 5.077678E+02 8.991367E+01 7.650717E-01 5.077672E+02 + 2.630006E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.630006E+01 3.000000E+01 1 4.393940E+01 8.991367E+01 6.620029E-02 4.393935E+01 + 2.630006E+01 3.000000E+01 2 2.680844E+01 8.989908E+01 4.722099E-02 2.680840E+01 + 2.630006E+01 3.000000E+01 3 1.808641E+02 3.678109E-01 1.808603E+02 1.161051E+00 + 2.630006E+01 3.000000E+01 4 8.803287E+01 8.989824E+01 1.563495E-01 8.803273E+01 + 2.630006E+01 3.000000E+01 5 4.416592E+02 8.991367E+01 6.654167E-01 4.416587E+02 + 2.630006E+01 3.000000E+01 6 7.752633E+01 -1.444522E-03 7.752633E+01 -1.954567E-03 + 2.630006E+01 6.000000E+01 1 2.559350E+01 8.991370E+01 3.855051E-02 2.559347E+01 + 2.630006E+01 6.000000E+01 2 4.688665E+01 8.989906E+01 8.260126E-02 4.688658E+01 + 2.630006E+01 6.000000E+01 3 1.826747E+02 3.694938E-01 1.826709E+02 1.178040E+00 + 2.630006E+01 6.000000E+01 4 1.552378E+02 8.989906E+01 2.734921E-01 1.552376E+02 + 2.630006E+01 6.000000E+01 5 2.572104E+02 8.991368E+01 3.874862E-01 2.572101E+02 + 2.630006E+01 6.000000E+01 6 7.830399E+01 -1.439627E-03 7.830399E+01 -1.967484E-03 + 2.630006E+01 9.000000E+01 1 2.661636E-06 -9.005674E+01 -2.635820E-09 -2.661635E-06 + 2.630006E+01 9.000000E+01 2 5.440361E+01 8.989906E+01 9.585236E-02 5.440353E+01 + 2.630006E+01 9.000000E+01 3 1.835871E+02 3.703380E-01 1.835832E+02 1.186628E+00 + 2.630006E+01 9.000000E+01 4 1.808585E+02 8.989946E+01 3.173669E-01 1.808582E+02 + 2.630006E+01 9.000000E+01 5 1.213248E-04 -8.998672E+01 2.812506E-08 -1.213248E-04 + 2.630006E+01 9.000000E+01 6 6.736523E-06 1.799990E+02 -6.736523E-06 1.138494E-10 + 2.640006E+01 0.000000E+00 1 5.032254E+01 8.991439E+01 7.519586E-02 5.032248E+01 + 2.640006E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.640006E+01 0.000000E+00 3 1.801734E+02 3.640529E-01 1.801698E+02 1.144800E+00 + 2.640006E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.640006E+01 0.000000E+00 5 5.063096E+02 8.991439E+01 7.565247E-01 5.063090E+02 + 2.640006E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.640006E+01 3.000000E+01 1 4.377151E+01 8.991439E+01 6.539898E-02 4.377147E+01 + 2.640006E+01 3.000000E+01 2 2.670610E+01 8.989999E+01 4.661248E-02 2.670606E+01 + 2.640006E+01 3.000000E+01 3 1.810648E+02 3.648795E-01 1.810612E+02 1.153076E+00 + 2.640006E+01 3.000000E+01 4 8.767094E+01 8.989918E+01 1.542793E-01 8.767080E+01 + 2.640006E+01 3.000000E+01 5 4.403716E+02 8.991439E+01 6.579621E-01 4.403712E+02 + 2.640006E+01 3.000000E+01 6 7.690427E+01 -1.419140E-03 7.690427E+01 -1.904816E-03 + 2.640006E+01 6.000000E+01 1 2.549375E+01 8.991441E+01 3.808119E-02 2.549372E+01 + 2.640006E+01 6.000000E+01 2 4.670385E+01 8.989998E+01 8.152983E-02 4.670377E+01 + 2.640006E+01 6.000000E+01 3 1.828615E+02 3.665332E-01 1.828577E+02 1.169795E+00 + 2.640006E+01 6.000000E+01 4 1.545782E+02 8.989998E+01 2.698491E-01 1.545780E+02 + 2.640006E+01 6.000000E+01 5 2.564434E+02 8.991440E+01 3.831136E-01 2.564431E+02 + 2.640006E+01 6.000000E+01 6 7.766911E+01 -1.414375E-03 7.766911E+01 -1.917301E-03 + 2.640006E+01 9.000000E+01 1 2.651050E-06 -9.005642E+01 -2.610633E-09 -2.651049E-06 + 2.640006E+01 9.000000E+01 2 5.418918E+01 8.989998E+01 9.460504E-02 5.418909E+01 + 2.640006E+01 9.000000E+01 3 1.837673E+02 3.673604E-01 1.837635E+02 1.178243E+00 + 2.640006E+01 9.000000E+01 4 1.800775E+02 8.990038E+01 3.131272E-01 1.800772E+02 + 2.640006E+01 9.000000E+01 5 1.208786E-04 -8.998688E+01 2.769650E-08 -1.208786E-04 + 2.640006E+01 9.000000E+01 6 6.681551E-06 1.799991E+02 -6.681551E-06 1.109505E-10 + 2.650006E+01 0.000000E+00 1 5.013262E+01 8.991509E+01 7.429196E-02 5.013257E+01 + 2.650006E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.650006E+01 0.000000E+00 3 1.803780E+02 3.611699E-01 1.803744E+02 1.137024E+00 + 2.650006E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.650006E+01 0.000000E+00 5 5.048548E+02 8.991510E+01 7.481000E-01 5.048543E+02 + 2.650006E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.650006E+01 3.000000E+01 1 4.360493E+01 8.991511E+01 6.461056E-02 4.360489E+01 + 2.650006E+01 3.000000E+01 2 2.660445E+01 8.990090E+01 4.601443E-02 2.660441E+01 + 2.650006E+01 3.000000E+01 3 1.812630E+02 3.619791E-01 1.812593E+02 1.145162E+00 + 2.650006E+01 3.000000E+01 4 8.731237E+01 8.990009E+01 1.522471E-01 8.731224E+01 + 2.650006E+01 3.000000E+01 5 4.390908E+02 8.991511E+01 6.506217E-01 4.390903E+02 + 2.650006E+01 3.000000E+01 6 7.628987E+01 -1.394326E-03 7.628987E+01 -1.856558E-03 + 2.650006E+01 6.000000E+01 1 2.539485E+01 8.991512E+01 3.761959E-02 2.539482E+01 + 2.650006E+01 6.000000E+01 2 4.652246E+01 8.990089E+01 8.047722E-02 4.652239E+01 + 2.650006E+01 6.000000E+01 3 1.830477E+02 3.636064E-01 1.830440E+02 1.161637E+00 + 2.650006E+01 6.000000E+01 4 1.539234E+02 8.990089E+01 2.662709E-01 1.539231E+02 + 2.650006E+01 6.000000E+01 5 2.556804E+02 8.991511E+01 3.788157E-01 2.556801E+02 + 2.650006E+01 6.000000E+01 6 7.704235E+01 -1.389681E-03 7.704235E+01 -1.868624E-03 + 2.650006E+01 9.000000E+01 1 2.640545E-06 -9.005611E+01 -2.585707E-09 -2.640544E-06 + 2.650006E+01 9.000000E+01 2 5.397648E+01 8.990088E+01 9.337966E-02 5.397640E+01 + 2.650006E+01 9.000000E+01 3 1.839465E+02 3.644179E-01 1.839428E+02 1.169946E+00 + 2.650006E+01 9.000000E+01 4 1.793023E+02 8.990128E+01 3.089624E-01 1.793020E+02 + 2.650006E+01 9.000000E+01 5 1.204361E-04 -8.998702E+01 2.727646E-08 -1.204361E-04 + 2.650006E+01 9.000000E+01 6 6.627258E-06 1.799991E+02 -6.627258E-06 1.081387E-10 + 2.660007E+01 0.000000E+00 1 4.994437E+01 8.991579E+01 7.340250E-02 4.994431E+01 + 2.660007E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.660007E+01 0.000000E+00 3 1.805811E+02 3.583170E-01 1.805776E+02 1.129313E+00 + 2.660007E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.660007E+01 0.000000E+00 5 5.034080E+02 8.991580E+01 7.398058E-01 5.034074E+02 + 2.660007E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.660007E+01 3.000000E+01 1 4.343951E+01 8.991580E+01 6.383497E-02 4.343946E+01 + 2.660007E+01 3.000000E+01 2 2.650364E+01 8.990180E+01 4.542688E-02 2.650360E+01 + 2.660007E+01 3.000000E+01 3 1.814593E+02 3.591148E-01 1.814557E+02 1.137331E+00 + 2.660007E+01 3.000000E+01 4 8.695663E+01 8.990100E+01 1.502510E-01 8.695650E+01 + 2.660007E+01 3.000000E+01 5 4.378155E+02 8.991580E+01 6.433796E-01 4.378150E+02 + 2.660007E+01 3.000000E+01 6 7.568286E+01 -1.370062E-03 7.568286E+01 -1.809736E-03 + 2.660007E+01 6.000000E+01 1 2.529667E+01 8.991582E+01 3.716544E-02 2.529665E+01 + 2.660007E+01 6.000000E+01 2 4.634241E+01 8.990178E+01 7.944313E-02 4.634234E+01 + 2.660007E+01 6.000000E+01 3 1.832295E+02 3.607149E-01 1.832259E+02 1.153543E+00 + 2.660007E+01 6.000000E+01 4 1.532749E+02 8.990178E+01 2.627592E-01 1.532746E+02 + 2.660007E+01 6.000000E+01 5 2.549184E+02 8.991581E+01 3.745768E-01 2.549181E+02 + 2.660007E+01 6.000000E+01 6 7.642311E+01 -1.365538E-03 7.642311E+01 -1.821402E-03 + 2.660007E+01 9.000000E+01 1 2.630131E-06 -9.005579E+01 -2.561041E-09 -2.630130E-06 + 2.660007E+01 9.000000E+01 2 5.376562E+01 8.990177E+01 9.217608E-02 5.376554E+01 + 2.660007E+01 9.000000E+01 3 1.841226E+02 3.615143E-01 1.841189E+02 1.161735E+00 + 2.660007E+01 9.000000E+01 4 1.785347E+02 8.990216E+01 3.048739E-01 1.785345E+02 + 2.660007E+01 9.000000E+01 5 1.199960E-04 -8.998717E+01 2.686492E-08 -1.199960E-04 + 2.660007E+01 9.000000E+01 6 6.573651E-06 1.799991E+02 -6.573651E-06 1.054108E-10 + 2.670007E+01 0.000000E+00 1 4.975744E+01 8.991648E+01 7.252754E-02 4.975739E+01 + 2.670007E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.670007E+01 0.000000E+00 3 1.807815E+02 3.555000E-01 1.807780E+02 1.121678E+00 + 2.670007E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.670007E+01 0.000000E+00 5 5.019677E+02 8.991649E+01 7.316379E-01 5.019671E+02 + 2.670007E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.670007E+01 3.000000E+01 1 4.327540E+01 8.991650E+01 6.307177E-02 4.327536E+01 + 2.670007E+01 3.000000E+01 2 2.640359E+01 8.990268E+01 4.484951E-02 2.640355E+01 + 2.670007E+01 3.000000E+01 3 1.816536E+02 3.562858E-01 1.816501E+02 1.129580E+00 + 2.670007E+01 3.000000E+01 4 8.660397E+01 8.990189E+01 1.482904E-01 8.660384E+01 + 2.670007E+01 3.000000E+01 5 4.365475E+02 8.991649E+01 6.362560E-01 4.365471E+02 + 2.670007E+01 3.000000E+01 6 7.508324E+01 -1.346339E-03 7.508324E+01 -1.764310E-03 + 2.670007E+01 6.000000E+01 1 2.519938E+01 8.991651E+01 3.671863E-02 2.519935E+01 + 2.670007E+01 6.000000E+01 2 4.616380E+01 8.990266E+01 7.842716E-02 4.616373E+01 + 2.670007E+01 6.000000E+01 3 1.834113E+02 3.578544E-01 1.834077E+02 1.145531E+00 + 2.670007E+01 6.000000E+01 4 1.526322E+02 8.990266E+01 2.593098E-01 1.526319E+02 + 2.670007E+01 6.000000E+01 5 2.541618E+02 8.991650E+01 3.703984E-01 2.541615E+02 + 2.670007E+01 6.000000E+01 6 7.581155E+01 -1.341930E-03 7.581155E+01 -1.775589E-03 + 2.670007E+01 9.000000E+01 1 2.619800E-06 -9.005548E+01 -2.536655E-09 -2.619799E-06 + 2.670007E+01 9.000000E+01 2 5.355633E+01 8.990266E+01 9.099358E-02 5.355625E+01 + 2.670007E+01 9.000000E+01 3 1.842975E+02 3.586431E-01 1.842939E+02 1.153603E+00 + 2.670007E+01 9.000000E+01 4 1.777730E+02 8.990304E+01 3.008603E-01 1.777727E+02 + 2.670007E+01 9.000000E+01 5 1.195592E-04 -8.998732E+01 2.646168E-08 -1.195592E-04 + 2.670007E+01 9.000000E+01 6 6.520702E-06 1.799991E+02 -6.520702E-06 1.027639E-10 + 2.680007E+01 0.000000E+00 1 4.957199E+01 8.991717E+01 7.166658E-02 4.957193E+01 + 2.680007E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.680007E+01 0.000000E+00 3 1.809795E+02 3.527180E-01 1.809761E+02 1.114119E+00 + 2.680007E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.680007E+01 0.000000E+00 5 5.005284E+02 8.991718E+01 7.235785E-01 5.005278E+02 + 2.680007E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.680007E+01 3.000000E+01 1 4.311250E+01 8.991718E+01 6.232109E-02 4.311246E+01 + 2.680007E+01 3.000000E+01 2 2.630436E+01 8.990355E+01 4.428224E-02 2.630432E+01 + 2.680007E+01 3.000000E+01 3 1.818457E+02 3.534885E-01 1.818422E+02 1.121897E+00 + 2.680007E+01 3.000000E+01 4 8.625410E+01 8.990278E+01 1.463647E-01 8.625397E+01 + 2.680007E+01 3.000000E+01 5 4.352836E+02 8.991718E+01 6.292251E-01 4.352831E+02 + 2.680007E+01 3.000000E+01 6 7.449078E+01 -1.323138E-03 7.449078E+01 -1.720224E-03 + 2.680007E+01 6.000000E+01 1 2.510277E+01 8.991719E+01 3.627928E-02 2.510275E+01 + 2.680007E+01 6.000000E+01 2 4.598661E+01 8.990353E+01 7.742900E-02 4.598655E+01 + 2.680007E+01 6.000000E+01 3 1.835903E+02 3.550344E-01 1.835868E+02 1.137614E+00 + 2.680007E+01 6.000000E+01 4 1.519946E+02 8.990353E+01 2.559225E-01 1.519944E+02 + 2.680007E+01 6.000000E+01 5 2.534075E+02 8.991718E+01 3.662858E-01 2.534072E+02 + 2.680007E+01 6.000000E+01 6 7.520734E+01 -1.318840E-03 7.520734E+01 -1.731130E-03 + 2.680007E+01 9.000000E+01 1 2.609547E-06 -9.005516E+01 -2.512525E-09 -2.609546E-06 + 2.680007E+01 9.000000E+01 2 5.334876E+01 8.990352E+01 8.983179E-02 5.334868E+01 + 2.680007E+01 9.000000E+01 3 1.844700E+02 3.558068E-01 1.844665E+02 1.145552E+00 + 2.680007E+01 9.000000E+01 4 1.770188E+02 8.990389E+01 2.969182E-01 1.770186E+02 + 2.680007E+01 9.000000E+01 5 1.191260E-04 -8.998746E+01 2.606647E-08 -1.191260E-04 + 2.680007E+01 9.000000E+01 6 6.468401E-06 1.799991E+02 -6.468401E-06 1.001952E-10 + 2.690007E+01 0.000000E+00 1 4.938780E+01 8.991785E+01 7.081942E-02 4.938775E+01 + 2.690007E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.690007E+01 0.000000E+00 3 1.811754E+02 3.499687E-01 1.811720E+02 1.106632E+00 + 2.690007E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.690007E+01 0.000000E+00 5 4.990980E+02 8.991785E+01 7.156407E-01 4.990975E+02 + 2.690007E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.690007E+01 3.000000E+01 1 4.295082E+01 8.991785E+01 6.158246E-02 4.295078E+01 + 2.690007E+01 3.000000E+01 2 2.620577E+01 8.990440E+01 4.372468E-02 2.620573E+01 + 2.690007E+01 3.000000E+01 3 1.820351E+02 3.507273E-01 1.820317E+02 1.114293E+00 + 2.690007E+01 3.000000E+01 4 8.590702E+01 8.990364E+01 1.444738E-01 8.590690E+01 + 2.690007E+01 3.000000E+01 5 4.340239E+02 8.991785E+01 6.222978E-01 4.340234E+02 + 2.690007E+01 3.000000E+01 6 7.390546E+01 -1.300444E-03 7.390546E+01 -1.677434E-03 + 2.690007E+01 6.000000E+01 1 2.500688E+01 8.991787E+01 3.584683E-02 2.500686E+01 + 2.690007E+01 6.000000E+01 2 4.581085E+01 8.990439E+01 7.644784E-02 4.581078E+01 + 2.690007E+01 6.000000E+01 3 1.837681E+02 3.522452E-01 1.837646E+02 1.129770E+00 + 2.690007E+01 6.000000E+01 4 1.513629E+02 8.990439E+01 2.525952E-01 1.513627E+02 + 2.690007E+01 6.000000E+01 5 2.526579E+02 8.991785E+01 3.622274E-01 2.526577E+02 + 2.690007E+01 6.000000E+01 6 7.461059E+01 -1.296254E-03 7.461059E+01 -1.687982E-03 + 2.690007E+01 9.000000E+01 1 2.599385E-06 -9.005486E+01 -2.488661E-09 -2.599384E-06 + 2.690007E+01 9.000000E+01 2 5.314262E+01 8.990438E+01 8.869006E-02 5.314255E+01 + 2.690007E+01 9.000000E+01 3 1.846405E+02 3.530075E-01 1.846369E+02 1.137589E+00 + 2.690007E+01 9.000000E+01 4 1.762712E+02 8.990475E+01 2.930458E-01 1.762710E+02 + 2.690007E+01 9.000000E+01 5 1.186961E-04 -8.998761E+01 2.567913E-08 -1.186961E-04 + 2.690007E+01 9.000000E+01 6 6.416746E-06 1.799991E+02 -6.416746E-06 9.770214E-11 + 2.700007E+01 0.000000E+00 1 4.920490E+01 8.991850E+01 6.998554E-02 4.920485E+01 + 2.700007E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.700007E+01 0.000000E+00 3 1.813689E+02 3.472509E-01 1.813656E+02 1.099211E+00 + 2.700007E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.700007E+01 0.000000E+00 5 4.976733E+02 8.991851E+01 7.078170E-01 4.976729E+02 + 2.700007E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.700007E+01 3.000000E+01 1 4.279038E+01 8.991852E+01 6.085530E-02 4.279034E+01 + 2.700007E+01 3.000000E+01 2 2.610797E+01 8.990525E+01 4.317663E-02 2.610794E+01 + 2.700007E+01 3.000000E+01 3 1.822231E+02 3.479971E-01 1.822197E+02 1.106760E+00 + 2.700007E+01 3.000000E+01 4 8.556313E+01 8.990450E+01 1.426155E-01 8.556300E+01 + 2.700007E+01 3.000000E+01 5 4.327675E+02 8.991851E+01 6.154766E-01 4.327670E+02 + 2.700007E+01 3.000000E+01 6 7.332723E+01 -1.278245E-03 7.332723E+01 -1.635900E-03 + 2.700007E+01 6.000000E+01 1 2.491184E+01 8.991853E+01 3.542138E-02 2.491181E+01 + 2.700007E+01 6.000000E+01 2 4.563639E+01 8.990524E+01 7.548375E-02 4.563633E+01 + 2.700007E+01 6.000000E+01 3 1.839427E+02 3.494898E-01 1.839393E+02 1.121997E+00 + 2.700007E+01 6.000000E+01 4 1.507368E+02 8.990523E+01 2.493267E-01 1.507366E+02 + 2.700007E+01 6.000000E+01 5 2.519093E+02 8.991852E+01 3.582369E-01 2.519090E+02 + 2.700007E+01 6.000000E+01 6 7.402103E+01 -1.274159E-03 7.402103E+01 -1.646100E-03 + 2.700007E+01 9.000000E+01 1 2.589300E-06 -9.005455E+01 -2.465060E-09 -2.589299E-06 + 2.700007E+01 9.000000E+01 2 5.293827E+01 8.990523E+01 8.756818E-02 5.293820E+01 + 2.700007E+01 9.000000E+01 3 1.848093E+02 3.502394E-01 1.848058E+02 1.129701E+00 + 2.700007E+01 9.000000E+01 4 1.755305E+02 8.990559E+01 2.892429E-01 1.755303E+02 + 2.700007E+01 9.000000E+01 5 1.182691E-04 -8.998774E+01 2.529955E-08 -1.182691E-04 + 2.700007E+01 9.000000E+01 6 6.365723E-06 1.799991E+02 -6.365723E-06 9.528219E-11 + 2.710007E+01 0.000000E+00 1 4.902344E+01 8.991917E+01 6.916495E-02 4.902339E+01 + 2.710007E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.710007E+01 0.000000E+00 3 1.815618E+02 3.445647E-01 1.815585E+02 1.091867E+00 + 2.710007E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.710007E+01 0.000000E+00 5 4.962538E+02 8.991917E+01 7.001016E-01 4.962533E+02 + 2.710007E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.710007E+01 3.000000E+01 1 4.263114E+01 8.991917E+01 6.013989E-02 4.263110E+01 + 2.710007E+01 3.000000E+01 2 2.601083E+01 8.990608E+01 4.263784E-02 2.601079E+01 + 2.710007E+01 3.000000E+01 3 1.824096E+02 3.452974E-01 1.824062E+02 1.099298E+00 + 2.710007E+01 3.000000E+01 4 8.522180E+01 8.990534E+01 1.407893E-01 8.522169E+01 + 2.710007E+01 3.000000E+01 5 4.315216E+02 8.991917E+01 6.087543E-01 4.315212E+02 + 2.710007E+01 3.000000E+01 6 7.275581E+01 -1.256524E-03 7.275581E+01 -1.595569E-03 + 2.710007E+01 6.000000E+01 1 2.481732E+01 8.991919E+01 3.500267E-02 2.481729E+01 + 2.710007E+01 6.000000E+01 2 4.546335E+01 8.990607E+01 7.453614E-02 4.546329E+01 + 2.710007E+01 6.000000E+01 3 1.841169E+02 3.467660E-01 1.841135E+02 1.114307E+00 + 2.710007E+01 6.000000E+01 4 1.501154E+02 8.990606E+01 2.461157E-01 1.501152E+02 + 2.710007E+01 6.000000E+01 5 2.511670E+02 8.991918E+01 3.542949E-01 2.511668E+02 + 2.710007E+01 6.000000E+01 6 7.343852E+01 -1.252542E-03 7.343852E+01 -1.605438E-03 + 2.710007E+01 9.000000E+01 1 2.579291E-06 -9.005424E+01 -2.441710E-09 -2.579290E-06 + 2.710007E+01 9.000000E+01 2 5.273567E+01 8.990606E+01 8.646568E-02 5.273560E+01 + 2.710007E+01 9.000000E+01 3 1.849767E+02 3.475021E-01 1.849733E+02 1.121887E+00 + 2.710007E+01 9.000000E+01 4 1.747955E+02 8.990642E+01 2.855069E-01 1.747953E+02 + 2.710007E+01 9.000000E+01 5 1.178443E-04 -8.998788E+01 2.492732E-08 -1.178443E-04 + 2.710007E+01 9.000000E+01 6 6.315318E-06 1.799992E+02 -6.315318E-06 9.293270E-11 + 2.720007E+01 0.000000E+00 1 4.884344E+01 8.991982E+01 6.835720E-02 4.884339E+01 + 2.720007E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.720007E+01 0.000000E+00 3 1.817517E+02 3.419110E-01 1.817485E+02 1.084592E+00 + 2.720007E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.720007E+01 0.000000E+00 5 4.948399E+02 8.991982E+01 6.925036E-01 4.948394E+02 + 2.720007E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.720007E+01 3.000000E+01 1 4.247307E+01 8.991982E+01 5.943553E-02 4.247303E+01 + 2.720007E+01 3.000000E+01 2 2.591444E+01 8.990690E+01 4.210823E-02 2.591440E+01 + 2.720007E+01 3.000000E+01 3 1.825933E+02 3.426316E-01 1.825900E+02 1.091911E+00 + 2.720007E+01 3.000000E+01 4 8.488303E+01 8.990617E+01 1.389956E-01 8.488292E+01 + 2.720007E+01 3.000000E+01 5 4.302785E+02 8.991982E+01 6.021183E-01 4.302781E+02 + 2.720007E+01 3.000000E+01 6 7.219109E+01 -1.235276E-03 7.219109E+01 -1.556413E-03 + 2.720007E+01 6.000000E+01 1 2.472375E+01 8.991984E+01 3.459062E-02 2.472373E+01 + 2.720007E+01 6.000000E+01 2 4.529155E+01 8.990689E+01 7.360472E-02 4.529148E+01 + 2.720007E+01 6.000000E+01 3 1.842882E+02 3.440768E-01 1.842848E+02 1.106694E+00 + 2.720007E+01 6.000000E+01 4 1.494998E+02 8.990689E+01 2.429615E-01 1.494996E+02 + 2.720007E+01 6.000000E+01 5 2.504262E+02 8.991983E+01 3.504170E-01 2.504259E+02 + 2.720007E+01 6.000000E+01 6 7.286304E+01 -1.231394E-03 7.286304E+01 -1.565964E-03 + 2.720007E+01 9.000000E+01 1 2.569363E-06 -9.005393E+01 -2.418613E-09 -2.569362E-06 + 2.720007E+01 9.000000E+01 2 5.253433E+01 8.990688E+01 8.538185E-02 5.253426E+01 + 2.720007E+01 9.000000E+01 3 1.851433E+02 3.447990E-01 1.851400E+02 1.114163E+00 + 2.720007E+01 9.000000E+01 4 1.740674E+02 8.990723E+01 2.818376E-01 1.740672E+02 + 2.720007E+01 9.000000E+01 5 1.174236E-04 -8.998801E+01 2.456243E-08 -1.174236E-04 + 2.720007E+01 9.000000E+01 6 6.265522E-06 1.799992E+02 -6.265522E-06 9.065138E-11 + 2.730007E+01 0.000000E+00 1 4.866451E+01 8.992046E+01 6.756207E-02 4.866446E+01 + 2.730007E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.730007E+01 0.000000E+00 3 1.819394E+02 3.392879E-01 1.819362E+02 1.077383E+00 + 2.730007E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.730007E+01 0.000000E+00 5 4.934328E+02 8.992046E+01 6.850067E-01 4.934323E+02 + 2.730007E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.730007E+01 3.000000E+01 1 4.231627E+01 8.992046E+01 5.874249E-02 4.231622E+01 + 2.730007E+01 3.000000E+01 2 2.581881E+01 8.990771E+01 4.158749E-02 2.581878E+01 + 2.730007E+01 3.000000E+01 3 1.827751E+02 3.399976E-01 1.827719E+02 1.084595E+00 + 2.730007E+01 3.000000E+01 4 8.454766E+01 8.990701E+01 1.372326E-01 8.454755E+01 + 2.730007E+01 3.000000E+01 5 4.290386E+02 8.992046E+01 5.955858E-01 4.290382E+02 + 2.730007E+01 3.000000E+01 6 7.163303E+01 -1.214485E-03 7.163303E+01 -1.518388E-03 + 2.730007E+01 6.000000E+01 1 2.463076E+01 8.992048E+01 3.418513E-02 2.463073E+01 + 2.730007E+01 6.000000E+01 2 4.512109E+01 8.990770E+01 7.268921E-02 4.512103E+01 + 2.730007E+01 6.000000E+01 3 1.844582E+02 3.414169E-01 1.844549E+02 1.099152E+00 + 2.730007E+01 6.000000E+01 4 1.488900E+02 8.990770E+01 2.398632E-01 1.488898E+02 + 2.730007E+01 6.000000E+01 5 2.496882E+02 8.992046E+01 3.465922E-01 2.496879E+02 + 2.730007E+01 6.000000E+01 6 7.229449E+01 -1.210696E-03 7.229449E+01 -1.527628E-03 + 2.730007E+01 9.000000E+01 1 2.559514E-06 -9.005363E+01 -2.395775E-09 -2.559513E-06 + 2.730007E+01 9.000000E+01 2 5.233474E+01 8.990769E+01 8.431654E-02 5.233467E+01 + 2.730007E+01 9.000000E+01 3 1.853064E+02 3.421285E-01 1.853031E+02 1.106508E+00 + 2.730007E+01 9.000000E+01 4 1.733455E+02 8.990804E+01 2.782318E-01 1.733453E+02 + 2.730007E+01 9.000000E+01 5 1.170052E-04 -8.998814E+01 2.420465E-08 -1.170052E-04 + 2.730007E+01 9.000000E+01 6 6.216318E-06 1.799992E+02 -6.216318E-06 8.843600E-11 + 2.740007E+01 0.000000E+00 1 4.848690E+01 8.992109E+01 6.677949E-02 4.848685E+01 + 2.740007E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.740007E+01 0.000000E+00 3 1.821252E+02 3.366948E-01 1.821221E+02 1.070241E+00 + 2.740007E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.740007E+01 0.000000E+00 5 4.920308E+02 8.992110E+01 6.776208E-01 4.920303E+02 + 2.740007E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.740007E+01 3.000000E+01 1 4.216036E+01 8.992110E+01 5.806039E-02 4.216032E+01 + 2.740007E+01 3.000000E+01 2 2.572382E+01 8.990852E+01 4.107559E-02 2.572379E+01 + 2.740007E+01 3.000000E+01 3 1.829552E+02 3.373922E-01 1.829521E+02 1.077345E+00 + 2.740007E+01 3.000000E+01 4 8.421449E+01 8.990781E+01 1.355001E-01 8.421438E+01 + 2.740007E+01 3.000000E+01 5 4.278035E+02 8.992110E+01 5.891410E-01 4.278031E+02 + 2.740007E+01 3.000000E+01 6 7.108159E+01 -1.194137E-03 7.108159E+01 -1.481456E-03 + 2.740007E+01 6.000000E+01 1 2.453847E+01 8.992111E+01 3.378597E-02 2.453845E+01 + 2.740007E+01 6.000000E+01 2 4.495183E+01 8.990850E+01 7.178903E-02 4.495177E+01 + 2.740007E+01 6.000000E+01 3 1.846259E+02 3.387916E-01 1.846227E+02 1.091692E+00 + 2.740007E+01 6.000000E+01 4 1.482844E+02 8.990850E+01 2.368169E-01 1.482843E+02 + 2.740007E+01 6.000000E+01 5 2.489519E+02 8.992110E+01 3.428245E-01 2.489516E+02 + 2.740007E+01 6.000000E+01 6 7.173272E+01 -1.190445E-03 7.173272E+01 -1.490404E-03 + 2.740007E+01 9.000000E+01 1 2.549738E-06 -9.005333E+01 -2.373185E-09 -2.549737E-06 + 2.740007E+01 9.000000E+01 2 5.213666E+01 8.990849E+01 8.326934E-02 5.213660E+01 + 2.740007E+01 9.000000E+01 3 1.854675E+02 3.394896E-01 1.854642E+02 1.098928E+00 + 2.740007E+01 9.000000E+01 4 1.726298E+02 8.990884E+01 2.746894E-01 1.726296E+02 + 2.740007E+01 9.000000E+01 5 1.165900E-04 -8.998827E+01 2.385390E-08 -1.165900E-04 + 2.740007E+01 9.000000E+01 6 6.167719E-06 1.799992E+02 -6.167719E-06 8.628445E-11 + 2.750007E+01 0.000000E+00 1 4.831063E+01 8.992171E+01 6.600901E-02 4.831059E+01 + 2.750007E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.750007E+01 0.000000E+00 3 1.823094E+02 3.341334E-01 1.823063E+02 1.063173E+00 + 2.750007E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.750007E+01 0.000000E+00 5 4.906328E+02 8.992171E+01 6.703410E-01 4.906323E+02 + 2.750007E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.750007E+01 3.000000E+01 1 4.200584E+01 8.992172E+01 5.738883E-02 4.200580E+01 + 2.750007E+01 3.000000E+01 2 2.562960E+01 8.990930E+01 4.057218E-02 2.562957E+01 + 2.750007E+01 3.000000E+01 3 1.831329E+02 3.348190E-01 1.831297E+02 1.070166E+00 + 2.750007E+01 3.000000E+01 4 8.388406E+01 8.990862E+01 1.337978E-01 8.388396E+01 + 2.750007E+01 3.000000E+01 5 4.265785E+02 8.992172E+01 5.827969E-01 4.265781E+02 + 2.750007E+01 3.000000E+01 6 7.053657E+01 -1.174226E-03 7.053657E+01 -1.445584E-03 + 2.750007E+01 6.000000E+01 1 2.444687E+01 8.992174E+01 3.339313E-02 2.444685E+01 + 2.750007E+01 6.000000E+01 2 4.478394E+01 8.990929E+01 7.090422E-02 4.478388E+01 + 2.750007E+01 6.000000E+01 3 1.847924E+02 3.361934E-01 1.847893E+02 1.084297E+00 + 2.750007E+01 6.000000E+01 4 1.476844E+02 8.990929E+01 2.338234E-01 1.476842E+02 + 2.750007E+01 6.000000E+01 5 2.482252E+02 8.992173E+01 3.391076E-01 2.482250E+02 + 2.750007E+01 6.000000E+01 6 7.117751E+01 -1.170623E-03 7.117751E+01 -1.454244E-03 + 2.750007E+01 9.000000E+01 1 2.540039E-06 -9.005302E+01 -2.350846E-09 -2.540038E-06 + 2.750007E+01 9.000000E+01 2 5.194011E+01 8.990928E+01 8.223996E-02 5.194005E+01 + 2.750007E+01 9.000000E+01 3 1.856278E+02 3.368838E-01 1.856246E+02 1.091435E+00 + 2.750007E+01 9.000000E+01 4 1.719206E+02 8.990961E+01 2.712083E-01 1.719204E+02 + 2.750007E+01 9.000000E+01 5 1.161768E-04 -8.998840E+01 2.350978E-08 -1.161768E-04 + 2.750007E+01 9.000000E+01 6 6.119692E-06 1.799992E+02 -6.119692E-06 8.419448E-11 + 2.760007E+01 0.000000E+00 1 4.813564E+01 8.992233E+01 6.525052E-02 4.813560E+01 + 2.760007E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.760007E+01 0.000000E+00 3 1.824921E+02 3.315973E-01 1.824891E+02 1.056161E+00 + 2.760007E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.760007E+01 0.000000E+00 5 4.892461E+02 8.992234E+01 6.631604E-01 4.892456E+02 + 2.760007E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.760007E+01 3.000000E+01 1 4.185225E+01 8.992235E+01 5.672759E-02 4.185221E+01 + 2.760007E+01 3.000000E+01 2 2.553599E+01 8.991008E+01 4.007721E-02 2.553596E+01 + 2.760007E+01 3.000000E+01 3 1.833097E+02 3.322738E-01 1.833067E+02 1.063057E+00 + 2.760007E+01 3.000000E+01 4 8.355618E+01 8.990940E+01 1.321238E-01 8.355607E+01 + 2.760007E+01 3.000000E+01 5 4.253565E+02 8.992234E+01 5.765409E-01 4.253561E+02 + 2.760007E+01 3.000000E+01 6 6.999789E+01 -1.154733E-03 6.999789E+01 -1.410730E-03 + 2.760007E+01 6.000000E+01 1 2.435611E+01 8.992236E+01 3.300640E-02 2.435608E+01 + 2.760007E+01 6.000000E+01 2 4.461734E+01 8.991006E+01 7.003406E-02 4.461728E+01 + 2.760007E+01 6.000000E+01 3 1.849570E+02 3.336269E-01 1.849538E+02 1.076977E+00 + 2.760007E+01 6.000000E+01 4 1.470889E+02 8.991006E+01 2.308832E-01 1.470887E+02 + 2.760007E+01 6.000000E+01 5 2.474967E+02 8.992235E+01 3.354477E-01 2.474964E+02 + 2.760007E+01 6.000000E+01 6 7.062881E+01 -1.151217E-03 7.062881E+01 -1.419111E-03 + 2.760007E+01 9.000000E+01 1 2.530414E-06 -9.005273E+01 -2.328743E-09 -2.530413E-06 + 2.760007E+01 9.000000E+01 2 5.174487E+01 8.991006E+01 8.122753E-02 5.174480E+01 + 2.760007E+01 9.000000E+01 3 1.857875E+02 3.343015E-01 1.857844E+02 1.084001E+00 + 2.760007E+01 9.000000E+01 4 1.712166E+02 8.991039E+01 2.677870E-01 1.712164E+02 + 2.760007E+01 9.000000E+01 5 1.157683E-04 -8.998853E+01 2.317238E-08 -1.157683E-04 + 2.760007E+01 9.000000E+01 6 6.072243E-06 1.799992E+02 -6.072243E-06 8.216394E-11 + 2.770007E+01 0.000000E+00 1 4.796184E+01 8.992294E+01 6.450374E-02 4.796180E+01 + 2.770007E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.770007E+01 0.000000E+00 3 1.826720E+02 3.290921E-01 1.826689E+02 1.049214E+00 + 2.770007E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.770007E+01 0.000000E+00 5 4.878579E+02 8.992294E+01 6.560824E-01 4.878575E+02 + 2.770007E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.770007E+01 3.000000E+01 1 4.170002E+01 8.992295E+01 5.607668E-02 4.169999E+01 + 2.770007E+01 3.000000E+01 2 2.544310E+01 8.991085E+01 3.959041E-02 2.544307E+01 + 2.770007E+01 3.000000E+01 3 1.834834E+02 3.297578E-01 1.834803E+02 1.056007E+00 + 2.770007E+01 3.000000E+01 4 8.323134E+01 8.991018E+01 1.304788E-01 8.323124E+01 + 2.770007E+01 3.000000E+01 5 4.241356E+02 8.992295E+01 5.703716E-01 4.241352E+02 + 2.770007E+01 3.000000E+01 6 6.946550E+01 -1.135652E-03 6.946550E+01 -1.376866E-03 + 2.770007E+01 6.000000E+01 1 2.426589E+01 8.992297E+01 3.262576E-02 2.426587E+01 + 2.770007E+01 6.000000E+01 2 4.445199E+01 8.991084E+01 6.917854E-02 4.445193E+01 + 2.770007E+01 6.000000E+01 3 1.851198E+02 3.310885E-01 1.851167E+02 1.069724E+00 + 2.770007E+01 6.000000E+01 4 1.464987E+02 8.991084E+01 2.279924E-01 1.464985E+02 + 2.770007E+01 6.000000E+01 5 2.467748E+02 8.992295E+01 3.318392E-01 2.467746E+02 + 2.770007E+01 6.000000E+01 6 7.008666E+01 -1.132223E-03 7.008666E+01 -1.384983E-03 + 2.770007E+01 9.000000E+01 1 2.520866E-06 -9.005243E+01 -2.306889E-09 -2.520865E-06 + 2.770007E+01 9.000000E+01 2 5.155136E+01 8.991083E+01 8.023254E-02 5.155130E+01 + 2.770007E+01 9.000000E+01 3 1.859445E+02 3.317517E-01 1.859414E+02 1.076642E+00 + 2.770007E+01 9.000000E+01 4 1.705203E+02 8.991116E+01 2.644240E-01 1.705201E+02 + 2.770007E+01 9.000000E+01 5 1.153612E-04 -8.998866E+01 2.284139E-08 -1.153612E-04 + 2.770007E+01 9.000000E+01 6 6.025352E-06 1.799992E+02 -6.025352E-06 8.019128E-11 + 2.780007E+01 0.000000E+00 1 4.778943E+01 8.992355E+01 6.376842E-02 4.778939E+01 + 2.780007E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.780007E+01 0.000000E+00 3 1.828498E+02 3.266193E-01 1.828468E+02 1.042345E+00 + 2.780007E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.780007E+01 0.000000E+00 5 4.864798E+02 8.992355E+01 6.491061E-01 4.864794E+02 + 2.780007E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.780007E+01 3.000000E+01 1 4.154868E+01 8.992355E+01 5.543589E-02 4.154864E+01 + 2.780007E+01 3.000000E+01 2 2.535089E+01 8.991161E+01 3.911167E-02 2.535086E+01 + 2.780007E+01 3.000000E+01 3 1.836570E+02 3.272706E-01 1.836540E+02 1.049034E+00 + 2.780007E+01 3.000000E+01 4 8.290870E+01 8.991094E+01 1.288622E-01 8.290860E+01 + 2.780007E+01 3.000000E+01 5 4.229265E+02 8.992355E+01 5.642854E-01 4.229261E+02 + 2.780007E+01 3.000000E+01 6 6.893920E+01 -1.116972E-03 6.893920E+01 -1.343959E-03 + 2.780007E+01 6.000000E+01 1 2.417634E+01 8.992357E+01 3.225103E-02 2.417632E+01 + 2.780007E+01 6.000000E+01 2 4.428777E+01 8.991159E+01 6.833703E-02 4.428772E+01 + 2.780007E+01 6.000000E+01 3 1.852806E+02 3.285831E-01 1.852776E+02 1.062552E+00 + 2.780007E+01 6.000000E+01 4 1.459133E+02 8.991159E+01 2.251514E-01 1.459132E+02 + 2.780007E+01 6.000000E+01 5 2.460548E+02 8.992356E+01 3.282776E-01 2.460546E+02 + 2.780007E+01 6.000000E+01 6 6.955079E+01 -1.113628E-03 6.955079E+01 -1.351822E-03 + 2.780007E+01 9.000000E+01 1 2.511394E-06 -9.005214E+01 -2.285283E-09 -2.511393E-06 + 2.780007E+01 9.000000E+01 2 5.135925E+01 8.991158E+01 7.925393E-02 5.135918E+01 + 2.780007E+01 9.000000E+01 3 1.860998E+02 3.292342E-01 1.860967E+02 1.069365E+00 + 2.780007E+01 9.000000E+01 4 1.698282E+02 8.991191E+01 2.611189E-01 1.698280E+02 + 2.780007E+01 9.000000E+01 5 1.149569E-04 -8.998878E+01 2.251673E-08 -1.149569E-04 + 2.780007E+01 9.000000E+01 6 5.979010E-06 1.799993E+02 -5.979010E-06 7.827420E-11 + 2.790007E+01 0.000000E+00 1 4.761823E+01 8.992414E+01 6.304449E-02 4.761819E+01 + 2.790007E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.790007E+01 0.000000E+00 3 1.830271E+02 3.241700E-01 1.830242E+02 1.035532E+00 + 2.790007E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.790007E+01 0.000000E+00 5 4.851045E+02 8.992415E+01 6.422254E-01 4.851041E+02 + 2.790007E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.790007E+01 3.000000E+01 1 4.139865E+01 8.992416E+01 5.480478E-02 4.139861E+01 + 2.790007E+01 3.000000E+01 2 2.525932E+01 8.991235E+01 3.864074E-02 2.525929E+01 + 2.790007E+01 3.000000E+01 3 1.838277E+02 3.248135E-01 1.838247E+02 1.042126E+00 + 2.790007E+01 3.000000E+01 4 8.258921E+01 8.991171E+01 1.272726E-01 8.258911E+01 + 2.790007E+01 3.000000E+01 5 4.217174E+02 8.992415E+01 5.582868E-01 4.217170E+02 + 2.790007E+01 3.000000E+01 6 6.841891E+01 -1.098685E-03 6.841891E+01 -1.311978E-03 + 2.790007E+01 6.000000E+01 1 2.408754E+01 8.992417E+01 3.188213E-02 2.408752E+01 + 2.790007E+01 6.000000E+01 2 4.412487E+01 8.991234E+01 6.750953E-02 4.412482E+01 + 2.790007E+01 6.000000E+01 3 1.854400E+02 3.261012E-01 1.854370E+02 1.055433E+00 + 2.790007E+01 6.000000E+01 4 1.453328E+02 8.991234E+01 2.223575E-01 1.453327E+02 + 2.790007E+01 6.000000E+01 5 2.453364E+02 8.992416E+01 3.247714E-01 2.453362E+02 + 2.790007E+01 6.000000E+01 6 6.902113E+01 -1.095419E-03 6.902113E+01 -1.319592E-03 + 2.790007E+01 9.000000E+01 1 2.501991E-06 -9.005184E+01 -2.263919E-09 -2.501990E-06 + 2.790007E+01 9.000000E+01 2 5.116870E+01 8.991233E+01 7.829168E-02 5.116864E+01 + 2.790007E+01 9.000000E+01 3 1.862526E+02 3.267466E-01 1.862496E+02 1.062156E+00 + 2.790007E+01 9.000000E+01 4 1.691419E+02 8.991265E+01 2.578705E-01 1.691417E+02 + 2.790007E+01 9.000000E+01 5 1.145557E-04 -8.998890E+01 2.219828E-08 -1.145557E-04 + 2.790007E+01 9.000000E+01 6 5.933215E-06 1.799993E+02 -5.933215E-06 7.641110E-11 + 2.800007E+01 0.000000E+00 1 4.744809E+01 8.992474E+01 6.233130E-02 4.744805E+01 + 2.800007E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.800007E+01 0.000000E+00 3 1.832010E+02 3.217495E-01 1.831982E+02 1.028776E+00 + 2.800007E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.800007E+01 0.000000E+00 5 4.837372E+02 8.992474E+01 6.354414E-01 4.837368E+02 + 2.800007E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.800007E+01 3.000000E+01 1 4.124949E+01 8.992474E+01 5.418339E-02 4.124946E+01 + 2.800007E+01 3.000000E+01 2 2.516845E+01 8.991309E+01 3.817756E-02 2.516842E+01 + 2.800007E+01 3.000000E+01 3 1.839966E+02 3.223823E-01 1.839937E+02 1.035276E+00 + 2.800007E+01 3.000000E+01 4 8.227146E+01 8.991245E+01 1.257093E-01 8.227136E+01 + 2.800007E+01 3.000000E+01 5 4.205184E+02 8.992474E+01 5.523752E-01 4.205181E+02 + 2.800007E+01 3.000000E+01 6 6.790480E+01 -1.080773E-03 6.790480E+01 -1.280892E-03 + 2.800007E+01 6.000000E+01 1 2.399938E+01 8.992476E+01 3.151871E-02 2.399936E+01 + 2.800007E+01 6.000000E+01 2 4.396320E+01 8.991308E+01 6.669591E-02 4.396315E+01 + 2.800007E+01 6.000000E+01 3 1.855984E+02 3.236502E-01 1.855955E+02 1.048396E+00 + 2.800007E+01 6.000000E+01 4 1.447571E+02 8.991308E+01 2.196120E-01 1.447570E+02 + 2.800007E+01 6.000000E+01 5 2.446227E+02 8.992474E+01 3.213120E-01 2.446225E+02 + 2.800007E+01 6.000000E+01 6 6.849780E+01 -1.077585E-03 6.849780E+01 -1.288266E-03 + 2.800007E+01 9.000000E+01 1 2.492656E-06 -9.005155E+01 -2.242774E-09 -2.492656E-06 + 2.800007E+01 9.000000E+01 2 5.097934E+01 8.991308E+01 7.734487E-02 5.097928E+01 + 2.800007E+01 9.000000E+01 3 1.864052E+02 3.242849E-01 1.864023E+02 1.055018E+00 + 2.800007E+01 9.000000E+01 4 1.684627E+02 8.991338E+01 2.546772E-01 1.684625E+02 + 2.800007E+01 9.000000E+01 5 1.141573E-04 -8.998901E+01 2.188575E-08 -1.141573E-04 + 2.800007E+01 9.000000E+01 6 5.887949E-06 1.799993E+02 -5.887949E-06 7.460020E-11 + 2.810007E+01 0.000000E+00 1 4.727943E+01 8.992532E+01 6.162915E-02 4.727939E+01 + 2.810007E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.810007E+01 0.000000E+00 3 1.833738E+02 3.193567E-01 1.833709E+02 1.022088E+00 + 2.810007E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.810007E+01 0.000000E+00 5 4.823730E+02 8.992532E+01 6.287509E-01 4.823727E+02 + 2.810007E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.810007E+01 3.000000E+01 1 4.110149E+01 8.992532E+01 5.357149E-02 4.110145E+01 + 2.810007E+01 3.000000E+01 2 2.507817E+01 8.991382E+01 3.772182E-02 2.507814E+01 + 2.810007E+01 3.000000E+01 3 1.841638E+02 3.199789E-01 1.841610E+02 1.028492E+00 + 2.810007E+01 3.000000E+01 4 8.195668E+01 8.991319E+01 1.241722E-01 8.195659E+01 + 2.810007E+01 3.000000E+01 5 4.193215E+02 8.992532E+01 5.465394E-01 4.193211E+02 + 2.810007E+01 3.000000E+01 6 6.739633E+01 -1.063236E-03 6.739633E+01 -1.250672E-03 + 2.810007E+01 6.000000E+01 1 2.391177E+01 8.992534E+01 3.116108E-02 2.391175E+01 + 2.810007E+01 6.000000E+01 2 4.380273E+01 8.991380E+01 6.589521E-02 4.380268E+01 + 2.810007E+01 6.000000E+01 3 1.857555E+02 3.212252E-01 1.857526E+02 1.041421E+00 + 2.810007E+01 6.000000E+01 4 1.441860E+02 8.991380E+01 2.169119E-01 1.441858E+02 + 2.810007E+01 6.000000E+01 5 2.439112E+02 8.992532E+01 3.179022E-01 2.439110E+02 + 2.810007E+01 6.000000E+01 6 6.798024E+01 -1.060128E-03 6.798024E+01 -1.257820E-03 + 2.810007E+01 9.000000E+01 1 2.483399E-06 -9.005126E+01 -2.221880E-09 -2.483398E-06 + 2.810007E+01 9.000000E+01 2 5.079157E+01 8.991380E+01 7.641418E-02 5.079152E+01 + 2.810007E+01 9.000000E+01 3 1.865555E+02 3.218505E-01 1.865526E+02 1.047943E+00 + 2.810007E+01 9.000000E+01 4 1.677881E+02 8.991411E+01 2.515384E-01 1.677879E+02 + 2.810007E+01 9.000000E+01 5 1.137617E-04 -8.998913E+01 2.157909E-08 -1.137617E-04 + 2.810007E+01 9.000000E+01 6 5.843222E-06 1.799993E+02 -5.843222E-06 7.283976E-11 + 2.820007E+01 0.000000E+00 1 4.711179E+01 8.992589E+01 6.093765E-02 4.711176E+01 + 2.820007E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.820007E+01 0.000000E+00 3 1.835450E+02 3.169907E-01 1.835422E+02 1.015463E+00 + 2.820007E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.820007E+01 0.000000E+00 5 4.810190E+02 8.992590E+01 6.221502E-01 4.810186E+02 + 2.820007E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.820007E+01 3.000000E+01 1 4.095451E+01 8.992590E+01 5.296883E-02 4.095447E+01 + 2.820007E+01 3.000000E+01 2 2.498859E+01 8.991454E+01 3.727363E-02 2.498856E+01 + 2.820007E+01 3.000000E+01 3 1.843295E+02 3.176023E-01 1.843267E+02 1.021771E+00 + 2.820007E+01 3.000000E+01 4 8.164420E+01 8.991393E+01 1.226603E-01 8.164410E+01 + 2.820007E+01 3.000000E+01 5 4.181278E+02 8.992590E+01 5.407942E-01 4.181275E+02 + 2.820007E+01 3.000000E+01 6 6.689375E+01 -1.046059E-03 6.689375E+01 -1.221291E-03 + 2.820007E+01 6.000000E+01 1 2.382490E+01 8.992591E+01 3.080876E-02 2.382488E+01 + 2.820007E+01 6.000000E+01 2 4.364328E+01 8.991452E+01 6.510767E-02 4.364323E+01 + 2.820007E+01 6.000000E+01 3 1.859091E+02 3.188306E-01 1.859062E+02 1.034512E+00 + 2.820007E+01 6.000000E+01 4 1.436199E+02 8.991452E+01 2.142572E-01 1.436198E+02 + 2.820007E+01 6.000000E+01 5 2.432052E+02 8.992590E+01 3.145411E-01 2.432050E+02 + 2.820007E+01 6.000000E+01 6 6.746886E+01 -1.043021E-03 6.746886E+01 -1.228213E-03 + 2.820007E+01 9.000000E+01 1 2.474212E-06 -9.005098E+01 -2.201207E-09 -2.474211E-06 + 2.820007E+01 9.000000E+01 2 5.060510E+01 8.991452E+01 7.549848E-02 5.060505E+01 + 2.820007E+01 9.000000E+01 3 1.867050E+02 3.194449E-01 1.867021E+02 1.040943E+00 + 2.820007E+01 9.000000E+01 4 1.671197E+02 8.991483E+01 2.484505E-01 1.671196E+02 + 2.820007E+01 9.000000E+01 5 1.133686E-04 -8.998924E+01 2.127823E-08 -1.133686E-04 + 2.820007E+01 9.000000E+01 6 5.799000E-06 1.799993E+02 -5.799000E-06 7.112817E-11 + 2.830007E+01 0.000000E+00 1 4.694517E+01 8.992645E+01 6.025654E-02 4.694513E+01 + 2.830007E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.830007E+01 0.000000E+00 3 1.837143E+02 3.146522E-01 1.837115E+02 1.008901E+00 + 2.830007E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.830007E+01 0.000000E+00 5 4.796661E+02 8.992646E+01 6.156455E-01 4.796657E+02 + 2.830007E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.830007E+01 3.000000E+01 1 4.080869E+01 8.992646E+01 5.237546E-02 4.080865E+01 + 2.830007E+01 3.000000E+01 2 2.489963E+01 8.991525E+01 3.683248E-02 2.489960E+01 + 2.830007E+01 3.000000E+01 3 1.844937E+02 3.152546E-01 1.844909E+02 1.015122E+00 + 2.830007E+01 3.000000E+01 4 8.133396E+01 8.991464E+01 1.211739E-01 8.133387E+01 + 2.830007E+01 3.000000E+01 5 4.169438E+02 8.992646E+01 5.351219E-01 4.169435E+02 + 2.830007E+01 3.000000E+01 6 6.639690E+01 -1.029236E-03 6.639690E+01 -1.192724E-03 + 2.830007E+01 6.000000E+01 1 2.373865E+01 8.992648E+01 3.046190E-02 2.373863E+01 + 2.830007E+01 6.000000E+01 2 4.348512E+01 8.991524E+01 6.433313E-02 4.348507E+01 + 2.830007E+01 6.000000E+01 3 1.860634E+02 3.164616E-01 1.860605E+02 1.027678E+00 + 2.830007E+01 6.000000E+01 4 1.430579E+02 8.991524E+01 2.116471E-01 1.430577E+02 + 2.830007E+01 6.000000E+01 5 2.425011E+02 8.992647E+01 3.112257E-01 2.425009E+02 + 2.830007E+01 6.000000E+01 6 6.696328E+01 -1.026270E-03 6.696328E+01 -1.199433E-03 + 2.830007E+01 9.000000E+01 1 2.465086E-06 -9.005069E+01 -2.180761E-09 -2.465085E-06 + 2.830007E+01 9.000000E+01 2 5.042012E+01 8.991524E+01 7.459762E-02 5.042007E+01 + 2.830007E+01 9.000000E+01 3 1.868528E+02 3.170685E-01 1.868499E+02 1.034017E+00 + 2.830007E+01 9.000000E+01 4 1.664560E+02 8.991553E+01 2.454160E-01 1.664558E+02 + 2.830007E+01 9.000000E+01 5 1.129783E-04 -8.998936E+01 2.098303E-08 -1.129783E-04 + 2.830007E+01 9.000000E+01 6 5.755298E-06 1.799993E+02 -5.755298E-06 6.946392E-11 + 2.840007E+01 0.000000E+00 1 4.677987E+01 8.992702E+01 5.958563E-02 4.677983E+01 + 2.840007E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.840007E+01 0.000000E+00 3 1.838813E+02 3.123398E-01 1.838786E+02 1.002398E+00 + 2.840007E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.840007E+01 0.000000E+00 5 4.783223E+02 8.992702E+01 6.092303E-01 4.783219E+02 + 2.840007E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.840007E+01 3.000000E+01 1 4.066379E+01 8.992703E+01 5.179086E-02 4.066375E+01 + 2.840007E+01 3.000000E+01 2 2.481134E+01 8.991595E+01 3.639850E-02 2.481132E+01 + 2.840007E+01 3.000000E+01 3 1.846556E+02 3.129305E-01 1.846528E+02 1.008522E+00 + 2.840007E+01 3.000000E+01 4 8.102666E+01 8.991535E+01 1.197123E-01 8.102657E+01 + 2.840007E+01 3.000000E+01 5 4.157625E+02 8.992703E+01 5.295332E-01 4.157622E+02 + 2.840007E+01 3.000000E+01 6 6.590559E+01 -1.012755E-03 6.590559E+01 -1.164941E-03 + 2.840007E+01 6.000000E+01 1 2.365303E+01 8.992704E+01 3.012023E-02 2.365301E+01 + 2.840007E+01 6.000000E+01 2 4.332825E+01 8.991594E+01 6.357099E-02 4.332820E+01 + 2.840007E+01 6.000000E+01 3 1.862146E+02 3.141187E-01 1.862118E+02 1.020899E+00 + 2.840007E+01 6.000000E+01 4 1.425012E+02 8.991594E+01 2.090798E-01 1.425010E+02 + 2.840007E+01 6.000000E+01 5 2.418004E+02 8.992703E+01 3.079569E-01 2.418002E+02 + 2.840007E+01 6.000000E+01 6 6.646344E+01 -1.009861E-03 6.646344E+01 -1.171445E-03 + 2.840007E+01 9.000000E+01 1 2.456037E-06 -9.005040E+01 -2.160548E-09 -2.456036E-06 + 2.840007E+01 9.000000E+01 2 5.023649E+01 8.991593E+01 7.371149E-02 5.023643E+01 + 2.840007E+01 9.000000E+01 3 1.869987E+02 3.147150E-01 1.869958E+02 1.027143E+00 + 2.840007E+01 9.000000E+01 4 1.657985E+02 8.991622E+01 2.424307E-01 1.657984E+02 + 2.840007E+01 9.000000E+01 5 1.125906E-04 -8.998947E+01 2.069316E-08 -1.125906E-04 + 2.840007E+01 9.000000E+01 6 5.712103E-06 1.799993E+02 -5.712103E-06 6.784557E-11 + 2.850007E+01 0.000000E+00 1 4.661565E+01 8.992757E+01 5.892463E-02 4.661562E+01 + 2.850007E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.850007E+01 0.000000E+00 3 1.840484E+02 3.100492E-01 1.840457E+02 9.959512E-01 + 2.850007E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.850007E+01 0.000000E+00 5 4.769853E+02 8.992758E+01 6.029006E-01 4.769849E+02 + 2.850007E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.850007E+01 3.000000E+01 1 4.051995E+01 8.992758E+01 5.121486E-02 4.051992E+01 + 2.850007E+01 3.000000E+01 2 2.472359E+01 8.991664E+01 3.597154E-02 2.472357E+01 + 2.850007E+01 3.000000E+01 3 1.848165E+02 3.106342E-01 1.848137E+02 1.001994E+00 + 2.850007E+01 3.000000E+01 4 8.072145E+01 8.991605E+01 1.182747E-01 8.072137E+01 + 2.850007E+01 3.000000E+01 5 4.145861E+02 8.992758E+01 5.240204E-01 4.145857E+02 + 2.850007E+01 3.000000E+01 6 6.541982E+01 -9.966095E-04 6.541982E+01 -1.137920E-03 + 2.850007E+01 6.000000E+01 1 2.356802E+01 8.992760E+01 2.978378E-02 2.356800E+01 + 2.850007E+01 6.000000E+01 2 4.317225E+01 8.991663E+01 6.282101E-02 4.317220E+01 + 2.850007E+01 6.000000E+01 3 1.863645E+02 3.118035E-01 1.863618E+02 1.014191E+00 + 2.850007E+01 6.000000E+01 4 1.419480E+02 8.991663E+01 2.065548E-01 1.419479E+02 + 2.850007E+01 6.000000E+01 5 2.411035E+02 8.992758E+01 3.047306E-01 2.411033E+02 + 2.850007E+01 6.000000E+01 6 6.596940E+01 -9.937821E-04 6.596940E+01 -1.144224E-03 + 2.850007E+01 9.000000E+01 1 2.447048E-06 -9.005013E+01 -2.140565E-09 -2.447047E-06 + 2.850007E+01 9.000000E+01 2 5.005430E+01 8.991662E+01 7.283960E-02 5.005425E+01 + 2.850007E+01 9.000000E+01 3 1.871428E+02 3.123914E-01 1.871401E+02 1.020346E+00 + 2.850007E+01 9.000000E+01 4 1.651463E+02 8.991691E+01 2.394964E-01 1.651462E+02 + 2.850007E+01 9.000000E+01 5 1.122053E-04 -8.998958E+01 2.040873E-08 -1.122053E-04 + 2.850007E+01 9.000000E+01 6 5.669390E-06 1.799993E+02 -5.669390E-06 6.627149E-11 + 2.860007E+01 0.000000E+00 1 4.645269E+01 8.992812E+01 5.827371E-02 4.645265E+01 + 2.860007E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.860007E+01 0.000000E+00 3 1.842122E+02 3.077878E-01 1.842095E+02 9.895664E-01 + 2.860007E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.860007E+01 0.000000E+00 5 4.756524E+02 8.992813E+01 5.966589E-01 4.756520E+02 + 2.860007E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.860007E+01 3.000000E+01 1 4.037712E+01 8.992813E+01 5.064785E-02 4.037709E+01 + 2.860007E+01 3.000000E+01 2 2.463656E+01 8.991733E+01 3.555132E-02 2.463653E+01 + 2.860007E+01 3.000000E+01 3 1.849752E+02 3.083637E-01 1.849725E+02 9.955246E-01 + 2.860007E+01 3.000000E+01 4 8.041879E+01 8.991674E+01 1.168599E-01 8.041870E+01 + 2.860007E+01 3.000000E+01 5 4.134140E+02 8.992813E+01 5.185757E-01 4.134136E+02 + 2.860007E+01 3.000000E+01 6 6.493947E+01 -9.807913E-04 6.493947E+01 -1.111636E-03 + 2.860007E+01 6.000000E+01 1 2.348356E+01 8.992815E+01 2.945225E-02 2.348354E+01 + 2.860007E+01 6.000000E+01 2 4.301755E+01 8.991731E+01 6.208301E-02 4.301750E+01 + 2.860007E+01 6.000000E+01 3 1.865120E+02 3.095161E-01 1.865093E+02 1.007547E+00 + 2.860007E+01 6.000000E+01 4 1.413996E+02 8.991731E+01 2.040714E-01 1.413995E+02 + 2.860007E+01 6.000000E+01 5 2.404083E+02 8.992814E+01 3.015527E-01 2.404081E+02 + 2.860007E+01 6.000000E+01 6 6.548082E+01 -9.780284E-04 6.548082E+01 -1.117745E-03 + 2.860007E+01 9.000000E+01 1 2.438129E-06 -9.004984E+01 -2.120792E-09 -2.438128E-06 + 2.860007E+01 9.000000E+01 2 4.987325E+01 8.991730E+01 7.198154E-02 4.987319E+01 + 2.860007E+01 9.000000E+01 3 1.872858E+02 3.100912E-01 1.872831E+02 1.013607E+00 + 2.860007E+01 9.000000E+01 4 1.644998E+02 8.991759E+01 2.366087E-01 1.644997E+02 + 2.860007E+01 9.000000E+01 5 1.118234E-04 -8.998969E+01 2.012946E-08 -1.118234E-04 + 2.860007E+01 9.000000E+01 6 5.627169E-06 1.799993E+02 -5.627169E-06 6.474039E-11 + 2.870007E+01 0.000000E+00 1 4.629090E+01 8.992867E+01 5.763241E-02 4.629087E+01 + 2.870007E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.870007E+01 0.000000E+00 3 1.843742E+02 3.055500E-01 1.843716E+02 9.832358E-01 + 2.870007E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.870007E+01 0.000000E+00 5 4.743232E+02 8.992867E+01 5.905062E-01 4.743228E+02 + 2.870007E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.870007E+01 3.000000E+01 1 4.023531E+01 8.992867E+01 5.008899E-02 4.023528E+01 + 2.870007E+01 3.000000E+01 2 2.455005E+01 8.991799E+01 3.513776E-02 2.455002E+01 + 2.870007E+01 3.000000E+01 3 1.851326E+02 3.061164E-01 1.851300E+02 9.891106E-01 + 2.870007E+01 3.000000E+01 4 8.011801E+01 8.991743E+01 1.154684E-01 8.011793E+01 + 2.870007E+01 3.000000E+01 5 4.122494E+02 8.992867E+01 5.132151E-01 4.122491E+02 + 2.870007E+01 3.000000E+01 6 6.446452E+01 -9.652921E-04 6.446452E+01 -1.086068E-03 + 2.870007E+01 6.000000E+01 1 2.339984E+01 8.992868E+01 2.912585E-02 2.339982E+01 + 2.870007E+01 6.000000E+01 2 4.286395E+01 8.991798E+01 6.135697E-02 4.286390E+01 + 2.870007E+01 6.000000E+01 3 1.866599E+02 3.072492E-01 1.866572E+02 1.000961E+00 + 2.870007E+01 6.000000E+01 4 1.408558E+02 8.991798E+01 2.016285E-01 1.408556E+02 + 2.870007E+01 6.000000E+01 5 2.397190E+02 8.992867E+01 2.984205E-01 2.397188E+02 + 2.870007E+01 6.000000E+01 6 6.499773E+01 -9.625954E-04 6.499773E+01 -1.091992E-03 + 2.870007E+01 9.000000E+01 1 2.429276E-06 -9.004955E+01 -2.101240E-09 -2.429275E-06 + 2.870007E+01 9.000000E+01 2 4.969361E+01 8.991798E+01 7.113768E-02 4.969356E+01 + 2.870007E+01 9.000000E+01 3 1.874273E+02 3.078184E-01 1.874246E+02 1.006938E+00 + 2.870007E+01 9.000000E+01 4 1.638578E+02 8.991826E+01 2.337690E-01 1.638577E+02 + 2.870007E+01 9.000000E+01 5 1.114432E-04 -8.998979E+01 1.985536E-08 -1.114432E-04 + 2.870007E+01 9.000000E+01 6 5.585436E-06 1.799993E+02 -5.585436E-06 6.325095E-11 + 2.880007E+01 0.000000E+00 1 4.613022E+01 8.992920E+01 5.700032E-02 4.613018E+01 + 2.880007E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.880007E+01 0.000000E+00 3 1.845348E+02 3.033354E-01 1.845323E+02 9.769601E-01 + 2.880007E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.880007E+01 0.000000E+00 5 4.730033E+02 8.992921E+01 5.844322E-01 4.730029E+02 + 2.880007E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.880007E+01 3.000000E+01 1 4.009457E+01 8.992921E+01 4.953853E-02 4.009454E+01 + 2.880007E+01 3.000000E+01 2 2.446420E+01 8.991866E+01 3.473059E-02 2.446418E+01 + 2.880007E+01 3.000000E+01 3 1.852882E+02 3.038919E-01 1.852856E+02 9.827483E-01 + 2.880007E+01 3.000000E+01 4 7.981991E+01 8.991810E+01 1.140992E-01 7.981982E+01 + 2.880007E+01 3.000000E+01 5 4.110927E+02 8.992921E+01 5.079241E-01 4.110923E+02 + 2.880007E+01 3.000000E+01 6 6.399482E+01 -9.501004E-04 6.399482E+01 -1.061186E-03 + 2.880007E+01 6.000000E+01 1 2.331664E+01 8.992922E+01 2.880419E-02 2.331662E+01 + 2.880007E+01 6.000000E+01 2 4.271136E+01 8.991865E+01 6.064233E-02 4.271132E+01 + 2.880007E+01 6.000000E+01 3 1.868046E+02 3.050091E-01 1.868019E+02 9.944332E-01 + 2.880007E+01 6.000000E+01 4 1.403165E+02 8.991865E+01 1.992254E-01 1.403164E+02 + 2.880007E+01 6.000000E+01 5 2.390303E+02 8.992921E+01 2.953278E-01 2.390302E+02 + 2.880007E+01 6.000000E+01 6 6.452022E+01 -9.474657E-04 6.452022E+01 -1.066932E-03 + 2.880007E+01 9.000000E+01 1 2.420488E-06 -9.004929E+01 -2.081912E-09 -2.420487E-06 + 2.880007E+01 9.000000E+01 2 4.951539E+01 8.991865E+01 7.030696E-02 4.951534E+01 + 2.880007E+01 9.000000E+01 3 1.875682E+02 3.055684E-01 1.875655E+02 1.000329E+00 + 2.880007E+01 9.000000E+01 4 1.632213E+02 8.991892E+01 2.309761E-01 1.632211E+02 + 2.880007E+01 9.000000E+01 5 1.110659E-04 -8.998990E+01 1.958618E-08 -1.110659E-04 + 2.880007E+01 9.000000E+01 6 5.544158E-06 1.799994E+02 -5.544158E-06 6.180179E-11 + 2.890007E+01 0.000000E+00 1 4.597051E+01 8.992973E+01 5.637762E-02 4.597048E+01 + 2.890007E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.890007E+01 0.000000E+00 3 1.846951E+02 3.011470E-01 1.846926E+02 9.707543E-01 + 2.890007E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.890007E+01 0.000000E+00 5 4.716823E+02 8.992973E+01 5.784411E-01 4.716820E+02 + 2.890007E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.890007E+01 3.000000E+01 1 3.995467E+01 8.992974E+01 4.899608E-02 3.995464E+01 + 2.890007E+01 3.000000E+01 2 2.437893E+01 8.991932E+01 3.433002E-02 2.437890E+01 + 2.890007E+01 3.000000E+01 3 1.854426E+02 3.016971E-01 1.854400E+02 9.764636E-01 + 2.890007E+01 3.000000E+01 4 7.952345E+01 8.991876E+01 1.127526E-01 7.952338E+01 + 2.890007E+01 3.000000E+01 5 4.099373E+02 8.992974E+01 5.027046E-01 4.099370E+02 + 2.890007E+01 3.000000E+01 6 6.353027E+01 -9.352144E-04 6.353027E+01 -1.036977E-03 + 2.890007E+01 6.000000E+01 1 2.323405E+01 8.992975E+01 2.848738E-02 2.323404E+01 + 2.890007E+01 6.000000E+01 2 4.255993E+01 8.991931E+01 5.993906E-02 4.255989E+01 + 2.890007E+01 6.000000E+01 3 1.869487E+02 3.027964E-01 1.869461E+02 9.879808E-01 + 2.890007E+01 6.000000E+01 4 1.397805E+02 8.991930E+01 1.968617E-01 1.397803E+02 + 2.890007E+01 6.000000E+01 5 2.383465E+02 8.992974E+01 2.922797E-01 2.383463E+02 + 2.890007E+01 6.000000E+01 6 6.404784E+01 -9.326427E-04 6.404784E+01 -1.042551E-03 + 2.890007E+01 9.000000E+01 1 2.411764E-06 -9.004900E+01 -2.062795E-09 -2.411763E-06 + 2.890007E+01 9.000000E+01 2 4.933831E+01 8.991930E+01 6.948937E-02 4.933826E+01 + 2.890007E+01 9.000000E+01 3 1.877075E+02 3.033449E-01 1.877048E+02 9.937877E-01 + 2.890007E+01 9.000000E+01 4 1.625896E+02 8.991957E+01 2.282291E-01 1.625895E+02 + 2.890007E+01 9.000000E+01 5 1.106909E-04 -8.999000E+01 1.932194E-08 -1.106909E-04 + 2.890007E+01 9.000000E+01 6 5.503363E-06 1.799994E+02 -5.503363E-06 6.039165E-11 + 2.900007E+01 0.000000E+00 1 4.581194E+01 8.993026E+01 5.576444E-02 4.581190E+01 + 2.900007E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.900007E+01 0.000000E+00 3 1.848529E+02 2.989812E-01 1.848504E+02 9.645963E-01 + 2.900007E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.900007E+01 0.000000E+00 5 4.703759E+02 8.993026E+01 5.725312E-01 4.703756E+02 + 2.900007E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.900007E+01 3.000000E+01 1 3.981580E+01 8.993026E+01 4.846161E-02 3.981577E+01 + 2.900007E+01 3.000000E+01 2 2.429428E+01 8.991997E+01 3.393558E-02 2.429426E+01 + 2.900007E+01 3.000000E+01 3 1.855956E+02 2.995215E-01 1.855931E+02 9.702220E-01 + 2.900007E+01 3.000000E+01 4 7.922995E+01 8.991942E+01 1.114271E-01 7.922987E+01 + 2.900007E+01 3.000000E+01 5 4.087864E+02 8.993026E+01 4.975584E-01 4.087861E+02 + 2.900007E+01 3.000000E+01 6 6.307088E+01 -9.206262E-04 6.307088E+01 -1.013420E-03 + 2.900007E+01 6.000000E+01 1 2.315207E+01 8.993027E+01 2.817525E-02 2.315206E+01 + 2.900007E+01 6.000000E+01 2 4.240964E+01 8.991996E+01 5.924690E-02 4.240960E+01 + 2.900007E+01 6.000000E+01 3 1.870907E+02 3.006066E-01 1.870882E+02 9.815809E-01 + 2.900007E+01 6.000000E+01 4 1.392496E+02 8.991995E+01 1.945360E-01 1.392495E+02 + 2.900007E+01 6.000000E+01 5 2.376660E+02 8.993027E+01 2.892712E-01 2.376659E+02 + 2.900007E+01 6.000000E+01 6 6.358087E+01 -9.181129E-04 6.358087E+01 -1.018826E-03 + 2.900007E+01 9.000000E+01 1 2.403105E-06 -9.004873E+01 -2.043889E-09 -2.403104E-06 + 2.900007E+01 9.000000E+01 2 4.916262E+01 8.991995E+01 6.868486E-02 4.916257E+01 + 2.900007E+01 9.000000E+01 3 1.878439E+02 3.011484E-01 1.878413E+02 9.873088E-01 + 2.900007E+01 9.000000E+01 4 1.619632E+02 8.992022E+01 2.255255E-01 1.619631E+02 + 2.900007E+01 9.000000E+01 5 1.103186E-04 -8.999010E+01 1.906248E-08 -1.103186E-04 + 2.900007E+01 9.000000E+01 6 5.463011E-06 1.799994E+02 -5.463011E-06 5.901934E-11 + 2.910007E+01 0.000000E+00 1 4.565451E+01 8.993078E+01 5.515980E-02 4.565447E+01 + 2.910007E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.910007E+01 0.000000E+00 3 1.850083E+02 2.968405E-01 1.850058E+02 9.584949E-01 + 2.910007E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.910007E+01 0.000000E+00 5 4.690703E+02 8.993078E+01 5.667050E-01 4.690700E+02 + 2.910007E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.910007E+01 3.000000E+01 1 3.967776E+01 8.993078E+01 4.793527E-02 3.967773E+01 + 2.910007E+01 3.000000E+01 2 2.421017E+01 8.992061E+01 3.354733E-02 2.421014E+01 + 2.910007E+01 3.000000E+01 3 1.857465E+02 2.973713E-01 1.857440E+02 9.640398E-01 + 2.910007E+01 3.000000E+01 4 7.893834E+01 8.992007E+01 1.101233E-01 7.893826E+01 + 2.910007E+01 3.000000E+01 5 4.076400E+02 8.993078E+01 4.924771E-01 4.076396E+02 + 2.910007E+01 3.000000E+01 6 6.261650E+01 -9.063248E-04 6.261650E+01 -9.904898E-04 + 2.910007E+01 6.000000E+01 1 2.307065E+01 8.993079E+01 2.786764E-02 2.307064E+01 + 2.910007E+01 6.000000E+01 2 4.226030E+01 8.992059E+01 5.856558E-02 4.226025E+01 + 2.910007E+01 6.000000E+01 3 1.872321E+02 2.984377E-01 1.872296E+02 9.752351E-01 + 2.910007E+01 6.000000E+01 4 1.387225E+02 8.992059E+01 1.922476E-01 1.387224E+02 + 2.910007E+01 6.000000E+01 5 2.369875E+02 8.993078E+01 2.863030E-01 2.369873E+02 + 2.910007E+01 6.000000E+01 6 6.311901E+01 -9.038706E-04 6.311901E+01 -9.957352E-04 + 2.910007E+01 9.000000E+01 1 2.394512E-06 -9.004845E+01 -2.025197E-09 -2.394511E-06 + 2.910007E+01 9.000000E+01 2 4.898807E+01 8.992059E+01 6.789295E-02 4.898802E+01 + 2.910007E+01 9.000000E+01 3 1.879809E+02 2.989702E-01 1.879783E+02 9.808823E-01 + 2.910007E+01 9.000000E+01 4 1.613429E+02 8.992085E+01 2.228654E-01 1.613427E+02 + 2.910007E+01 9.000000E+01 5 1.099485E-04 -8.999020E+01 1.880766E-08 -1.099485E-04 + 2.910007E+01 9.000000E+01 6 5.423113E-06 1.799994E+02 -5.423113E-06 5.768371E-11 + 2.920008E+01 0.000000E+00 1 4.549806E+01 8.993128E+01 5.456414E-02 4.549802E+01 + 2.920008E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.920008E+01 0.000000E+00 3 1.851628E+02 2.947226E-01 1.851604E+02 9.524513E-01 + 2.920008E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.920008E+01 0.000000E+00 5 4.677693E+02 8.993129E+01 5.609504E-01 4.677689E+02 + 2.920008E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.920008E+01 3.000000E+01 1 3.954085E+01 8.993129E+01 4.741634E-02 3.954082E+01 + 2.920008E+01 3.000000E+01 2 2.412669E+01 8.992123E+01 3.316514E-02 2.412667E+01 + 2.920008E+01 3.000000E+01 3 1.858962E+02 2.952467E-01 1.858938E+02 9.579241E-01 + 2.920008E+01 3.000000E+01 4 7.864951E+01 8.992072E+01 1.088400E-01 7.864943E+01 + 2.920008E+01 3.000000E+01 5 4.065047E+02 8.993129E+01 4.874707E-01 4.065044E+02 + 2.920008E+01 3.000000E+01 6 6.216718E+01 -8.923067E-04 6.216718E+01 -9.681724E-04 + 2.920008E+01 6.000000E+01 1 2.298986E+01 8.993130E+01 2.756465E-02 2.298984E+01 + 2.920008E+01 6.000000E+01 2 4.211215E+01 8.992123E+01 5.789485E-02 4.211211E+01 + 2.920008E+01 6.000000E+01 3 1.873722E+02 2.962984E-01 1.873697E+02 9.689689E-01 + 2.920008E+01 6.000000E+01 4 1.382000E+02 8.992123E+01 1.899966E-01 1.381999E+02 + 2.920008E+01 6.000000E+01 5 2.363138E+02 8.993129E+01 2.833776E-01 2.363137E+02 + 2.920008E+01 6.000000E+01 6 6.266233E+01 -8.899080E-04 6.266233E+01 -9.732604E-04 + 2.920008E+01 9.000000E+01 1 2.385977E-06 -9.004819E+01 -2.006705E-09 -2.385976E-06 + 2.920008E+01 9.000000E+01 2 4.881489E+01 8.992123E+01 6.711344E-02 4.881485E+01 + 2.920008E+01 9.000000E+01 3 1.881146E+02 2.968224E-01 1.881121E+02 9.745286E-01 + 2.920008E+01 9.000000E+01 4 1.607267E+02 8.992149E+01 2.202494E-01 1.607265E+02 + 2.920008E+01 9.000000E+01 5 1.095814E-04 -8.999030E+01 1.855737E-08 -1.095814E-04 + 2.920008E+01 9.000000E+01 6 5.383661E-06 1.799994E+02 -5.383661E-06 5.638373E-11 + 2.930008E+01 0.000000E+00 1 4.534274E+01 8.993180E+01 5.397703E-02 4.534271E+01 + 2.930008E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.930008E+01 0.000000E+00 3 1.853160E+02 2.926262E-01 1.853136E+02 9.464585E-01 + 2.930008E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.930008E+01 0.000000E+00 5 4.664778E+02 8.993180E+01 5.552765E-01 4.664775E+02 + 2.930008E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.930008E+01 3.000000E+01 1 3.940488E+01 8.993180E+01 4.690501E-02 3.940486E+01 + 2.930008E+01 3.000000E+01 2 2.404375E+01 8.992187E+01 3.278877E-02 2.404373E+01 + 2.930008E+01 3.000000E+01 3 1.860446E+02 2.931412E-01 1.860421E+02 9.518520E-01 + 2.930008E+01 3.000000E+01 4 7.836202E+01 8.992135E+01 1.075768E-01 7.836195E+01 + 2.930008E+01 3.000000E+01 5 4.053678E+02 8.993180E+01 4.825287E-01 4.053676E+02 + 2.930008E+01 3.000000E+01 6 6.172264E+01 -8.785634E-04 6.172264E+01 -9.464441E-04 + 2.930008E+01 6.000000E+01 1 2.290953E+01 8.993181E+01 2.726608E-02 2.290951E+01 + 2.930008E+01 6.000000E+01 2 4.196497E+01 8.992186E+01 5.723463E-02 4.196493E+01 + 2.930008E+01 6.000000E+01 3 1.875102E+02 2.941777E-01 1.875077E+02 9.627420E-01 + 2.930008E+01 6.000000E+01 4 1.376808E+02 8.992186E+01 1.877802E-01 1.376807E+02 + 2.930008E+01 6.000000E+01 5 2.356416E+02 8.993180E+01 2.804900E-01 2.356414E+02 + 2.930008E+01 6.000000E+01 6 6.221064E+01 -8.762188E-04 6.221064E+01 -9.513813E-04 + 2.930008E+01 9.000000E+01 1 2.377505E-06 -9.004792E+01 -1.988428E-09 -2.377504E-06 + 2.930008E+01 9.000000E+01 2 4.864286E+01 8.992185E+01 6.634599E-02 4.864281E+01 + 2.930008E+01 9.000000E+01 3 1.882483E+02 2.946921E-01 1.882458E+02 9.682223E-01 + 2.930008E+01 9.000000E+01 4 1.601145E+02 8.992210E+01 2.176737E-01 1.601144E+02 + 2.930008E+01 9.000000E+01 5 1.092160E-04 -8.999039E+01 1.831153E-08 -1.092160E-04 + 2.930008E+01 9.000000E+01 6 5.344647E-06 1.799994E+02 -5.344647E-06 5.511807E-11 + 2.940008E+01 0.000000E+00 1 4.518850E+01 8.993230E+01 5.339843E-02 4.518847E+01 + 2.940008E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.940008E+01 0.000000E+00 3 1.854676E+02 2.905528E-01 1.854652E+02 9.405209E-01 + 2.940008E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.940008E+01 0.000000E+00 5 4.651899E+02 8.993230E+01 5.496780E-01 4.651896E+02 + 2.940008E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.940008E+01 3.000000E+01 1 3.926988E+01 8.993230E+01 4.640102E-02 3.926986E+01 + 2.940008E+01 3.000000E+01 2 2.396139E+01 8.992248E+01 3.241828E-02 2.396137E+01 + 2.940008E+01 3.000000E+01 3 1.861911E+02 2.910613E-01 1.861888E+02 9.458427E-01 + 2.940008E+01 3.000000E+01 4 7.807688E+01 8.992197E+01 1.063335E-01 7.807681E+01 + 2.940008E+01 3.000000E+01 5 4.042377E+02 8.993230E+01 4.776469E-01 4.042374E+02 + 2.940008E+01 3.000000E+01 6 6.128293E+01 -8.650887E-04 6.128293E+01 -9.252893E-04 + 2.940008E+01 6.000000E+01 1 2.282981E+01 8.993231E+01 2.697182E-02 2.282980E+01 + 2.940008E+01 6.000000E+01 2 4.181889E+01 8.992248E+01 5.658454E-02 4.181886E+01 + 2.940008E+01 6.000000E+01 3 1.876475E+02 2.920804E-01 1.876450E+02 9.565786E-01 + 2.940008E+01 6.000000E+01 4 1.371663E+02 8.992248E+01 1.855994E-01 1.371662E+02 + 2.940008E+01 6.000000E+01 5 2.349724E+02 8.993230E+01 2.776411E-01 2.349723E+02 + 2.940008E+01 6.000000E+01 6 6.176389E+01 -8.627969E-04 6.176389E+01 -9.300805E-04 + 2.940008E+01 9.000000E+01 1 2.369096E-06 -9.004765E+01 -1.970345E-09 -2.369095E-06 + 2.940008E+01 9.000000E+01 2 4.847226E+01 8.992248E+01 6.559054E-02 4.847221E+01 + 2.940008E+01 9.000000E+01 3 1.883794E+02 2.925909E-01 1.883770E+02 9.619884E-01 + 2.940008E+01 9.000000E+01 4 1.595086E+02 8.992272E+01 2.151389E-01 1.595084E+02 + 2.940008E+01 9.000000E+01 5 1.088531E-04 -8.999049E+01 1.807004E-08 -1.088531E-04 + 2.940008E+01 9.000000E+01 6 5.306068E-06 1.799994E+02 -5.306068E-06 5.388587E-11 + 2.950008E+01 0.000000E+00 1 4.503524E+01 8.993279E+01 5.282796E-02 4.503521E+01 + 2.950008E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.950008E+01 0.000000E+00 3 1.856178E+02 2.885004E-01 1.856155E+02 9.346341E-01 + 2.950008E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.950008E+01 0.000000E+00 5 4.639080E+02 8.993279E+01 5.441520E-01 4.639077E+02 + 2.950008E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.950008E+01 3.000000E+01 1 3.913564E+01 8.993279E+01 4.590441E-02 3.913562E+01 + 2.950008E+01 3.000000E+01 2 2.387957E+01 8.992310E+01 3.205346E-02 2.387955E+01 + 2.950008E+01 3.000000E+01 3 1.863369E+02 2.890021E-01 1.863346E+02 9.398865E-01 + 2.950008E+01 3.000000E+01 4 7.779379E+01 8.992258E+01 1.051103E-01 7.779372E+01 + 2.950008E+01 3.000000E+01 5 4.031126E+02 8.993279E+01 4.728397E-01 4.031123E+02 + 2.950008E+01 3.000000E+01 6 6.084794E+01 -8.518766E-04 6.084794E+01 -9.046903E-04 + 2.950008E+01 6.000000E+01 1 2.275075E+01 8.993281E+01 2.668183E-02 2.275074E+01 + 2.950008E+01 6.000000E+01 2 4.167384E+01 8.992308E+01 5.594446E-02 4.167380E+01 + 2.950008E+01 6.000000E+01 3 1.877826E+02 2.900069E-01 1.877802E+02 9.504718E-01 + 2.950008E+01 6.000000E+01 4 1.366552E+02 8.992308E+01 1.834532E-01 1.366551E+02 + 2.950008E+01 6.000000E+01 5 2.343090E+02 8.993279E+01 2.748291E-01 2.343089E+02 + 2.950008E+01 6.000000E+01 6 6.132202E+01 -8.496349E-04 6.132202E+01 -9.093396E-04 + 2.950008E+01 9.000000E+01 1 2.360742E-06 -9.004739E+01 -1.952473E-09 -2.360742E-06 + 2.950008E+01 9.000000E+01 2 4.830267E+01 8.992308E+01 6.484669E-02 4.830262E+01 + 2.950008E+01 9.000000E+01 3 1.885108E+02 2.905099E-01 1.885083E+02 9.558124E-01 + 2.950008E+01 9.000000E+01 4 1.589058E+02 8.992332E+01 2.126458E-01 1.589057E+02 + 2.950008E+01 9.000000E+01 5 1.084931E-04 -8.999059E+01 1.783283E-08 -1.084931E-04 + 2.950008E+01 9.000000E+01 6 5.267908E-06 1.799994E+02 -5.267908E-06 5.268607E-11 + 2.960008E+01 0.000000E+00 1 4.488310E+01 8.993328E+01 5.226607E-02 4.488307E+01 + 2.960008E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.960008E+01 0.000000E+00 3 1.857660E+02 2.864744E-01 1.857637E+02 9.288118E-01 + 2.960008E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.960008E+01 0.000000E+00 5 4.626335E+02 8.993329E+01 5.387046E-01 4.626332E+02 + 2.960008E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.960008E+01 3.000000E+01 1 3.900241E+01 8.993329E+01 4.541489E-02 3.900238E+01 + 2.960008E+01 3.000000E+01 2 2.379830E+01 8.992370E+01 3.169409E-02 2.379828E+01 + 2.960008E+01 3.000000E+01 3 1.864805E+02 2.869669E-01 1.864781E+02 9.339865E-01 + 2.960008E+01 3.000000E+01 4 7.751311E+01 8.992319E+01 1.039054E-01 7.751304E+01 + 2.960008E+01 3.000000E+01 5 4.019959E+02 8.993329E+01 4.680890E-01 4.019956E+02 + 2.960008E+01 3.000000E+01 6 6.041780E+01 -8.389194E-04 6.041780E+01 -8.846318E-04 + 2.960008E+01 6.000000E+01 1 2.267214E+01 8.993330E+01 2.639602E-02 2.267212E+01 + 2.960008E+01 6.000000E+01 2 4.152969E+01 8.992369E+01 5.531419E-02 4.152965E+01 + 2.960008E+01 6.000000E+01 3 1.879169E+02 2.879573E-01 1.879145E+02 9.444292E-01 + 2.960008E+01 6.000000E+01 4 1.361490E+02 8.992369E+01 1.813403E-01 1.361488E+02 + 2.960008E+01 6.000000E+01 5 2.336446E+02 8.993329E+01 2.720580E-01 2.336444E+02 + 2.960008E+01 6.000000E+01 6 6.088495E+01 -8.367306E-04 6.088495E+01 -8.891458E-04 + 2.960008E+01 9.000000E+01 1 2.352451E-06 -9.004713E+01 -1.934784E-09 -2.352450E-06 + 2.960008E+01 9.000000E+01 2 4.813428E+01 8.992368E+01 6.411441E-02 4.813424E+01 + 2.960008E+01 9.000000E+01 3 1.886402E+02 2.884483E-01 1.886378E+02 9.496808E-01 + 2.960008E+01 9.000000E+01 4 1.583091E+02 8.992393E+01 2.101913E-01 1.583089E+02 + 2.960008E+01 9.000000E+01 5 1.081352E-04 -8.999068E+01 1.759984E-08 -1.081352E-04 + 2.960008E+01 9.000000E+01 6 5.230166E-06 1.799994E+02 -5.230166E-06 5.151773E-11 + 2.970008E+01 0.000000E+00 1 4.473183E+01 8.993376E+01 5.171188E-02 4.473180E+01 + 2.970008E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.970008E+01 0.000000E+00 3 1.859136E+02 2.844649E-01 1.859113E+02 9.230294E-01 + 2.970008E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.970008E+01 0.000000E+00 5 4.613603E+02 8.993376E+01 5.333279E-01 4.613600E+02 + 2.970008E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.970008E+01 3.000000E+01 1 3.887003E+01 8.993377E+01 4.493246E-02 3.887001E+01 + 2.970008E+01 3.000000E+01 2 2.371763E+01 8.992429E+01 3.134031E-02 2.371761E+01 + 2.970008E+01 3.000000E+01 3 1.866223E+02 2.849506E-01 1.866200E+02 9.281297E-01 + 2.970008E+01 3.000000E+01 4 7.723470E+01 8.992380E+01 1.027199E-01 7.723463E+01 + 2.970008E+01 3.000000E+01 5 4.008798E+02 8.993377E+01 4.634041E-01 4.008795E+02 + 2.970008E+01 3.000000E+01 6 5.999210E+01 -8.262128E-04 5.999210E+01 -8.650940E-04 + 2.970008E+01 6.000000E+01 1 2.259411E+01 8.993378E+01 2.611432E-02 2.259409E+01 + 2.970008E+01 6.000000E+01 2 4.138663E+01 8.992429E+01 5.469355E-02 4.138660E+01 + 2.970008E+01 6.000000E+01 3 1.880501E+02 2.859252E-01 1.880478E+02 9.384295E-01 + 2.970008E+01 6.000000E+01 4 1.356459E+02 8.992429E+01 1.792611E-01 1.356457E+02 + 2.970008E+01 6.000000E+01 5 2.329868E+02 8.993377E+01 2.693222E-01 2.329866E+02 + 2.970008E+01 6.000000E+01 6 6.045265E+01 -8.240722E-04 6.045265E+01 -8.694767E-04 + 2.970008E+01 9.000000E+01 1 2.344221E-06 -9.004687E+01 -1.917299E-09 -2.344220E-06 + 2.970008E+01 9.000000E+01 2 4.796714E+01 8.992428E+01 6.339323E-02 4.796710E+01 + 2.970008E+01 9.000000E+01 3 1.887684E+02 2.864132E-01 1.887661E+02 9.436218E-01 + 2.970008E+01 9.000000E+01 4 1.577163E+02 8.992452E+01 2.077747E-01 1.577162E+02 + 2.970008E+01 9.000000E+01 5 1.077796E-04 -8.999077E+01 1.737087E-08 -1.077796E-04 + 2.970008E+01 9.000000E+01 6 5.192836E-06 1.799995E+02 -5.192836E-06 5.037978E-11 + 2.980008E+01 0.000000E+00 1 4.458161E+01 8.993424E+01 5.116573E-02 4.458158E+01 + 2.980008E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.980008E+01 0.000000E+00 3 1.860588E+02 2.824788E-01 1.860565E+02 9.173005E-01 + 2.980008E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.980008E+01 0.000000E+00 5 4.600951E+02 8.993425E+01 5.280202E-01 4.600948E+02 + 2.980008E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.980008E+01 3.000000E+01 1 3.873870E+01 8.993425E+01 4.445663E-02 3.873868E+01 + 2.980008E+01 3.000000E+01 2 2.363745E+01 8.992488E+01 3.099185E-02 2.363742E+01 + 2.980008E+01 3.000000E+01 3 1.867638E+02 2.829582E-01 1.867615E+02 9.223391E-01 + 2.980008E+01 3.000000E+01 4 7.695767E+01 8.992439E+01 1.015526E-01 7.695760E+01 + 2.980008E+01 3.000000E+01 5 3.997693E+02 8.993425E+01 4.587857E-01 3.997691E+02 + 2.980008E+01 3.000000E+01 6 5.957100E+01 -8.137521E-04 5.957100E+01 -8.460662E-04 + 2.980008E+01 6.000000E+01 1 2.251657E+01 8.993426E+01 2.583669E-02 2.251655E+01 + 2.980008E+01 6.000000E+01 2 4.124451E+01 8.992487E+01 5.408248E-02 4.124448E+01 + 2.980008E+01 6.000000E+01 3 1.881823E+02 2.839167E-01 1.881800E+02 9.324922E-01 + 2.980008E+01 6.000000E+01 4 1.351464E+02 8.992487E+01 1.772145E-01 1.351463E+02 + 2.980008E+01 6.000000E+01 5 2.323321E+02 8.993425E+01 2.666237E-01 2.323319E+02 + 2.980008E+01 6.000000E+01 6 6.002500E+01 -8.116572E-04 6.002500E+01 -8.503196E-04 + 2.980008E+01 9.000000E+01 1 2.336046E-06 -9.004660E+01 -1.900011E-09 -2.336046E-06 + 2.980008E+01 9.000000E+01 2 4.780128E+01 8.992487E+01 6.268329E-02 4.780124E+01 + 2.980008E+01 9.000000E+01 3 1.888957E+02 2.843975E-01 1.888934E+02 9.376126E-01 + 2.980008E+01 9.000000E+01 4 1.571293E+02 8.992510E+01 2.053965E-01 1.571291E+02 + 2.980008E+01 9.000000E+01 5 1.074264E-04 -8.999086E+01 1.714589E-08 -1.074264E-04 + 2.980008E+01 9.000000E+01 6 5.155914E-06 1.799995E+02 -5.155914E-06 4.927143E-11 + 2.990008E+01 0.000000E+00 1 4.443261E+01 8.993472E+01 5.062736E-02 4.443258E+01 + 2.990008E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.990008E+01 0.000000E+00 3 1.862035E+02 2.805118E-01 1.862012E+02 9.116213E-01 + 2.990008E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.990008E+01 0.000000E+00 5 4.588384E+02 8.993472E+01 5.227810E-01 4.588381E+02 + 2.990008E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 2.990008E+01 3.000000E+01 1 3.860804E+01 8.993472E+01 4.398783E-02 3.860802E+01 + 2.990008E+01 3.000000E+01 2 2.355785E+01 8.992546E+01 3.064860E-02 2.355783E+01 + 2.990008E+01 3.000000E+01 3 1.869043E+02 2.809834E-01 1.869021E+02 9.165912E-01 + 2.990008E+01 3.000000E+01 4 7.668298E+01 8.992498E+01 1.004033E-01 7.668291E+01 + 2.990008E+01 3.000000E+01 5 3.986673E+02 8.993472E+01 4.542212E-01 3.986671E+02 + 2.990008E+01 3.000000E+01 6 5.915438E+01 -8.015265E-04 5.915438E+01 -8.275269E-04 + 2.990008E+01 6.000000E+01 1 2.243959E+01 8.993473E+01 2.556304E-02 2.243958E+01 + 2.990008E+01 6.000000E+01 2 4.110343E+01 8.992545E+01 5.348057E-02 4.110339E+01 + 2.990008E+01 6.000000E+01 3 1.883131E+02 2.819290E-01 1.883108E+02 9.266077E-01 + 2.990008E+01 6.000000E+01 4 1.346508E+02 8.992545E+01 1.751986E-01 1.346507E+02 + 2.990008E+01 6.000000E+01 5 2.316790E+02 8.993472E+01 2.639591E-01 2.316788E+02 + 2.990008E+01 6.000000E+01 6 5.960191E+01 -7.994796E-04 5.960191E+01 -8.316583E-04 + 2.990008E+01 9.000000E+01 1 2.327931E-06 -9.004635E+01 -1.882912E-09 -2.327931E-06 + 2.990008E+01 9.000000E+01 2 4.763644E+01 8.992545E+01 6.198391E-02 4.763639E+01 + 2.990008E+01 9.000000E+01 3 1.890210E+02 2.824030E-01 1.890187E+02 9.316548E-01 + 2.990008E+01 9.000000E+01 4 1.565448E+02 8.992568E+01 2.030558E-01 1.565446E+02 + 2.990008E+01 9.000000E+01 5 1.070752E-04 -8.999094E+01 1.692479E-08 -1.070752E-04 + 2.990008E+01 9.000000E+01 6 5.119384E-06 1.799995E+02 -5.119384E-06 4.819163E-11 + 3.000008E+01 0.000000E+00 1 4.428444E+01 8.993519E+01 5.009654E-02 4.428441E+01 + 3.000008E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.000008E+01 0.000000E+00 3 1.863466E+02 2.785688E-01 1.863445E+02 9.060031E-01 + 3.000008E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.000008E+01 0.000000E+00 5 4.575834E+02 8.993519E+01 5.176095E-01 4.575831E+02 + 3.000008E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.000008E+01 3.000000E+01 1 3.847847E+01 8.993519E+01 4.352576E-02 3.847845E+01 + 3.000008E+01 3.000000E+01 2 2.347882E+01 8.992603E+01 3.031052E-02 2.347880E+01 + 3.000008E+01 3.000000E+01 3 1.870421E+02 2.790350E-01 1.870399E+02 9.109065E-01 + 3.000008E+01 3.000000E+01 4 7.640999E+01 8.992556E+01 9.927158E-02 7.640993E+01 + 3.000008E+01 3.000000E+01 5 3.975689E+02 8.993519E+01 4.497190E-01 3.975686E+02 + 3.000008E+01 3.000000E+01 6 5.874228E+01 -7.895360E-04 5.874228E+01 -8.094688E-04 + 3.000008E+01 6.000000E+01 1 2.236315E+01 8.993520E+01 2.529320E-02 2.236314E+01 + 3.000008E+01 6.000000E+01 2 4.096333E+01 8.992603E+01 5.288776E-02 4.096329E+01 + 3.000008E+01 6.000000E+01 3 1.884412E+02 2.799668E-01 1.884389E+02 9.207846E-01 + 3.000008E+01 6.000000E+01 4 1.341592E+02 8.992603E+01 1.732149E-01 1.341591E+02 + 3.000008E+01 6.000000E+01 5 2.310289E+02 8.993519E+01 2.613340E-01 2.310288E+02 + 3.000008E+01 6.000000E+01 6 5.918349E+01 -7.875339E-04 5.918349E+01 -8.134806E-04 + 3.000008E+01 9.000000E+01 1 2.319874E-06 -9.004609E+01 -1.866006E-09 -2.319874E-06 + 3.000008E+01 9.000000E+01 2 4.747283E+01 8.992603E+01 6.129526E-02 4.747279E+01 + 3.000008E+01 9.000000E+01 3 1.891457E+02 2.804316E-01 1.891434E+02 9.257614E-01 + 3.000008E+01 9.000000E+01 4 1.559664E+02 8.992625E+01 2.007503E-01 1.559662E+02 + 3.000008E+01 9.000000E+01 5 1.067263E-04 -8.999103E+01 1.670759E-08 -1.067263E-04 + 3.000008E+01 9.000000E+01 6 5.083257E-06 1.799995E+02 -5.083257E-06 4.713976E-11 + 3.010008E+01 0.000000E+00 1 4.413715E+01 8.993565E+01 4.957308E-02 4.413712E+01 + 3.010008E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.010008E+01 0.000000E+00 3 1.864881E+02 2.766453E-01 1.864859E+02 9.004302E-01 + 3.010008E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.010008E+01 0.000000E+00 5 4.563321E+02 8.993565E+01 5.125093E-01 4.563318E+02 + 3.010008E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.010008E+01 3.000000E+01 1 3.834960E+01 8.993565E+01 4.307000E-02 3.834958E+01 + 3.010008E+01 3.000000E+01 2 2.340023E+01 8.992660E+01 2.997750E-02 2.340022E+01 + 3.010008E+01 3.000000E+01 3 1.871787E+02 2.771035E-01 1.871766E+02 9.052616E-01 + 3.010008E+01 3.000000E+01 4 7.613928E+01 8.992613E+01 9.815692E-02 7.613922E+01 + 3.010008E+01 3.000000E+01 5 3.964720E+02 8.993565E+01 4.452759E-01 3.964718E+02 + 3.010008E+01 3.000000E+01 6 5.833445E+01 -7.777730E-04 5.833445E+01 -7.918726E-04 + 3.010008E+01 6.000000E+01 1 2.228726E+01 8.993566E+01 2.502731E-02 2.228725E+01 + 3.010008E+01 6.000000E+01 2 4.082419E+01 8.992659E+01 5.230393E-02 4.082416E+01 + 3.010008E+01 6.000000E+01 3 1.885693E+02 2.780216E-01 1.885671E+02 9.150085E-01 + 3.010008E+01 6.000000E+01 4 1.336717E+02 8.992659E+01 1.712611E-01 1.336716E+02 + 3.010008E+01 6.000000E+01 5 2.303822E+02 8.993565E+01 2.587382E-01 2.303821E+02 + 3.010008E+01 6.000000E+01 6 5.876945E+01 -7.758149E-04 5.876945E+01 -7.957692E-04 + 3.010008E+01 9.000000E+01 1 2.311875E-06 -9.004584E+01 -1.849279E-09 -2.311875E-06 + 3.010008E+01 9.000000E+01 2 4.731023E+01 8.992659E+01 6.061680E-02 4.731019E+01 + 3.010008E+01 9.000000E+01 3 1.892687E+02 2.784809E-01 1.892664E+02 9.199195E-01 + 3.010008E+01 9.000000E+01 4 1.553916E+02 8.992682E+01 1.984811E-01 1.553914E+02 + 3.010008E+01 9.000000E+01 5 1.063797E-04 -8.999112E+01 1.649406E-08 -1.063797E-04 + 3.010008E+01 9.000000E+01 6 5.047520E-06 1.799995E+02 -5.047520E-06 4.611490E-11 + 3.020008E+01 0.000000E+00 1 4.399104E+01 8.993610E+01 4.905705E-02 4.399102E+01 + 3.020008E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.020008E+01 0.000000E+00 3 1.866277E+02 2.747404E-01 1.866255E+02 8.948994E-01 + 3.020008E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.020008E+01 0.000000E+00 5 4.550890E+02 8.993610E+01 5.074785E-01 4.550887E+02 + 3.020008E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.020008E+01 3.000000E+01 1 3.822173E+01 8.993611E+01 4.262054E-02 3.822170E+01 + 3.020008E+01 3.000000E+01 2 2.332226E+01 8.992716E+01 2.964941E-02 2.332224E+01 + 3.020008E+01 3.000000E+01 3 1.873143E+02 2.751917E-01 1.873121E+02 8.996674E-01 + 3.020008E+01 3.000000E+01 4 7.587064E+01 8.992670E+01 9.705951E-02 7.587057E+01 + 3.020008E+01 3.000000E+01 5 3.953836E+02 8.993610E+01 4.408927E-01 3.953834E+02 + 3.020008E+01 3.000000E+01 6 5.793094E+01 -7.662302E-04 5.793094E+01 -7.747244E-04 + 3.020008E+01 6.000000E+01 1 2.221184E+01 8.993612E+01 2.476502E-02 2.221183E+01 + 3.020008E+01 6.000000E+01 2 4.068599E+01 8.992715E+01 5.172871E-02 4.068595E+01 + 3.020008E+01 6.000000E+01 3 1.886955E+02 2.760973E-01 1.886933E+02 9.092838E-01 + 3.020008E+01 6.000000E+01 4 1.331873E+02 8.992715E+01 1.693382E-01 1.331871E+02 + 3.020008E+01 6.000000E+01 5 2.297372E+02 8.993611E+01 2.561796E-01 2.297370E+02 + 3.020008E+01 6.000000E+01 6 5.835978E+01 -7.643160E-04 5.835978E+01 -7.785096E-04 + 3.020008E+01 9.000000E+01 1 2.303925E-06 -9.004558E+01 -1.832743E-09 -2.303924E-06 + 3.020008E+01 9.000000E+01 2 4.714886E+01 8.992715E+01 5.994865E-02 4.714883E+01 + 3.020008E+01 9.000000E+01 3 1.893911E+02 2.765493E-01 1.893889E+02 9.141296E-01 + 3.020008E+01 9.000000E+01 4 1.548217E+02 8.992738E+01 1.962462E-01 1.548215E+02 + 3.020008E+01 9.000000E+01 5 1.060351E-04 -8.999120E+01 1.628421E-08 -1.060351E-04 + 3.020008E+01 9.000000E+01 6 5.012160E-06 1.799995E+02 -5.012160E-06 4.511613E-11 + 3.030008E+01 0.000000E+00 1 4.384571E+01 8.993656E+01 4.854807E-02 4.384568E+01 + 3.030008E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.030008E+01 0.000000E+00 3 1.867672E+02 2.728531E-01 1.867651E+02 8.894166E-01 + 3.030008E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.030008E+01 0.000000E+00 5 4.538535E+02 8.993656E+01 5.025070E-01 4.538533E+02 + 3.030008E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.030008E+01 3.000000E+01 1 3.809455E+01 8.993656E+01 4.217757E-02 3.809453E+01 + 3.030008E+01 3.000000E+01 2 2.324474E+01 8.992771E+01 2.932620E-02 2.324472E+01 + 3.030008E+01 3.000000E+01 3 1.874488E+02 2.733010E-01 1.874466E+02 8.941275E-01 + 3.030008E+01 3.000000E+01 4 7.560383E+01 8.992726E+01 9.597894E-02 7.560377E+01 + 3.030008E+01 3.000000E+01 5 3.942994E+02 8.993656E+01 4.365642E-01 3.942992E+02 + 3.030008E+01 3.000000E+01 6 5.753164E+01 -7.549060E-04 5.753164E+01 -7.580137E-04 + 3.030008E+01 6.000000E+01 1 2.213692E+01 8.993657E+01 2.450664E-02 2.213691E+01 + 3.030008E+01 6.000000E+01 2 4.054869E+01 8.992770E+01 5.116217E-02 4.054866E+01 + 3.030008E+01 6.000000E+01 3 1.888214E+02 2.741920E-01 1.888193E+02 9.036114E-01 + 3.030008E+01 6.000000E+01 4 1.327063E+02 8.992770E+01 1.674437E-01 1.327062E+02 + 3.030008E+01 6.000000E+01 5 2.290964E+02 8.993656E+01 2.536536E-01 2.290963E+02 + 3.030008E+01 6.000000E+01 6 5.795443E+01 -7.530344E-04 5.795443E+01 -7.616910E-04 + 3.030008E+01 9.000000E+01 1 2.296035E-06 -9.004533E+01 -1.816389E-09 -2.296034E-06 + 3.030008E+01 9.000000E+01 2 4.698862E+01 8.992770E+01 5.929046E-02 4.698859E+01 + 3.030008E+01 9.000000E+01 3 1.895123E+02 2.746371E-01 1.895101E+02 9.083899E-01 + 3.030008E+01 9.000000E+01 4 1.542555E+02 8.992793E+01 1.940461E-01 1.542554E+02 + 3.030008E+01 9.000000E+01 5 1.056931E-04 -8.999129E+01 1.607786E-08 -1.056931E-04 + 3.030008E+01 9.000000E+01 6 4.977173E-06 1.799995E+02 -4.977173E-06 4.414284E-11 + 3.040008E+01 0.000000E+00 1 4.370139E+01 8.993701E+01 4.804649E-02 4.370137E+01 + 3.040008E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.040008E+01 0.000000E+00 3 1.869051E+02 2.709897E-01 1.869030E+02 8.839947E-01 + 3.040008E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.040008E+01 0.000000E+00 5 4.526188E+02 8.993701E+01 4.975999E-01 4.526185E+02 + 3.040008E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.040008E+01 3.000000E+01 1 3.796838E+01 8.993702E+01 4.174079E-02 3.796835E+01 + 3.040008E+01 3.000000E+01 2 2.316777E+01 8.992826E+01 2.900782E-02 2.316776E+01 + 3.040008E+01 3.000000E+01 3 1.875829E+02 2.714281E-01 1.875808E+02 8.886361E-01 + 3.040008E+01 3.000000E+01 4 7.533876E+01 8.992782E+01 9.491497E-02 7.533870E+01 + 3.040008E+01 3.000000E+01 5 3.932216E+02 8.993701E+01 4.322958E-01 3.932214E+02 + 3.040008E+01 3.000000E+01 6 5.713646E+01 -7.437957E-04 5.713646E+01 -7.417274E-04 + 3.040008E+01 6.000000E+01 1 2.206254E+01 8.993702E+01 2.425172E-02 2.206253E+01 + 3.040008E+01 6.000000E+01 2 4.041239E+01 8.992825E+01 5.060411E-02 4.041236E+01 + 3.040008E+01 6.000000E+01 3 1.889464E+02 2.723086E-01 1.889442E+02 8.979985E-01 + 3.040008E+01 6.000000E+01 4 1.322292E+02 8.992825E+01 1.655786E-01 1.322291E+02 + 3.040008E+01 6.000000E+01 5 2.284614E+02 8.993702E+01 2.511606E-01 2.284613E+02 + 3.040008E+01 6.000000E+01 6 5.755345E+01 -7.419637E-04 5.755345E+01 -7.453004E-04 + 3.040008E+01 9.000000E+01 1 2.288200E-06 -9.004507E+01 -1.800219E-09 -2.288199E-06 + 3.040008E+01 9.000000E+01 2 4.682941E+01 8.992825E+01 5.864220E-02 4.682937E+01 + 3.040008E+01 9.000000E+01 3 1.896316E+02 2.727475E-01 1.896294E+02 9.027076E-01 + 3.040008E+01 9.000000E+01 4 1.536942E+02 8.992847E+01 1.918793E-01 1.536940E+02 + 3.040008E+01 9.000000E+01 5 1.053537E-04 -8.999137E+01 1.587513E-08 -1.053537E-04 + 3.040008E+01 9.000000E+01 6 4.942566E-06 1.799995E+02 -4.942566E-06 4.319428E-11 + 3.050008E+01 0.000000E+00 1 4.355813E+01 8.993745E+01 4.755162E-02 4.355810E+01 + 3.050008E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.050008E+01 0.000000E+00 3 1.870413E+02 2.691429E-01 1.870393E+02 8.786101E-01 + 3.050008E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.050008E+01 0.000000E+00 5 4.513942E+02 8.993745E+01 4.927564E-01 4.513939E+02 + 3.050008E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.050008E+01 3.000000E+01 1 3.784296E+01 8.993745E+01 4.131014E-02 3.784294E+01 + 3.050008E+01 3.000000E+01 2 2.309130E+01 8.992880E+01 2.869410E-02 2.309128E+01 + 3.050008E+01 3.000000E+01 3 1.877141E+02 2.695771E-01 1.877121E+02 8.831933E-01 + 3.050008E+01 3.000000E+01 4 7.507595E+01 8.992836E+01 9.386633E-02 7.507589E+01 + 3.050008E+01 3.000000E+01 5 3.921465E+02 8.993745E+01 4.280784E-01 3.921463E+02 + 3.050008E+01 3.000000E+01 6 5.674545E+01 -7.328924E-04 5.674545E+01 -7.258530E-04 + 3.050008E+01 6.000000E+01 1 2.198871E+01 8.993747E+01 2.400045E-02 2.198870E+01 + 3.050008E+01 6.000000E+01 2 4.027695E+01 8.992880E+01 5.005425E-02 4.027692E+01 + 3.050008E+01 6.000000E+01 3 1.890693E+02 2.704426E-01 1.890672E+02 8.924252E-01 + 3.050008E+01 6.000000E+01 4 1.317560E+02 8.992880E+01 1.637411E-01 1.317559E+02 + 3.050008E+01 6.000000E+01 5 2.278264E+02 8.993745E+01 2.487008E-01 2.278262E+02 + 3.050008E+01 6.000000E+01 6 5.715665E+01 -7.310992E-04 5.715665E+01 -7.293238E-04 + 3.050008E+01 9.000000E+01 1 2.280426E-06 -9.004483E+01 -1.784220E-09 -2.280425E-06 + 3.050008E+01 9.000000E+01 2 4.667132E+01 8.992879E+01 5.800344E-02 4.667128E+01 + 3.050008E+01 9.000000E+01 3 1.897509E+02 2.708740E-01 1.897488E+02 8.970714E-01 + 3.050008E+01 9.000000E+01 4 1.531367E+02 8.992901E+01 1.897454E-01 1.531366E+02 + 3.050008E+01 9.000000E+01 5 1.050156E-04 -8.999145E+01 1.567574E-08 -1.050156E-04 + 3.050008E+01 9.000000E+01 6 4.908320E-06 1.799995E+02 -4.908320E-06 4.226957E-11 + 3.060008E+01 0.000000E+00 1 4.341547E+01 8.993789E+01 4.706380E-02 4.341545E+01 + 3.060008E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.060008E+01 0.000000E+00 3 1.871758E+02 2.673157E-01 1.871738E+02 8.732731E-01 + 3.060008E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.060008E+01 0.000000E+00 5 4.501742E+02 8.993790E+01 4.879782E-01 4.501739E+02 + 3.060008E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.060008E+01 3.000000E+01 1 3.771829E+01 8.993790E+01 4.088533E-02 3.771827E+01 + 3.060008E+01 3.000000E+01 2 2.301533E+01 8.992934E+01 2.838496E-02 2.301531E+01 + 3.060008E+01 3.000000E+01 3 1.878450E+02 2.677438E-01 1.878429E+02 8.777985E-01 + 3.060008E+01 3.000000E+01 4 7.481495E+01 8.992891E+01 9.283397E-02 7.481489E+01 + 3.060008E+01 3.000000E+01 5 3.910774E+02 8.993790E+01 4.239163E-01 3.910772E+02 + 3.060008E+01 3.000000E+01 6 5.635844E+01 -7.221899E-04 5.635844E+01 -7.103751E-04 + 3.060008E+01 6.000000E+01 1 2.191535E+01 8.993790E+01 2.375261E-02 2.191534E+01 + 3.060008E+01 6.000000E+01 2 4.014241E+01 8.992933E+01 4.951235E-02 4.014238E+01 + 3.060008E+01 6.000000E+01 3 1.891911E+02 2.685968E-01 1.891890E+02 8.869054E-01 + 3.060008E+01 6.000000E+01 4 1.312857E+02 8.992933E+01 1.619315E-01 1.312856E+02 + 3.060008E+01 6.000000E+01 5 2.271952E+02 8.993790E+01 2.462717E-01 2.271951E+02 + 3.060008E+01 6.000000E+01 6 5.676398E+01 -7.204352E-04 5.676398E+01 -7.137483E-04 + 3.060008E+01 9.000000E+01 1 2.272691E-06 -9.004459E+01 -1.768402E-09 -2.272690E-06 + 3.060008E+01 9.000000E+01 2 4.651435E+01 8.992933E+01 5.737413E-02 4.651432E+01 + 3.060008E+01 9.000000E+01 3 1.898685E+02 2.690236E-01 1.898664E+02 8.914955E-01 + 3.060008E+01 9.000000E+01 4 1.525838E+02 8.992954E+01 1.876438E-01 1.525837E+02 + 3.060008E+01 9.000000E+01 5 1.046796E-04 -8.999152E+01 1.547975E-08 -1.046796E-04 + 3.060008E+01 9.000000E+01 6 4.874436E-06 1.799995E+02 -4.874436E-06 4.136818E-11 + 3.070008E+01 0.000000E+00 1 4.327412E+01 8.993832E+01 4.658252E-02 4.327409E+01 + 3.070008E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.070008E+01 0.000000E+00 3 1.873088E+02 2.655096E-01 1.873068E+02 8.679889E-01 + 3.070008E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.070008E+01 0.000000E+00 5 4.489539E+02 8.993832E+01 4.832589E-01 4.489536E+02 + 3.070008E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.070008E+01 3.000000E+01 1 3.759457E+01 8.993832E+01 4.046637E-02 3.759455E+01 + 3.070008E+01 3.000000E+01 2 2.293990E+01 8.992986E+01 2.808030E-02 2.293988E+01 + 3.070008E+01 3.000000E+01 3 1.879740E+02 2.659305E-01 1.879720E+02 8.724524E-01 + 3.070008E+01 3.000000E+01 4 7.455549E+01 8.992944E+01 9.181644E-02 7.455544E+01 + 3.070008E+01 3.000000E+01 5 3.900139E+02 8.993832E+01 4.198111E-01 3.900136E+02 + 3.070008E+01 3.000000E+01 6 5.597549E+01 -7.116874E-04 5.597549E+01 -6.952877E-04 + 3.070008E+01 6.000000E+01 1 2.184251E+01 8.993833E+01 2.350826E-02 2.184250E+01 + 3.070008E+01 6.000000E+01 2 4.000882E+01 8.992986E+01 4.897862E-02 4.000879E+01 + 3.070008E+01 6.000000E+01 3 1.893117E+02 2.667704E-01 1.893097E+02 8.814362E-01 + 3.070008E+01 6.000000E+01 4 1.308191E+02 8.992986E+01 1.601499E-01 1.308190E+02 + 3.070008E+01 6.000000E+01 5 2.265663E+02 8.993832E+01 2.438751E-01 2.265661E+02 + 3.070008E+01 6.000000E+01 6 5.637542E+01 -7.099709E-04 5.637542E+01 -6.985664E-04 + 3.070008E+01 9.000000E+01 1 2.265018E-06 -9.004434E+01 -1.752754E-09 -2.265018E-06 + 3.070008E+01 9.000000E+01 2 4.635834E+01 8.992986E+01 5.675413E-02 4.635830E+01 + 3.070008E+01 9.000000E+01 3 1.899848E+02 2.671911E-01 1.899827E+02 8.859651E-01 + 3.070008E+01 9.000000E+01 4 1.520348E+02 8.993006E+01 1.855742E-01 1.520347E+02 + 3.070008E+01 9.000000E+01 5 1.043465E-04 -8.999161E+01 1.528707E-08 -1.043465E-04 + 3.070008E+01 9.000000E+01 6 4.840912E-06 1.799995E+02 -4.840912E-06 4.048949E-11 + 3.080008E+01 0.000000E+00 1 4.313348E+01 8.993876E+01 4.610780E-02 4.313346E+01 + 3.080008E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.080008E+01 0.000000E+00 3 1.874410E+02 2.637186E-01 1.874390E+02 8.627427E-01 + 3.080008E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.080008E+01 0.000000E+00 5 4.477463E+02 8.993876E+01 4.785979E-01 4.477460E+02 + 3.080008E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.080008E+01 3.000000E+01 1 3.747162E+01 8.993876E+01 4.005323E-02 3.747160E+01 + 3.080008E+01 3.000000E+01 2 2.286489E+01 8.993039E+01 2.778010E-02 2.286487E+01 + 3.080008E+01 3.000000E+01 3 1.881021E+02 2.641324E-01 1.881001E+02 8.671439E-01 + 3.080008E+01 3.000000E+01 4 7.429823E+01 8.992997E+01 9.081502E-02 7.429818E+01 + 3.080008E+01 3.000000E+01 5 3.889516E+02 8.993876E+01 4.157513E-01 3.889514E+02 + 3.080008E+01 3.000000E+01 6 5.559647E+01 -7.013758E-04 5.559647E+01 -6.805740E-04 + 3.080008E+01 6.000000E+01 1 2.177006E+01 8.993877E+01 2.326731E-02 2.177005E+01 + 3.080008E+01 6.000000E+01 2 3.987618E+01 8.993038E+01 4.845255E-02 3.987615E+01 + 3.080008E+01 6.000000E+01 3 1.894314E+02 2.649621E-01 1.894293E+02 8.760148E-01 + 3.080008E+01 6.000000E+01 4 1.303561E+02 8.993038E+01 1.583941E-01 1.303560E+02 + 3.080008E+01 6.000000E+01 5 2.259407E+02 8.993876E+01 2.415084E-01 2.259406E+02 + 3.080008E+01 6.000000E+01 6 5.599092E+01 -6.996971E-04 5.599092E+01 -6.837621E-04 + 3.080008E+01 9.000000E+01 1 2.257399E-06 -9.004409E+01 -1.737281E-09 -2.257398E-06 + 3.080008E+01 9.000000E+01 2 4.620346E+01 8.993037E+01 5.614324E-02 4.620343E+01 + 3.080008E+01 9.000000E+01 3 1.901001E+02 2.653768E-01 1.900981E+02 8.804832E-01 + 3.080008E+01 9.000000E+01 4 1.514902E+02 8.993059E+01 1.835350E-01 1.514901E+02 + 3.080008E+01 9.000000E+01 5 1.040144E-04 -8.999168E+01 1.509754E-08 -1.040144E-04 + 3.080008E+01 9.000000E+01 6 4.807736E-06 1.799995E+02 -4.807736E-06 3.963256E-11 + 3.090008E+01 0.000000E+00 1 4.299379E+01 8.993918E+01 4.563982E-02 4.299377E+01 + 3.090008E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.090008E+01 0.000000E+00 3 1.875726E+02 2.619484E-01 1.875706E+02 8.575530E-01 + 3.090008E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.090008E+01 0.000000E+00 5 4.465399E+02 8.993918E+01 4.739981E-01 4.465397E+02 + 3.090008E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.090008E+01 3.000000E+01 1 3.734951E+01 8.993918E+01 3.964584E-02 3.734948E+01 + 3.090008E+01 3.000000E+01 2 2.279037E+01 8.993090E+01 2.748421E-02 2.279035E+01 + 3.090008E+01 3.000000E+01 3 1.882289E+02 2.623577E-01 1.882269E+02 8.618982E-01 + 3.090008E+01 3.000000E+01 4 7.404259E+01 8.993050E+01 8.982762E-02 7.404254E+01 + 3.090008E+01 3.000000E+01 5 3.878961E+02 8.993918E+01 4.117511E-01 3.878959E+02 + 3.090008E+01 3.000000E+01 6 5.522128E+01 -6.912568E-04 5.522128E+01 -6.662285E-04 + 3.090008E+01 6.000000E+01 1 2.169816E+01 8.993919E+01 2.302962E-02 2.169815E+01 + 3.090008E+01 6.000000E+01 2 3.974430E+01 8.993089E+01 4.793413E-02 3.974427E+01 + 3.090008E+01 6.000000E+01 3 1.895503E+02 2.631741E-01 1.895483E+02 8.706501E-01 + 3.090008E+01 6.000000E+01 4 1.298961E+02 8.993089E+01 1.566642E-01 1.298960E+02 + 3.090008E+01 6.000000E+01 5 2.253170E+02 8.993918E+01 2.391713E-01 2.253169E+02 + 3.090008E+01 6.000000E+01 6 5.561031E+01 -6.896126E-04 5.561031E+01 -6.693262E-04 + 3.090008E+01 9.000000E+01 1 2.249829E-06 -9.004385E+01 -1.721973E-09 -2.249828E-06 + 3.090008E+01 9.000000E+01 2 4.604965E+01 8.993089E+01 5.554111E-02 4.604961E+01 + 3.090008E+01 9.000000E+01 3 1.902134E+02 2.635837E-01 1.902114E+02 8.750553E-01 + 3.090008E+01 9.000000E+01 4 1.509488E+02 8.993110E+01 1.815263E-01 1.509487E+02 + 3.090008E+01 9.000000E+01 5 1.036849E-04 -8.999176E+01 1.491125E-08 -1.036849E-04 + 3.090008E+01 9.000000E+01 6 4.774903E-06 1.799995E+02 -4.774903E-06 3.879698E-11 + 3.100008E+01 0.000000E+00 1 4.285502E+01 8.993960E+01 4.517803E-02 4.285500E+01 + 3.100008E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.100008E+01 0.000000E+00 3 1.877029E+02 2.601949E-01 1.877009E+02 8.524042E-01 + 3.100008E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.100008E+01 0.000000E+00 5 4.453406E+02 8.993961E+01 4.694585E-01 4.453404E+02 + 3.100008E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.100008E+01 3.000000E+01 1 3.722807E+01 8.993961E+01 3.924388E-02 3.722805E+01 + 3.100008E+01 3.000000E+01 2 2.271643E+01 8.993141E+01 2.719263E-02 2.271642E+01 + 3.100008E+01 3.000000E+01 3 1.883554E+02 2.605982E-01 1.883535E+02 8.566936E-01 + 3.100008E+01 3.000000E+01 4 7.378862E+01 8.993101E+01 8.885553E-02 7.378857E+01 + 3.100008E+01 3.000000E+01 5 3.868489E+02 8.993961E+01 4.077967E-01 3.868487E+02 + 3.100008E+01 3.000000E+01 6 5.485001E+01 -6.813236E-04 5.485001E+01 -6.522401E-04 + 3.100008E+01 6.000000E+01 1 2.162674E+01 8.993961E+01 2.279516E-02 2.162673E+01 + 3.100008E+01 6.000000E+01 2 3.961340E+01 8.993141E+01 4.742325E-02 3.961337E+01 + 3.100008E+01 6.000000E+01 3 1.896681E+02 2.614026E-01 1.896662E+02 8.653268E-01 + 3.100008E+01 6.000000E+01 4 1.294397E+02 8.993141E+01 1.549607E-01 1.294396E+02 + 3.100008E+01 6.000000E+01 5 2.246980E+02 8.993961E+01 2.368684E-01 2.246979E+02 + 3.100008E+01 6.000000E+01 6 5.523374E+01 -6.797137E-04 5.523374E+01 -6.552512E-04 + 3.100008E+01 9.000000E+01 1 2.242310E-06 -9.004362E+01 -1.706840E-09 -2.242310E-06 + 3.100008E+01 9.000000E+01 2 4.589690E+01 8.993141E+01 5.494807E-02 4.589687E+01 + 3.100008E+01 9.000000E+01 3 1.903277E+02 2.618063E-01 1.903257E+02 8.696770E-01 + 3.100008E+01 9.000000E+01 4 1.504123E+02 8.993160E+01 1.795485E-01 1.504122E+02 + 3.100008E+01 9.000000E+01 5 1.033579E-04 -8.999184E+01 1.472793E-08 -1.033579E-04 + 3.100008E+01 9.000000E+01 6 4.742417E-06 1.799995E+02 -4.742417E-06 3.798223E-11 + 3.110008E+01 0.000000E+00 1 4.271725E+01 8.994002E+01 4.472252E-02 4.271722E+01 + 3.110008E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.110008E+01 0.000000E+00 3 1.878313E+02 2.584578E-01 1.878293E+02 8.472925E-01 + 3.110008E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.110008E+01 0.000000E+00 5 4.441506E+02 8.994002E+01 4.649782E-01 4.441503E+02 + 3.110008E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.110008E+01 3.000000E+01 1 3.710766E+01 8.994002E+01 3.884733E-02 3.710764E+01 + 3.110008E+01 3.000000E+01 2 2.264285E+01 8.993192E+01 2.690524E-02 2.264283E+01 + 3.110008E+01 3.000000E+01 3 1.884795E+02 2.588557E-01 1.884776E+02 8.515257E-01 + 3.110008E+01 3.000000E+01 4 7.353658E+01 8.993152E+01 8.789667E-02 7.353653E+01 + 3.110008E+01 3.000000E+01 5 3.858040E+02 8.994002E+01 4.038925E-01 3.858038E+02 + 3.110008E+01 3.000000E+01 6 5.448254E+01 -6.715673E-04 5.448254E+01 -6.385931E-04 + 3.110008E+01 6.000000E+01 1 2.155575E+01 8.994003E+01 2.256396E-02 2.155574E+01 + 3.110008E+01 6.000000E+01 2 3.948326E+01 8.993192E+01 4.691983E-02 3.948323E+01 + 3.110008E+01 6.000000E+01 3 1.897842E+02 2.596489E-01 1.897823E+02 8.600475E-01 + 3.110008E+01 6.000000E+01 4 1.289867E+02 8.993192E+01 1.532820E-01 1.289866E+02 + 3.110008E+01 6.000000E+01 5 2.240822E+02 8.994002E+01 2.345902E-01 2.240821E+02 + 3.110008E+01 6.000000E+01 6 5.486097E+01 -6.699933E-04 5.486097E+01 -6.415217E-04 + 3.110008E+01 9.000000E+01 1 2.234839E-06 -9.004337E+01 -1.691864E-09 -2.234839E-06 + 3.110008E+01 9.000000E+01 2 4.574520E+01 8.993192E+01 5.436330E-02 4.574517E+01 + 3.110008E+01 9.000000E+01 3 1.904401E+02 2.600465E-01 1.904381E+02 8.643413E-01 + 3.110008E+01 9.000000E+01 4 1.498793E+02 8.993211E+01 1.775985E-01 1.498792E+02 + 3.110008E+01 9.000000E+01 5 1.030330E-04 -8.999191E+01 1.454769E-08 -1.030330E-04 + 3.110008E+01 9.000000E+01 6 4.710264E-06 1.799996E+02 -4.710264E-06 3.718752E-11 + 3.120008E+01 0.000000E+00 1 4.258026E+01 8.994042E+01 4.427331E-02 4.258024E+01 + 3.120008E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.120008E+01 0.000000E+00 3 1.879590E+02 2.567396E-01 1.879572E+02 8.422326E-01 + 3.120008E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.120008E+01 0.000000E+00 5 4.429591E+02 8.994043E+01 4.605506E-01 4.429588E+02 + 3.120008E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.120008E+01 3.000000E+01 1 3.698774E+01 8.994043E+01 3.845636E-02 3.698772E+01 + 3.120008E+01 3.000000E+01 2 2.256986E+01 8.993242E+01 2.662198E-02 2.256985E+01 + 3.120008E+01 3.000000E+01 3 1.886033E+02 2.571312E-01 1.886014E+02 8.464085E-01 + 3.120008E+01 3.000000E+01 4 7.328609E+01 8.993202E+01 8.695251E-02 7.328603E+01 + 3.120008E+01 3.000000E+01 5 3.847628E+02 8.994043E+01 4.000409E-01 3.847626E+02 + 3.120008E+01 3.000000E+01 6 5.411873E+01 -6.619911E-04 5.411873E+01 -6.252836E-04 + 3.120008E+01 6.000000E+01 1 2.148526E+01 8.994044E+01 2.233585E-02 2.148524E+01 + 3.120008E+01 6.000000E+01 2 3.935412E+01 8.993241E+01 4.642364E-02 3.935410E+01 + 3.120008E+01 6.000000E+01 3 1.898994E+02 2.579163E-01 1.898975E+02 8.548273E-01 + 3.120008E+01 6.000000E+01 4 1.285365E+02 8.993241E+01 1.516277E-01 1.285364E+02 + 3.120008E+01 6.000000E+01 5 2.234675E+02 8.994043E+01 2.323439E-01 2.234673E+02 + 3.120008E+01 6.000000E+01 6 5.449213E+01 -6.604489E-04 5.449213E+01 -6.281313E-04 + 3.120008E+01 9.000000E+01 1 2.227424E-06 -9.004314E+01 -1.677062E-09 -2.227424E-06 + 3.120008E+01 9.000000E+01 2 4.559439E+01 8.993241E+01 5.378699E-02 4.559436E+01 + 3.120008E+01 9.000000E+01 3 1.905505E+02 2.583078E-01 1.905486E+02 8.590598E-01 + 3.120008E+01 9.000000E+01 4 1.493502E+02 8.993260E+01 1.756782E-01 1.493501E+02 + 3.120008E+01 9.000000E+01 5 1.027095E-04 -8.999198E+01 1.437044E-08 -1.027095E-04 + 3.120008E+01 9.000000E+01 6 4.678442E-06 1.799996E+02 -4.678442E-06 3.641232E-11 + 3.130008E+01 0.000000E+00 1 4.244415E+01 8.994083E+01 4.383010E-02 4.244413E+01 + 3.130008E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.130008E+01 0.000000E+00 3 1.880849E+02 2.550395E-01 1.880830E+02 8.372157E-01 + 3.130008E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.130008E+01 0.000000E+00 5 4.417768E+02 8.994083E+01 4.561822E-01 4.417766E+02 + 3.130008E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.130008E+01 3.000000E+01 1 3.686876E+01 8.994084E+01 3.807050E-02 3.686874E+01 + 3.130008E+01 3.000000E+01 2 2.249725E+01 8.993291E+01 2.634262E-02 2.249723E+01 + 3.130008E+01 3.000000E+01 3 1.887257E+02 2.554244E-01 1.887238E+02 8.413358E-01 + 3.130008E+01 3.000000E+01 4 7.303760E+01 8.993252E+01 8.602200E-02 7.303754E+01 + 3.130008E+01 3.000000E+01 5 3.837261E+02 8.994084E+01 3.962370E-01 3.837259E+02 + 3.130008E+01 3.000000E+01 6 5.375858E+01 -6.525866E-04 5.375858E+01 -6.122987E-04 + 3.130008E+01 6.000000E+01 1 2.141525E+01 8.994085E+01 2.211093E-02 2.141524E+01 + 3.130008E+01 6.000000E+01 2 3.922577E+01 8.993291E+01 4.593449E-02 3.922575E+01 + 3.130008E+01 6.000000E+01 3 1.900133E+02 2.561975E-01 1.900114E+02 8.496398E-01 + 3.130008E+01 6.000000E+01 4 1.280902E+02 8.993291E+01 1.499988E-01 1.280901E+02 + 3.130008E+01 6.000000E+01 5 2.228578E+02 8.994083E+01 2.301247E-01 2.228577E+02 + 3.130008E+01 6.000000E+01 6 5.412697E+01 -6.510770E-04 5.412697E+01 -6.150684E-04 + 3.130008E+01 9.000000E+01 1 2.220058E-06 -9.004291E+01 -1.662420E-09 -2.220057E-06 + 3.130008E+01 9.000000E+01 2 4.544458E+01 8.993291E+01 5.321904E-02 4.544455E+01 + 3.130008E+01 9.000000E+01 3 1.906605E+02 2.565849E-01 1.906586E+02 8.538228E-01 + 3.130008E+01 9.000000E+01 4 1.488255E+02 8.993310E+01 1.737858E-01 1.488254E+02 + 3.130008E+01 9.000000E+01 5 1.023886E-04 -8.999206E+01 1.419605E-08 -1.023886E-04 + 3.130008E+01 9.000000E+01 6 4.646949E-06 1.799996E+02 -4.646949E-06 3.565608E-11 + 3.140008E+01 0.000000E+00 1 4.230868E+01 8.994124E+01 4.339260E-02 4.230866E+01 + 3.140008E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.140008E+01 0.000000E+00 3 1.882101E+02 2.533561E-01 1.882083E+02 8.322434E-01 + 3.140008E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.140008E+01 0.000000E+00 5 4.405977E+02 8.994125E+01 4.518622E-01 4.405974E+02 + 3.140008E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.140008E+01 3.000000E+01 1 3.675054E+01 8.994125E+01 3.768987E-02 3.675052E+01 + 3.140008E+01 3.000000E+01 2 2.242517E+01 8.993340E+01 2.606731E-02 2.242516E+01 + 3.140008E+01 3.000000E+01 3 1.888465E+02 2.537359E-01 1.888446E+02 8.363090E-01 + 3.140008E+01 3.000000E+01 4 7.279086E+01 8.993301E+01 8.510463E-02 7.279081E+01 + 3.140008E+01 3.000000E+01 5 3.826943E+02 8.994125E+01 3.924760E-01 3.826941E+02 + 3.140008E+01 3.000000E+01 6 5.340209E+01 -6.433519E-04 5.340209E+01 -5.996312E-04 + 3.140008E+01 6.000000E+01 1 2.134567E+01 8.994125E+01 2.188901E-02 2.134566E+01 + 3.140008E+01 6.000000E+01 2 3.909828E+01 8.993340E+01 4.545228E-02 3.909825E+01 + 3.140008E+01 6.000000E+01 3 1.901261E+02 2.544982E-01 1.901242E+02 8.445050E-01 + 3.140008E+01 6.000000E+01 4 1.276465E+02 8.993340E+01 1.483917E-01 1.276465E+02 + 3.140008E+01 6.000000E+01 5 2.222494E+02 8.994124E+01 2.279338E-01 2.222492E+02 + 3.140008E+01 6.000000E+01 6 5.376556E+01 -6.418732E-04 5.376556E+01 -6.023248E-04 + 3.140008E+01 9.000000E+01 1 2.212740E-06 -9.004267E+01 -1.647934E-09 -2.212739E-06 + 3.140008E+01 9.000000E+01 2 4.529589E+01 8.993339E+01 5.265917E-02 4.529586E+01 + 3.140008E+01 9.000000E+01 3 1.907693E+02 2.548800E-01 1.907674E+02 8.486333E-01 + 3.140008E+01 9.000000E+01 4 1.483038E+02 8.993358E+01 1.719213E-01 1.483037E+02 + 3.140008E+01 9.000000E+01 5 1.020689E-04 -8.999213E+01 1.402449E-08 -1.020689E-04 + 3.140008E+01 9.000000E+01 6 4.615771E-06 1.799996E+02 -4.615771E-06 3.491831E-11 + 3.150008E+01 0.000000E+00 1 4.217438E+01 8.994164E+01 4.296125E-02 4.217436E+01 + 3.150008E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.150008E+01 0.000000E+00 3 1.883341E+02 2.516885E-01 1.883323E+02 8.273101E-01 + 3.150008E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.150008E+01 0.000000E+00 5 4.394270E+02 8.994164E+01 4.476003E-01 4.394268E+02 + 3.150008E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.150008E+01 3.000000E+01 1 3.663300E+01 8.994164E+01 3.731441E-02 3.663298E+01 + 3.150008E+01 3.000000E+01 2 2.235349E+01 8.993388E+01 2.579601E-02 2.235347E+01 + 3.150008E+01 3.000000E+01 3 1.889663E+02 2.520641E-01 1.889645E+02 8.313261E-01 + 3.150008E+01 3.000000E+01 4 7.254544E+01 8.993349E+01 8.420121E-02 7.254539E+01 + 3.150008E+01 3.000000E+01 5 3.816672E+02 8.994164E+01 3.887678E-01 3.816670E+02 + 3.150008E+01 3.000000E+01 6 5.304921E+01 -6.342840E-04 5.304921E+01 -5.872730E-04 + 3.150008E+01 6.000000E+01 1 2.127658E+01 8.994164E+01 2.167005E-02 2.127657E+01 + 3.150008E+01 6.000000E+01 2 3.897163E+01 8.993388E+01 4.497702E-02 3.897160E+01 + 3.150008E+01 6.000000E+01 3 1.902381E+02 2.528161E-01 1.902362E+02 8.394178E-01 + 3.150008E+01 6.000000E+01 4 1.272065E+02 8.993388E+01 1.468103E-01 1.272064E+02 + 3.150008E+01 6.000000E+01 5 2.216435E+02 8.994164E+01 2.257711E-01 2.216434E+02 + 3.150008E+01 6.000000E+01 6 5.340778E+01 -6.328357E-04 5.340778E+01 -5.898924E-04 + 3.150008E+01 9.000000E+01 1 2.205470E-06 -9.004244E+01 -1.633608E-09 -2.205469E-06 + 3.150008E+01 9.000000E+01 2 4.514809E+01 8.993388E+01 5.210731E-02 4.514806E+01 + 3.150008E+01 9.000000E+01 3 1.908779E+02 2.531905E-01 1.908760E+02 8.434882E-01 + 3.150008E+01 9.000000E+01 4 1.477864E+02 8.993406E+01 1.700838E-01 1.477863E+02 + 3.150008E+01 9.000000E+01 5 1.017515E-04 -8.999220E+01 1.385574E-08 -1.017515E-04 + 3.150008E+01 9.000000E+01 6 4.584919E-06 1.799996E+02 -4.584919E-06 3.419857E-11 + 3.160008E+01 0.000000E+00 1 4.204083E+01 8.994203E+01 4.253544E-02 4.204081E+01 + 3.160008E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.160008E+01 0.000000E+00 3 1.884562E+02 2.500386E-01 1.884544E+02 8.224198E-01 + 3.160008E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.160008E+01 0.000000E+00 5 4.382549E+02 8.994204E+01 4.433883E-01 4.382547E+02 + 3.160008E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.160008E+01 3.000000E+01 1 3.651622E+01 8.994204E+01 3.694400E-02 3.651620E+01 + 3.160008E+01 3.000000E+01 2 2.228225E+01 8.993436E+01 2.552840E-02 2.228224E+01 + 3.160008E+01 3.000000E+01 3 1.890855E+02 2.504062E-01 1.890837E+02 8.263793E-01 + 3.160008E+01 3.000000E+01 4 7.230212E+01 8.993398E+01 8.331058E-02 7.230207E+01 + 3.160008E+01 3.000000E+01 5 3.806456E+02 8.994204E+01 3.851067E-01 3.806454E+02 + 3.160008E+01 3.000000E+01 6 5.269993E+01 -6.253745E-04 5.269993E+01 -5.752115E-04 + 3.160008E+01 6.000000E+01 1 2.120787E+01 8.994204E+01 2.145409E-02 2.120786E+01 + 3.160008E+01 6.000000E+01 2 3.884573E+01 8.993435E+01 4.450839E-02 3.884570E+01 + 3.160008E+01 6.000000E+01 3 1.903499E+02 2.511452E-01 1.903480E+02 8.343601E-01 + 3.160008E+01 6.000000E+01 4 1.267692E+02 8.993435E+01 1.452493E-01 1.267691E+02 + 3.160008E+01 6.000000E+01 5 2.210407E+02 8.994204E+01 2.236348E-01 2.210406E+02 + 3.160008E+01 6.000000E+01 6 5.305369E+01 -6.239574E-04 5.305369E+01 -5.777606E-04 + 3.160008E+01 9.000000E+01 1 2.198246E-06 -9.004221E+01 -1.619432E-09 -2.198245E-06 + 3.160008E+01 9.000000E+01 2 4.500122E+01 8.993435E+01 5.156337E-02 4.500119E+01 + 3.160008E+01 9.000000E+01 3 1.909846E+02 2.515182E-01 1.909828E+02 8.383856E-01 + 3.160008E+01 9.000000E+01 4 1.472733E+02 8.993454E+01 1.682731E-01 1.472732E+02 + 3.160008E+01 9.000000E+01 5 1.014360E-04 -8.999227E+01 1.368970E-08 -1.014360E-04 + 3.160008E+01 9.000000E+01 6 4.554380E-06 1.799996E+02 -4.554380E-06 3.349617E-11 + 3.170008E+01 0.000000E+00 1 4.190809E+01 8.994243E+01 4.211542E-02 4.190807E+01 + 3.170008E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.170008E+01 0.000000E+00 3 1.885789E+02 2.484026E-01 1.885771E+02 8.175706E-01 + 3.170008E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.170008E+01 0.000000E+00 5 4.370938E+02 8.994243E+01 4.392354E-01 4.370936E+02 + 3.170008E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.170008E+01 3.000000E+01 1 3.640022E+01 8.994243E+01 3.657847E-02 3.640020E+01 + 3.170008E+01 3.000000E+01 2 2.221152E+01 8.993483E+01 2.526463E-02 2.221151E+01 + 3.170008E+01 3.000000E+01 3 1.892030E+02 2.487685E-01 1.892012E+02 8.214847E-01 + 3.170008E+01 3.000000E+01 4 7.206001E+01 8.993446E+01 8.243237E-02 7.205997E+01 + 3.170008E+01 3.000000E+01 5 3.796264E+02 8.994243E+01 3.814907E-01 3.796263E+02 + 3.170008E+01 3.000000E+01 6 5.235402E+01 -6.166263E-04 5.235402E+01 -5.634424E-04 + 3.170008E+01 6.000000E+01 1 2.113974E+01 8.994243E+01 2.124105E-02 2.113973E+01 + 3.170008E+01 6.000000E+01 2 3.872069E+01 8.993482E+01 4.404656E-02 3.872066E+01 + 3.170008E+01 6.000000E+01 3 1.904602E+02 2.494981E-01 1.904584E+02 8.293681E-01 + 3.170008E+01 6.000000E+01 4 1.263347E+02 8.993482E+01 1.437122E-01 1.263346E+02 + 3.170008E+01 6.000000E+01 5 2.204412E+02 8.994243E+01 2.215249E-01 2.204411E+02 + 3.170008E+01 6.000000E+01 6 5.270306E+01 -6.152387E-04 5.270306E+01 -5.659224E-04 + 3.170008E+01 9.000000E+01 1 2.191076E-06 -9.004198E+01 -1.605421E-09 -2.191076E-06 + 3.170008E+01 9.000000E+01 2 4.485546E+01 8.993482E+01 5.102707E-02 4.485543E+01 + 3.170008E+01 9.000000E+01 3 1.910912E+02 2.498643E-01 1.910894E+02 8.333375E-01 + 3.170008E+01 9.000000E+01 4 1.467623E+02 8.993501E+01 1.664887E-01 1.467622E+02 + 3.170008E+01 9.000000E+01 5 1.011228E-04 -8.999234E+01 1.352632E-08 -1.011228E-04 + 3.170008E+01 9.000000E+01 6 4.524147E-06 1.799996E+02 -4.524147E-06 3.281071E-11 + 3.180009E+01 0.000000E+00 1 4.177626E+01 8.994281E+01 4.170094E-02 4.177624E+01 + 3.180009E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.180009E+01 0.000000E+00 3 1.886985E+02 2.467859E-01 1.886967E+02 8.127648E-01 + 3.180009E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.180009E+01 0.000000E+00 5 4.359382E+02 8.994282E+01 4.351280E-01 4.359380E+02 + 3.180009E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.180009E+01 3.000000E+01 1 3.628497E+01 8.994282E+01 3.621782E-02 3.628495E+01 + 3.180009E+01 3.000000E+01 2 2.214123E+01 8.993530E+01 2.500446E-02 2.214121E+01 + 3.180009E+01 3.000000E+01 3 1.893201E+02 2.471441E-01 1.893183E+02 8.166255E-01 + 3.180009E+01 3.000000E+01 4 7.182027E+01 8.993493E+01 8.156680E-02 7.182023E+01 + 3.180009E+01 3.000000E+01 5 3.786160E+02 8.994282E+01 3.779165E-01 3.786158E+02 + 3.180009E+01 3.000000E+01 6 5.201163E+01 -6.080327E-04 5.201163E+01 -5.519564E-04 + 3.180009E+01 6.000000E+01 1 2.107197E+01 8.994282E+01 2.103077E-02 2.107196E+01 + 3.180009E+01 6.000000E+01 2 3.859646E+01 8.993529E+01 4.359111E-02 3.859644E+01 + 3.180009E+01 6.000000E+01 3 1.905677E+02 2.478663E-01 1.905659E+02 8.244089E-01 + 3.180009E+01 6.000000E+01 4 1.259037E+02 8.993529E+01 1.421973E-01 1.259036E+02 + 3.180009E+01 6.000000E+01 5 2.198459E+02 8.994281E+01 2.194431E-01 2.198458E+02 + 3.180009E+01 6.000000E+01 6 5.235597E+01 -6.066744E-04 5.235597E+01 -5.543694E-04 + 3.180009E+01 9.000000E+01 1 2.183949E-06 -9.004176E+01 -1.591557E-09 -2.183949E-06 + 3.180009E+01 9.000000E+01 2 4.471059E+01 8.993529E+01 5.049825E-02 4.471057E+01 + 3.180009E+01 9.000000E+01 3 1.911960E+02 2.482258E-01 1.911942E+02 8.283267E-01 + 3.180009E+01 9.000000E+01 4 1.462562E+02 8.993546E+01 1.647293E-01 1.462561E+02 + 3.180009E+01 9.000000E+01 5 1.008110E-04 -8.999240E+01 1.336559E-08 -1.008110E-04 + 3.180009E+01 9.000000E+01 6 4.494217E-06 1.799996E+02 -4.494217E-06 3.214170E-11 + 3.190009E+01 0.000000E+00 1 4.164527E+01 8.994319E+01 4.129188E-02 4.164525E+01 + 3.190009E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.190009E+01 0.000000E+00 3 1.888182E+02 2.451834E-01 1.888164E+02 8.079990E-01 + 3.190009E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.190009E+01 0.000000E+00 5 4.347829E+02 8.994320E+01 4.310761E-01 4.347827E+02 + 3.190009E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.190009E+01 3.000000E+01 1 3.617052E+01 8.994320E+01 3.586186E-02 3.617050E+01 + 3.190009E+01 3.000000E+01 2 2.207140E+01 8.993576E+01 2.474802E-02 2.207138E+01 + 3.190009E+01 3.000000E+01 3 1.894362E+02 2.455358E-01 1.894345E+02 8.118090E-01 + 3.190009E+01 3.000000E+01 4 7.158137E+01 8.993539E+01 8.071379E-02 7.158132E+01 + 3.190009E+01 3.000000E+01 5 3.776061E+02 8.994320E+01 3.743875E-01 3.776059E+02 + 3.190009E+01 3.000000E+01 6 5.167256E+01 -5.995906E-04 5.167256E+01 -5.407446E-04 + 3.190009E+01 6.000000E+01 1 2.100459E+01 8.994320E+01 2.082334E-02 2.100458E+01 + 3.190009E+01 6.000000E+01 2 3.847307E+01 8.993575E+01 4.314199E-02 3.847305E+01 + 3.190009E+01 6.000000E+01 3 1.906760E+02 2.462474E-01 1.906742E+02 8.194901E-01 + 3.190009E+01 6.000000E+01 4 1.254759E+02 8.993575E+01 1.407038E-01 1.254758E+02 + 3.190009E+01 6.000000E+01 5 2.192515E+02 8.994319E+01 2.173868E-01 2.192514E+02 + 3.190009E+01 6.000000E+01 6 5.201238E+01 -5.982598E-04 5.201238E+01 -5.430927E-04 + 3.190009E+01 9.000000E+01 1 2.176870E-06 -9.004153E+01 -1.577846E-09 -2.176870E-06 + 3.190009E+01 9.000000E+01 2 4.456656E+01 8.993575E+01 4.997700E-02 4.456654E+01 + 3.190009E+01 9.000000E+01 3 1.912997E+02 2.466044E-01 1.912979E+02 8.233623E-01 + 3.190009E+01 9.000000E+01 4 1.457529E+02 8.993593E+01 1.629959E-01 1.457528E+02 + 3.190009E+01 9.000000E+01 5 1.005013E-04 -8.999247E+01 1.320738E-08 -1.005013E-04 + 3.190009E+01 9.000000E+01 6 4.464596E-06 1.799996E+02 -4.464596E-06 3.148874E-11 + 3.200008E+01 0.000000E+00 1 4.151496E+01 8.994357E+01 4.088827E-02 4.151494E+01 + 3.200008E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.200008E+01 0.000000E+00 3 1.889369E+02 2.435945E-01 1.889352E+02 8.032676E-01 + 3.200008E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.200008E+01 0.000000E+00 5 4.336381E+02 8.994357E+01 4.270725E-01 4.336379E+02 + 3.200008E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.200008E+01 3.000000E+01 1 3.605668E+01 8.994357E+01 3.551064E-02 3.605666E+01 + 3.200008E+01 3.000000E+01 2 2.200198E+01 8.993621E+01 2.449506E-02 2.200197E+01 + 3.200008E+01 3.000000E+01 3 1.895500E+02 2.439445E-01 1.895483E+02 8.070324E-01 + 3.200008E+01 3.000000E+01 4 7.134460E+01 8.993585E+01 7.987279E-02 7.134456E+01 + 3.200008E+01 3.000000E+01 5 3.766031E+02 8.994357E+01 3.709035E-01 3.766029E+02 + 3.200008E+01 3.000000E+01 6 5.133684E+01 -5.912976E-04 5.133684E+01 -5.298008E-04 + 3.200008E+01 6.000000E+01 1 2.093769E+01 8.994358E+01 2.061860E-02 2.093768E+01 + 3.200008E+01 6.000000E+01 2 3.835047E+01 8.993621E+01 4.269923E-02 3.835044E+01 + 3.200008E+01 6.000000E+01 3 1.907836E+02 2.446454E-01 1.907819E+02 8.146182E-01 + 3.200008E+01 6.000000E+01 4 1.250506E+02 8.993621E+01 1.392321E-01 1.250505E+02 + 3.200008E+01 6.000000E+01 5 2.186613E+02 8.994357E+01 2.153551E-01 2.186612E+02 + 3.200008E+01 6.000000E+01 6 5.167227E+01 -5.899935E-04 5.167227E+01 -5.320864E-04 + 3.200008E+01 9.000000E+01 1 2.169839E-06 -9.004131E+01 -1.564281E-09 -2.169839E-06 + 3.200008E+01 9.000000E+01 2 4.442363E+01 8.993620E+01 4.946293E-02 4.442361E+01 + 3.200008E+01 9.000000E+01 3 1.914030E+02 2.449974E-01 1.914012E+02 8.184388E-01 + 3.200008E+01 9.000000E+01 4 1.452537E+02 8.993638E+01 1.612873E-01 1.452536E+02 + 3.200008E+01 9.000000E+01 5 1.001939E-04 -8.999254E+01 1.305173E-08 -1.001939E-04 + 3.200008E+01 9.000000E+01 6 4.435266E-06 1.799996E+02 -4.435266E-06 3.085144E-11 + 3.210008E+01 0.000000E+00 1 4.138552E+01 8.994395E+01 4.049001E-02 4.138551E+01 + 3.210008E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.210008E+01 0.000000E+00 3 1.890545E+02 2.420243E-01 1.890528E+02 7.985864E-01 + 3.210008E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.210008E+01 0.000000E+00 5 4.324951E+02 8.994395E+01 4.231172E-01 4.324949E+02 + 3.210008E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.210008E+01 3.000000E+01 1 3.594356E+01 8.994395E+01 3.516399E-02 3.594354E+01 + 3.210008E+01 3.000000E+01 2 2.193302E+01 8.993667E+01 2.424563E-02 2.193301E+01 + 3.210008E+01 3.000000E+01 3 1.896640E+02 2.423693E-01 1.896624E+02 8.023036E-01 + 3.210008E+01 3.000000E+01 4 7.110902E+01 8.993631E+01 7.904386E-02 7.110898E+01 + 3.210008E+01 3.000000E+01 5 3.756074E+02 8.994395E+01 3.674622E-01 3.756072E+02 + 3.210008E+01 3.000000E+01 6 5.100443E+01 -5.831493E-04 5.100443E+01 -5.191167E-04 + 3.210008E+01 6.000000E+01 1 2.087120E+01 8.994395E+01 2.041666E-02 2.087119E+01 + 3.210008E+01 6.000000E+01 2 3.822867E+01 8.993666E+01 4.226264E-02 3.822865E+01 + 3.210008E+01 6.000000E+01 3 1.908896E+02 2.430616E-01 1.908879E+02 8.097945E-01 + 3.210008E+01 6.000000E+01 4 1.246291E+02 8.993666E+01 1.377807E-01 1.246290E+02 + 3.210008E+01 6.000000E+01 5 2.180737E+02 8.994395E+01 2.133478E-01 2.180736E+02 + 3.210008E+01 6.000000E+01 6 5.133543E+01 -5.818719E-04 5.133543E+01 -5.213410E-04 + 3.210008E+01 9.000000E+01 1 2.162853E-06 -9.004108E+01 -1.550861E-09 -2.162853E-06 + 3.210008E+01 9.000000E+01 2 4.428160E+01 8.993665E+01 4.895616E-02 4.428158E+01 + 3.210008E+01 9.000000E+01 3 1.915062E+02 2.434063E-01 1.915045E+02 8.135623E-01 + 3.210008E+01 9.000000E+01 4 1.447575E+02 8.993683E+01 1.596025E-01 1.447574E+02 + 3.210008E+01 9.000000E+01 5 9.988794E-05 -8.999260E+01 1.289854E-08 -9.988794E-05 + 3.210008E+01 9.000000E+01 6 4.406237E-06 1.799996E+02 -4.406237E-06 3.022927E-11 + 3.220008E+01 0.000000E+00 1 4.125680E+01 8.994432E+01 4.009678E-02 4.125678E+01 + 3.220008E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.220008E+01 0.000000E+00 3 1.891709E+02 2.404694E-01 1.891692E+02 7.939445E-01 + 3.220008E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.220008E+01 0.000000E+00 5 4.313605E+02 8.994432E+01 4.192114E-01 4.313603E+02 + 3.220008E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.220008E+01 3.000000E+01 1 3.583120E+01 8.994432E+01 3.482202E-02 3.583118E+01 + 3.220008E+01 3.000000E+01 2 2.186450E+01 8.993711E+01 2.399961E-02 2.186448E+01 + 3.220008E+01 3.000000E+01 3 1.897765E+02 2.408099E-01 1.897748E+02 7.976139E-01 + 3.220008E+01 3.000000E+01 4 7.087527E+01 8.993676E+01 7.822643E-02 7.087522E+01 + 3.220008E+01 3.000000E+01 5 3.746130E+02 8.994432E+01 3.640628E-01 3.746128E+02 + 3.220008E+01 3.000000E+01 6 5.067528E+01 -5.751448E-04 5.067528E+01 -5.086872E-04 + 3.220008E+01 6.000000E+01 1 2.080516E+01 8.994432E+01 2.021730E-02 2.080515E+01 + 3.220008E+01 6.000000E+01 2 3.810759E+01 8.993710E+01 4.183198E-02 3.810756E+01 + 3.220008E+01 6.000000E+01 3 1.909952E+02 2.414915E-01 1.909935E+02 8.050085E-01 + 3.220008E+01 6.000000E+01 4 1.242095E+02 8.993710E+01 1.363501E-01 1.242094E+02 + 3.220008E+01 6.000000E+01 5 2.174872E+02 8.994432E+01 2.113664E-01 2.174871E+02 + 3.220008E+01 6.000000E+01 6 5.100198E+01 -5.738919E-04 5.100198E+01 -5.108513E-04 + 3.220008E+01 9.000000E+01 1 2.155913E-06 -9.004086E+01 -1.537593E-09 -2.155913E-06 + 3.220008E+01 9.000000E+01 2 4.414053E+01 8.993710E+01 4.845633E-02 4.414050E+01 + 3.220008E+01 9.000000E+01 3 1.916070E+02 2.418338E-01 1.916053E+02 8.087315E-01 + 3.220008E+01 9.000000E+01 4 1.442664E+02 8.993728E+01 1.579417E-01 1.442663E+02 + 3.220008E+01 9.000000E+01 5 9.958397E-05 -8.999267E+01 1.274775E-08 -9.958397E-05 + 3.220008E+01 9.000000E+01 6 4.377488E-06 1.799996E+02 -4.377488E-06 2.962181E-11 + 3.230008E+01 0.000000E+00 1 4.112895E+01 8.994469E+01 3.970887E-02 4.112893E+01 + 3.230008E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.230008E+01 0.000000E+00 3 1.892857E+02 2.389284E-01 1.892840E+02 7.893355E-01 + 3.230008E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.230008E+01 0.000000E+00 5 4.302268E+02 8.994469E+01 4.153519E-01 4.302266E+02 + 3.230008E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.230008E+01 3.000000E+01 1 3.571948E+01 8.994469E+01 3.448439E-02 3.571946E+01 + 3.230008E+01 3.000000E+01 2 2.179637E+01 8.993755E+01 2.375698E-02 2.179636E+01 + 3.230008E+01 3.000000E+01 3 1.898883E+02 2.392633E-01 1.898867E+02 7.929583E-01 + 3.230008E+01 3.000000E+01 4 7.064333E+01 8.993721E+01 7.742055E-02 7.064329E+01 + 3.230008E+01 3.000000E+01 5 3.736209E+02 8.994469E+01 3.607068E-01 3.736207E+02 + 3.230008E+01 3.000000E+01 6 5.034934E+01 -5.672779E-04 5.034934E+01 -4.985021E-04 + 3.230008E+01 6.000000E+01 1 2.073949E+01 8.994469E+01 2.002059E-02 2.073948E+01 + 3.230008E+01 6.000000E+01 2 3.798725E+01 8.993755E+01 4.140727E-02 3.798723E+01 + 3.230008E+01 6.000000E+01 3 1.910985E+02 2.399381E-01 1.910968E+02 8.002629E-01 + 3.230008E+01 6.000000E+01 4 1.237939E+02 8.993755E+01 1.349392E-01 1.237938E+02 + 3.230008E+01 6.000000E+01 5 2.169046E+02 8.994469E+01 2.094097E-01 2.169044E+02 + 3.230008E+01 6.000000E+01 6 5.067178E+01 -5.660514E-04 5.067178E+01 -5.006098E-04 + 3.230008E+01 9.000000E+01 1 2.149018E-06 -9.004064E+01 -1.524460E-09 -2.149018E-06 + 3.230008E+01 9.000000E+01 2 4.400010E+01 8.993754E+01 4.796338E-02 4.400007E+01 + 3.230008E+01 9.000000E+01 3 1.917073E+02 2.402732E-01 1.917056E+02 8.039336E-01 + 3.230008E+01 9.000000E+01 4 1.437770E+02 8.993771E+01 1.563048E-01 1.437769E+02 + 3.230008E+01 9.000000E+01 5 9.928187E-05 -8.999273E+01 1.259932E-08 -9.928187E-05 + 3.230008E+01 9.000000E+01 6 4.349024E-06 1.799996E+02 -4.349024E-06 2.902866E-11 + 3.240008E+01 0.000000E+00 1 4.100199E+01 8.994505E+01 3.932587E-02 4.100197E+01 + 3.240008E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.240008E+01 0.000000E+00 3 1.894001E+02 2.374020E-01 1.893985E+02 7.847670E-01 + 3.240008E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.240008E+01 0.000000E+00 5 4.291011E+02 8.994505E+01 4.115402E-01 4.291009E+02 + 3.240008E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.240008E+01 3.000000E+01 1 3.560848E+01 8.994505E+01 3.415127E-02 3.560846E+01 + 3.240008E+01 3.000000E+01 2 2.172871E+01 8.993799E+01 2.351772E-02 2.172870E+01 + 3.240008E+01 3.000000E+01 3 1.899988E+02 2.377335E-01 1.899972E+02 7.883469E-01 + 3.240008E+01 3.000000E+01 4 7.041291E+01 8.993765E+01 7.662544E-02 7.041287E+01 + 3.240008E+01 3.000000E+01 5 3.726361E+02 8.994505E+01 3.573909E-01 3.726360E+02 + 3.240008E+01 3.000000E+01 6 5.002665E+01 -5.595473E-04 5.002665E+01 -4.885573E-04 + 3.240008E+01 6.000000E+01 1 2.067430E+01 8.994505E+01 1.982643E-02 2.067429E+01 + 3.240008E+01 6.000000E+01 2 3.786776E+01 8.993799E+01 4.098853E-02 3.786774E+01 + 3.240008E+01 6.000000E+01 3 1.912020E+02 2.383991E-01 1.912004E+02 7.955605E-01 + 3.240008E+01 6.000000E+01 4 1.233801E+02 8.993799E+01 1.335490E-01 1.233801E+02 + 3.240008E+01 6.000000E+01 5 2.163262E+02 8.994505E+01 2.074770E-01 2.163261E+02 + 3.240008E+01 6.000000E+01 6 5.034487E+01 -5.583456E-04 5.034487E+01 -4.906092E-04 + 3.240008E+01 9.000000E+01 1 2.142163E-06 -9.004043E+01 -1.511472E-09 -2.142163E-06 + 3.240008E+01 9.000000E+01 2 4.386096E+01 8.993798E+01 4.747720E-02 4.386093E+01 + 3.240008E+01 9.000000E+01 3 1.918069E+02 2.387314E-01 1.918052E+02 7.991897E-01 + 3.240008E+01 9.000000E+01 4 1.432912E+02 8.993815E+01 1.546903E-01 1.432911E+02 + 3.240008E+01 9.000000E+01 5 9.898109E-05 -8.999279E+01 1.245321E-08 -9.898109E-05 + 3.240008E+01 9.000000E+01 6 4.320847E-06 1.799996E+02 -4.320847E-06 2.844953E-11 + 3.250008E+01 0.000000E+00 1 4.087568E+01 8.994541E+01 3.894788E-02 4.087566E+01 + 3.250008E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.250008E+01 0.000000E+00 3 1.895135E+02 2.358895E-01 1.895119E+02 7.802342E-01 + 3.250008E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.250008E+01 0.000000E+00 5 4.279817E+02 8.994541E+01 4.077779E-01 4.279815E+02 + 3.250008E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.250008E+01 3.000000E+01 1 3.549810E+01 8.994541E+01 3.382239E-02 3.549809E+01 + 3.250008E+01 3.000000E+01 2 2.166137E+01 8.993842E+01 2.328165E-02 2.166136E+01 + 3.250008E+01 3.000000E+01 3 1.901080E+02 2.362162E-01 1.901064E+02 7.837657E-01 + 3.250008E+01 3.000000E+01 4 7.018360E+01 8.993809E+01 7.584215E-02 7.018356E+01 + 3.250008E+01 3.000000E+01 5 3.716557E+02 8.994541E+01 3.541102E-01 3.716555E+02 + 3.250008E+01 3.000000E+01 6 4.970701E+01 -5.519501E-04 4.970701E+01 -4.788449E-04 + 3.250008E+01 6.000000E+01 1 2.060950E+01 8.994542E+01 1.963478E-02 2.060949E+01 + 3.250008E+01 6.000000E+01 2 3.774897E+01 8.993842E+01 4.057537E-02 3.774894E+01 + 3.250008E+01 6.000000E+01 3 1.913042E+02 2.368745E-01 1.913026E+02 7.908953E-01 + 3.250008E+01 6.000000E+01 4 1.229697E+02 8.993842E+01 1.321773E-01 1.229697E+02 + 3.250008E+01 6.000000E+01 5 2.157487E+02 8.994541E+01 2.055700E-01 2.157487E+02 + 3.250008E+01 6.000000E+01 6 5.002107E+01 -5.507733E-04 5.002107E+01 -4.808429E-04 + 3.250008E+01 9.000000E+01 1 2.135361E-06 -9.004021E+01 -1.498625E-09 -2.135360E-06 + 3.250008E+01 9.000000E+01 2 4.372243E+01 8.993842E+01 4.699778E-02 4.372240E+01 + 3.250008E+01 9.000000E+01 3 1.919054E+02 2.372008E-01 1.919038E+02 7.944735E-01 + 3.250008E+01 9.000000E+01 4 1.428095E+02 8.993858E+01 1.530993E-01 1.428094E+02 + 3.250008E+01 9.000000E+01 5 9.868251E-05 -8.999285E+01 1.230938E-08 -9.868251E-05 + 3.250008E+01 9.000000E+01 6 4.292944E-06 1.799996E+02 -4.292944E-06 2.788391E-11 + 3.260007E+01 0.000000E+00 1 4.075017E+01 8.994576E+01 3.857466E-02 4.075015E+01 + 3.260007E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.260007E+01 0.000000E+00 3 1.896254E+02 2.343947E-01 1.896239E+02 7.757479E-01 + 3.260007E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.260007E+01 0.000000E+00 5 4.268635E+02 8.994576E+01 4.040548E-01 4.268633E+02 + 3.260007E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.260007E+01 3.000000E+01 1 3.538857E+01 8.994576E+01 3.349778E-02 3.538855E+01 + 3.260007E+01 3.000000E+01 2 2.159455E+01 8.993884E+01 2.304880E-02 2.159454E+01 + 3.260007E+01 3.000000E+01 3 1.902169E+02 2.347176E-01 1.902153E+02 7.792391E-01 + 3.260007E+01 3.000000E+01 4 6.995581E+01 8.993851E+01 7.506908E-02 6.995577E+01 + 3.260007E+01 3.000000E+01 5 3.706799E+02 8.994576E+01 3.508785E-01 3.706798E+02 + 3.260007E+01 3.000000E+01 6 4.939045E+01 -5.444839E-04 4.939045E+01 -4.693592E-04 + 3.260007E+01 6.000000E+01 1 2.054506E+01 8.994577E+01 1.944564E-02 2.054505E+01 + 3.260007E+01 6.000000E+01 2 3.763100E+01 8.993884E+01 4.016798E-02 3.763098E+01 + 3.260007E+01 6.000000E+01 3 1.914061E+02 2.353635E-01 1.914045E+02 7.862688E-01 + 3.260007E+01 6.000000E+01 4 1.225619E+02 8.993884E+01 1.308252E-01 1.225618E+02 + 3.260007E+01 6.000000E+01 5 2.151736E+02 8.994576E+01 2.036822E-01 2.151735E+02 + 3.260007E+01 6.000000E+01 6 4.970055E+01 -5.433299E-04 4.970055E+01 -4.713051E-04 + 3.260007E+01 9.000000E+01 1 2.128597E-06 -9.003999E+01 -1.485917E-09 -2.128596E-06 + 3.260007E+01 9.000000E+01 2 4.358488E+01 8.993884E+01 4.652485E-02 4.358485E+01 + 3.260007E+01 9.000000E+01 3 1.920032E+02 2.356875E-01 1.920016E+02 7.898074E-01 + 3.260007E+01 9.000000E+01 4 1.423310E+02 8.993900E+01 1.515296E-01 1.423309E+02 + 3.260007E+01 9.000000E+01 5 9.838604E-05 -8.999291E+01 1.216779E-08 -9.838604E-05 + 3.260007E+01 9.000000E+01 6 4.265306E-06 1.799996E+02 -4.265306E-06 2.733150E-11 + 3.270007E+01 0.000000E+00 1 4.062551E+01 8.994612E+01 3.820643E-02 4.062550E+01 + 3.270007E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.270007E+01 0.000000E+00 3 1.897361E+02 2.329117E-01 1.897345E+02 7.712896E-01 + 3.270007E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.270007E+01 0.000000E+00 5 4.257521E+02 8.994612E+01 4.003795E-01 4.257519E+02 + 3.270007E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.270007E+01 3.000000E+01 1 3.527961E+01 8.994612E+01 3.317728E-02 3.527960E+01 + 3.270007E+01 3.000000E+01 2 2.152806E+01 8.993927E+01 2.281912E-02 2.152805E+01 + 3.270007E+01 3.000000E+01 3 1.903243E+02 2.332301E-01 1.903228E+02 7.747384E-01 + 3.270007E+01 3.000000E+01 4 6.972990E+01 8.993894E+01 7.430685E-02 6.972986E+01 + 3.270007E+01 3.000000E+01 5 3.697094E+02 8.994612E+01 3.476809E-01 3.697092E+02 + 3.270007E+01 3.000000E+01 6 4.907703E+01 -5.371456E-04 4.907703E+01 -4.600952E-04 + 3.270007E+01 6.000000E+01 1 2.048114E+01 8.994613E+01 1.925889E-02 2.048113E+01 + 3.270007E+01 6.000000E+01 2 3.751371E+01 8.993926E+01 3.976609E-02 3.751369E+01 + 3.270007E+01 6.000000E+01 3 1.915064E+02 2.338690E-01 1.915048E+02 7.816854E-01 + 3.270007E+01 6.000000E+01 4 1.221573E+02 8.993926E+01 1.294923E-01 1.221572E+02 + 3.270007E+01 6.000000E+01 5 2.146027E+02 8.994612E+01 2.018178E-01 2.146026E+02 + 3.270007E+01 6.000000E+01 6 4.938311E+01 -5.360143E-04 4.938311E+01 -4.619896E-04 + 3.270007E+01 9.000000E+01 1 2.121884E-06 -9.003978E+01 -1.473344E-09 -2.121883E-06 + 3.270007E+01 9.000000E+01 2 4.344816E+01 8.993926E+01 4.605846E-02 4.344814E+01 + 3.270007E+01 9.000000E+01 3 1.921006E+02 2.341865E-01 1.920990E+02 7.851754E-01 + 3.270007E+01 9.000000E+01 4 1.418556E+02 8.993942E+01 1.499822E-01 1.418555E+02 + 3.270007E+01 9.000000E+01 5 9.809092E-05 -8.999297E+01 1.202839E-08 -9.809092E-05 + 3.270007E+01 9.000000E+01 6 4.237947E-06 1.799996E+02 -4.237947E-06 2.679195E-11 + 3.280007E+01 0.000000E+00 1 4.050157E+01 8.994647E+01 3.784274E-02 4.050155E+01 + 3.280007E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.280007E+01 0.000000E+00 3 1.898468E+02 2.314430E-01 1.898453E+02 7.668732E-01 + 3.280007E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.280007E+01 0.000000E+00 5 4.246447E+02 8.994647E+01 3.967502E-01 4.246445E+02 + 3.280007E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.280007E+01 3.000000E+01 1 3.517133E+01 8.994647E+01 3.286090E-02 3.517131E+01 + 3.280007E+01 3.000000E+01 2 2.146205E+01 8.993969E+01 2.259255E-02 2.146204E+01 + 3.280007E+01 3.000000E+01 3 1.904306E+02 2.317582E-01 1.904290E+02 7.702790E-01 + 3.280007E+01 3.000000E+01 4 6.950526E+01 8.993936E+01 7.355542E-02 6.950522E+01 + 3.280007E+01 3.000000E+01 5 3.687395E+02 8.994647E+01 3.445204E-01 3.687393E+02 + 3.280007E+01 3.000000E+01 6 4.876656E+01 -5.299335E-04 4.876656E+01 -4.510460E-04 + 3.280007E+01 6.000000E+01 1 2.041751E+01 8.994647E+01 1.907471E-02 2.041751E+01 + 3.280007E+01 6.000000E+01 2 3.739711E+01 8.993969E+01 3.936956E-02 3.739709E+01 + 3.280007E+01 6.000000E+01 3 1.916055E+02 2.323883E-01 1.916039E+02 7.771385E-01 + 3.280007E+01 6.000000E+01 4 1.217550E+02 8.993969E+01 1.281774E-01 1.217549E+02 + 3.280007E+01 6.000000E+01 5 2.140330E+02 8.994647E+01 1.999796E-01 2.140329E+02 + 3.280007E+01 6.000000E+01 6 4.906877E+01 -5.288246E-04 4.906877E+01 -4.528915E-04 + 3.280007E+01 9.000000E+01 1 2.115198E-06 -9.003957E+01 -1.460903E-09 -2.115197E-06 + 3.280007E+01 9.000000E+01 2 4.331230E+01 8.993968E+01 4.559829E-02 4.331228E+01 + 3.280007E+01 9.000000E+01 3 1.921956E+02 2.327027E-01 1.921940E+02 7.805864E-01 + 3.280007E+01 9.000000E+01 4 1.413835E+02 8.993983E+01 1.484559E-01 1.413834E+02 + 3.280007E+01 9.000000E+01 5 9.779726E-05 -8.999303E+01 1.189116E-08 -9.779726E-05 + 3.280007E+01 9.000000E+01 6 4.210858E-06 1.799996E+02 -4.210858E-06 2.626491E-11 + 3.290007E+01 0.000000E+00 1 4.037837E+01 8.994681E+01 3.748371E-02 4.037835E+01 + 3.290007E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.290007E+01 0.000000E+00 3 1.899555E+02 2.299896E-01 1.899539E+02 7.624938E-01 + 3.290007E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.290007E+01 0.000000E+00 5 4.235428E+02 8.994682E+01 3.931653E-01 4.235426E+02 + 3.290007E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.290007E+01 3.000000E+01 1 3.506364E+01 8.994682E+01 3.254865E-02 3.506363E+01 + 3.290007E+01 3.000000E+01 2 2.139643E+01 8.994010E+01 2.236903E-02 2.139642E+01 + 3.290007E+01 3.000000E+01 3 1.905367E+02 2.302989E-01 1.905351E+02 7.658550E-01 + 3.290007E+01 3.000000E+01 4 6.928204E+01 8.993978E+01 7.281420E-02 6.928200E+01 + 3.290007E+01 3.000000E+01 5 3.677775E+02 8.994682E+01 3.413959E-01 3.677773E+02 + 3.290007E+01 3.000000E+01 6 4.845910E+01 -5.228421E-04 4.845910E+01 -4.422046E-04 + 3.290007E+01 6.000000E+01 1 2.035437E+01 8.994682E+01 1.889274E-02 2.035436E+01 + 3.290007E+01 6.000000E+01 2 3.728128E+01 8.994009E+01 3.897846E-02 3.728126E+01 + 3.290007E+01 6.000000E+01 3 1.917040E+02 2.309203E-01 1.917024E+02 7.726262E-01 + 3.290007E+01 6.000000E+01 4 1.213558E+02 8.994009E+01 1.268805E-01 1.213557E+02 + 3.290007E+01 6.000000E+01 5 2.134662E+02 8.994681E+01 1.981611E-01 2.134661E+02 + 3.290007E+01 6.000000E+01 6 4.875742E+01 -5.217555E-04 4.875742E+01 -4.440022E-04 + 3.290007E+01 9.000000E+01 1 2.108570E-06 -9.003937E+01 -1.448598E-09 -2.108569E-06 + 3.290007E+01 9.000000E+01 2 4.317736E+01 8.994009E+01 4.514453E-02 4.317733E+01 + 3.290007E+01 9.000000E+01 3 1.922909E+02 2.312311E-01 1.922893E+02 7.760345E-01 + 3.290007E+01 9.000000E+01 4 1.409151E+02 8.994025E+01 1.469510E-01 1.409151E+02 + 3.290007E+01 9.000000E+01 5 9.750568E-05 -8.999309E+01 1.175602E-08 -9.750568E-05 + 3.290007E+01 9.000000E+01 6 4.184036E-06 1.799996E+02 -4.184036E-06 2.575009E-11 + 3.300007E+01 0.000000E+00 1 4.025585E+01 8.994716E+01 3.712926E-02 4.025583E+01 + 3.300007E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.300007E+01 0.000000E+00 3 1.900640E+02 2.285481E-01 1.900625E+02 7.581477E-01 + 3.300007E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.300007E+01 0.000000E+00 5 4.224463E+02 8.994716E+01 3.896166E-01 4.224461E+02 + 3.300007E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.300007E+01 3.000000E+01 1 3.495679E+01 8.994716E+01 3.224034E-02 3.495678E+01 + 3.300007E+01 3.000000E+01 2 2.133117E+01 8.994051E+01 2.214840E-02 2.133116E+01 + 3.300007E+01 3.000000E+01 3 1.906416E+02 2.288531E-01 1.906401E+02 7.614663E-01 + 3.300007E+01 3.000000E+01 4 6.906031E+01 8.994020E+01 7.208294E-02 6.906027E+01 + 3.300007E+01 3.000000E+01 5 3.668197E+02 8.994716E+01 3.383159E-01 3.668195E+02 + 3.300007E+01 3.000000E+01 6 4.815453E+01 -5.158705E-04 4.815453E+01 -4.335660E-04 + 3.300007E+01 6.000000E+01 1 2.029157E+01 8.994717E+01 1.871317E-02 2.029156E+01 + 3.300007E+01 6.000000E+01 2 3.716633E+01 8.994051E+01 3.859261E-02 3.716631E+01 + 3.300007E+01 6.000000E+01 3 1.918021E+02 2.294670E-01 1.918006E+02 7.681569E-01 + 3.300007E+01 6.000000E+01 4 1.209585E+02 8.994051E+01 1.256014E-01 1.209585E+02 + 3.300007E+01 6.000000E+01 5 2.129026E+02 8.994716E+01 1.963649E-01 2.129025E+02 + 3.300007E+01 6.000000E+01 6 4.844903E+01 -5.148064E-04 4.844903E+01 -4.353177E-04 + 3.300007E+01 9.000000E+01 1 2.101973E-06 -9.003915E+01 -1.436424E-09 -2.101973E-06 + 3.300007E+01 9.000000E+01 2 4.304322E+01 8.994051E+01 4.469663E-02 4.304320E+01 + 3.300007E+01 9.000000E+01 3 1.923854E+02 2.297733E-01 1.923839E+02 7.715214E-01 + 3.300007E+01 9.000000E+01 4 1.404492E+02 8.994066E+01 1.454666E-01 1.404491E+02 + 3.300007E+01 9.000000E+01 5 9.721555E-05 -8.999316E+01 1.162294E-08 -9.721555E-05 + 3.300007E+01 9.000000E+01 6 4.157459E-06 1.799996E+02 -4.157459E-06 2.524701E-11 + 3.310007E+01 0.000000E+00 1 4.013415E+01 8.994749E+01 3.677930E-02 4.013413E+01 + 3.310007E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.310007E+01 0.000000E+00 3 1.901713E+02 2.271214E-01 1.901698E+02 7.538400E-01 + 3.310007E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.310007E+01 0.000000E+00 5 4.213561E+02 8.994750E+01 3.861173E-01 4.213559E+02 + 3.310007E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.310007E+01 3.000000E+01 1 3.485051E+01 8.994750E+01 3.193597E-02 3.485050E+01 + 3.310007E+01 3.000000E+01 2 2.126639E+01 8.994092E+01 2.193080E-02 2.126638E+01 + 3.310007E+01 3.000000E+01 3 1.907446E+02 2.274259E-01 1.907431E+02 7.571262E-01 + 3.310007E+01 3.000000E+01 4 6.884032E+01 8.994061E+01 7.136160E-02 6.884028E+01 + 3.310007E+01 3.000000E+01 5 3.658636E+02 8.994749E+01 3.352709E-01 3.658634E+02 + 3.310007E+01 3.000000E+01 6 4.785292E+01 -5.090184E-04 4.785292E+01 -4.251276E-04 + 3.310007E+01 6.000000E+01 1 2.022916E+01 8.994750E+01 1.853587E-02 2.022915E+01 + 3.310007E+01 6.000000E+01 2 3.705191E+01 8.994091E+01 3.821192E-02 3.705189E+01 + 3.310007E+01 6.000000E+01 3 1.918990E+02 2.280288E-01 1.918974E+02 7.637275E-01 + 3.310007E+01 6.000000E+01 4 1.205647E+02 8.994091E+01 1.243399E-01 1.205647E+02 + 3.310007E+01 6.000000E+01 5 2.123428E+02 8.994749E+01 1.945905E-01 2.123427E+02 + 3.310007E+01 6.000000E+01 6 4.814366E+01 -5.079747E-04 4.814366E+01 -4.268336E-04 + 3.310007E+01 9.000000E+01 1 2.095427E-06 -9.003895E+01 -1.424380E-09 -2.095426E-06 + 3.310007E+01 9.000000E+01 2 4.290991E+01 8.994091E+01 4.425495E-02 4.290989E+01 + 3.310007E+01 9.000000E+01 3 1.924789E+02 2.283318E-01 1.924774E+02 7.670537E-01 + 3.310007E+01 9.000000E+01 4 1.399865E+02 8.994106E+01 1.440035E-01 1.399864E+02 + 3.310007E+01 9.000000E+01 5 9.692730E-05 -8.999321E+01 1.149185E-08 -9.692730E-05 + 3.310007E+01 9.000000E+01 6 4.131145E-06 1.799996E+02 -4.131145E-06 2.475558E-11 + 3.320007E+01 0.000000E+00 1 4.001321E+01 8.994783E+01 3.643377E-02 4.001320E+01 + 3.320007E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.320007E+01 0.000000E+00 3 1.902766E+02 2.257106E-01 1.902751E+02 7.495722E-01 + 3.320007E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.320007E+01 0.000000E+00 5 4.202658E+02 8.994784E+01 3.826576E-01 4.202656E+02 + 3.320007E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.320007E+01 3.000000E+01 1 3.474481E+01 8.994784E+01 3.163544E-02 3.474479E+01 + 3.320007E+01 3.000000E+01 2 2.120192E+01 8.994132E+01 2.171606E-02 2.120191E+01 + 3.320007E+01 3.000000E+01 3 1.908476E+02 2.260078E-01 1.908461E+02 7.528118E-01 + 3.320007E+01 3.000000E+01 4 6.862160E+01 8.994101E+01 7.065042E-02 6.862156E+01 + 3.320007E+01 3.000000E+01 5 3.649148E+02 8.994784E+01 3.322608E-01 3.649147E+02 + 3.320007E+01 3.000000E+01 6 4.755409E+01 -5.022815E-04 4.755409E+01 -4.168813E-04 + 3.320007E+01 6.000000E+01 1 2.016714E+01 8.994784E+01 1.836078E-02 2.016713E+01 + 3.320007E+01 6.000000E+01 2 3.693820E+01 8.994131E+01 3.783626E-02 3.693818E+01 + 3.320007E+01 6.000000E+01 3 1.919947E+02 2.266037E-01 1.919932E+02 7.593333E-01 + 3.320007E+01 6.000000E+01 4 1.201731E+02 8.994131E+01 1.230952E-01 1.201731E+02 + 3.320007E+01 6.000000E+01 5 2.117833E+02 8.994784E+01 1.928348E-01 2.117832E+02 + 3.320007E+01 6.000000E+01 6 4.784115E+01 -5.012579E-04 4.784115E+01 -4.185432E-04 + 3.320007E+01 9.000000E+01 1 2.088918E-06 -9.003874E+01 -1.412462E-09 -2.088917E-06 + 3.320007E+01 9.000000E+01 2 4.277749E+01 8.994131E+01 4.381904E-02 4.277747E+01 + 3.320007E+01 9.000000E+01 3 1.925713E+02 2.269027E-01 1.925698E+02 7.626185E-01 + 3.320007E+01 9.000000E+01 4 1.395276E+02 8.994146E+01 1.425587E-01 1.395276E+02 + 3.320007E+01 9.000000E+01 5 9.664099E-05 -8.999326E+01 1.136279E-08 -9.664099E-05 + 3.320007E+01 9.000000E+01 6 4.105087E-06 1.799997E+02 -4.105087E-06 2.427533E-11 + 3.330006E+01 0.000000E+00 1 3.989290E+01 8.994817E+01 3.609265E-02 3.989289E+01 + 3.330006E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.330006E+01 0.000000E+00 3 1.903828E+02 2.243082E-01 1.903813E+02 7.453308E-01 + 3.330006E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.330006E+01 0.000000E+00 5 4.191859E+02 8.994817E+01 3.792374E-01 4.191858E+02 + 3.330006E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.330006E+01 3.000000E+01 1 3.463985E+01 8.994817E+01 3.133862E-02 3.463984E+01 + 3.330006E+01 3.000000E+01 2 2.113789E+01 8.994171E+01 2.150420E-02 2.113788E+01 + 3.330006E+01 3.000000E+01 3 1.909505E+02 2.246025E-01 1.909490E+02 7.485340E-01 + 3.330006E+01 3.000000E+01 4 6.840399E+01 8.994141E+01 6.994873E-02 6.840395E+01 + 3.330006E+01 3.000000E+01 5 3.639682E+02 8.994817E+01 3.292862E-01 3.639681E+02 + 3.330006E+01 3.000000E+01 6 4.725818E+01 -4.956563E-04 4.725818E+01 -4.088227E-04 + 3.330006E+01 6.000000E+01 1 2.010546E+01 8.994817E+01 1.818799E-02 2.010545E+01 + 3.330006E+01 6.000000E+01 2 3.682528E+01 8.994171E+01 3.746574E-02 3.682526E+01 + 3.330006E+01 6.000000E+01 3 1.920908E+02 2.251912E-01 1.920893E+02 7.549779E-01 + 3.330006E+01 6.000000E+01 4 1.197841E+02 8.994171E+01 1.218680E-01 1.197840E+02 + 3.330006E+01 6.000000E+01 5 2.112272E+02 8.994817E+01 1.911036E-01 2.112271E+02 + 3.330006E+01 6.000000E+01 6 4.754157E+01 -4.946532E-04 4.754157E+01 -4.104419E-04 + 3.330006E+01 9.000000E+01 1 2.082450E-06 -9.003854E+01 -1.400675E-09 -2.082449E-06 + 3.330006E+01 9.000000E+01 2 4.264584E+01 8.994171E+01 4.338904E-02 4.264582E+01 + 3.330006E+01 9.000000E+01 3 1.926637E+02 2.254867E-01 1.926622E+02 7.582231E-01 + 3.330006E+01 9.000000E+01 4 1.390710E+02 8.994186E+01 1.411347E-01 1.390710E+02 + 3.330006E+01 9.000000E+01 5 9.635598E-05 -8.999332E+01 1.123567E-08 -9.635598E-05 + 3.330006E+01 9.000000E+01 6 4.079272E-06 1.799997E+02 -4.079272E-06 2.380602E-11 + 3.340006E+01 0.000000E+00 1 3.977332E+01 8.994849E+01 3.575583E-02 3.977330E+01 + 3.340006E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.340006E+01 0.000000E+00 3 1.904877E+02 2.229205E-01 1.904863E+02 7.411280E-01 + 3.340006E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.340006E+01 0.000000E+00 5 4.181083E+02 8.994849E+01 3.758605E-01 4.181081E+02 + 3.340006E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.340006E+01 3.000000E+01 1 3.453543E+01 8.994849E+01 3.104566E-02 3.453542E+01 + 3.340006E+01 3.000000E+01 2 2.107421E+01 8.994210E+01 2.129508E-02 2.107420E+01 + 3.340006E+01 3.000000E+01 3 1.910508E+02 2.232130E-01 1.910493E+02 7.442940E-01 + 3.340006E+01 3.000000E+01 4 6.818805E+01 8.994181E+01 6.925596E-02 6.818801E+01 + 3.340006E+01 3.000000E+01 5 3.630287E+02 8.994849E+01 3.263490E-01 3.630285E+02 + 3.340006E+01 3.000000E+01 6 4.696491E+01 -4.891424E-04 4.696491E+01 -4.009463E-04 + 3.340006E+01 6.000000E+01 1 2.004414E+01 8.994849E+01 1.801731E-02 2.004414E+01 + 3.340006E+01 6.000000E+01 2 3.671303E+01 8.994210E+01 3.709995E-02 3.671301E+01 + 3.340006E+01 6.000000E+01 3 1.921849E+02 2.237944E-01 1.921834E+02 7.506623E-01 + 3.340006E+01 6.000000E+01 4 1.193978E+02 8.994210E+01 1.206570E-01 1.193977E+02 + 3.340006E+01 6.000000E+01 5 2.106739E+02 8.994849E+01 1.893928E-01 2.106738E+02 + 3.340006E+01 6.000000E+01 6 4.724491E+01 -4.881580E-04 4.724491E+01 -4.025249E-04 + 3.340006E+01 9.000000E+01 1 2.076021E-06 -9.003834E+01 -1.389009E-09 -2.076020E-06 + 3.340006E+01 9.000000E+01 2 4.251513E+01 8.994210E+01 4.296470E-02 4.251511E+01 + 3.340006E+01 9.000000E+01 3 1.927546E+02 2.240849E-01 1.927531E+02 7.538652E-01 + 3.340006E+01 9.000000E+01 4 1.386183E+02 8.994225E+01 1.397293E-01 1.386183E+02 + 3.340006E+01 9.000000E+01 5 9.607337E-05 -8.999338E+01 1.111041E-08 -9.607337E-05 + 3.340006E+01 9.000000E+01 6 4.053707E-06 1.799997E+02 -4.053707E-06 2.334736E-11 + 3.350006E+01 0.000000E+00 1 3.965461E+01 8.994881E+01 3.542322E-02 3.965459E+01 + 3.350006E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.350006E+01 0.000000E+00 3 1.905910E+02 2.215475E-01 1.905896E+02 7.369626E-01 + 3.350006E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.350006E+01 0.000000E+00 5 4.170345E+02 8.994881E+01 3.725198E-01 4.170343E+02 + 3.350006E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.350006E+01 3.000000E+01 1 3.443173E+01 8.994881E+01 3.075631E-02 3.443172E+01 + 3.350006E+01 3.000000E+01 2 2.101094E+01 8.994249E+01 2.108870E-02 2.101093E+01 + 3.350006E+01 3.000000E+01 3 1.911513E+02 2.218343E-01 1.911499E+02 7.400862E-01 + 3.350006E+01 3.000000E+01 4 6.797367E+01 8.994220E+01 6.857287E-02 6.797363E+01 + 3.350006E+01 3.000000E+01 5 3.620924E+02 8.994881E+01 3.234438E-01 3.620922E+02 + 3.350006E+01 3.000000E+01 6 4.667448E+01 -4.827369E-04 4.667448E+01 -3.932487E-04 + 3.350006E+01 6.000000E+01 1 1.998332E+01 8.994882E+01 1.784883E-02 1.998331E+01 + 3.350006E+01 6.000000E+01 2 3.660141E+01 8.994249E+01 3.673913E-02 3.660139E+01 + 3.350006E+01 6.000000E+01 3 1.922785E+02 2.224091E-01 1.922771E+02 7.463794E-01 + 3.350006E+01 6.000000E+01 4 1.190141E+02 8.994249E+01 1.194625E-01 1.190140E+02 + 3.350006E+01 6.000000E+01 5 2.101224E+02 8.994881E+01 1.877010E-01 2.101223E+02 + 3.350006E+01 6.000000E+01 6 4.695098E+01 -4.817709E-04 4.695098E+01 -3.947868E-04 + 3.350006E+01 9.000000E+01 1 2.069632E-06 -9.003814E+01 -1.377468E-09 -2.069631E-06 + 3.350006E+01 9.000000E+01 2 4.238506E+01 8.994249E+01 4.254586E-02 4.238503E+01 + 3.350006E+01 9.000000E+01 3 1.928446E+02 2.226968E-01 1.928431E+02 7.495451E-01 + 3.350006E+01 9.000000E+01 4 1.381679E+02 8.994263E+01 1.383440E-01 1.381678E+02 + 3.350006E+01 9.000000E+01 5 9.579137E-05 -8.999342E+01 1.098708E-08 -9.579137E-05 + 3.350006E+01 9.000000E+01 6 4.028387E-06 1.799997E+02 -4.028387E-06 2.289907E-11 + 3.360006E+01 0.000000E+00 1 3.953648E+01 8.994914E+01 3.509463E-02 3.953646E+01 + 3.360006E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.360006E+01 0.000000E+00 3 1.906935E+02 2.201875E-01 1.906921E+02 7.328328E-01 + 3.360006E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.360006E+01 0.000000E+00 5 4.159681E+02 8.994914E+01 3.692213E-01 4.159680E+02 + 3.360006E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.360006E+01 3.000000E+01 1 3.432856E+01 8.994914E+01 3.047062E-02 3.432855E+01 + 3.360006E+01 3.000000E+01 2 2.094806E+01 8.994288E+01 2.088508E-02 2.094805E+01 + 3.360006E+01 3.000000E+01 3 1.912510E+02 2.204702E-01 1.912496E+02 7.359189E-01 + 3.360006E+01 3.000000E+01 4 6.776035E+01 8.994259E+01 6.789912E-02 6.776032E+01 + 3.360006E+01 3.000000E+01 5 3.611580E+02 8.994914E+01 3.205728E-01 3.611579E+02 + 3.360006E+01 3.000000E+01 6 4.638676E+01 -4.764366E-04 4.638676E+01 -3.857239E-04 + 3.360006E+01 6.000000E+01 1 1.992280E+01 8.994914E+01 1.768249E-02 1.992279E+01 + 3.360006E+01 6.000000E+01 2 3.649052E+01 8.994288E+01 3.638297E-02 3.649050E+01 + 3.360006E+01 6.000000E+01 3 1.923710E+02 2.210367E-01 1.923696E+02 7.421306E-01 + 3.360006E+01 6.000000E+01 4 1.186326E+02 8.994288E+01 1.182837E-01 1.186326E+02 + 3.360006E+01 6.000000E+01 5 2.095754E+02 8.994914E+01 1.860294E-01 2.095753E+02 + 3.360006E+01 6.000000E+01 6 4.665978E+01 -4.754898E-04 4.665978E+01 -3.872231E-04 + 3.360006E+01 9.000000E+01 1 2.063289E-06 -9.003794E+01 -1.366047E-09 -2.063289E-06 + 3.360006E+01 9.000000E+01 2 4.225586E+01 8.994287E+01 4.213268E-02 4.225583E+01 + 3.360006E+01 9.000000E+01 3 1.929343E+02 2.213204E-01 1.929328E+02 7.452589E-01 + 3.360006E+01 9.000000E+01 4 1.377205E+02 8.994302E+01 1.369766E-01 1.377205E+02 + 3.360006E+01 9.000000E+01 5 9.551140E-05 -8.999348E+01 1.086559E-08 -9.551140E-05 + 3.360006E+01 9.000000E+01 6 4.003303E-06 1.799997E+02 -4.003303E-06 2.246091E-11 + 3.370006E+01 0.000000E+00 1 3.941903E+01 8.994946E+01 3.477030E-02 3.941902E+01 + 3.370006E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.370006E+01 0.000000E+00 3 1.907948E+02 2.188378E-01 1.907935E+02 7.287277E-01 + 3.370006E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.370006E+01 0.000000E+00 5 4.149079E+02 8.994947E+01 3.659608E-01 4.149077E+02 + 3.370006E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.370006E+01 3.000000E+01 1 3.422599E+01 8.994947E+01 3.018847E-02 3.422598E+01 + 3.370006E+01 3.000000E+01 2 2.088553E+01 8.994326E+01 2.068408E-02 2.088552E+01 + 3.370006E+01 3.000000E+01 3 1.913493E+02 2.191173E-01 1.913479E+02 7.317789E-01 + 3.370006E+01 3.000000E+01 4 6.754848E+01 8.994297E+01 6.723402E-02 6.754845E+01 + 3.370006E+01 3.000000E+01 5 3.602292E+02 8.994947E+01 3.177367E-01 3.602291E+02 + 3.370006E+01 3.000000E+01 6 4.610175E+01 -4.702416E-04 4.610175E+01 -3.783692E-04 + 3.370006E+01 6.000000E+01 1 1.986265E+01 8.994947E+01 1.751814E-02 1.986264E+01 + 3.370006E+01 6.000000E+01 2 3.638029E+01 8.994325E+01 3.603162E-02 3.638027E+01 + 3.370006E+01 6.000000E+01 3 1.924628E+02 2.196764E-01 1.924614E+02 7.379153E-01 + 3.370006E+01 6.000000E+01 4 1.182544E+02 8.994325E+01 1.171209E-01 1.182544E+02 + 3.370006E+01 6.000000E+01 5 2.090304E+02 8.994946E+01 1.843785E-01 2.090303E+02 + 3.370006E+01 6.000000E+01 6 4.637133E+01 -4.693134E-04 4.637133E+01 -3.798305E-04 + 3.370006E+01 9.000000E+01 1 2.056978E-06 -9.003773E+01 -1.354751E-09 -2.056977E-06 + 3.370006E+01 9.000000E+01 2 4.212744E+01 8.994325E+01 4.172492E-02 4.212742E+01 + 3.370006E+01 9.000000E+01 3 1.930227E+02 2.199568E-01 1.930213E+02 7.410066E-01 + 3.370006E+01 9.000000E+01 4 1.372767E+02 8.994340E+01 1.356272E-01 1.372766E+02 + 3.370006E+01 9.000000E+01 5 9.523307E-05 -8.999354E+01 1.074594E-08 -9.523307E-05 + 3.370006E+01 9.000000E+01 6 3.978461E-06 1.799997E+02 -3.978461E-06 2.203259E-11 + 3.380006E+01 0.000000E+00 1 3.930218E+01 8.994978E+01 3.444978E-02 3.930216E+01 + 3.380006E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.380006E+01 0.000000E+00 3 1.908964E+02 2.174999E-01 1.908950E+02 7.246583E-01 + 3.380006E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.380006E+01 0.000000E+00 5 4.138488E+02 8.994978E+01 3.627357E-01 4.138487E+02 + 3.380006E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.380006E+01 3.000000E+01 1 3.412407E+01 8.994978E+01 2.990977E-02 3.412405E+01 + 3.380006E+01 3.000000E+01 2 2.082336E+01 8.994363E+01 2.048573E-02 2.082335E+01 + 3.380006E+01 3.000000E+01 3 1.914473E+02 2.177773E-01 1.914459E+02 7.276760E-01 + 3.380006E+01 3.000000E+01 4 6.733807E+01 8.994335E+01 6.657772E-02 6.733804E+01 + 3.380006E+01 3.000000E+01 5 3.593055E+02 8.994978E+01 3.149348E-01 3.593054E+02 + 3.380006E+01 3.000000E+01 6 4.581934E+01 -4.641483E-04 4.581934E+01 -3.711787E-04 + 3.380006E+01 6.000000E+01 1 1.980288E+01 8.994979E+01 1.735591E-02 1.980288E+01 + 3.380006E+01 6.000000E+01 2 3.627076E+01 8.994363E+01 3.568467E-02 3.627074E+01 + 3.380006E+01 6.000000E+01 3 1.925543E+02 2.183298E-01 1.925529E+02 7.337406E-01 + 3.380006E+01 6.000000E+01 4 1.178778E+02 8.994363E+01 1.159738E-01 1.178778E+02 + 3.380006E+01 6.000000E+01 5 2.084864E+02 8.994978E+01 1.827458E-01 2.084863E+02 + 3.380006E+01 6.000000E+01 6 4.608560E+01 -4.632380E-04 4.608560E+01 -3.726034E-04 + 3.380006E+01 9.000000E+01 1 2.050707E-06 -9.003754E+01 -1.343575E-09 -2.050706E-06 + 3.380006E+01 9.000000E+01 2 4.199990E+01 8.994363E+01 4.132249E-02 4.199989E+01 + 3.380006E+01 9.000000E+01 3 1.931105E+02 2.186055E-01 1.931091E+02 7.367893E-01 + 3.380006E+01 9.000000E+01 4 1.368353E+02 8.994377E+01 1.342966E-01 1.368352E+02 + 3.380006E+01 9.000000E+01 5 9.495654E-05 -8.999359E+01 1.062802E-08 -9.495654E-05 + 3.380006E+01 9.000000E+01 6 3.953850E-06 1.799997E+02 -3.953850E-06 2.161383E-11 + 3.390005E+01 0.000000E+00 1 3.918617E+01 8.995010E+01 3.413335E-02 3.918615E+01 + 3.390005E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.390005E+01 0.000000E+00 3 1.909960E+02 2.161779E-01 1.909947E+02 7.206295E-01 + 3.390005E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.390005E+01 0.000000E+00 5 4.127961E+02 8.995010E+01 3.595535E-01 4.127960E+02 + 3.390005E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.390005E+01 3.000000E+01 1 3.402280E+01 8.995010E+01 2.963470E-02 3.402279E+01 + 3.390005E+01 3.000000E+01 2 2.076159E+01 8.994401E+01 2.028989E-02 2.076159E+01 + 3.390005E+01 3.000000E+01 3 1.915440E+02 2.164503E-01 1.915426E+02 7.236077E-01 + 3.390005E+01 3.000000E+01 4 6.712875E+01 8.994373E+01 6.593039E-02 6.712872E+01 + 3.390005E+01 3.000000E+01 5 3.583869E+02 8.995010E+01 3.121656E-01 3.583867E+02 + 3.390005E+01 3.000000E+01 6 4.553960E+01 -4.581544E-04 4.553960E+01 -3.641484E-04 + 3.390005E+01 6.000000E+01 1 1.974346E+01 8.995010E+01 1.719568E-02 1.974345E+01 + 3.390005E+01 6.000000E+01 2 3.616187E+01 8.994400E+01 3.534235E-02 3.616185E+01 + 3.390005E+01 6.000000E+01 3 1.926449E+02 2.169954E-01 1.926435E+02 7.295989E-01 + 3.390005E+01 6.000000E+01 4 1.175042E+02 8.994400E+01 1.148419E-01 1.175042E+02 + 3.390005E+01 6.000000E+01 5 2.079469E+02 8.995010E+01 1.811315E-01 2.079469E+02 + 3.390005E+01 6.000000E+01 6 4.580251E+01 -4.572622E-04 4.580251E+01 -3.655375E-04 + 3.390005E+01 9.000000E+01 1 2.044483E-06 -9.003735E+01 -1.332509E-09 -2.044482E-06 + 3.390005E+01 9.000000E+01 2 4.187303E+01 8.994400E+01 4.092541E-02 4.187301E+01 + 3.390005E+01 9.000000E+01 3 1.931985E+02 2.172666E-01 1.931971E+02 7.326102E-01 + 3.390005E+01 9.000000E+01 4 1.363971E+02 8.994414E+01 1.329831E-01 1.363971E+02 + 3.390005E+01 9.000000E+01 5 9.468116E-05 -8.999364E+01 1.051181E-08 -9.468116E-05 + 3.390005E+01 9.000000E+01 6 3.929469E-06 1.799997E+02 -3.929469E-06 2.120445E-11 + 3.400005E+01 0.000000E+00 1 3.907083E+01 8.995040E+01 3.382083E-02 3.907082E+01 + 3.400005E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.400005E+01 0.000000E+00 3 1.910952E+02 2.148654E-01 1.910939E+02 7.166262E-01 + 3.400005E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.400005E+01 0.000000E+00 5 4.117466E+02 8.995041E+01 3.564029E-01 4.117465E+02 + 3.400005E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.400005E+01 3.000000E+01 1 3.392203E+01 8.995040E+01 2.936275E-02 3.392202E+01 + 3.400005E+01 3.000000E+01 2 2.070027E+01 8.994438E+01 2.009663E-02 2.070026E+01 + 3.400005E+01 3.000000E+01 3 1.916397E+02 2.151350E-01 1.916384E+02 7.195699E-01 + 3.400005E+01 3.000000E+01 4 6.692104E+01 8.994410E+01 6.529147E-02 6.692101E+01 + 3.400005E+01 3.000000E+01 5 3.574666E+02 8.995040E+01 3.094259E-01 3.574665E+02 + 3.400005E+01 3.000000E+01 6 4.526242E+01 -4.522591E-04 4.526242E+01 -3.572749E-04 + 3.400005E+01 6.000000E+01 1 1.968440E+01 8.995041E+01 1.703744E-02 1.968439E+01 + 3.400005E+01 6.000000E+01 2 3.605368E+01 8.994437E+01 3.500450E-02 3.605367E+01 + 3.400005E+01 6.000000E+01 3 1.927338E+02 2.156741E-01 1.927324E+02 7.254912E-01 + 3.400005E+01 6.000000E+01 4 1.171330E+02 8.994437E+01 1.137248E-01 1.171329E+02 + 3.400005E+01 6.000000E+01 5 2.074086E+02 8.995040E+01 1.795366E-01 2.074086E+02 + 3.400005E+01 6.000000E+01 6 4.552207E+01 -4.513839E-04 4.552207E+01 -3.586290E-04 + 3.400005E+01 9.000000E+01 1 2.038288E-06 -9.003716E+01 -1.321565E-09 -2.038288E-06 + 3.400005E+01 9.000000E+01 2 4.174704E+01 8.994437E+01 4.053334E-02 4.174702E+01 + 3.400005E+01 9.000000E+01 3 1.932842E+02 2.159432E-01 1.932829E+02 7.284712E-01 + 3.400005E+01 9.000000E+01 4 1.359620E+02 8.994451E+01 1.316872E-01 1.359619E+02 + 3.400005E+01 9.000000E+01 5 9.440799E-05 -8.999369E+01 1.039739E-08 -9.440799E-05 + 3.400005E+01 9.000000E+01 6 3.905322E-06 1.799997E+02 -3.905322E-06 2.080413E-11 + 3.410005E+01 0.000000E+00 1 3.895607E+01 8.995071E+01 3.351206E-02 3.895606E+01 + 3.410005E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.410005E+01 0.000000E+00 3 1.911934E+02 2.135657E-01 1.911921E+02 7.126575E-01 + 3.410005E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.410005E+01 0.000000E+00 5 4.107012E+02 8.995071E+01 3.532951E-01 4.107010E+02 + 3.410005E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.410005E+01 3.000000E+01 1 3.382191E+01 8.995071E+01 2.909433E-02 3.382190E+01 + 3.410005E+01 3.000000E+01 2 2.063913E+01 8.994474E+01 1.990585E-02 2.063912E+01 + 3.410005E+01 3.000000E+01 3 1.917356E+02 2.138311E-01 1.917343E+02 7.155666E-01 + 3.410005E+01 3.000000E+01 4 6.671435E+01 8.994447E+01 6.466094E-02 6.671432E+01 + 3.410005E+01 3.000000E+01 5 3.565597E+02 8.995071E+01 3.067199E-01 3.565596E+02 + 3.410005E+01 3.000000E+01 6 4.498774E+01 -4.464596E-04 4.498774E+01 -3.505531E-04 + 3.410005E+01 6.000000E+01 1 1.962566E+01 8.995071E+01 1.688116E-02 1.962565E+01 + 3.410005E+01 6.000000E+01 2 3.594605E+01 8.994474E+01 3.467092E-02 3.594604E+01 + 3.410005E+01 6.000000E+01 3 1.928227E+02 2.143649E-01 1.928214E+02 7.214200E-01 + 3.410005E+01 6.000000E+01 4 1.167640E+02 8.994474E+01 1.126223E-01 1.167640E+02 + 3.410005E+01 6.000000E+01 5 2.068734E+02 8.995071E+01 1.779629E-01 2.068734E+02 + 3.410005E+01 6.000000E+01 6 4.524427E+01 -4.456003E-04 4.524427E+01 -3.518733E-04 + 3.410005E+01 9.000000E+01 1 2.032130E-06 -9.003696E+01 -1.310731E-09 -2.032130E-06 + 3.410005E+01 9.000000E+01 2 4.162177E+01 8.994473E+01 4.014638E-02 4.162175E+01 + 3.410005E+01 9.000000E+01 3 1.933700E+02 2.146287E-01 1.933686E+02 7.243579E-01 + 3.410005E+01 9.000000E+01 4 1.355293E+02 8.994487E+01 1.304089E-01 1.355293E+02 + 3.410005E+01 9.000000E+01 5 9.413626E-05 -8.999374E+01 1.028458E-08 -9.413626E-05 + 3.410005E+01 9.000000E+01 6 3.881387E-06 1.799997E+02 -3.881387E-06 2.041273E-11 + 3.420005E+01 0.000000E+00 1 3.884214E+01 8.995102E+01 3.320713E-02 3.884213E+01 + 3.420005E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.420005E+01 0.000000E+00 3 1.912910E+02 2.122780E-01 1.912897E+02 7.087221E-01 + 3.420005E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.420005E+01 0.000000E+00 5 4.096624E+02 8.995102E+01 3.502164E-01 4.096622E+02 + 3.420005E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.420005E+01 3.000000E+01 1 3.372246E+01 8.995102E+01 2.882922E-02 3.372245E+01 + 3.420005E+01 3.000000E+01 2 2.057844E+01 8.994510E+01 1.971754E-02 2.057843E+01 + 3.420005E+01 3.000000E+01 3 1.918292E+02 2.125403E-01 1.918279E+02 7.115940E-01 + 3.420005E+01 3.000000E+01 4 6.650908E+01 8.994484E+01 6.403850E-02 6.650905E+01 + 3.420005E+01 3.000000E+01 5 3.556488E+02 8.995102E+01 3.040474E-01 3.556487E+02 + 3.420005E+01 3.000000E+01 6 4.471568E+01 -4.407538E-04 4.471568E+01 -3.439801E-04 + 3.420005E+01 6.000000E+01 1 1.956731E+01 8.995103E+01 1.672681E-02 1.956731E+01 + 3.420005E+01 6.000000E+01 2 3.583922E+01 8.994510E+01 3.434163E-02 3.583920E+01 + 3.420005E+01 6.000000E+01 3 1.929110E+02 2.130659E-01 1.929097E+02 7.173767E-01 + 3.420005E+01 6.000000E+01 4 1.163975E+02 8.994510E+01 1.115347E-01 1.163975E+02 + 3.420005E+01 6.000000E+01 5 2.063403E+02 8.995102E+01 1.764052E-01 2.063403E+02 + 3.420005E+01 6.000000E+01 6 4.496900E+01 -4.399107E-04 4.496900E+01 -3.452670E-04 + 3.420005E+01 9.000000E+01 1 2.026014E-06 -9.003677E+01 -1.300017E-09 -2.026014E-06 + 3.420005E+01 9.000000E+01 2 4.149716E+01 8.994510E+01 3.976450E-02 4.149714E+01 + 3.420005E+01 9.000000E+01 3 1.934550E+02 2.133281E-01 1.934536E+02 7.202849E-01 + 3.420005E+01 9.000000E+01 4 1.350997E+02 8.994523E+01 1.291466E-01 1.350996E+02 + 3.420005E+01 9.000000E+01 5 9.386538E-05 -8.999379E+01 1.017344E-08 -9.386538E-05 + 3.420005E+01 9.000000E+01 6 3.857687E-06 1.799997E+02 -3.857687E-06 2.002991E-11 + 3.430005E+01 0.000000E+00 1 3.872882E+01 8.995132E+01 3.290593E-02 3.872881E+01 + 3.430005E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.430005E+01 0.000000E+00 3 1.913871E+02 2.110021E-01 1.913858E+02 7.048159E-01 + 3.430005E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.430005E+01 0.000000E+00 5 4.086259E+02 8.995132E+01 3.471771E-01 4.086258E+02 + 3.430005E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.430005E+01 3.000000E+01 1 3.362355E+01 8.995132E+01 2.856727E-02 3.362354E+01 + 3.430005E+01 3.000000E+01 2 2.051813E+01 8.994546E+01 1.953158E-02 2.051812E+01 + 3.430005E+01 3.000000E+01 3 1.919223E+02 2.112613E-01 1.919209E+02 7.076553E-01 + 3.430005E+01 3.000000E+01 4 6.630528E+01 8.994520E+01 6.342429E-02 6.630525E+01 + 3.430005E+01 3.000000E+01 5 3.547445E+02 8.995132E+01 3.014019E-01 3.547444E+02 + 3.430005E+01 3.000000E+01 6 4.444604E+01 -4.351407E-04 4.444604E+01 -3.375516E-04 + 3.430005E+01 6.000000E+01 1 1.950934E+01 8.995132E+01 1.657432E-02 1.950933E+01 + 3.430005E+01 6.000000E+01 2 3.573286E+01 8.994546E+01 3.401675E-02 3.573285E+01 + 3.430005E+01 6.000000E+01 3 1.929984E+02 2.117788E-01 1.929971E+02 7.133664E-01 + 3.430005E+01 6.000000E+01 4 1.160334E+02 8.994546E+01 1.104610E-01 1.160334E+02 + 3.430005E+01 6.000000E+01 5 2.058100E+02 8.995132E+01 1.748671E-01 2.058099E+02 + 3.430005E+01 6.000000E+01 6 4.469635E+01 -4.343129E-04 4.469635E+01 -3.388068E-04 + 3.430005E+01 9.000000E+01 1 2.019941E-06 -9.003658E+01 -1.289411E-09 -2.019940E-06 + 3.430005E+01 9.000000E+01 2 4.137342E+01 8.994546E+01 3.938750E-02 4.137340E+01 + 3.430005E+01 9.000000E+01 3 1.935388E+02 2.120385E-01 1.935375E+02 7.162409E-01 + 3.430005E+01 9.000000E+01 4 1.346734E+02 8.994559E+01 1.279012E-01 1.346734E+02 + 3.430005E+01 9.000000E+01 5 9.359654E-05 -8.999384E+01 1.006393E-08 -9.359654E-05 + 3.430005E+01 9.000000E+01 6 3.834203E-06 1.799997E+02 -3.834203E-06 1.965557E-11 + 3.440005E+01 0.000000E+00 1 3.861600E+01 8.995162E+01 3.260842E-02 3.861599E+01 + 3.440005E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.440005E+01 0.000000E+00 3 1.914837E+02 2.097367E-01 1.914825E+02 7.009432E-01 + 3.440005E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.440005E+01 0.000000E+00 5 4.076013E+02 8.995162E+01 3.441715E-01 4.076011E+02 + 3.440005E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.440005E+01 3.000000E+01 1 3.352515E+01 8.995162E+01 2.830854E-02 3.352514E+01 + 3.440005E+01 3.000000E+01 2 2.045809E+01 8.994582E+01 1.934802E-02 2.045808E+01 + 3.440005E+01 3.000000E+01 3 1.920156E+02 2.099940E-01 1.920143E+02 7.037520E-01 + 3.440005E+01 3.000000E+01 4 6.610255E+01 8.994556E+01 6.281795E-02 6.610252E+01 + 3.440005E+01 3.000000E+01 5 3.538477E+02 8.995162E+01 2.987881E-01 3.538476E+02 + 3.440005E+01 3.000000E+01 6 4.417879E+01 -4.296174E-04 4.417879E+01 -3.312631E-04 + 3.440005E+01 6.000000E+01 1 1.945168E+01 8.995162E+01 1.642371E-02 1.945168E+01 + 3.440005E+01 6.000000E+01 2 3.562713E+01 8.994582E+01 3.369583E-02 3.562711E+01 + 3.440005E+01 6.000000E+01 3 1.930847E+02 2.105051E-01 1.930835E+02 7.093930E-01 + 3.440005E+01 6.000000E+01 4 1.156715E+02 8.994582E+01 1.094015E-01 1.156714E+02 + 3.440005E+01 6.000000E+01 5 2.052818E+02 8.995162E+01 1.733446E-01 2.052818E+02 + 3.440005E+01 6.000000E+01 6 4.442604E+01 -4.288058E-04 4.442604E+01 -3.324877E-04 + 3.440005E+01 9.000000E+01 1 2.013890E-06 -9.003638E+01 -1.278914E-09 -2.013890E-06 + 3.440005E+01 9.000000E+01 2 4.125039E+01 8.994582E+01 3.901527E-02 4.125037E+01 + 3.440005E+01 9.000000E+01 3 1.936228E+02 2.107600E-01 1.936215E+02 7.122312E-01 + 3.440005E+01 9.000000E+01 4 1.342484E+02 8.994594E+01 1.266718E-01 1.342483E+02 + 3.440005E+01 9.000000E+01 5 9.332901E-05 -8.999389E+01 9.955983E-09 -9.332901E-05 + 3.440005E+01 9.000000E+01 6 3.810930E-06 1.799997E+02 -3.810930E-06 1.928943E-11 + 3.450005E+01 0.000000E+00 1 3.850412E+01 8.995192E+01 3.231448E-02 3.850410E+01 + 3.450005E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.450005E+01 0.000000E+00 3 1.915782E+02 2.084854E-01 1.915769E+02 6.971048E-01 + 3.450005E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.450005E+01 0.000000E+00 5 4.065757E+02 8.995192E+01 3.412012E-01 4.065756E+02 + 3.450005E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.450005E+01 3.000000E+01 1 3.342742E+01 8.995192E+01 2.805291E-02 3.342741E+01 + 3.450005E+01 3.000000E+01 2 2.039851E+01 8.994617E+01 1.916681E-02 2.039850E+01 + 3.450005E+01 3.000000E+01 3 1.921078E+02 2.087367E-01 1.921066E+02 6.998748E-01 + 3.450005E+01 3.000000E+01 4 6.590118E+01 8.994591E+01 6.221944E-02 6.590115E+01 + 3.450005E+01 3.000000E+01 5 3.529504E+02 8.995192E+01 2.962039E-01 3.529503E+02 + 3.450005E+01 3.000000E+01 6 4.391412E+01 -4.241830E-04 4.391412E+01 -3.251134E-04 + 3.450005E+01 6.000000E+01 1 1.939433E+01 8.995192E+01 1.627497E-02 1.939432E+01 + 3.450005E+01 6.000000E+01 2 3.552214E+01 8.994616E+01 3.337909E-02 3.552212E+01 + 3.450005E+01 6.000000E+01 3 1.931709E+02 2.092436E-01 1.931696E+02 7.054566E-01 + 3.450005E+01 6.000000E+01 4 1.153121E+02 8.994616E+01 1.083552E-01 1.153121E+02 + 3.450005E+01 6.000000E+01 5 2.047556E+02 8.995192E+01 1.718409E-01 2.047555E+02 + 3.450005E+01 6.000000E+01 6 4.415838E+01 -4.233874E-04 4.415838E+01 -3.263085E-04 + 3.450005E+01 9.000000E+01 1 2.007891E-06 -9.003619E+01 -1.268531E-09 -2.007891E-06 + 3.450005E+01 9.000000E+01 2 4.112812E+01 8.994616E+01 3.864783E-02 4.112811E+01 + 3.450005E+01 9.000000E+01 3 1.937057E+02 2.094953E-01 1.937044E+02 7.082606E-01 + 3.450005E+01 9.000000E+01 4 1.338276E+02 8.994629E+01 1.254597E-01 1.338276E+02 + 3.450005E+01 9.000000E+01 5 9.306328E-05 -8.999393E+01 9.849639E-09 -9.306328E-05 + 3.450005E+01 9.000000E+01 6 3.787876E-06 1.799997E+02 -3.787876E-06 1.893127E-11 + 3.460004E+01 0.000000E+00 1 3.839270E+01 8.995221E+01 3.202403E-02 3.839268E+01 + 3.460004E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.460004E+01 0.000000E+00 3 1.916720E+02 2.072441E-01 1.916708E+02 6.932938E-01 + 3.460004E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.460004E+01 0.000000E+00 5 4.055526E+02 8.995221E+01 3.382632E-01 4.055524E+02 + 3.460004E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.460004E+01 3.000000E+01 1 3.333018E+01 8.995221E+01 2.780049E-02 3.333017E+01 + 3.460004E+01 3.000000E+01 2 2.033922E+01 8.994651E+01 1.898784E-02 2.033921E+01 + 3.460004E+01 3.000000E+01 3 1.921990E+02 2.074935E-01 1.921977E+02 6.960364E-01 + 3.460004E+01 3.000000E+01 4 6.570105E+01 8.994626E+01 6.162897E-02 6.570102E+01 + 3.460004E+01 3.000000E+01 5 3.520589E+02 8.995221E+01 2.936520E-01 3.520588E+02 + 3.460004E+01 3.000000E+01 6 4.365172E+01 -4.188360E-04 4.365172E+01 -3.190970E-04 + 3.460004E+01 6.000000E+01 1 1.933741E+01 8.995221E+01 1.612801E-02 1.933740E+01 + 3.460004E+01 6.000000E+01 2 3.541766E+01 8.994651E+01 3.306628E-02 3.541765E+01 + 3.460004E+01 6.000000E+01 3 1.932563E+02 2.079926E-01 1.932550E+02 7.015489E-01 + 3.460004E+01 6.000000E+01 4 1.149547E+02 8.994651E+01 1.073231E-01 1.149546E+02 + 3.460004E+01 6.000000E+01 5 2.042325E+02 8.995221E+01 1.703553E-01 2.042324E+02 + 3.460004E+01 6.000000E+01 6 4.389307E+01 -4.180543E-04 4.389307E+01 -3.202625E-04 + 3.460004E+01 9.000000E+01 1 2.001920E-06 -9.003601E+01 -1.258253E-09 -2.001919E-06 + 3.460004E+01 9.000000E+01 2 4.100655E+01 8.994651E+01 3.828514E-02 4.100653E+01 + 3.460004E+01 9.000000E+01 3 1.937877E+02 2.082420E-01 1.937864E+02 7.043214E-01 + 3.460004E+01 9.000000E+01 4 1.334088E+02 8.994663E+01 1.242620E-01 1.334087E+02 + 3.460004E+01 9.000000E+01 5 9.279925E-05 -8.999399E+01 9.744760E-09 -9.279925E-05 + 3.460004E+01 9.000000E+01 6 3.765038E-06 1.799997E+02 -3.765038E-06 1.858096E-11 + 3.470004E+01 0.000000E+00 1 3.828198E+01 8.995250E+01 3.173710E-02 3.828197E+01 + 3.470004E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.470004E+01 0.000000E+00 3 1.917661E+02 2.060119E-01 1.917648E+02 6.895097E-01 + 3.470004E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.470004E+01 0.000000E+00 5 4.045352E+02 8.995250E+01 3.353630E-01 4.045350E+02 + 3.470004E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.470004E+01 3.000000E+01 1 3.323360E+01 8.995250E+01 2.755093E-02 3.323359E+01 + 3.470004E+01 3.000000E+01 2 2.028024E+01 8.994686E+01 1.881117E-02 2.028024E+01 + 3.470004E+01 3.000000E+01 3 1.922891E+02 2.062576E-01 1.922878E+02 6.922148E-01 + 3.470004E+01 3.000000E+01 4 6.550204E+01 8.994660E+01 6.104593E-02 6.550201E+01 + 3.470004E+01 3.000000E+01 5 3.511710E+02 8.995250E+01 2.911268E-01 3.511709E+02 + 3.470004E+01 3.000000E+01 6 4.339181E+01 -4.135736E-04 4.339181E+01 -3.132117E-04 + 3.470004E+01 6.000000E+01 1 1.928073E+01 8.995251E+01 1.598278E-02 1.928073E+01 + 3.470004E+01 6.000000E+01 2 3.531391E+01 8.994685E+01 3.275752E-02 3.531390E+01 + 3.470004E+01 6.000000E+01 3 1.933406E+02 2.067509E-01 1.933394E+02 6.976652E-01 + 3.470004E+01 6.000000E+01 4 1.145994E+02 8.994685E+01 1.063041E-01 1.145993E+02 + 3.470004E+01 6.000000E+01 5 2.037125E+02 8.995250E+01 1.688858E-01 2.037124E+02 + 3.470004E+01 6.000000E+01 6 4.363018E+01 -4.128074E-04 4.363018E+01 -3.143488E-04 + 3.470004E+01 9.000000E+01 1 1.995988E-06 -9.003583E+01 -1.248082E-09 -1.995987E-06 + 3.470004E+01 9.000000E+01 2 4.088573E+01 8.994685E+01 3.792702E-02 4.088572E+01 + 3.470004E+01 9.000000E+01 3 1.938689E+02 2.069982E-01 1.938677E+02 7.004082E-01 + 3.470004E+01 9.000000E+01 4 1.329931E+02 8.994698E+01 1.230801E-01 1.329930E+02 + 3.470004E+01 9.000000E+01 5 9.253614E-05 -8.999403E+01 9.641385E-09 -9.253614E-05 + 3.470004E+01 9.000000E+01 6 3.742401E-06 1.799997E+02 -3.742401E-06 1.823821E-11 + 3.480004E+01 0.000000E+00 1 3.817182E+01 8.995279E+01 3.145370E-02 3.817181E+01 + 3.480004E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.480004E+01 0.000000E+00 3 1.918590E+02 2.047918E-01 1.918578E+02 6.857587E-01 + 3.480004E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.480004E+01 0.000000E+00 5 4.035247E+02 8.995280E+01 3.324912E-01 4.035246E+02 + 3.480004E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.480004E+01 3.000000E+01 1 3.313750E+01 8.995280E+01 2.730451E-02 3.313749E+01 + 3.480004E+01 3.000000E+01 2 2.022166E+01 8.994720E+01 1.863669E-02 2.022165E+01 + 3.480004E+01 3.000000E+01 3 1.923790E+02 2.050359E-01 1.923777E+02 6.884367E-01 + 3.480004E+01 3.000000E+01 4 6.530428E+01 8.994695E+01 6.047025E-02 6.530425E+01 + 3.480004E+01 3.000000E+01 5 3.502878E+02 8.995280E+01 2.886325E-01 3.502877E+02 + 3.480004E+01 3.000000E+01 6 4.313417E+01 -4.083954E-04 4.313417E+01 -3.074537E-04 + 3.480004E+01 6.000000E+01 1 1.922439E+01 8.995280E+01 1.583939E-02 1.922439E+01 + 3.480004E+01 6.000000E+01 2 3.521078E+01 8.994719E+01 3.245264E-02 3.521076E+01 + 3.480004E+01 6.000000E+01 3 1.934247E+02 2.055226E-01 1.934235E+02 6.938217E-01 + 3.480004E+01 6.000000E+01 4 1.142474E+02 8.994719E+01 1.052982E-01 1.142474E+02 + 3.480004E+01 6.000000E+01 5 2.031938E+02 8.995279E+01 1.674338E-01 2.031937E+02 + 3.480004E+01 6.000000E+01 6 4.336976E+01 -4.076424E-04 4.336976E+01 -3.085629E-04 + 3.480004E+01 9.000000E+01 1 1.990087E-06 -9.003564E+01 -1.238019E-09 -1.990086E-06 + 3.480004E+01 9.000000E+01 2 4.076549E+01 8.994719E+01 3.757337E-02 4.076547E+01 + 3.480004E+01 9.000000E+01 3 1.939492E+02 2.057671E-01 1.939480E+02 6.965309E-01 + 3.480004E+01 9.000000E+01 4 1.325797E+02 8.994732E+01 1.219134E-01 1.325796E+02 + 3.480004E+01 9.000000E+01 5 9.227471E-05 -8.999407E+01 9.539542E-09 -9.227471E-05 + 3.480004E+01 9.000000E+01 6 3.719979E-06 1.799997E+02 -3.719979E-06 1.790291E-11 + 3.490004E+01 0.000000E+00 1 3.806224E+01 8.995307E+01 3.117362E-02 3.806223E+01 + 3.490004E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.490004E+01 0.000000E+00 3 1.919511E+02 2.035830E-01 1.919499E+02 6.820379E-01 + 3.490004E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.490004E+01 0.000000E+00 5 4.025160E+02 8.995307E+01 3.296574E-01 4.025159E+02 + 3.490004E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.490004E+01 3.000000E+01 1 3.304195E+01 8.995307E+01 2.706098E-02 3.304194E+01 + 3.490004E+01 3.000000E+01 2 2.016346E+01 8.994753E+01 1.846446E-02 2.016346E+01 + 3.490004E+01 3.000000E+01 3 1.924683E+02 2.038238E-01 1.924671E+02 6.846845E-01 + 3.490004E+01 3.000000E+01 4 6.510779E+01 8.994729E+01 5.990160E-02 6.510776E+01 + 3.490004E+01 3.000000E+01 5 3.494085E+02 8.995307E+01 2.861628E-01 3.494084E+02 + 3.490004E+01 3.000000E+01 6 4.287885E+01 -4.032986E-04 4.287885E+01 -3.018194E-04 + 3.490004E+01 6.000000E+01 1 1.916846E+01 8.995308E+01 1.569767E-02 1.916845E+01 + 3.490004E+01 6.000000E+01 2 3.510817E+01 8.994753E+01 3.215162E-02 3.510815E+01 + 3.490004E+01 6.000000E+01 3 1.935076E+02 2.043044E-01 1.935064E+02 6.900049E-01 + 3.490004E+01 6.000000E+01 4 1.138965E+02 8.994753E+01 1.043052E-01 1.138964E+02 + 3.490004E+01 6.000000E+01 5 2.026765E+02 8.995307E+01 1.659977E-01 2.026764E+02 + 3.490004E+01 6.000000E+01 6 4.311163E+01 -4.025592E-04 4.311163E+01 -3.029016E-04 + 3.490004E+01 9.000000E+01 1 1.984223E-06 -9.003546E+01 -1.228055E-09 -1.984222E-06 + 3.490004E+01 9.000000E+01 2 4.064616E+01 8.994753E+01 3.722418E-02 4.064615E+01 + 3.490004E+01 9.000000E+01 3 1.940294E+02 2.045455E-01 1.940282E+02 6.926820E-01 + 3.490004E+01 9.000000E+01 4 1.321692E+02 8.994765E+01 1.207615E-01 1.321692E+02 + 3.490004E+01 9.000000E+01 5 9.201452E-05 -8.999413E+01 9.439129E-09 -9.201452E-05 + 3.490004E+01 9.000000E+01 6 3.697755E-06 1.799997E+02 -3.697755E-06 1.757481E-11 + 3.500004E+01 0.000000E+00 1 3.795351E+01 8.995336E+01 3.089688E-02 3.795350E+01 + 3.500004E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.500004E+01 0.000000E+00 3 1.920423E+02 2.023840E-01 1.920411E+02 6.783434E-01 + 3.500004E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.500004E+01 0.000000E+00 5 4.015163E+02 8.995336E+01 3.268485E-01 4.015162E+02 + 3.500004E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.500004E+01 3.000000E+01 1 3.294705E+01 8.995336E+01 2.682038E-02 3.294704E+01 + 3.500004E+01 3.000000E+01 2 2.010550E+01 8.994787E+01 1.829428E-02 2.010549E+01 + 3.500004E+01 3.000000E+01 3 1.925567E+02 2.026219E-01 1.925555E+02 6.809596E-01 + 3.500004E+01 3.000000E+01 4 6.491261E+01 8.994762E+01 5.934080E-02 6.491257E+01 + 3.500004E+01 3.000000E+01 5 3.485332E+02 8.995336E+01 2.837231E-01 3.485331E+02 + 3.500004E+01 3.000000E+01 6 4.262578E+01 -3.982828E-04 4.262578E+01 -2.963066E-04 + 3.500004E+01 6.000000E+01 1 1.911280E+01 8.995336E+01 1.555773E-02 1.911280E+01 + 3.500004E+01 6.000000E+01 2 3.500626E+01 8.994786E+01 3.185429E-02 3.500624E+01 + 3.500004E+01 6.000000E+01 3 1.935907E+02 2.030970E-01 1.935895E+02 6.862218E-01 + 3.500004E+01 6.000000E+01 4 1.135478E+02 8.994786E+01 1.033246E-01 1.135478E+02 + 3.500004E+01 6.000000E+01 5 2.021646E+02 8.995336E+01 1.645771E-01 2.021646E+02 + 3.500004E+01 6.000000E+01 6 4.285572E+01 -3.975577E-04 4.285572E+01 -2.973626E-04 + 3.500004E+01 9.000000E+01 1 1.978392E-06 -9.003528E+01 -1.218199E-09 -1.978391E-06 + 3.500004E+01 9.000000E+01 2 4.052742E+01 8.994786E+01 3.687941E-02 4.052741E+01 + 3.500004E+01 9.000000E+01 3 1.941088E+02 2.033347E-01 1.941076E+02 6.888635E-01 + 3.500004E+01 9.000000E+01 4 1.317611E+02 8.994798E+01 1.196246E-01 1.317610E+02 + 3.500004E+01 9.000000E+01 5 9.175624E-05 -8.999417E+01 9.340133E-09 -9.175624E-05 + 3.500004E+01 9.000000E+01 6 3.675732E-06 1.799997E+02 -3.675732E-06 1.725378E-11 + 3.510004E+01 0.000000E+00 1 3.784522E+01 8.995364E+01 3.062340E-02 3.784521E+01 + 3.510004E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.510004E+01 0.000000E+00 3 1.921323E+02 2.011986E-01 1.921311E+02 6.746861E-01 + 3.510004E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.510004E+01 0.000000E+00 5 4.005159E+02 8.995364E+01 3.240772E-01 4.005157E+02 + 3.510004E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.510004E+01 3.000000E+01 1 3.285258E+01 8.995364E+01 2.658270E-02 3.285257E+01 + 3.510004E+01 3.000000E+01 2 2.004789E+01 8.994820E+01 1.812631E-02 2.004788E+01 + 3.510004E+01 3.000000E+01 3 1.926437E+02 2.014320E-01 1.926425E+02 6.772668E-01 + 3.510004E+01 3.000000E+01 4 6.471822E+01 8.994796E+01 5.878688E-02 6.471820E+01 + 3.510004E+01 3.000000E+01 5 3.476617E+02 8.995364E+01 2.813121E-01 3.476616E+02 + 3.510004E+01 3.000000E+01 6 4.237505E+01 -3.933454E-04 4.237505E+01 -2.909121E-04 + 3.510004E+01 6.000000E+01 1 1.905746E+01 8.995364E+01 1.541935E-02 1.905745E+01 + 3.510004E+01 6.000000E+01 2 3.490485E+01 8.994820E+01 3.156079E-02 3.490484E+01 + 3.510004E+01 6.000000E+01 3 1.936721E+02 2.019015E-01 1.936709E+02 6.824692E-01 + 3.510004E+01 6.000000E+01 4 1.132020E+02 8.994820E+01 1.023572E-01 1.132019E+02 + 3.510004E+01 6.000000E+01 5 2.016539E+02 8.995364E+01 1.631736E-01 2.016539E+02 + 3.510004E+01 6.000000E+01 6 4.260228E+01 -3.926331E-04 4.260228E+01 -2.919424E-04 + 3.510004E+01 9.000000E+01 1 1.972597E-06 -9.003510E+01 -1.208441E-09 -1.972596E-06 + 3.510004E+01 9.000000E+01 2 4.040936E+01 8.994819E+01 3.653902E-02 4.040934E+01 + 3.510004E+01 9.000000E+01 3 1.941877E+02 2.021375E-01 1.941865E+02 6.850861E-01 + 3.510004E+01 9.000000E+01 4 1.313557E+02 8.994831E+01 1.185021E-01 1.313557E+02 + 3.510004E+01 9.000000E+01 5 9.149918E-05 -8.999421E+01 9.242510E-09 -9.149918E-05 + 3.510004E+01 9.000000E+01 6 3.653911E-06 1.799997E+02 -3.653911E-06 1.693964E-11 + 3.520004E+01 0.000000E+00 1 3.773761E+01 8.995391E+01 3.035335E-02 3.773759E+01 + 3.520004E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.520004E+01 0.000000E+00 3 1.922220E+02 2.000209E-01 1.922208E+02 6.710501E-01 + 3.520004E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.520004E+01 0.000000E+00 5 3.995221E+02 8.995392E+01 3.213328E-01 3.995220E+02 + 3.520004E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.520004E+01 3.000000E+01 1 3.275866E+01 8.995392E+01 2.634779E-02 3.275865E+01 + 3.520004E+01 3.000000E+01 2 1.999064E+01 8.994852E+01 1.796036E-02 1.999063E+01 + 3.520004E+01 3.000000E+01 3 1.927310E+02 2.002532E-01 1.927299E+02 6.736085E-01 + 3.520004E+01 3.000000E+01 4 6.452542E+01 8.994829E+01 5.823993E-02 6.452540E+01 + 3.520004E+01 3.000000E+01 5 3.467957E+02 8.995392E+01 2.789291E-01 3.467956E+02 + 3.520004E+01 3.000000E+01 6 4.212649E+01 -3.884865E-04 4.212649E+01 -2.856331E-04 + 3.520004E+01 6.000000E+01 1 1.900245E+01 8.995392E+01 1.528268E-02 1.900244E+01 + 3.520004E+01 6.000000E+01 2 3.480407E+01 8.994852E+01 3.127093E-02 3.480406E+01 + 3.520004E+01 6.000000E+01 3 1.937533E+02 2.007143E-01 1.937521E+02 6.787407E-01 + 3.520004E+01 6.000000E+01 4 1.128584E+02 8.994852E+01 1.014013E-01 1.128583E+02 + 3.520004E+01 6.000000E+01 5 2.011441E+02 8.995391E+01 1.617859E-01 2.011441E+02 + 3.520004E+01 6.000000E+01 6 4.235104E+01 -3.877869E-04 4.235104E+01 -2.866386E-04 + 3.520004E+01 9.000000E+01 1 1.966843E-06 -9.003492E+01 -1.198787E-09 -1.966843E-06 + 3.520004E+01 9.000000E+01 2 4.029213E+01 8.994852E+01 3.620280E-02 4.029211E+01 + 3.520004E+01 9.000000E+01 3 1.942664E+02 2.009482E-01 1.942653E+02 6.813314E-01 + 3.520004E+01 9.000000E+01 4 1.309527E+02 8.994864E+01 1.173940E-01 1.309526E+02 + 3.520004E+01 9.000000E+01 5 9.124355E-05 -8.999426E+01 9.146307E-09 -9.124355E-05 + 3.520004E+01 9.000000E+01 6 3.632280E-06 1.799997E+02 -3.632280E-06 1.663220E-11 + 3.530003E+01 0.000000E+00 1 3.763055E+01 8.995419E+01 3.008623E-02 3.763054E+01 + 3.530003E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.530003E+01 0.000000E+00 3 1.923106E+02 1.988533E-01 1.923095E+02 6.674405E-01 + 3.530003E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.530003E+01 0.000000E+00 5 3.985317E+02 8.995419E+01 3.186210E-01 3.985316E+02 + 3.530003E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.530003E+01 3.000000E+01 1 3.266527E+01 8.995419E+01 2.611567E-02 3.266526E+01 + 3.530003E+01 3.000000E+01 2 1.993369E+01 8.994884E+01 1.779652E-02 1.993368E+01 + 3.530003E+01 3.000000E+01 3 1.928163E+02 1.990832E-01 1.928151E+02 6.699691E-01 + 3.530003E+01 3.000000E+01 4 6.433378E+01 8.994862E+01 5.769991E-02 6.433376E+01 + 3.530003E+01 3.000000E+01 5 3.459283E+02 8.995419E+01 2.765716E-01 3.459282E+02 + 3.530003E+01 3.000000E+01 6 4.188017E+01 -3.837014E-04 4.188017E+01 -2.804653E-04 + 3.530003E+01 6.000000E+01 1 1.894780E+01 8.995419E+01 1.514764E-02 1.894779E+01 + 3.530003E+01 6.000000E+01 2 3.470378E+01 8.994884E+01 3.098455E-02 3.470377E+01 + 3.530003E+01 6.000000E+01 3 1.938325E+02 1.995412E-01 1.938313E+02 6.750494E-01 + 3.530003E+01 6.000000E+01 4 1.125162E+02 8.994884E+01 1.004579E-01 1.125162E+02 + 3.530003E+01 6.000000E+01 5 2.006375E+02 8.995419E+01 1.604136E-01 2.006374E+02 + 3.530003E+01 6.000000E+01 6 4.210201E+01 -3.830161E-04 4.210201E+01 -2.814473E-04 + 3.530003E+01 9.000000E+01 1 1.961117E-06 -9.003475E+01 -1.189225E-09 -1.961117E-06 + 3.530003E+01 9.000000E+01 2 4.017547E+01 8.994884E+01 3.587072E-02 4.017545E+01 + 3.530003E+01 9.000000E+01 3 1.943434E+02 1.997693E-01 1.943422E+02 6.776026E-01 + 3.530003E+01 9.000000E+01 4 1.305525E+02 8.994896E+01 1.162998E-01 1.305525E+02 + 3.530003E+01 9.000000E+01 5 9.098926E-05 -8.999430E+01 9.051415E-09 -9.098926E-05 + 3.530003E+01 9.000000E+01 6 3.610850E-06 1.799997E+02 -3.610850E-06 1.633129E-11 + 3.540003E+01 0.000000E+00 1 3.752418E+01 8.995447E+01 2.982253E-02 3.752417E+01 + 3.540003E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.540003E+01 0.000000E+00 3 1.923982E+02 1.976994E-01 1.923971E+02 6.638698E-01 + 3.540003E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.540003E+01 0.000000E+00 5 3.975461E+02 8.995447E+01 3.159379E-01 3.975459E+02 + 3.540003E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.540003E+01 3.000000E+01 1 3.257248E+01 8.995447E+01 2.588621E-02 3.257247E+01 + 3.540003E+01 3.000000E+01 2 1.987711E+01 8.994917E+01 1.763467E-02 1.987710E+01 + 3.540003E+01 3.000000E+01 3 1.929014E+02 1.979246E-01 1.929002E+02 6.663642E-01 + 3.540003E+01 3.000000E+01 4 6.414345E+01 8.994894E+01 5.716662E-02 6.414342E+01 + 3.540003E+01 3.000000E+01 5 3.450691E+02 8.995447E+01 2.742382E-01 3.450690E+02 + 3.540003E+01 3.000000E+01 6 4.163603E+01 -3.789929E-04 4.163603E+01 -2.754088E-04 + 3.540003E+01 6.000000E+01 1 1.889341E+01 8.995447E+01 1.501421E-02 1.889340E+01 + 3.540003E+01 6.000000E+01 2 3.460426E+01 8.994917E+01 3.070184E-02 3.460424E+01 + 3.540003E+01 6.000000E+01 3 1.939129E+02 1.983769E-01 1.939117E+02 6.713892E-01 + 3.540003E+01 6.000000E+01 4 1.121770E+02 8.994917E+01 9.952672E-02 1.121769E+02 + 3.540003E+01 6.000000E+01 5 2.001317E+02 8.995447E+01 1.590576E-01 2.001316E+02 + 3.540003E+01 6.000000E+01 6 4.185524E+01 -3.783190E-04 4.185524E+01 -2.763665E-04 + 3.540003E+01 9.000000E+01 1 1.955424E-06 -9.003457E+01 -1.179767E-09 -1.955423E-06 + 3.540003E+01 9.000000E+01 2 4.005956E+01 8.994917E+01 3.554284E-02 4.005954E+01 + 3.540003E+01 9.000000E+01 3 1.944197E+02 1.986047E-01 1.944185E+02 6.739168E-01 + 3.540003E+01 9.000000E+01 4 1.301551E+02 8.994928E+01 1.152196E-01 1.301550E+02 + 3.540003E+01 9.000000E+01 5 9.073657E-05 -8.999434E+01 8.957885E-09 -9.073657E-05 + 3.540003E+01 9.000000E+01 6 3.589610E-06 1.799997E+02 -3.589610E-06 1.603677E-11 + 3.550003E+01 0.000000E+00 1 3.741840E+01 8.995473E+01 2.956179E-02 3.741839E+01 + 3.550003E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.550003E+01 0.000000E+00 3 1.924855E+02 1.965533E-01 1.924844E+02 6.603207E-01 + 3.550003E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.550003E+01 0.000000E+00 5 3.965663E+02 8.995474E+01 3.132882E-01 3.965662E+02 + 3.550003E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.550003E+01 3.000000E+01 1 3.248018E+01 8.995474E+01 2.565960E-02 3.248017E+01 + 3.550003E+01 3.000000E+01 2 1.982079E+01 8.994949E+01 1.747475E-02 1.982078E+01 + 3.550003E+01 3.000000E+01 3 1.929865E+02 1.967766E-01 1.929853E+02 6.627911E-01 + 3.550003E+01 3.000000E+01 4 6.395364E+01 8.994926E+01 5.664000E-02 6.395361E+01 + 3.550003E+01 3.000000E+01 5 3.442131E+02 8.995473E+01 2.719341E-01 3.442130E+02 + 3.550003E+01 3.000000E+01 6 4.139398E+01 -3.743564E-04 4.139398E+01 -2.704580E-04 + 3.550003E+01 6.000000E+01 1 1.883936E+01 8.995474E+01 1.488230E-02 1.883935E+01 + 3.550003E+01 6.000000E+01 2 3.450518E+01 8.994949E+01 3.042253E-02 3.450517E+01 + 3.550003E+01 6.000000E+01 3 1.939920E+02 1.972226E-01 1.939909E+02 6.677548E-01 + 3.550003E+01 6.000000E+01 4 1.118389E+02 8.994949E+01 9.860662E-02 1.118388E+02 + 3.550003E+01 6.000000E+01 5 1.996325E+02 8.995473E+01 1.577173E-01 1.996324E+02 + 3.550003E+01 6.000000E+01 6 4.161071E+01 -3.736948E-04 4.161071E+01 -2.713936E-04 + 3.550003E+01 9.000000E+01 1 1.949764E-06 -9.003439E+01 -1.170405E-09 -1.949764E-06 + 3.550003E+01 9.000000E+01 2 3.994423E+01 8.994948E+01 3.521904E-02 3.994421E+01 + 3.550003E+01 9.000000E+01 3 1.944955E+02 1.974477E-01 1.944943E+02 6.702519E-01 + 3.550003E+01 9.000000E+01 4 1.297594E+02 8.994960E+01 1.141529E-01 1.297593E+02 + 3.550003E+01 9.000000E+01 5 9.048496E-05 -8.999439E+01 8.865646E-09 -9.048496E-05 + 3.550003E+01 9.000000E+01 6 3.568554E-06 1.799997E+02 -3.568554E-06 1.574851E-11 + 3.560003E+01 0.000000E+00 1 3.731315E+01 8.995501E+01 2.930408E-02 3.731314E+01 + 3.560003E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.560003E+01 0.000000E+00 3 1.925725E+02 1.954165E-01 1.925714E+02 6.567985E-01 + 3.560003E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.560003E+01 0.000000E+00 5 3.955910E+02 8.995501E+01 3.106649E-01 3.955909E+02 + 3.560003E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.560003E+01 3.000000E+01 1 3.238846E+01 8.995501E+01 2.543555E-02 3.238845E+01 + 3.560003E+01 3.000000E+01 2 1.976484E+01 8.994980E+01 1.731684E-02 1.976483E+01 + 3.560003E+01 3.000000E+01 3 1.930702E+02 1.956372E-01 1.930690E+02 6.592395E-01 + 3.560003E+01 3.000000E+01 4 6.376530E+01 8.994958E+01 5.611995E-02 6.376528E+01 + 3.560003E+01 3.000000E+01 5 3.433607E+02 8.995501E+01 2.696547E-01 3.433606E+02 + 3.560003E+01 3.000000E+01 6 4.115409E+01 -3.697917E-04 4.115409E+01 -2.656119E-04 + 3.560003E+01 6.000000E+01 1 1.878559E+01 8.995501E+01 1.475204E-02 1.878558E+01 + 3.560003E+01 6.000000E+01 2 3.440669E+01 8.994980E+01 3.014669E-02 3.440668E+01 + 3.560003E+01 6.000000E+01 3 1.940701E+02 1.960781E-01 1.940690E+02 6.641473E-01 + 3.560003E+01 6.000000E+01 4 1.115035E+02 8.994980E+01 9.769826E-02 1.115035E+02 + 3.560003E+01 6.000000E+01 5 1.991318E+02 8.995501E+01 1.563908E-01 1.991317E+02 + 3.560003E+01 6.000000E+01 6 4.136828E+01 -3.691419E-04 4.136828E+01 -2.665252E-04 + 3.560003E+01 9.000000E+01 1 1.944139E-06 -9.003423E+01 -1.161135E-09 -1.944139E-06 + 3.560003E+01 9.000000E+01 2 3.982970E+01 8.994980E+01 3.489913E-02 3.982968E+01 + 3.560003E+01 9.000000E+01 3 1.945722E+02 1.962985E-01 1.945710E+02 6.666135E-01 + 3.560003E+01 9.000000E+01 4 1.293665E+02 8.994991E+01 1.130998E-01 1.293664E+02 + 3.560003E+01 9.000000E+01 5 9.023506E-05 -8.999443E+01 8.774662E-09 -9.023506E-05 + 3.560003E+01 9.000000E+01 6 3.547692E-06 1.799997E+02 -3.547692E-06 1.546635E-11 + 3.570003E+01 0.000000E+00 1 3.720853E+01 8.995527E+01 2.904937E-02 3.720852E+01 + 3.570003E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.570003E+01 0.000000E+00 3 1.926582E+02 1.942910E-01 1.926571E+02 6.533061E-01 + 3.570003E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.570003E+01 0.000000E+00 5 3.946154E+02 8.995527E+01 3.080730E-01 3.946153E+02 + 3.570003E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.570003E+01 3.000000E+01 1 3.229712E+01 8.995527E+01 2.521421E-02 3.229711E+01 + 3.570003E+01 3.000000E+01 2 1.970915E+01 8.995012E+01 1.716087E-02 1.970914E+01 + 3.570003E+01 3.000000E+01 3 1.931540E+02 1.945079E-01 1.931529E+02 6.557187E-01 + 3.570003E+01 3.000000E+01 4 6.357809E+01 8.994989E+01 5.560630E-02 6.357807E+01 + 3.570003E+01 3.000000E+01 5 3.425139E+02 8.995527E+01 2.673998E-01 3.425138E+02 + 3.570003E+01 3.000000E+01 6 4.091636E+01 -3.652969E-04 4.091636E+01 -2.608677E-04 + 3.570003E+01 6.000000E+01 1 1.873211E+01 8.995527E+01 1.462321E-02 1.873211E+01 + 3.570003E+01 6.000000E+01 2 3.430878E+01 8.995011E+01 2.987421E-02 3.430877E+01 + 3.570003E+01 6.000000E+01 3 1.941476E+02 1.949451E-01 1.941465E+02 6.605732E-01 + 3.570003E+01 6.000000E+01 4 1.111703E+02 8.995011E+01 9.680121E-02 1.111702E+02 + 3.570003E+01 6.000000E+01 5 1.986332E+02 8.995527E+01 1.550790E-01 1.986331E+02 + 3.570003E+01 6.000000E+01 6 4.112794E+01 -3.646594E-04 4.112794E+01 -2.617591E-04 + 3.570003E+01 9.000000E+01 1 1.938544E-06 -9.003404E+01 -1.151964E-09 -1.938543E-06 + 3.570003E+01 9.000000E+01 2 3.971572E+01 8.995011E+01 3.458322E-02 3.971570E+01 + 3.570003E+01 9.000000E+01 3 1.946469E+02 1.951629E-01 1.946458E+02 6.630120E-01 + 3.570003E+01 9.000000E+01 4 1.289766E+02 8.995022E+01 1.120595E-01 1.289766E+02 + 3.570003E+01 9.000000E+01 5 8.998632E-05 -8.999447E+01 8.684960E-09 -8.998632E-05 + 3.570003E+01 9.000000E+01 6 3.527016E-06 1.799998E+02 -3.527016E-06 1.519010E-11 + 3.580003E+01 0.000000E+00 1 3.710444E+01 8.995554E+01 2.879764E-02 3.710443E+01 + 3.580003E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.580003E+01 0.000000E+00 3 1.927434E+02 1.931735E-01 1.927423E+02 6.498357E-01 + 3.580003E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.580003E+01 0.000000E+00 5 3.936500E+02 8.995554E+01 3.055085E-01 3.936499E+02 + 3.580003E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.580003E+01 3.000000E+01 1 3.220644E+01 8.995554E+01 2.499547E-02 3.220643E+01 + 3.580003E+01 3.000000E+01 2 1.965380E+01 8.995042E+01 1.700681E-02 1.965379E+01 + 3.580003E+01 3.000000E+01 3 1.932356E+02 1.933892E-01 1.932345E+02 6.522228E-01 + 3.580003E+01 3.000000E+01 4 6.339210E+01 8.995020E+01 5.509906E-02 6.339207E+01 + 3.580003E+01 3.000000E+01 5 3.416677E+02 8.995554E+01 2.651704E-01 3.416676E+02 + 3.580003E+01 3.000000E+01 6 4.068060E+01 -3.608723E-04 4.068060E+01 -2.562231E-04 + 3.580003E+01 6.000000E+01 1 1.867904E+01 8.995554E+01 1.449593E-02 1.867904E+01 + 3.580003E+01 6.000000E+01 2 3.421143E+01 8.995042E+01 2.960512E-02 3.421142E+01 + 3.580003E+01 6.000000E+01 3 1.942248E+02 1.938199E-01 1.942237E+02 6.570213E-01 + 3.580003E+01 6.000000E+01 4 1.108390E+02 8.995042E+01 9.591527E-02 1.108389E+02 + 3.580003E+01 6.000000E+01 5 1.981366E+02 8.995554E+01 1.537814E-01 1.981365E+02 + 3.580003E+01 6.000000E+01 6 4.088980E+01 -3.602456E-04 4.088980E+01 -2.570935E-04 + 3.580003E+01 9.000000E+01 1 1.932983E-06 -9.003387E+01 -1.142886E-09 -1.932982E-06 + 3.580003E+01 9.000000E+01 2 3.960241E+01 8.995042E+01 3.427111E-02 3.960239E+01 + 3.580003E+01 9.000000E+01 3 1.947211E+02 1.940352E-01 1.947200E+02 6.594324E-01 + 3.580003E+01 9.000000E+01 4 1.285885E+02 8.995052E+01 1.110324E-01 1.285885E+02 + 3.580003E+01 9.000000E+01 5 8.973895E-05 -8.999451E+01 8.596469E-09 -8.973895E-05 + 3.580003E+01 9.000000E+01 6 3.506517E-06 1.799998E+02 -3.506517E-06 1.491962E-11 + 3.590002E+01 0.000000E+00 1 3.700101E+01 8.995580E+01 2.854883E-02 3.700100E+01 + 3.590002E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.590002E+01 0.000000E+00 3 1.928284E+02 1.920665E-01 1.928274E+02 6.463969E-01 + 3.590002E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.590002E+01 0.000000E+00 5 3.926839E+02 8.995580E+01 3.029725E-01 3.926838E+02 + 3.590002E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.590002E+01 3.000000E+01 1 3.211624E+01 8.995580E+01 2.477914E-02 3.211623E+01 + 3.590002E+01 3.000000E+01 2 1.959876E+01 8.995073E+01 1.685455E-02 1.959876E+01 + 3.590002E+01 3.000000E+01 3 1.933183E+02 1.922779E-01 1.933172E+02 6.487524E-01 + 3.590002E+01 3.000000E+01 4 6.320710E+01 8.995052E+01 5.459804E-02 6.320708E+01 + 3.590002E+01 3.000000E+01 5 3.408278E+02 8.995580E+01 2.629664E-01 3.408277E+02 + 3.590002E+01 3.000000E+01 6 4.044693E+01 -3.565148E-04 4.044693E+01 -2.516752E-04 + 3.590002E+01 6.000000E+01 1 1.862624E+01 8.995580E+01 1.437013E-02 1.862623E+01 + 3.590002E+01 6.000000E+01 2 3.411459E+01 8.995072E+01 2.933923E-02 3.411458E+01 + 3.590002E+01 6.000000E+01 3 1.943020E+02 1.927044E-01 1.943009E+02 6.534997E-01 + 3.590002E+01 6.000000E+01 4 1.105094E+02 8.995072E+01 9.504028E-02 1.105094E+02 + 3.590002E+01 6.000000E+01 5 1.976456E+02 8.995580E+01 1.524990E-01 1.976455E+02 + 3.590002E+01 6.000000E+01 6 4.065371E+01 -3.558997E-04 4.065371E+01 -2.525255E-04 + 3.590002E+01 9.000000E+01 1 1.927459E-06 -9.003371E+01 -1.133897E-09 -1.927459E-06 + 3.590002E+01 9.000000E+01 2 3.948977E+01 8.995072E+01 3.396285E-02 3.948975E+01 + 3.590002E+01 9.000000E+01 3 1.947946E+02 1.929185E-01 1.947935E+02 6.558845E-01 + 3.590002E+01 9.000000E+01 4 1.282025E+02 8.995084E+01 1.100178E-01 1.282025E+02 + 3.590002E+01 9.000000E+01 5 8.949287E-05 -8.999455E+01 8.509219E-09 -8.949287E-05 + 3.590002E+01 9.000000E+01 6 3.486200E-06 1.799998E+02 -3.486200E-06 1.465479E-11 + 3.600002E+01 0.000000E+00 1 3.689823E+01 8.995605E+01 2.830295E-02 3.689822E+01 + 3.600002E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.600002E+01 0.000000E+00 3 1.929125E+02 1.909696E-01 1.929114E+02 6.429854E-01 + 3.600002E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.600002E+01 0.000000E+00 5 3.917276E+02 8.995605E+01 3.004604E-01 3.917275E+02 + 3.600002E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.600002E+01 3.000000E+01 1 3.202650E+01 8.995605E+01 2.456541E-02 3.202649E+01 + 3.600002E+01 3.000000E+01 2 1.954401E+01 8.995103E+01 1.670416E-02 1.954401E+01 + 3.600002E+01 3.000000E+01 3 1.933998E+02 1.911795E-01 1.933987E+02 6.453182E-01 + 3.600002E+01 3.000000E+01 4 6.302334E+01 8.995081E+01 5.410337E-02 6.302332E+01 + 3.600002E+01 3.000000E+01 5 3.399887E+02 8.995605E+01 2.607855E-01 3.399886E+02 + 3.600002E+01 3.000000E+01 6 4.021523E+01 -3.522242E-04 4.021523E+01 -2.472220E-04 + 3.600002E+01 6.000000E+01 1 1.857365E+01 8.995605E+01 1.424583E-02 1.857364E+01 + 3.600002E+01 6.000000E+01 2 3.401836E+01 8.995103E+01 2.907652E-02 3.401834E+01 + 3.600002E+01 6.000000E+01 3 1.943775E+02 1.916006E-01 1.943764E+02 6.500092E-01 + 3.600002E+01 6.000000E+01 4 1.101818E+02 8.995103E+01 9.417623E-02 1.101818E+02 + 3.600002E+01 6.000000E+01 5 1.971542E+02 8.995605E+01 1.512313E-01 1.971541E+02 + 3.600002E+01 6.000000E+01 6 4.041957E+01 -3.516201E-04 4.041957E+01 -2.480520E-04 + 3.600002E+01 9.000000E+01 1 1.921960E-06 -9.003354E+01 -1.125001E-09 -1.921960E-06 + 3.600002E+01 9.000000E+01 2 3.937778E+01 8.995103E+01 3.365833E-02 3.937777E+01 + 3.600002E+01 9.000000E+01 3 1.948680E+02 1.918119E-01 1.948669E+02 6.523678E-01 + 3.600002E+01 9.000000E+01 4 1.278193E+02 8.995113E+01 1.090161E-01 1.278193E+02 + 3.600002E+01 9.000000E+01 5 8.924866E-05 -8.999459E+01 8.423156E-09 -8.924866E-05 + 3.600002E+01 9.000000E+01 6 3.466062E-06 1.799998E+02 -3.466062E-06 1.439546E-11 + 3.610002E+01 0.000000E+00 1 3.679582E+01 8.995631E+01 2.805987E-02 3.679581E+01 + 3.610002E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.610002E+01 0.000000E+00 3 1.929950E+02 1.898817E-01 1.929939E+02 6.395960E-01 + 3.610002E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.610002E+01 0.000000E+00 5 3.907667E+02 8.995631E+01 2.979841E-01 3.907665E+02 + 3.610002E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.610002E+01 3.000000E+01 1 3.193724E+01 8.995631E+01 2.435412E-02 3.193723E+01 + 3.610002E+01 3.000000E+01 2 1.948962E+01 8.995133E+01 1.655562E-02 1.948961E+01 + 3.610002E+01 3.000000E+01 3 1.934799E+02 1.900889E-01 1.934788E+02 6.419027E-01 + 3.610002E+01 3.000000E+01 4 6.284051E+01 8.995112E+01 5.361466E-02 6.284049E+01 + 3.610002E+01 3.000000E+01 5 3.391558E+02 8.995631E+01 2.586276E-01 3.391557E+02 + 3.610002E+01 3.000000E+01 6 3.998563E+01 -3.479987E-04 3.998563E+01 -2.428617E-04 + 3.610002E+01 6.000000E+01 1 1.852148E+01 8.995631E+01 1.412293E-02 1.852147E+01 + 3.610002E+01 6.000000E+01 2 3.392264E+01 8.995133E+01 2.881715E-02 3.392263E+01 + 3.610002E+01 6.000000E+01 3 1.944521E+02 1.905053E-01 1.944511E+02 6.465414E-01 + 3.610002E+01 6.000000E+01 4 1.098569E+02 8.995133E+01 9.332321E-02 1.098569E+02 + 3.610002E+01 6.000000E+01 5 1.966663E+02 8.995631E+01 1.499770E-01 1.966662E+02 + 3.610002E+01 6.000000E+01 6 4.018764E+01 -3.474052E-04 4.018764E+01 -2.436724E-04 + 3.610002E+01 9.000000E+01 1 1.916497E-06 -9.003337E+01 -1.116193E-09 -1.916497E-06 + 3.610002E+01 9.000000E+01 2 3.926650E+01 8.995132E+01 3.335751E-02 3.926648E+01 + 3.610002E+01 9.000000E+01 3 1.949404E+02 1.907122E-01 1.949393E+02 6.488689E-01 + 3.610002E+01 9.000000E+01 4 1.274387E+02 8.995143E+01 1.080264E-01 1.274386E+02 + 3.610002E+01 9.000000E+01 5 8.900501E-05 -8.999464E+01 8.338271E-09 -8.900501E-05 + 3.610002E+01 9.000000E+01 6 3.446104E-06 1.799998E+02 -3.446104E-06 1.414156E-11 + 3.620002E+01 0.000000E+00 1 3.669408E+01 8.995657E+01 2.781959E-02 3.669407E+01 + 3.620002E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.620002E+01 0.000000E+00 3 1.930782E+02 1.888036E-01 1.930771E+02 6.362386E-01 + 3.620002E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.620002E+01 0.000000E+00 5 3.898209E+02 8.995657E+01 2.955300E-01 3.898207E+02 + 3.620002E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.620002E+01 3.000000E+01 1 3.184851E+01 8.995657E+01 2.414526E-02 3.184850E+01 + 3.620002E+01 3.000000E+01 2 1.943553E+01 8.995162E+01 1.640883E-02 1.943553E+01 + 3.620002E+01 3.000000E+01 3 1.935594E+02 1.890092E-01 1.935584E+02 6.385192E-01 + 3.620002E+01 3.000000E+01 4 6.265878E+01 8.995142E+01 5.313190E-02 6.265875E+01 + 3.620002E+01 3.000000E+01 5 3.383251E+02 8.995657E+01 2.564960E-01 3.383250E+02 + 3.620002E+01 3.000000E+01 6 3.975798E+01 -3.438369E-04 3.975798E+01 -2.385911E-04 + 3.620002E+01 6.000000E+01 1 1.846953E+01 8.995657E+01 1.400147E-02 1.846952E+01 + 3.620002E+01 6.000000E+01 2 3.382750E+01 8.995162E+01 2.856081E-02 3.382749E+01 + 3.620002E+01 6.000000E+01 3 1.945269E+02 1.894189E-01 1.945258E+02 6.431016E-01 + 3.620002E+01 6.000000E+01 4 1.095331E+02 8.995162E+01 9.247953E-02 1.095331E+02 + 3.620002E+01 6.000000E+01 5 1.961805E+02 8.995657E+01 1.487358E-01 1.961804E+02 + 3.620002E+01 6.000000E+01 6 3.995770E+01 -3.432540E-04 3.995770E+01 -2.393830E-04 + 3.620002E+01 9.000000E+01 1 1.911062E-06 -9.003320E+01 -1.107475E-09 -1.911062E-06 + 3.620002E+01 9.000000E+01 2 3.915574E+01 8.995162E+01 3.306032E-02 3.915572E+01 + 3.620002E+01 9.000000E+01 3 1.950125E+02 1.896253E-01 1.950114E+02 6.454095E-01 + 3.620002E+01 9.000000E+01 4 1.270602E+02 8.995173E+01 1.070489E-01 1.270602E+02 + 3.620002E+01 9.000000E+01 5 8.876305E-05 -8.999467E+01 8.254527E-09 -8.876305E-05 + 3.620002E+01 9.000000E+01 6 3.426316E-06 1.799998E+02 -3.426316E-06 1.389287E-11 + 3.630002E+01 0.000000E+00 1 3.659297E+01 8.995682E+01 2.758211E-02 3.659296E+01 + 3.630002E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.630002E+01 0.000000E+00 3 1.931599E+02 1.877341E-01 1.931589E+02 6.329024E-01 + 3.630002E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.630002E+01 0.000000E+00 5 3.888706E+02 8.995682E+01 2.931029E-01 3.888705E+02 + 3.630002E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.630002E+01 3.000000E+01 1 3.176025E+01 8.995682E+01 2.393882E-02 3.176024E+01 + 3.630002E+01 3.000000E+01 2 1.938172E+01 8.995193E+01 1.626377E-02 1.938171E+01 + 3.630002E+01 3.000000E+01 3 1.936391E+02 1.879366E-01 1.936380E+02 6.351566E-01 + 3.630002E+01 3.000000E+01 4 6.247813E+01 8.995171E+01 5.265464E-02 6.247811E+01 + 3.630002E+01 3.000000E+01 5 3.375006E+02 8.995682E+01 2.543879E-01 3.375005E+02 + 3.630002E+01 3.000000E+01 6 3.953231E+01 -3.397380E-04 3.953231E+01 -2.344087E-04 + 3.630002E+01 6.000000E+01 1 1.841787E+01 8.995682E+01 1.388142E-02 1.841787E+01 + 3.630002E+01 6.000000E+01 2 3.373294E+01 8.995192E+01 2.830754E-02 3.373293E+01 + 3.630002E+01 6.000000E+01 3 1.946010E+02 1.883430E-01 1.946000E+02 6.396926E-01 + 3.630002E+01 6.000000E+01 4 1.092118E+02 8.995192E+01 9.164707E-02 1.092118E+02 + 3.630002E+01 6.000000E+01 5 1.956963E+02 8.995682E+01 1.475096E-01 1.956962E+02 + 3.630002E+01 6.000000E+01 6 3.972966E+01 -3.391659E-04 3.972966E+01 -2.351822E-04 + 3.630002E+01 9.000000E+01 1 1.905662E-06 -9.003304E+01 -1.098845E-09 -1.905662E-06 + 3.630002E+01 9.000000E+01 2 3.904569E+01 8.995192E+01 3.276663E-02 3.904568E+01 + 3.630002E+01 9.000000E+01 3 1.950837E+02 1.885462E-01 1.950827E+02 6.419712E-01 + 3.630002E+01 9.000000E+01 4 1.266842E+02 8.995202E+01 1.060835E-01 1.266842E+02 + 3.630002E+01 9.000000E+01 5 8.852229E-05 -8.999471E+01 8.171919E-09 -8.852229E-05 + 3.630002E+01 9.000000E+01 6 3.406700E-06 1.799998E+02 -3.406700E-06 1.364934E-11 + 3.640002E+01 0.000000E+00 1 3.649230E+01 8.995706E+01 2.734727E-02 3.649229E+01 + 3.640002E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.640002E+01 0.000000E+00 3 1.932409E+02 1.866754E-01 1.932399E+02 6.295972E-01 + 3.640002E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.640002E+01 0.000000E+00 5 3.879283E+02 8.995706E+01 2.907011E-01 3.879281E+02 + 3.640002E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.640002E+01 3.000000E+01 1 3.167256E+01 8.995706E+01 2.373479E-02 3.167255E+01 + 3.640002E+01 3.000000E+01 2 1.932821E+01 8.995221E+01 1.612047E-02 1.932820E+01 + 3.640002E+01 3.000000E+01 3 1.937179E+02 1.868748E-01 1.937168E+02 6.318254E-01 + 3.640002E+01 3.000000E+01 4 6.229844E+01 8.995201E+01 5.218397E-02 6.229842E+01 + 3.640002E+01 3.000000E+01 5 3.366772E+02 8.995706E+01 2.522999E-01 3.366771E+02 + 3.640002E+01 3.000000E+01 6 3.930856E+01 -3.357013E-04 3.930856E+01 -2.303125E-04 + 3.640002E+01 6.000000E+01 1 1.836656E+01 8.995707E+01 1.376274E-02 1.836655E+01 + 3.640002E+01 6.000000E+01 2 3.363881E+01 8.995221E+01 2.805732E-02 3.363880E+01 + 3.640002E+01 6.000000E+01 3 1.946739E+02 1.872777E-01 1.946728E+02 6.363124E-01 + 3.640002E+01 6.000000E+01 4 1.088920E+02 8.995221E+01 9.082424E-02 1.088919E+02 + 3.640002E+01 6.000000E+01 5 1.952157E+02 8.995706E+01 1.462976E-01 1.952156E+02 + 3.640002E+01 6.000000E+01 6 3.950373E+01 -3.351382E-04 3.950373E+01 -2.310678E-04 + 3.640002E+01 9.000000E+01 1 1.900292E-06 -9.003288E+01 -1.090306E-09 -1.900291E-06 + 3.640002E+01 9.000000E+01 2 3.893615E+01 8.995221E+01 3.247654E-02 3.893613E+01 + 3.640002E+01 9.000000E+01 3 1.951549E+02 1.874767E-01 1.951539E+02 6.385625E-01 + 3.640002E+01 9.000000E+01 4 1.263099E+02 8.995232E+01 1.051301E-01 1.263099E+02 + 3.640002E+01 9.000000E+01 5 8.828314E-05 -8.999475E+01 8.090429E-09 -8.828314E-05 + 3.640002E+01 9.000000E+01 6 3.387258E-06 1.799998E+02 -3.387258E-06 1.341080E-11 + 3.650002E+01 0.000000E+00 1 3.639219E+01 8.995731E+01 2.711521E-02 3.639218E+01 + 3.650002E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.650002E+01 0.000000E+00 3 1.933211E+02 1.856236E-01 1.933201E+02 6.263095E-01 + 3.650002E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.650002E+01 0.000000E+00 5 3.869905E+02 8.995731E+01 2.883295E-01 3.869904E+02 + 3.650002E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.650002E+01 3.000000E+01 1 3.158527E+01 8.995731E+01 2.353300E-02 3.158526E+01 + 3.650002E+01 3.000000E+01 2 1.927492E+01 8.995251E+01 1.597885E-02 1.927491E+01 + 3.650002E+01 3.000000E+01 3 1.937955E+02 1.858225E-01 1.937944E+02 6.285192E-01 + 3.650002E+01 3.000000E+01 4 6.212008E+01 8.995230E+01 5.171850E-02 6.212006E+01 + 3.650002E+01 3.000000E+01 5 3.358566E+02 8.995731E+01 2.502373E-01 3.358565E+02 + 3.650002E+01 3.000000E+01 6 3.908673E+01 -3.317248E-04 3.908673E+01 -2.263001E-04 + 3.650002E+01 6.000000E+01 1 1.831544E+01 8.995731E+01 1.364543E-02 1.831544E+01 + 3.650002E+01 6.000000E+01 2 3.354522E+01 8.995250E+01 2.781012E-02 3.354521E+01 + 3.650002E+01 6.000000E+01 3 1.947467E+02 1.862186E-01 1.947456E+02 6.329504E-01 + 3.650002E+01 6.000000E+01 4 1.085748E+02 8.995250E+01 9.001180E-02 1.085747E+02 + 3.650002E+01 6.000000E+01 5 1.947344E+02 8.995731E+01 1.450961E-01 1.947343E+02 + 3.650002E+01 6.000000E+01 6 3.927964E+01 -3.311723E-04 3.927964E+01 -2.270382E-04 + 3.650002E+01 9.000000E+01 1 1.894949E-06 -9.003271E+01 -1.081844E-09 -1.894949E-06 + 3.650002E+01 9.000000E+01 2 3.882741E+01 8.995250E+01 3.218987E-02 3.882740E+01 + 3.650002E+01 9.000000E+01 3 1.952245E+02 1.864177E-01 1.952235E+02 6.351821E-01 + 3.650002E+01 9.000000E+01 4 1.259385E+02 8.995260E+01 1.041880E-01 1.259385E+02 + 3.650002E+01 9.000000E+01 5 8.804460E-05 -8.999478E+01 8.010020E-09 -8.804460E-05 + 3.650002E+01 9.000000E+01 6 3.367978E-06 1.799998E+02 -3.367978E-06 1.317715E-11 + 3.660001E+01 0.000000E+00 1 3.629268E+01 8.995756E+01 2.688573E-02 3.629267E+01 + 3.660001E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.660001E+01 0.000000E+00 3 1.934017E+02 1.845804E-01 1.934007E+02 6.230494E-01 + 3.660001E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.660001E+01 0.000000E+00 5 3.860558E+02 8.995756E+01 2.859814E-01 3.860557E+02 + 3.660001E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.660001E+01 3.000000E+01 1 3.149850E+01 8.995756E+01 2.333347E-02 3.149849E+01 + 3.660001E+01 3.000000E+01 2 1.922201E+01 8.995279E+01 1.583892E-02 1.922200E+01 + 3.660001E+01 3.000000E+01 3 1.938728E+02 1.847774E-01 1.938718E+02 6.252338E-01 + 3.660001E+01 3.000000E+01 4 6.194261E+01 8.995259E+01 5.125874E-02 6.194259E+01 + 3.660001E+01 3.000000E+01 5 3.350448E+02 8.995756E+01 2.481959E-01 3.350447E+02 + 3.660001E+01 3.000000E+01 6 3.886675E+01 -3.278083E-04 3.886675E+01 -2.223697E-04 + 3.660001E+01 6.000000E+01 1 1.826464E+01 8.995756E+01 1.352943E-02 1.826464E+01 + 3.660001E+01 6.000000E+01 2 3.345223E+01 8.995279E+01 2.756577E-02 3.345222E+01 + 3.660001E+01 6.000000E+01 3 1.948195E+02 1.851693E-01 1.948185E+02 6.296191E-01 + 3.660001E+01 6.000000E+01 4 1.082585E+02 8.995279E+01 8.920918E-02 1.082584E+02 + 3.660001E+01 6.000000E+01 5 1.942572E+02 8.995756E+01 1.439083E-01 1.942571E+02 + 3.660001E+01 6.000000E+01 6 3.905750E+01 -3.272648E-04 3.905750E+01 -2.230905E-04 + 3.660001E+01 9.000000E+01 1 1.889641E-06 -9.003255E+01 -1.073472E-09 -1.889641E-06 + 3.660001E+01 9.000000E+01 2 3.871917E+01 8.995279E+01 3.190666E-02 3.871916E+01 + 3.660001E+01 9.000000E+01 3 1.952944E+02 1.853659E-01 1.952933E+02 6.318239E-01 + 3.660001E+01 9.000000E+01 4 1.255691E+02 8.995289E+01 1.032575E-01 1.255690E+02 + 3.660001E+01 9.000000E+01 5 8.780773E-05 -8.999483E+01 7.930714E-09 -8.780773E-05 + 3.660001E+01 9.000000E+01 6 3.348868E-06 1.799998E+02 -3.348868E-06 1.294828E-11 + 3.670001E+01 0.000000E+00 1 3.619368E+01 8.995780E+01 2.665881E-02 3.619366E+01 + 3.670001E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.670001E+01 0.000000E+00 3 1.934808E+02 1.835479E-01 1.934798E+02 6.198175E-01 + 3.670001E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.670001E+01 0.000000E+00 5 3.851220E+02 8.995780E+01 2.836561E-01 3.851219E+02 + 3.670001E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.670001E+01 3.000000E+01 1 3.141212E+01 8.995780E+01 2.313636E-02 3.141212E+01 + 3.670001E+01 3.000000E+01 2 1.916936E+01 8.995307E+01 1.570067E-02 1.916935E+01 + 3.670001E+01 3.000000E+01 3 1.939490E+02 1.837421E-01 1.939480E+02 6.219749E-01 + 3.670001E+01 3.000000E+01 4 6.176599E+01 8.995287E+01 5.080429E-02 6.176597E+01 + 3.670001E+01 3.000000E+01 5 3.342333E+02 8.995780E+01 2.461769E-01 3.342332E+02 + 3.670001E+01 3.000000E+01 6 3.864867E+01 -3.239498E-04 3.864867E+01 -2.185192E-04 + 3.670001E+01 6.000000E+01 1 1.821420E+01 8.995780E+01 1.341476E-02 1.821419E+01 + 3.670001E+01 6.000000E+01 2 3.335966E+01 8.995307E+01 2.732434E-02 3.335965E+01 + 3.670001E+01 6.000000E+01 3 1.948910E+02 1.841283E-01 1.948900E+02 6.263096E-01 + 3.670001E+01 6.000000E+01 4 1.079451E+02 8.995307E+01 8.841609E-02 1.079451E+02 + 3.670001E+01 6.000000E+01 5 1.937811E+02 8.995780E+01 1.427354E-01 1.937810E+02 + 3.670001E+01 6.000000E+01 6 3.883728E+01 -3.234157E-04 3.883728E+01 -2.192236E-04 + 3.670001E+01 9.000000E+01 1 1.884358E-06 -9.003239E+01 -1.065184E-09 -1.884358E-06 + 3.670001E+01 9.000000E+01 2 3.861162E+01 8.995307E+01 3.162677E-02 3.861161E+01 + 3.670001E+01 9.000000E+01 3 1.953642E+02 1.843226E-01 1.953632E+02 6.284927E-01 + 3.670001E+01 9.000000E+01 4 1.252020E+02 8.995317E+01 1.023381E-01 1.252020E+02 + 3.670001E+01 9.000000E+01 5 8.757207E-05 -8.999486E+01 7.852456E-09 -8.757207E-05 + 3.670001E+01 9.000000E+01 6 3.329919E-06 1.799998E+02 -3.329919E-06 1.272406E-11 + 3.680001E+01 0.000000E+00 1 3.609518E+01 8.995804E+01 2.643451E-02 3.609517E+01 + 3.680001E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.680001E+01 0.000000E+00 3 1.935592E+02 1.825232E-01 1.935582E+02 6.166071E-01 + 3.680001E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.680001E+01 0.000000E+00 5 3.841978E+02 8.995804E+01 2.813598E-01 3.841977E+02 + 3.680001E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.680001E+01 3.000000E+01 1 3.132634E+01 8.995804E+01 2.294147E-02 3.132633E+01 + 3.680001E+01 3.000000E+01 2 1.911706E+01 8.995335E+01 1.556402E-02 1.911705E+01 + 3.680001E+01 3.000000E+01 3 1.940258E+02 1.827141E-01 1.940249E+02 6.187401E-01 + 3.680001E+01 3.000000E+01 4 6.159063E+01 8.995316E+01 5.035570E-02 6.159061E+01 + 3.680001E+01 3.000000E+01 5 3.334243E+02 8.995804E+01 2.441790E-01 3.334242E+02 + 3.680001E+01 3.000000E+01 6 3.843254E+01 -3.201480E-04 3.843254E+01 -2.147471E-04 + 3.680001E+01 6.000000E+01 1 1.816397E+01 8.995805E+01 1.330144E-02 1.816397E+01 + 3.680001E+01 6.000000E+01 2 3.326767E+01 8.995335E+01 2.708580E-02 3.326765E+01 + 3.680001E+01 6.000000E+01 3 1.949625E+02 1.830970E-01 1.949615E+02 6.230302E-01 + 3.680001E+01 6.000000E+01 4 1.076324E+02 8.995335E+01 8.763277E-02 1.076324E+02 + 3.680001E+01 6.000000E+01 5 1.933075E+02 8.995804E+01 1.415731E-01 1.933075E+02 + 3.680001E+01 6.000000E+01 6 3.861890E+01 -3.196244E-04 3.861890E+01 -2.154355E-04 + 3.680001E+01 9.000000E+01 1 1.879113E-06 -9.003223E+01 -1.056974E-09 -1.879113E-06 + 3.680001E+01 9.000000E+01 2 3.850458E+01 8.995335E+01 3.135026E-02 3.850457E+01 + 3.680001E+01 9.000000E+01 3 1.954319E+02 1.832886E-01 1.954308E+02 6.251832E-01 + 3.680001E+01 9.000000E+01 4 1.248370E+02 8.995345E+01 1.014297E-01 1.248370E+02 + 3.680001E+01 9.000000E+01 5 8.733774E-05 -8.999490E+01 7.775218E-09 -8.733774E-05 + 3.680001E+01 9.000000E+01 6 3.311137E-06 1.799998E+02 -3.311137E-06 1.250442E-11 + 3.690001E+01 0.000000E+00 1 3.599728E+01 8.995827E+01 2.621271E-02 3.599727E+01 + 3.690001E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.690001E+01 0.000000E+00 3 1.936374E+02 1.815081E-01 1.936364E+02 6.134256E-01 + 3.690001E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.690001E+01 0.000000E+00 5 3.832786E+02 8.995827E+01 2.790852E-01 3.832785E+02 + 3.690001E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.690001E+01 3.000000E+01 1 3.124096E+01 8.995827E+01 2.274868E-02 3.124096E+01 + 3.690001E+01 3.000000E+01 2 1.906494E+01 8.995364E+01 1.542901E-02 1.906494E+01 + 3.690001E+01 3.000000E+01 3 1.941015E+02 1.816968E-01 1.941005E+02 6.155351E-01 + 3.690001E+01 3.000000E+01 4 6.141599E+01 8.995344E+01 4.991201E-02 6.141597E+01 + 3.690001E+01 3.000000E+01 5 3.326176E+02 8.995827E+01 2.422045E-01 3.326175E+02 + 3.690001E+01 3.000000E+01 6 3.821808E+01 -3.164035E-04 3.821808E+01 -2.110511E-04 + 3.690001E+01 6.000000E+01 1 1.811399E+01 8.995828E+01 1.318936E-02 1.811398E+01 + 3.690001E+01 6.000000E+01 2 3.317612E+01 8.995364E+01 2.685007E-02 3.317611E+01 + 3.690001E+01 6.000000E+01 3 1.950322E+02 1.820760E-01 1.950312E+02 6.197773E-01 + 3.690001E+01 6.000000E+01 4 1.073225E+02 8.995364E+01 8.685882E-02 1.073224E+02 + 3.690001E+01 6.000000E+01 5 1.928387E+02 8.995827E+01 1.404242E-01 1.928387E+02 + 3.690001E+01 6.000000E+01 6 3.840244E+01 -3.158883E-04 3.840244E+01 -2.117238E-04 + 3.690001E+01 9.000000E+01 1 1.873892E-06 -9.003207E+01 -1.048851E-09 -1.873891E-06 + 3.690001E+01 9.000000E+01 2 3.839815E+01 8.995363E+01 3.107703E-02 3.839814E+01 + 3.690001E+01 9.000000E+01 3 1.954996E+02 1.822653E-01 1.954986E+02 6.219084E-01 + 3.690001E+01 9.000000E+01 4 1.244742E+02 8.995373E+01 1.005322E-01 1.244741E+02 + 3.690001E+01 9.000000E+01 5 8.710453E-05 -8.999493E+01 7.699029E-09 -8.710453E-05 + 3.690001E+01 9.000000E+01 6 3.292510E-06 1.799998E+02 -3.292510E-06 1.228920E-11 + 3.700001E+01 0.000000E+00 1 3.589978E+01 8.995852E+01 2.599344E-02 3.589977E+01 + 3.700001E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.700001E+01 0.000000E+00 3 1.937148E+02 1.805010E-01 1.937138E+02 6.102659E-01 + 3.700001E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.700001E+01 0.000000E+00 5 3.823571E+02 8.995852E+01 2.768368E-01 3.823570E+02 + 3.700001E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.700001E+01 3.000000E+01 1 3.115604E+01 8.995852E+01 2.255808E-02 3.115603E+01 + 3.700001E+01 3.000000E+01 2 1.901317E+01 8.995390E+01 1.529554E-02 1.901317E+01 + 3.700001E+01 3.000000E+01 3 1.941762E+02 1.806874E-01 1.941752E+02 6.123512E-01 + 3.700001E+01 3.000000E+01 4 6.124279E+01 8.995371E+01 4.947377E-02 6.124277E+01 + 3.700001E+01 3.000000E+01 5 3.318172E+02 8.995852E+01 2.402489E-01 3.318171E+02 + 3.700001E+01 3.000000E+01 6 3.800550E+01 -3.127140E-04 3.800550E+01 -2.074298E-04 + 3.700001E+01 6.000000E+01 1 1.806436E+01 8.995852E+01 1.307851E-02 1.806435E+01 + 3.700001E+01 6.000000E+01 2 3.308511E+01 8.995390E+01 2.661712E-02 3.308510E+01 + 3.700001E+01 6.000000E+01 3 1.951026E+02 1.810615E-01 1.951017E+02 6.165468E-01 + 3.700001E+01 6.000000E+01 4 1.070143E+02 8.995390E+01 8.609351E-02 1.070143E+02 + 3.700001E+01 6.000000E+01 5 1.923697E+02 8.995852E+01 1.392885E-01 1.923696E+02 + 3.700001E+01 6.000000E+01 6 3.818773E+01 -3.122081E-04 3.818773E+01 -2.080872E-04 + 3.700001E+01 9.000000E+01 1 1.868694E-06 -9.003191E+01 -1.040809E-09 -1.868694E-06 + 3.700001E+01 9.000000E+01 2 3.829226E+01 8.995390E+01 3.080693E-02 3.829224E+01 + 3.700001E+01 9.000000E+01 3 1.955675E+02 1.812486E-01 1.955665E+02 6.186541E-01 + 3.700001E+01 9.000000E+01 4 1.241135E+02 8.995400E+01 9.964576E-02 1.241135E+02 + 3.700001E+01 9.000000E+01 5 8.687268E-05 -8.999497E+01 7.623820E-09 -8.687268E-05 + 3.700001E+01 9.000000E+01 6 3.274045E-06 1.799998E+02 -3.274045E-06 1.207833E-11 + 3.710001E+01 0.000000E+00 1 3.580303E+01 8.995875E+01 2.577649E-02 3.580302E+01 + 3.710001E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.710001E+01 0.000000E+00 3 1.937917E+02 1.795006E-01 1.937907E+02 6.071245E-01 + 3.710001E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.710001E+01 0.000000E+00 5 3.814402E+02 8.995875E+01 2.746114E-01 3.814401E+02 + 3.710001E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.710001E+01 3.000000E+01 1 3.107160E+01 8.995875E+01 2.236967E-02 3.107159E+01 + 3.710001E+01 3.000000E+01 2 1.896167E+01 8.995418E+01 1.516363E-02 1.896166E+01 + 3.710001E+01 3.000000E+01 3 1.942503E+02 1.796866E-01 1.942493E+02 6.091916E-01 + 3.710001E+01 3.000000E+01 4 6.107037E+01 8.995399E+01 4.904100E-02 6.107035E+01 + 3.710001E+01 3.000000E+01 5 3.310197E+02 8.995875E+01 2.383163E-01 3.310196E+02 + 3.710001E+01 3.000000E+01 6 3.779467E+01 -3.090784E-04 3.779467E+01 -2.038809E-04 + 3.710001E+01 6.000000E+01 1 1.801499E+01 8.995876E+01 1.296894E-02 1.801498E+01 + 3.710001E+01 6.000000E+01 2 3.299469E+01 8.995418E+01 2.638684E-02 3.299468E+01 + 3.710001E+01 6.000000E+01 3 1.951720E+02 1.800560E-01 1.951711E+02 6.133407E-01 + 3.710001E+01 6.000000E+01 4 1.067082E+02 8.995418E+01 8.533775E-02 1.067082E+02 + 3.710001E+01 6.000000E+01 5 1.919026E+02 8.995875E+01 1.381631E-01 1.919025E+02 + 3.710001E+01 6.000000E+01 6 3.797492E+01 -3.085806E-04 3.797492E+01 -2.045233E-04 + 3.710001E+01 9.000000E+01 1 1.863535E-06 -9.003175E+01 -1.032844E-09 -1.863535E-06 + 3.710001E+01 9.000000E+01 2 3.818700E+01 8.995418E+01 3.054006E-02 3.818699E+01 + 3.710001E+01 9.000000E+01 3 1.956349E+02 1.802405E-01 1.956339E+02 6.154253E-01 + 3.710001E+01 9.000000E+01 4 1.237551E+02 8.995428E+01 9.876946E-02 1.237550E+02 + 3.710001E+01 9.000000E+01 5 8.664217E-05 -8.999501E+01 7.549617E-09 -8.664217E-05 + 3.710001E+01 9.000000E+01 6 3.255738E-06 1.799998E+02 -3.255738E-06 1.187168E-11 + 3.720000E+01 0.000000E+00 1 3.570667E+01 8.995898E+01 2.556218E-02 3.570666E+01 + 3.720000E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.720000E+01 0.000000E+00 3 1.938675E+02 1.785106E-01 1.938665E+02 6.040121E-01 + 3.720000E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.720000E+01 0.000000E+00 5 3.805318E+02 8.995899E+01 2.724096E-01 3.805317E+02 + 3.720000E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.720000E+01 3.000000E+01 1 3.098772E+01 8.995898E+01 2.218330E-02 3.098772E+01 + 3.720000E+01 3.000000E+01 2 1.891045E+01 8.995445E+01 1.503326E-02 1.891044E+01 + 3.720000E+01 3.000000E+01 3 1.943250E+02 1.786926E-01 1.943240E+02 6.060547E-01 + 3.720000E+01 3.000000E+01 4 6.089897E+01 8.995426E+01 4.861289E-02 6.089895E+01 + 3.720000E+01 3.000000E+01 5 3.302250E+02 8.995898E+01 2.364022E-01 3.302249E+02 + 3.720000E+01 3.000000E+01 6 3.758564E+01 -3.054968E-04 3.758564E+01 -2.004038E-04 + 3.720000E+01 6.000000E+01 1 1.796583E+01 8.995899E+01 1.286062E-02 1.796583E+01 + 3.720000E+01 6.000000E+01 2 3.290464E+01 8.995445E+01 2.615929E-02 3.290462E+01 + 3.720000E+01 6.000000E+01 3 1.952406E+02 1.790596E-01 1.952397E+02 6.101611E-01 + 3.720000E+01 6.000000E+01 4 1.064036E+02 8.995445E+01 8.459132E-02 1.064035E+02 + 3.720000E+01 6.000000E+01 5 1.914371E+02 8.995898E+01 1.370518E-01 1.914371E+02 + 3.720000E+01 6.000000E+01 6 3.776382E+01 -3.050082E-04 3.776382E+01 -2.010318E-04 + 3.720000E+01 9.000000E+01 1 1.858400E-06 -9.003160E+01 -1.024959E-09 -1.858399E-06 + 3.720000E+01 9.000000E+01 2 3.808233E+01 8.995445E+01 3.027625E-02 3.808232E+01 + 3.720000E+01 9.000000E+01 3 1.957003E+02 1.792426E-01 1.956993E+02 6.122227E-01 + 3.720000E+01 9.000000E+01 4 1.233988E+02 8.995454E+01 9.790403E-02 1.233987E+02 + 3.720000E+01 9.000000E+01 5 8.641278E-05 -8.999505E+01 7.476406E-09 -8.641278E-05 + 3.720000E+01 9.000000E+01 6 3.237583E-06 1.799998E+02 -3.237583E-06 1.166921E-11 + 3.730000E+01 0.000000E+00 1 3.561084E+01 8.995921E+01 2.535003E-02 3.561084E+01 + 3.730000E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.730000E+01 0.000000E+00 3 1.939441E+02 1.775283E-01 1.939431E+02 6.009256E-01 + 3.730000E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.730000E+01 0.000000E+00 5 3.796246E+02 8.995921E+01 2.702333E-01 3.796245E+02 + 3.730000E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.730000E+01 3.000000E+01 1 3.090408E+01 8.995921E+01 2.199898E-02 3.090407E+01 + 3.730000E+01 3.000000E+01 2 1.885950E+01 8.995472E+01 1.490441E-02 1.885950E+01 + 3.730000E+01 3.000000E+01 3 1.943984E+02 1.777083E-01 1.943975E+02 6.029441E-01 + 3.730000E+01 3.000000E+01 4 6.072842E+01 8.995454E+01 4.819021E-02 6.072840E+01 + 3.730000E+01 3.000000E+01 5 3.294380E+02 8.995921E+01 2.345089E-01 3.294380E+02 + 3.730000E+01 3.000000E+01 6 3.737830E+01 -3.019680E-04 3.737830E+01 -1.969962E-04 + 3.730000E+01 6.000000E+01 1 1.791701E+01 8.995922E+01 1.275356E-02 1.791700E+01 + 3.730000E+01 6.000000E+01 2 3.281517E+01 8.995472E+01 2.593441E-02 3.281516E+01 + 3.730000E+01 6.000000E+01 3 1.953093E+02 1.780708E-01 1.953084E+02 6.070051E-01 + 3.730000E+01 6.000000E+01 4 1.060998E+02 8.995472E+01 8.385316E-02 1.060997E+02 + 3.730000E+01 6.000000E+01 5 1.909745E+02 8.995921E+01 1.359511E-01 1.909745E+02 + 3.730000E+01 6.000000E+01 6 3.755458E+01 -3.014875E-04 3.755458E+01 -1.976103E-04 + 3.730000E+01 9.000000E+01 1 1.853295E-06 -9.003145E+01 -1.017150E-09 -1.853295E-06 + 3.730000E+01 9.000000E+01 2 3.797836E+01 8.995472E+01 3.001556E-02 3.797834E+01 + 3.730000E+01 9.000000E+01 3 1.957673E+02 1.782511E-01 1.957663E+02 6.090444E-01 + 3.730000E+01 9.000000E+01 4 1.230442E+02 8.995481E+01 9.704840E-02 1.230442E+02 + 3.730000E+01 9.000000E+01 5 8.618405E-05 -8.999508E+01 7.404151E-09 -8.618405E-05 + 3.730000E+01 9.000000E+01 6 3.219585E-06 1.799998E+02 -3.219585E-06 1.147080E-11 + 3.740000E+01 0.000000E+00 1 3.551552E+01 8.995944E+01 2.514040E-02 3.551551E+01 + 3.740000E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.740000E+01 0.000000E+00 3 1.940185E+02 1.765533E-01 1.940176E+02 5.978546E-01 + 3.740000E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.740000E+01 0.000000E+00 5 3.787233E+02 8.995944E+01 2.680781E-01 3.787232E+02 + 3.740000E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.740000E+01 3.000000E+01 1 3.082098E+01 8.995944E+01 2.181681E-02 3.082097E+01 + 3.740000E+01 3.000000E+01 2 1.880880E+01 8.995499E+01 1.477704E-02 1.880879E+01 + 3.740000E+01 3.000000E+01 3 1.944707E+02 1.767317E-01 1.944698E+02 5.998538E-01 + 3.740000E+01 3.000000E+01 4 6.055895E+01 8.995480E+01 4.777238E-02 6.055893E+01 + 3.740000E+01 3.000000E+01 5 3.286491E+02 8.995944E+01 2.326372E-01 3.286490E+02 + 3.740000E+01 3.000000E+01 6 3.717279E+01 -2.984897E-04 3.717279E+01 -1.936564E-04 + 3.740000E+01 6.000000E+01 1 1.786840E+01 8.995944E+01 1.264762E-02 1.786839E+01 + 3.740000E+01 6.000000E+01 2 3.272618E+01 8.995499E+01 2.571209E-02 3.272617E+01 + 3.740000E+01 6.000000E+01 3 1.953771E+02 1.770899E-01 1.953762E+02 6.038708E-01 + 3.740000E+01 6.000000E+01 4 1.057991E+02 8.995499E+01 8.312398E-02 1.057991E+02 + 3.740000E+01 6.000000E+01 5 1.905139E+02 8.995944E+01 1.348622E-01 1.905138E+02 + 3.740000E+01 6.000000E+01 6 3.734701E+01 -2.980173E-04 3.734701E+01 -1.942562E-04 + 3.740000E+01 9.000000E+01 1 1.848217E-06 -9.003130E+01 -1.009421E-09 -1.848216E-06 + 3.740000E+01 9.000000E+01 2 3.787478E+01 8.995499E+01 2.975787E-02 3.787477E+01 + 3.740000E+01 9.000000E+01 3 1.958323E+02 1.772688E-01 1.958314E+02 6.058893E-01 + 3.740000E+01 9.000000E+01 4 1.226922E+02 8.995508E+01 9.620330E-02 1.226922E+02 + 3.740000E+01 9.000000E+01 5 8.595712E-05 -8.999511E+01 7.332817E-09 -8.595712E-05 + 3.740000E+01 9.000000E+01 6 3.201735E-06 1.799998E+02 -3.201735E-06 1.127630E-11 + 3.750000E+01 0.000000E+00 1 3.542072E+01 8.995967E+01 2.493308E-02 3.542071E+01 + 3.750000E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.750000E+01 0.000000E+00 3 1.940933E+02 1.755875E-01 1.940924E+02 5.948136E-01 + 3.750000E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.750000E+01 0.000000E+00 5 3.778259E+02 8.995967E+01 2.659465E-01 3.778258E+02 + 3.750000E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.750000E+01 3.000000E+01 1 3.073839E+01 8.995967E+01 2.163660E-02 3.073838E+01 + 3.750000E+01 3.000000E+01 2 1.875841E+01 8.995525E+01 1.465115E-02 1.875840E+01 + 3.750000E+01 3.000000E+01 3 1.945428E+02 1.757639E-01 1.945419E+02 5.967901E-01 + 3.750000E+01 3.000000E+01 4 6.039027E+01 8.995507E+01 4.735931E-02 6.039025E+01 + 3.750000E+01 3.000000E+01 5 3.278664E+02 8.995967E+01 2.307838E-01 3.278663E+02 + 3.750000E+01 3.000000E+01 6 3.696891E+01 -2.950625E-04 3.696891E+01 -1.903830E-04 + 3.750000E+01 6.000000E+01 1 1.782012E+01 8.995967E+01 1.254284E-02 1.782011E+01 + 3.750000E+01 6.000000E+01 2 3.263757E+01 8.995525E+01 2.549235E-02 3.263755E+01 + 3.750000E+01 6.000000E+01 3 1.954447E+02 1.761179E-01 1.954438E+02 6.007640E-01 + 3.750000E+01 6.000000E+01 4 1.054997E+02 8.995525E+01 8.240302E-02 1.054997E+02 + 3.750000E+01 6.000000E+01 5 1.900555E+02 8.995967E+01 1.337853E-01 1.900555E+02 + 3.750000E+01 6.000000E+01 6 3.714124E+01 -2.945984E-04 3.714124E+01 -1.909695E-04 + 3.750000E+01 9.000000E+01 1 1.843173E-06 -9.003114E+01 -1.001765E-09 -1.843173E-06 + 3.750000E+01 9.000000E+01 2 3.777192E+01 8.995525E+01 2.950320E-02 3.777191E+01 + 3.750000E+01 9.000000E+01 3 1.958978E+02 1.762942E-01 1.958969E+02 6.027599E-01 + 3.750000E+01 9.000000E+01 4 1.223418E+02 8.995534E+01 9.536795E-02 1.223418E+02 + 3.750000E+01 9.000000E+01 5 8.573143E-05 -8.999515E+01 7.262398E-09 -8.573143E-05 + 3.750000E+01 9.000000E+01 6 3.184033E-06 1.799998E+02 -3.184033E-06 1.108569E-11 + 3.760000E+01 0.000000E+00 1 3.532641E+01 8.995990E+01 2.472806E-02 3.532640E+01 + 3.760000E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.760000E+01 0.000000E+00 3 1.941674E+02 1.746290E-01 1.941665E+02 5.917922E-01 + 3.760000E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.760000E+01 0.000000E+00 5 3.769309E+02 8.995990E+01 2.638378E-01 3.769308E+02 + 3.760000E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.760000E+01 3.000000E+01 1 3.065624E+01 8.995990E+01 2.145841E-02 3.065624E+01 + 3.760000E+01 3.000000E+01 2 1.870827E+01 8.995551E+01 1.452670E-02 1.870827E+01 + 3.760000E+01 3.000000E+01 3 1.946130E+02 1.748050E-01 1.946121E+02 5.937486E-01 + 3.760000E+01 3.000000E+01 4 6.022271E+01 8.995534E+01 4.695121E-02 6.022269E+01 + 3.760000E+01 3.000000E+01 5 3.270844E+02 8.995990E+01 2.289510E-01 3.270843E+02 + 3.760000E+01 3.000000E+01 6 3.676674E+01 -2.916853E-04 3.676674E+01 -1.871746E-04 + 3.760000E+01 6.000000E+01 1 1.777201E+01 8.995990E+01 1.243931E-02 1.777201E+01 + 3.760000E+01 6.000000E+01 2 3.254964E+01 8.995551E+01 2.527520E-02 3.254963E+01 + 3.760000E+01 6.000000E+01 3 1.955117E+02 1.751526E-01 1.955108E+02 5.976764E-01 + 3.760000E+01 6.000000E+01 4 1.052019E+02 8.995551E+01 8.169108E-02 1.052018E+02 + 3.760000E+01 6.000000E+01 5 1.895983E+02 8.995990E+01 1.327199E-01 1.895982E+02 + 3.760000E+01 6.000000E+01 6 3.693717E+01 -2.912291E-04 3.693717E+01 -1.877482E-04 + 3.760000E+01 9.000000E+01 1 1.838151E-06 -9.003099E+01 -9.941880E-10 -1.838151E-06 + 3.760000E+01 9.000000E+01 2 3.766951E+01 8.995551E+01 2.925150E-02 3.766950E+01 + 3.760000E+01 9.000000E+01 3 1.959611E+02 1.753282E-01 1.959602E+02 5.996506E-01 + 3.760000E+01 9.000000E+01 4 1.219939E+02 8.995560E+01 9.454259E-02 1.219939E+02 + 3.760000E+01 9.000000E+01 5 8.550697E-05 -8.999518E+01 7.192929E-09 -8.550697E-05 + 3.760000E+01 9.000000E+01 6 3.166490E-06 1.799998E+02 -3.166490E-06 1.089889E-11 + 3.770000E+01 0.000000E+00 1 3.523265E+01 8.996011E+01 2.452518E-02 3.523264E+01 + 3.770000E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.770000E+01 0.000000E+00 3 1.942398E+02 1.736797E-01 1.942389E+02 5.887948E-01 + 3.770000E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.770000E+01 0.000000E+00 5 3.760396E+02 8.996012E+01 2.617493E-01 3.760395E+02 + 3.770000E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.770000E+01 3.000000E+01 1 3.057445E+01 8.996011E+01 2.128232E-02 3.057444E+01 + 3.770000E+01 3.000000E+01 2 1.865842E+01 8.995577E+01 1.440366E-02 1.865842E+01 + 3.770000E+01 3.000000E+01 3 1.946850E+02 1.738515E-01 1.946841E+02 5.907283E-01 + 3.770000E+01 3.000000E+01 4 6.005615E+01 8.995560E+01 4.654782E-02 6.005613E+01 + 3.770000E+01 3.000000E+01 5 3.263070E+02 8.996011E+01 2.271385E-01 3.263069E+02 + 3.770000E+01 3.000000E+01 6 3.656622E+01 -2.883568E-04 3.656622E+01 -1.840296E-04 + 3.770000E+01 6.000000E+01 1 1.772424E+01 8.996012E+01 1.233690E-02 1.772424E+01 + 3.770000E+01 6.000000E+01 2 3.246197E+01 8.995577E+01 2.506052E-02 3.246196E+01 + 3.770000E+01 6.000000E+01 3 1.955773E+02 1.741974E-01 1.955764E+02 5.946164E-01 + 3.770000E+01 6.000000E+01 4 1.049062E+02 8.995577E+01 8.098717E-02 1.049062E+02 + 3.770000E+01 6.000000E+01 5 1.891437E+02 8.996011E+01 1.316649E-01 1.891437E+02 + 3.770000E+01 6.000000E+01 6 3.673475E+01 -2.879080E-04 3.673475E+01 -1.845900E-04 + 3.770000E+01 9.000000E+01 1 1.833153E-06 -9.003085E+01 -9.866805E-10 -1.833153E-06 + 3.770000E+01 9.000000E+01 2 3.756766E+01 8.995577E+01 2.900263E-02 3.756765E+01 + 3.770000E+01 9.000000E+01 3 1.960254E+02 1.743704E-01 1.960245E+02 5.965705E-01 + 3.770000E+01 9.000000E+01 4 1.216478E+02 8.995586E+01 9.372678E-02 1.216478E+02 + 3.770000E+01 9.000000E+01 5 8.528346E-05 -8.999522E+01 7.124344E-09 -8.528346E-05 + 3.770000E+01 9.000000E+01 6 3.149081E-06 1.799998E+02 -3.149081E-06 1.071572E-11 + 3.780000E+01 0.000000E+00 1 3.513924E+01 8.996034E+01 2.432460E-02 3.513923E+01 + 3.780000E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.780000E+01 0.000000E+00 3 1.943123E+02 1.727374E-01 1.943114E+02 5.858189E-01 + 3.780000E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.780000E+01 0.000000E+00 5 3.751520E+02 8.996034E+01 2.596821E-01 3.751519E+02 + 3.780000E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.780000E+01 3.000000E+01 1 3.049315E+01 8.996034E+01 2.110793E-02 3.049315E+01 + 3.780000E+01 3.000000E+01 2 1.860884E+01 8.995602E+01 1.428207E-02 1.860883E+01 + 3.780000E+01 3.000000E+01 3 1.947545E+02 1.729080E-01 1.947536E+02 5.877321E-01 + 3.780000E+01 3.000000E+01 4 5.989046E+01 8.995586E+01 4.614917E-02 5.989045E+01 + 3.780000E+01 3.000000E+01 5 3.255338E+02 8.996034E+01 2.253425E-01 3.255337E+02 + 3.780000E+01 3.000000E+01 6 3.636741E+01 -2.850756E-04 3.636741E+01 -1.809463E-04 + 3.780000E+01 6.000000E+01 1 1.767672E+01 8.996034E+01 1.223558E-02 1.767672E+01 + 3.780000E+01 6.000000E+01 2 3.237489E+01 8.995602E+01 2.484830E-02 3.237488E+01 + 3.780000E+01 6.000000E+01 3 1.956429E+02 1.732492E-01 1.956420E+02 5.915777E-01 + 3.780000E+01 6.000000E+01 4 1.046122E+02 8.995602E+01 8.029181E-02 1.046122E+02 + 3.780000E+01 6.000000E+01 5 1.886924E+02 8.996034E+01 1.306212E-01 1.886924E+02 + 3.780000E+01 6.000000E+01 6 3.653410E+01 -2.846348E-04 3.653410E+01 -1.814946E-04 + 3.780000E+01 9.000000E+01 1 1.828188E-06 -9.003069E+01 -9.792515E-10 -1.828188E-06 + 3.780000E+01 9.000000E+01 2 3.746643E+01 8.995602E+01 2.875663E-02 3.746642E+01 + 3.780000E+01 9.000000E+01 3 1.960886E+02 1.734206E-01 1.960877E+02 5.935124E-01 + 3.780000E+01 9.000000E+01 4 1.213039E+02 8.995612E+01 9.292052E-02 1.213038E+02 + 3.780000E+01 9.000000E+01 5 8.506112E-05 -8.999525E+01 7.056638E-09 -8.506112E-05 + 3.780000E+01 9.000000E+01 6 3.131823E-06 1.799998E+02 -3.131823E-06 1.053619E-11 + 3.789999E+01 0.000000E+00 1 3.504645E+01 8.996056E+01 2.412626E-02 3.504644E+01 + 3.789999E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.789999E+01 0.000000E+00 3 1.943845E+02 1.718028E-01 1.943837E+02 5.828659E-01 + 3.789999E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.789999E+01 0.000000E+00 5 3.742676E+02 8.996056E+01 2.576386E-01 3.742675E+02 + 3.789999E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.789999E+01 3.000000E+01 1 3.041226E+01 8.996056E+01 2.093559E-02 3.041225E+01 + 3.789999E+01 3.000000E+01 2 1.855947E+01 8.995628E+01 1.416183E-02 1.855946E+01 + 3.789999E+01 3.000000E+01 3 1.948246E+02 1.719720E-01 1.948237E+02 5.847607E-01 + 3.789999E+01 3.000000E+01 4 5.972560E+01 8.995611E+01 4.575526E-02 5.972558E+01 + 3.789999E+01 3.000000E+01 5 3.247654E+02 8.996056E+01 2.235660E-01 3.247654E+02 + 3.789999E+01 3.000000E+01 6 3.617013E+01 -2.818428E-04 3.617013E+01 -1.779240E-04 + 3.789999E+01 6.000000E+01 1 1.762939E+01 8.996056E+01 1.213540E-02 1.762938E+01 + 3.789999E+01 6.000000E+01 2 3.228830E+01 8.995628E+01 2.463846E-02 3.228829E+01 + 3.789999E+01 6.000000E+01 3 1.957083E+02 1.723089E-01 1.957074E+02 5.885640E-01 + 3.789999E+01 6.000000E+01 4 1.043195E+02 8.995628E+01 7.960381E-02 1.043195E+02 + 3.789999E+01 6.000000E+01 5 1.882422E+02 8.996056E+01 1.295894E-01 1.882421E+02 + 3.789999E+01 6.000000E+01 6 3.633500E+01 -2.814091E-04 3.633500E+01 -1.784599E-04 + 3.789999E+01 9.000000E+01 1 1.823248E-06 -9.003054E+01 -9.718899E-10 -1.823248E-06 + 3.789999E+01 9.000000E+01 2 3.736568E+01 8.995628E+01 2.851348E-02 3.736567E+01 + 3.789999E+01 9.000000E+01 3 1.961514E+02 1.724782E-01 1.961505E+02 5.904762E-01 + 3.789999E+01 9.000000E+01 4 1.209620E+02 8.995637E+01 9.212315E-02 1.209620E+02 + 3.789999E+01 9.000000E+01 5 8.483945E-05 -8.999529E+01 6.989779E-09 -8.483945E-05 + 3.789999E+01 9.000000E+01 6 3.114706E-06 1.799998E+02 -3.114706E-06 1.036019E-11 + 3.799999E+01 0.000000E+00 1 3.495421E+01 8.996078E+01 2.393005E-02 3.495420E+01 + 3.799999E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.799999E+01 0.000000E+00 3 1.944568E+02 1.708748E-01 1.944559E+02 5.799330E-01 + 3.799999E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.799999E+01 0.000000E+00 5 3.733889E+02 8.996078E+01 2.556180E-01 3.733888E+02 + 3.799999E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.799999E+01 3.000000E+01 1 3.033183E+01 8.996078E+01 2.076511E-02 3.033182E+01 + 3.799999E+01 3.000000E+01 2 1.851044E+01 8.995654E+01 1.404292E-02 1.851043E+01 + 3.799999E+01 3.000000E+01 3 1.948943E+02 1.710430E-01 1.948935E+02 5.818102E-01 + 3.799999E+01 3.000000E+01 4 5.956176E+01 8.995636E+01 4.536559E-02 5.956174E+01 + 3.799999E+01 3.000000E+01 5 3.239963E+02 8.996078E+01 2.218107E-01 3.239962E+02 + 3.799999E+01 3.000000E+01 6 3.597455E+01 -2.786547E-04 3.597455E+01 -1.749601E-04 + 3.799999E+01 6.000000E+01 1 1.758238E+01 8.996078E+01 1.203630E-02 1.758238E+01 + 3.799999E+01 6.000000E+01 2 3.220208E+01 8.995653E+01 2.443106E-02 3.220208E+01 + 3.799999E+01 6.000000E+01 3 1.957732E+02 1.713764E-01 1.957723E+02 5.855727E-01 + 3.799999E+01 6.000000E+01 4 1.040285E+02 8.995653E+01 7.892429E-02 1.040284E+02 + 3.799999E+01 6.000000E+01 5 1.877928E+02 8.996078E+01 1.285691E-01 1.877927E+02 + 3.799999E+01 6.000000E+01 6 3.613800E+01 -2.782307E-04 3.613800E+01 -1.754876E-04 + 3.799999E+01 9.000000E+01 1 1.818341E-06 -9.003040E+01 -9.646056E-10 -1.818340E-06 + 3.799999E+01 9.000000E+01 2 3.726551E+01 8.995653E+01 2.827307E-02 3.726550E+01 + 3.799999E+01 9.000000E+01 3 1.962141E+02 1.715433E-01 1.962132E+02 5.874630E-01 + 3.799999E+01 9.000000E+01 4 1.206220E+02 8.995662E+01 9.133600E-02 1.206219E+02 + 3.799999E+01 9.000000E+01 5 8.461963E-05 -8.999531E+01 6.923800E-09 -8.461963E-05 + 3.799999E+01 9.000000E+01 6 3.097734E-06 1.799998E+02 -3.097734E-06 1.018763E-11 + 3.809999E+01 0.000000E+00 1 3.486228E+01 8.996099E+01 2.373597E-02 3.486227E+01 + 3.809999E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.809999E+01 0.000000E+00 3 1.945269E+02 1.699565E-01 1.945260E+02 5.770244E-01 + 3.809999E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.809999E+01 0.000000E+00 5 3.725117E+02 8.996099E+01 2.536160E-01 3.725117E+02 + 3.809999E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.809999E+01 3.000000E+01 1 3.025176E+01 8.996099E+01 2.059648E-02 3.025176E+01 + 3.809999E+01 3.000000E+01 2 1.846157E+01 8.995678E+01 1.392544E-02 1.846156E+01 + 3.809999E+01 3.000000E+01 3 1.949627E+02 1.701212E-01 1.949619E+02 5.788776E-01 + 3.809999E+01 3.000000E+01 4 5.939889E+01 8.995661E+01 4.498062E-02 5.939887E+01 + 3.809999E+01 3.000000E+01 5 3.232348E+02 8.996099E+01 2.200700E-01 3.232347E+02 + 3.809999E+01 3.000000E+01 6 3.578088E+01 -2.755157E-04 3.578088E+01 -1.720579E-04 + 3.809999E+01 6.000000E+01 1 1.753559E+01 8.996100E+01 1.193830E-02 1.753559E+01 + 3.809999E+01 6.000000E+01 2 3.211641E+01 8.995678E+01 2.422601E-02 3.211641E+01 + 3.809999E+01 6.000000E+01 3 1.958373E+02 1.704507E-01 1.958364E+02 5.826007E-01 + 3.809999E+01 6.000000E+01 4 1.037392E+02 8.995678E+01 7.825250E-02 1.037392E+02 + 3.809999E+01 6.000000E+01 5 1.873469E+02 8.996099E+01 1.275576E-01 1.873468E+02 + 3.809999E+01 6.000000E+01 6 3.594220E+01 -2.750968E-04 3.594220E+01 -1.725709E-04 + 3.809999E+01 9.000000E+01 1 1.813455E-06 -9.003025E+01 -9.573888E-10 -1.813455E-06 + 3.809999E+01 9.000000E+01 2 3.716589E+01 8.995678E+01 2.803547E-02 3.716588E+01 + 3.809999E+01 9.000000E+01 3 1.962754E+02 1.706165E-01 1.962745E+02 5.844717E-01 + 3.809999E+01 9.000000E+01 4 1.202840E+02 8.995686E+01 9.055747E-02 1.202840E+02 + 3.809999E+01 9.000000E+01 5 8.440075E-05 -8.999535E+01 6.858656E-09 -8.440075E-05 + 3.809999E+01 9.000000E+01 6 3.080899E-06 1.799998E+02 -3.080899E-06 1.001845E-11 + 3.819999E+01 0.000000E+00 1 3.477097E+01 8.996120E+01 2.354402E-02 3.477096E+01 + 3.819999E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.819999E+01 0.000000E+00 3 1.945977E+02 1.690437E-01 1.945969E+02 5.741343E-01 + 3.819999E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.819999E+01 0.000000E+00 5 3.716402E+02 8.996120E+01 2.516356E-01 3.716401E+02 + 3.819999E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.819999E+01 3.000000E+01 1 3.017216E+01 8.996120E+01 2.042966E-02 3.017216E+01 + 3.819999E+01 3.000000E+01 2 1.841299E+01 8.995703E+01 1.380922E-02 1.841298E+01 + 3.819999E+01 3.000000E+01 3 1.950316E+02 1.692058E-01 1.950308E+02 5.759662E-01 + 3.819999E+01 3.000000E+01 4 5.923672E+01 8.995686E+01 4.459998E-02 5.923670E+01 + 3.819999E+01 3.000000E+01 5 3.224754E+02 8.996120E+01 2.183504E-01 3.224753E+02 + 3.819999E+01 3.000000E+01 6 3.558846E+01 -2.724184E-04 3.558846E+01 -1.692088E-04 + 3.819999E+01 6.000000E+01 1 1.748909E+01 8.996120E+01 1.184138E-02 1.748909E+01 + 3.819999E+01 6.000000E+01 2 3.203118E+01 8.995703E+01 2.402324E-02 3.203117E+01 + 3.819999E+01 6.000000E+01 3 1.959011E+02 1.695328E-01 1.959003E+02 5.796521E-01 + 3.819999E+01 6.000000E+01 4 1.034517E+02 8.995703E+01 7.758854E-02 1.034517E+02 + 3.819999E+01 6.000000E+01 5 1.869014E+02 8.996120E+01 1.265575E-01 1.869014E+02 + 3.819999E+01 6.000000E+01 6 3.574800E+01 -2.720069E-04 3.574800E+01 -1.697106E-04 + 3.819999E+01 9.000000E+01 1 1.808592E-06 -9.003011E+01 -9.502413E-10 -1.808592E-06 + 3.819999E+01 9.000000E+01 2 3.706679E+01 8.995703E+01 2.780049E-02 3.706678E+01 + 3.819999E+01 9.000000E+01 3 1.963370E+02 1.696968E-01 1.963362E+02 5.815037E-01 + 3.819999E+01 9.000000E+01 4 1.199473E+02 8.995711E+01 8.978783E-02 1.199473E+02 + 3.819999E+01 9.000000E+01 5 8.418305E-05 -8.999538E+01 6.794342E-09 -8.418305E-05 + 3.819999E+01 9.000000E+01 6 3.064201E-06 1.799998E+02 -3.064201E-06 9.852551E-12 + 3.829999E+01 0.000000E+00 1 3.468003E+01 8.996142E+01 2.335418E-02 3.468002E+01 + 3.829999E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.829999E+01 0.000000E+00 3 1.946672E+02 1.681380E-01 1.946664E+02 5.712622E-01 + 3.829999E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.829999E+01 0.000000E+00 5 3.707715E+02 8.996142E+01 2.496768E-01 3.707714E+02 + 3.829999E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.829999E+01 3.000000E+01 1 3.009303E+01 8.996142E+01 2.026470E-02 3.009303E+01 + 3.829999E+01 3.000000E+01 2 1.836469E+01 8.995728E+01 1.369432E-02 1.836468E+01 + 3.829999E+01 3.000000E+01 3 1.950982E+02 1.683000E-01 1.950974E+02 5.730785E-01 + 3.829999E+01 3.000000E+01 4 5.907571E+01 8.995711E+01 4.422360E-02 5.907570E+01 + 3.829999E+01 3.000000E+01 5 3.217174E+02 8.996142E+01 2.166486E-01 3.217173E+02 + 3.829999E+01 3.000000E+01 6 3.539756E+01 -2.693656E-04 3.539756E+01 -1.664151E-04 + 3.829999E+01 6.000000E+01 1 1.744281E+01 8.996142E+01 1.174549E-02 1.744281E+01 + 3.829999E+01 6.000000E+01 2 3.194634E+01 8.995728E+01 2.382282E-02 3.194633E+01 + 3.829999E+01 6.000000E+01 3 1.959636E+02 1.686223E-01 1.959627E+02 5.767229E-01 + 3.829999E+01 6.000000E+01 4 1.031661E+02 8.995728E+01 7.693203E-02 1.031660E+02 + 3.829999E+01 6.000000E+01 5 1.864578E+02 8.996141E+01 1.255679E-01 1.864578E+02 + 3.829999E+01 6.000000E+01 6 3.555539E+01 -2.689601E-04 3.555539E+01 -1.669055E-04 + 3.829999E+01 9.000000E+01 1 1.803759E-06 -9.002996E+01 -9.431657E-10 -1.803759E-06 + 3.829999E+01 9.000000E+01 2 3.696821E+01 8.995728E+01 2.756819E-02 3.696820E+01 + 3.829999E+01 9.000000E+01 3 1.963979E+02 1.687841E-01 1.963970E+02 5.785557E-01 + 3.829999E+01 9.000000E+01 4 1.196137E+02 8.995736E+01 8.902670E-02 1.196137E+02 + 3.829999E+01 9.000000E+01 5 8.396599E-05 -8.999541E+01 6.730840E-09 -8.396599E-05 + 3.829999E+01 9.000000E+01 6 3.047637E-06 1.799998E+02 -3.047637E-06 9.689864E-12 + 3.839999E+01 0.000000E+00 1 3.458966E+01 8.996162E+01 2.316631E-02 3.458965E+01 + 3.839999E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.839999E+01 0.000000E+00 3 1.947369E+02 1.672419E-01 1.947361E+02 5.684209E-01 + 3.839999E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.839999E+01 0.000000E+00 5 3.699066E+02 8.996163E+01 2.477349E-01 3.699065E+02 + 3.839999E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.839999E+01 3.000000E+01 1 3.001420E+01 8.996163E+01 2.010148E-02 3.001419E+01 + 3.839999E+01 3.000000E+01 2 1.831668E+01 8.995752E+01 1.358072E-02 1.831667E+01 + 3.839999E+01 3.000000E+01 3 1.951666E+02 1.674010E-01 1.951657E+02 5.702170E-01 + 3.839999E+01 3.000000E+01 4 5.891519E+01 8.995736E+01 4.385172E-02 5.891518E+01 + 3.839999E+01 3.000000E+01 5 3.209645E+02 8.996163E+01 2.149600E-01 3.209644E+02 + 3.839999E+01 3.000000E+01 6 3.520827E+01 -2.663557E-04 3.520827E+01 -1.636756E-04 + 3.839999E+01 6.000000E+01 1 1.739679E+01 8.996163E+01 1.165067E-02 1.739678E+01 + 3.839999E+01 6.000000E+01 2 3.186199E+01 8.995752E+01 2.362458E-02 3.186198E+01 + 3.839999E+01 6.000000E+01 3 1.960269E+02 1.677210E-01 1.960261E+02 5.738257E-01 + 3.839999E+01 6.000000E+01 4 1.028811E+02 8.995752E+01 7.628284E-02 1.028811E+02 + 3.839999E+01 6.000000E+01 5 1.860197E+02 8.996162E+01 1.245880E-01 1.860196E+02 + 3.839999E+01 6.000000E+01 6 3.536435E+01 -2.659573E-04 3.536435E+01 -1.641553E-04 + 3.839999E+01 9.000000E+01 1 1.798952E-06 -9.002982E+01 -9.361557E-10 -1.798952E-06 + 3.839999E+01 9.000000E+01 2 3.687025E+01 8.995752E+01 2.733845E-02 3.687024E+01 + 3.839999E+01 9.000000E+01 3 1.964591E+02 1.678807E-01 1.964582E+02 5.756382E-01 + 3.839999E+01 9.000000E+01 4 1.192811E+02 8.995760E+01 8.827484E-02 1.192811E+02 + 3.839999E+01 9.000000E+01 5 8.374990E-05 -8.999544E+01 6.668135E-09 -8.374990E-05 + 3.839999E+01 9.000000E+01 6 3.031218E-06 1.799998E+02 -3.031218E-06 9.530353E-12 + 3.849998E+01 0.000000E+00 1 3.449977E+01 8.996184E+01 2.298047E-02 3.449976E+01 + 3.849998E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.849998E+01 0.000000E+00 3 1.948059E+02 1.663502E-01 1.948051E+02 5.655909E-01 + 3.849998E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.849998E+01 0.000000E+00 5 3.690460E+02 8.996184E+01 2.458162E-01 3.690459E+02 + 3.849998E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.849998E+01 3.000000E+01 1 2.993586E+01 8.996184E+01 1.994009E-02 2.993586E+01 + 3.849998E+01 3.000000E+01 2 1.826886E+01 8.995776E+01 1.346837E-02 1.826886E+01 + 3.849998E+01 3.000000E+01 3 1.952324E+02 1.665085E-01 1.952316E+02 5.673683E-01 + 3.849998E+01 3.000000E+01 4 5.875619E+01 8.995760E+01 4.348381E-02 5.875618E+01 + 3.849998E+01 3.000000E+01 5 3.202123E+02 8.996184E+01 2.132935E-01 3.202122E+02 + 3.849998E+01 3.000000E+01 6 3.502040E+01 -2.633889E-04 3.502040E+01 -1.609889E-04 + 3.849998E+01 6.000000E+01 1 1.735099E+01 8.996184E+01 1.155688E-02 1.735098E+01 + 3.849998E+01 6.000000E+01 2 3.177813E+01 8.995776E+01 2.342860E-02 3.177812E+01 + 3.849998E+01 6.000000E+01 3 1.960889E+02 1.668241E-01 1.960880E+02 5.709372E-01 + 3.849998E+01 6.000000E+01 4 1.025988E+02 8.995776E+01 7.564160E-02 1.025988E+02 + 3.849998E+01 6.000000E+01 5 1.855794E+02 8.996184E+01 1.236184E-01 1.855794E+02 + 3.849998E+01 6.000000E+01 6 3.517489E+01 -2.629961E-04 3.517489E+01 -1.614580E-04 + 3.849998E+01 9.000000E+01 1 1.794170E-06 -9.002967E+01 -9.292148E-10 -1.794169E-06 + 3.849998E+01 9.000000E+01 2 3.677270E+01 8.995776E+01 2.711136E-02 3.677269E+01 + 3.849998E+01 9.000000E+01 3 1.965185E+02 1.669825E-01 1.965177E+02 5.727317E-01 + 3.849998E+01 9.000000E+01 4 1.189512E+02 8.995784E+01 8.753150E-02 1.189511E+02 + 3.849998E+01 9.000000E+01 5 8.353601E-05 -8.999547E+01 6.606227E-09 -8.353601E-05 + 3.849998E+01 9.000000E+01 6 3.014928E-06 1.799998E+02 -3.014928E-06 9.373904E-12 + 3.859998E+01 0.000000E+00 1 3.441029E+01 8.996204E+01 2.279671E-02 3.441029E+01 + 3.859998E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.859998E+01 0.000000E+00 3 1.948741E+02 1.654676E-01 1.948733E+02 5.627869E-01 + 3.859998E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.859998E+01 0.000000E+00 5 3.681898E+02 8.996204E+01 2.439158E-01 3.681897E+02 + 3.859998E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.859998E+01 3.000000E+01 1 2.985792E+01 8.996204E+01 1.978032E-02 2.985792E+01 + 3.859998E+01 3.000000E+01 2 1.822135E+01 8.995800E+01 1.335728E-02 1.822134E+01 + 3.859998E+01 3.000000E+01 3 1.952984E+02 1.656235E-01 1.952976E+02 5.645435E-01 + 3.859998E+01 3.000000E+01 4 5.859755E+01 8.995784E+01 4.312038E-02 5.859753E+01 + 3.859998E+01 3.000000E+01 5 3.194663E+02 8.996204E+01 2.116415E-01 3.194662E+02 + 3.859998E+01 3.000000E+01 6 3.483408E+01 -2.604633E-04 3.483408E+01 -1.583537E-04 + 3.859998E+01 6.000000E+01 1 1.730544E+01 8.996205E+01 1.146407E-02 1.730544E+01 + 3.859998E+01 6.000000E+01 2 3.169465E+01 8.995800E+01 2.323485E-02 3.169464E+01 + 3.859998E+01 6.000000E+01 3 1.961509E+02 1.659355E-01 1.961501E+02 5.680760E-01 + 3.859998E+01 6.000000E+01 4 1.023174E+02 8.995800E+01 7.500722E-02 1.023173E+02 + 3.859998E+01 6.000000E+01 5 1.851430E+02 8.996204E+01 1.226605E-01 1.851430E+02 + 3.859998E+01 6.000000E+01 6 3.498689E+01 -2.600776E-04 3.498689E+01 -1.588128E-04 + 3.859998E+01 9.000000E+01 1 1.789424E-06 -9.002953E+01 -9.223416E-10 -1.789424E-06 + 3.859998E+01 9.000000E+01 2 3.667565E+01 8.995800E+01 2.688683E-02 3.667564E+01 + 3.859998E+01 9.000000E+01 3 1.965779E+02 1.660928E-01 1.965770E+02 5.698522E-01 + 3.859998E+01 9.000000E+01 4 1.186225E+02 8.995808E+01 8.679637E-02 1.186225E+02 + 3.859998E+01 9.000000E+01 5 8.332237E-05 -8.999550E+01 6.545080E-09 -8.332237E-05 + 3.859998E+01 9.000000E+01 6 2.998770E-06 1.799998E+02 -2.998770E-06 9.220468E-12 + 3.869998E+01 0.000000E+00 1 3.432128E+01 8.996225E+01 2.261486E-02 3.432127E+01 + 3.869998E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.869998E+01 0.000000E+00 3 1.949422E+02 1.645907E-01 1.949414E+02 5.600000E-01 + 3.869998E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.869998E+01 0.000000E+00 5 3.673383E+02 8.996225E+01 2.420353E-01 3.673383E+02 + 3.869998E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.869998E+01 3.000000E+01 1 2.978041E+01 8.996225E+01 1.962240E-02 2.978041E+01 + 3.869998E+01 3.000000E+01 2 1.817397E+01 8.995824E+01 1.324745E-02 1.817397E+01 + 3.869998E+01 3.000000E+01 3 1.953644E+02 1.647459E-01 1.953636E+02 5.617420E-01 + 3.869998E+01 3.000000E+01 4 5.843998E+01 8.995808E+01 4.276097E-02 5.843997E+01 + 3.869998E+01 3.000000E+01 5 3.187232E+02 8.996225E+01 2.100082E-01 3.187231E+02 + 3.869998E+01 3.000000E+01 6 3.464930E+01 -2.575781E-04 3.464930E+01 -1.557689E-04 + 3.869998E+01 6.000000E+01 1 1.726012E+01 8.996225E+01 1.137227E-02 1.726012E+01 + 3.869998E+01 6.000000E+01 2 3.161165E+01 8.995824E+01 2.304325E-02 3.161164E+01 + 3.869998E+01 6.000000E+01 3 1.962120E+02 1.650551E-01 1.962112E+02 5.652379E-01 + 3.869998E+01 6.000000E+01 4 1.020378E+02 8.995824E+01 7.438006E-02 1.020377E+02 + 3.869998E+01 6.000000E+01 5 1.847064E+02 8.996225E+01 1.217106E-01 1.847063E+02 + 3.869998E+01 6.000000E+01 6 3.480049E+01 -2.571990E-04 3.480049E+01 -1.562183E-04 + 3.869998E+01 9.000000E+01 1 1.784687E-06 -9.002940E+01 -9.155313E-10 -1.784687E-06 + 3.869998E+01 9.000000E+01 2 3.657920E+01 8.995824E+01 2.666473E-02 3.657919E+01 + 3.869998E+01 9.000000E+01 3 1.966374E+02 1.652094E-01 1.966366E+02 5.669930E-01 + 3.869998E+01 9.000000E+01 4 1.182951E+02 8.995831E+01 8.606980E-02 1.182951E+02 + 3.869998E+01 9.000000E+01 5 8.310971E-05 -8.999553E+01 6.484684E-09 -8.310971E-05 + 3.869998E+01 9.000000E+01 6 2.982742E-06 1.799998E+02 -2.982742E-06 9.069962E-12 + 3.879998E+01 0.000000E+00 1 3.423267E+01 8.996245E+01 2.243490E-02 3.423266E+01 + 3.879998E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.879998E+01 0.000000E+00 3 1.950095E+02 1.637224E-01 1.950087E+02 5.572378E-01 + 3.879998E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.879998E+01 0.000000E+00 5 3.664887E+02 8.996245E+01 2.401737E-01 3.664886E+02 + 3.879998E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.879998E+01 3.000000E+01 1 2.970324E+01 8.996245E+01 1.946608E-02 2.970324E+01 + 3.879998E+01 3.000000E+01 2 1.812698E+01 8.995847E+01 1.313880E-02 1.812697E+01 + 3.879998E+01 3.000000E+01 3 1.954297E+02 1.638752E-01 1.954289E+02 5.589599E-01 + 3.879998E+01 3.000000E+01 4 5.828310E+01 8.995831E+01 4.240539E-02 5.828309E+01 + 3.879998E+01 3.000000E+01 5 3.179832E+02 8.996245E+01 2.083906E-01 3.179831E+02 + 3.879998E+01 3.000000E+01 6 3.446599E+01 -2.547337E-04 3.446599E+01 -1.532338E-04 + 3.879998E+01 6.000000E+01 1 1.721502E+01 8.996245E+01 1.128144E-02 1.721502E+01 + 3.879998E+01 6.000000E+01 2 3.152910E+01 8.995847E+01 2.285371E-02 3.152909E+01 + 3.879998E+01 6.000000E+01 3 1.962736E+02 1.641803E-01 1.962728E+02 5.624187E-01 + 3.879998E+01 6.000000E+01 4 1.017596E+02 8.995847E+01 7.376023E-02 1.017596E+02 + 3.879998E+01 6.000000E+01 5 1.842768E+02 8.996245E+01 1.207709E-01 1.842768E+02 + 3.879998E+01 6.000000E+01 6 3.461555E+01 -2.543607E-04 3.461555E+01 -1.536734E-04 + 3.879998E+01 9.000000E+01 1 1.779986E-06 -9.002926E+01 -9.087877E-10 -1.779985E-06 + 3.879998E+01 9.000000E+01 2 3.648320E+01 8.995847E+01 2.644516E-02 3.648318E+01 + 3.879998E+01 9.000000E+01 3 1.966966E+02 1.643332E-01 1.966958E+02 5.641557E-01 + 3.879998E+01 9.000000E+01 4 1.179707E+02 8.995854E+01 8.535144E-02 1.179706E+02 + 3.879998E+01 9.000000E+01 5 8.289875E-05 -8.999556E+01 6.425076E-09 -8.289875E-05 + 3.879998E+01 9.000000E+01 6 2.966845E-06 1.799998E+02 -2.966845E-06 8.922348E-12 + 3.889998E+01 0.000000E+00 1 3.414457E+01 8.996265E+01 2.225692E-02 3.414457E+01 + 3.889998E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.889998E+01 0.000000E+00 3 1.950762E+02 1.628608E-01 1.950754E+02 5.544951E-01 + 3.889998E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.889998E+01 0.000000E+00 5 3.656395E+02 8.996265E+01 2.383312E-01 3.656394E+02 + 3.889998E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.889998E+01 3.000000E+01 1 2.962646E+01 8.996265E+01 1.931144E-02 2.962645E+01 + 3.889998E+01 3.000000E+01 2 1.808017E+01 8.995871E+01 1.303136E-02 1.808017E+01 + 3.889998E+01 3.000000E+01 3 1.954939E+02 1.630118E-01 1.954931E+02 5.561976E-01 + 3.889998E+01 3.000000E+01 4 5.812726E+01 8.995855E+01 4.205388E-02 5.812724E+01 + 3.889998E+01 3.000000E+01 5 3.172439E+02 8.996265E+01 2.067901E-01 3.172438E+02 + 3.889998E+01 3.000000E+01 6 3.428415E+01 -2.519286E-04 3.428415E+01 -1.507468E-04 + 3.889998E+01 6.000000E+01 1 1.717017E+01 8.996265E+01 1.119160E-02 1.717017E+01 + 3.889998E+01 6.000000E+01 2 3.144697E+01 8.995870E+01 2.266631E-02 3.144696E+01 + 3.889998E+01 6.000000E+01 3 1.963335E+02 1.633135E-01 1.963327E+02 5.596203E-01 + 3.889998E+01 6.000000E+01 4 1.014834E+02 8.995870E+01 7.314708E-02 1.014833E+02 + 3.889998E+01 6.000000E+01 5 1.838428E+02 8.996265E+01 1.198407E-01 1.838428E+02 + 3.889998E+01 6.000000E+01 6 3.443210E+01 -2.515617E-04 3.443210E+01 -1.511769E-04 + 3.889998E+01 9.000000E+01 1 1.775305E-06 -9.002911E+01 -9.021112E-10 -1.775304E-06 + 3.889998E+01 9.000000E+01 2 3.638785E+01 8.995870E+01 2.622797E-02 3.638784E+01 + 3.889998E+01 9.000000E+01 3 1.967545E+02 1.634650E-01 1.967537E+02 5.613403E-01 + 3.889998E+01 9.000000E+01 4 1.176478E+02 8.995878E+01 8.464115E-02 1.176478E+02 + 3.889998E+01 9.000000E+01 5 8.268830E-05 -8.999559E+01 6.366200E-09 -8.268830E-05 + 3.889998E+01 9.000000E+01 6 2.951078E-06 1.799998E+02 -2.951078E-06 8.777554E-12 + 3.899998E+01 0.000000E+00 1 3.405686E+01 8.996285E+01 2.208090E-02 3.405685E+01 + 3.899998E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.899998E+01 0.000000E+00 3 1.951421E+02 1.620051E-01 1.951413E+02 5.517677E-01 + 3.899998E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.899998E+01 0.000000E+00 5 3.647970E+02 8.996285E+01 2.365089E-01 3.647969E+02 + 3.899998E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.899998E+01 3.000000E+01 1 2.955007E+01 8.996285E+01 1.915849E-02 2.955006E+01 + 3.899998E+01 3.000000E+01 2 1.803357E+01 8.995893E+01 1.292512E-02 1.803357E+01 + 3.899998E+01 3.000000E+01 3 1.955587E+02 1.621533E-01 1.955579E+02 5.534516E-01 + 3.899998E+01 3.000000E+01 4 5.797203E+01 8.995879E+01 4.170631E-02 5.797201E+01 + 3.899998E+01 3.000000E+01 5 3.165098E+02 8.996285E+01 2.052068E-01 3.165097E+02 + 3.899998E+01 3.000000E+01 6 3.410376E+01 -2.491638E-04 3.410376E+01 -1.483080E-04 + 3.899998E+01 6.000000E+01 1 1.712564E+01 8.996285E+01 1.110271E-02 1.712564E+01 + 3.899998E+01 6.000000E+01 2 3.136529E+01 8.995893E+01 2.248104E-02 3.136529E+01 + 3.899998E+01 6.000000E+01 3 1.963934E+02 1.624531E-01 1.963926E+02 5.568416E-01 + 3.899998E+01 6.000000E+01 4 1.012081E+02 8.995893E+01 7.254077E-02 1.012081E+02 + 3.899998E+01 6.000000E+01 5 1.834148E+02 8.996285E+01 1.189201E-01 1.834147E+02 + 3.899998E+01 6.000000E+01 6 3.425019E+01 -2.488024E-04 3.425019E+01 -1.487288E-04 + 3.899998E+01 9.000000E+01 1 1.770651E-06 -9.002898E+01 -8.954974E-10 -1.770651E-06 + 3.899998E+01 9.000000E+01 2 3.629293E+01 8.995893E+01 2.601330E-02 3.629293E+01 + 3.899998E+01 9.000000E+01 3 1.968125E+02 1.626020E-01 1.968117E+02 5.585414E-01 + 3.899998E+01 9.000000E+01 4 1.173267E+02 8.995901E+01 8.393834E-02 1.173267E+02 + 3.899998E+01 9.000000E+01 5 8.247911E-05 -8.999562E+01 6.308041E-09 -8.247911E-05 + 3.899998E+01 9.000000E+01 6 2.935438E-06 1.799998E+02 -2.935438E-06 8.635521E-12 + 3.909998E+01 0.000000E+00 1 3.396978E+01 8.996305E+01 2.190661E-02 3.396977E+01 + 3.909998E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.909998E+01 0.000000E+00 3 1.952079E+02 1.611567E-01 1.952072E+02 5.490637E-01 + 3.909998E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.909998E+01 0.000000E+00 5 3.639585E+02 8.996305E+01 2.347051E-01 3.639584E+02 + 3.909998E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.909998E+01 3.000000E+01 1 2.947422E+01 8.996305E+01 1.900715E-02 2.947422E+01 + 3.909998E+01 3.000000E+01 2 1.798721E+01 8.995917E+01 1.282006E-02 1.798721E+01 + 3.909998E+01 3.000000E+01 3 1.956223E+02 1.613045E-01 1.956215E+02 5.507337E-01 + 3.909998E+01 3.000000E+01 4 5.781799E+01 8.995901E+01 4.136275E-02 5.781797E+01 + 3.909998E+01 3.000000E+01 5 3.157769E+02 8.996305E+01 2.036388E-01 3.157769E+02 + 3.909998E+01 3.000000E+01 6 3.392479E+01 -2.464363E-04 3.392479E+01 -1.459147E-04 + 3.909998E+01 6.000000E+01 1 1.708125E+01 8.996305E+01 1.101480E-02 1.708125E+01 + 3.909998E+01 6.000000E+01 2 3.128394E+01 8.995917E+01 2.229775E-02 3.128393E+01 + 3.909998E+01 6.000000E+01 3 1.964524E+02 1.616001E-01 1.964516E+02 5.540842E-01 + 3.909998E+01 6.000000E+01 4 1.009349E+02 8.995917E+01 7.194161E-02 1.009349E+02 + 3.909998E+01 6.000000E+01 5 1.829868E+02 8.996305E+01 1.180084E-01 1.829867E+02 + 3.909998E+01 6.000000E+01 6 3.406966E+01 -2.460813E-04 3.406966E+01 -1.463267E-04 + 3.909998E+01 9.000000E+01 1 1.766017E-06 -9.002884E+01 -8.889448E-10 -1.766017E-06 + 3.909998E+01 9.000000E+01 2 3.619840E+01 8.995917E+01 2.580091E-02 3.619839E+01 + 3.909998E+01 9.000000E+01 3 1.968699E+02 1.617472E-01 1.968691E+02 5.557670E-01 + 3.909998E+01 9.000000E+01 4 1.170073E+02 8.995924E+01 8.324438E-02 1.170073E+02 + 3.909998E+01 9.000000E+01 5 8.227113E-05 -8.999564E+01 6.250598E-09 -8.227113E-05 + 3.909998E+01 9.000000E+01 6 2.919919E-06 1.799998E+02 -2.919919E-06 8.496176E-12 + 3.919997E+01 0.000000E+00 1 3.388295E+01 8.996325E+01 2.173422E-02 3.388294E+01 + 3.919997E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.919997E+01 0.000000E+00 3 1.952734E+02 1.603131E-01 1.952726E+02 5.463727E-01 + 3.919997E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.919997E+01 0.000000E+00 5 3.631222E+02 8.996325E+01 2.329175E-01 3.631221E+02 + 3.919997E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.919997E+01 3.000000E+01 1 2.939861E+01 8.996325E+01 1.885731E-02 2.939861E+01 + 3.919997E+01 3.000000E+01 2 1.794117E+01 8.995939E+01 1.271612E-02 1.794117E+01 + 3.919997E+01 3.000000E+01 3 1.956850E+02 1.604601E-01 1.956842E+02 5.480261E-01 + 3.919997E+01 3.000000E+01 4 5.766457E+01 8.995924E+01 4.102307E-02 5.766455E+01 + 3.919997E+01 3.000000E+01 5 3.150517E+02 8.996325E+01 2.020848E-01 3.150516E+02 + 3.919997E+01 3.000000E+01 6 3.374725E+01 -2.437465E-04 3.374725E+01 -1.435669E-04 + 3.919997E+01 6.000000E+01 1 1.703708E+01 8.996325E+01 1.092779E-02 1.703708E+01 + 3.919997E+01 6.000000E+01 2 3.120308E+01 8.995939E+01 2.211652E-02 3.120308E+01 + 3.919997E+01 6.000000E+01 3 1.965120E+02 1.607524E-01 1.965112E+02 5.513449E-01 + 3.919997E+01 6.000000E+01 4 1.006631E+02 8.995939E+01 7.134892E-02 1.006630E+02 + 3.919997E+01 6.000000E+01 5 1.825623E+02 8.996325E+01 1.171067E-01 1.825623E+02 + 3.919997E+01 6.000000E+01 6 3.389055E+01 -2.433969E-04 3.389055E+01 -1.439697E-04 + 3.919997E+01 9.000000E+01 1 1.761410E-06 -9.002870E+01 -8.824554E-10 -1.761410E-06 + 3.919997E+01 9.000000E+01 2 3.610443E+01 8.995939E+01 2.559089E-02 3.610442E+01 + 3.919997E+01 9.000000E+01 3 1.969265E+02 1.608983E-01 1.969257E+02 5.530092E-01 + 3.919997E+01 9.000000E+01 4 1.166896E+02 8.995947E+01 8.255763E-02 1.166896E+02 + 3.919997E+01 9.000000E+01 5 8.206412E-05 -8.999567E+01 6.193852E-09 -8.206412E-05 + 3.919997E+01 9.000000E+01 6 2.904526E-06 1.799998E+02 -2.904526E-06 8.359447E-12 + 3.929997E+01 0.000000E+00 1 3.379663E+01 8.996344E+01 2.156364E-02 3.379663E+01 + 3.929997E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.929997E+01 0.000000E+00 3 1.953394E+02 1.594785E-01 1.953386E+02 5.437119E-01 + 3.929997E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.929997E+01 0.000000E+00 5 3.622920E+02 8.996345E+01 2.311483E-01 3.622919E+02 + 3.929997E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.929997E+01 3.000000E+01 1 2.932339E+01 8.996344E+01 1.870916E-02 2.932339E+01 + 3.929997E+01 3.000000E+01 2 1.789528E+01 8.995962E+01 1.261331E-02 1.789528E+01 + 3.929997E+01 3.000000E+01 3 1.957492E+02 1.596229E-01 1.957484E+02 5.453456E-01 + 3.929997E+01 3.000000E+01 4 5.751168E+01 8.995947E+01 4.068685E-02 5.751167E+01 + 3.929997E+01 3.000000E+01 5 3.143284E+02 8.996344E+01 2.005516E-01 3.143284E+02 + 3.929997E+01 3.000000E+01 6 3.357107E+01 -2.410939E-04 3.357107E+01 -1.412631E-04 + 3.929997E+01 6.000000E+01 1 1.699323E+01 8.996345E+01 1.084175E-02 1.699322E+01 + 3.929997E+01 6.000000E+01 2 3.112264E+01 8.995962E+01 2.193721E-02 3.112263E+01 + 3.929997E+01 6.000000E+01 3 1.965709E+02 1.599131E-01 1.965702E+02 5.486308E-01 + 3.929997E+01 6.000000E+01 4 1.003924E+02 8.995962E+01 7.076288E-02 1.003924E+02 + 3.929997E+01 6.000000E+01 5 1.821382E+02 8.996344E+01 1.162149E-01 1.821382E+02 + 3.929997E+01 6.000000E+01 6 3.371286E+01 -2.407503E-04 3.371286E+01 -1.416576E-04 + 3.929997E+01 9.000000E+01 1 1.756834E-06 -9.002857E+01 -8.760297E-10 -1.756833E-06 + 3.929997E+01 9.000000E+01 2 3.601104E+01 8.995962E+01 2.538322E-02 3.601103E+01 + 3.929997E+01 9.000000E+01 3 1.969830E+02 1.600578E-01 1.969823E+02 5.502785E-01 + 3.929997E+01 9.000000E+01 4 1.163734E+02 8.995969E+01 8.187878E-02 1.163734E+02 + 3.929997E+01 9.000000E+01 5 8.185828E-05 -8.999570E+01 6.137809E-09 -8.185828E-05 + 3.929997E+01 9.000000E+01 6 2.889259E-06 1.799998E+02 -2.889259E-06 8.225309E-12 + 3.939997E+01 0.000000E+00 1 3.371078E+01 8.996364E+01 2.139489E-02 3.371077E+01 + 3.939997E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.939997E+01 0.000000E+00 3 1.954022E+02 1.586507E-01 1.954014E+02 5.410634E-01 + 3.939997E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.939997E+01 0.000000E+00 5 3.614624E+02 8.996364E+01 2.293965E-01 3.614623E+02 + 3.939997E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.939997E+01 3.000000E+01 1 2.924857E+01 8.996364E+01 1.856255E-02 2.924856E+01 + 3.939997E+01 3.000000E+01 2 1.784966E+01 8.995984E+01 1.251166E-02 1.784965E+01 + 3.939997E+01 3.000000E+01 3 1.958103E+02 1.587934E-01 1.958095E+02 5.426812E-01 + 3.939997E+01 3.000000E+01 4 5.736006E+01 8.995969E+01 4.035443E-02 5.736004E+01 + 3.939997E+01 3.000000E+01 5 3.136049E+02 8.996364E+01 1.990298E-01 3.136048E+02 + 3.939997E+01 3.000000E+01 6 3.339635E+01 -2.384769E-04 3.339635E+01 -1.390025E-04 + 3.939997E+01 6.000000E+01 1 1.694951E+01 8.996364E+01 1.075653E-02 1.694951E+01 + 3.939997E+01 6.000000E+01 2 3.104264E+01 8.995984E+01 2.175990E-02 3.104263E+01 + 3.939997E+01 6.000000E+01 3 1.966287E+02 1.590798E-01 1.966279E+02 5.459322E-01 + 3.939997E+01 6.000000E+01 4 1.001236E+02 8.995984E+01 7.018323E-02 1.001236E+02 + 3.939997E+01 6.000000E+01 5 1.817164E+02 8.996364E+01 1.153312E-01 1.817164E+02 + 3.939997E+01 6.000000E+01 6 3.353666E+01 -2.381391E-04 3.353666E+01 -1.393888E-04 + 3.939997E+01 9.000000E+01 1 1.752274E-06 -9.002843E+01 -8.696640E-10 -1.752274E-06 + 3.939997E+01 9.000000E+01 2 3.591804E+01 8.995984E+01 2.517774E-02 3.591803E+01 + 3.939997E+01 9.000000E+01 3 1.970393E+02 1.592227E-01 1.970385E+02 5.475637E-01 + 3.939997E+01 9.000000E+01 4 1.160600E+02 8.995991E+01 8.120712E-02 1.160599E+02 + 3.939997E+01 9.000000E+01 5 8.165303E-05 -8.999574E+01 6.082472E-09 -8.165303E-05 + 3.939997E+01 9.000000E+01 6 2.874111E-06 1.799998E+02 -2.874111E-06 8.093693E-12 + 3.949997E+01 0.000000E+00 1 3.362540E+01 8.996383E+01 2.122781E-02 3.362540E+01 + 3.949997E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.949997E+01 0.000000E+00 3 1.954662E+02 1.578299E-01 1.954655E+02 5.384407E-01 + 3.949997E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.949997E+01 0.000000E+00 5 3.606382E+02 8.996383E+01 2.276646E-01 3.606382E+02 + 3.949997E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.949997E+01 3.000000E+01 1 2.917422E+01 8.996383E+01 1.841743E-02 2.917421E+01 + 3.949997E+01 3.000000E+01 2 1.780424E+01 8.996006E+01 1.241106E-02 1.780424E+01 + 3.949997E+01 3.000000E+01 3 1.958724E+02 1.579709E-01 1.958716E+02 5.400416E-01 + 3.949997E+01 3.000000E+01 4 5.720912E+01 8.995992E+01 4.002571E-02 5.720910E+01 + 3.949997E+01 3.000000E+01 5 3.128855E+02 8.996383E+01 1.975245E-01 3.128854E+02 + 3.949997E+01 3.000000E+01 6 3.322294E+01 -2.358966E-04 3.322294E+01 -1.367846E-04 + 3.949997E+01 6.000000E+01 1 1.690606E+01 8.996383E+01 1.067225E-02 1.690606E+01 + 3.949997E+01 6.000000E+01 2 3.096300E+01 8.996006E+01 2.158453E-02 3.096299E+01 + 3.949997E+01 6.000000E+01 3 1.966864E+02 1.582534E-01 1.966857E+02 5.432558E-01 + 3.949997E+01 6.000000E+01 4 9.985601E+01 8.996006E+01 6.961045E-02 9.985599E+01 + 3.949997E+01 6.000000E+01 5 1.812978E+02 8.996383E+01 1.144561E-01 1.812977E+02 + 3.949997E+01 6.000000E+01 6 3.336178E+01 -2.355634E-04 3.336178E+01 -1.371622E-04 + 3.949997E+01 9.000000E+01 1 1.747740E-06 -9.002830E+01 -8.633546E-10 -1.747740E-06 + 3.949997E+01 9.000000E+01 2 3.582547E+01 8.996006E+01 2.497452E-02 3.582546E+01 + 3.949997E+01 9.000000E+01 3 1.970947E+02 1.583952E-01 1.970939E+02 5.448712E-01 + 3.949997E+01 9.000000E+01 4 1.157473E+02 8.996013E+01 8.054294E-02 1.157473E+02 + 3.949997E+01 9.000000E+01 5 8.144906E-05 -8.999577E+01 6.027777E-09 -8.144906E-05 + 3.949997E+01 9.000000E+01 6 2.859083E-06 1.799998E+02 -2.859083E-06 7.964525E-12 + 3.959997E+01 0.000000E+00 1 3.354033E+01 8.996402E+01 2.106253E-02 3.354033E+01 + 3.959997E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.959997E+01 0.000000E+00 3 1.955294E+02 1.570129E-01 1.955287E+02 5.358268E-01 + 3.959997E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.959997E+01 0.000000E+00 5 3.598151E+02 8.996402E+01 2.259508E-01 3.598151E+02 + 3.959997E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.959997E+01 3.000000E+01 1 2.910024E+01 8.996402E+01 1.827392E-02 2.910023E+01 + 3.959997E+01 3.000000E+01 2 1.775911E+01 8.996028E+01 1.231158E-02 1.775911E+01 + 3.959997E+01 3.000000E+01 3 1.959340E+02 1.571523E-01 1.959333E+02 5.374121E-01 + 3.959997E+01 3.000000E+01 4 5.705909E+01 8.996014E+01 3.970068E-02 5.705908E+01 + 3.959997E+01 3.000000E+01 5 3.121678E+02 8.996402E+01 1.960340E-01 3.121678E+02 + 3.959997E+01 3.000000E+01 6 3.305095E+01 -2.333516E-04 3.305095E+01 -1.346084E-04 + 3.959997E+01 6.000000E+01 1 1.686282E+01 8.996402E+01 1.058887E-02 1.686282E+01 + 3.959997E+01 6.000000E+01 2 3.088385E+01 8.996028E+01 2.141110E-02 3.088384E+01 + 3.959997E+01 6.000000E+01 3 1.967436E+02 1.574331E-01 1.967428E+02 5.405967E-01 + 3.959997E+01 6.000000E+01 4 9.959005E+01 8.996028E+01 6.904355E-02 9.959003E+01 + 3.959997E+01 6.000000E+01 5 1.808781E+02 8.996402E+01 1.135908E-01 1.808781E+02 + 3.959997E+01 6.000000E+01 6 3.318834E+01 -2.330239E-04 3.318834E+01 -1.349781E-04 + 3.959997E+01 9.000000E+01 1 1.743232E-06 -9.002817E+01 -8.571087E-10 -1.743231E-06 + 3.959997E+01 9.000000E+01 2 3.573349E+01 8.996028E+01 2.477355E-02 3.573348E+01 + 3.959997E+01 9.000000E+01 3 1.971499E+02 1.575725E-01 1.971491E+02 5.421928E-01 + 3.959997E+01 9.000000E+01 4 1.154367E+02 8.996035E+01 7.988608E-02 1.154367E+02 + 3.959997E+01 9.000000E+01 5 8.124601E-05 -8.999579E+01 5.973753E-09 -8.124601E-05 + 3.959997E+01 9.000000E+01 6 2.844173E-06 1.799998E+02 -2.844173E-06 7.837810E-12 + 3.969997E+01 0.000000E+00 1 3.345576E+01 8.996420E+01 2.089904E-02 3.345575E+01 + 3.969997E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.969997E+01 0.000000E+00 3 1.955931E+02 1.562038E-01 1.955923E+02 5.332388E-01 + 3.969997E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.969997E+01 0.000000E+00 5 3.590002E+02 8.996421E+01 2.242514E-01 3.590001E+02 + 3.969997E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.969997E+01 3.000000E+01 1 2.902649E+01 8.996421E+01 1.813183E-02 2.902649E+01 + 3.969997E+01 3.000000E+01 2 1.771418E+01 8.996049E+01 1.221318E-02 1.771418E+01 + 3.969997E+01 3.000000E+01 3 1.959948E+02 1.563422E-01 1.959940E+02 5.348075E-01 + 3.969997E+01 3.000000E+01 4 5.690964E+01 8.996036E+01 3.937916E-02 5.690963E+01 + 3.969997E+01 3.000000E+01 5 3.114583E+02 8.996421E+01 1.945570E-01 3.114583E+02 + 3.969997E+01 3.000000E+01 6 3.288022E+01 -2.308407E-04 3.288022E+01 -1.324721E-04 + 3.969997E+01 6.000000E+01 1 1.681982E+01 8.996421E+01 1.050632E-02 1.681982E+01 + 3.969997E+01 6.000000E+01 2 3.080498E+01 8.996049E+01 2.123948E-02 3.080497E+01 + 3.969997E+01 6.000000E+01 3 1.968004E+02 1.566199E-01 1.967996E+02 5.379595E-01 + 3.969997E+01 6.000000E+01 4 9.932550E+01 8.996049E+01 6.848279E-02 9.932548E+01 + 3.969997E+01 6.000000E+01 5 1.804632E+02 8.996420E+01 1.127336E-01 1.804632E+02 + 3.969997E+01 6.000000E+01 6 3.301622E+01 -2.305184E-04 3.301622E+01 -1.328343E-04 + 3.969997E+01 9.000000E+01 1 1.738743E-06 -9.002804E+01 -8.509217E-10 -1.738743E-06 + 3.969997E+01 9.000000E+01 2 3.564193E+01 8.996049E+01 2.457472E-02 3.564192E+01 + 3.969997E+01 9.000000E+01 3 1.972052E+02 1.567585E-01 1.972045E+02 5.395434E-01 + 3.969997E+01 9.000000E+01 4 1.151276E+02 8.996056E+01 7.923673E-02 1.151276E+02 + 3.969997E+01 9.000000E+01 5 8.104412E-05 -8.999582E+01 5.920403E-09 -8.104412E-05 + 3.969997E+01 9.000000E+01 6 2.829380E-06 1.799998E+02 -2.829380E-06 7.713447E-12 + 3.979996E+01 0.000000E+00 1 3.337165E+01 8.996440E+01 2.073719E-02 3.337165E+01 + 3.979996E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.979996E+01 0.000000E+00 3 1.956555E+02 1.554000E-01 1.956548E+02 5.306646E-01 + 3.979996E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.979996E+01 0.000000E+00 5 3.581830E+02 8.996440E+01 2.225686E-01 3.581829E+02 + 3.979996E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.979996E+01 3.000000E+01 1 2.895323E+01 8.996440E+01 1.799129E-02 2.895322E+01 + 3.979996E+01 3.000000E+01 2 1.766949E+01 8.996072E+01 1.211583E-02 1.766948E+01 + 3.979996E+01 3.000000E+01 3 1.960547E+02 1.555372E-01 1.960539E+02 5.322164E-01 + 3.979996E+01 3.000000E+01 4 5.676097E+01 8.996057E+01 3.906113E-02 5.676096E+01 + 3.979996E+01 3.000000E+01 5 3.107473E+02 8.996440E+01 1.930959E-01 3.107473E+02 + 3.979996E+01 3.000000E+01 6 3.271090E+01 -2.283640E-04 3.271090E+01 -1.303760E-04 + 3.979996E+01 6.000000E+01 1 1.677704E+01 8.996440E+01 1.042467E-02 1.677704E+01 + 3.979996E+01 6.000000E+01 2 3.072663E+01 8.996071E+01 2.106973E-02 3.072662E+01 + 3.979996E+01 6.000000E+01 3 1.968573E+02 1.558108E-01 1.968566E+02 5.353352E-01 + 3.979996E+01 6.000000E+01 4 9.906238E+01 8.996071E+01 6.792869E-02 9.906236E+01 + 3.979996E+01 6.000000E+01 5 1.800471E+02 8.996440E+01 1.118849E-01 1.800470E+02 + 3.979996E+01 6.000000E+01 6 3.284549E+01 -2.280467E-04 3.284549E+01 -1.307305E-04 + 3.979996E+01 9.000000E+01 1 1.734281E-06 -9.002791E+01 -8.447912E-10 -1.734280E-06 + 3.979996E+01 9.000000E+01 2 3.555087E+01 8.996071E+01 2.437809E-02 3.555086E+01 + 3.979996E+01 9.000000E+01 3 1.972593E+02 1.559485E-01 1.972585E+02 5.369024E-01 + 3.979996E+01 9.000000E+01 4 1.148204E+02 8.996078E+01 7.859468E-02 1.148204E+02 + 3.979996E+01 9.000000E+01 5 8.084311E-05 -8.999584E+01 5.867694E-09 -8.084311E-05 + 3.979996E+01 9.000000E+01 6 2.814705E-06 1.799998E+02 -2.814705E-06 7.591388E-12 + 3.989996E+01 0.000000E+00 1 3.328785E+01 8.996458E+01 2.057702E-02 3.328784E+01 + 3.989996E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.989996E+01 0.000000E+00 3 1.957177E+02 1.546028E-01 1.957170E+02 5.281100E-01 + 3.989996E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.989996E+01 0.000000E+00 5 3.573719E+02 8.996458E+01 2.209041E-01 3.573719E+02 + 3.989996E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.989996E+01 3.000000E+01 1 2.888029E+01 8.996458E+01 1.785210E-02 2.888028E+01 + 3.989996E+01 3.000000E+01 2 1.762500E+01 8.996093E+01 1.201955E-02 1.762499E+01 + 3.989996E+01 3.000000E+01 3 1.961149E+02 1.547392E-01 1.961142E+02 5.296485E-01 + 3.989996E+01 3.000000E+01 4 5.661314E+01 8.996078E+01 3.874672E-02 5.661313E+01 + 3.989996E+01 3.000000E+01 5 3.100419E+02 8.996458E+01 1.916507E-01 3.100419E+02 + 3.989996E+01 3.000000E+01 6 3.254287E+01 -2.259212E-04 3.254287E+01 -1.283188E-04 + 3.989996E+01 6.000000E+01 1 1.673446E+01 8.996458E+01 1.034388E-02 1.673446E+01 + 3.989996E+01 6.000000E+01 2 3.064868E+01 8.996093E+01 2.090178E-02 3.064867E+01 + 3.989996E+01 6.000000E+01 3 1.969134E+02 1.550093E-01 1.969127E+02 5.327333E-01 + 3.989996E+01 6.000000E+01 4 9.880065E+01 8.996093E+01 6.738003E-02 9.880063E+01 + 3.989996E+01 6.000000E+01 5 1.796355E+02 8.996458E+01 1.110448E-01 1.796355E+02 + 3.989996E+01 6.000000E+01 6 3.267602E+01 -2.256090E-04 3.267602E+01 -1.286658E-04 + 3.989996E+01 9.000000E+01 1 1.729837E-06 -9.002778E+01 -8.387184E-10 -1.729837E-06 + 3.989996E+01 9.000000E+01 2 3.546024E+01 8.996093E+01 2.418354E-02 3.546024E+01 + 3.989996E+01 9.000000E+01 3 1.973143E+02 1.551450E-01 1.973135E+02 5.342851E-01 + 3.989996E+01 9.000000E+01 4 1.145147E+02 8.996100E+01 7.795913E-02 1.145147E+02 + 3.989996E+01 9.000000E+01 5 8.064335E-05 -8.999587E+01 5.815583E-09 -8.064335E-05 + 3.989996E+01 9.000000E+01 6 2.800145E-06 1.799998E+02 -2.800145E-06 7.471601E-12 + 3.999996E+01 0.000000E+00 1 3.320465E+01 8.996477E+01 2.041850E-02 3.320465E+01 + 3.999996E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.999996E+01 0.000000E+00 3 1.957785E+02 1.538118E-01 1.957778E+02 5.255712E-01 + 3.999996E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.999996E+01 0.000000E+00 5 3.565649E+02 8.996477E+01 2.192550E-01 3.565648E+02 + 3.999996E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 3.999996E+01 3.000000E+01 1 2.880771E+01 8.996477E+01 1.771444E-02 2.880770E+01 + 3.999996E+01 3.000000E+01 2 1.758072E+01 8.996114E+01 1.192426E-02 1.758072E+01 + 3.999996E+01 3.000000E+01 3 1.961747E+02 1.539455E-01 1.961740E+02 5.270925E-01 + 3.999996E+01 3.000000E+01 4 5.646617E+01 8.996101E+01 3.843560E-02 5.646616E+01 + 3.999996E+01 3.000000E+01 5 3.093363E+02 8.996477E+01 1.902190E-01 3.093362E+02 + 3.999996E+01 3.000000E+01 6 3.237609E+01 -2.235112E-04 3.237609E+01 -1.262993E-04 + 3.999996E+01 6.000000E+01 1 1.669209E+01 8.996478E+01 1.026392E-02 1.669209E+01 + 3.999996E+01 6.000000E+01 2 3.057104E+01 8.996114E+01 2.073569E-02 3.057104E+01 + 3.999996E+01 6.000000E+01 3 1.969688E+02 1.542149E-01 1.969681E+02 5.301523E-01 + 3.999996E+01 6.000000E+01 4 9.854043E+01 8.996114E+01 6.683791E-02 9.854041E+01 + 3.999996E+01 6.000000E+01 5 1.792234E+02 8.996477E+01 1.102135E-01 1.792234E+02 + 3.999996E+01 6.000000E+01 6 3.250790E+01 -2.232043E-04 3.250790E+01 -1.266394E-04 + 3.999996E+01 9.000000E+01 1 1.725425E-06 -9.002765E+01 -8.327025E-10 -1.725425E-06 + 3.999996E+01 9.000000E+01 2 3.537007E+01 8.996114E+01 2.399109E-02 3.537006E+01 + 3.999996E+01 9.000000E+01 3 1.973673E+02 1.543482E-01 1.973666E+02 5.316841E-01 + 3.999996E+01 9.000000E+01 4 1.142105E+02 8.996120E+01 7.733064E-02 1.142104E+02 + 3.999996E+01 9.000000E+01 5 8.044456E-05 -8.999590E+01 5.764136E-09 -8.044456E-05 + 3.999996E+01 9.000000E+01 6 2.785697E-06 1.799999E+02 -2.785697E-06 7.354008E-12 + 4.009996E+01 0.000000E+00 1 3.312164E+01 8.996495E+01 2.026160E-02 3.312163E+01 + 4.009996E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 4.009996E+01 0.000000E+00 3 1.958400E+02 1.530287E-01 1.958392E+02 5.230594E-01 + 4.009996E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 4.009996E+01 0.000000E+00 5 3.557611E+02 8.996495E+01 2.176235E-01 3.557611E+02 + 4.009996E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 4.009996E+01 3.000000E+01 1 2.873561E+01 8.996495E+01 1.757813E-02 2.873560E+01 + 4.009996E+01 3.000000E+01 2 1.753668E+01 8.996135E+01 1.183001E-02 1.753667E+01 + 4.009996E+01 3.000000E+01 3 1.962338E+02 1.531619E-01 1.962331E+02 5.245677E-01 + 4.009996E+01 3.000000E+01 4 5.631999E+01 8.996121E+01 3.812789E-02 5.631998E+01 + 4.009996E+01 3.000000E+01 5 3.086360E+02 8.996495E+01 1.887998E-01 3.086359E+02 + 4.009996E+01 3.000000E+01 6 3.221068E+01 -2.211336E-04 3.221068E+01 -1.243174E-04 + 4.009996E+01 6.000000E+01 1 1.665001E+01 8.996495E+01 1.018477E-02 1.665000E+01 + 4.009996E+01 6.000000E+01 2 3.049393E+01 8.996135E+01 2.057135E-02 3.049392E+01 + 4.009996E+01 6.000000E+01 3 1.970240E+02 1.534273E-01 1.970233E+02 5.275925E-01 + 4.009996E+01 6.000000E+01 4 9.828146E+01 8.996135E+01 6.630120E-02 9.828143E+01 + 4.009996E+01 6.000000E+01 5 1.788146E+02 8.996495E+01 1.093894E-01 1.788146E+02 + 4.009996E+01 6.000000E+01 6 3.234111E+01 -2.208314E-04 3.234111E+01 -1.246502E-04 + 4.009996E+01 9.000000E+01 1 1.721028E-06 -9.002752E+01 -8.267444E-10 -1.721028E-06 + 4.009996E+01 9.000000E+01 2 3.528042E+01 8.996135E+01 2.380072E-02 3.528041E+01 + 4.009996E+01 9.000000E+01 3 1.974205E+02 1.535598E-01 1.974198E+02 5.291107E-01 + 4.009996E+01 9.000000E+01 4 1.139085E+02 8.996142E+01 7.670912E-02 1.139085E+02 + 4.009996E+01 9.000000E+01 5 8.024606E-05 -8.999592E+01 5.713281E-09 -8.024606E-05 + 4.009996E+01 9.000000E+01 6 2.771365E-06 1.799999E+02 -2.771365E-06 7.238607E-12 + 4.019996E+01 0.000000E+00 1 3.303928E+01 8.996513E+01 2.010638E-02 3.303927E+01 + 4.019996E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 4.019996E+01 0.000000E+00 3 1.959009E+02 1.522496E-01 1.959002E+02 5.205586E-01 + 4.019996E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 4.019996E+01 0.000000E+00 5 3.549574E+02 8.996513E+01 2.160077E-01 3.549573E+02 + 4.019996E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 4.019996E+01 3.000000E+01 1 2.866374E+01 8.996513E+01 1.744330E-02 2.866374E+01 + 4.019996E+01 3.000000E+01 2 1.749287E+01 8.996156E+01 1.173675E-02 1.749286E+01 + 4.019996E+01 3.000000E+01 3 1.962927E+02 1.523809E-01 1.962921E+02 5.220496E-01 + 4.019996E+01 3.000000E+01 4 5.617453E+01 8.996142E+01 3.782352E-02 5.617452E+01 + 4.019996E+01 3.000000E+01 5 3.079387E+02 8.996513E+01 1.873970E-01 3.079387E+02 + 4.019996E+01 3.000000E+01 6 3.204650E+01 -2.187878E-04 3.204650E+01 -1.223717E-04 + 4.019996E+01 6.000000E+01 1 1.660806E+01 8.996513E+01 1.010648E-02 1.660806E+01 + 4.019996E+01 6.000000E+01 2 3.041706E+01 8.996156E+01 2.040876E-02 3.041706E+01 + 4.019996E+01 6.000000E+01 3 1.970783E+02 1.526451E-01 1.970776E+02 5.250474E-01 + 4.019996E+01 6.000000E+01 4 9.802399E+01 8.996156E+01 6.577053E-02 9.802396E+01 + 4.019996E+01 6.000000E+01 5 1.784067E+02 8.996513E+01 1.085742E-01 1.784067E+02 + 4.019996E+01 6.000000E+01 6 3.217555E+01 -2.184905E-04 3.217555E+01 -1.226976E-04 + 4.019996E+01 9.000000E+01 1 1.716656E-06 -9.002740E+01 -8.208414E-10 -1.716656E-06 + 4.019996E+01 9.000000E+01 2 3.519121E+01 8.996156E+01 2.361234E-02 3.519120E+01 + 4.019996E+01 9.000000E+01 3 1.974738E+02 1.527754E-01 1.974731E+02 5.265502E-01 + 4.019996E+01 9.000000E+01 4 1.136077E+02 8.996162E+01 7.609409E-02 1.136077E+02 + 4.019996E+01 9.000000E+01 5 8.004906E-05 -8.999595E+01 5.663037E-09 -8.004906E-05 + 4.019996E+01 9.000000E+01 6 2.757139E-06 1.799999E+02 -2.757139E-06 7.125311E-12 + 4.029996E+01 0.000000E+00 1 3.295703E+01 8.996532E+01 1.995263E-02 3.295702E+01 + 4.029996E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 4.029996E+01 0.000000E+00 3 1.959606E+02 1.514774E-01 1.959600E+02 5.180761E-01 + 4.029996E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 4.029996E+01 0.000000E+00 5 3.541636E+02 8.996532E+01 2.144059E-01 3.541636E+02 + 4.029996E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 4.029996E+01 3.000000E+01 1 2.859224E+01 8.996532E+01 1.730978E-02 2.859224E+01 + 4.029996E+01 3.000000E+01 2 1.744927E+01 8.996177E+01 1.164448E-02 1.744927E+01 + 4.029996E+01 3.000000E+01 3 1.963510E+02 1.516075E-01 1.963503E+02 5.195538E-01 + 4.029996E+01 3.000000E+01 4 5.602977E+01 8.996163E+01 3.752217E-02 5.602976E+01 + 4.029996E+01 3.000000E+01 5 3.072437E+02 8.996532E+01 1.860085E-01 3.072437E+02 + 4.029996E+01 3.000000E+01 6 3.188359E+01 -2.164738E-04 3.188359E+01 -1.204619E-04 + 4.029996E+01 6.000000E+01 1 1.656636E+01 8.996532E+01 1.002894E-02 1.656636E+01 + 4.029996E+01 6.000000E+01 2 3.034069E+01 8.996176E+01 2.024794E-02 3.034068E+01 + 4.029996E+01 6.000000E+01 3 1.971331E+02 1.518685E-01 1.971324E+02 5.225213E-01 + 4.029996E+01 6.000000E+01 4 9.776756E+01 8.996176E+01 6.524529E-02 9.776753E+01 + 4.029996E+01 6.000000E+01 5 1.780007E+02 8.996532E+01 1.077677E-01 1.780007E+02 + 4.029996E+01 6.000000E+01 6 3.201136E+01 -2.161809E-04 3.201136E+01 -1.207811E-04 + 4.029996E+01 9.000000E+01 1 1.712306E-06 -9.002727E+01 -8.149911E-10 -1.712306E-06 + 4.029996E+01 9.000000E+01 2 3.510244E+01 8.996176E+01 2.342605E-02 3.510243E+01 + 4.029996E+01 9.000000E+01 3 1.975260E+02 1.519973E-01 1.975253E+02 5.240071E-01 + 4.029996E+01 9.000000E+01 4 1.133087E+02 8.996183E+01 7.548621E-02 1.133086E+02 + 4.029996E+01 9.000000E+01 5 7.985276E-05 -8.999597E+01 5.613394E-09 -7.985276E-05 + 4.029996E+01 9.000000E+01 6 2.743030E-06 1.799999E+02 -2.743030E-06 7.014102E-12 + 4.039996E+01 0.000000E+00 1 3.287546E+01 8.996549E+01 1.980058E-02 3.287545E+01 + 4.039996E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 4.039996E+01 0.000000E+00 3 1.960204E+02 1.507102E-01 1.960197E+02 5.156092E-01 + 4.039996E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 4.039996E+01 0.000000E+00 5 3.533676E+02 8.996549E+01 2.128220E-01 3.533676E+02 + 4.039996E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 4.039996E+01 3.000000E+01 1 2.852114E+01 8.996549E+01 1.717774E-02 2.852114E+01 + 4.039996E+01 3.000000E+01 2 1.740592E+01 8.996198E+01 1.155320E-02 1.740591E+01 + 4.039996E+01 3.000000E+01 3 1.964086E+02 1.508387E-01 1.964080E+02 5.170711E-01 + 4.039996E+01 3.000000E+01 4 5.588592E+01 8.996184E+01 3.722446E-02 5.588591E+01 + 4.039996E+01 3.000000E+01 5 3.065521E+02 8.996549E+01 1.846313E-01 3.065520E+02 + 4.039996E+01 3.000000E+01 6 3.172192E+01 -2.141900E-04 3.172192E+01 -1.185867E-04 + 4.039996E+01 6.000000E+01 1 1.652482E+01 8.996550E+01 9.952208E-03 1.652481E+01 + 4.039996E+01 6.000000E+01 2 3.026465E+01 8.996198E+01 2.008883E-02 3.026465E+01 + 4.039996E+01 6.000000E+01 3 1.971876E+02 1.510966E-01 1.971869E+02 5.200093E-01 + 4.039996E+01 6.000000E+01 4 9.751318E+01 8.996198E+01 6.472613E-02 9.751316E+01 + 4.039996E+01 6.000000E+01 5 1.775966E+02 8.996549E+01 1.069684E-01 1.775965E+02 + 4.039996E+01 6.000000E+01 6 3.184841E+01 -2.139018E-04 3.184841E+01 -1.188994E-04 + 4.039996E+01 9.000000E+01 1 1.707981E-06 -9.002715E+01 -8.092000E-10 -1.707981E-06 + 4.039996E+01 9.000000E+01 2 3.501406E+01 8.996197E+01 2.324169E-02 3.501406E+01 + 4.039996E+01 9.000000E+01 3 1.975780E+02 1.512246E-01 1.975773E+02 5.214803E-01 + 4.039996E+01 9.000000E+01 4 1.130111E+02 8.996204E+01 7.488450E-02 1.130111E+02 + 4.039996E+01 9.000000E+01 5 7.965770E-05 -8.999600E+01 5.564346E-09 -7.965770E-05 + 4.039996E+01 9.000000E+01 6 2.729023E-06 1.799999E+02 -2.729023E-06 6.904941E-12 + 4.049995E+01 0.000000E+00 1 3.279421E+01 8.996567E+01 1.964999E-02 3.279420E+01 + 4.049995E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 4.049995E+01 0.000000E+00 3 1.960799E+02 1.499503E-01 1.960792E+02 5.131652E-01 + 4.049995E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 4.049995E+01 0.000000E+00 5 3.525754E+02 8.996567E+01 2.112527E-01 3.525753E+02 + 4.049995E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 4.049995E+01 3.000000E+01 1 2.845046E+01 8.996567E+01 1.704697E-02 2.845045E+01 + 4.049995E+01 3.000000E+01 2 1.736274E+01 8.996217E+01 1.146286E-02 1.736274E+01 + 4.049995E+01 3.000000E+01 3 1.964659E+02 1.500772E-01 1.964653E+02 5.146107E-01 + 4.049995E+01 3.000000E+01 4 5.574275E+01 8.996204E+01 3.692957E-02 5.574274E+01 + 4.049995E+01 3.000000E+01 5 3.058630E+02 8.996567E+01 1.832678E-01 3.058629E+02 + 4.049995E+01 3.000000E+01 6 3.156149E+01 -2.119369E-04 3.156149E+01 -1.167458E-04 + 4.049995E+01 6.000000E+01 1 1.648354E+01 8.996568E+01 9.876294E-03 1.648354E+01 + 4.049995E+01 6.000000E+01 2 3.018898E+01 8.996217E+01 1.993131E-02 3.018898E+01 + 4.049995E+01 6.000000E+01 3 1.972407E+02 1.503313E-01 1.972400E+02 5.175146E-01 + 4.049995E+01 6.000000E+01 4 9.725953E+01 8.996217E+01 6.421261E-02 9.725951E+01 + 4.049995E+01 6.000000E+01 5 1.771948E+02 8.996567E+01 1.061767E-01 1.771948E+02 + 4.049995E+01 6.000000E+01 6 3.168669E+01 -2.116531E-04 3.168669E+01 -1.170520E-04 + 4.049995E+01 9.000000E+01 1 1.703676E-06 -9.002702E+01 -8.034552E-10 -1.703675E-06 + 4.049995E+01 9.000000E+01 2 3.492622E+01 8.996217E+01 2.305922E-02 3.492622E+01 + 4.049995E+01 9.000000E+01 3 1.976297E+02 1.504593E-01 1.976290E+02 5.189769E-01 + 4.049995E+01 9.000000E+01 4 1.127156E+02 8.996224E+01 7.428924E-02 1.127155E+02 + 4.049995E+01 9.000000E+01 5 7.946385E-05 -8.999603E+01 5.515868E-09 -7.946385E-05 + 4.049995E+01 9.000000E+01 6 2.715130E-06 1.799999E+02 -2.715130E-06 6.797745E-12 + 4.059995E+01 0.000000E+00 1 3.271325E+01 8.996584E+01 1.950096E-02 3.271324E+01 + 4.059995E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 4.059995E+01 0.000000E+00 3 1.961385E+02 1.491946E-01 1.961378E+02 5.107317E-01 + 4.059995E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 4.059995E+01 0.000000E+00 5 3.517873E+02 8.996584E+01 2.096995E-01 3.517872E+02 + 4.059995E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 4.059995E+01 3.000000E+01 1 2.837998E+01 8.996584E+01 1.691754E-02 2.837998E+01 + 4.059995E+01 3.000000E+01 2 1.731980E+01 8.996238E+01 1.137349E-02 1.731979E+01 + 4.059995E+01 3.000000E+01 3 1.965233E+02 1.493207E-01 1.965226E+02 5.121662E-01 + 4.059995E+01 3.000000E+01 4 5.560034E+01 8.996225E+01 3.663821E-02 5.560033E+01 + 4.059995E+01 3.000000E+01 5 3.051753E+02 8.996584E+01 1.819187E-01 3.051753E+02 + 4.059995E+01 3.000000E+01 6 3.140228E+01 -2.097140E-04 3.140228E+01 -1.149386E-04 + 4.059995E+01 6.000000E+01 1 1.644245E+01 8.996584E+01 9.801122E-03 1.644245E+01 + 4.059995E+01 6.000000E+01 2 3.011368E+01 8.996238E+01 1.977553E-02 3.011367E+01 + 4.059995E+01 6.000000E+01 3 1.972942E+02 1.495721E-01 1.972936E+02 5.150411E-01 + 4.059995E+01 6.000000E+01 4 9.700747E+01 8.996238E+01 6.370434E-02 9.700745E+01 + 4.059995E+01 6.000000E+01 5 1.767935E+02 8.996584E+01 1.053927E-01 1.767935E+02 + 4.059995E+01 6.000000E+01 6 3.152621E+01 -2.094345E-04 3.152621E+01 -1.152385E-04 + 4.059995E+01 9.000000E+01 1 1.699390E-06 -9.002690E+01 -7.977697E-10 -1.699390E-06 + 4.059995E+01 9.000000E+01 2 3.483888E+01 8.996238E+01 2.287880E-02 3.483887E+01 + 4.059995E+01 9.000000E+01 3 1.976806E+02 1.496988E-01 1.976799E+02 5.164867E-01 + 4.059995E+01 9.000000E+01 4 1.124213E+02 8.996244E+01 7.370064E-02 1.124213E+02 + 4.059995E+01 9.000000E+01 5 7.927052E-05 -8.999605E+01 5.467943E-09 -7.927052E-05 + 4.059995E+01 9.000000E+01 6 2.701340E-06 1.799999E+02 -2.701340E-06 6.692506E-12 + 4.069995E+01 0.000000E+00 1 3.263289E+01 8.996603E+01 1.935353E-02 3.263288E+01 + 4.069995E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 4.069995E+01 0.000000E+00 3 1.961976E+02 1.484455E-01 1.961970E+02 5.083206E-01 + 4.069995E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 4.069995E+01 0.000000E+00 5 3.510041E+02 8.996603E+01 2.081631E-01 3.510041E+02 + 4.069995E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 4.069995E+01 3.000000E+01 1 2.830993E+01 8.996603E+01 1.678942E-02 2.830993E+01 + 4.069995E+01 3.000000E+01 2 1.727706E+01 8.996258E+01 1.128505E-02 1.727706E+01 + 4.069995E+01 3.000000E+01 3 1.965800E+02 1.485692E-01 1.965794E+02 5.097358E-01 + 4.069995E+01 3.000000E+01 4 5.545845E+01 8.996245E+01 3.634970E-02 5.545844E+01 + 4.069995E+01 3.000000E+01 5 3.044943E+02 8.996603E+01 1.805845E-01 3.044942E+02 + 4.069995E+01 3.000000E+01 6 3.124430E+01 -2.075199E-04 3.124430E+01 -1.131639E-04 + 4.069995E+01 6.000000E+01 1 1.640158E+01 8.996603E+01 9.726741E-03 1.640157E+01 + 4.069995E+01 6.000000E+01 2 3.003879E+01 8.996258E+01 1.962136E-02 3.003879E+01 + 4.069995E+01 6.000000E+01 3 1.973477E+02 1.488191E-01 1.973470E+02 5.125871E-01 + 4.069995E+01 6.000000E+01 4 9.675658E+01 8.996258E+01 6.320155E-02 9.675656E+01 + 4.069995E+01 6.000000E+01 5 1.763951E+02 8.996603E+01 1.046166E-01 1.763950E+02 + 4.069995E+01 6.000000E+01 6 3.136693E+01 -2.072453E-04 3.136693E+01 -1.134577E-04 + 4.069995E+01 9.000000E+01 1 1.695126E-06 -9.002678E+01 -7.921360E-10 -1.695126E-06 + 4.069995E+01 9.000000E+01 2 3.475193E+01 8.996258E+01 2.270026E-02 3.475192E+01 + 4.069995E+01 9.000000E+01 3 1.977326E+02 1.489436E-01 1.977319E+02 5.140165E-01 + 4.069995E+01 9.000000E+01 4 1.121284E+02 8.996264E+01 7.311802E-02 1.121284E+02 + 4.069995E+01 9.000000E+01 5 7.907810E-05 -8.999608E+01 5.420604E-09 -7.907810E-05 + 4.069995E+01 9.000000E+01 6 2.687661E-06 1.799999E+02 -2.687661E-06 6.589171E-12 + 4.079995E+01 0.000000E+00 1 3.255276E+01 8.996619E+01 1.920751E-02 3.255275E+01 + 4.079995E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 4.079995E+01 0.000000E+00 3 1.962558E+02 1.477009E-01 1.962551E+02 5.059208E-01 + 4.079995E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 4.079995E+01 0.000000E+00 5 3.502239E+02 8.996619E+01 2.066392E-01 3.502238E+02 + 4.079995E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 4.079995E+01 3.000000E+01 1 2.824017E+01 8.996619E+01 1.666256E-02 2.824016E+01 + 4.079995E+01 3.000000E+01 2 1.723453E+01 8.996277E+01 1.119755E-02 1.723453E+01 + 4.079995E+01 3.000000E+01 3 1.966361E+02 1.478246E-01 1.966355E+02 5.073256E-01 + 4.079995E+01 3.000000E+01 4 5.531755E+01 8.996265E+01 3.606433E-02 5.531754E+01 + 4.079995E+01 3.000000E+01 5 3.038132E+02 8.996619E+01 1.792597E-01 3.038131E+02 + 4.079995E+01 3.000000E+01 6 3.108752E+01 -2.053552E-04 3.108752E+01 -1.114216E-04 + 4.079995E+01 6.000000E+01 1 1.636086E+01 8.996619E+01 9.653110E-03 1.636086E+01 + 4.079995E+01 6.000000E+01 2 2.996427E+01 8.996277E+01 1.946885E-02 2.996426E+01 + 4.079995E+01 6.000000E+01 3 1.973997E+02 1.480717E-01 1.973990E+02 5.101469E-01 + 4.079995E+01 6.000000E+01 4 9.650729E+01 8.996277E+01 6.270389E-02 9.650727E+01 + 4.079995E+01 6.000000E+01 5 1.759977E+02 8.996619E+01 1.038493E-01 1.759977E+02 + 4.079995E+01 6.000000E+01 6 3.120890E+01 -2.050848E-04 3.120890E+01 -1.117093E-04 + 4.079995E+01 9.000000E+01 1 1.690887E-06 -9.002666E+01 -7.865527E-10 -1.690886E-06 + 4.079995E+01 9.000000E+01 2 3.466522E+01 8.996277E+01 2.252354E-02 3.466521E+01 + 4.079995E+01 9.000000E+01 3 1.977833E+02 1.481944E-01 1.977827E+02 5.115621E-01 + 4.079995E+01 9.000000E+01 4 1.118374E+02 8.996284E+01 7.254177E-02 1.118374E+02 + 4.079995E+01 9.000000E+01 5 7.888634E-05 -8.999609E+01 5.373834E-09 -7.888634E-05 + 4.079995E+01 9.000000E+01 6 2.674085E-06 1.799999E+02 -2.674085E-06 6.487719E-12 + 4.089995E+01 0.000000E+00 1 3.247310E+01 8.996636E+01 1.906293E-02 3.247309E+01 + 4.089995E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 4.089995E+01 0.000000E+00 3 1.963145E+02 1.469615E-01 1.963138E+02 5.035388E-01 + 4.089995E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 4.089995E+01 0.000000E+00 5 3.494464E+02 8.996636E+01 2.051320E-01 3.494464E+02 + 4.089995E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 4.089995E+01 3.000000E+01 1 2.817088E+01 8.996636E+01 1.653707E-02 2.817087E+01 + 4.089995E+01 3.000000E+01 2 1.719222E+01 8.996297E+01 1.111097E-02 1.719222E+01 + 4.089995E+01 3.000000E+01 3 1.966925E+02 1.470845E-01 1.966918E+02 5.049306E-01 + 4.089995E+01 3.000000E+01 4 5.517721E+01 8.996284E+01 3.578190E-02 5.517720E+01 + 4.089995E+01 3.000000E+01 5 3.031367E+02 8.996636E+01 1.779512E-01 3.031367E+02 + 4.089995E+01 3.000000E+01 6 3.093188E+01 -2.032194E-04 3.093188E+01 -1.097107E-04 + 4.089995E+01 6.000000E+01 1 1.632039E+01 8.996636E+01 9.580210E-03 1.632039E+01 + 4.089995E+01 6.000000E+01 2 2.989011E+01 8.996297E+01 1.931791E-02 2.989010E+01 + 4.089995E+01 6.000000E+01 3 1.974520E+02 1.473293E-01 1.974513E+02 5.077238E-01 + 4.089995E+01 6.000000E+01 4 9.625885E+01 8.996297E+01 6.221196E-02 9.625883E+01 + 4.089995E+01 6.000000E+01 5 1.756040E+02 8.996636E+01 1.030882E-01 1.756040E+02 + 4.089995E+01 6.000000E+01 6 3.105209E+01 -2.029524E-04 3.105209E+01 -1.099923E-04 + 4.089995E+01 9.000000E+01 1 1.686668E-06 -9.002654E+01 -7.810206E-10 -1.686668E-06 + 4.089995E+01 9.000000E+01 2 3.457918E+01 8.996297E+01 2.234869E-02 3.457917E+01 + 4.089995E+01 9.000000E+01 3 1.978335E+02 1.474513E-01 1.978328E+02 5.091259E-01 + 4.089995E+01 9.000000E+01 4 1.115479E+02 8.996303E+01 7.197204E-02 1.115479E+02 + 4.089995E+01 9.000000E+01 5 7.869596E-05 -8.999612E+01 5.327563E-09 -7.869596E-05 + 4.089995E+01 9.000000E+01 6 2.660611E-06 1.799999E+02 -2.660611E-06 6.388090E-12 + 4.099995E+01 0.000000E+00 1 3.239382E+01 8.996654E+01 1.891988E-02 3.239382E+01 + 4.099995E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 4.099995E+01 0.000000E+00 3 1.963704E+02 1.462304E-01 1.963698E+02 5.011762E-01 + 4.099995E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 4.099995E+01 0.000000E+00 5 3.486714E+02 8.996654E+01 2.036370E-01 3.486713E+02 + 4.099995E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 4.099995E+01 3.000000E+01 1 2.810176E+01 8.996654E+01 1.641283E-02 2.810175E+01 + 4.099995E+01 3.000000E+01 2 1.715014E+01 8.996317E+01 1.102528E-02 1.715014E+01 + 4.099995E+01 3.000000E+01 3 1.967476E+02 1.463505E-01 1.967469E+02 5.025514E-01 + 4.099995E+01 3.000000E+01 4 5.503794E+01 8.996304E+01 3.550260E-02 5.503793E+01 + 4.099995E+01 3.000000E+01 5 3.024617E+02 8.996654E+01 1.766532E-01 3.024617E+02 + 4.099995E+01 3.000000E+01 6 3.077749E+01 -2.011104E-04 3.077749E+01 -1.080302E-04 + 4.099995E+01 6.000000E+01 1 1.628016E+01 8.996654E+01 9.508057E-03 1.628015E+01 + 4.099995E+01 6.000000E+01 2 2.981628E+01 8.996317E+01 1.916851E-02 2.981628E+01 + 4.099995E+01 6.000000E+01 3 1.975037E+02 1.465924E-01 1.975031E+02 5.053167E-01 + 4.099995E+01 6.000000E+01 4 9.601196E+01 8.996317E+01 6.172496E-02 9.601194E+01 + 4.099995E+01 6.000000E+01 5 1.752095E+02 8.996654E+01 1.023354E-01 1.752095E+02 + 4.099995E+01 6.000000E+01 6 3.089643E+01 -2.008485E-04 3.089643E+01 -1.083064E-04 + 4.099995E+01 9.000000E+01 1 1.682470E-06 -9.002641E+01 -7.755393E-10 -1.682470E-06 + 4.099995E+01 9.000000E+01 2 3.449349E+01 8.996317E+01 2.217570E-02 3.449348E+01 + 4.099995E+01 9.000000E+01 3 1.978830E+02 1.467138E-01 1.978823E+02 5.067064E-01 + 4.099995E+01 9.000000E+01 4 1.112597E+02 8.996323E+01 7.140781E-02 1.112596E+02 + 4.099995E+01 9.000000E+01 5 7.850649E-05 -8.999615E+01 5.281842E-09 -7.850649E-05 + 4.099995E+01 9.000000E+01 6 2.647239E-06 1.799999E+02 -2.647239E-06 6.290251E-12 + 4.109995E+01 0.000000E+00 1 3.231490E+01 8.996671E+01 1.877822E-02 3.231489E+01 + 4.109995E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 4.109995E+01 0.000000E+00 3 1.964281E+02 1.455039E-01 1.964275E+02 4.988329E-01 + 4.109995E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 4.109995E+01 0.000000E+00 5 3.479012E+02 8.996671E+01 2.021575E-01 3.479011E+02 + 4.109995E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 4.109995E+01 3.000000E+01 1 2.803311E+01 8.996671E+01 1.628979E-02 2.803311E+01 + 4.109995E+01 3.000000E+01 2 1.710815E+01 8.996336E+01 1.094047E-02 1.710815E+01 + 4.109995E+01 3.000000E+01 3 1.968031E+02 1.456230E-01 1.968025E+02 5.001945E-01 + 4.109995E+01 3.000000E+01 4 5.489897E+01 8.996323E+01 3.522610E-02 5.489896E+01 + 4.109995E+01 3.000000E+01 5 3.017893E+02 8.996671E+01 1.753680E-01 3.017892E+02 + 4.109995E+01 3.000000E+01 6 3.062420E+01 -1.990296E-04 3.062420E+01 -1.063799E-04 + 4.109995E+01 6.000000E+01 1 1.624005E+01 8.996671E+01 9.436644E-03 1.624005E+01 + 4.109995E+01 6.000000E+01 2 2.974290E+01 8.996336E+01 1.902069E-02 2.974290E+01 + 4.109995E+01 6.000000E+01 3 1.975564E+02 1.458618E-01 1.975558E+02 5.029322E-01 + 4.109995E+01 6.000000E+01 4 9.576618E+01 8.996336E+01 6.124310E-02 9.576616E+01 + 4.109995E+01 6.000000E+01 5 1.748182E+02 8.996671E+01 1.015888E-01 1.748182E+02 + 4.109995E+01 6.000000E+01 6 3.074196E+01 -1.987714E-04 3.074196E+01 -1.066505E-04 + 4.109995E+01 9.000000E+01 1 1.678294E-06 -9.002629E+01 -7.701091E-10 -1.678294E-06 + 4.109995E+01 9.000000E+01 2 3.440830E+01 8.996336E+01 2.200449E-02 3.440829E+01 + 4.109995E+01 9.000000E+01 3 1.979326E+02 1.459821E-01 1.979320E+02 5.043058E-01 + 4.109995E+01 9.000000E+01 4 1.109734E+02 8.996342E+01 7.084974E-02 1.109734E+02 + 4.109995E+01 9.000000E+01 5 7.831767E-05 -8.999617E+01 5.236675E-09 -7.831767E-05 + 4.109995E+01 9.000000E+01 6 2.633970E-06 1.799999E+02 -2.633970E-06 6.194161E-12 + 4.119994E+01 0.000000E+00 1 3.223639E+01 8.996688E+01 1.863800E-02 3.223639E+01 + 4.119994E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 4.119994E+01 0.000000E+00 3 1.964843E+02 1.447822E-01 1.964837E+02 4.965008E-01 + 4.119994E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 4.119994E+01 0.000000E+00 5 3.471302E+02 8.996688E+01 2.006911E-01 3.471302E+02 + 4.119994E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 4.119994E+01 3.000000E+01 1 2.796481E+01 8.996688E+01 1.616803E-02 2.796480E+01 + 4.119994E+01 3.000000E+01 2 1.706651E+01 8.996355E+01 1.085656E-02 1.706650E+01 + 4.119994E+01 3.000000E+01 3 1.968574E+02 1.449003E-01 1.968568E+02 4.978493E-01 + 4.119994E+01 3.000000E+01 4 5.476097E+01 8.996342E+01 3.495253E-02 5.476096E+01 + 4.119994E+01 3.000000E+01 5 3.011182E+02 8.996688E+01 1.740967E-01 3.011181E+02 + 4.119994E+01 3.000000E+01 6 3.047206E+01 -1.969765E-04 3.047206E+01 -1.047596E-04 + 4.119994E+01 6.000000E+01 1 1.620018E+01 8.996688E+01 9.365939E-03 1.620017E+01 + 4.119994E+01 6.000000E+01 2 2.966987E+01 8.996355E+01 1.887443E-02 2.966987E+01 + 4.119994E+01 6.000000E+01 3 1.976069E+02 1.451368E-01 1.976063E+02 5.005605E-01 + 4.119994E+01 6.000000E+01 4 9.552213E+01 8.996355E+01 6.076624E-02 9.552210E+01 + 4.119994E+01 6.000000E+01 5 1.744270E+02 8.996687E+01 1.008510E-01 1.744269E+02 + 4.119994E+01 6.000000E+01 6 3.058869E+01 -1.967219E-04 3.058869E+01 -1.050246E-04 + 4.119994E+01 9.000000E+01 1 1.674138E-06 -9.002617E+01 -7.647286E-10 -1.674137E-06 + 4.119994E+01 9.000000E+01 2 3.432342E+01 8.996355E+01 2.183509E-02 3.432341E+01 + 4.119994E+01 9.000000E+01 3 1.979819E+02 1.452558E-01 1.979812E+02 5.019214E-01 + 4.119994E+01 9.000000E+01 4 1.106882E+02 8.996362E+01 7.029747E-02 1.106882E+02 + 4.119994E+01 9.000000E+01 5 7.813003E-05 -8.999619E+01 5.192008E-09 -7.813003E-05 + 4.119994E+01 9.000000E+01 6 2.620804E-06 1.799999E+02 -2.620804E-06 6.099818E-12 + 4.129994E+01 0.000000E+00 1 3.215831E+01 8.996704E+01 1.849917E-02 3.215830E+01 + 4.129994E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 4.129994E+01 0.000000E+00 3 1.965396E+02 1.440657E-01 1.965389E+02 4.941826E-01 + 4.129994E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 4.129994E+01 0.000000E+00 5 3.463657E+02 8.996704E+01 1.992409E-01 3.463656E+02 + 4.129994E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 4.129994E+01 3.000000E+01 1 2.789677E+01 8.996704E+01 1.604749E-02 2.789677E+01 + 4.129994E+01 3.000000E+01 2 1.702501E+01 8.996375E+01 1.077350E-02 1.702500E+01 + 4.129994E+01 3.000000E+01 3 1.969117E+02 1.441831E-01 1.969111E+02 4.955220E-01 + 4.129994E+01 3.000000E+01 4 5.462371E+01 8.996362E+01 3.468196E-02 5.462370E+01 + 4.129994E+01 3.000000E+01 5 3.004536E+02 8.996704E+01 1.728359E-01 3.004535E+02 + 4.129994E+01 3.000000E+01 6 3.032113E+01 -1.949495E-04 3.032113E+01 -1.031679E-04 + 4.129994E+01 6.000000E+01 1 1.616049E+01 8.996704E+01 9.295954E-03 1.616048E+01 + 4.129994E+01 6.000000E+01 2 2.959719E+01 8.996375E+01 1.872970E-02 2.959719E+01 + 4.129994E+01 6.000000E+01 3 1.976570E+02 1.444177E-01 1.976563E+02 4.982067E-01 + 4.129994E+01 6.000000E+01 4 9.527947E+01 8.996375E+01 6.029442E-02 9.527945E+01 + 4.129994E+01 6.000000E+01 5 1.740376E+02 8.996704E+01 1.001183E-01 1.740376E+02 + 4.129994E+01 6.000000E+01 6 3.043653E+01 -1.946994E-04 3.043653E+01 -1.034277E-04 + 4.129994E+01 9.000000E+01 1 1.670004E-06 -9.002605E+01 -7.593959E-10 -1.670004E-06 + 4.129994E+01 9.000000E+01 2 3.423899E+01 8.996375E+01 2.166739E-02 3.423898E+01 + 4.129994E+01 9.000000E+01 3 1.980305E+02 1.445356E-01 1.980299E+02 4.995557E-01 + 4.129994E+01 9.000000E+01 4 1.104047E+02 8.996381E+01 6.975102E-02 1.104047E+02 + 4.129994E+01 9.000000E+01 5 7.794305E-05 -8.999622E+01 5.147867E-09 -7.794305E-05 + 4.129994E+01 9.000000E+01 6 2.607728E-06 1.799999E+02 -2.607728E-06 6.007129E-12 + 4.139994E+01 0.000000E+00 1 3.208051E+01 8.996720E+01 1.836172E-02 3.208050E+01 + 4.139994E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 4.139994E+01 0.000000E+00 3 1.965956E+02 1.433545E-01 1.965950E+02 4.918833E-01 + 4.139994E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 4.139994E+01 0.000000E+00 5 3.456003E+02 8.996720E+01 1.978056E-01 3.456002E+02 + 4.139994E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 4.139994E+01 3.000000E+01 1 2.782909E+01 8.996720E+01 1.592808E-02 2.782909E+01 + 4.139994E+01 3.000000E+01 2 1.698372E+01 8.996394E+01 1.069130E-02 1.698371E+01 + 4.139994E+01 3.000000E+01 3 1.969649E+02 1.434706E-01 1.969643E+02 4.932063E-01 + 4.139994E+01 3.000000E+01 4 5.448686E+01 8.996381E+01 3.441423E-02 5.448685E+01 + 4.139994E+01 3.000000E+01 5 2.997913E+02 8.996720E+01 1.715882E-01 2.997912E+02 + 4.139994E+01 3.000000E+01 6 3.017126E+01 -1.929491E-04 3.017126E+01 -1.016046E-04 + 4.139994E+01 6.000000E+01 1 1.612102E+01 8.996721E+01 9.226641E-03 1.612101E+01 + 4.139994E+01 6.000000E+01 2 2.952482E+01 8.996394E+01 1.858645E-02 2.952482E+01 + 4.139994E+01 6.000000E+01 3 1.977071E+02 1.437027E-01 1.977065E+02 4.958657E-01 + 4.139994E+01 6.000000E+01 4 9.503753E+01 8.996394E+01 5.982786E-02 9.503751E+01 + 4.139994E+01 6.000000E+01 5 1.736500E+02 8.996720E+01 9.939387E-02 1.736499E+02 + 4.139994E+01 6.000000E+01 6 3.028553E+01 -1.927027E-04 3.028553E+01 -1.018592E-04 + 4.139994E+01 9.000000E+01 1 1.665889E-06 -9.002594E+01 -7.541124E-10 -1.665889E-06 + 4.139994E+01 9.000000E+01 2 3.415503E+01 8.996394E+01 2.150146E-02 3.415503E+01 + 4.139994E+01 9.000000E+01 3 1.980793E+02 1.438184E-01 1.980787E+02 4.971993E-01 + 4.139994E+01 9.000000E+01 4 1.101234E+02 8.996400E+01 6.921072E-02 1.101233E+02 + 4.139994E+01 9.000000E+01 5 7.775707E-05 -8.999624E+01 5.104229E-09 -7.775707E-05 + 4.139994E+01 9.000000E+01 6 2.594763E-06 1.799999E+02 -2.594763E-06 5.916115E-12 + 4.149994E+01 0.000000E+00 1 3.200307E+01 8.996737E+01 1.822561E-02 3.200307E+01 + 4.149994E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 4.149994E+01 0.000000E+00 3 1.966507E+02 1.426483E-01 1.966501E+02 4.895974E-01 + 4.149994E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 4.149994E+01 0.000000E+00 5 3.448411E+02 8.996737E+01 1.963807E-01 3.448410E+02 + 4.149994E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 4.149994E+01 3.000000E+01 1 2.776168E+01 8.996737E+01 1.580994E-02 2.776168E+01 + 4.149994E+01 3.000000E+01 2 1.694263E+01 8.996412E+01 1.060992E-02 1.694263E+01 + 4.149994E+01 3.000000E+01 3 1.970181E+02 1.427636E-01 1.970174E+02 4.909084E-01 + 4.149994E+01 3.000000E+01 4 5.435096E+01 8.996400E+01 3.414890E-02 5.435095E+01 + 4.149994E+01 3.000000E+01 5 2.991281E+02 8.996737E+01 1.703518E-01 2.991280E+02 + 4.149994E+01 3.000000E+01 6 3.002252E+01 -1.909746E-04 3.002252E+01 -1.000691E-04 + 4.149994E+01 6.000000E+01 1 1.608171E+01 8.996738E+01 9.158031E-03 1.608171E+01 + 4.149994E+01 6.000000E+01 2 2.945286E+01 8.996412E+01 1.844464E-02 2.945286E+01 + 4.149994E+01 6.000000E+01 3 1.977572E+02 1.429930E-01 1.977566E+02 4.935420E-01 + 4.149994E+01 6.000000E+01 4 9.479705E+01 8.996412E+01 5.936589E-02 9.479704E+01 + 4.149994E+01 6.000000E+01 5 1.732650E+02 8.996737E+01 9.867683E-02 1.732650E+02 + 4.149994E+01 6.000000E+01 6 3.013568E+01 -1.907316E-04 3.013568E+01 -1.003185E-04 + 4.149994E+01 9.000000E+01 1 1.661794E-06 -9.002582E+01 -7.488778E-10 -1.661794E-06 + 4.149994E+01 9.000000E+01 2 3.407139E+01 8.996412E+01 2.133723E-02 3.407138E+01 + 4.149994E+01 9.000000E+01 3 1.981269E+02 1.431084E-01 1.981263E+02 4.948636E-01 + 4.149994E+01 9.000000E+01 4 1.098428E+02 8.996418E+01 6.867573E-02 1.098428E+02 + 4.149994E+01 9.000000E+01 5 7.757172E-05 -8.999626E+01 5.061101E-09 -7.757172E-05 + 4.149994E+01 9.000000E+01 6 2.581888E-06 1.799999E+02 -2.581888E-06 5.826696E-12 + 4.159994E+01 0.000000E+00 1 3.192614E+01 8.996753E+01 1.809090E-02 3.192613E+01 + 4.159994E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 4.159994E+01 0.000000E+00 3 1.967056E+02 1.419500E-01 1.967050E+02 4.873366E-01 + 4.159994E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 4.159994E+01 0.000000E+00 5 3.440872E+02 8.996753E+01 1.949723E-01 3.440872E+02 + 4.159994E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 4.159994E+01 3.000000E+01 1 2.769471E+01 8.996753E+01 1.569294E-02 2.769471E+01 + 4.159994E+01 3.000000E+01 2 1.690174E+01 8.996431E+01 1.052938E-02 1.690174E+01 + 4.159994E+01 3.000000E+01 3 1.970720E+02 1.420630E-01 1.970714E+02 4.886332E-01 + 4.159994E+01 3.000000E+01 4 5.421552E+01 8.996419E+01 3.388662E-02 5.421551E+01 + 4.159994E+01 3.000000E+01 5 2.984710E+02 8.996753E+01 1.691272E-01 2.984709E+02 + 4.159994E+01 3.000000E+01 6 2.987486E+01 -1.890252E-04 2.987486E+01 -9.856051E-05 + 4.159994E+01 6.000000E+01 1 1.604262E+01 8.996753E+01 9.090105E-03 1.604262E+01 + 4.159994E+01 6.000000E+01 2 2.938123E+01 8.996431E+01 1.830431E-02 2.938122E+01 + 4.159994E+01 6.000000E+01 3 1.978063E+02 1.422910E-01 1.978056E+02 4.912407E-01 + 4.159994E+01 6.000000E+01 4 9.455788E+01 8.996431E+01 5.890870E-02 9.455786E+01 + 4.159994E+01 6.000000E+01 5 1.728810E+02 8.996753E+01 9.796600E-02 1.728810E+02 + 4.159994E+01 6.000000E+01 6 2.998695E+01 -1.887858E-04 2.998695E+01 -9.880501E-05 + 4.159994E+01 9.000000E+01 1 1.657723E-06 -9.002570E+01 -7.436894E-10 -1.657723E-06 + 4.159994E+01 9.000000E+01 2 3.398825E+01 8.996431E+01 2.117467E-02 3.398825E+01 + 4.159994E+01 9.000000E+01 3 1.981756E+02 1.424040E-01 1.981750E+02 4.925489E-01 + 4.159994E+01 9.000000E+01 4 1.095636E+02 8.996436E+01 6.814620E-02 1.095636E+02 + 4.159994E+01 9.000000E+01 5 7.738743E-05 -8.999628E+01 5.018445E-09 -7.738743E-05 + 4.159994E+01 9.000000E+01 6 2.569109E-06 1.799999E+02 -2.569109E-06 5.738859E-12 + 4.169994E+01 0.000000E+00 1 3.184952E+01 8.996770E+01 1.795752E-02 3.184951E+01 + 4.169994E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 4.169994E+01 0.000000E+00 3 1.967602E+02 1.412541E-01 1.967596E+02 4.850822E-01 + 4.169994E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 4.169994E+01 0.000000E+00 5 3.433343E+02 8.996770E+01 1.935746E-01 3.433342E+02 + 4.169994E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 4.169994E+01 3.000000E+01 1 2.762793E+01 8.996770E+01 1.557708E-02 2.762793E+01 + 4.169994E+01 3.000000E+01 2 1.686105E+01 8.996449E+01 1.044969E-02 1.686105E+01 + 4.169994E+01 3.000000E+01 3 1.971250E+02 1.413667E-01 1.971244E+02 4.863688E-01 + 4.169994E+01 3.000000E+01 4 5.408092E+01 8.996438E+01 3.362707E-02 5.408091E+01 + 4.169994E+01 3.000000E+01 5 2.978172E+02 8.996770E+01 1.679160E-01 2.978172E+02 + 4.169994E+01 3.000000E+01 6 2.972837E+01 -1.871010E-04 2.972837E+01 -9.707885E-05 + 4.169994E+01 6.000000E+01 1 1.600369E+01 8.996770E+01 9.022900E-03 1.600369E+01 + 4.169994E+01 6.000000E+01 2 2.930994E+01 8.996449E+01 1.816543E-02 2.930993E+01 + 4.169994E+01 6.000000E+01 3 1.978561E+02 1.415912E-01 1.978555E+02 4.889480E-01 + 4.169994E+01 6.000000E+01 4 9.431992E+01 8.996449E+01 5.845638E-02 9.431990E+01 + 4.169994E+01 6.000000E+01 5 1.724973E+02 8.996770E+01 9.726115E-02 1.724973E+02 + 4.169994E+01 6.000000E+01 6 2.983928E+01 -1.868654E-04 2.983928E+01 -9.731831E-05 + 4.169994E+01 9.000000E+01 1 1.653668E-06 -9.002559E+01 -7.385495E-10 -1.653668E-06 + 4.169994E+01 9.000000E+01 2 3.390548E+01 8.996449E+01 2.101381E-02 3.390548E+01 + 4.169994E+01 9.000000E+01 3 1.982223E+02 1.417046E-01 1.982217E+02 4.902453E-01 + 4.169994E+01 9.000000E+01 4 1.092858E+02 8.996455E+01 6.762217E-02 1.092858E+02 + 4.169994E+01 9.000000E+01 5 7.720428E-05 -8.999631E+01 4.976278E-09 -7.720428E-05 + 4.169994E+01 9.000000E+01 6 2.556429E-06 1.799999E+02 -2.556429E-06 5.652582E-12 + 4.179993E+01 0.000000E+00 1 3.177319E+01 8.996786E+01 1.782549E-02 3.177319E+01 + 4.179993E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 4.179993E+01 0.000000E+00 3 1.968141E+02 1.405636E-01 1.968135E+02 4.828432E-01 + 4.179993E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 4.179993E+01 0.000000E+00 5 3.425842E+02 8.996786E+01 1.921921E-01 3.425841E+02 + 4.179993E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 4.179993E+01 3.000000E+01 1 2.756153E+01 8.996786E+01 1.546244E-02 2.756153E+01 + 4.179993E+01 3.000000E+01 2 1.682053E+01 8.996468E+01 1.037080E-02 1.682053E+01 + 4.179993E+01 3.000000E+01 3 1.971770E+02 1.406749E-01 1.971764E+02 4.841162E-01 + 4.179993E+01 3.000000E+01 4 5.394693E+01 8.996456E+01 3.337028E-02 5.394692E+01 + 4.179993E+01 3.000000E+01 5 2.971655E+02 8.996786E+01 1.667133E-01 2.971654E+02 + 4.179993E+01 3.000000E+01 6 2.958294E+01 -1.852015E-04 2.958294E+01 -9.562315E-05 + 4.179993E+01 6.000000E+01 1 1.596499E+01 8.996786E+01 8.956323E-03 1.596499E+01 + 4.179993E+01 6.000000E+01 2 2.923900E+01 8.996467E+01 1.802796E-02 2.923900E+01 + 4.179993E+01 6.000000E+01 3 1.979050E+02 1.408982E-01 1.979044E+02 4.866752E-01 + 4.179993E+01 6.000000E+01 4 9.408327E+01 8.996467E+01 5.800894E-02 9.408326E+01 + 4.179993E+01 6.000000E+01 5 1.721169E+02 8.996786E+01 9.656462E-02 1.721168E+02 + 4.179993E+01 6.000000E+01 6 2.969277E+01 -1.849691E-04 2.969277E+01 -9.585775E-05 + 4.179993E+01 9.000000E+01 1 1.649634E-06 -9.002547E+01 -7.334572E-10 -1.649634E-06 + 4.179993E+01 9.000000E+01 2 3.382306E+01 8.996467E+01 2.085456E-02 3.382305E+01 + 4.179993E+01 9.000000E+01 3 1.982701E+02 1.410097E-01 1.982695E+02 4.879587E-01 + 4.179993E+01 9.000000E+01 4 1.090095E+02 8.996473E+01 6.710392E-02 1.090095E+02 + 4.179993E+01 9.000000E+01 5 7.702148E-05 -8.999633E+01 4.934618E-09 -7.702148E-05 + 4.179993E+01 9.000000E+01 6 2.543847E-06 1.799999E+02 -2.543847E-06 5.567821E-12 + 4.189993E+01 0.000000E+00 1 3.169726E+01 8.996802E+01 1.769472E-02 3.169726E+01 + 4.189993E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 4.189993E+01 0.000000E+00 3 1.968671E+02 1.398788E-01 1.968665E+02 4.806201E-01 + 4.189993E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 4.189993E+01 0.000000E+00 5 3.418394E+02 8.996802E+01 1.908225E-01 3.418393E+02 + 4.189993E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 4.189993E+01 3.000000E+01 1 2.749547E+01 8.996802E+01 1.534886E-02 2.749546E+01 + 4.189993E+01 3.000000E+01 2 1.678023E+01 8.996486E+01 1.029271E-02 1.678022E+01 + 4.189993E+01 3.000000E+01 3 1.972283E+02 1.399894E-01 1.972278E+02 4.818829E-01 + 4.189993E+01 3.000000E+01 4 5.381390E+01 8.996474E+01 3.311593E-02 5.381388E+01 + 4.189993E+01 3.000000E+01 5 2.965127E+02 8.996802E+01 1.655249E-01 2.965127E+02 + 4.189993E+01 3.000000E+01 6 2.943853E+01 -1.833262E-04 2.943853E+01 -9.419290E-05 + 4.189993E+01 6.000000E+01 1 1.592647E+01 8.996802E+01 8.890377E-03 1.592647E+01 + 4.189993E+01 6.000000E+01 2 2.916839E+01 8.996486E+01 1.789187E-02 2.916839E+01 + 4.189993E+01 6.000000E+01 3 1.979532E+02 1.402093E-01 1.979526E+02 4.844135E-01 + 4.189993E+01 6.000000E+01 4 9.384766E+01 8.996486E+01 5.756581E-02 9.384765E+01 + 4.189993E+01 6.000000E+01 5 1.717385E+02 8.996802E+01 9.587416E-02 1.717384E+02 + 4.189993E+01 6.000000E+01 6 2.954734E+01 -1.830975E-04 2.954734E+01 -9.442304E-05 + 4.189993E+01 9.000000E+01 1 1.645620E-06 -9.002537E+01 -7.284074E-10 -1.645620E-06 + 4.189993E+01 9.000000E+01 2 3.374107E+01 8.996486E+01 2.069700E-02 3.374106E+01 + 4.189993E+01 9.000000E+01 3 1.983167E+02 1.403194E-01 1.983161E+02 4.856843E-01 + 4.189993E+01 9.000000E+01 4 1.087346E+02 8.996491E+01 6.659083E-02 1.087346E+02 + 4.189993E+01 9.000000E+01 5 7.684010E-05 -8.999635E+01 4.893390E-09 -7.684010E-05 + 4.189993E+01 9.000000E+01 6 2.531352E-06 1.799999E+02 -2.531352E-06 5.484548E-12 + 4.199993E+01 0.000000E+00 1 3.162169E+01 8.996818E+01 1.756517E-02 3.162169E+01 + 4.199993E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 4.199993E+01 0.000000E+00 3 1.969216E+02 1.391986E-01 1.969211E+02 4.784157E-01 + 4.199993E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 4.199993E+01 0.000000E+00 5 3.410953E+02 8.996818E+01 1.894655E-01 3.410952E+02 + 4.199993E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 + 4.199993E+01 3.000000E+01 1 2.742975E+01 8.996818E+01 1.523634E-02 2.742974E+01 + 4.199993E+01 3.000000E+01 2 1.674008E+01 8.996504E+01 1.021539E-02 1.674008E+01 + 4.199993E+01 3.000000E+01 3 1.972803E+02 1.393080E-01 1.972797E+02 4.796635E-01 + 4.199993E+01 3.000000E+01 4 5.368106E+01 8.996492E+01 3.286424E-02 5.368105E+01 + 4.199993E+01 3.000000E+01 5 2.958658E+02 8.996818E+01 1.643461E-01 2.958658E+02 + 4.199993E+01 3.000000E+01 6 2.929523E+01 -1.814753E-04 2.929523E+01 -9.278800E-05 + 4.199993E+01 6.000000E+01 1 1.588813E+01 8.996818E+01 8.825126E-03 1.588813E+01 + 4.199993E+01 6.000000E+01 2 2.909819E+01 8.996503E+01 1.775723E-02 2.909819E+01 + 4.199993E+01 6.000000E+01 3 1.980013E+02 1.395273E-01 1.980007E+02 4.821744E-01 + 4.199993E+01 6.000000E+01 4 9.361299E+01 8.996503E+01 5.712739E-02 9.361298E+01 + 4.199993E+01 6.000000E+01 5 1.713600E+02 8.996818E+01 9.519084E-02 1.713600E+02 + 4.199993E+01 6.000000E+01 6 2.940291E+01 -1.812501E-04 2.940291E+01 -9.301350E-05 + 4.199993E+01 9.000000E+01 1 1.641623E-06 -9.002525E+01 -7.234043E-10 -1.641623E-06 + 4.199993E+01 9.000000E+01 2 3.365955E+01 8.996503E+01 2.054098E-02 3.365954E+01 + 4.199993E+01 9.000000E+01 3 1.983625E+02 1.396369E-01 1.983619E+02 4.834336E-01 + 4.199993E+01 9.000000E+01 4 1.084613E+02 8.996510E+01 6.608290E-02 1.084613E+02 + 4.199993E+01 9.000000E+01 5 7.665897E-05 -8.999638E+01 4.852652E-09 -7.665897E-05 + 4.199993E+01 9.000000E+01 6 2.518950E-06 1.799999E+02 -2.518950E-06 5.402741E-12 \ No newline at end of file diff --git a/Test_Cases/MHK_RM1/MHK_RM1_Floating.fst b/Test_Cases/MHK_RM1/MHK_RM1_Floating.fst new file mode 100644 index 00000000..a19bf661 --- /dev/null +++ b/Test_Cases/MHK_RM1/MHK_RM1_Floating.fst @@ -0,0 +1,71 @@ +------- OpenFAST EXAMPLE INPUT FILE -------------------------------------------- +Floating MHK turbine, based on the RM1 tidal current rotor +---------------------- SIMULATION CONTROL -------------------------------------- +False Echo - Echo input data to .ech (flag) +"FATAL" AbortLevel - Error level when simulation should abort (string) {"WARNING", "SEVERE", "FATAL"} + 100 TMax - Total run time (s) + 0.01 DT - Recommended module time step (s) + 2 InterpOrder - Interpolation order for input/output time history (-) {1=linear, 2=quadratic} + 2 NumCrctn - Number of correction iterations (-) {0=explicit calculation, i.e., no corrections} + 1 DT_UJac - Time between calls to get Jacobians (s) + 1E+06 UJacSclFact - Scaling factor used in Jacobians (-) +---------------------- FEATURE SWITCHES AND FLAGS ------------------------------ + 1 CompElast - Compute structural dynamics (switch) {1=ElastoDyn; 2=ElastoDyn + BeamDyn for blades} + 1 CompInflow - Compute inflow wind velocities (switch) {0=still air; 1=InflowWind; 2=external from OpenFOAM} + 2 CompAero - Compute aerodynamic loads (switch) {0=None; 1=AeroDyn v14; 2=AeroDyn v15} + 1 CompServo - Compute control and electrical-drive dynamics (switch) {0=None; 1=ServoDyn} + 1 CompHydro - Compute hydrodynamic loads (switch) {0=None; 1=HydroDyn} + 0 CompSub - Compute sub-structural dynamics (switch) {0=None; 1=SubDyn; 2=External Platform MCKF} + 3 CompMooring - Compute mooring system (switch) {0=None; 1=MAP++; 2=FEAMooring; 3=MoorDyn; 4=OrcaFlex} + 0 CompIce - Compute ice loads (switch) {0=None; 1=IceFloe; 2=IceDyn} + 2 MHK - MHK turbine type (switch) {0=Not an MHK turbine; 1=Fixed MHK turbine; 2=Floating MHK turbine} +---------------------- ENVIRONMENTAL CONDITIONS -------------------------------- + 9.80665 Gravity - Gravitational acceleration (m/s^2) + 1.225 AirDens - Air density (kg/m^3) + 1025.0 WtrDens - Water density (kg/m^3) + 1.06E-06 KinVisc - Kinematic viscosity of working fluid (m^2/s) + 1500 SpdSound - Speed of sound in working fluid (m/s) + 101325 Patm - Atmospheric pressure (Pa) [used only for an MHK turbine cavitation check] + 2500 Pvap - Vapour pressure of working fluid (Pa) [used only for an MHK turbine cavitation check] + 50 WtrDpth - Water depth (m) + 0 MSL2SWL - Offset between still-water level and mean sea level (m) [positive upward] +---------------------- INPUT FILES --------------------------------------------- +"MHK_RM1_Floating_ElastoDyn.dat" EDFile - Name of file containing ElastoDyn input parameters (quoted string) +"unused" BDBldFile(1) - Name of file containing BeamDyn input parameters for blade 1 (quoted string) +"unused" BDBldFile(2) - Name of file containing BeamDyn input parameters for blade 2 (quoted string) +"unused" BDBldFile(3) - Name of file containing BeamDyn input parameters for blade 3 (quoted string) +"MHK_RM1_Floating_InflowWind.dat" InflowFile - Name of file containing inflow wind input parameters (quoted string) +"MHK_RM1_Floating_AeroDyn15.dat" AeroFile - Name of file containing aerodynamic input parameters (quoted string) +"MHK_RM1_ServoDyn.dat" ServoFile - Name of file containing control and electrical-drive input parameters (quoted string) +"MHK_RM1_Floating_HydroDyn.dat" HydroFile - Name of file containing hydrodynamic input parameters (quoted string) +"unused" SubFile - Name of file containing sub-structural input parameters (quoted string) +"MHK_RM1_Floating_MoorDyn.dat" MooringFile - Name of file containing mooring system input parameters (quoted string) +"unused" IceFile - Name of file containing ice input parameters (quoted string) +---------------------- OUTPUT -------------------------------------------------- +True SumPrint - Print summary data to ".sum" (flag) + 5 SttsTime - Amount of time between screen status messages (s) + 99999 ChkptTime - Amount of time between creating checkpoint files for potential restart (s) + default DT_Out - Time step for tabular output (s) (or "default") + 0 TStart - Time to begin tabular output (s) + 3 OutFileFmt - Format for tabular (time-marching) output file (switch) {0: uncompressed binary [.outb], 1: text file [.out], 2: binary file [.outb], 3: both 1 and 2} +True TabDelim - Use tab delimiters in text tabular output file? (flag) {uses spaces if false} +"ES10.3E2" OutFmt - Format used for text tabular output, excluding the time channel. Resulting field should be 10 characters. (quoted string) +---------------------- LINEARIZATION ------------------------------------------- +False Linearize - Linearization analysis (flag) +False CalcSteady - Calculate a steady-state periodic operating point before linearization? [unused if Linearize=False] (flag) + 1 TrimCase - Controller parameter to be trimmed {1:yaw; 2:torque; 3:pitch} [used only if CalcSteady=True] (-) + 0.01 TrimTol - Tolerance for the rotational speed convergence [used only if CalcSteady=True] (-) + 0.01 TrimGain - Proportional gain for the rotational speed error (>0) [used only if CalcSteady=True] (rad/(rad/s) for yaw or pitch; Nm/(rad/s) for torque) + 0 Twr_Kdmp - Damping factor for the tower [used only if CalcSteady=True] (N/(m/s)) + 0 Bld_Kdmp - Damping factor for the blades [used only if CalcSteady=True] (N/(m/s)) + 0 NLinTimes - Number of times to linearize (-) [>=1] [unused if Linearize=False] + 0 LinTimes - List of times at which to linearize (s) [1 to NLinTimes] [used only when Linearize=True and CalcSteady=False] + 0 LinInputs - Inputs included in linearization (switch) {0=none; 1=standard; 2=all module inputs (debug)} [unused if Linearize=False] + 0 LinOutputs - Outputs included in linearization (switch) {0=none; 1=from OutList(s); 2=all module outputs (debug)} [unused if Linearize=False] +False LinOutJac - Include full Jacobians in linearization output (for debug) (flag) [unused if Linearize=False; used only if LinInputs=LinOutputs=2] +False LinOutMod - Write module-level linearization output files in addition to output for full system? (flag) [unused if Linearize=False] +---------------------- VISUALIZATION ------------------------------------------- + 0 WrVTK - VTK visualization data output: (switch) {0=none; 1=initialization data only; 2=animation; 3=mode shapes} + 1 VTK_type - Type of VTK visualization data: (switch) {1=surfaces; 2=basic meshes (lines/points); 3=all meshes (debug)} [unused if WrVTK=0] +False VTK_fields - Write mesh fields to VTK data files? (flag) {true/false} [unused if WrVTK=0] + 0 VTK_fps - Frame rate for VTK output (frames per second){will use closest integer multiple of DT} [used only if WrVTK=2 or WrVTK=3] diff --git a/Test_Cases/MHK_RM1/MHK_RM1_Floating.hst b/Test_Cases/MHK_RM1/MHK_RM1_Floating.hst new file mode 100644 index 00000000..7f6dc63e --- /dev/null +++ b/Test_Cases/MHK_RM1/MHK_RM1_Floating.hst @@ -0,0 +1,36 @@ + 1 1 0.000000E+00 + 1 2 0.000000E+00 + 1 3 0.000000E+00 + 1 4 0.000000E+00 + 1 5 0.000000E+00 + 1 6 0.000000E+00 + 2 1 0.000000E+00 + 2 2 0.000000E+00 + 2 3 0.000000E+00 + 2 4 0.000000E+00 + 2 5 0.000000E+00 + 2 6 0.000000E+00 + 3 1 0.000000E+00 + 3 2 0.000000E+00 + 3 3 2.083175E+02 + 3 4 0.000000E+00 + 3 5 0.000000E+00 + 3 6 0.000000E+00 + 4 1 0.000000E+00 + 4 2 0.000000E+00 + 4 3 0.000000E+00 + 4 4 -1.035433E+03 + 4 5 0.000000E+00 + 4 6 0.000000E+00 + 5 1 0.000000E+00 + 5 2 0.000000E+00 + 5 3 0.000000E+00 + 5 4 0.000000E+00 + 5 5 6.307686E+04 + 5 6 0.000000E+00 + 6 1 0.000000E+00 + 6 2 0.000000E+00 + 6 3 0.000000E+00 + 6 4 0.000000E+00 + 6 5 0.000000E+00 + 6 6 0.000000E+00 \ No newline at end of file diff --git a/Test_Cases/MHK_RM1/MHK_RM1_Floating_AeroDyn15.dat b/Test_Cases/MHK_RM1/MHK_RM1_Floating_AeroDyn15.dat new file mode 100644 index 00000000..707ba8d9 --- /dev/null +++ b/Test_Cases/MHK_RM1/MHK_RM1_Floating_AeroDyn15.dat @@ -0,0 +1,123 @@ +------- AERODYN v15 for OpenFAST INPUT FILE --------------------------------------------------------- +Floating MHK turbine hydrodynamic input properties, based on the RM1 tidal current rotor +====== General Options ============================================================================ +False Echo - Echo the input to ".AD.ech"? (flag) +"default" DTAero - Time interval for aerodynamic calculations {or "default"} (s) + 2 WakeMod - Type of wake/induction model (switch) {0=none, 1=BEMT, 2=DBEMT, 3=OLAF} [WakeMod cannot be 2 or 3 when linearizing] + 1 AFAeroMod - Type of blade airfoil aerodynamics model (switch) {1=steady model, 2=Beddoes-Leishman unsteady model} [AFAeroMod must be 1 when linearizing] + 1 TwrPotent - Type tower influence on wind based on potential flow around the tower (switch) {0=none, 1=baseline potential flow, 2=potential flow with Bak correction} + 0 TwrShadow - Calculate tower influence on wind based on downstream tower shadow (switch) {0=none, 1=Powles model, 2=Eames model} +True TwrAero - Calculate tower aerodynamic loads? (flag) +False FrozenWake - Assume frozen wake during linearization? (flag) [used only when WakeMod=1 and when linearizing] +True CavitCheck - Perform cavitation check? (flag) [AFAeroMod must be 1 when CavitCheck=true] +True Buoyancy - Include buoyancy effects? (flag) +False CompAA - Flag to compute AeroAcoustics calculation [used only when WakeMod = 1 or 2] +"unused" AA_InputFile - AeroAcoustics input file [used only when CompAA=true] +====== Environmental Conditions =================================================================== +"default" AirDens - Air density (kg/m^3) +"default" KinVisc - Kinematic viscosity of working fluid (m^2/s) +"default" SpdSound - Speed of sound in working fluid (m/s) +"default" Patm - Atmospheric pressure (Pa) [used only when CavitCheck=True] +"default" Pvap - Vapour pressure of working fluid (Pa) [used only when CavitCheck=True] +====== Blade-Element/Momentum Theory Options ====================================================== [unused when WakeMod=0 or 3] + 2 SkewMod - Type of skewed-wake correction model (switch) {1=uncoupled, 2=Pitt/Peters, 3=coupled} [unused when WakeMod=0 or 3] +"default" SkewModFactor - Constant used in Pitt/Peters skewed wake model {or "default" is 15/32*pi} (-) [used only when SkewMod=2; unused when WakeMod=0 or 3] +True TipLoss - Use the Prandtl tip-loss model? (flag) [unused when WakeMod=0 or 3] +True HubLoss - Use the Prandtl hub-loss model? (flag) [unused when WakeMod=0 or 3] +True TanInd - Include tangential induction in BEMT calculations? (flag) [unused when WakeMod=0 or 3] +True AIDrag - Include the drag term in the axial-induction calculation? (flag) [unused when WakeMod=0 or 3] +True TIDrag - Include the drag term in the tangential-induction calculation? (flag) [unused when WakeMod=0,3 or TanInd=FALSE] +"default" IndToler - Convergence tolerance for BEMT nonlinear solve residual equation {or "default"} (-) [unused when WakeMod=0 or 3] + 1000 MaxIter - Maximum number of iteration steps (-) [unused when WakeMod=0] +====== Dynamic Blade-Element/Momentum Theory Options ============================================== [used only when WakeMod=2] + 2 DBEMT_Mod - Type of dynamic BEMT (DBEMT) model {1=constant tau1, 2=time-dependent tau1} (-) [used only when WakeMod=2] + 4 tau1_const - Time constant for DBEMT (s) [used only when WakeMod=2 and DBEMT_Mod=1] +====== OLAF -- cOnvecting LAgrangian Filaments (Free Vortex Wake) Theory Options ================== [used only when WakeMod=3] +"unused" OLAFInputFileName - Input file for OLAF [used only when WakeMod=3] +====== Beddoes-Leishman Unsteady Airfoil Aerodynamics Options ===================================== [used only when AFAeroMod=2] + 3 UAMod - Unsteady Aero Model Switch (switch) {1=Baseline model (Original), 2=Gonzalez's variant (changes in Cn,Cc,Cm), 3=Minnema/Pierce variant (changes in Cc and Cm)} [used only when AFAeroMod=2] +True FLookup - Flag to indicate whether a lookup for f' will be calculated (TRUE) or whether best-fit exponential equations will be used (FALSE); if FALSE S1-S4 must be provided in airfoil input files (flag) [used only when AFAeroMod=2] +====== Airfoil Information ========================================================================= + 2 AFTabMod - Interpolation method for multiple airfoil tables {1=1D interpolation on AoA (first table only); 2=2D interpolation on AoA and Re; 3=2D interpolation on AoA and UserProp} (-) + 1 InCol_Alfa - The column in the airfoil tables that contains the angle of attack (-) + 2 InCol_Cl - The column in the airfoil tables that contains the lift coefficient (-) + 3 InCol_Cd - The column in the airfoil tables that contains the drag coefficient (-) + 0 InCol_Cm - The column in the airfoil tables that contains the pitching-moment coefficient; use zero if there is no Cm column (-) + 4 InCol_Cpmin - The column in the airfoil tables that contains the Cpmin coefficient; use zero if there is no Cpmin column (-) + 9 NumAFfiles - Number of airfoil files used (-) +"Airfoils/NACA6_1000.dat" AFNames - Airfoil file names (NumAFfiles lines) (quoted strings) +"Airfoils/NACA6_0864.dat" +"Airfoils/NACA6_0629.dat" +"Airfoils/NACA6_0444.dat" +"Airfoils/NACA6_0329.dat" +"Airfoils/NACA6_0276.dat" +"Airfoils/NACA6_0259.dat" +"Airfoils/NACA6_0247.dat" +"Airfoils/NACA6_0240.dat" +====== Rotor/Blade Properties ===================================================================== +False UseBlCm - Include aerodynamic pitching moment in calculations? (flag) +"MHK_RM1_AeroDyn15_Blade.dat" ADBlFile(1) - Name of file containing distributed aerodynamic properties for Blade #1 (-) +"MHK_RM1_AeroDyn15_Blade.dat" ADBlFile(2) - Name of file containing distributed aerodynamic properties for Blade #2 (-) [unused if NumBl < 2] +"unused" ADBlFile(3) - Name of file containing distributed aerodynamic properties for Blade #3 (-) [unused if NumBl < 3] +====== Hub Properties ============================================================================== [used only when Buoyancy=True] +7.2 VolHub - Hub volume (m^3) +0.2222 HubCenBx - Hub center of buoyancy x direction offset (m) +====== Nacelle Properties ========================================================================== [used only when Buoyancy=True] +38.6 VolNac - Nacelle volume (m^3) +0.43,0,0 NacCenB - Position of nacelle center of buoyancy from yaw bearing in nacelle coordinates (m) +====== Tail fin Aerodynamics ======================================================================== +False TFinAero - Calculate tail fin aerodynamics model (flag) +"unused" TFinFile - Input file for tail fin aerodynamics [used only when TFinAero=True] +====== Tower Influence and Aerodynamics ============================================================ [used only when TwrPotent/=0, TwrShadow/=0, TwrAero=True, or Buoyancy=True] + 4 NumTwrNds - Number of tower nodes used in the analysis (-) [used only when TwrPotent/=0, TwrShadow/=0, TwrAero=True, or Buoyancy=True] +TwrElev TwrDiam TwrCd TwrTI TwrCb !TwrTI used only with TwrShadow=2, TwrCb used only with Buoyancy=True +(m) (m) (-) (-) (-) +-9 0.3253 0.2 0.0 1.0 +-14 0.3253 0.2 0.0 1.0 +-19 0.3253 0.2 0.0 1.0 +-24 0.3253 0.2 0.0 1.0 +====== Outputs ==================================================================================== +True SumPrint - Generate a summary file listing input options and interpolated properties to ".AD.sum"? (flag) + 9 NBlOuts - Number of blade node outputs [0 - 9] (-) +1,5,9,13,17,21,25,27,30 BlOutNd - Blade nodes whose values will be output (-) + 4 NTwOuts - Number of tower node outputs [0 - 9] (-) + 1,2,3,4 TwOutNd - Tower nodes whose values will be output (-) + OutList - The next line(s) contains a list of output parameters. See OutListParameters.xlsx for a listing of available output channels. +"TwN1Fbx" - x-component of buoyant force per unit length at Tw node 1 +"TwN3Fby" - y-component of buoyant force per unit length at Tw node 3 +"TwN4Fbz" - z-component of buoyant force per unit length at Tw node 4 +"TwN1Mbx" - x-component of buoyant moment per unit length at Tw node 6 +"TwN2Mby" - y-component of buoyant moment per unit length at Tw node 5 +"TwN3Mbz" - z-component of buoyant moment per unit length at Tw node 2 +"B2N4Fbn" - Buoyant force normal to chord per unit length at blade 2 node 4 +"B1N7Fbt" - Buoyant force tangential to chord per unit length at blade 1 node 7 +"B2N8Fbs" - Buoyant spanwise force per unit length at blade 2 node 8 +"B1N2Mbn" - Buoyant moment normal to chord per unit length at blade 1 node 2 +"B2N3Mbt" - Buoyant moment tangential to chord per unit length at blade 2 node 3 +"B1N6Mbs" - Buoyant spanwise moment per unit length at blade 1 node 6 +"B1FldFz" - Total blade aerodynamic/hydrodynamic load for blade 1 (force in z-direction) +"B2FldMx" - Total blade aerodynamic/hydrodynamic load for blade 2 (moment in x-direction) +"HbFbx" - x-component of buoyant force at hub node +"HbFby" - y-component of buoyant force at hub node +"HbFbz" - z-component of buoyant force at hub node +"HbMbx" - x-component of buoyant moment at hub node +"HbMby" - y-component of buoyant moment at hub node +"HbMbz" - z-component of buoyant moment at hub node +"NcFbx" - x-component of buoyant force at nacelle node +"NcFby" - y-component of buoyant force at nacelle node +"NcFbz" - z-component of buoyant force at nacelle node +"NcMbx" - x-component of buoyant moment at nacelle node +"NcMby" - y-component of buoyant moment at nacelle node +"NcMbz" - z-component of buoyant moment at nacelle node +"RtFldFxh" - Total rotor aerodynamic/hydrodynamic and buoyant load (force in x direction) +"RtFldFyh" - Total rotor aerodynamic/hydrodynamic and buoyant load (force in y direction) +"RtFldFzg" - Total rotor aerodynamic/hydrodynamic and buoyant load (force in global z direction) +"RtFldMxh" - Total rotor aerodynamic/hydrodynamic and buoyant load (moment in x direction) +"RtFldMyg" - Total rotor aerodynamic/hydrodynamic and buoyant load (moment in global y direction) +"RtFldMzh" - Total rotor aerodynamic/hydrodynamic and buoyant load (moment in z direction) +"B1N3SigCr" - Critical cavitation number blade 1 node 3 +"B2N5SigCr" - Critical cavitation number blade 2 node 5 +"B1N2SgCav" - Cavitation number blade 1 node 2 +"B2N6SgCav" - Cavitation number blade 2 node 6 +END of input file (the word "END" must appear in the first 3 columns of this last OutList line) +----------------------------------------------------------------------------------------------------- diff --git a/Test_Cases/MHK_RM1/MHK_RM1_Floating_ElastoDyn.dat b/Test_Cases/MHK_RM1/MHK_RM1_Floating_ElastoDyn.dat new file mode 100644 index 00000000..5a79e239 --- /dev/null +++ b/Test_Cases/MHK_RM1/MHK_RM1_Floating_ElastoDyn.dat @@ -0,0 +1,134 @@ +------- ELASTODYN for OpenFAST INPUT FILE -------------------------------------- +Floating MHK turbine structural input properties, based on the RM1 tidal current rotor +---------------------- SIMULATION CONTROL -------------------------------------- +False Echo - Echo input data to ".ech" (flag) + 3 Method - Integration method: {1: RK4, 2: AB4, or 3: ABM4} (-) +"default" DT - Integration time step (s) +---------------------- DEGREES OF FREEDOM -------------------------------------- +False FlapDOF1 - First flapwise blade mode DOF (flag) +False FlapDOF2 - Second flapwise blade mode DOF (flag) +False EdgeDOF - First edgewise blade mode DOF (flag) +False TeetDOF - Rotor-teeter DOF (flag) [unused for 3 blades] +False DrTrDOF - Drivetrain rotational-flexibility DOF (flag) +True GenDOF - Generator DOF (flag) +False YawDOF - Yaw DOF (flag) +False TwFADOF1 - First fore-aft tower bending-mode DOF (flag) +False TwFADOF2 - Second fore-aft tower bending-mode DOF (flag) +False TwSSDOF1 - First side-to-side tower bending-mode DOF (flag) +False TwSSDOF2 - Second side-to-side tower bending-mode DOF (flag) +True PtfmSgDOF - Platform horizontal surge translation DOF (flag) +True PtfmSwDOF - Platform horizontal sway translation DOF (flag) +True PtfmHvDOF - Platform vertical heave translation DOF (flag) +True PtfmRDOF - Platform roll tilt rotation DOF (flag) +True PtfmPDOF - Platform pitch tilt rotation DOF (flag) +True PtfmYDOF - Platform yaw rotation DOF (flag) +---------------------- INITIAL CONDITIONS -------------------------------------- + 0 OoPDefl - Initial out-of-plane blade-tip displacement (meters) + 0 IPDefl - Initial in-plane blade-tip deflection (meters) + 10 BlPitch(1) - Blade 1 initial pitch (degrees) + 10 BlPitch(2) - Blade 2 initial pitch (degrees) + 10 BlPitch(3) - Blade 3 initial pitch (degrees) [unused for 2 blades] + 0 TeetDefl - Initial or fixed teeter angle (degrees) [unused for 3 blades] + 0 Azimuth - Initial azimuth angle for blade 1 (degrees) + 11.50 RotSpeed - Initial or fixed rotor speed (rpm) + 0 NacYaw - Initial or fixed nacelle-yaw angle (degrees) + 0 TTDspFA - Initial fore-aft tower-top displacement (meters) + 0 TTDspSS - Initial side-to-side tower-top displacement (meters) + 20 PtfmSurge - Initial or fixed horizontal surge translational displacement of platform (meters) + 0 PtfmSway - Initial or fixed horizontal sway translational displacement of platform (meters) + 0 PtfmHeave - Initial or fixed vertical heave translational displacement of platform (meters) + 0 PtfmRoll - Initial or fixed roll tilt rotational displacement of platform (degrees) + 0 PtfmPitch - Initial or fixed pitch tilt rotational displacement of platform (degrees) + 0 PtfmYaw - Initial or fixed yaw rotational displacement of platform (degrees) +---------------------- TURBINE CONFIGURATION ----------------------------------- + 2 NumBl - Number of blades (-) + 10.0 TipRad - The distance from the rotor apex to the blade tip (meters) + 1.0 HubRad - The distance from the rotor apex to the blade root (meters) + 0.0 PreCone(1) - Blade 1 cone angle (degrees) + 0.0 PreCone(2) - Blade 2 cone angle (degrees) + 0.0 PreCone(3) - Blade 3 cone angle (degrees) [unused for 2 blades] + 0.2222 HubCM - Distance from rotor apex to hub mass [positive downwind] (meters) + 0 UndSling - Undersling length [distance from teeter pin to the rotor apex] (meters) [unused for 3 blades] + 0 Delta3 - Delta-3 angle for teetering rotors (degrees) [unused for 3 blades] + 0 AzimB1Up - Azimuth value to use for I/O when blade 1 points up (degrees) + -4.91 OverHang - Distance from yaw axis to rotor apex [3 blades] or teeter pin [2 blades] (meters) + 0 ShftGagL - Distance from rotor apex [3 blades] or teeter pin [2 blades] to shaft strain gages [positive for upwind rotors] (meters) + 0 ShftTilt - Rotor shaft tilt angle (degrees) + 0.43 NacCMxn - Downwind distance from the tower-top to the nacelle CM (meters) + 0 NacCMyn - Lateral distance from the tower-top to the nacelle CM (meters) + -1.2 NacCMzn - Vertical distance from the tower-top to the nacelle CM (meters) + 0 NcIMUxn - Downwind distance from the tower-top to the nacelle IMU (meters) + 0 NcIMUyn - Lateral distance from the tower-top to the nacelle IMU (meters) + -1.2 NcIMUzn - Vertical distance from the tower-top to the nacelle IMU (meters) + -1.2 Twr2Shft - Vertical distance from the tower-top to the rotor shaft (meters) + -24.0 TowerHt - Height of tower relative to ground level [onshore], MSL [offshore wind or floating MHK], or seabed [fixed MHK] (meters) + -9.0 TowerBsHt - Height of tower base relative to ground level [onshore], MSL [offshore wind or floating MHK], or seabed [fixed MHK] (meters) + 0 PtfmCMxt - Downwind distance from the ground level [onshore], MSL [offshore wind or floating MHK], or seabed [fixed MHK] to the platform CM (meters) + 0 PtfmCMyt - Lateral distance from the ground level [onshore], MSL [offshore wind or floating MHK], or seabed [fixed MHK] to the platform CM (meters) + -6.09 PtfmCMzt - Vertical distance from the ground level [onshore], MSL [offshore wind or floating MHK], or seabed [fixed MHK] to the platform CM (meters) + 0 PtfmRefzt - Vertical distance from the ground level [onshore], MSL [offshore wind or floating MHK], or seabed [fixed MHK] to the platform reference point (meters) +---------------------- MASS AND INERTIA ---------------------------------------- + 0 TipMass(1) - Tip-brake mass, blade 1 (kg) + 0 TipMass(2) - Tip-brake mass, blade 2 (kg) + 0 TipMass(3) - Tip-brake mass, blade 3 (kg) [unused for 2 blades] + 140 HubMass - Hub mass (kg) + 79.6 HubIner - Hub inertia about rotor axis [3 blades] or teeter axis [2 blades] (kg m^2) + 139.50 GenIner - Generator inertia about HSS (kg m^2) + 40100 NacMass - Nacelle mass (kg) + 244643 NacYIner - Nacelle inertia about yaw axis (kg m^2) + 0 YawBrMass - Yaw bearing mass (kg) + 2525214 PtfmMass - Platform mass (kg) + 195242474 PtfmRIner - Platform inertia for roll tilt rotation about the platform CM (kg m^2) + 919435755 PtfmPIner - Platform inertia for pitch tilt rotation about the platform CM (kg m^2) + 1053535885 PtfmYIner - Platform inertia for yaw rotation about the platform CM (kg m^2) +---------------------- BLADE --------------------------------------------------- + 8 BldNodes - Number of blade nodes (per blade) used for analysis (-) +"MHK_RM1_ElastoDyn_Blade.dat" BldFile(1) - Name of file containing properties for blade 1 (quoted string) +"MHK_RM1_ElastoDyn_Blade.dat" BldFile(2) - Name of file containing properties for blade 2 (quoted string) +"unused" BldFile(3) - Name of file containing properties for blade 3 (quoted string) [unused for 2 blades] +---------------------- ROTOR-TEETER -------------------------------------------- + 0 TeetMod - Rotor-teeter spring/damper model {0: none, 1: standard, 2: user-defined from routine UserTeet} (switch) [unused for 3 blades] + 0 TeetDmpP - Rotor-teeter damper position (degrees) [used only for 2 blades and when TeetMod=1] + 0 TeetDmp - Rotor-teeter damping constant (N-m/(rad/s)) [used only for 2 blades and when TeetMod=1] + 0 TeetCDmp - Rotor-teeter rate-independent Coulomb-damping moment (N-m) [used only for 2 blades and when TeetMod=1] + 0 TeetSStP - Rotor-teeter soft-stop position (degrees) [used only for 2 blades and when TeetMod=1] + 0 TeetHStP - Rotor-teeter hard-stop position (degrees) [used only for 2 blades and when TeetMod=1] + 0 TeetSSSp - Rotor-teeter soft-stop linear-spring constant (N-m/rad) [used only for 2 blades and when TeetMod=1] + 0 TeetHSSp - Rotor-teeter hard-stop linear-spring constant (N-m/rad) [used only for 2 blades and when TeetMod=1] +---------------------- DRIVETRAIN ---------------------------------------------- + 92 GBoxEff - Gearbox efficiency (%) + 53 GBRatio - Gearbox ratio (-) + 600000 DTTorSpr - Drivetrain torsional spring (N-m/rad) + 100000 DTTorDmp - Drivetrain torsional damper (N-m/(rad/s)) +---------------------- FURLING ------------------------------------------------- +False Furling - Read in additional model properties for furling turbine (flag) [must currently be FALSE) +"unused" FurlFile - Name of file containing furling properties (quoted string) [unused when Furling=False] +---------------------- TOWER --------------------------------------------------- + 2 TwrNodes - Number of tower nodes used for analysis (-) +"MHK_RM1_ElastoDyn_Tower.dat" TwrFile - Name of file containing tower properties (quoted string) +---------------------- OUTPUT -------------------------------------------------- +True SumPrint - Print summary data to ".sum" (flag) + 1 OutFile - Switch to determine where output will be placed: {1: in module output file only; 2: in glue code output file only; 3: both} (currently unused) +True TabDelim - Use tab delimiters in text tabular output file? (flag) (currently unused) +"ES10.3E2" OutFmt - Format used for text tabular output (except time). Resulting field should be 10 characters. (quoted string) (currently unused) + 0 TStart - Time to begin tabular output (s) (currently unused) + 1 DecFact - Decimation factor for tabular output {1: output every time step} (-) (currently unused) + 0 NTwGages - Number of tower nodes that have strain gages for output [0 to 9] (-) + 0 TwrGagNd - List of tower nodes that have strain gages [1 to TwrNodes] (-) [unused if NTwGages=0] + 0 NBlGages - Number of blade nodes that have strain gages for output [0 to 9] (-) + 0 BldGagNd - List of blade nodes that have strain gages [1 to BldNodes] (-) [unused if NBlGages=0] + OutList - The next line(s) contains a list of output parameters. See OutListParameters.xlsx for a listing of available output channels, (-) +"PtfmSurge" +"PtfmSway" +"PtfmHeave" +"PtfmRoll" +"PtfmPitch" +"PtfmYaw" +"TwrTpTDxi" +"TwrTpTDyi" +"TwrTpTDzi" +"OoPDefl1" +"RotSpeed" +"GenSpeed" +END of input file (the word "END" must appear in the first 3 columns of this last OutList line) +-------------------------------------------------------------------------------- diff --git a/Test_Cases/MHK_RM1/MHK_RM1_Floating_HydroDyn.dat b/Test_Cases/MHK_RM1/MHK_RM1_Floating_HydroDyn.dat new file mode 100644 index 00000000..336853a1 --- /dev/null +++ b/Test_Cases/MHK_RM1/MHK_RM1_Floating_HydroDyn.dat @@ -0,0 +1,207 @@ +------- HydroDyn Input File ---------------------------------------------------- +Floating MHK turbine hydrodynamic support structure input properties, based on the RM1 tidal current rotor with a quad-style floating platform +False Echo - Echo the input file data (flag) +---------------------- ENVIRONMENTAL CONDITIONS -------------------------------- +"DEFAULT" WtrDens - Water density (kg/m^3) +"DEFAULT" WtrDpth - Water depth (meters) +"DEFAULT" MSL2SWL - Offset between still-water level and mean sea level (meters) [positive upward; unused when WaveMod = 6; must be zero if PotMod=1 or 2] +---------------------- WAVES --------------------------------------------------- + 0 WaveMod - Incident wave kinematics model {0: none=still water, 1: regular (periodic), 1P#: regular with user-specified phase, 2: JONSWAP/Pierson-Moskowitz spectrum (irregular), 3: White noise spectrum (irregular), 4: user-defined spectrum from routine UserWaveSpctrm (irregular), 5: Externally generated wave-elevation time series, 6: Externally generated full wave-kinematics time series [option 6 is invalid for PotMod/=0]} (switch) + 0 WaveStMod - Model for stretching incident wave kinematics to instantaneous free surface {0: none=no stretching, 1: vertical stretching, 2: extrapolation stretching, 3: Wheeler stretching} (switch) [unused when WaveMod=0 or when PotMod/=0] + 3600 WaveTMax - Analysis time for incident wave calculations (sec) [unused when WaveMod=0; determines WaveDOmega=2Pi/WaveTMax in the IFFT] + 0.1 WaveDT - Time step for incident wave calculations (sec) [unused when WaveMod=0; 0.1<=WaveDT<=1.0 recommended; determines WaveOmegaMax=Pi/WaveDT in the IFFT] + 1.0 WaveHs - Significant wave height of incident waves (meters) [used only when WaveMod=1, 2, or 3] + 10 WaveTp - Peak-spectral period of incident waves (sec) [used only when WaveMod=1 or 2] +"DEFAULT" WavePkShp - Peak-shape parameter of incident wave spectrum (-) or DEFAULT (string) [used only when WaveMod=2; use 1.0 for Pierson-Moskowitz] + 0.314159 WvLowCOff - Low cut-off frequency or lower frequency limit of the wave spectrum beyond which the wave spectrum is zeroed (rad/s) [unused when WaveMod=0, 1, or 6] + 1.570796 WvHiCOff - High cut-off frequency or upper frequency limit of the wave spectrum beyond which the wave spectrum is zeroed (rad/s) [unused when WaveMod=0, 1, or 6] + 0 WaveDir - Incident wave propagation heading direction (degrees) [unused when WaveMod=0 or 6] + 0 WaveDirMod - Directional spreading function {0: none, 1: COS2S} (-) [only used when WaveMod=2,3, or 4] + 1 WaveDirSpread - Wave direction spreading coefficient ( > 0 ) (-) [only used when WaveMod=2,3, or 4 and WaveDirMod=1] + 1 WaveNDir - Number of wave directions (-) [only used when WaveMod=2,3, or 4 and WaveDirMod=1; odd number only] + 0 WaveDirRange - Range of wave directions (full range: WaveDir +/- 1/2*WaveDirRange) (degrees) [only used when WaveMod=2,3,or 4 and WaveDirMod=1] + 123456789 WaveSeed(1) - First random seed of incident waves [-2147483648 to 2147483647] (-) [unused when WaveMod=0, 5, or 6] + RANLUX WaveSeed(2) - Second random seed of incident waves [-2147483648 to 2147483647] for intrinsic pRNG, or an alternative pRNG: "RanLux" (-) [unused when WaveMod=0, 5, or 6] +FALSE WaveNDAmp - Flag for normally distributed amplitudes (flag) [only used when WaveMod=2, 3, or 4] +"" WvKinFile - Root name of externally generated wave data file(s) (quoted string) [used only when WaveMod=5 or 6] + 1 NWaveElev - Number of points where the incident wave elevations can be computed (-) [maximum of 9 output locations] + 0 WaveElevxi - List of xi-coordinates for points where the incident wave elevations can be output (meters) [NWaveElev points, separated by commas or white space; usused if NWaveElev = 0] + 0 WaveElevyi - List of yi-coordinates for points where the incident wave elevations can be output (meters) [NWaveElev points, separated by commas or white space; usused if NWaveElev = 0] +---------------------- 2ND-ORDER WAVES ----------------------------------------- [unused with WaveMod=0 or 6] +FALSE WvDiffQTF - Full difference-frequency 2nd-order wave kinematics (flag) +FALSE WvSumQTF - Full summation-frequency 2nd-order wave kinematics (flag) + 0 WvLowCOffD - Low frequency cutoff used in the difference-frequencies (rad/s) [Only used with a difference-frequency method] + 1.256637 WvHiCOffD - High frequency cutoff used in the difference-frequencies (rad/s) [Only used with a difference-frequency method] + 0.618319 WvLowCOffS - Low frequency cutoff used in the summation-frequencies (rad/s) [Only used with a summation-frequency method] + 3.141593 WvHiCOffS - High frequency cutoff used in the summation-frequencies (rad/s) [Only used with a summation-frequency method] +---------------------- CURRENT ------------------------------------------------- [unused with WaveMod=6] + 1 CurrMod - Current profile model {0: none=no current, 1: standard, 2: user-defined from routine UserCurrent} (switch) + 0 CurrSSV0 - Sub-surface current velocity at still water level (m/s) [used only when CurrMod=1] + 0 CurrSSDir - Sub-surface current heading direction (degrees) or DEFAULT (string) [used only when CurrMod=1] + 12.2 CurrNSRef - Near-surface current reference depth (meters) [used only when CurrMod=1] + 0 CurrNSV0 - Near-surface current velocity at still water level (m/s) [used only when CurrMod=1] + 0 CurrNSDir - Near-surface current heading direction (degrees) [used only when CurrMod=1] + 1.9 CurrDIV - Depth-independent current velocity (m/s) [used only when CurrMod=1] + 0 CurrDIDir - Depth-independent current heading direction (degrees) [used only when CurrMod=1] +---------------------- FLOATING PLATFORM --------------------------------------- [unused with WaveMod=6] + 1 PotMod - Potential-flow model {0: none=no potential flow, 1: frequency-to-time-domain transforms based on WAMIT output, 2: fluid-impulse theory (FIT)} (switch) + 1 ExctnMod - Wave-excitation model {0: no wave-excitation calculation, 1: DFT, 2: state-space} (switch) [only used when PotMod=1; STATE-SPACE REQUIRES *.ssexctn INPUT FILE] + 1 RdtnMod - Radiation memory-effect model {0: no memory-effect calculation, 1: convolution, 2: state-space} (switch) [only used when PotMod=1; STATE-SPACE REQUIRES *.ss INPUT FILE] + 60 RdtnTMax - Analysis time for wave radiation kernel calculations (sec) [only used when PotMod=1 and RdtnMod=1; determines RdtnDOmega=Pi/RdtnTMax in the cosine transform; MAKE SURE THIS IS LONG ENOUGH FOR THE RADIATION IMPULSE RESPONSE FUNCTIONS TO DECAY TO NEAR-ZERO FOR THE GIVEN PLATFORM!] + "DEFAULT" RdtnDT - Time step for wave radiation kernel calculations (sec) [only used when PotMod=1 and ExctnMod>1 or RdtnMod>0; DT<=RdtnDT<=0.1 recommended; determines RdtnOmegaMax=Pi/RdtnDT in the cosine transform] + 1 NBody - Number of WAMIT bodies to be used (-) [>=1; only used when PotMod=1. If NBodyMod=1, the WAMIT data contains a vector of size 6*NBody x 1 and matrices of size 6*NBody x 6*NBody; if NBodyMod>1, there are NBody sets of WAMIT data each with a vector of size 6 x 1 and matrices of size 6 x 6] + 2 NBodyMod - Body coupling model {1: include coupling terms between each body and NBody in HydroDyn equals NBODY in WAMIT, 2: neglect coupling terms between each body and NBODY=1 with XBODY=0 in WAMIT, 3: Neglect coupling terms between each body and NBODY=1 with XBODY=/0 in WAMIT} (switch) [only used when PotMod=1] +"MHK_RM1_Floating" PotFile - Root name of potential-flow model data; WAMIT output files containing the linear, nondimensionalized, hydrostatic restoring matrix (.hst), frequency-dependent hydrodynamic added mass matrix and damping matrix (.1), and frequency- and direction-dependent wave excitation force vector per unit wave amplitude (.3) (quoted string) [1 to NBody if NBodyMod>1] [only used when PotMod=1 and ExctnMod>0 or RdtnMod>0] [MAKE SURE THE FREQUENCIES INHERENT IN THESE WAMIT FILES SPAN THE PHYSICALLY-SIGNIFICANT RANGE OF FREQUENCIES FOR THE GIVEN PLATFORM; THEY MUST CONTAIN THE ZERO- AND INFINITE-FREQUENCY LIMITS!] + 1 WAMITULEN - Characteristic body length scale used to redimensionalize WAMIT output (meters) [1 to NBody if NBodyMod>1] [only used when PotMod=1 and ExctnMod=1 or RdtnMod=1] + 0 PtfmRefxt - The xt offset of the body reference point(s) from (0,0,0) (meters) [1 to NBody] [only used when PotMod=1] + 0 PtfmRefyt - The yt offset of the body reference point(s) from (0,0,0) (meters) [1 to NBody] [only used when PotMod=1] + 0 PtfmRefzt - The zt offset of the body reference point(s) from (0,0,0) (meters) [1 to NBody] [only used when PotMod=1. If NBodyMod=2,PtfmRefzt=0.0] + 0 PtfmRefztRot - The rotation about zt of the body reference frame(s) from xt/yt (degrees) [1 to NBody] [only used when PotMod=1] + 2671.85 PtfmVol0 - **Note - 2672.6 from WAMIT with -0.748 correction for missing tower base hydrostatic pressure ** Displaced volume of water when the body is in its undisplaced position (m^3) [1 to NBody] [only used when PotMod=1; USE THE SAME VALUE COMPUTED BY WAMIT AS OUTPUT IN THE .OUT FILE!] + 0 PtfmCOBxt - The xt offset of the center of buoyancy (COB) from (0,0) (meters) [1 to NBody] [only used when PotMod=1] + 0 PtfmCOByt - The yt offset of the center of buoyancy (COB) from (0,0) (meters) [1 to NBody] [only used when PotMod=1] +---------------------- 2ND-ORDER FLOATING PLATFORM FORCES ---------------------- [unused with WaveMod=0 or 6, or PotMod=0 or 2] + 0 MnDrift - Mean-drift 2nd-order forces computed {0: None; [7, 8, 9, 10, 11, or 12]: WAMIT file to use} [Only one of MnDrift, NewmanApp, or DiffQTF can be non-zero. If NBody>1, MnDrift /=8] + 0 NewmanApp - Mean- and slow-drift 2nd-order forces computed with Newman's approximation {0: None; [7, 8, 9, 10, 11, or 12]: WAMIT file to use} [Only one of MnDrift, NewmanApp, or DiffQTF can be non-zero. If NBody>1, NewmanApp/=8. Used only when WaveDirMod=0] + 0 DiffQTF - Full difference-frequency 2nd-order forces computed with full QTF {0: None; [10, 11, or 12]: WAMIT file to use} [Only one of MnDrift, NewmanApp, or DiffQTF can be non-zero] + 0 SumQTF - Full summation -frequency 2nd-order forces computed with full QTF {0: None; [10, 11, or 12]: WAMIT file to use} +---------------------- PLATFORM ADDITIONAL STIFFNESS AND DAMPING -------------- [unused with PotMod=0 or 2] + 0 AddF0 - Additional preload (N, N-m) [If NBodyMod=1, one size 6*NBody x 1 vector; if NBodyMod>1, NBody size 6 x 1 vectors] + 0 + 0 + 0 + 0 + 0 + 0 0 0 0 0 0 AddCLin - Additional linear stiffness (N/m, N/rad, N-m/m, N-m/rad) [If NBodyMod=1, one size 6*NBody x 6*NBody matrix; if NBodyMod>1, NBody size 6 x 6 matrices] + 0 0 0 0 0 0 + 0 0 0 0 0 0 + 0 0 0 0 0 0 + 0 0 0 0 0 0 + 0 0 0 0 0 0 + 0 0 0 0 0 0 AddBLin - Additional linear damping(N/(m/s), N/(rad/s), N-m/(m/s), N-m/(rad/s)) [If NBodyMod=1, one size 6*NBody x 6*NBody matrix; if NBodyMod>1, NBody size 6 x 6 matrices] + 0 0 0 0 0 0 + 0 0 0 0 0 0 + 0 0 0 0 0 0 + 0 0 0 0 0 0 + 0 0 0 0 0 0 + 0 0 0 0 0 0 AddBQuad - Additional quadratic drag(N/(m/s)^2, N/(rad/s)^2, N-m(m/s)^2, N-m/(rad/s)^2) [If NBodyMod=1, one size 6*NBody x 6*NBody matrix; if NBodyMod>1, NBody size 6 x 6 matrices] + 0 0 0 0 0 0 + 0 0 0 0 0 0 + 0 0 0 0 0 0 + 0 0 0 0 0 0 + 0 0 0 0 0 0 +---------------------- AXIAL COEFFICIENTS -------------------------------------- + 2 NAxCoef - Number of axial coefficients (-) +AxCoefID AxCd AxCa AxCp +(-) (-) (-) (-) +1 0.00 0.00 0.00 ! Columns / Braces (no exposed member ends) +2 1.00 1.00 1.00 ! Heave Plates +---------------------- MEMBER JOINTS ------------------------------------------- + 33 NJoints - Number of joints (-) [must be exactly 0 or at least 2] +JointID Jointxi Jointyi Jointzi JointAxID JointOvrlp [JointOvrlp= 0: do nothing at joint, 1: eliminate overlaps by calculating super member] +(-) (m) (m) (m) (-) (switch) +0 28.0 0 -10 1 0 ! Downstream Column +1 28.0 0 6 1 0 +2 -28.0 0 -10 1 0 ! Upstream Column +3 -28.0 0 6 1 0 +4 0 -12.0 -10 1 0 ! Starboard Column +5 0 -12.0 6 1 0 +6 0 12.0 -10 1 0 ! Port Column +7 0 12.0 6 1 0 +8 3.67658 10.4243 4.5 1 0 ! Upper Braces +9 24.3234 1.57568 4.5 1 0 +10 3.67658 -10.4243 4.5 1 0 +11 24.3234 -1.57568 4.5 1 0 +12 -3.67658 10.4243 4.5 1 0 +13 -24.3234 1.57568 4.5 1 0 +14 -3.67658 -10.4243 4.5 1 0 +15 -24.3234 -1.57568 4.5 1 0 +16 3.67658 10.4243 -8.5 1 0 ! Lower Braces +17 24.3234 1.57568 -8.5 1 0 +18 3.67658 -10.4243 -8.5 1 0 +19 24.3234 -1.57568 -8.5 1 0 +20 -3.67658 10.4243 -8.5 1 0 +21 -24.3234 1.57568 -8.5 1 0 +22 -3.67658 -10.4243 -8.5 1 0 +23 -24.3234 -1.57568 -8.5 1 0 +24 0 -8 4.5 1 0 ! Tower Braces +25 0 8 4.5 1 0 +26 0 -8 -8.5 1 0 +27 0 8 -8.5 1 0 +28 0 0 -8.5 1 0 +29 28.0 0 -10.5 2 0 ! Heave Plates +30 -28.0 0 -10.5 2 0 +31 0 -12.0 -10.5 2 0 +32 0 12.0 -10.5 2 0 +---------------------- MEMBER CROSS-SECTION PROPERTIES ------------------------- + 4 NPropSets - Number of member property sets (-) +PropSetID PropD PropThck +(-) (m) (m) +0 8.0 0.02 ! Columns +1 2.0 0.02 ! Braces +2 2.0 0.081 ! Flooded Braces (not flooded in hydrodyn) +3 12.0 0.3925 ! Flooded Heave Plates (not flooded in hydrodyn) +---------------------- SIMPLE HYDRODYNAMIC COEFFICIENTS (model 1) -------------- +SimplCd SimplCdMG SimplCa SimplCaMG SimplCp SimplCpMG SimplAxCd SimplAxCdMG SimplAxCa SimplAxCaMG SimplAxCp SimplAxCpMG +(-) (-) (-) (-) (-) (-) (-) (-) (-) (-) (-) (-) +1.2 0.00 1.00 0.00 1.00 1.00 0.00 0.00 0.00 0.00 1.00 1.00 +---------------------- DEPTH-BASED HYDRODYNAMIC COEFFICIENTS (model 2) --------- + 0 NCoefDpth - Number of depth-dependent coefficients (-) +Dpth DpthCd DpthCdMG DpthCa DpthCaMG DpthCp DpthCpMG DpthAxCd DpthAxCdMG DpthAxCa DpthAxCaMG DpthAxCp DpthAxCpMG +(m) (-) (-) (-) (-) (-) (-) (-) (-) (-) (-) (-) (-) +---------------------- MEMBER-BASED HYDRODYNAMIC COEFFICIENTS (model 3) -------- + 0 NCoefMembers - Number of member-based coefficients (-) +MemberID MemberCd1 MemberCd2 MemberCdMG1 MemberCdMG2 MemberCa1 MemberCa2 MemberCaMG1 MemberCaMG2 MemberCp1 MemberCp2 MemberCpMG1 MemberCpMG2 MemberAxCd1 MemberAxCd2 MemberAxCdMG1 MemberAxCdMG2 MemberAxCa1 MemberAxCa2 MemberAxCaMG1 MemberAxCaMG2 MemberAxCp1 MemberAxCp2 MemberAxCpMG1 MemberAxCpMG2 +(-) (-) (-) (-) (-) (-) (-) (-) (-) (-) (-) (-) (-) (-) (-) (-) (-) (-) (-) (-) (-) (-) (-) (-) (-) +-------------------- MEMBERS --------------------------------------------------- + 20 NMembers - Number of members (-) +MemberID MJointID1 MJointID2 MPropSetID1 MPropSetID2 MDivSize MCoefMod PropPot [MCoefMod=1: use simple coeff table, 2: use depth-based coeff table, 3: use member-based coeff table] [ PropPot/=0 if member is modeled with potential-flow theory] +(-) (-) (-) (-) (-) (m) (switch) (flag) +0 0 1 0 0 0.1 1 TRUE ! Columns +1 2 3 0 0 0.1 1 TRUE +2 4 5 0 0 0.1 1 TRUE +3 6 7 0 0 0.1 1 TRUE +4 8 9 1 1 0.1 1 TRUE ! Upper Braces +5 10 11 1 1 0.1 1 TRUE +6 12 13 1 1 0.1 1 TRUE +7 14 15 1 1 0.1 1 TRUE +8 16 17 2 2 0.1 1 TRUE ! Lower Braces +9 18 19 2 2 0.1 1 TRUE +10 20 21 2 2 0.1 1 TRUE +11 22 23 2 2 0.1 1 TRUE +12 24 25 1 1 0.1 1 TRUE ! Tower Braces +13 26 27 1 1 0.1 1 TRUE +14 24 28 1 1 0.1 1 TRUE +15 25 28 1 1 0.1 1 TRUE +16 0 29 3 3 0.1 1 TRUE ! Heave Plates +17 2 30 3 3 0.1 1 TRUE +18 4 31 3 3 0.1 1 TRUE +19 6 32 3 3 0.1 1 TRUE +---------------------- FILLED MEMBERS ------------------------------------------ + 0 NFillGroups - Number of filled member groups (-) [If FillDens = DEFAULT, then FillDens = WtrDens; FillFSLoc is related to MSL2SWL] +FillNumM FillMList FillFSLoc FillDens +(-) (-) (m) (kg/m^3) +---------------------- MARINE GROWTH ------------------------------------------- + 0 NMGDepths - Number of -growth depths specified (-) +MGDpth MGThck MGDens +(m) (m) (kg/m^3) +---------------------- MEMBER OUTPUT LIST -------------------------------------- + 0 NMOutputs - Number of member outputs (-) [must be < 10] +MemberID NOutLoc NodeLocs [NOutLoc < 10; node locations are normalized distance from the start of the member, and must be >=0 and <= 1] [unused if NMOutputs=0] +(-) (-) (-) +---------------------- JOINT OUTPUT LIST --------------------------------------- + 0 NJOutputs - Number of joint outputs [Must be < 10] + 0 JOutLst - List of JointIDs which are to be output (-)[unused if NJOutputs=0] +---------------------- OUTPUT -------------------------------------------------- +True HDSum - Output a summary file [flag] +False OutAll - Output all user-specified member and joint loads (only at each member end, not interior locations) [flag] + 2 OutSwtch - Output requested channels to: [1=Hydrodyn.out, 2=GlueCode.out, 3=both files] +"E15.7e2" OutFmt - Output format for numerical results (quoted string) [not checked for validity!] +"A11" OutSFmt - Output format for header strings (quoted string) [not checked for validity!] +---------------------- OUTPUT CHANNELS ----------------------------------------- +"Wave1Elev" - Wave elevation at the platform reference point (0, 0) +"HydroFxi" - Buoyancy force [N] in the X direction. +"HydroFyi" - Buoyancy force [N] in the Y direction. +"HydroFzi" - Buoyancy force [N] in the vertical direction (Z). +END of output channels and end of file. (the word "END" must appear in the first 3 columns of this line) + diff --git a/Test_Cases/MHK_RM1/MHK_RM1_Floating_InflowWind.dat b/Test_Cases/MHK_RM1/MHK_RM1_Floating_InflowWind.dat new file mode 100644 index 00000000..73c0b2f7 --- /dev/null +++ b/Test_Cases/MHK_RM1/MHK_RM1_Floating_InflowWind.dat @@ -0,0 +1,69 @@ +------- InflowWind INPUT FILE --------------------------------------------------------------------------------- +Steady 1.9 m/s inflow for floating MHK turbine, based on the RM1 tidal current rotor +--------------------------------------------------------------------------------------------------------------- +False Echo - Echo input data to .ech (flag) + 1 WindType - Switch for wind file type (1=steady; 2=uniform; 3=binary TurbSim FF; 4=binary Bladed-style FF; 5=HAWC format; 6=User defined; 7=native Bladed FF) + 0 PropagationDir - Direction of wind propagation (meteorological rotation from aligned with X (positive rotates towards -Y) -- degrees) (not used for native Bladed format WindType=7) + 0 VFlowAng - Upflow angle (degrees) (not used for native Bladed format WindType=7) +False VelInterpCubic - Use cubic interpolation for velocity in time (false=linear, true=cubic) [Used with WindType=2,3,4,5,7] + 1 NWindVel - Number of points to output the wind velocity (0 to 9) + 0 WindVxiList - List of coordinates in the inertial X direction (m) + 0 WindVyiList - List of coordinates in the inertial Y direction (m) + 12.2 WindVziList - List of coordinates in the inertial Z direction (m) +================== Parameters for Steady Wind Conditions [used only for WindType = 1] ======================= + 1.9 HWindSpeed - Horizontal wind speed (m/s) + 12.2 RefHt - Reference height for horizontal wind speed (m) + 0 PLExp - Power law exponent (-) +================== Parameters for Uniform wind file [used only for WindType = 2] ============================ +"unused" Filename_Uni - Filename of time series data for uniform wind field. (-) + 30 RefHt_Uni - Reference height for horizontal wind speed (m) + 125.88 RefLength - Reference length for linear horizontal and vertical sheer (-) +================== Parameters for Binary TurbSim Full-Field files [used only for WindType = 3] ============== +"unused" FileName_BTS - Name of the Full field wind file to use (.bts) +================== Parameters for Binary Bladed-style Full-Field files [used only for WindType = 4 or WindType = 7] ======= +"unused" FileNameRoot - WindType=4: Rootname of the full-field wind file to use (.wnd, .sum); WindType=7: name of the intermediate file with wind scaling values +False TowerFile - Have tower file (.twr) (flag) ignored when WindType = 7 +================== Parameters for HAWC-format binary files [Only used with WindType = 5] ==================== +"unused" FileName_u - name of the file containing the u-component fluctuating wind (.bin) +"unused" FileName_v - name of the file containing the v-component fluctuating wind (.bin) +"unused" FileName_w - name of the file containing the w-component fluctuating wind (.bin) + 64 nx - number of grids in the x direction (in the 3 files above) (-) + 32 ny - number of grids in the y direction (in the 3 files above) (-) + 32 nz - number of grids in the z direction (in the 3 files above) (-) + 16 dx - distance (in meters) between points in the x direction (m) + 3 dy - distance (in meters) between points in the y direction (m) + 3 dz - distance (in meters) between points in the z direction (m) + 90 RefHt_Hawc - reference height; the height (in meters) of the vertical center of the grid (m) + ------------- Scaling parameters for turbulence --------------------------------------------------------- + 1 ScaleMethod - Turbulence scaling method [0 = none, 1 = direct scaling, 2 = calculate scaling factor based on a desired standard deviation] + 1 SFx - Turbulence scaling factor for the x direction (-) [ScaleMethod=1] + 1 SFy - Turbulence scaling factor for the y direction (-) [ScaleMethod=1] + 1 SFz - Turbulence scaling factor for the z direction (-) [ScaleMethod=1] + 1 SigmaFx - Turbulence standard deviation to calculate scaling from in x direction (m/s) [ScaleMethod=2] + 1 SigmaFy - Turbulence standard deviation to calculate scaling from in y direction (m/s) [ScaleMethod=2] + 1 SigmaFz - Turbulence standard deviation to calculate scaling from in z direction (m/s) [ScaleMethod=2] + ------------- Mean wind profile parameters (added to HAWC-format files) --------------------------------- + 5 URef - Mean u-component wind speed at the reference height (m/s) + 2 WindProfile - Wind profile type (0=constant;1=logarithmic,2=power law) + 0 PLExp_Hawc - Power law exponent (-) (used for PL wind profile type only) + 0.03 Z0 - Surface roughness length (m) (used for LG wind profile type only) + 0 XOffset - Initial offset in +x direction (shift of wind box) +================== LIDAR Parameters =========================================================================== +0 SensorType - Switch for lidar configuration (0 = None, 1 = Single Point Beam(s), 2 = Continuous, 3 = Pulsed) +0 NumPulseGate - Number of lidar measurement gates (used when SensorType = 3) +30 PulseSpacing - Distance between range gates (m) (used when SensorType = 3) +0 NumBeam - Number of lidar measurement beams (0-5)(used when SensorType = 1) +-200 FocalDistanceX - Focal distance co-ordinates of the lidar beam in the x direction (relative to hub height) (only first coordinate used for SensorType 2 and 3) (m) +0 FocalDistanceY - Focal distance co-ordinates of the lidar beam in the y direction (relative to hub height) (only first coordinate used for SensorType 2 and 3) (m) +0 FocalDistanceZ - Focal distance co-ordinates of the lidar beam in the z direction (relative to hub height) (only first coordinate used for SensorType 2 and 3) (m) +0.0 0.0 0.0 RotorApexOffsetPos - Offset of the lidar from hub height (m) +17 URefLid - Reference average wind speed for the lidar[m/s] +0.25 MeasurementInterval - Time between each measurement [s] +False LidRadialVel - TRUE => return radial component, FALSE => return 'x' direction estimate +1 ConsiderHubMotion - Flag whether to consider the hub motion's impact on Lidar measurements +================== OUTPUT ===================================================================================== +True SumPrint - Print summary data to .IfW.sum (flag) + OutList - The next line(s) contains a list of output parameters. See OutListParameters.xlsx for a listing of available output channels, (-) +Wind1VelX +END of input file (the word "END" must appear in the first 3 columns of this last OutList line) +--------------------------------------------------------------------------------------------------------------- diff --git a/Test_Cases/MHK_RM1/MHK_RM1_Floating_MoorDyn.dat b/Test_Cases/MHK_RM1/MHK_RM1_Floating_MoorDyn.dat new file mode 100644 index 00000000..89e416dc --- /dev/null +++ b/Test_Cases/MHK_RM1/MHK_RM1_Floating_MoorDyn.dat @@ -0,0 +1,58 @@ +--------------------- MoorDyn Input File ------------------------------------ +Floating MHK turbine mooring input properties, based on the RM1 tidal current rotor with a quad-style floating platform +FALSE Echo - echo the input file data (flag) +----------------------- LINE TYPES Chain studless 0.018m -------------------- +Name Diam MassDen EA BA/-zeta EI Cd Ca CdAx CaAx +(-) (m) (kg/m) (N) (N-s/-) (-) (-) (-) (-) (-) +main 0.324 644.8 85.4e8 -0.8 0.8 2.4 1.0 1.15 0.5 +---------------------- POINTS ----------------------------------------------- +Node Type X Y Z M V CdA CA +(-) (-) (m) (m) (m) (kg) (m^3) (m^2) (-) +1 Fixed -152.0 -50.0 -50.0 0 0 0 0 +2 Fixed -152.0 0.0 -50.0 0 0 0 0 +3 Fixed -152.0 50.0 -50.0 0 0 0 0 +4 Fixed 152.0 -50.0 -50.0 0 0 0 0 +5 Fixed 152.0 0.0 -50.0 0 0 0 0 +6 Fixed 152.0 50.0 -50.0 0 0 0 0 +7 Vessel -34.0 0.0 -10.0 0 0 0 0 +8 Vessel -34.0 0.0 -10.0 0 0 0 0 +9 Vessel -34.0 0.0 -10.0 0 0 0 0 +10 Vessel 34.0 0.0 -10.0 0 0 0 0 +11 Vessel 34.0 0.0 -10.0 0 0 0 0 +12 Vessel 34.0 0.0 -10.0 0 0 0 0 +---------------------- LINES ------------------------------------------------ +Line LineType AttachA AttachB UnstrLen NumSegs Outputs +(-) (-) (-) (-) (m) (-) (-) +1 main 1 7 160.0 30 - +2 main 2 8 152.0 30 - +3 main 3 9 160.0 30 - +4 main 4 10 160.0 30 - +5 main 5 11 152.0 30 - +6 main 6 12 160.0 30 - +---------------------- SOLVER OPTIONS --------------------------------------- +0.5e-4 dtM - time step to use in mooring integration (s) +3.0e6 kbot - bottom stiffness (Pa/m) +3.0e5 cbot - bottom damping (Pa-s/m) +1.0 dtIC - time interval for analyzing convergence during IC gen (s) +10.0 TmaxIC - max time for ic gen (s) +4.0 CdScaleIC - factor by which to scale drag coefficients during dynamic relaxation (-) +0.1 threshIC - threshold for IC convergence (-) +------------------------ OUTPUTS -------------------------------------------- +FairTen1 FairTen2 FairTen3 FairTen4 FairTen5 FairTen6 +AnchTen1 AnchTen2 AnchTen3 AnchTen4 AnchTen5 AnchTen6 +Con1fX Con1fY Con1fZ +Con2fX Con2fY Con2fZ +Con3fX Con3fY Con3fZ +Con4fX Con4fY Con4fZ +Con5fX Con5fY Con5fZ +Con6fX Con6fY Con6fZ +Con7fX Con7fY Con7fZ Con7pX Con7pY Con7pZ +Con8fX Con8fY Con8fZ Con8pX Con8pY Con8pZ +Con9fX Con9fY Con9fZ Con9pX Con9pY Con9pZ +Con10fX Con10fY Con10fZ Con10pX Con10pY Con10pZ +Con11fX Con11fY Con11fZ Con11pX Con11pY Con11pZ +Con12fX Con12fY Con12fZ Con12pX Con12pY Con12pZ +L1N1pZ L1N2pZ L1N3pZ L1N4pZ L1N5pZ L1N6pZ L1N7pZ L1N8pZ L1N9pZ L1N10pZ L1N11pZ L1N12pZ L1N13pZ L1N14pZ L1N15pZ L1N16pZ L1N17pZ L1N18pZ L1N19pZ L1N20pZ L1N21pZ L1N22pZ L1N23pZ L1N24pZ L1N25pZ L1N26pZ L1N27pZ L1N28pZ L1N29pZ L1N30pZ +L2N1pZ L2N2pZ L2N3pZ L2N4pZ L2N5pZ L2N6pZ L2N7pZ L2N8pZ L2N9pZ L2N10pZ L2N11pZ L2N12pZ L2N13pZ L2N14pZ L2N15pZ L2N16pZ L2N17pZ L2N18pZ L2N19pZ L2N20pZ L2N21pZ L2N22pZ L2N23pZ L2N24pZ L2N25pZ L2N26pZ L2N27pZ L2N28pZ L2N29pZ L2N30pZ +END +------------------------- need this line ------------------------------------ diff --git a/Test_Cases/MHK_RM1/MHK_RM1_ServoDyn.dat b/Test_Cases/MHK_RM1/MHK_RM1_ServoDyn.dat new file mode 100644 index 00000000..1e9b8ff8 --- /dev/null +++ b/Test_Cases/MHK_RM1/MHK_RM1_ServoDyn.dat @@ -0,0 +1,111 @@ +------- SERVODYN v1.05.* INPUT FILE -------------------------------------------- +NREL 5.0 MW Baseline Wind Turbine for Use in Offshore Analysis. Properties from Dutch Offshore Wind Energy Converter (DOWEC) 6MW Pre-Design (10046_009.pdf) and REpower 5M 5MW (5m_uk.pdf) +---------------------- SIMULATION CONTROL -------------------------------------- +False Echo - Echo input data to .ech (flag) +"default" DT - Communication interval for controllers (s) (or "default") +---------------------- PITCH CONTROL ------------------------------------------- + 5 PCMode - Pitch control mode {0: none, 3: user-defined from routine PitchCntrl, 4: user-defined from Simulink/Labview, 5: user-defined from Bladed-style DLL} (switch) + 0 TPCOn - Time to enable active pitch control (s) [unused when PCMode=0] + 9999.9 TPitManS(1) - Time to start override pitch maneuver for blade 1 and end standard pitch control (s) + 9999.9 TPitManS(2) - Time to start override pitch maneuver for blade 2 and end standard pitch control (s) + 9999.9 TPitManS(3) - Time to start override pitch maneuver for blade 3 and end standard pitch control (s) [unused for 2 blades] + 2 PitManRat(1) - Pitch rate at which override pitch maneuver heads toward final pitch angle for blade 1 (deg/s) + 2 PitManRat(2) - Pitch rate at which override pitch maneuver heads toward final pitch angle for blade 2 (deg/s) + 2 PitManRat(3) - Pitch rate at which override pitch maneuver heads toward final pitch angle for blade 3 (deg/s) [unused for 2 blades] + 0 BlPitchF(1) - Blade 1 final pitch for pitch maneuvers (degrees) + 0 BlPitchF(2) - Blade 2 final pitch for pitch maneuvers (degrees) + 0 BlPitchF(3) - Blade 3 final pitch for pitch maneuvers (degrees) [unused for 2 blades] +---------------------- GENERATOR AND TORQUE CONTROL ---------------------------- + 5 VSContrl - Variable-speed control mode {0: none, 1: simple VS, 3: user-defined from routine UserVSCont, 4: user-defined from Simulink/Labview, 5: user-defined from Bladed-style DLL} (switch) + 2 GenModel - Generator model {1: simple, 2: Thevenin, 3: user-defined from routine UserGen} (switch) [used only when VSContrl=0] + 94.4 GenEff - Generator efficiency [ignored by the Thevenin and user-defined generator models] (%) +True GenTiStr - Method to start the generator {T: timed using TimGenOn, F: generator speed using SpdGenOn} (flag) +True GenTiStp - Method to stop the generator {T: timed using TimGenOf, F: when generator power = 0} (flag) + 9999.9 SpdGenOn - Generator speed to turn on the generator for a startup (HSS speed) (rpm) [used only when GenTiStr=False] + 0 TimGenOn - Time to turn on the generator for a startup (s) [used only when GenTiStr=True] + 9999.9 TimGenOf - Time to turn off the generator (s) [used only when GenTiStp=True] +---------------------- SIMPLE VARIABLE-SPEED TORQUE CONTROL -------------------- + 9999.9 VS_RtGnSp - Rated generator speed for simple variable-speed generator control (HSS side) (rpm) [used only when VSContrl=1] + 9999.9 VS_RtTq - Rated generator torque/constant generator torque in Region 3 for simple variable-speed generator control (HSS side) (N-m) [used only when VSContrl=1] + 9999.9 VS_Rgn2K - Generator torque constant in Region 2 for simple variable-speed generator control (HSS side) (N-m/rpm^2) [used only when VSContrl=1] + 9999.9 VS_SlPc - Rated generator slip percentage in Region 2 1/2 for simple variable-speed generator control (%) [used only when VSContrl=1] +---------------------- SIMPLE INDUCTION GENERATOR ------------------------------ + 9999.9 SIG_SlPc - Rated generator slip percentage (%) [used only when VSContrl=0 and GenModel=1] + 9999.9 SIG_SySp - Synchronous (zero-torque) generator speed (rpm) [used only when VSContrl=0 and GenModel=1] + 9999.9 SIG_RtTq - Rated torque (N-m) [used only when VSContrl=0 and GenModel=1] + 9999.9 SIG_PORt - Pull-out ratio (Tpullout/Trated) (-) [used only when VSContrl=0 and GenModel=1] +---------------------- THEVENIN-EQUIVALENT INDUCTION GENERATOR ----------------- + 9999.9 TEC_Freq - Line frequency [50 or 60] (Hz) [used only when VSContrl=0 and GenModel=2] + 9998 TEC_NPol - Number of poles [even integer > 0] (-) [used only when VSContrl=0 and GenModel=2] + 9999.9 TEC_SRes - Stator resistance (ohms) [used only when VSContrl=0 and GenModel=2] + 9999.9 TEC_RRes - Rotor resistance (ohms) [used only when VSContrl=0 and GenModel=2] + 9999.9 TEC_VLL - Line-to-line RMS voltage (volts) [used only when VSContrl=0 and GenModel=2] + 9999.9 TEC_SLR - Stator leakage reactance (ohms) [used only when VSContrl=0 and GenModel=2] + 9999.9 TEC_RLR - Rotor leakage reactance (ohms) [used only when VSContrl=0 and GenModel=2] + 9999.9 TEC_MR - Magnetizing reactance (ohms) [used only when VSContrl=0 and GenModel=2] +---------------------- HIGH-SPEED SHAFT BRAKE ---------------------------------- + 0 HSSBrMode - HSS brake model {0: none, 1: simple, 3: user-defined from routine UserHSSBr, 4: user-defined from Simulink/Labview, 5: user-defined from Bladed-style DLL} (switch) + 9999.9 THSSBrDp - Time to initiate deployment of the HSS brake (s) + 0.6 HSSBrDT - Time for HSS-brake to reach full deployment once initiated (sec) [used only when HSSBrMode=1] + 28116.2 HSSBrTqF - Fully deployed HSS-brake torque (N-m) +---------------------- NACELLE-YAW CONTROL ------------------------------------- + 0 YCMode - Yaw control mode {0: none, 3: user-defined from routine UserYawCont, 4: user-defined from Simulink/Labview, 5: user-defined from Bladed-style DLL} (switch) + 9999.9 TYCOn - Time to enable active yaw control (s) [unused when YCMode=0] + 0 YawNeut - Neutral yaw position--yaw spring force is zero at this yaw (degrees) +9.02832E+09 YawSpr - Nacelle-yaw spring constant (N-m/rad) + 1.916E+07 YawDamp - Nacelle-yaw damping constant (N-m/(rad/s)) + 9999.9 TYawManS - Time to start override yaw maneuver and end standard yaw control (s) + 2 YawManRat - Yaw maneuver rate (in absolute value) (deg/s) + 0 NacYawF - Final yaw angle for override yaw maneuvers (degrees) +---------------------- AERODYNAMIC FLOW CONTROL -------------------------------- + 0 AfCmode - Airfoil control mode {0: none, 1: cosine wave cycle, 4: user-defined from Simulink/Labview, 5: user-defined from Bladed-style DLL} (switch) + 0 AfC_Mean - Mean level for cosine cycling or steady value (-) [used only with AfCmode==1] + 0 AfC_Amp - Amplitude for for cosine cycling of flap signal (-) [used only with AfCmode==1] + 0 AfC_Phase - Phase relative to the blade azimuth (0 is vertical) for for cosine cycling of flap signal (deg) [used only with AfCmode==1] +---------------------- STRUCTURAL CONTROL -------------------------------------- +0 NumBStC - Number of blade structural controllers (integer) +"unused" BStCfiles - Name of the files for blade structural controllers (quoted strings) [unused when NumBStC==0] +0 NumNStC - Number of nacelle structural controllers (integer) +"unused" NStCfiles - Name of the files for nacelle structural controllers (quoted strings) [unused when NumNStC==0] +0 NumTStC - Number of tower structural controllers (integer) +"unused" TStCfiles - Name of the files for tower structural controllers (quoted strings) [unused when NumTStC==0] +0 NumSStC - Number of substructure structural controllers (integer) +"unused" SStCfiles - Name of the files for substructure structural controllers (quoted strings) [unused when NumSStC==0] +---------------------- CABLE CONTROL ------------------------------------------- + 0 CCmode - Cable control mode {0: none, 4: user-defined from Simulink/Labview, 5: user-defined from Bladed-style DLL} (switch) +---------------------- BLADED INTERFACE ---------------------------------------- [used only with Bladed Interface] +"../../ROSCO/install/lib/libdiscon.so" DLL_FileName - Name/location of the dynamic library {.dll [Windows] or .so [Linux]} in the Bladed-DLL format (-) [used only with Bladed Interface] +"MHK_RM1_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] +false DLL_Ramp - Whether a linear ramp should be used between DLL_DT time steps [introduces time shift when true] (flag) [used only with Bladed Interface] + 9999.9 BPCutoff - Cutoff frequency for low-pass filter on blade pitch from DLL (Hz) [used only with Bladed Interface] + 0 NacYaw_North - Reference yaw angle of the nacelle when the upwind end points due North (deg) [used only with Bladed Interface] + 1 Ptch_Cntrl - Record 28: Use individual pitch control {0: collective pitch; 1: individual pitch control} (switch) [used only with Bladed Interface] + 0 Ptch_SetPnt - Record 5: Below-rated pitch angle set-point (deg) [used only with Bladed Interface] + 0 Ptch_Min - Record 6: Minimum pitch angle (deg) [used only with Bladed Interface] + 0 Ptch_Max - Record 7: Maximum pitch angle (deg) [used only with Bladed Interface] + 0 PtchRate_Min - Record 8: Minimum pitch rate (most negative value allowed) (deg/s) [used only with Bladed Interface] + 0 PtchRate_Max - Record 9: Maximum pitch rate (deg/s) [used only with Bladed Interface] + 0 Gain_OM - Record 16: Optimal mode gain (Nm/(rad/s)^2) [used only with Bladed Interface] + 0 GenSpd_MinOM - Record 17: Minimum generator speed (rpm) [used only with Bladed Interface] + 0 GenSpd_MaxOM - Record 18: Optimal mode maximum speed (rpm) [used only with Bladed Interface] + 0 GenSpd_Dem - Record 19: Demanded generator speed above rated (rpm) [used only with Bladed Interface] + 0 GenTrq_Dem - Record 22: Demanded generator torque above rated (Nm) [used only with Bladed Interface] + 0 GenPwr_Dem - Record 13: Demanded power (W) [used only with Bladed Interface] +---------------------- BLADED INTERFACE TORQUE-SPEED LOOK-UP TABLE ------------- + 0 DLL_NumTrq - Record 26: No. of points in torque-speed look-up table {0 = none and use the optimal mode parameters; nonzero = ignore the optimal mode PARAMETERs by setting Record 16 to 0.0} (-) [used only with Bladed Interface] + GenSpd_TLU GenTrq_TLU + (rpm) (Nm) +---------------------- OUTPUT -------------------------------------------------- +True SumPrint - Print summary data to .sum (flag) (currently unused) + 1 OutFile - Switch to determine where output will be placed: {1: in module output file only; 2: in glue code output file only; 3: both} (currently unused) +True TabDelim - Use tab delimiters in text tabular output file? (flag) (currently unused) +"ES10.3E2" OutFmt - Format used for text tabular output (except time). Resulting field should be 10 characters. (quoted string) (currently unused) + 0 TStart - Time to begin tabular output (s) (currently unused) + OutList - The next line(s) contains a list of output parameters. See OutListParameters.xlsx for a listing of available output channels, (-) +"GenPwr" - Electrical generator power and torque +"GenTq" - Electrical generator power and torque +"GenSpeed" +END of input file (the word "END" must appear in the first 3 columns of this last OutList line) +--------------------------------------------------------------------------------------- diff --git a/Test_Cases/NREL-5MW/DISCON.IN b/Test_Cases/NREL-5MW/DISCON.IN index 96930d27..e0f8d251 100644 --- a/Test_Cases/NREL-5MW/DISCON.IN +++ b/Test_Cases/NREL-5MW/DISCON.IN @@ -1,45 +1,51 @@ ! Controller parameter input file for the NREL-5MW wind turbine -! - File written using ROSCO version 2.8.0 controller tuning logic on 08/03/23 +! - File written using ROSCO version 2.8.0 controller tuning logic on 08/23/23 !------- SIMULATION CONTROL ------------------------------------------------------------ 1 ! LoggingLevel - {0: write no debug files, 1: write standard output .dbg-file, 2: LoggingLevel 1 + ROSCO LocalVars (.dbg2) 3: LoggingLevel 2 + complete avrSWAP-array (.dbg3)} -0 ! DT_Out - {Time step to output .dbg* files, or 0 to match sampling period of OpenFAST} +0 ! DT_Out - {Time step to output .dbg* files, or 0 to match sampling period of OpenFAST} 0 ! Echo - (0 - no Echo, 1 - Echo input data to .echo) !------- 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 and/or tower fore-aft motion (for floating) {0: disable, 1: generator speed, 2: tower-top fore-aft motion, 3: generator speed and tower-top fore-aft motion} +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 ! IPC_ControlMode - Turn Individual Pitch Control (IPC) for fatigue load reductions (pitch contribution) {0: off, 1: 1P reductions, 2: 1P+2P reductions} -3 ! VS_ControlMode - Generator torque control mode in above rated conditions {0: constant torque, 1: constant power, 2: TSR tracking PI control with constant torque, 3: TSR tracking PI control with constant power} -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: Immersion and Invariance Estimator, 2: Extended Kalman Filter} -1 ! PS_Mode - Pitch saturation mode {0: no pitch saturation, 1: implement pitch saturation} -0 ! SD_Mode - Shutdown mode {0: no shutdown procedure, 1: pitch to max pitch at shutdown} -0 ! Fl_Mode - Floating specific feedback mode {0: no nacelle velocity feedback, 1: feed back translational velocity, 2: feed back rotational veloicty} -0 ! TD_Mode - Tower damper mode {0: no tower damper, 1: feed back translational nacelle accelleration to pitch angle} -0 ! Flp_Mode - Flap control mode {0: no flap control, 1: steady state flap angle, 2: Proportional flap control, 2: Cyclic (1P) flap control} -0 ! OL_Mode - Open loop control mode {0: no open loop control, 1: open loop control vs. time, 2: rotor position control} -0 ! PA_Mode - Pitch actuator mode {0 - not used, 1 - first order filter, 2 - second order filter} -0 ! PF_Mode - Pitch fault mode {0 - not used, 1 - constant offset on one or more blades} -0 ! AWC_Mode - Active wake control {0 - not used, 1 - complex number method, 2 - Coleman transform method} -0 ! Ext_Mode - External control mode {0 - not used, 1 - call external dynamic library} -0 ! ZMQ_Mode - Fuse ZeroMQ interface {0: unused, 1: Yaw Control} -0 ! CC_Mode - Cable control mode [0- unused, 1- User defined, 2- Open loop control] -0 ! StC_Mode - Structural control mode [0- unused, 1- User defined, 2- Open loop control] +3 ! VS_ControlMode - Generator torque control mode in above rated conditions (0- no torque control, 1- k*omega^2 with PI transitions, 2- WSE TSR Tracking, 3- Power-based TSR Tracking)} +0 ! VS_ConstPower - Do constant power torque control, where above rated torque varies, 0 for constant torque} +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: Immersion and Invariance Estimator, 2: Extended Kalman Filter} +1 ! PS_Mode - Pitch saturation mode {0: no pitch saturation, 1: implement pitch saturation} +0 ! SD_Mode - Shutdown mode {0: no shutdown procedure, 1: pitch to max pitch at shutdown} +0 ! Fl_Mode - Floating specific feedback mode {0: no nacelle velocity feedback, 1: feed back translational velocity, 2: feed back rotational veloicty} +0 ! TD_Mode - Tower damper mode {0: no tower damper, 1: feed back translational nacelle accelleration to pitch angle} +0 ! Flp_Mode - Flap control mode {0: no flap control, 1: steady state flap angle, 2: Proportional flap control, 2: Cyclic (1P) flap control} +0 ! OL_Mode - Open loop control mode {0: no open loop control, 1: open loop control vs. time, 2: rotor position control} +0 ! PA_Mode - Pitch actuator mode {0 - not used, 1 - first order filter, 2 - second order filter} +0 ! PF_Mode - Pitch fault mode {0 - not used, 1 - constant offset on one or more blades} +0 ! AWC_Mode - Active wake control {0 - not used, 1 - complex number method, 2 - Coleman transform method} +0 ! Ext_Mode - External control mode {0 - not used, 1 - call external dynamic library} +0 ! ZMQ_Mode - Fuse ZeroMQ interface {0: unused, 1: Yaw Control} +0 ! CC_Mode - Cable control mode [0- unused, 1- User defined, 2- Open loop control] +0 ! StC_Mode - Structural control mode [0- unused, 1- User defined, 2- Open loop control] !------- FILTERS ---------------------------------------------------------- -1.57080 ! F_LPFCornerFreq - Corner frequency (-3dB point) in the low-pass filters, [rad/s] -0.00000 ! F_LPFDamping - Damping coefficient {used only when F_FilterType = 2} [-] -0.00000 ! F_NotchCornerFreq - Natural frequency of the notch filter, [rad/s] -0.000000 0.250000 ! F_NotchBetaNumDen - Two notch damping values (numerator and denominator, resp) - determines the width and depth of the notch, [-] +1.57080 ! F_LPFCornerFreq - Corner frequency (-3dB point) in the low-pass filters, [rad/s] +0.00000 ! F_LPFDamping - Damping coefficient {used only when F_FilterType = 2} [-] +0 ! F_NumNotchFilts - Number of notch filters placed on sensors +0.0000 ! F_NotchFreqs - Natural frequency of the notch filters. Array with length F_NumNotchFilts +0.0000 ! F_NotchBetaNum - Damping value of numerator (determines the width of notch). Array with length F_NumNotchFilts, [-] +0.0000 ! F_NotchBetaDen - Damping value of denominator (determines the depth of notch). Array with length F_NumNotchFilts, [-] +0 ! F_GenSpdNotch_N - Number of notch filters on generator speed +0 ! F_GenSpdNotch_Ind - Indices of notch filters on generator speed +0 ! F_TwrTopNotch_N - Number of notch filters on tower top acceleration signal +0 ! F_TwrTopNotch_Ind - Indices of notch filters on tower top acceleration signal 0.62830 ! F_SSCornerFreq - Corner frequency (-3dB point) in the first order low pass filter for the setpoint smoother, [rad/s]. 0.20944 ! F_WECornerFreq - Corner frequency (-3dB point) in the first order low pass filter for the wind speed estimate [rad/s]. 0.17952 ! F_YawErr - Low pass filter corner frequency for yaw controller [rad/s]. 0.000000 1.000000 ! F_FlCornerFreq - Natural frequency and damping in the second order low pass filter of the tower-top fore-aft motion for floating feedback control [rad/s, -]. -0.01042 ! F_FlHighPassFreq - Natural frequency of first-order high-pass filter for nacelle fore-aft motion [rad/s]. -0.000000 1.000000 ! F_FlpCornerFreq - Corner frequency and damping in the second order low pass filter of the blade root bending moment for flap control [rad/s, -]. +0.01042 ! F_FlHighPassFreq - Natural frequency of first-order high-pass filter for nacelle fore-aft motion [rad/s]. +0.0000 1.0000 ! F_FlpCornerFreq - Corner frequency and damping in the second order low pass filter of the blade root bending moment for flap control !------- BLADE PITCH CONTROL ---------------------------------------------- 30 ! PC_GS_n - Amount of gain-scheduling table entries @@ -72,14 +78,15 @@ 47402.87063000 ! VS_MaxTq - Maximum generator torque in Region 3 (HSS side), [Nm]. 0.000000000000 ! VS_MinTq - Minimum generator torque (HSS side), [Nm]. 35.29006000000 ! VS_MinOMSpd - Minimum generator speed [rad/s] -2.185750000000 ! VS_Rgn2K - Generator torque constant in Region 2 (HSS side), [Nm/(rad/s)^2] +2.063350000000 ! VS_Rgn2K - Generator torque constant in Region 2 (HSS side). Only used in VS_ControlMode = 1,3 5000000.000000 ! VS_RtPwr - Wind turbine rated power [W] 43093.51876000 ! VS_RtTq - Rated torque, [Nm]. 122.9096700000 ! VS_RefSpd - Rated generator speed [rad/s] 1 ! VS_n - Number of generator PI torque controller gains -657.442080000 ! VS_KP - Proportional gain for generator PI torque controller [-]. (Only used in the transitional 2.5 region if VS_ControlMode =/ 2) -104.507080000 ! VS_KI - Integral gain for generator PI torque controller [s]. (Only used in the transitional 2.5 region if VS_ControlMode =/ 2) -7.64 ! VS_TSRopt - Power-maximizing region 2 tip-speed-ratio [rad]. +7.64 ! VS_TSRopt - Power-maximizing region 2 tip-speed-ratio. Only used in VS_ControlMode = 2. +0.314000000000 ! VS_PwrFiltF - Low pass filter on power used to determine generator speed set point. Only used in VS_ControlMode = 3. !------- SETPOINT SMOOTHER --------------------------------------------- 1.00000 ! SS_VSGain - Variable speed torque controller setpoint smoother gain, [-]. @@ -89,9 +96,9 @@ 63.000 ! WE_BladeRadius - Blade length (distance from hub center to blade tip), [m] 1 ! WE_CP_n - Amount of parameters in the Cp array 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] +0.0 ! WE_Gamma - Adaption gain of the wind speed estimator algorithm [m/rad] 97.0 ! WE_GearboxRatio - Gearbox ratio [>=1], [-] -43702538.05700 ! WE_Jtot - Total drivetrain inertia, including blades, hub and casted generator inertia to LSS, [kg m^2] +43702538.05700 ! 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.NREL5MW.txt" ! PerfFileName - File containing rotor performance tables (Cp,Ct,Cq) (absolute path or relative to this file) 36 26 ! PerfTableSize - Size of rotor performance tables, first number refers to number of blade pitch angles, second number referse to number of tip-speed ratios @@ -123,9 +130,9 @@ 0.418880000000 ! SD_CornerFreq - Cutoff Frequency for first order low-pass filter for blade pitch angle, [rad/s] !------- Floating ----------------------------------------------------------- -1 ! Fl_n - Number of Fl_Kp gains in gain scheduling, optional with default of 1 -0.0000 ! Fl_Kp - Nacelle velocity proportional feedback gain [s] -0.0000 ! Fl_U - Wind speeds for scheduling Fl_Kp, optional if Fl_Kp is single value [m/s] +1 ! Fl_n - Number of Fl_Kp gains in gain scheduling, optional with default of 1 +0.0000 ! Fl_Kp - Nacelle velocity proportional feedback gain [s] +0.0000 ! Fl_U - Wind speeds for scheduling Fl_Kp, optional if Fl_Kp is single value [m/s] !------- FLAP ACTUATION ----------------------------------------------------- 0.000000000000 ! Flp_Angle - Initial or steady state flap angle [rad] @@ -145,19 +152,19 @@ 0 ! Ind_StructControl - The column(s) in OL_Filename that contains the structural control inputs [Used with StC_Mode = 2, must be the same size as StC_Group_N] !------- Pitch Actuator Model ----------------------------------------------------- -3.140000000000 ! PA_CornerFreq - Pitch actuator bandwidth/cut-off frequency [rad/s] -0.707000000000 ! PA_Damping - Pitch actuator damping ratio [-, unused if PA_Mode = 1] +3.140000000000 ! PA_CornerFreq - Pitch actuator bandwidth/cut-off frequency [rad/s] +0.707000000000 ! PA_Damping - Pitch actuator damping ratio [-, unused if PA_Mode = 1] !------- Pitch Actuator Faults ----------------------------------------------------- 0.00000000 0.00000000 0.00000000 ! PF_Offsets - Constant blade pitch offsets for blades 1-3 [rad] !------- Active Wake Control ----------------------------------------------------- -1 ! AWC_NumModes - Number of user-defined AWC forcing modes -1 ! AWC_n - Azimuthal mode number(s) (i.e., the number and direction of the lobes of the wake structure) -1 ! AWC_harmonic - Harmonic(s) to apply in the AWC Inverse Coleman Transformation (only used when AWC_Mode = 2) -0.0500 ! AWC_freq - Frequency(s) of forcing mode(s) [Hz] -1.0000 ! AWC_amp - Pitch amplitude(s) of individual forcing mode(s) [deg] -0.0000 ! AWC_clockangle - Initial angle(s) of forcing mode(s) [deg] +1 ! AWC_NumModes - Number of user-defined AWC forcing modes +1 ! AWC_n - Azimuthal mode number(s) (i.e., the number and direction of the lobes of the wake structure) +1 ! AWC_harmonic - Harmonic(s) to apply in the AWC Inverse Coleman Transformation (only used when AWC_Mode = 2) +0.0500 ! AWC_freq - Frequency(s) of forcing mode(s) [Hz] +1.0000 ! AWC_amp - Pitch amplitude(s) of individual forcing mode(s) [deg] +0.0000 ! AWC_clockangle - Initial angle(s) of forcing mode(s) [deg] !------- External Controller Interface ----------------------------------------------------- "unused" ! DLL_FileName - Name/location of the dynamic library in the Bladed-DLL format @@ -170,9 +177,9 @@ !------- Cable Control --------------------------------------------------------- 1 ! CC_Group_N - Number of cable control groups - 0 ! CC_GroupIndex - First index for cable control group, should correspond to deltaL +0 ! CC_GroupIndex - First index for cable control group, should correspond to deltaL 20.000000 ! CC_ActTau - Time constant for line actuator [s] !------- Structural Controllers --------------------------------------------------------- 1 ! StC_Group_N - Number of cable control groups - 0 ! StC_GroupIndex - First index for structural control group, options specified in ServoDyn summary output +0 ! StC_GroupIndex - First index for structural control group, options specified in ServoDyn summary output diff --git a/Test_Cases/NREL_2p8_127/NREL-2p8-127_DISCON.IN b/Test_Cases/NREL_2p8_127/NREL-2p8-127_DISCON.IN index f327e491..a0531ce6 100644 --- a/Test_Cases/NREL_2p8_127/NREL-2p8-127_DISCON.IN +++ b/Test_Cases/NREL_2p8_127/NREL-2p8-127_DISCON.IN @@ -1,45 +1,51 @@ ! Controller parameter input file for the NREL-2p8-127 wind turbine -! - File written using ROSCO version 2.8.0 controller tuning logic on 08/03/23 +! - File written using ROSCO version 2.8.0 controller tuning logic on 08/23/23 !------- SIMULATION CONTROL ------------------------------------------------------------ 2 ! LoggingLevel - {0: write no debug files, 1: write standard output .dbg-file, 2: LoggingLevel 1 + ROSCO LocalVars (.dbg2) 3: LoggingLevel 2 + complete avrSWAP-array (.dbg3)} -0 ! DT_Out - {Time step to output .dbg* files, or 0 to match sampling period of OpenFAST} +0 ! DT_Out - {Time step to output .dbg* files, or 0 to match sampling period of OpenFAST} 0 ! Echo - (0 - no Echo, 1 - Echo input data to .echo) !------- 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 and/or tower fore-aft motion (for floating) {0: disable, 1: generator speed, 2: tower-top fore-aft motion, 3: generator speed and tower-top fore-aft motion} +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 1 ! IPC_ControlMode - Turn Individual Pitch Control (IPC) for fatigue load reductions (pitch contribution) {0: off, 1: 1P reductions, 2: 1P+2P reductions} -3 ! VS_ControlMode - Generator torque control mode in above rated conditions {0: constant torque, 1: constant power, 2: TSR tracking PI control with constant torque, 3: TSR tracking PI control with constant power} -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: Immersion and Invariance Estimator, 2: Extended Kalman Filter} -1 ! PS_Mode - Pitch saturation mode {0: no pitch saturation, 1: implement pitch saturation} -0 ! SD_Mode - Shutdown mode {0: no shutdown procedure, 1: pitch to max pitch at shutdown} -0 ! Fl_Mode - Floating specific feedback mode {0: no nacelle velocity feedback, 1: feed back translational velocity, 2: feed back rotational veloicty} -0 ! TD_Mode - Tower damper mode {0: no tower damper, 1: feed back translational nacelle accelleration to pitch angle} -0 ! Flp_Mode - Flap control mode {0: no flap control, 1: steady state flap angle, 2: Proportional flap control, 2: Cyclic (1P) flap control} -0 ! OL_Mode - Open loop control mode {0: no open loop control, 1: open loop control vs. time, 2: rotor position control} -0 ! PA_Mode - Pitch actuator mode {0 - not used, 1 - first order filter, 2 - second order filter} -0 ! PF_Mode - Pitch fault mode {0 - not used, 1 - constant offset on one or more blades} -0 ! AWC_Mode - Active wake control {0 - not used, 1 - complex number method, 2 - Coleman transform method} -0 ! Ext_Mode - External control mode {0 - not used, 1 - call external dynamic library} -0 ! ZMQ_Mode - Fuse ZeroMQ interface {0: unused, 1: Yaw Control} -0 ! CC_Mode - Cable control mode [0- unused, 1- User defined, 2- Open loop control] -0 ! StC_Mode - Structural control mode [0- unused, 1- User defined, 2- Open loop control] +3 ! VS_ControlMode - Generator torque control mode in above rated conditions (0- no torque control, 1- k*omega^2 with PI transitions, 2- WSE TSR Tracking, 3- Power-based TSR Tracking)} +0 ! VS_ConstPower - Do constant power torque control, where above rated torque varies, 0 for constant torque} +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: Immersion and Invariance Estimator, 2: Extended Kalman Filter} +1 ! PS_Mode - Pitch saturation mode {0: no pitch saturation, 1: implement pitch saturation} +0 ! SD_Mode - Shutdown mode {0: no shutdown procedure, 1: pitch to max pitch at shutdown} +0 ! Fl_Mode - Floating specific feedback mode {0: no nacelle velocity feedback, 1: feed back translational velocity, 2: feed back rotational veloicty} +0 ! TD_Mode - Tower damper mode {0: no tower damper, 1: feed back translational nacelle accelleration to pitch angle} +0 ! Flp_Mode - Flap control mode {0: no flap control, 1: steady state flap angle, 2: Proportional flap control, 2: Cyclic (1P) flap control} +0 ! OL_Mode - Open loop control mode {0: no open loop control, 1: open loop control vs. time, 2: rotor position control} +0 ! PA_Mode - Pitch actuator mode {0 - not used, 1 - first order filter, 2 - second order filter} +0 ! PF_Mode - Pitch fault mode {0 - not used, 1 - constant offset on one or more blades} +0 ! AWC_Mode - Active wake control {0 - not used, 1 - complex number method, 2 - Coleman transform method} +0 ! Ext_Mode - External control mode {0 - not used, 1 - call external dynamic library} +0 ! ZMQ_Mode - Fuse ZeroMQ interface {0: unused, 1: Yaw Control} +0 ! CC_Mode - Cable control mode [0- unused, 1- User defined, 2- Open loop control] +0 ! StC_Mode - Structural control mode [0- unused, 1- User defined, 2- Open loop control] !------- FILTERS ---------------------------------------------------------- -2.07080 ! F_LPFCornerFreq - Corner frequency (-3dB point) in the low-pass filters, [rad/s] -0.00000 ! F_LPFDamping - Damping coefficient {used only when F_FilterType = 2} [-] -0.00000 ! F_NotchCornerFreq - Natural frequency of the notch filter, [rad/s] -0.000000 0.250000 ! F_NotchBetaNumDen - Two notch damping values (numerator and denominator, resp) - determines the width and depth of the notch, [-] +2.07080 ! F_LPFCornerFreq - Corner frequency (-3dB point) in the low-pass filters, [rad/s] +0.00000 ! F_LPFDamping - Damping coefficient {used only when F_FilterType = 2} [-] +0 ! F_NumNotchFilts - Number of notch filters placed on sensors +0.0000 ! F_NotchFreqs - Natural frequency of the notch filters. Array with length F_NumNotchFilts +0.0000 ! F_NotchBetaNum - Damping value of numerator (determines the width of notch). Array with length F_NumNotchFilts, [-] +0.0000 ! F_NotchBetaDen - Damping value of denominator (determines the depth of notch). Array with length F_NumNotchFilts, [-] +0 ! F_GenSpdNotch_N - Number of notch filters on generator speed +0 ! F_GenSpdNotch_Ind - Indices of notch filters on generator speed +0 ! F_TwrTopNotch_N - Number of notch filters on tower top acceleration signal +0 ! F_TwrTopNotch_Ind - Indices of notch filters on tower top acceleration signal 0.62830 ! F_SSCornerFreq - Corner frequency (-3dB point) in the first order low pass filter for the setpoint smoother, [rad/s]. 0.20944 ! F_WECornerFreq - Corner frequency (-3dB point) in the first order low pass filter for the wind speed estimate [rad/s]. 0.17952 ! F_YawErr - Low pass filter corner frequency for yaw controller [rad/s]. 0.000000 1.000000 ! F_FlCornerFreq - Natural frequency and damping in the second order low pass filter of the tower-top fore-aft motion for floating feedback control [rad/s, -]. -0.01042 ! F_FlHighPassFreq - Natural frequency of first-order high-pass filter for nacelle fore-aft motion [rad/s]. -0.000000 1.000000 ! F_FlpCornerFreq - Corner frequency and damping in the second order low pass filter of the blade root bending moment for flap control [rad/s, -]. +0.01042 ! F_FlHighPassFreq - Natural frequency of first-order high-pass filter for nacelle fore-aft motion [rad/s]. +0.0000 1.0000 ! F_FlpCornerFreq - Corner frequency and damping in the second order low pass filter of the blade root bending moment for flap control !------- BLADE PITCH CONTROL ---------------------------------------------- 30 ! PC_GS_n - Amount of gain-scheduling table entries @@ -72,14 +78,15 @@ 26673.40024000 ! VS_MaxTq - Maximum generator torque in Region 3 (HSS side), [Nm]. 0.000000000000 ! VS_MinTq - Minimum generator torque (HSS side), [Nm]. 37.81562000000 ! VS_MinOMSpd - Minimum generator speed [rad/s] -1.931170000000 ! VS_Rgn2K - Generator torque constant in Region 2 (HSS side), [Nm/(rad/s)^2] +1.654680000000 ! VS_Rgn2K - Generator torque constant in Region 2 (HSS side). Only used in VS_ControlMode = 1,3 2800000.000000 ! VS_RtPwr - Wind turbine rated power [W] 24248.54567000 ! VS_RtTq - Rated torque, [Nm]. 122.9096700000 ! VS_RefSpd - Rated generator speed [rad/s] 1 ! VS_n - Number of generator PI torque controller gains -600.450450000 ! VS_KP - Proportional gain for generator PI torque controller [-]. (Only used in the transitional 2.5 region if VS_ControlMode =/ 2) -85.3230300000 ! VS_KI - Integral gain for generator PI torque controller [s]. (Only used in the transitional 2.5 region if VS_ControlMode =/ 2) -8.25 ! VS_TSRopt - Power-maximizing region 2 tip-speed-ratio [rad]. +8.25 ! VS_TSRopt - Power-maximizing region 2 tip-speed-ratio. Only used in VS_ControlMode = 2. +0.314000000000 ! VS_PwrFiltF - Low pass filter on power used to determine generator speed set point. Only used in VS_ControlMode = 3. !------- SETPOINT SMOOTHER --------------------------------------------- 1.00000 ! SS_VSGain - Variable speed torque controller setpoint smoother gain, [-]. @@ -89,9 +96,9 @@ 63.457 ! WE_BladeRadius - Blade length (distance from hub center to blade tip), [m] 1 ! WE_CP_n - Amount of parameters in the Cp array 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] +0.0 ! WE_Gamma - Adaption gain of the wind speed estimator algorithm [m/rad] 97.0 ! WE_GearboxRatio - Gearbox ratio [>=1], [-] -66347470.49793 ! WE_Jtot - Total drivetrain inertia, including blades, hub and casted generator inertia to LSS, [kg m^2] +66347470.49793 ! 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] "NREL-2p8-127_Cp_Ct_Cq.txt" ! PerfFileName - File containing rotor performance tables (Cp,Ct,Cq) (absolute path or relative to this file) 30 30 ! PerfTableSize - Size of rotor performance tables, first number refers to number of blade pitch angles, second number referse to number of tip-speed ratios @@ -123,9 +130,9 @@ 0.418880000000 ! SD_CornerFreq - Cutoff Frequency for first order low-pass filter for blade pitch angle, [rad/s] !------- Floating ----------------------------------------------------------- -1 ! Fl_n - Number of Fl_Kp gains in gain scheduling, optional with default of 1 -0.0000 ! Fl_Kp - Nacelle velocity proportional feedback gain [s] -0.0000 ! Fl_U - Wind speeds for scheduling Fl_Kp, optional if Fl_Kp is single value [m/s] +1 ! Fl_n - Number of Fl_Kp gains in gain scheduling, optional with default of 1 +0.0000 ! Fl_Kp - Nacelle velocity proportional feedback gain [s] +0.0000 ! Fl_U - Wind speeds for scheduling Fl_Kp, optional if Fl_Kp is single value [m/s] !------- FLAP ACTUATION ----------------------------------------------------- 0.000000000000 ! Flp_Angle - Initial or steady state flap angle [rad] @@ -145,19 +152,19 @@ 0 ! Ind_StructControl - The column(s) in OL_Filename that contains the structural control inputs [Used with StC_Mode = 2, must be the same size as StC_Group_N] !------- Pitch Actuator Model ----------------------------------------------------- -3.140000000000 ! PA_CornerFreq - Pitch actuator bandwidth/cut-off frequency [rad/s] -0.707000000000 ! PA_Damping - Pitch actuator damping ratio [-, unused if PA_Mode = 1] +3.140000000000 ! PA_CornerFreq - Pitch actuator bandwidth/cut-off frequency [rad/s] +0.707000000000 ! PA_Damping - Pitch actuator damping ratio [-, unused if PA_Mode = 1] !------- Pitch Actuator Faults ----------------------------------------------------- 0.00000000 0.00000000 0.00000000 ! PF_Offsets - Constant blade pitch offsets for blades 1-3 [rad] !------- Active Wake Control ----------------------------------------------------- -1 ! AWC_NumModes - Number of user-defined AWC forcing modes -1 ! AWC_n - Azimuthal mode number(s) (i.e., the number and direction of the lobes of the wake structure) -1 ! AWC_harmonic - Harmonic(s) to apply in the AWC Inverse Coleman Transformation (only used when AWC_Mode = 2) -0.0500 ! AWC_freq - Frequency(s) of forcing mode(s) [Hz] -1.0000 ! AWC_amp - Pitch amplitude(s) of individual forcing mode(s) [deg] -0.0000 ! AWC_clockangle - Initial angle(s) of forcing mode(s) [deg] +1 ! AWC_NumModes - Number of user-defined AWC forcing modes +1 ! AWC_n - Azimuthal mode number(s) (i.e., the number and direction of the lobes of the wake structure) +1 ! AWC_harmonic - Harmonic(s) to apply in the AWC Inverse Coleman Transformation (only used when AWC_Mode = 2) +0.0500 ! AWC_freq - Frequency(s) of forcing mode(s) [Hz] +1.0000 ! AWC_amp - Pitch amplitude(s) of individual forcing mode(s) [deg] +0.0000 ! AWC_clockangle - Initial angle(s) of forcing mode(s) [deg] !------- External Controller Interface ----------------------------------------------------- "unused" ! DLL_FileName - Name/location of the dynamic library in the Bladed-DLL format @@ -170,9 +177,9 @@ !------- Cable Control --------------------------------------------------------- 1 ! CC_Group_N - Number of cable control groups - 0 ! CC_GroupIndex - First index for cable control group, should correspond to deltaL +0 ! CC_GroupIndex - First index for cable control group, should correspond to deltaL 20.000000 ! CC_ActTau - Time constant for line actuator [s] !------- Structural Controllers --------------------------------------------------------- 1 ! StC_Group_N - Number of cable control groups - 0 ! StC_GroupIndex - First index for structural control group, options specified in ServoDyn summary output +0 ! StC_GroupIndex - First index for structural control group, options specified in ServoDyn summary output diff --git a/Test_Cases/update_rosco_discons.py b/Test_Cases/update_rosco_discons.py index 9a299991..b2a724fb 100644 --- a/Test_Cases/update_rosco_discons.py +++ b/Test_Cases/update_rosco_discons.py @@ -14,6 +14,7 @@ 'IEA15MW.yaml': 'IEA-15-240-RWT-UMaineSemi/DISCON-UMaineSemi.IN', 'BAR.yaml': 'BAR_10/BAR_10_DISCON.IN', 'NREL2p8.yaml': 'NREL_2p8_127/NREL-2p8-127_DISCON.IN', + 'RM1_MHK.yaml': 'MHK_RM1/MHK_RM1_DISCON.IN', } # Directories diff --git a/Tune_Cases/IEA15MW.yaml b/Tune_Cases/IEA15MW.yaml index b654cf9a..0bf65e99 100644 --- a/Tune_Cases/IEA15MW.yaml +++ b/Tune_Cases/IEA15MW.yaml @@ -53,4 +53,5 @@ controller_params: ps_percent: 0.8 # Percent peak shaving [%, <= 1 ], {default = 80%} PA_CornerFreq: 1.5708 # Pitch actuator natural frequency [rad/s] PA_Damping: 0.707 # Pitch actuator natural frequency [rad/s] + rgn2k_factor: 0.85926 diff --git a/Tune_Cases/RM1_MHK.yaml b/Tune_Cases/RM1_MHK.yaml new file mode 100644 index 00000000..12b294c2 --- /dev/null +++ b/Tune_Cases/RM1_MHK.yaml @@ -0,0 +1,68 @@ +--- # ---------------------NREL Generic controller tuning input file ------------------- + # Written for use with ROSCO_Toolbox tuning procedures + # Turbine: NREL 5MW Reference Wind Turbine +# ------------------------------ OpenFAST PATH DEFINITIONS ------------------------------ +path_params: + FAST_InputFile: 'MHK_RM1_Floating.fst' # Name of *.fst file + FAST_directory: '../Test_Cases/MHK_RM1' # Main OpenFAST model directory, where the *.fst lives + # Optional + rotor_performance_filename: '../Test_Cases/MHK_RM1/MHK_RM1_Cp_Ct_Cq.txt' # Filename for rotor performance text file (if it has been generated by ccblade already) + +# -------------------------------- TURBINE PARAMETERS ----------------------------------- +turbine_params: + rotor_inertia: 92169 # Rotor inertia [kg m^2], {Available in Elastodyn .sum file} + rated_rotor_speed: 1.204 # 11.5 rpm # Rated rotor speed [rad/s] + v_min: 0.5 # Cut-in wind speed [m/s] + v_rated: 2.0 # Rated wind speed [m/s] + v_max: 3.0 # Cut-out wind speed [m/s], -- Does not need to be exact (JUST ASSUME FOR NOW) + max_pitch_rate: 0.1745 # Maximum blade pitch rate [rad/s] + max_torque_rate: 1500000. # Maximum torque rate [Nm/s], {~1/4 VS_RtTq/s} + rated_power: 500000 # Rated Power [W] + bld_edgewise_freq: 60.2831853 # Blade edgewise first natural frequency [rad/s] + bld_flapwise_freq: 0.0 # Blade flapwise first natural frequency [rad/s] + reynolds_ref: 8e6 + # Optional + # TSR_operational: # None # Desired below-rated operational tip speed ratio (Cp-maximizing TSR is used if not defined) +#------------------------------- CONTROLLER PARAMETERS ---------------------------------- +controller_params: + # Controller flags + LoggingLevel: 2 # {0: write no debug files, 1: write standard output .dbg-file, 2: write standard output .dbg-file and complete avrSWAP-array .dbg2-file + F_LPFType: 1 # {1: first-order low-pass filter, 2: second-order low-pass filter}, [rad/s] (currently filters generator speed and pitch control signals) + F_NotchType: 1 # Notch filter on generator speed and/or tower fore-aft motion (for floating) {0: disable, 1: generator speed, 2: tower-top fore-aft motion, 3: generator speed and tower-top fore-aft motion} + IPC_ControlMode: 0 # Turn Individual Pitch Control (IPC) for fatigue load reductions (pitch contribution) {0: off, 1: 1P reductions, 2: 1P+2P reductions} + VS_ControlMode: 3 # Generator torque control mode in above rated conditions {0: constant torque, 1: constant power, 2: TSR tracking PI control} + VS_ConstPower: 1 # Generator torque control mode in above rated conditions {0: constant torque, 1: constant power, 2: TSR tracking PI control} + PC_ControlMode: 1 # Blade pitch control mode {0: No pitch, fix to fine pitch, 1: active PI blade pitch control} + Y_ControlMode: 0 # Yaw control mode {0: no yaw control, 1: yaw rate control, 2: yaw-by-IPC} + SS_Mode: 1 # Setpoint Smoother mode {0: no setpoint smoothing, 1: introduce setpoint smoothing} + WE_Mode: 0 # Wind speed estimator mode {0: One-second low pass filtered hub height wind speed, 1: Immersion and Invariance Estimator (Ortega et al.)} + PS_Mode: 0 # Pitch saturation mode {0: no pitch saturation, 1: peak shaving, 2: Cp-maximizing pitch saturation, 3: peak shaving and Cp-maximizing pitch saturation} + SD_Mode: 0 # Shutdown mode {0: no shutdown procedure, 1: pitch to max pitch at shutdown} + Fl_Mode: 1 # Floating specific feedback mode {0: no nacelle velocity feedback, 1: nacelle velocity feedback} + Flp_Mode: 0 # Flap control mode {0: no flap control, 1: steady state flap angle, 2: Proportional flap control} + # Controller parameters + U_pc: [2.3,2.5] + interp_type: sigma + zeta_pc: [0.7,0.7] # Pitch controller desired damping ratio [-] + omega_pc: [0.9,0.9] # Pitch controller desired natural frequency [rad/s] + zeta_vs: 0.7 # Torque controller desired damping ratio [-] + omega_vs: 0.7 # Torque controller desired natural frequency [rad/s] + twr_freq: 3.3404 # Tower natural frequency [rad/s] # 0.4499 (old value) 3.3404(new value) + # twr_freq: 0.061009 # 2P + ptfm_freq: 0.6613 # Platform natural frequency [rad/s] (OC4Hywind Parameters, here) 0.2325 (old value) 0.6613879263 (new value) + # Optional + ps_percent: 0.80 # Percent peak shaving [%, <= 1 ], {default = 80%} + sd_maxpit: 0.4363 # Maximum blade pitch angle to initiate shutdown [rad], {default = bld pitch at v_max} + Kp_float: -0.3897 + max_torque_factor: 1.5 + DISCON: + F_NumNotchFilts: 2 + F_NotchFreqs: [1.0, 2.4200] # 2P + F_NotchBetaNum: [0.0, 0.0] + F_NotchBetaDen: [0.25, 0.25] + F_GenSpdNotch_N: 2 + F_GenSpdNotch_Ind: [1,2] + F_TwrTopNotch_N: 2 + F_TwrTopNotch_Ind: [1,2] + F_NotchCornerFreq_GS: [2.42] + F_FlHighPassFreq: 1.5 diff --git a/docs/source/api_change.rst b/docs/source/api_change.rst index 86d88444..27377410 100644 --- a/docs/source/api_change.rst +++ b/docs/source/api_change.rst @@ -15,14 +15,22 @@ Gain scheduling of floating feedback - The floating feedback gain can be scheduled on the low pass filtered wind speed signal. Note that Fl_Kp can now be an array. - Control all three blade pitch inputs in open loop - Rotor position control of azimuth position with PID (RP_Gains) control inputs + +New torque control mode settings +- VS_ControlMode determines how the generator speed set point is determined: using the WSE or (P/K)^(1/3) +- VS_ConstPower determines whether constant power is used + +Multiple notch filters +- Users can list any number of notch filters and apply them to either the generator speed and/or tower top accelleration signal based on their index + ====== ================= ====================================================================================================================================================================================================== -Changed in ROSCO develop +Removed in ROSCO develop ---------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- Line Input Name Example Value ====== ================= ====================================================================================================================================================================================================== -126 OL_mode 0 ! OL_Mode - Open loop control mode {0: no open loop control, 1: open loop control vs. time, 2: rotor position control} -126 Fl_Kp 0.0000 ! Fl_Kp - Nacelle velocity proportional feedback gain [s] -139 Ind_BldPitch 0 0 0 ! Ind_BldPitch - The columns in OL_Filename that contains the blade pitch (1,2,3) inputs in rad [array] +11 F_NotchType 2 ! F_NotchType - Notch on the measured generator speed and/or tower fore-aft motion (for floating) {0: disable, 1: generator speed, 2: tower-top fore-aft motion, 3: generator speed and tower-top fore-aft motion} +35 F_NotchCornerFreq 3.35500 ! F_NotchCornerFreq - Natural frequency of the notch filter, [rad/s] +36 F_NotchBetaNumDen 0.000000 0.250000 ! F_NotchBetaNumDen - Two notch damping values (numerator and denominator, resp) - determines the width and depth of the notch, [-] ====== ================= ====================================================================================================================================================================================================== @@ -31,12 +39,31 @@ New in ROSCO develop ---------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- Line Input Name Example Value ====== ================= ====================================================================================================================================================================================================== -125 Fl_n 1 ! Fl_n - Number of Fl_Kp gains in gain scheduling, optional with default of 1 -127 Fl_U 0.0000 ! Fl_U - Wind speeds for scheduling Fl_Kp, optional if Fl_Kp is single value [m/s] -142 Ind_Azimuth 0 ! Ind_Azimuth - The column in OL_Filename that contains the desired azimuth position in rad (used if OL_Mode = 2) -143 RP_Gains 0.0000 0.0000 0.0000 0.0000 ! RP_Gains - PID gains and Tf of derivative for rotor position control (used if OL_Mode = 2) +13 VS_ConstPower 0 ! VS_ConstPower - Do constant power torque control, where above rated torque varies, 0 for constant torque} +35 F_NumNotchFilts 1 ! F_NumNotchFilts - Number of notch filters placed on sensors +36 F_NotchFreqs 3.3550 ! F_NotchFreqs - Natural frequency of the notch filters. Array with length F_NumNotchFilts +37 F_NotchBetaNum 0.0000 ! F_NotchBetaNum - Damping value of numerator (determines the width of notch). Array with length F_NumNotchFilts, [-] +38 F_NotchBetaDen 0.2500 ! F_NotchBetaDen - Damping value of denominator (determines the depth of notch). Array with length F_NumNotchFilts, [-] +39 F_GenSpdNotch_N 0 ! F_GenSpdNotch_N - Number of notch filters on generator speed +40 F_GenSpdNotch_Ind 0 ! F_GenSpdNotch_Ind - Indices of notch filters on generator speed +41 F_TwrTopNotch_N 1 ! F_TwrTopNotch_N - Number of notch filters on tower top acceleration signal +42 F_TwrTopNotch_Ind 1 ! F_TwrTopNotch_Ind - Indices of notch filters on tower top acceleration signal +89 VS_PwrFiltF 0.3140 ! VS_PwrFiltF - Low pass filter on power used to determine generator speed set point. Only used in VS_ControlMode = 3. +133 Fl_n 1 ! Fl_n - Number of Fl_Kp gains in gain scheduling, optional with default of 1 +135 Fl_U 0.0000 ! Fl_U - Wind speeds for scheduling Fl_Kp, optional if Fl_Kp is single value [m/s] +149 Ind_Azimuth 0 ! Ind_Azimuth - The column in OL_Filename that contains the desired azimuth position in rad (used if OL_Mode = 2) +150 RP_Gains 0.0000 0.0000 0.0000 0.0000 ! RP_Gains - PID gains and Tf of derivative for rotor position control (used if OL_Mode = 2) ====== ================= ====================================================================================================================================================================================================== +====== ================= ====================================================================================================================================================================================================== +Changed in ROSCO develop +---------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- +Line Input Name Example Value +====== ================= ====================================================================================================================================================================================================== +12 VS_ControlMode 2 ! VS_ControlMode - Generator torque control mode in above rated conditions (0- no torque control, 1- k*omega^2 with PI transitions, 2- WSE TSR Tracking, 3- Power-based TSR Tracking)}126 OL_mode 0 ! OL_Mode - Open loop control mode {0: no open loop control, 1: open loop control vs. time, 2: rotor position control} +134 Fl_Kp 0.0000 ! Fl_Kp - Nacelle velocity proportional feedback gain [s] +146 Ind_BldPitch 0 0 0 ! Ind_BldPitch - The columns in OL_Filename that contains the blade pitch (1,2,3) inputs in rad [array] +====== ================= ====================================================================================================================================================================================================== 2.7.0 to 2.8.0 diff --git a/docs/source/toolbox_input.rst b/docs/source/toolbox_input.rst index 94ae3683..fc25dc85 100644 --- a/docs/source/toolbox_input.rst +++ b/docs/source/toolbox_input.rst @@ -89,6 +89,14 @@ turbine_params *Minimum* = 0 +:code:`reynolds_ref` : Float + Reynolds number near rated speeds, used to interpolate airfoils, + if provided + + *Default* = 0 + + *Minimum* = 0 + controller_params @@ -136,15 +144,24 @@ controller_params :code:`VS_ControlMode` : Float - Generator torque control mode in above rated conditions (0- - constant torque, 1- constant power, 2- TSR tracking PI control - with constant torque, 3- TSR tracking with constant power) + Generator torque control mode in above rated conditions (0- no + torque control, 1- k*omega^2 with PI transitions, 2- WSE TSR + Tracking, 3- Power-based TSR Tracking) *Default* = 2 *Minimum* = 0 *Maximum* = 3 +:code:`VS_ConstPower` : Float + Do constant power torque control, where above rated torque varies, + 0 for constant torque + + *Default* = 0 + + *Minimum* = 0 *Maximum* = 1 + + :code:`PC_ControlMode` : Float Blade pitch control mode (0- No pitch, fix to fine pitch, 1- active PI blade pitch control) @@ -273,6 +290,7 @@ controller_params *Minimum* = 0 *Maximum* = 2 + :code:`AWC_Mode` : Float Active wake control mode {0 - not used, 1 - SNL method, 2 - NREL method} @@ -490,6 +508,15 @@ controller_params *Minimum* = 0.0 +:code:`rgn2k_factor` : Float + Factor on VS_Rgn2K to increase/decrease optimal torque control + gain, default is 1. Sometimes environmental conditions or + differences in BEM solvers necessitate this change. + + *Default* = 1 + + *Minimum* = 0 + filter_params @@ -596,6 +623,14 @@ open_loop *Default* = 0 +:code:`Ind_CableControl` : Array of Floats + The column in OL_Filename that contains the cable control inputs + in m + +:code:`Ind_StructControl` : Array of Floats + The column in OL_Filename that contains the structural control + inputs in various units + :code:`PA_CornerFreq` : Float, rad/s Pitch actuator natural frequency [rad/s] @@ -628,10 +663,30 @@ These are pass-through parameters for the DISCON.IN file. Use with caution. Do *Default* = 0 +:code:`DT_Out` : Float + Time step to output .dbg* files, or 0 to match sampling period of + OpenFAST + + *Default* = 0 + :code:`F_LPFType` : Float 1- first-order low-pass filter, 2- second-order low-pass filter (currently filters generator speed and pitch control signals +:code:`VS_ControlMode` : Float + Generator torque control mode in above rated conditions (0- no + torque control, 1- k*omega^2 with PI transitions, 2- WSE TSR + Tracking, 3- Power-based TSR Tracking) + + *Minimum* = 0 *Maximum* = 3 + + +:code:`VS_ConstPower` : Float + Do constant power torque control, where above rated torque varies + + *Minimum* = 0 *Maximum* = 1 + + :code:`F_NotchType` : Float Notch on the measured generator speed and/or tower fore-aft motion (for floating) (0- disable, 1- generator speed, 2- tower-top fore- @@ -642,12 +697,6 @@ These are pass-through parameters for the DISCON.IN file. Use with caution. Do (pitch contribution) (0- off, 1- 1P reductions, 2- 1P+2P reductions) -:code:`VS_ControlMode` : Float - Generator torque control mode in above rated conditions (0- - constant torque, 1- constant power, 2- TSR tracking PI control - with constant torque, 3- TSR tracking PI control with constant - power) - :code:`PC_ControlMode` : Float Blade pitch control mode (0- No pitch, fix to fine pitch, 1- active PI blade pitch control) @@ -692,12 +741,32 @@ These are pass-through parameters for the DISCON.IN file. Use with caution. Do :code:`F_LPFDamping` : Float Damping coefficient (used only when F_FilterType = 2 [-] -:code:`F_NotchCornerFreq` : Float, rad/s - Natural frequency of the notch filter, +:code:`F_NumNotchFilts` : Float + Number of notch filters placed on sensors + +:code:`F_NotchFreqs` : Array of Floats or Float, rad/s + Natural frequency of the notch filters. Array with length + F_NumNotchFilts + +:code:`F_NotchBetaNum` : Array of Floats or Float + Damping value of numerator (determines the width of notch). Array + with length F_NumNotchFilts, [-] + +:code:`F_NotchBetaDen` : Array of Floats or Float + Damping value of denominator (determines the depth of notch). + Array with length F_NumNotchFilts, [-] + +:code:`F_GenSpdNotch_N` : Float + Number of notch filters on generator speed -:code:`F_NotchBetaNumDen` : Array of Floats - Two notch damping values (numerator and denominator, resp) - - determines the width and depth of the notch, [-] +:code:`F_TwrTopNotch_N` : Float + Number of notch filters on tower top acceleration signal + +:code:`F_GenSpdNotch_Ind` : Array of Floats or Float + Indices of notch filters on generator speed + +:code:`F_TwrTopNotch_Ind` : Array of Floats or Float + Indices of notch filters on tower top acceleration signal :code:`F_SSCornerFreq` : Float, rad/s. Corner frequency (-3dB point) in the first order low pass filter @@ -802,7 +871,8 @@ These are pass-through parameters for the DISCON.IN file. Use with caution. Do Minimum generator speed :code:`VS_Rgn2K` : Float, Nm/(rad/s)^2 - Generator torque constant in Region 2 (HSS side) + Generator torque constant in Region 2 (HSS side). Only used in + VS_ControlMode = 1,3 :code:`VS_RtPwr` : Float, W Wind turbine rated power @@ -825,7 +895,14 @@ These are pass-through parameters for the DISCON.IN file. Use with caution. Do the transitional 2.5 region if VS_ControlMode =/ 2) :code:`VS_TSRopt` : Float, rad - Power-maximizing region 2 tip-speed-ratio + Power-maximizing region 2 tip-speed-ratio. Only used in + VS_ControlMode = 2. + +:code:`VS_PwrFiltF` : Float, rad + Low pass filter on power used to determine generator speed set + point. Only used in VS_ControlMode = 3. + + *Default* = 0.314 :code:`SS_VSGain` : Float Variable speed torque controller setpoint smoother gain @@ -984,10 +1061,11 @@ These are pass-through parameters for the DISCON.IN file. Use with caution. Do position in rad (used if OL_Mode = 2) :code:`RP_Gains` : Array of Floats - PID gains for rotor position control (used if OL_Mode = 2) + PID gains and Tf of derivative for rotor position control (used if + OL_Mode = 2) + + *Default* = [0, 0, 0, 0] - *Default* = [0, 0, 0] - :code:`Ind_CableControl` : Array of Floats The column in OL_Filename that contains the cable control inputs in m From b27629b3dc5c02a09956efde632fad6136554162 Mon Sep 17 00:00:00 2001 From: dzalkind Date: Fri, 22 Sep 2023 12:13:41 -0600 Subject: [PATCH 112/224] Rename power ref example --- Examples/{24_power_ref_control.py => 27_power_ref_control.py} | 0 Examples/test_examples.py | 1 + 2 files changed, 1 insertion(+) rename Examples/{24_power_ref_control.py => 27_power_ref_control.py} (100%) diff --git a/Examples/24_power_ref_control.py b/Examples/27_power_ref_control.py similarity index 100% rename from Examples/24_power_ref_control.py rename to Examples/27_power_ref_control.py diff --git a/Examples/test_examples.py b/Examples/test_examples.py index 7e504f8e..8c3ef7d4 100644 --- a/Examples/test_examples.py +++ b/Examples/test_examples.py @@ -29,6 +29,7 @@ '24_floating_feedback', '25_rotor_position_control', '26_marine_hydro', + '27_power_ref_control', 'update_rosco_discons', ] From ea55560f7e93f63e8745c8d73409cb1896a4f9d2 Mon Sep 17 00:00:00 2001 From: dzalkind Date: Fri, 22 Sep 2023 15:50:51 -0600 Subject: [PATCH 113/224] Shorten PRC example --- Examples/27_power_ref_control.py | 25 +++++++++++++++++++------ 1 file changed, 19 insertions(+), 6 deletions(-) diff --git a/Examples/27_power_ref_control.py b/Examples/27_power_ref_control.py index e309ae02..c2b96b09 100644 --- a/Examples/27_power_ref_control.py +++ b/Examples/27_power_ref_control.py @@ -23,6 +23,8 @@ ''' +FULL_TEST = False + #directories this_dir = os.path.dirname(os.path.abspath(__file__)) @@ -74,12 +76,23 @@ def main(): r = run_FAST_ROSCO() r.tuning_yaml = parameter_filename r.wind_case_fcn = cl.ramp # single step wind input - r.wind_case_opts = { - 'U_start': 5, # from 10 to 15 m/s - 'U_end': 35, - 't_start': 100, - 't_end': 2500, - } + + if FULL_TEST: + # Full test + r.wind_case_opts = { + 'U_start': 5, # from 10 to 15 m/s + 'U_end': 35, + 't_start': 100, + 't_end': 2500, + } + else: + r.wind_case_opts = { + 'U_start': 25, # from 10 to 15 m/s + 'U_end': 27, + 't_start': 50, + 't_end': 100, + } + # Short test for CI r.save_dir = run_dir r.rosco_dir = rosco_dir r.controller_params = { From b5eb5c0ad9400add4aee088ac699027d32c05526 Mon Sep 17 00:00:00 2001 From: dzalkind Date: Fri, 22 Sep 2023 15:51:29 -0600 Subject: [PATCH 114/224] Use updated DISCON writing functions for PRC inputs --- ROSCO_toolbox/utilities.py | 4 ++-- Test_Cases/BAR_10/BAR_10_DISCON.IN | 4 ++-- Test_Cases/IEA-15-240-RWT-UMaineSemi/DISCON-UMaineSemi.IN | 4 ++-- Test_Cases/MHK_RM1/MHK_RM1_DISCON.IN | 4 ++-- Test_Cases/NREL-5MW/DISCON.IN | 4 ++-- Test_Cases/NREL_2p8_127/NREL-2p8-127_DISCON.IN | 4 ++-- 6 files changed, 12 insertions(+), 12 deletions(-) diff --git a/ROSCO_toolbox/utilities.py b/ROSCO_toolbox/utilities.py index 4fd1f185..71e6ca90 100644 --- a/ROSCO_toolbox/utilities.py +++ b/ROSCO_toolbox/utilities.py @@ -186,8 +186,8 @@ def write_DISCON(turbine, controller, param_file='DISCON.IN', txt_filename='Cp_C file.write('\n') file.write('!------- POWER REFERENCE TRACKING --------------------------------------\n') file.write('{:<11d} ! PRC_n - Number of elements in PRC_WindSpeeds and PRC_RotorSpeeds array\n'.format(int(rosco_vt['PRC_n']))) - file.write('{} ! PRC_WindSpeeds - Array of wind speeds used in rotor speed vs. wind speed lookup table [m/s].\n'.format(''.join('{:<4.3f} '.format(rosco_vt['PRC_WindSpeeds'][i]) for i in range(rosco_vt['PRC_n'])))) - file.write('{} ! PRC_RotorSpeeds - Array of rotor speeds corresponding to PRC_WindSpeeds [rad/s].\n'.format(''.join('{:<4.3f} '.format(rosco_vt['PRC_RotorSpeeds'][i]) for i in range(rosco_vt['PRC_n'])))) + file.write('{} ! PRC_WindSpeeds - {}\n'.format(write_array(rosco_vt["PRC_WindSpeeds"]), input_descriptions["PRC_WindSpeeds"])) + file.write('{} ! PRC_RotorSpeeds - {}\n'.format(write_array(rosco_vt["PRC_RotorSpeeds"]), input_descriptions["PRC_RotorSpeeds"])) file.write('\n') file.write('!------- WIND SPEED ESTIMATOR ---------------------------------------------\n') file.write('{:<13.3f} ! WE_BladeRadius - Blade length (distance from hub center to blade tip), [m]\n'.format(rosco_vt['WE_BladeRadius'])) diff --git a/Test_Cases/BAR_10/BAR_10_DISCON.IN b/Test_Cases/BAR_10/BAR_10_DISCON.IN index 9eca6d81..931aa346 100644 --- a/Test_Cases/BAR_10/BAR_10_DISCON.IN +++ b/Test_Cases/BAR_10/BAR_10_DISCON.IN @@ -95,8 +95,8 @@ !------- POWER REFERENCE TRACKING -------------------------------------- 2 ! PRC_n - Number of elements in PRC_WindSpeeds and PRC_RotorSpeeds array -3.000 25.000 ! PRC_WindSpeeds - Array of wind speeds used in rotor speed vs. wind speed lookup table [m/s]. -0.792 0.792 ! PRC_RotorSpeeds - Array of rotor speeds corresponding to PRC_WindSpeeds [rad/s]. +3.0000 25.0000 ! PRC_WindSpeeds - Array of wind speeds used in rotor speed vs. wind speed lookup table +0.7917 0.7917 ! PRC_RotorSpeeds - Array of rotor speeds corresponding to PRC_WindSpeeds !------- WIND SPEED ESTIMATOR --------------------------------------------- 102.996 ! WE_BladeRadius - Blade length (distance from hub center to blade tip), [m] diff --git a/Test_Cases/IEA-15-240-RWT-UMaineSemi/DISCON-UMaineSemi.IN b/Test_Cases/IEA-15-240-RWT-UMaineSemi/DISCON-UMaineSemi.IN index 9b5dee69..52286435 100644 --- a/Test_Cases/IEA-15-240-RWT-UMaineSemi/DISCON-UMaineSemi.IN +++ b/Test_Cases/IEA-15-240-RWT-UMaineSemi/DISCON-UMaineSemi.IN @@ -95,8 +95,8 @@ !------- POWER REFERENCE TRACKING -------------------------------------- 2 ! PRC_n - Number of elements in PRC_WindSpeeds and PRC_RotorSpeeds array -3.000 25.000 ! PRC_WindSpeeds - Array of wind speeds used in rotor speed vs. wind speed lookup table [m/s]. -0.792 0.792 ! PRC_RotorSpeeds - Array of rotor speeds corresponding to PRC_WindSpeeds [rad/s]. +3.0000 25.0000 ! PRC_WindSpeeds - Array of wind speeds used in rotor speed vs. wind speed lookup table +0.7917 0.7917 ! PRC_RotorSpeeds - Array of rotor speeds corresponding to PRC_WindSpeeds !------- WIND SPEED ESTIMATOR --------------------------------------------- 120.000 ! WE_BladeRadius - Blade length (distance from hub center to blade tip), [m] diff --git a/Test_Cases/MHK_RM1/MHK_RM1_DISCON.IN b/Test_Cases/MHK_RM1/MHK_RM1_DISCON.IN index 4e2236ad..0868164f 100644 --- a/Test_Cases/MHK_RM1/MHK_RM1_DISCON.IN +++ b/Test_Cases/MHK_RM1/MHK_RM1_DISCON.IN @@ -95,8 +95,8 @@ !------- POWER REFERENCE TRACKING -------------------------------------- 2 ! PRC_n - Number of elements in PRC_WindSpeeds and PRC_RotorSpeeds array -3.000 25.000 ! PRC_WindSpeeds - Array of wind speeds used in rotor speed vs. wind speed lookup table [m/s]. -0.792 0.792 ! PRC_RotorSpeeds - Array of rotor speeds corresponding to PRC_WindSpeeds [rad/s]. +3.0000 25.0000 ! PRC_WindSpeeds - Array of wind speeds used in rotor speed vs. wind speed lookup table +0.7917 0.7917 ! PRC_RotorSpeeds - Array of rotor speeds corresponding to PRC_WindSpeeds !------- WIND SPEED ESTIMATOR --------------------------------------------- 10.000 ! WE_BladeRadius - Blade length (distance from hub center to blade tip), [m] diff --git a/Test_Cases/NREL-5MW/DISCON.IN b/Test_Cases/NREL-5MW/DISCON.IN index b5ac2808..f735a4cd 100644 --- a/Test_Cases/NREL-5MW/DISCON.IN +++ b/Test_Cases/NREL-5MW/DISCON.IN @@ -95,8 +95,8 @@ !------- POWER REFERENCE TRACKING -------------------------------------- 2 ! PRC_n - Number of elements in PRC_WindSpeeds and PRC_RotorSpeeds array -3.000 25.000 ! PRC_WindSpeeds - Array of wind speeds used in rotor speed vs. wind speed lookup table [m/s]. -0.792 0.792 ! PRC_RotorSpeeds - Array of rotor speeds corresponding to PRC_WindSpeeds [rad/s]. +3.0000 25.0000 ! PRC_WindSpeeds - Array of wind speeds used in rotor speed vs. wind speed lookup table +0.7917 0.7917 ! PRC_RotorSpeeds - Array of rotor speeds corresponding to PRC_WindSpeeds !------- WIND SPEED ESTIMATOR --------------------------------------------- 63.000 ! WE_BladeRadius - Blade length (distance from hub center to blade tip), [m] diff --git a/Test_Cases/NREL_2p8_127/NREL-2p8-127_DISCON.IN b/Test_Cases/NREL_2p8_127/NREL-2p8-127_DISCON.IN index 84a1e769..24e37715 100644 --- a/Test_Cases/NREL_2p8_127/NREL-2p8-127_DISCON.IN +++ b/Test_Cases/NREL_2p8_127/NREL-2p8-127_DISCON.IN @@ -95,8 +95,8 @@ !------- POWER REFERENCE TRACKING -------------------------------------- 2 ! PRC_n - Number of elements in PRC_WindSpeeds and PRC_RotorSpeeds array -3.000 25.000 ! PRC_WindSpeeds - Array of wind speeds used in rotor speed vs. wind speed lookup table [m/s]. -0.792 0.792 ! PRC_RotorSpeeds - Array of rotor speeds corresponding to PRC_WindSpeeds [rad/s]. +3.0000 25.0000 ! PRC_WindSpeeds - Array of wind speeds used in rotor speed vs. wind speed lookup table +0.7917 0.7917 ! PRC_RotorSpeeds - Array of rotor speeds corresponding to PRC_WindSpeeds !------- WIND SPEED ESTIMATOR --------------------------------------------- 63.457 ! WE_BladeRadius - Blade length (distance from hub center to blade tip), [m] From 24052dc2018a162bb8793a3663a78d6dfd367fb8 Mon Sep 17 00:00:00 2001 From: dzalkind Date: Mon, 25 Sep 2023 10:46:16 -0600 Subject: [PATCH 115/224] Revert run_FAST cases --- ROSCO_toolbox/ofTools/case_gen/run_FAST.py | 26 ---------------------- 1 file changed, 26 deletions(-) diff --git a/ROSCO_toolbox/ofTools/case_gen/run_FAST.py b/ROSCO_toolbox/ofTools/case_gen/run_FAST.py index b7708fd2..97c6b053 100644 --- a/ROSCO_toolbox/ofTools/case_gen/run_FAST.py +++ b/ROSCO_toolbox/ofTools/case_gen/run_FAST.py @@ -300,32 +300,6 @@ def run_FAST(self): r.n_cores = 2 - elif sim_config == 12: - - # RAAW FAD set up - r.tuning_yaml = '/Users/dzalkind/Projects/BAR/BAR_Designs/BAR_USC/WEIS/ROSCO_BAR_USC.yaml' - r.wind_case_fcn = cl.turb_bts - r.wind_case_opts = { - 'TMax': 720, - 'wind_filenames': ['/Users/dzalkind/Tools/WEIS-1/outputs/02_loads/wind/IEA15_NTM_U7.000000_Seed1501552846.0.bts'] - } - r.save_dir = '/Users/dzalkind/Projects/BAR/BAR_Designs/BAR_USC' - # r.control_sweep_fcn = cl.sweep_ps_percent - r.n_cores = 1 - - elif sim_config == 14: - - # RAAW FAD set up - r.tuning_yaml = '/Users/dzalkind/Tools/ROSCO/Tune_Cases/IEA15MW_PRC.yaml' - r.wind_case_fcn = cl.power_curve - r.wind_case_opts = { - # 'U': [16], - 'T_max': 200 - } - r.save_dir = '/Users/dzalkind/Tools/ROSCO/outputs/PRC_2' - # r.control_sweep_fcn = cl.sweep_ps_percent - r.n_cores = 8 - else: raise Exception('This simulation configuration is not supported.') From 3092e387b63af4b1c75522ec485b716df9f079b4 Mon Sep 17 00:00:00 2001 From: dzalkind Date: Mon, 25 Sep 2023 10:46:34 -0600 Subject: [PATCH 116/224] Tidy example documentation, output --- Examples/27_power_ref_control.py | 10 ++++------ 1 file changed, 4 insertions(+), 6 deletions(-) diff --git a/Examples/27_power_ref_control.py b/Examples/27_power_ref_control.py index c2b96b09..93d24b98 100644 --- a/Examples/27_power_ref_control.py +++ b/Examples/27_power_ref_control.py @@ -1,20 +1,18 @@ ''' ------------ 24_outdata_in_control ------------------------ +----------- 27_power_ref_control ------------------------ Run openfast with ROSCO and cable control ----------------------------------------------- -Set up and run simulation with pitch offsets, check outputs +Demonstrate a simulation with a generator reference speed that changes with estimated wind speed + ''' import os, platform from ROSCO_toolbox.ofTools.case_gen.run_FAST import run_FAST_ROSCO from ROSCO_toolbox.ofTools.case_gen import CaseLibrary as cl -from ROSCO_toolbox.ofTools.fast_io import output_processing from ROSCO_toolbox.tune import yaml_to_objs import numpy as np -from ROSCO_toolbox.ofTools.fast_io.FAST_reader import InputReader_OpenFAST -from ROSCO_toolbox.ofTools.fast_io.FAST_writer import InputWriter_OpenFAST from ROSCO_toolbox.inputs.validation import load_rosco_yaml import matplotlib.pyplot as plt @@ -44,7 +42,7 @@ def main(): # Input yaml and output directory parameter_filename = os.path.join(rosco_dir,'Tune_Cases/IEA15MW.yaml') - run_dir = os.path.join(example_out_dir,'24_PRC_0') + run_dir = os.path.join(example_out_dir,'27_PRC_0') os.makedirs(run_dir,exist_ok=True) From b817a5ca845be6770c3595e2e94f5fcf4ab7f677 Mon Sep 17 00:00:00 2001 From: dzalkind Date: Mon, 25 Sep 2023 11:01:18 -0600 Subject: [PATCH 117/224] Bring back new VS_ControlMode that merge lost --- ROSCO/src/ControllerBlocks.f90 | 8 +++++--- 1 file changed, 5 insertions(+), 3 deletions(-) diff --git a/ROSCO/src/ControllerBlocks.f90 b/ROSCO/src/ControllerBlocks.f90 index d0a6f9fc..234850f4 100644 --- a/ROSCO/src/ControllerBlocks.f90 +++ b/ROSCO/src/ControllerBlocks.f90 @@ -54,9 +54,11 @@ SUBROUTINE ComputeVariablesSetpoints(CntrPar, LocalVar, objInst, ErrVar) ! ----- Torque controller reference errors ----- ! Define VS reference generator speed [rad/s] - IF ((CntrPar%VS_ControlMode == 2) .OR. (CntrPar%VS_ControlMode == 3)) THEN + IF (CntrPar%VS_ControlMode == 2) THEN LocalVar%VS_RefSpd = (CntrPar%VS_TSRopt * LocalVar%We_Vw_F / CntrPar%WE_BladeRadius) * CntrPar%WE_GearboxRatio - LocalVar%VS_RefSpd = saturate(LocalVar%VS_RefSpd,CntrPar%VS_MinOMSpd, CntrPar%VS_RefSpd) + ELSEIF (CntrPar%VS_ControlMode == 3) THEN + LocalVar%VS_GenPwrF = LPFilter(LocalVar%VS_GenPwr, LocalVar%DT,CntrPar%VS_PwrFiltF, LocalVar%FP, LocalVar%iStatus, LocalVar%restart, objInst%instLPF) + LocalVar%VS_RefSpd = (LocalVar%VS_GenPwrF/CntrPar%VS_Rgn2K)**(1./3.) ! Genspeed reference that doesnt depend on wind speed estimate (https://doi.org/10.2172/1259805) ELSE LocalVar%VS_RefSpd = CntrPar%VS_RefSpd ENDIF @@ -79,7 +81,7 @@ SUBROUTINE ComputeVariablesSetpoints(CntrPar, LocalVar, objInst, ErrVar) ! Force minimum rotor speed LocalVar%VS_RefSpd = max(LocalVar%VS_RefSpd, CntrPar%VS_MinOmSpd) - ! TSR-tracking reference error or PRC reference tracking error + ! Reference error IF ((CntrPar%VS_ControlMode == 2) .OR. (CntrPar%VS_ControlMode == 3)) THEN LocalVar%VS_SpdErr = LocalVar%VS_RefSpd - LocalVar%GenSpeedF ENDIF From 38f27def40e354599ebec6d1e35d62818ac747b4 Mon Sep 17 00:00:00 2001 From: dzalkind Date: Tue, 26 Sep 2023 09:54:29 -0600 Subject: [PATCH 118/224] Add LPF on WSE for speed selection, use gen speed rather than rotor --- ROSCO/rosco_registry/rosco_types.yaml | 10 ++- ROSCO/src/ControllerBlocks.f90 | 7 +- ROSCO/src/ROSCO_IO.f90 | 83 ++++++++++--------- ROSCO/src/ROSCO_Types.f90 | 6 +- ROSCO/src/ReadSetParameters.f90 | 7 +- ROSCO_toolbox/inputs/toolbox_schema.yaml | 12 ++- ROSCO_toolbox/utilities.py | 7 +- Test_Cases/BAR_10/BAR_10_DISCON.IN | 9 +- .../DISCON-UMaineSemi.IN | 9 +- Test_Cases/MHK_RM1/MHK_RM1_DISCON.IN | 9 +- Test_Cases/NREL-5MW/DISCON.IN | 9 +- .../NREL_2p8_127/NREL-2p8-127_DISCON.IN | 9 +- Tune_Cases/IEA15MW_PRC.yaml | 2 +- 13 files changed, 101 insertions(+), 78 deletions(-) diff --git a/ROSCO/rosco_registry/rosco_types.yaml b/ROSCO/rosco_registry/rosco_types.yaml index cce1856f..21738501 100644 --- a/ROSCO/rosco_registry/rosco_types.yaml +++ b/ROSCO/rosco_registry/rosco_types.yaml @@ -316,13 +316,16 @@ ControlParameters: <<: *real description: Array of wind speeds used in rotor speed vs. wind speed lookup table allocatable: True - PRC_RotorSpeeds: + PRC_GenSpeeds: <<: *real description: Array of rotor speeds corresponding to PRC_WindSpeeds allocatable: True PRC_n: <<: *integer - description: Number of elements in PRC_WindSpeeds and PRC_RotorSpeeds array + description: Number of elements in PRC_WindSpeeds and PRC_GenSpeeds array + PRC_LPF_Freq: + <<: *real + description: Frequency of the low pass filter on the wind speed estimate used to set PRC_GenSpeeds [rad/s] # Wind Speed Estimator WE_Mode: @@ -1159,6 +1162,9 @@ LocalVariables: VS_LastGenTrqF: <<: *real description: Differentiated integrated wind speed quantity for estimation [m/s] + PRC_WSE_F: + <<: *real + description: Filtered wind speed estimate for power reference control SD: <<: *logical description: Shutdown, .FALSE. if inactive, .TRUE. if active diff --git a/ROSCO/src/ControllerBlocks.f90 b/ROSCO/src/ControllerBlocks.f90 index 234850f4..d69ca9e3 100644 --- a/ROSCO/src/ControllerBlocks.f90 +++ b/ROSCO/src/ControllerBlocks.f90 @@ -36,9 +36,10 @@ SUBROUTINE ComputeVariablesSetpoints(CntrPar, LocalVar, objInst, ErrVar) ! ----- Pitch controller speed and power error ----- - ! Power reference tracking rotor speed + ! Power reference tracking generator speed IF (CntrPar%PRC_Mode == 1) THEN - LocalVar%PC_RefSpd = interp1d(CntrPar%PRC_WindSpeeds,CntrPar%PRC_RotorSpeeds,LocalVar%WE_Vw_F,ErrVar) * CntrPar%WE_GearboxRatio + LocalVar%PRC_WSE_F = LPFilter(LocalVar%WE_Vw, LocalVar%DT,CntrPar%PRC_LPF_Freq, LocalVar%FP, LocalVar%iStatus, LocalVar%restart, objInst%instLPF) + LocalVar%PC_RefSpd = interp1d(CntrPar%PRC_WindSpeeds,CntrPar%PRC_GenSpeeds,LocalVar%PRC_WSE_F,ErrVar) ELSE LocalVar%PC_RefSpd = CntrPar%PC_RefSpd ENDIF @@ -65,7 +66,7 @@ SUBROUTINE ComputeVariablesSetpoints(CntrPar, LocalVar, objInst, ErrVar) ! Implement power reference rotor speed (overwrites above), convert to generator speed IF (CntrPar%PRC_Mode == 1) THEN - LocalVar%VS_RefSpd = interp1d(CntrPar%PRC_WindSpeeds,CntrPar%PRC_RotorSpeeds,LocalVar%WE_Vw_F,ErrVar) * CntrPar%WE_GearboxRatio + LocalVar%VS_RefSpd = interp1d(CntrPar%PRC_WindSpeeds,CntrPar%PRC_GenSpeeds,LocalVar%WE_Vw_F,ErrVar) ENDIF ! Implement setpoint smoothing diff --git a/ROSCO/src/ROSCO_IO.f90 b/ROSCO/src/ROSCO_IO.f90 index 66ee2626..adac7c34 100644 --- a/ROSCO/src/ROSCO_IO.f90 +++ b/ROSCO/src/ROSCO_IO.f90 @@ -137,6 +137,7 @@ SUBROUTINE WriteRestartFile(LocalVar, CntrPar, ErrVar, objInst, RootName, size_a WRITE( Un, IOSTAT=ErrStat) LocalVar%WE_VwI WRITE( Un, IOSTAT=ErrStat) LocalVar%WE_VwIdot WRITE( Un, IOSTAT=ErrStat) LocalVar%VS_LastGenTrqF + WRITE( Un, IOSTAT=ErrStat) LocalVar%PRC_WSE_F WRITE( Un, IOSTAT=ErrStat) LocalVar%SD WRITE( Un, IOSTAT=ErrStat) LocalVar%Fl_PitCom WRITE( Un, IOSTAT=ErrStat) LocalVar%NACIMU_FA_AccF @@ -420,6 +421,7 @@ SUBROUTINE ReadRestartFile(avrSWAP, LocalVar, CntrPar, objInst, PerfData, RootNa READ( Un, IOSTAT=ErrStat) LocalVar%WE_VwI READ( Un, IOSTAT=ErrStat) LocalVar%WE_VwIdot READ( Un, IOSTAT=ErrStat) LocalVar%VS_LastGenTrqF + READ( Un, IOSTAT=ErrStat) LocalVar%PRC_WSE_F READ( Un, IOSTAT=ErrStat) LocalVar%SD READ( Un, IOSTAT=ErrStat) LocalVar%Fl_PitCom READ( Un, IOSTAT=ErrStat) LocalVar%NACIMU_FA_AccF @@ -649,7 +651,7 @@ SUBROUTINE Debug(LocalVar, CntrPar, DebugVar, ErrVar, avrSWAP, RootName, size_av '[rad/s]', '[rad/s]', '[m/s]', '[rad]', '[rad]', & '[N/A]', '[N/A]', '[N/A]', '[N/A]', '[rad/s]', & '[deg]', '[deg]', '[deg]', '[N/A]'] - nLocalVars = 111 + nLocalVars = 112 Allocate(LocalVarOutData(nLocalVars)) Allocate(LocalVarOutStrings(nLocalVars)) LocalVarOutData(1) = LocalVar%iStatus @@ -734,35 +736,36 @@ SUBROUTINE Debug(LocalVar, CntrPar, DebugVar, ErrVar, avrSWAP, RootName, size_av LocalVarOutData(80) = LocalVar%WE_VwI LocalVarOutData(81) = LocalVar%WE_VwIdot LocalVarOutData(82) = LocalVar%VS_LastGenTrqF - LocalVarOutData(83) = LocalVar%Fl_PitCom - LocalVarOutData(84) = LocalVar%NACIMU_FA_AccF - LocalVarOutData(85) = LocalVar%FA_AccF - LocalVarOutData(86) = LocalVar%PtfmTDX - LocalVarOutData(87) = LocalVar%PtfmTDY - LocalVarOutData(88) = LocalVar%PtfmTDZ - LocalVarOutData(89) = LocalVar%PtfmRDX - LocalVarOutData(90) = LocalVar%PtfmRDY - LocalVarOutData(91) = LocalVar%PtfmRDZ - LocalVarOutData(92) = LocalVar%PtfmTVX - LocalVarOutData(93) = LocalVar%PtfmTVY - LocalVarOutData(94) = LocalVar%PtfmTVZ - LocalVarOutData(95) = LocalVar%PtfmRVX - LocalVarOutData(96) = LocalVar%PtfmRVY - LocalVarOutData(97) = LocalVar%PtfmRVZ - LocalVarOutData(98) = LocalVar%PtfmTAX - LocalVarOutData(99) = LocalVar%PtfmTAY - LocalVarOutData(100) = LocalVar%PtfmTAZ - LocalVarOutData(101) = LocalVar%PtfmRAX - LocalVarOutData(102) = LocalVar%PtfmRAY - LocalVarOutData(103) = LocalVar%PtfmRAZ - LocalVarOutData(104) = LocalVar%CC_DesiredL(1) - LocalVarOutData(105) = LocalVar%CC_ActuatedL(1) - LocalVarOutData(106) = LocalVar%CC_ActuatedDL(1) - LocalVarOutData(107) = LocalVar%StC_Input(1) - LocalVarOutData(108) = LocalVar%Flp_Angle(1) - LocalVarOutData(109) = LocalVar%RootMyb_Last(1) - LocalVarOutData(110) = LocalVar%ACC_INFILE_SIZE - LocalVarOutData(111) = LocalVar%AWC_complexangle(1) + LocalVarOutData(83) = LocalVar%PRC_WSE_F + LocalVarOutData(84) = LocalVar%Fl_PitCom + LocalVarOutData(85) = LocalVar%NACIMU_FA_AccF + LocalVarOutData(86) = LocalVar%FA_AccF + LocalVarOutData(87) = LocalVar%PtfmTDX + LocalVarOutData(88) = LocalVar%PtfmTDY + LocalVarOutData(89) = LocalVar%PtfmTDZ + LocalVarOutData(90) = LocalVar%PtfmRDX + LocalVarOutData(91) = LocalVar%PtfmRDY + LocalVarOutData(92) = LocalVar%PtfmRDZ + LocalVarOutData(93) = LocalVar%PtfmTVX + LocalVarOutData(94) = LocalVar%PtfmTVY + LocalVarOutData(95) = LocalVar%PtfmTVZ + LocalVarOutData(96) = LocalVar%PtfmRVX + LocalVarOutData(97) = LocalVar%PtfmRVY + LocalVarOutData(98) = LocalVar%PtfmRVZ + LocalVarOutData(99) = LocalVar%PtfmTAX + LocalVarOutData(100) = LocalVar%PtfmTAY + LocalVarOutData(101) = LocalVar%PtfmTAZ + LocalVarOutData(102) = LocalVar%PtfmRAX + LocalVarOutData(103) = LocalVar%PtfmRAY + LocalVarOutData(104) = LocalVar%PtfmRAZ + LocalVarOutData(105) = LocalVar%CC_DesiredL(1) + LocalVarOutData(106) = LocalVar%CC_ActuatedL(1) + LocalVarOutData(107) = LocalVar%CC_ActuatedDL(1) + LocalVarOutData(108) = LocalVar%StC_Input(1) + LocalVarOutData(109) = LocalVar%Flp_Angle(1) + LocalVarOutData(110) = LocalVar%RootMyb_Last(1) + LocalVarOutData(111) = LocalVar%ACC_INFILE_SIZE + LocalVarOutData(112) = LocalVar%AWC_complexangle(1) LocalVarOutStrings = [CHARACTER(15) :: 'iStatus', 'Time', 'DT', 'n_DT', 'Time_Last', & 'VS_GenPwr', 'VS_GenPwrF', 'GenSpeed', 'RotSpeed', 'NacHeading', & 'NacVane', 'HorWindV', 'rootMOOP', 'rootMOOPF', 'BlPitch', & @@ -779,13 +782,13 @@ SUBROUTINE Debug(LocalVar, CntrPar, DebugVar, ErrVar, avrSWAP, RootName, size_av 'SS_DelOmegaF', 'TestType', 'Kp_Float', 'VS_MaxTq', 'VS_LastGenTrq', & 'VS_LastGenPwr', 'VS_MechGenPwr', 'VS_SpdErrAr', 'VS_SpdErrBr', 'VS_SpdErr', & 'VS_State', 'VS_Rgn3Pitch', 'WE_Vw', 'WE_Vw_F', 'WE_VwI', & - 'WE_VwIdot', 'VS_LastGenTrqF', 'Fl_PitCom', 'NACIMU_FA_AccF', 'FA_AccF', & - 'PtfmTDX', 'PtfmTDY', 'PtfmTDZ', 'PtfmRDX', 'PtfmRDY', & - 'PtfmRDZ', 'PtfmTVX', 'PtfmTVY', 'PtfmTVZ', 'PtfmRVX', & - 'PtfmRVY', 'PtfmRVZ', 'PtfmTAX', 'PtfmTAY', 'PtfmTAZ', & - 'PtfmRAX', 'PtfmRAY', 'PtfmRAZ', 'CC_DesiredL', 'CC_ActuatedL', & - 'CC_ActuatedDL', 'StC_Input', 'Flp_Angle', 'RootMyb_Last', 'ACC_INFILE_SIZE', & - 'AWC_complexangle'] + 'WE_VwIdot', 'VS_LastGenTrqF', 'PRC_WSE_F', 'Fl_PitCom', 'NACIMU_FA_AccF', & + 'FA_AccF', 'PtfmTDX', 'PtfmTDY', 'PtfmTDZ', 'PtfmRDX', & + 'PtfmRDY', 'PtfmRDZ', 'PtfmTVX', 'PtfmTVY', 'PtfmTVZ', & + 'PtfmRVX', 'PtfmRVY', 'PtfmRVZ', 'PtfmTAX', 'PtfmTAY', & + 'PtfmTAZ', 'PtfmRAX', 'PtfmRAY', 'PtfmRAZ', 'CC_DesiredL', & + 'CC_ActuatedL', 'CC_ActuatedDL', 'StC_Input', 'Flp_Angle', 'RootMyb_Last', & + 'ACC_INFILE_SIZE', 'AWC_complexangle'] ! Initialize debug file IF ((LocalVar%iStatus == 0) .OR. (LocalVar%iStatus == -9)) THEN ! .TRUE. if we're on the first call to the DLL IF (CntrPar%LoggingLevel > 0) THEN @@ -800,8 +803,8 @@ SUBROUTINE Debug(LocalVar, CntrPar, DebugVar, ErrVar, avrSWAP, RootName, size_av CALL GetNewUnit(UnDb2, ErrVar) OPEN(unit=UnDb2, FILE=TRIM(RootName)//'.RO.dbg2') WRITE(UnDb2, *) 'Generated on '//CurDate()//' at '//CurTime()//' using ROSCO-'//TRIM(rosco_version) - WRITE(UnDb2, '(112(a20,TR5:))') 'Time', LocalVarOutStrings - WRITE(UnDb2, '(112(a20,TR5:))') + WRITE(UnDb2, '(113(a20,TR5:))') 'Time', LocalVarOutStrings + WRITE(UnDb2, '(113(a20,TR5:))') END IF IF (CntrPar%LoggingLevel > 2) THEN @@ -864,7 +867,7 @@ SUBROUTINE Debug(LocalVar, CntrPar, DebugVar, ErrVar, avrSWAP, RootName, size_av END DO ! Write debug files - FmtDat = "(F20.5,TR5,111(ES20.5E2,TR5:))" ! The format of the debugging data + FmtDat = "(F20.5,TR5,112(ES20.5E2,TR5:))" ! The format of the debugging data IF ( MOD(LocalVar%n_DT, CntrPar%n_DT_Out) == 0) THEN IF(CntrPar%LoggingLevel > 0) THEN WRITE (UnDb, FmtDat) LocalVar%Time, DebugOutData diff --git a/ROSCO/src/ROSCO_Types.f90 b/ROSCO/src/ROSCO_Types.f90 index db564f2b..363e2e7a 100644 --- a/ROSCO/src/ROSCO_Types.f90 +++ b/ROSCO/src/ROSCO_Types.f90 @@ -77,8 +77,9 @@ MODULE ROSCO_Types REAL(DbKi) :: SS_PCGain ! Collective pitch controller setpoint smoother gain, [-]. INTEGER(IntKi) :: PRC_Mode ! Power reference tracking mode, 0- use standard rotor speed set points, 1- use PRC rotor speed setpoints REAL(DbKi), DIMENSION(:), ALLOCATABLE :: PRC_WindSpeeds ! Array of wind speeds used in rotor speed vs. wind speed lookup table - REAL(DbKi), DIMENSION(:), ALLOCATABLE :: PRC_RotorSpeeds ! Array of rotor speeds corresponding to PRC_WindSpeeds - INTEGER(IntKi) :: PRC_n ! Number of elements in PRC_WindSpeeds and PRC_RotorSpeeds array + REAL(DbKi), DIMENSION(:), ALLOCATABLE :: PRC_GenSpeeds ! Array of rotor speeds corresponding to PRC_WindSpeeds + INTEGER(IntKi) :: PRC_n ! Number of elements in PRC_WindSpeeds and PRC_GenSpeeds array + REAL(DbKi) :: PRC_LPF_Freq ! Frequency of the low pass filter on the wind speed estimate used to set PRC_GenSpeeds [rad/s] INTEGER(IntKi) :: WE_Mode ! Wind speed estimator mode {0 - One-second low pass filtered hub height wind speed, 1 - Imersion and Invariance Estimator (Ortega et al.) REAL(DbKi) :: WE_BladeRadius ! Blade length [m] INTEGER(IntKi) :: WE_CP_n ! Amount of parameters in the Cp array @@ -322,6 +323,7 @@ MODULE ROSCO_Types REAL(DbKi) :: WE_VwI ! Integrated wind speed quantity for estimation [m/s] REAL(DbKi) :: WE_VwIdot ! Differentiated integrated wind speed quantity for estimation [m/s] REAL(DbKi) :: VS_LastGenTrqF ! Differentiated integrated wind speed quantity for estimation [m/s] + REAL(DbKi) :: PRC_WSE_F ! Filtered wind speed estimate for power reference control LOGICAL :: SD ! Shutdown, .FALSE. if inactive, .TRUE. if active REAL(DbKi) :: Fl_PitCom ! Shutdown, .FALSE. if inactive, .TRUE. if active REAL(DbKi) :: NACIMU_FA_AccF ! None diff --git a/ROSCO/src/ReadSetParameters.f90 b/ROSCO/src/ReadSetParameters.f90 index bb6f866f..7df23a84 100644 --- a/ROSCO/src/ReadSetParameters.f90 +++ b/ROSCO/src/ReadSetParameters.f90 @@ -437,9 +437,10 @@ SUBROUTINE ReadControlParameterFileSub(CntrPar, LocalVar, zmqVar, accINFILE, acc IF (ErrVar%aviFAIL < 0) RETURN !------------ POWER REFERENCE TRACKING SETPOINTS -------------- - CALL ParseInput(FileLines, 'PRC_n', CntrPar%PRC_n, accINFILE(1), ErrVar, CntrPar%PRC_Mode == 0) - CALL ParseAry( FileLines, 'PRC_WindSpeeds', CntrPar%PRC_WindSpeeds, CntrPar%PRC_n, accINFILE(1), ErrVar, CntrPar%PRC_Mode == 0) - CALL ParseAry( FileLines, 'PRC_RotorSpeeds', CntrPar%PRC_RotorSpeeds, CntrPar%PRC_n, accINFILE(1), ErrVar, CntrPar%PRC_Mode == 0) + CALL ParseInput(FileLines, 'PRC_n', CntrPar%PRC_n, accINFILE(1), ErrVar, CntrPar%PRC_Mode == 0) + CALL ParseInput(FileLines, 'PRC_LPF_Freq', CntrPar%PRC_LPF_Freq, accINFILE(1), ErrVar, CntrPar%PRC_Mode == 0) + CALL ParseAry( FileLines, 'PRC_WindSpeeds', CntrPar%PRC_WindSpeeds, CntrPar%PRC_n, accINFILE(1), ErrVar, CntrPar%PRC_Mode == 0) + CALL ParseAry( FileLines, 'PRC_GenSpeeds', CntrPar%PRC_GenSpeeds, CntrPar%PRC_n, accINFILE(1), ErrVar, CntrPar%PRC_Mode == 0) !------------ WIND SPEED ESTIMATOR CONTANTS -------------- CALL ParseInput(FileLines, 'WE_BladeRadius', CntrPar%WE_BladeRadius, accINFILE(1), ErrVar, .FALSE., UnEc) diff --git a/ROSCO_toolbox/inputs/toolbox_schema.yaml b/ROSCO_toolbox/inputs/toolbox_schema.yaml index 8ad312f8..f06eb576 100644 --- a/ROSCO_toolbox/inputs/toolbox_schema.yaml +++ b/ROSCO_toolbox/inputs/toolbox_schema.yaml @@ -816,15 +816,19 @@ properties: type: array items: type: number - description: Array of wind speeds used in rotor speed vs. wind speed lookup table - PRC_RotorSpeeds: + description: Array of wind speeds used in rotor speed vs. wind speed lookup table [m/s] + PRC_GenSpeeds: type: array items: type: number - description: Array of rotor speeds corresponding to PRC_WindSpeeds + description: Array of generator speeds corresponding to PRC_WindSpeeds [rad/s] + PRC_LPF_Freq: + type: number + description: Frequency of the low pass filter on the wind speed estimate used to set PRC_GenSpeeds [rad/s] + default: 0.078539 PRC_n: type: number - description: Number of elements in PRC_WindSpeeds and PRC_RotorSpeeds array + description: Number of elements in PRC_WindSpeeds and PRC_GenSpeeds array WE_BladeRadius: type: number description: Blade length (distance from hub center to blade tip) diff --git a/ROSCO_toolbox/utilities.py b/ROSCO_toolbox/utilities.py index 71e6ca90..06906703 100644 --- a/ROSCO_toolbox/utilities.py +++ b/ROSCO_toolbox/utilities.py @@ -185,9 +185,10 @@ def write_DISCON(turbine, controller, param_file='DISCON.IN', txt_filename='Cp_C file.write('{:<13.5f} ! SS_PCGain - Collective pitch controller setpoint smoother gain, [-].\n'.format(rosco_vt['SS_PCGain'])) file.write('\n') file.write('!------- POWER REFERENCE TRACKING --------------------------------------\n') - file.write('{:<11d} ! PRC_n - Number of elements in PRC_WindSpeeds and PRC_RotorSpeeds array\n'.format(int(rosco_vt['PRC_n']))) + file.write('{:<11d} ! PRC_n - Number of elements in PRC_WindSpeeds and PRC_GenSpeeds array\n'.format(int(rosco_vt['PRC_n']))) + file.write('{:<13.5f} ! PRC_LPF_Freq - {}\n'.format(float(rosco_vt['PRC_LPF_Freq']), input_descriptions["PRC_LPF_Freq"])) file.write('{} ! PRC_WindSpeeds - {}\n'.format(write_array(rosco_vt["PRC_WindSpeeds"]), input_descriptions["PRC_WindSpeeds"])) - file.write('{} ! PRC_RotorSpeeds - {}\n'.format(write_array(rosco_vt["PRC_RotorSpeeds"]), input_descriptions["PRC_RotorSpeeds"])) + file.write('{} ! PRC_GenSpeeds - {}\n'.format(write_array(rosco_vt["PRC_GenSpeeds"]), input_descriptions["PRC_GenSpeeds"])) file.write('\n') file.write('!------- WIND SPEED ESTIMATOR ---------------------------------------------\n') file.write('{:<13.3f} ! WE_BladeRadius - Blade length (distance from hub center to blade tip), [m]\n'.format(rosco_vt['WE_BladeRadius'])) @@ -553,7 +554,7 @@ def DISCON_dict(turbine, controller, txt_filename=None): # -------- POWER REFERENCE TRACKING ------ DISCON_dict['PRC_n'] = 2 DISCON_dict['PRC_WindSpeeds'] = [3,25] - DISCON_dict['PRC_RotorSpeeds'] = [rpm2RadSec * 7.56] * 2 + DISCON_dict['PRC_GenSpeeds'] = [rpm2RadSec * 7.56] * 2 # ------- WIND SPEED ESTIMATOR ------- DISCON_dict['WE_BladeRadius'] = turbine.rotor_radius diff --git a/Test_Cases/BAR_10/BAR_10_DISCON.IN b/Test_Cases/BAR_10/BAR_10_DISCON.IN index 931aa346..bb950f78 100644 --- a/Test_Cases/BAR_10/BAR_10_DISCON.IN +++ b/Test_Cases/BAR_10/BAR_10_DISCON.IN @@ -1,5 +1,5 @@ ! Controller parameter input file for the BAR_10 wind turbine -! - File written using ROSCO version 2.8.0 controller tuning logic on 09/22/23 +! - File written using ROSCO version 2.8.0 controller tuning logic on 09/26/23 !------- SIMULATION CONTROL ------------------------------------------------------------ 1 ! LoggingLevel - {0: write no debug files, 1: write standard output .dbg-file, 2: LoggingLevel 1 + ROSCO LocalVars (.dbg2) 3: LoggingLevel 2 + complete avrSWAP-array (.dbg3)} @@ -94,9 +94,10 @@ 0.00100 ! SS_PCGain - Collective pitch controller setpoint smoother gain, [-]. !------- POWER REFERENCE TRACKING -------------------------------------- -2 ! PRC_n - Number of elements in PRC_WindSpeeds and PRC_RotorSpeeds array -3.0000 25.0000 ! PRC_WindSpeeds - Array of wind speeds used in rotor speed vs. wind speed lookup table -0.7917 0.7917 ! PRC_RotorSpeeds - Array of rotor speeds corresponding to PRC_WindSpeeds +2 ! PRC_n - Number of elements in PRC_WindSpeeds and PRC_GenSpeeds array +0.07854 ! PRC_LPF_Freq - Frequency of the low pass filter on the wind speed estimate used to set PRC_GenSpeeds [rad/s] +3.0000 25.0000 ! PRC_WindSpeeds - Array of wind speeds used in rotor speed vs. wind speed lookup table [m/s] +0.7917 0.7917 ! PRC_GenSpeeds - Array of generator speeds corresponding to PRC_WindSpeeds [rad/s] !------- WIND SPEED ESTIMATOR --------------------------------------------- 102.996 ! WE_BladeRadius - Blade length (distance from hub center to blade tip), [m] diff --git a/Test_Cases/IEA-15-240-RWT-UMaineSemi/DISCON-UMaineSemi.IN b/Test_Cases/IEA-15-240-RWT-UMaineSemi/DISCON-UMaineSemi.IN index 52286435..3e5abc22 100644 --- a/Test_Cases/IEA-15-240-RWT-UMaineSemi/DISCON-UMaineSemi.IN +++ b/Test_Cases/IEA-15-240-RWT-UMaineSemi/DISCON-UMaineSemi.IN @@ -1,5 +1,5 @@ ! Controller parameter input file for the IEA-15-240-RWT-UMaineSemi wind turbine -! - File written using ROSCO version 2.8.0 controller tuning logic on 09/22/23 +! - File written using ROSCO version 2.8.0 controller tuning logic on 09/26/23 !------- SIMULATION CONTROL ------------------------------------------------------------ 2 ! LoggingLevel - {0: write no debug files, 1: write standard output .dbg-file, 2: LoggingLevel 1 + ROSCO LocalVars (.dbg2) 3: LoggingLevel 2 + complete avrSWAP-array (.dbg3)} @@ -94,9 +94,10 @@ 0.00100 ! SS_PCGain - Collective pitch controller setpoint smoother gain, [-]. !------- POWER REFERENCE TRACKING -------------------------------------- -2 ! PRC_n - Number of elements in PRC_WindSpeeds and PRC_RotorSpeeds array -3.0000 25.0000 ! PRC_WindSpeeds - Array of wind speeds used in rotor speed vs. wind speed lookup table -0.7917 0.7917 ! PRC_RotorSpeeds - Array of rotor speeds corresponding to PRC_WindSpeeds +2 ! PRC_n - Number of elements in PRC_WindSpeeds and PRC_GenSpeeds array +0.07854 ! PRC_LPF_Freq - Frequency of the low pass filter on the wind speed estimate used to set PRC_GenSpeeds [rad/s] +3.0000 25.0000 ! PRC_WindSpeeds - Array of wind speeds used in rotor speed vs. wind speed lookup table [m/s] +0.7917 0.7917 ! PRC_GenSpeeds - Array of generator speeds corresponding to PRC_WindSpeeds [rad/s] !------- WIND SPEED ESTIMATOR --------------------------------------------- 120.000 ! WE_BladeRadius - Blade length (distance from hub center to blade tip), [m] diff --git a/Test_Cases/MHK_RM1/MHK_RM1_DISCON.IN b/Test_Cases/MHK_RM1/MHK_RM1_DISCON.IN index 0868164f..52972e56 100644 --- a/Test_Cases/MHK_RM1/MHK_RM1_DISCON.IN +++ b/Test_Cases/MHK_RM1/MHK_RM1_DISCON.IN @@ -1,5 +1,5 @@ ! Controller parameter input file for the MHK_RM1_Floating wind turbine -! - File written using ROSCO version 2.8.0 controller tuning logic on 09/22/23 +! - File written using ROSCO version 2.8.0 controller tuning logic on 09/26/23 !------- SIMULATION CONTROL ------------------------------------------------------------ 2 ! LoggingLevel - {0: write no debug files, 1: write standard output .dbg-file, 2: LoggingLevel 1 + ROSCO LocalVars (.dbg2) 3: LoggingLevel 2 + complete avrSWAP-array (.dbg3)} @@ -94,9 +94,10 @@ 0.00100 ! SS_PCGain - Collective pitch controller setpoint smoother gain, [-]. !------- POWER REFERENCE TRACKING -------------------------------------- -2 ! PRC_n - Number of elements in PRC_WindSpeeds and PRC_RotorSpeeds array -3.0000 25.0000 ! PRC_WindSpeeds - Array of wind speeds used in rotor speed vs. wind speed lookup table -0.7917 0.7917 ! PRC_RotorSpeeds - Array of rotor speeds corresponding to PRC_WindSpeeds +2 ! PRC_n - Number of elements in PRC_WindSpeeds and PRC_GenSpeeds array +0.07854 ! PRC_LPF_Freq - Frequency of the low pass filter on the wind speed estimate used to set PRC_GenSpeeds [rad/s] +3.0000 25.0000 ! PRC_WindSpeeds - Array of wind speeds used in rotor speed vs. wind speed lookup table [m/s] +0.7917 0.7917 ! PRC_GenSpeeds - Array of generator speeds corresponding to PRC_WindSpeeds [rad/s] !------- WIND SPEED ESTIMATOR --------------------------------------------- 10.000 ! WE_BladeRadius - Blade length (distance from hub center to blade tip), [m] diff --git a/Test_Cases/NREL-5MW/DISCON.IN b/Test_Cases/NREL-5MW/DISCON.IN index f735a4cd..0acc523a 100644 --- a/Test_Cases/NREL-5MW/DISCON.IN +++ b/Test_Cases/NREL-5MW/DISCON.IN @@ -1,5 +1,5 @@ ! Controller parameter input file for the NREL-5MW wind turbine -! - File written using ROSCO version 2.8.0 controller tuning logic on 09/22/23 +! - File written using ROSCO version 2.8.0 controller tuning logic on 09/26/23 !------- SIMULATION CONTROL ------------------------------------------------------------ 1 ! LoggingLevel - {0: write no debug files, 1: write standard output .dbg-file, 2: LoggingLevel 1 + ROSCO LocalVars (.dbg2) 3: LoggingLevel 2 + complete avrSWAP-array (.dbg3)} @@ -94,9 +94,10 @@ 0.00100 ! SS_PCGain - Collective pitch controller setpoint smoother gain, [-]. !------- POWER REFERENCE TRACKING -------------------------------------- -2 ! PRC_n - Number of elements in PRC_WindSpeeds and PRC_RotorSpeeds array -3.0000 25.0000 ! PRC_WindSpeeds - Array of wind speeds used in rotor speed vs. wind speed lookup table -0.7917 0.7917 ! PRC_RotorSpeeds - Array of rotor speeds corresponding to PRC_WindSpeeds +2 ! PRC_n - Number of elements in PRC_WindSpeeds and PRC_GenSpeeds array +0.07854 ! PRC_LPF_Freq - Frequency of the low pass filter on the wind speed estimate used to set PRC_GenSpeeds [rad/s] +3.0000 25.0000 ! PRC_WindSpeeds - Array of wind speeds used in rotor speed vs. wind speed lookup table [m/s] +0.7917 0.7917 ! PRC_GenSpeeds - Array of generator speeds corresponding to PRC_WindSpeeds [rad/s] !------- WIND SPEED ESTIMATOR --------------------------------------------- 63.000 ! WE_BladeRadius - Blade length (distance from hub center to blade tip), [m] diff --git a/Test_Cases/NREL_2p8_127/NREL-2p8-127_DISCON.IN b/Test_Cases/NREL_2p8_127/NREL-2p8-127_DISCON.IN index 24e37715..c2b5a765 100644 --- a/Test_Cases/NREL_2p8_127/NREL-2p8-127_DISCON.IN +++ b/Test_Cases/NREL_2p8_127/NREL-2p8-127_DISCON.IN @@ -1,5 +1,5 @@ ! Controller parameter input file for the NREL-2p8-127 wind turbine -! - File written using ROSCO version 2.8.0 controller tuning logic on 09/22/23 +! - File written using ROSCO version 2.8.0 controller tuning logic on 09/26/23 !------- SIMULATION CONTROL ------------------------------------------------------------ 2 ! LoggingLevel - {0: write no debug files, 1: write standard output .dbg-file, 2: LoggingLevel 1 + ROSCO LocalVars (.dbg2) 3: LoggingLevel 2 + complete avrSWAP-array (.dbg3)} @@ -94,9 +94,10 @@ 0.00100 ! SS_PCGain - Collective pitch controller setpoint smoother gain, [-]. !------- POWER REFERENCE TRACKING -------------------------------------- -2 ! PRC_n - Number of elements in PRC_WindSpeeds and PRC_RotorSpeeds array -3.0000 25.0000 ! PRC_WindSpeeds - Array of wind speeds used in rotor speed vs. wind speed lookup table -0.7917 0.7917 ! PRC_RotorSpeeds - Array of rotor speeds corresponding to PRC_WindSpeeds +2 ! PRC_n - Number of elements in PRC_WindSpeeds and PRC_GenSpeeds array +0.07854 ! PRC_LPF_Freq - Frequency of the low pass filter on the wind speed estimate used to set PRC_GenSpeeds [rad/s] +3.0000 25.0000 ! PRC_WindSpeeds - Array of wind speeds used in rotor speed vs. wind speed lookup table [m/s] +0.7917 0.7917 ! PRC_GenSpeeds - Array of generator speeds corresponding to PRC_WindSpeeds [rad/s] !------- WIND SPEED ESTIMATOR --------------------------------------------- 63.457 ! WE_BladeRadius - Blade length (distance from hub center to blade tip), [m] diff --git a/Tune_Cases/IEA15MW_PRC.yaml b/Tune_Cases/IEA15MW_PRC.yaml index 5e70d1e0..5df0361e 100644 --- a/Tune_Cases/IEA15MW_PRC.yaml +++ b/Tune_Cases/IEA15MW_PRC.yaml @@ -58,7 +58,7 @@ controller_params: PS_BldPitchMin_N: 56 PS_WindSpeeds: [ 3. , 3.4, 3.8, 4.2, 4.6, 5. , 5.4, 5.8, 6.2, 6.6, 7. , 7.4, 7.8, 8.2, 8.6, 9. , 9.4, 9.8, 10.2, 10.6, 11. , 11.4, 11.8, 12.2, 12.6, 13. , 13.4, 13.8, 14.2, 14.6, 15. , 15.4, 15.8, 16.2, 16.6, 17. , 17.4, 17.8, 18.2, 18.6, 19. , 19.4, 19.8, 20.2, 20.6, 21. , 21.4, 21.8, 22.2, 22.6, 23. , 23.4, 23.8, 24.2, 24.6, 25. ] PS_BldPitchMin: [ 0.052, 0.032, 0.012, -0.012, -0.017, -0.017, -0.017, -0.017, -0.017, -0.017, -0.001, 0.01 , 0.02 , 0.029, 0.048, 0.068, 0.085, 0.1 , 0.113, 0.129, 0.145, 0.159, 0.172, 0.185, 0.197, 0.208, 0.219, 0.229, 0.238, 0.244, 0.251, 0.26 , 0.269, 0.277, 0.286, 0.296, 0.304, 0.313, 0.322, 0.332, 0.341, 0.35 , 0.359, 0.369, 0.378, 0.387, 0.396, 0.407, 0.416, 0.424, 0.434, 0.444, 0.454, 0.463, 0.473, 0.481] - PRC_RotorSpeeds: [0.292, 0.292, 0.292, 0.292, 0.311, 0.338, 0.365, 0.392, 0.419, 0.446, 0.459, 0.459, 0.459, 0.459, 0.475, 0.497, 0.519, 0.542, 0.564, 0.564, 0.564, 0.564, 0.564, 0.564, 0.564, 0.564, 0.564, 0.564, 0.564, 0.564, 0.564, 0.558, 0.553, 0.547, 0.542, 0.536, 0.531, 0.526, 0.52 , 0.515, 0.509, 0.504, 0.498, 0.493, 0.487, 0.482, 0.477, 0.471, 0.466, 0.46 , 0.455, 0.449, 0.444, 0.439, 0.433, 0.428] + PRC_GenSpeeds: [0.292, 0.292, 0.292, 0.292, 0.311, 0.338, 0.365, 0.392, 0.419, 0.446, 0.459, 0.459, 0.459, 0.459, 0.475, 0.497, 0.519, 0.542, 0.564, 0.564, 0.564, 0.564, 0.564, 0.564, 0.564, 0.564, 0.564, 0.564, 0.564, 0.564, 0.564, 0.558, 0.553, 0.547, 0.542, 0.536, 0.531, 0.526, 0.52 , 0.515, 0.509, 0.504, 0.498, 0.493, 0.487, 0.482, 0.477, 0.471, 0.466, 0.46 , 0.455, 0.449, 0.444, 0.439, 0.433, 0.428] PRC_WindSpeeds: [ 3. , 3.4, 3.8, 4.2, 4.6, 5. , 5.4, 5.8, 6.2, 6.6, 7. , 7.4, 7.8, 8.2, 8.6, 9. , 9.4, 9.8, 10.2, 10.6, 11. , 11.4, 11.8, 12.2, 12.6, 13. , 13.4, 13.8, 14.2, 14.6, 15. , 15.4, 15.8, 16.2, 16.6, 17. , 17.4, 17.8, 18.2, 18.6, 19. , 19.4, 19.8, 20.2, 20.6, 21. , 21.4, 21.8, 22.2, 22.6, 23. , 23.4, 23.8, 24.2, 24.6, 25. ] PRC_n: 56 PRC_Mode: 1 From d9a31fb769a6186ead470b93daa3d68c8da475c1 Mon Sep 17 00:00:00 2001 From: dzalkind Date: Tue, 26 Sep 2023 10:44:43 -0600 Subject: [PATCH 119/224] Document API changes --- docs/source/api_change.rst | 41 ++++++++++++++++++++++++-------------- 1 file changed, 26 insertions(+), 15 deletions(-) diff --git a/docs/source/api_change.rst b/docs/source/api_change.rst index 27377410..6bde8d85 100644 --- a/docs/source/api_change.rst +++ b/docs/source/api_change.rst @@ -23,6 +23,10 @@ New torque control mode settings Multiple notch filters - Users can list any number of notch filters and apply them to either the generator speed and/or tower top accelleration signal based on their index +Power reference control via generator speed set points +- With this feature, enabled with `PRC_Mode`, a user can prescribe a set of generator speed set points (`PRC_GenSpeeds`) vs. the estimated wind speed (`PRC_WindSpeeds`), which can be used to avoid certain natural frequencies or implement a soft cut-out scheme. +- A low pass filter with frequency `PRC_LPF_Freq` is used to filter the wind speed estimate. A lower value increases the stability of the generator speed reference signal. + ====== ================= ====================================================================================================================================================================================================== Removed in ROSCO develop ---------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- @@ -40,19 +44,26 @@ New in ROSCO develop Line Input Name Example Value ====== ================= ====================================================================================================================================================================================================== 13 VS_ConstPower 0 ! VS_ConstPower - Do constant power torque control, where above rated torque varies, 0 for constant torque} -35 F_NumNotchFilts 1 ! F_NumNotchFilts - Number of notch filters placed on sensors -36 F_NotchFreqs 3.3550 ! F_NotchFreqs - Natural frequency of the notch filters. Array with length F_NumNotchFilts -37 F_NotchBetaNum 0.0000 ! F_NotchBetaNum - Damping value of numerator (determines the width of notch). Array with length F_NumNotchFilts, [-] -38 F_NotchBetaDen 0.2500 ! F_NotchBetaDen - Damping value of denominator (determines the depth of notch). Array with length F_NumNotchFilts, [-] -39 F_GenSpdNotch_N 0 ! F_GenSpdNotch_N - Number of notch filters on generator speed -40 F_GenSpdNotch_Ind 0 ! F_GenSpdNotch_Ind - Indices of notch filters on generator speed -41 F_TwrTopNotch_N 1 ! F_TwrTopNotch_N - Number of notch filters on tower top acceleration signal -42 F_TwrTopNotch_Ind 1 ! F_TwrTopNotch_Ind - Indices of notch filters on tower top acceleration signal -89 VS_PwrFiltF 0.3140 ! VS_PwrFiltF - Low pass filter on power used to determine generator speed set point. Only used in VS_ControlMode = 3. -133 Fl_n 1 ! Fl_n - Number of Fl_Kp gains in gain scheduling, optional with default of 1 -135 Fl_U 0.0000 ! Fl_U - Wind speeds for scheduling Fl_Kp, optional if Fl_Kp is single value [m/s] -149 Ind_Azimuth 0 ! Ind_Azimuth - The column in OL_Filename that contains the desired azimuth position in rad (used if OL_Mode = 2) -150 RP_Gains 0.0000 0.0000 0.0000 0.0000 ! RP_Gains - PID gains and Tf of derivative for rotor position control (used if OL_Mode = 2) +17 PRC_Mode 0 ! PRC_Mode - Power reference tracking mode{0: use standard rotor speed set points, 1: use PRC rotor speed setpoints} +36 F_NumNotchFilts 1 ! F_NumNotchFilts - Number of notch filters placed on sensors +37 F_NotchFreqs 3.3550 ! F_NotchFreqs - Natural frequency of the notch filters. Array with length F_NumNotchFilts +38 F_NotchBetaNum 0.0000 ! F_NotchBetaNum - Damping value of numerator (determines the width of notch). Array with length F_NumNotchFilts, [-] +39 F_NotchBetaDen 0.2500 ! F_NotchBetaDen - Damping value of denominator (determines the depth of notch). Array with length F_NumNotchFilts, [-] +40 F_GenSpdNotch_N 0 ! F_GenSpdNotch_N - Number of notch filters on generator speed +41 F_GenSpdNotch_Ind 0 ! F_GenSpdNotch_Ind - Indices of notch filters on generator speed +42 F_TwrTopNotch_N 1 ! F_TwrTopNotch_N - Number of notch filters on tower top acceleration signal +43 F_TwrTopNotch_Ind 1 ! F_TwrTopNotch_Ind - Indices of notch filters on tower top acceleration signal +90 VS_PwrFiltF 0.3140 ! VS_PwrFiltF - Low pass filter on power used to determine generator speed set point. Only used in VS_ControlMode = 3. +96 PRC_Section !------- POWER REFERENCE TRACKING -------------------------------------- +97 PRC_n 2 ! PRC_n - Number of elements in PRC_WindSpeeds and PRC_GenSpeeds array +98 PRC_LPF_Freq 0.07854 ! PRC_LPF_Freq - Frequency of the low pass filter on the wind speed estimate used to set PRC_GenSpeeds [rad/s] +99 PRC_WindSpeeds 3.0000 25.0000 ! PRC_WindSpeeds - Array of wind speeds used in rotor speed vs. wind speed lookup table [m/s] +100 PRC_GenSpeeds 0.7917 0.7917 ! PRC_GenSpeeds - Array of generator speeds corresponding to PRC_WindSpeeds [rad/s] +101 Empty Line +140 Fl_n 1 ! Fl_n - Number of Fl_Kp gains in gain scheduling, optional with default of 1 +142 Fl_U 0.0000 ! Fl_U - Wind speeds for scheduling Fl_Kp, optional if Fl_Kp is single value [m/s] +156 Ind_Azimuth 0 ! Ind_Azimuth - The column in OL_Filename that contains the desired azimuth position in rad (used if OL_Mode = 2) +157 RP_Gains 0.0000 0.0000 0.0000 0.0000 ! RP_Gains - PID gains and Tf of derivative for rotor position control (used if OL_Mode = 2) ====== ================= ====================================================================================================================================================================================================== ====== ================= ====================================================================================================================================================================================================== @@ -61,8 +72,8 @@ Changed in ROSCO develop Line Input Name Example Value ====== ================= ====================================================================================================================================================================================================== 12 VS_ControlMode 2 ! VS_ControlMode - Generator torque control mode in above rated conditions (0- no torque control, 1- k*omega^2 with PI transitions, 2- WSE TSR Tracking, 3- Power-based TSR Tracking)}126 OL_mode 0 ! OL_Mode - Open loop control mode {0: no open loop control, 1: open loop control vs. time, 2: rotor position control} -134 Fl_Kp 0.0000 ! Fl_Kp - Nacelle velocity proportional feedback gain [s] -146 Ind_BldPitch 0 0 0 ! Ind_BldPitch - The columns in OL_Filename that contains the blade pitch (1,2,3) inputs in rad [array] +141 Fl_Kp 0.0000 ! Fl_Kp - Nacelle velocity proportional feedback gain [s] +153 Ind_BldPitch 0 0 0 ! Ind_BldPitch - The columns in OL_Filename that contains the blade pitch (1,2,3) inputs in rad [array] ====== ================= ====================================================================================================================================================================================================== From 32292e58878e39d15733f1ba75a5bed25a685116 Mon Sep 17 00:00:00 2001 From: dzalkind Date: Tue, 26 Sep 2023 11:40:29 -0600 Subject: [PATCH 120/224] Bring back saturation of torque reference speed --- ROSCO/src/ControllerBlocks.f90 | 3 +++ 1 file changed, 3 insertions(+) diff --git a/ROSCO/src/ControllerBlocks.f90 b/ROSCO/src/ControllerBlocks.f90 index d69ca9e3..9d49a030 100644 --- a/ROSCO/src/ControllerBlocks.f90 +++ b/ROSCO/src/ControllerBlocks.f90 @@ -64,6 +64,9 @@ SUBROUTINE ComputeVariablesSetpoints(CntrPar, LocalVar, objInst, ErrVar) LocalVar%VS_RefSpd = CntrPar%VS_RefSpd ENDIF + ! Saturate torque reference speed between min speed and rated speed + LocalVar%VS_RefSpd = saturate(LocalVar%VS_RefSpd,CntrPar%VS_MinOMSpd, CntrPar%VS_RefSpd) + ! Implement power reference rotor speed (overwrites above), convert to generator speed IF (CntrPar%PRC_Mode == 1) THEN LocalVar%VS_RefSpd = interp1d(CntrPar%PRC_WindSpeeds,CntrPar%PRC_GenSpeeds,LocalVar%WE_Vw_F,ErrVar) From 3b0bde0fa94f63ee74b6bf375aac5f8d70b5cc96 Mon Sep 17 00:00:00 2001 From: dzalkind Date: Tue, 26 Sep 2023 11:56:09 -0600 Subject: [PATCH 121/224] Update PRC example with PRC_GenSpeeds --- Examples/27_power_ref_control.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Examples/27_power_ref_control.py b/Examples/27_power_ref_control.py index 93d24b98..5afe58aa 100644 --- a/Examples/27_power_ref_control.py +++ b/Examples/27_power_ref_control.py @@ -99,7 +99,7 @@ def main(): 'PRC_Mode': 1, 'PRC_n': len(v), 'PRC_WindSpeeds': v, - 'PRC_RotorSpeeds': omega, + 'PRC_GenSpeeds': omega, }} # Use OutData in control r.run_FAST() From e75baa29a984c844f7dd77294b56df992ca2af20 Mon Sep 17 00:00:00 2001 From: dzalkind Date: Wed, 27 Sep 2023 14:31:31 -0600 Subject: [PATCH 122/224] Remove pCrunch notebook --- pCrunch_processing.ipynb | 1507 -------------------------------------- 1 file changed, 1507 deletions(-) delete mode 100644 pCrunch_processing.ipynb diff --git a/pCrunch_processing.ipynb b/pCrunch_processing.ipynb deleted file mode 100644 index 056eff06..00000000 --- a/pCrunch_processing.ipynb +++ /dev/null @@ -1,1507 +0,0 @@ -{ - "cells": [ - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "### pCrunch Update\n", - "\n", - "Jake Nunemaker\n", - "\n", - "Last Updated: 02/08/2021" - ] - }, - { - "cell_type": "code", - "execution_count": 30, - "metadata": {}, - "outputs": [], - "source": [ - "import os\n", - "from fnmatch import fnmatch\n", - "\n", - "import numpy as np\n", - "import pandas as pd\n", - "import ruamel_yaml as ry\n", - "\n", - "import matplotlib.pyplot as plt\n", - "\n", - "from weis.aeroelasticse import FileTools\n", - "\n", - "rpm2RadSec = 2.0*(np.pi)/60.0\n", - "\n", - "\n", - "from pCrunch import LoadsAnalysis, PowerProduction, FatigueParams\n", - "from pCrunch.io import load_FAST_out\n", - "from pCrunch.utility import save_yaml, get_windspeeds, convert_summary_stats\n", - "\n", - "def valid_extension(fp):\n", - " return any([fnmatch(fp, ext) for ext in [\"*.outb\", \"*.out\"]])" - ] - }, - { - "cell_type": "code", - "execution_count": 3, - "metadata": {}, - "outputs": [ - { - "data": { - "text/html": [ - "
\n", - "\n", - "\n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - "
(AeroDyn15, AFAeroMod)(AeroDyn15, AIDrag)(AeroDyn15, HubLoss)(AeroDyn15, IndToler)(AeroDyn15, MaxIter)(AeroDyn15, SkewMod)(AeroDyn15, TIDrag)(AeroDyn15, TanInd)(AeroDyn15, TipLoss)(AeroDyn15, TwrAero)...(ServoDyn, GenTiStp)(ServoDyn, GenTiStr)(ServoDyn, HSSBrMode)(ServoDyn, PCMode)(ServoDyn, SpdGenOn)(ServoDyn, TimGenOn)(ServoDyn, VSContrl)(ServoDyn, YCMode)Case_IDCase_Name
02TrueTrue0.0000150001TrueTrueTrueFalse...TrueTrue550.00.0550IEA15MW_PRC_00
12TrueTrue0.0000150001TrueTrueTrueFalse...TrueTrue550.00.0551IEA15MW_PRC_01
22TrueTrue0.0000150001TrueTrueTrueFalse...TrueTrue550.00.0552IEA15MW_PRC_02
32TrueTrue0.0000150001TrueTrueTrueFalse...TrueTrue550.00.0553IEA15MW_PRC_03
42TrueTrue0.0000150001TrueTrueTrueFalse...TrueTrue550.00.0554IEA15MW_PRC_04
52TrueTrue0.0000150001TrueTrueTrueFalse...TrueTrue550.00.0555IEA15MW_PRC_05
62TrueTrue0.0000150001TrueTrueTrueFalse...TrueTrue550.00.0556IEA15MW_PRC_06
72TrueTrue0.0000150001TrueTrueTrueFalse...TrueTrue550.00.0557IEA15MW_PRC_07
82TrueTrue0.0000150001TrueTrueTrueFalse...TrueTrue550.00.0558IEA15MW_PRC_08
92TrueTrue0.0000150001TrueTrueTrueFalse...TrueTrue550.00.0559IEA15MW_PRC_09
102TrueTrue0.0000150001TrueTrueTrueFalse...TrueTrue550.00.05510IEA15MW_PRC_10
112TrueTrue0.0000150001TrueTrueTrueFalse...TrueTrue550.00.05511IEA15MW_PRC_11
122TrueTrue0.0000150001TrueTrueTrueFalse...TrueTrue550.00.05512IEA15MW_PRC_12
132TrueTrue0.0000150001TrueTrueTrueFalse...TrueTrue550.00.05513IEA15MW_PRC_13
142TrueTrue0.0000150001TrueTrueTrueFalse...TrueTrue550.00.05514IEA15MW_PRC_14
152TrueTrue0.0000150001TrueTrueTrueFalse...TrueTrue550.00.05515IEA15MW_PRC_15
\n", - "

16 rows × 142 columns

\n", - "
" - ], - "text/plain": [ - " (AeroDyn15, AFAeroMod) (AeroDyn15, AIDrag) (AeroDyn15, HubLoss) \\\n", - "0 2 True True \n", - "1 2 True True \n", - "2 2 True True \n", - "3 2 True True \n", - "4 2 True True \n", - "5 2 True True \n", - "6 2 True True \n", - "7 2 True True \n", - "8 2 True True \n", - "9 2 True True \n", - "10 2 True True \n", - "11 2 True True \n", - "12 2 True True \n", - "13 2 True True \n", - "14 2 True True \n", - "15 2 True True \n", - "\n", - " (AeroDyn15, IndToler) (AeroDyn15, MaxIter) (AeroDyn15, SkewMod) \\\n", - "0 0.00001 5000 1 \n", - "1 0.00001 5000 1 \n", - "2 0.00001 5000 1 \n", - "3 0.00001 5000 1 \n", - "4 0.00001 5000 1 \n", - "5 0.00001 5000 1 \n", - "6 0.00001 5000 1 \n", - "7 0.00001 5000 1 \n", - "8 0.00001 5000 1 \n", - "9 0.00001 5000 1 \n", - "10 0.00001 5000 1 \n", - "11 0.00001 5000 1 \n", - "12 0.00001 5000 1 \n", - "13 0.00001 5000 1 \n", - "14 0.00001 5000 1 \n", - "15 0.00001 5000 1 \n", - "\n", - " (AeroDyn15, TIDrag) (AeroDyn15, TanInd) (AeroDyn15, TipLoss) \\\n", - "0 True True True \n", - "1 True True True \n", - "2 True True True \n", - "3 True True True \n", - "4 True True True \n", - "5 True True True \n", - "6 True True True \n", - "7 True True True \n", - "8 True True True \n", - "9 True True True \n", - "10 True True True \n", - "11 True True True \n", - "12 True True True \n", - "13 True True True \n", - "14 True True True \n", - "15 True True True \n", - "\n", - " (AeroDyn15, TwrAero) ... (ServoDyn, GenTiStp) (ServoDyn, GenTiStr) \\\n", - "0 False ... True True \n", - "1 False ... True True \n", - "2 False ... True True \n", - "3 False ... True True \n", - "4 False ... True True \n", - "5 False ... True True \n", - "6 False ... True True \n", - "7 False ... True True \n", - "8 False ... True True \n", - "9 False ... True True \n", - "10 False ... True True \n", - "11 False ... True True \n", - "12 False ... True True \n", - "13 False ... True True \n", - "14 False ... True True \n", - "15 False ... True True \n", - "\n", - " (ServoDyn, HSSBrMode) (ServoDyn, PCMode) (ServoDyn, SpdGenOn) \\\n", - "0 5 5 0.0 \n", - "1 5 5 0.0 \n", - "2 5 5 0.0 \n", - "3 5 5 0.0 \n", - "4 5 5 0.0 \n", - "5 5 5 0.0 \n", - "6 5 5 0.0 \n", - "7 5 5 0.0 \n", - "8 5 5 0.0 \n", - "9 5 5 0.0 \n", - "10 5 5 0.0 \n", - "11 5 5 0.0 \n", - "12 5 5 0.0 \n", - "13 5 5 0.0 \n", - "14 5 5 0.0 \n", - "15 5 5 0.0 \n", - "\n", - " (ServoDyn, TimGenOn) (ServoDyn, VSContrl) (ServoDyn, YCMode) Case_ID \\\n", - "0 0.0 5 5 0 \n", - "1 0.0 5 5 1 \n", - "2 0.0 5 5 2 \n", - "3 0.0 5 5 3 \n", - "4 0.0 5 5 4 \n", - "5 0.0 5 5 5 \n", - "6 0.0 5 5 6 \n", - "7 0.0 5 5 7 \n", - "8 0.0 5 5 8 \n", - "9 0.0 5 5 9 \n", - "10 0.0 5 5 10 \n", - "11 0.0 5 5 11 \n", - "12 0.0 5 5 12 \n", - "13 0.0 5 5 13 \n", - "14 0.0 5 5 14 \n", - "15 0.0 5 5 15 \n", - "\n", - " Case_Name \n", - "0 IEA15MW_PRC_00 \n", - "1 IEA15MW_PRC_01 \n", - "2 IEA15MW_PRC_02 \n", - "3 IEA15MW_PRC_03 \n", - "4 IEA15MW_PRC_04 \n", - "5 IEA15MW_PRC_05 \n", - "6 IEA15MW_PRC_06 \n", - "7 IEA15MW_PRC_07 \n", - "8 IEA15MW_PRC_08 \n", - "9 IEA15MW_PRC_09 \n", - "10 IEA15MW_PRC_10 \n", - "11 IEA15MW_PRC_11 \n", - "12 IEA15MW_PRC_12 \n", - "13 IEA15MW_PRC_13 \n", - "14 IEA15MW_PRC_14 \n", - "15 IEA15MW_PRC_15 \n", - "\n", - "[16 rows x 142 columns]" - ] - }, - "execution_count": 3, - "metadata": {}, - "output_type": "execute_result" - } - ], - "source": [ - "\n", - "fname_case_matrix = '/Users/dzalkind/Tools/ROSCO/outputs/PRC_2/IEA15MW_PRC/power_curve/base/case_matrix.yaml'\n", - "cm_dict = FileTools.load_yaml(fname_case_matrix, package=1)\n", - "cnames = []\n", - "for c in list(cm_dict.keys()):\n", - " if isinstance(c,ry.comments.CommentedKeySeq):\n", - " cnames.append(tuple(c))\n", - " else:\n", - " cnames.append(c)\n", - " \n", - "cm = pd.DataFrame(cm_dict, columns=cnames)\n", - "\n", - "if ('DLC','Label') in cm:\n", - " cm[('DLC','Label')].unique()\n", - "\n", - " dlc_inds = {}\n", - "\n", - " for dlc in cm[('DLC','Label')].unique():\n", - " dlc_inds[dlc] = cm[('DLC','Label')] == dlc\n", - " \n", - "cm" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "#### Project Directory" - ] - }, - { - "cell_type": "code", - "execution_count": 5, - "metadata": {}, - "outputs": [ - { - "name": "stdout", - "output_type": "stream", - "text": [ - "Found 16 files.\n" - ] - } - ], - "source": [ - "output_dir = \"/Users/dzalkind/Tools/ROSCO/outputs/PRC_2/IEA15MW_PRC/power_curve/base\"\n", - "# results_dir = os.path.join(output_dir, \"results\")\n", - "# save_results = True\n", - "\n", - "# outfiles = [\n", - "# os.path.join(output_dir, f) for f in os.listdir(output_dir)\n", - "# if valid_extension(f)\n", - "# ]\n", - "\n", - "outfiles = [os.path.join(output_dir,f'IEA15MW_PRC_{i:02d}.out') for i in range(len(cm))]\n", - "\n", - "# iea15mw_04.HD\n", - "\n", - "# /projects/esteyco/dzalkind/02_DLC_02_1661_Wide/rank_0/IEA15_00.out\n", - "\n", - "print(f\"Found {len(outfiles)} files.\")" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "#### Interacting with output files" - ] - }, - { - "cell_type": "code", - "execution_count": 37, - "metadata": {}, - "outputs": [], - "source": [ - "# The new framework provides an object oriented framework to interact with\n", - "# output files. The easiest way to use this is to use the 'load_FAST_out' function.\n", - "\n", - "# load_FAST_out(filenames, tmin=0, tmax=np.inf, cores=1, **kwargs)\n", - "# outputs = load_FAST_out(outfiles,tmin=120,cores=12)\n", - "# outputs" - ] - }, - { - "cell_type": "code", - "execution_count": 20, - "metadata": {}, - "outputs": [ - { - "data": { - "text/plain": [ - "array([10.85912037, 10.77266312, 10.68620682, ..., 13.05524254,\n", - " 13.10151958, 13.14779663])" - ] - }, - "execution_count": 20, - "metadata": {}, - "output_type": "execute_result" - } - ], - "source": [ - "# An instance of 'OpenFASTBinary' (or 'OpenFASTAscii' if applicable) is created.\n", - "# The instance stores the raw data but also provides many useful methods for\n", - "# interacting with the data:\n", - "\n", - "# print(outputs[0].data)\n", - "# print(outputs[0].time)\n", - "# print(outputs[0].channels)\n", - "# print(outputs[0].maxima)\n", - "# print(outputs[0].stddevs)\n", - "\n", - "# Individual channel time series can also be accessed with dict style indexing:\n", - "outputs[0][\"Wind1VelX\"]" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "#### pCrunch Configuration" - ] - }, - { - "cell_type": "code", - "execution_count": 6, - "metadata": {}, - "outputs": [], - "source": [ - "# Channel magnitudes are defined in a dict:\n", - "magnitude_channels = {\n", - " \"RootMc1\": [\"RootMxc1\", \"RootMyc1\", \"RootMzc1\"],\n", - " \"RootMc2\": [\"RootMxc2\", \"RootMyc2\", \"RootMzc2\"],\n", - " \"RootMc3\": [\"RootMxc3\", \"RootMyc3\", \"RootMzc3\"],\n", - "}\n", - "\n", - "# Define channels (and their fatigue slopes) in a dict:\n", - "fatigue_channels = {\n", - " \"RootMc1\": FatigueParams(lifetime=25.0, slope=10.0, ult_stress=6e8),\n", - " \"RootMc2\": FatigueParams(lifetime=25.0, slope=10.0, ult_stress=6e8),\n", - " \"RootMc3\": FatigueParams(lifetime=25.0, slope=10.0, ult_stress=6e8),\n", - "}\n", - "\n", - "# Define channels to save extreme data in a list:\n", - "channel_extremes = [\n", - " \"RotSpeed\",\n", - " \"RotThrust\",\n", - " \"RotTorq\",\n", - " \"RootMc1\",\n", - " \"RootMc2\",\n", - " \"RootMc3\",\n", - "]" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "#### Run pCrunch" - ] - }, - { - "cell_type": "code", - "execution_count": 18, - "metadata": {}, - "outputs": [], - "source": [ - "# The API has changed and is in more of an object oriented framework.\n", - "la = LoadsAnalysis(\n", - " outfiles, # The primary input is a list of output files\n", - " magnitude_channels=magnitude_channels, # All of the following inputs are optional\n", - " fatigue_channels=fatigue_channels, # \n", - " extreme_channels=channel_extremes, #\n", - " trim_data=(120,), # If 'trim_data' is passed, all input files will\n", - ") # be trimmed to (tmin, tmax(optional))\n", - "\n", - "la.process_outputs(cores=8) # Once LoadsAnalysis is configured, process outputs with\n", - " # `process_outputs`. `cores` is optional but will trigger parallel processing if configured" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "#### Outputs" - ] - }, - { - "cell_type": "code", - "execution_count": 32, - "metadata": {}, - "outputs": [ - { - "data": { - "text/plain": [ - "[]" - ] - }, - "execution_count": 32, - "metadata": {}, - "output_type": "execute_result" - }, - { - "data": { - "image/png": "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\n", - "text/plain": [ - "
" - ] - }, - "metadata": { - "needs_background": "light" - }, - "output_type": "display_data" - } - ], - "source": [ - "# The summary stats per each file are here:\n", - "ss = la.summary_stats\n", - "\n", - "ss['GenSpeed']['mean']\n", - "\n", - "chans = ['GenSpeed','TSR','BldPitch1']\n", - "\n", - "ss['TSR']\n", - "ss['TSR'] = ss['RotSpeed']['mean'] * 120 / ss['Wind1VelX']['mean'] * rpm2RadSec\n", - "\n", - "fig, axs = plt.subplots(len(chans),1)\n", - "\n", - "fig.set_size_inches(6,2.5*len(chans))\n", - "\n", - "for i_chan, chan in enumerate(chans):\n", - " \n", - " try:\n", - " axs[i_chan].plot(ss['Wind1VelX']['mean'],ss[chan]['mean'])\n", - " except:\n", - " axs[i_chan].plot(ss['Wind1VelX']['mean'],ss[chan])\n", - " \n", - "\n", - "[a.grid(True) for a in axs]\n", - "\n", - "\n", - "M = np.loadtxt('/Users/dzalkind/Downloads/Megablade_35_sr180_GenEff_control_schedule.txt',delimiter=',')\n", - "\n", - "UU = M[:,0]\n", - "\n", - "rot_speed = M[:,1] * rpm2RadSec\n", - "\n", - "rot_speed\n", - "\n", - "min_pitch = np.deg2rad(M[:,2])\n", - "\n", - "min_pitch\n", - "\n", - "ds = 1\n", - "\n", - "# fig, axs = plt.subplots(2,1)\n", - "\n", - "# axs[0].plot(UU,rot_speed)\n", - "axs[0].plot(UU[::ds],rot_speed[::ds]/ rpm2RadSec)\n", - "# axs[1].plot(UU,min_pitch)\n", - "axs[2].plot(UU[::ds],np.rad2deg(min_pitch[::ds]))\n" - ] - }, - { - "cell_type": "code", - "execution_count": 20, - "metadata": {}, - "outputs": [ - { - "ename": "NameError", - "evalue": "name 'dlc_inds' is not defined", - "output_type": "error", - "traceback": [ - "\u001b[0;31m---------------------------------------------------------------------------\u001b[0m", - "\u001b[0;31mNameError\u001b[0m Traceback (most recent call last)", - "\u001b[0;32m\u001b[0m in \u001b[0;36m\u001b[0;34m\u001b[0m\n\u001b[1;32m 6\u001b[0m \u001b[0;32mfor\u001b[0m \u001b[0mdlc\u001b[0m \u001b[0;32min\u001b[0m \u001b[0mdlcs\u001b[0m\u001b[0;34m:\u001b[0m\u001b[0;34m\u001b[0m\u001b[0;34m\u001b[0m\u001b[0m\n\u001b[1;32m 7\u001b[0m \u001b[0;32mfor\u001b[0m \u001b[0mchan\u001b[0m \u001b[0;32min\u001b[0m \u001b[0mchannels\u001b[0m\u001b[0;34m:\u001b[0m\u001b[0;34m\u001b[0m\u001b[0;34m\u001b[0m\u001b[0m\n\u001b[0;32m----> 8\u001b[0;31m \u001b[0mss_max\u001b[0m \u001b[0;34m=\u001b[0m \u001b[0mss\u001b[0m\u001b[0;34m.\u001b[0m\u001b[0mreset_index\u001b[0m\u001b[0;34m(\u001b[0m\u001b[0;34m)\u001b[0m\u001b[0;34m[\u001b[0m\u001b[0mdlc_inds\u001b[0m\u001b[0;34m[\u001b[0m\u001b[0mdlc\u001b[0m\u001b[0;34m]\u001b[0m\u001b[0;34m]\u001b[0m\u001b[0;34m[\u001b[0m\u001b[0mchan\u001b[0m\u001b[0;34m]\u001b[0m\u001b[0;34m[\u001b[0m\u001b[0;34m'max'\u001b[0m\u001b[0;34m]\u001b[0m\u001b[0;34m\u001b[0m\u001b[0;34m\u001b[0m\u001b[0m\n\u001b[0m\u001b[1;32m 9\u001b[0m \u001b[0mss_min\u001b[0m \u001b[0;34m=\u001b[0m \u001b[0mss\u001b[0m\u001b[0;34m.\u001b[0m\u001b[0mreset_index\u001b[0m\u001b[0;34m(\u001b[0m\u001b[0;34m)\u001b[0m\u001b[0;34m[\u001b[0m\u001b[0mdlc_inds\u001b[0m\u001b[0;34m[\u001b[0m\u001b[0mdlc\u001b[0m\u001b[0;34m]\u001b[0m\u001b[0;34m]\u001b[0m\u001b[0;34m[\u001b[0m\u001b[0mchan\u001b[0m\u001b[0;34m]\u001b[0m\u001b[0;34m[\u001b[0m\u001b[0;34m'min'\u001b[0m\u001b[0;34m]\u001b[0m\u001b[0;34m\u001b[0m\u001b[0;34m\u001b[0m\u001b[0m\n\u001b[1;32m 10\u001b[0m \u001b[0mi_max\u001b[0m \u001b[0;34m=\u001b[0m \u001b[0mss_max\u001b[0m\u001b[0;34m.\u001b[0m\u001b[0margmax\u001b[0m\u001b[0;34m(\u001b[0m\u001b[0;34m)\u001b[0m\u001b[0;34m\u001b[0m\u001b[0;34m\u001b[0m\u001b[0m\n", - "\u001b[0;31mNameError\u001b[0m: name 'dlc_inds' is not defined" - ] - } - ], - "source": [ - "dlcs = ['1.6','6.1']\n", - "# dlcs = ['1.1','1.3','1.4','1.5']\n", - "channels = ['GenSpeed','PtfmSurge', 'PtfmSway', 'PtfmHeave', 'PtfmRoll','PtfmPitch','PtfmYaw']\n", - "\n", - "\n", - "for dlc in dlcs:\n", - " for chan in channels:\n", - " ss_max = ss.reset_index()[dlc_inds[dlc]][chan]['max']\n", - " ss_min = ss.reset_index()[dlc_inds[dlc]][chan]['min']\n", - " i_max = ss_max.argmax()\n", - " i_min = ss_min.argmin()\n", - " print(f\"DLC {dlc}: Max {chan} of {ss_max.max():.3f} in {ss.index[ss_max.index[i_max]]}\")\n", - " print(f\"DLC {dlc}: Min {chan} of {ss_min.min():.3f} in {ss.index[ss_min.index[i_min]]}\")" - ] - }, - { - "cell_type": "code", - "execution_count": 27, - "metadata": {}, - "outputs": [ - { - "data": { - "text/plain": [ - "IEA15MW_PRC_00.out 1\n", - "IEA15MW_PRC_01.out 1\n", - "IEA15MW_PRC_02.out 1\n", - "IEA15MW_PRC_03.out 1\n", - "IEA15MW_PRC_04.out 1\n", - "IEA15MW_PRC_05.out 1\n", - "IEA15MW_PRC_06.out 1\n", - "IEA15MW_PRC_07.out 1\n", - "IEA15MW_PRC_08.out 1\n", - "IEA15MW_PRC_09.out 1\n", - "IEA15MW_PRC_10.out 1\n", - "IEA15MW_PRC_11.out 1\n", - "IEA15MW_PRC_12.out 1\n", - "IEA15MW_PRC_13.out 1\n", - "IEA15MW_PRC_14.out 1\n", - "IEA15MW_PRC_15.out 1\n", - "Name: TSR, dtype: int64" - ] - }, - "execution_count": 27, - "metadata": {}, - "output_type": "execute_result" - } - ], - "source": [ - "ss['TSR'] = 1\n", - "\n", - "ss['TSR']" - ] - }, - { - "cell_type": "code", - "execution_count": 74, - "metadata": {}, - "outputs": [], - "source": [ - "la.summary_stats[(\"Wind1VelX\", 'min')]\n", - "\n", - "10.12/7.56\n", - "\n", - "ss.to_pickle(\"/projects/esteyco/dzalkind/02_DLC_02_1661_NoCW/rank_0/ss_12345.p\")" - ] - }, - { - "cell_type": "code", - "execution_count": 27, - "metadata": {}, - "outputs": [ - { - "data": { - "text/plain": [ - "Wind1VelX min 7.331778e+00\n", - "Wind1VelY min -6.869149e+00\n", - "Wind1VelZ min -4.288182e+00\n", - "Azimuth min 7.724802e-04\n", - "BldPitch1 min 6.118227e+00\n", - " ... \n", - "GenPwr integrated -1.709636e+05\n", - "GenTq integrated 0.000000e+00\n", - "RootMc1 integrated 2.066127e+06\n", - "RootMc2 integrated 6.123670e+06\n", - "RootMc3 integrated 5.847567e+06\n", - "Name: BAR10_0_IEC_13.outb, Length: 1104, dtype: float64" - ] - }, - "execution_count": 27, - "metadata": {}, - "output_type": "execute_result" - } - ], - "source": [ - "# Or by file\n", - "la.summary_stats.loc[\"BAR10_0_IEC_13.outb\"]" - ] - }, - { - "cell_type": "code", - "execution_count": 28, - "metadata": {}, - "outputs": [ - { - "data": { - "text/html": [ - "
\n", - "\n", - "\n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - " \n", - "
RootMc1RootMc2RootMc3
BAR10_0_IEC_13.outb17155.97267218123.88292618975.048930
BAR10_0_IEC_44.outb20769.76053320173.28814820931.456407
BAR10_0_IEC_05.outb12965.95909612840.96246313141.212547
BAR10_0_IEC_29.outb17868.45067617151.79657316319.655247
BAR10_0_IEC_09.outb15761.53147916148.63270616634.678742
\n", - "
" - ], - "text/plain": [ - " RootMc1 RootMc2 RootMc3\n", - "BAR10_0_IEC_13.outb 17155.972672 18123.882926 18975.048930\n", - "BAR10_0_IEC_44.outb 20769.760533 20173.288148 20931.456407\n", - "BAR10_0_IEC_05.outb 12965.959096 12840.962463 13141.212547\n", - "BAR10_0_IEC_29.outb 17868.450676 17151.796573 16319.655247\n", - "BAR10_0_IEC_09.outb 15761.531479 16148.632706 16634.678742" - ] - }, - "execution_count": 28, - "metadata": {}, - "output_type": "execute_result" - } - ], - "source": [ - "# Damage equivalent loads are found here:\n", - "la.DELs" - ] - }, - { - "cell_type": "code", - "execution_count": 31, - "metadata": {}, - "outputs": [ - { - "data": { - "text/plain": [ - "[{'Time': 500.02000000000004,\n", - " 'RotSpeed': 9.196721076965332,\n", - " 'RotThrust': 1832.1434326171875,\n", - " 'RotTorq': 19779.529296875,\n", - " 'RootMc1': 37811.284398457174,\n", - " 'RootMc2': 55838.312057143645,\n", - " 'RootMc3': 50827.68616140148},\n", - " {'Time': 368.26,\n", - " 'RotSpeed': 9.146635055541992,\n", - " 'RotThrust': 1628.4447021484375,\n", - " 'RotTorq': 19790.078125,\n", - " 'RootMc1': 47771.370180076294,\n", - " 'RootMc2': 49087.65189598435,\n", - " 'RootMc3': 48430.43687242791},\n", - " {'Time': 368.72,\n", - " 'RotSpeed': 9.249673843383789,\n", - " 'RotThrust': 2189.477294921875,\n", - " 'RotTorq': 19810.16015625,\n", - " 'RootMc1': 59575.98150937143,\n", - " 'RootMc2': 68240.34957165274,\n", - " 'RootMc3': 52813.63114797467},\n", - " {'Time': 356.36,\n", - " 'RotSpeed': 9.03768539428711,\n", - " 'RotThrust': 1109.2626953125,\n", - " 'RotTorq': 19767.958984375,\n", - " 'RootMc1': 28428.160164204783,\n", - " 'RootMc2': 47520.51453251602,\n", - " 'RootMc3': 26678.213325803477},\n", - " {'Time': 218.85,\n", - " 'RotSpeed': 8.697166442871094,\n", - " 'RotThrust': 1519.8240966796875,\n", - " 'RotTorq': 19807.201171875,\n", - " 'RootMc1': 42921.23490015305,\n", - " 'RootMc2': 26077.389696628106,\n", - " 'RootMc3': 42566.349186912346},\n", - " {'Time': 368.73,\n", - " 'RotSpeed': 8.878805160522461,\n", - " 'RotThrust': 1549.9483642578125,\n", - " 'RotTorq': 19805.7890625,\n", - " 'RootMc1': 31664.332491803867,\n", - " 'RootMc2': 46879.82219401657,\n", - " 'RootMc3': 49487.4606661061},\n", - " {'Time': 519.4,\n", - " 'RotSpeed': 8.663159370422363,\n", - " 'RotThrust': 2036.2601318359375,\n", - " 'RotTorq': 19761.43359375,\n", - " 'RootMc1': 50181.80794211208,\n", - " 'RootMc2': 46826.314080330514,\n", - " 'RootMc3': 49344.15798839514},\n", - " {'Time': 162.29,\n", - " 'RotSpeed': 9.140069961547852,\n", - " 'RotThrust': 1878.1090087890625,\n", - " 'RotTorq': 19773.65234375,\n", - " 'RootMc1': 48787.83397343496,\n", - " 'RootMc2': 52380.788688063425,\n", - " 'RootMc3': 35632.23116383259},\n", - " {'Time': 355.8,\n", - " 'RotSpeed': 9.123079299926758,\n", - " 'RotThrust': 1792.07861328125,\n", - " 'RotTorq': 19774.005859375,\n", - " 'RootMc1': 50532.15050757147,\n", - " 'RootMc2': 43871.60336434941,\n", - " 'RootMc3': 58478.44111155466},\n", - " {'Time': 369.2,\n", - " 'RotSpeed': 9.184767723083496,\n", - " 'RotThrust': 2361.0,\n", - " 'RotTorq': 19795.474609375,\n", - " 'RootMc1': 67171.44060773586,\n", - " 'RootMc2': 64144.0015416387,\n", - " 'RootMc3': 66307.21959893759},\n", - " {'Time': 338.11,\n", - " 'RotSpeed': 9.081233024597168,\n", - " 'RotThrust': 1432.0780029296875,\n", - " 'RotTorq': 19794.19921875,\n", - " 'RootMc1': 44348.38533282857,\n", - " 'RootMc2': 35461.39568142322,\n", - " 'RootMc3': 35720.97401760876},\n", - " {'Time': 309.57,\n", - " 'RotSpeed': 8.808978080749512,\n", - " 'RotThrust': 1784.7720947265625,\n", - " 'RotTorq': 19794.677734375,\n", - " 'RootMc1': 51039.595345969086,\n", - " 'RootMc2': 33415.46799670461,\n", - " 'RootMc3': 49962.997862840064},\n", - " {'Time': 432.16,\n", - " 'RotSpeed': 8.889041900634766,\n", - " 'RotThrust': 1938.8626708984375,\n", - " 'RotTorq': 19759.9765625,\n", - " 'RootMc1': 50439.551159886076,\n", - " 'RootMc2': 59261.815251303284,\n", - " 'RootMc3': 39933.391602874246},\n", - " {'Time': 592.33,\n", - " 'RotSpeed': 9.256232261657715,\n", - " 'RotThrust': 2138.162841796875,\n", - " 'RotTorq': 19770.294921875,\n", - " 'RootMc1': 47760.279101389024,\n", - " 'RootMc2': 56772.73864663361,\n", - " 'RootMc3': 49697.389655866646},\n", - " {'Time': 140.01,\n", - " 'RotSpeed': 8.930659294128418,\n", - " 'RotThrust': 2355.755615234375,\n", - " 'RotTorq': 19798.275390625,\n", - " 'RootMc1': 55682.92431117121,\n", - " 'RootMc2': 54641.07015748553,\n", - " 'RootMc3': 77077.90317607606},\n", - " {'Time': 369.74,\n", - " 'RotSpeed': 10.078149795532227,\n", - " 'RotThrust': 2048.104736328125,\n", - " 'RotTorq': 19784.431640625,\n", - " 'RootMc1': 63686.819849083135,\n", - " 'RootMc2': 62722.78466291298,\n", - " 'RootMc3': 42559.807718172815},\n", - " {'Time': 145.98,\n", - " 'RotSpeed': 9.945197105407715,\n", - " 'RotThrust': 1736.0693359375,\n", - " 'RotTorq': 19766.533203125,\n", - " 'RootMc1': 57107.34525097212,\n", - " 'RootMc2': 20899.90533129373,\n", - " 'RootMc3': 44866.49202475942},\n", - " {'Time': 370.05,\n", - " 'RotSpeed': 9.10218334197998,\n", - " 'RotThrust': 2219.190185546875,\n", - " 'RotTorq': 19780.0625,\n", - " 'RootMc1': 57215.6716968554,\n", - " 'RootMc2': 62357.436171842215,\n", - " 'RootMc3': 61932.423372583435},\n", - " {'Time': 362.19,\n", - " 'RotSpeed': 1.0845158100128174,\n", - " 'RotThrust': -269.979248046875,\n", - " 'RotTorq': 24.871183395385742,\n", - " 'RootMc1': 58010.374504584404,\n", - " 'RootMc2': 73026.87023199385,\n", - " 'RootMc3': 11501.542745264986},\n", - " {'Time': 319.56,\n", - " 'RotSpeed': 2.1253559589385986,\n", - " 'RotThrust': 886.7853393554688,\n", - " 'RotTorq': -47.52824020385742,\n", - " 'RootMc1': 88873.58411735375,\n", - " 'RootMc2': 137240.6447854445,\n", - " 'RootMc3': 92696.27588271046},\n", - " {'Time': 532.14,\n", - " 'RotSpeed': 1.512349009513855,\n", - " 'RotThrust': -536.5031127929688,\n", - " 'RotTorq': -9.38508415222168,\n", - " 'RootMc1': 141657.0715266282,\n", - " 'RootMc2': 202748.90347223374,\n", - " 'RootMc3': 44464.73157894751},\n", - " {'Time': 548.21,\n", - " 'RotSpeed': 2.2312963008880615,\n", - " 'RotThrust': 443.90032958984375,\n", - " 'RotTorq': -3.8658337593078613,\n", - " 'RootMc1': 117455.15330477503,\n", - " 'RootMc2': 138826.02250426452,\n", - " 'RootMc3': 59169.92360525166},\n", - " {'Time': 363.38,\n", - " 'RotSpeed': 0.9708657264709473,\n", - " 'RotThrust': -1625.6156005859375,\n", - " 'RotTorq': -82.18456268310547,\n", - " 'RootMc1': 66760.709080843,\n", - " 'RootMc2': 106385.45271373939,\n", - " 'RootMc3': 92546.23548581263},\n", - " {'Time': 485.56,\n", - " 'RotSpeed': 2.1143946647644043,\n", - " 'RotThrust': 380.2807312011719,\n", - " 'RotTorq': 29.63134002685547,\n", - " 'RootMc1': 140224.03452825797,\n", - " 'RootMc2': 81751.8429490026,\n", - " 'RootMc3': 69690.85356305895},\n", - " {'Time': 580.13,\n", - " 'RotSpeed': 0.7789886593818665,\n", - " 'RotThrust': -1370.467529296875,\n", - " 'RotTorq': -104.5961685180664,\n", - " 'RootMc1': 37763.97319287498,\n", - " 'RootMc2': 70996.03458713405,\n", - " 'RootMc3': 87349.31356127908},\n", - " {'Time': 337.62,\n", - " 'RotSpeed': 2.252070665359497,\n", - " 'RotThrust': 80.88116455078125,\n", - " 'RotTorq': 49.50742721557617,\n", - " 'RootMc1': 102552.94313450111,\n", - " 'RootMc2': 18707.17113997944,\n", - " 'RootMc3': 83043.64130492897},\n", - " {'Time': 285.72,\n", - " 'RotSpeed': 1.4705394506454468,\n", - " 'RotThrust': -406.57525634765625,\n", - " 'RotTorq': 38.92527389526367,\n", - " 'RootMc1': 138110.54053477198,\n", - " 'RootMc2': 169304.80340388033,\n", - " 'RootMc3': 20140.25049010069},\n", - " {'Time': 717.8100000000001,\n", - " 'RotSpeed': 2.0292696952819824,\n", - " 'RotThrust': 411.42730712890625,\n", - " 'RotTorq': 14.589661598205566,\n", - " 'RootMc1': 62275.418866609376,\n", - " 'RootMc2': 147978.99754989002,\n", - " 'RootMc3': 114591.73863847277},\n", - " {'Time': 362.15000000000003,\n", - " 'RotSpeed': 1.5603829622268677,\n", - " 'RotThrust': 383.2719421386719,\n", - " 'RotTorq': -26.811803817749023,\n", - " 'RootMc1': 140662.91704337584,\n", - " 'RootMc2': 145032.08913958006,\n", - " 'RootMc3': 13956.956830886636},\n", - " {'Time': 683.59,\n", - " 'RotSpeed': 2.178495168685913,\n", - " 'RotThrust': 912.2911987304688,\n", - " 'RotTorq': -19.01127815246582,\n", - " 'RootMc1': 147077.7607709096,\n", - " 'RootMc2': 150881.86301316196,\n", - " 'RootMc3': 9552.38511948408},\n", - " {'Time': 371.35,\n", - " 'RotSpeed': 0.8236762285232544,\n", - " 'RotThrust': -972.6253051757812,\n", - " 'RotTorq': 10.888876914978027,\n", - " 'RootMc1': 61334.7989925495,\n", - " 'RootMc2': 73960.80131035403,\n", - " 'RootMc3': 61444.44756566308},\n", - " {'Time': 618.47,\n", - " 'RotSpeed': 2.1806609630584717,\n", - " 'RotThrust': 774.4859008789062,\n", - " 'RotTorq': -72.732666015625,\n", - " 'RootMc1': 56086.918586787964,\n", - " 'RootMc2': 116335.34531937476,\n", - " 'RootMc3': 156844.60812533938},\n", - " {'Time': 120.49000000000001,\n", - " 'RotSpeed': 1.4905682802200317,\n", - " 'RotThrust': -616.0191040039062,\n", - " 'RotTorq': -27.170148849487305,\n", - " 'RootMc1': 101656.89432714453,\n", - " 'RootMc2': 197091.84231484696,\n", - " 'RootMc3': 64010.11036702907},\n", - " {'Time': 502.17,\n", - " 'RotSpeed': 2.140622615814209,\n", - " 'RotThrust': 1057.51123046875,\n", - " 'RotTorq': -17.38741111755371,\n", - " 'RootMc1': 124323.0448939255,\n", - " 'RootMc2': 107238.89330603335,\n", - " 'RootMc3': 65575.35210504149},\n", - " {'Time': 542.19,\n", - " 'RotSpeed': 1.6982858180999756,\n", - " 'RotThrust': -339.0162658691406,\n", - " 'RotTorq': -26.61520767211914,\n", - " 'RootMc1': 139250.58071381506,\n", - " 'RootMc2': 191552.23033279885,\n", - " 'RootMc3': 37391.675248771586},\n", - " {'Time': 445.43,\n", - " 'RotSpeed': 2.012869119644165,\n", - " 'RotThrust': 960.855712890625,\n", - " 'RotTorq': -10.877129554748535,\n", - " 'RootMc1': 76787.92778794201,\n", - " 'RootMc2': 151362.73517860894,\n", - " 'RootMc3': 81804.42068809773},\n", - " {'Time': 363.47,\n", - " 'RotSpeed': 1.694690227508545,\n", - " 'RotThrust': -263.94842529296875,\n", - " 'RotTorq': -25.910903930664062,\n", - " 'RootMc1': 156963.48160764077,\n", - " 'RootMc2': 201551.08178892208,\n", - " 'RootMc3': 30926.970226574063},\n", - " {'Time': 641.34,\n", - " 'RotSpeed': 2.2814862728118896,\n", - " 'RotThrust': 653.01904296875,\n", - " 'RotTorq': 8.365302085876465,\n", - " 'RootMc1': 73873.17661947786,\n", - " 'RootMc2': 115032.19736012808,\n", - " 'RootMc3': 47605.537551260524},\n", - " {'Time': 220.67000000000002,\n", - " 'RotSpeed': 1.4255976676940918,\n", - " 'RotThrust': -37.78099822998047,\n", - " 'RotTorq': -70.7003402709961,\n", - " 'RootMc1': 86367.87757851247,\n", - " 'RootMc2': 159911.237938548,\n", - " 'RootMc3': 44026.22219167016},\n", - " {'Time': 322.40000000000003,\n", - " 'RotSpeed': 2.4135708808898926,\n", - " 'RotThrust': 1031.006103515625,\n", - " 'RotTorq': 3.167031764984131,\n", - " 'RootMc1': 117889.61765603493,\n", - " 'RootMc2': 93103.18101157891,\n", - " 'RootMc3': 176108.7206103024},\n", - " {'Time': 361.51,\n", - " 'RotSpeed': 1.502587080001831,\n", - " 'RotThrust': 201.8974151611328,\n", - " 'RotTorq': -3.726184368133545,\n", - " 'RootMc1': 144257.25669438674,\n", - " 'RootMc2': 158737.3617287686,\n", - " 'RootMc3': 29712.876836581345},\n", - " {'Time': 230.48000000000002,\n", - " 'RotSpeed': 2.0762851238250732,\n", - " 'RotThrust': 616.7235717773438,\n", - " 'RotTorq': 13.007423400878906,\n", - " 'RootMc1': 85186.64284667293,\n", - " 'RootMc2': 60036.467439487365,\n", - " 'RootMc3': 120489.81542490129},\n", - " {'Time': 360.99,\n", - " 'RotSpeed': 0.9616844058036804,\n", - " 'RotThrust': -1982.93603515625,\n", - " 'RotTorq': -81.02360534667969,\n", - " 'RootMc1': 59232.840667935176,\n", - " 'RootMc2': 78363.49722922806,\n", - " 'RootMc3': 107098.33420801},\n", - " {'Time': 611.25,\n", - " 'RotSpeed': 2.174319267272949,\n", - " 'RotThrust': 260.4977111816406,\n", - " 'RotTorq': -55.35261535644531,\n", - " 'RootMc1': 79280.41142281189,\n", - " 'RootMc2': 134543.36444773452,\n", - " 'RootMc3': 52657.85305474285},\n", - " {'Time': 361.63,\n", - " 'RotSpeed': 1.5833404064178467,\n", - " 'RotThrust': 74.41678619384766,\n", - " 'RotTorq': -1.6260857582092285,\n", - " 'RootMc1': 149049.1875939595,\n", - " 'RootMc2': 162782.64032074402,\n", - " 'RootMc3': 6944.901395886403},\n", - " {'Time': 179.27,\n", - " 'RotSpeed': 2.2349133491516113,\n", - " 'RotThrust': -637.0066528320312,\n", - " 'RotTorq': 26.083894729614258,\n", - " 'RootMc1': 68581.21306145628,\n", - " 'RootMc2': 67944.18234472333,\n", - " 'RootMc3': 79204.42921220326},\n", - " {'Time': 404.95,\n", - " 'RotSpeed': 1.5384154319763184,\n", - " 'RotThrust': -563.662353515625,\n", - " 'RotTorq': 40.3087043762207,\n", - " 'RootMc1': 85467.41996643576,\n", - " 'RootMc2': 180404.66875909013,\n", - " 'RootMc3': 70676.94690953195},\n", - " {'Time': 328.27,\n", - " 'RotSpeed': 1.944204568862915,\n", - " 'RotThrust': 399.10626220703125,\n", - " 'RotTorq': 20.774803161621094,\n", - " 'RootMc1': 49517.814015380696,\n", - " 'RootMc2': 115720.86150516325,\n", - " 'RootMc3': 99227.4960413297},\n", - " {'Time': 149.69,\n", - " 'RotSpeed': 1.5412728786468506,\n", - " 'RotThrust': -666.01953125,\n", - " 'RotTorq': 9.556767463684082,\n", - " 'RootMc1': 93277.69348175765,\n", - " 'RootMc2': 216225.14492550617,\n", - " 'RootMc3': 80878.64989207157},\n", - " {'Time': 599.0500000000001,\n", - " 'RotSpeed': 2.1643471717834473,\n", - " 'RotThrust': 1036.2357177734375,\n", - " 'RotTorq': -21.235111236572266,\n", - " 'RootMc1': 122089.35121634079,\n", - " 'RootMc2': 64029.00067137171,\n", - " 'RootMc3': 128470.74237645337},\n", - " {'Time': 539.88,\n", - " 'RotSpeed': 1.6076937913894653,\n", - " 'RotThrust': -771.647705078125,\n", - " 'RotTorq': -2.1965253353118896,\n", - " 'RootMc1': 137707.8663385115,\n", - " 'RootMc2': 207889.32578990934,\n", - " 'RootMc3': 46489.91055183886},\n", - " {'Time': 352.39,\n", - " 'RotSpeed': 2.3288607597351074,\n", - " 'RotThrust': 395.71697998046875,\n", - " 'RotTorq': 30.873764038085938,\n", - " 'RootMc1': 136270.11608488843,\n", - " 'RootMc2': 67387.69824493826,\n", - " 'RootMc3': 187807.69514581264},\n", - " {'Time': 375.34000000000003,\n", - " 'RotSpeed': 0.8010825514793396,\n", - " 'RotThrust': -243.02584838867188,\n", - " 'RotTorq': -0.4656263589859009,\n", - " 'RootMc1': 36891.37271612412,\n", - " 'RootMc2': 55038.42409595816,\n", - " 'RootMc3': 31419.79685091404},\n", - " {'Time': 510.97,\n", - " 'RotSpeed': 2.042186737060547,\n", - " 'RotThrust': 608.8619995117188,\n", - " 'RotTorq': -51.640777587890625,\n", - " 'RootMc1': 110874.1808363096,\n", - " 'RootMc2': 48979.6837848612,\n", - " 'RootMc3': 110748.08654790567}]" - ] - }, - "execution_count": 31, - "metadata": {}, - "output_type": "execute_result" - } - ], - "source": [ - "# Extreme events:\n", - "la.extreme_events['RotSpeed']" - ] - }, - { - "cell_type": "code", - "execution_count": null, - "metadata": {}, - "outputs": [], - "source": [] - } - ], - "metadata": { - "kernelspec": { - "display_name": "weis-env4", - "language": "python", - "name": "weis-env4" - }, - "language_info": { - "codemirror_mode": { - "name": "ipython", - "version": 3 - }, - "file_extension": ".py", - "mimetype": "text/x-python", - "name": "python", - "nbconvert_exporter": "python", - "pygments_lexer": "ipython3", - "version": "3.8.10" - } - }, - "nbformat": 4, - "nbformat_minor": 4 -} From 2c76747fa131c950b5a60c6a064f664a3a88b464 Mon Sep 17 00:00:00 2001 From: dzalkind <65573423+dzalkind@users.noreply.github.com> Date: Fri, 6 Oct 2023 09:21:49 -0600 Subject: [PATCH 123/224] Increase max file unit (#253) * Add back open loop yaw rate control * Check OL outputs in example * Update CI to use mamba, first attempt * Install extras when environment first set up * Remove potential libpython typo * Remove more potential typos * Use mamba in compile, too * Use environment.yml file * Remove conda installs from rosco-compile * Clean up CI scripts * Update BAR_10_InflowFile.dat added VelInterpCubic and LiDAR Parameters to the InflowFile * Update IEA-15-240-RWT_InflowFile.dat added VelInterpCubic and LiDAR Parameters to the InflowFile * Update NRELOffshrBsline5MW_InflowWind.dat added VelInterpCubic and LiDAR Parameters to the InflowFile * Update BAR_10_InflowFile.dat added VelInterpCubic and LiDAR Parameters to the InflowFile * Update NREL-2p8-127_InflowFile.dat added VelInterpCubic and LiDAR Parameters to the InflowFile * Update NREL-2p8-127_InflowFile.dat added VelInterpCubic and LiDAR Parameters to the InflowFile * Update IEA-15-240-RWT_InflowFile.dat added VelInterpCubic and LiDAR Parameters to the InflowFile * Update NRELOffshrBsline5MW_InflowWind.dat added VelInterpCubic and LiDAR Parameters to the InflowFile * Update NREL-2p8-127_InflowFile.dat added VelInterpCubic and LiDAR Parameters to the InflowFile * Update StC-Force-Col1.dat adjusted comment on StC_DOF_MODE * Update StC-Force-Col2.dat adjusted comment on StC_DOF_MODE * Update StC-Force-Col3.dat adjusted comment on StC_DOF_MODE * Update FAST_reader.py added parsing of cubic interpolation for velocity and LIDAR parameters in read_InflowWind method for the InflowWind data file * Update FAST_writer.py added writing of cubic interpolation for velocity and LIDAR parameters in write_InflowWind method for the InflowWind data file * Update mamba install in CI * Remove petsc and mpi * Revert CI back to conda * Sync FAST_reader/writer with WEIS versions * Increment openfast version in CI * Add nodes to FAST_vars_out * Add nodes to vartree * Remove duplicated F_NotchType check * Sync FAST_vars_out more * Add MoorDyn outlist params to FstOutput * Increase max unit, number of allowed open files * Close debug files * Remove numpy from DISCON_dict * Ensure a new-ish version of WISDEM is being used Part of effort to transition to yaml install of conda environment * Remove numpy from DISCON_dict * Add open loop control of StCs * Remove numpy from read_DISCON * Add struct control example to CI * Revert unnecessary changes --------- Co-authored-by: Rudy <107142607+Yuksel-Rudy@users.noreply.github.com> --- ROSCO/rosco_registry/write_registry.py | 11 +++++++++-- ROSCO/src/ROSCO_Helpers.f90 | 7 +++++-- ROSCO/src/ROSCO_IO.f90 | 10 ++++++++-- 3 files changed, 22 insertions(+), 6 deletions(-) diff --git a/ROSCO/rosco_registry/write_registry.py b/ROSCO/rosco_registry/write_registry.py index db9d7ad7..eeaa38a8 100644 --- a/ROSCO/rosco_registry/write_registry.py +++ b/ROSCO/rosco_registry/write_registry.py @@ -358,11 +358,11 @@ def write_roscoio(yfile): file.write(f' FmtDat = "(F20.5,TR5,{n_lv_outputs}(ES20.5E2,TR5:))" ! The format of the debugging data\n') file.write(" IF ( MOD(LocalVar%n_DT, CntrPar%n_DT_Out) == 0) THEN\n") file.write(" IF(CntrPar%LoggingLevel > 0) THEN\n") - file.write(" WRITE (UnDb, FmtDat) LocalVar%Time, DebugOutData\n") + file.write(" WRITE (UnDb, TRIM(FmtDat)) LocalVar%Time, DebugOutData\n") file.write(" END IF\n") file.write("\n") file.write(" IF(CntrPar%LoggingLevel > 1) THEN\n") - file.write(" WRITE (UnDb2, FmtDat) LocalVar%Time, LocalVarOutData\n") + file.write(" WRITE (UnDb2, TRIM(FmtDat)) LocalVar%Time, LocalVarOutData\n") file.write(" END IF\n") file.write("\n") file.write(" IF(CntrPar%LoggingLevel > 2) THEN\n") @@ -370,6 +370,13 @@ def write_roscoio(yfile): file.write(" END IF\n") file.write(" END IF\n") file.write("\n") + file.write(" ! Close all files when simulation finished\n") + file.write(" IF (LocalVar%iStatus < 0) THEN\n") + file.write(" CLOSE(UnDb)\n") + file.write(" CLOSE(UnDb2)\n") + file.write(" CLOSE(UnDb3)\n") + file.write(" ENDIF\n") + file.write("END SUBROUTINE Debug\n") file.write("\n") file.write("END MODULE ROSCO_IO") diff --git a/ROSCO/src/ROSCO_Helpers.f90 b/ROSCO/src/ROSCO_Helpers.f90 index 7bca4c93..1b0f1c70 100644 --- a/ROSCO/src/ROSCO_Helpers.f90 +++ b/ROSCO/src/ROSCO_Helpers.f90 @@ -1493,8 +1493,11 @@ SUBROUTINE GetNewUnit ( UnIn, ErrVar ) INTEGER :: Un ! Unit number LOGICAL :: Opened ! Flag indicating whether or not a file is opened. INTEGER(IntKi), PARAMETER :: StartUnit = 10 ! Starting unit number to check (numbers less than 10 reserved) - INTEGER(IntKi), PARAMETER :: MaxUnit = 99 ! The maximum unit number available (or 10 less than the number of files you want to have open at a time) - + ! NOTE: maximum unit numbers in fortran 90 and later is 2**31-1. However, there are limits within the OS. + ! macos -- 256 (change with ulimit -n) + ! linux -- 1024 (change with ulimit -n) + ! windows -- 512 (not sure how to change -- ADP) + INTEGER(IntKi), PARAMETER :: MaxUnit = 1024 ! The maximum unit number available (or 10 less than the number of files you want to have open at a time) ! Initialize subroutine outputs diff --git a/ROSCO/src/ROSCO_IO.f90 b/ROSCO/src/ROSCO_IO.f90 index adac7c34..1b4e2c4c 100644 --- a/ROSCO/src/ROSCO_IO.f90 +++ b/ROSCO/src/ROSCO_IO.f90 @@ -870,11 +870,11 @@ SUBROUTINE Debug(LocalVar, CntrPar, DebugVar, ErrVar, avrSWAP, RootName, size_av FmtDat = "(F20.5,TR5,112(ES20.5E2,TR5:))" ! The format of the debugging data IF ( MOD(LocalVar%n_DT, CntrPar%n_DT_Out) == 0) THEN IF(CntrPar%LoggingLevel > 0) THEN - WRITE (UnDb, FmtDat) LocalVar%Time, DebugOutData + WRITE (UnDb, TRIM(FmtDat)) LocalVar%Time, DebugOutData END IF IF(CntrPar%LoggingLevel > 1) THEN - WRITE (UnDb2, FmtDat) LocalVar%Time, LocalVarOutData + WRITE (UnDb2, TRIM(FmtDat)) LocalVar%Time, LocalVarOutData END IF IF(CntrPar%LoggingLevel > 2) THEN @@ -882,6 +882,12 @@ SUBROUTINE Debug(LocalVar, CntrPar, DebugVar, ErrVar, avrSWAP, RootName, size_av END IF END IF + ! Close all files when simulation finished + IF (LocalVar%iStatus < 0) THEN + CLOSE(UnDb) + CLOSE(UnDb2) + CLOSE(UnDb3) + ENDIF END SUBROUTINE Debug END MODULE ROSCO_IO \ No newline at end of file From b66cd11701359c83ee905861ef6ad6d54843518f Mon Sep 17 00:00:00 2001 From: Regis Thedin Date: Tue, 17 Oct 2023 10:19:56 -0600 Subject: [PATCH 124/224] Add types to scalars (#264) * Add missing types to scalars * Add mamba option for when CI is slow * Skip mac for now * Add mamba option to pytools, too * Try macos with Mambaforge * Use mamba for pytools * Use mamba for examples * Use mamba for testing --------- Co-authored-by: dzalkind --- .github/workflows/CI_rosco-compile.yml | 15 ++++++---- .github/workflows/CI_rosco-pytools.yml | 41 ++++++++++++++++++-------- ROSCO/src/Controllers.f90 | 4 +-- 3 files changed, 40 insertions(+), 20 deletions(-) diff --git a/.github/workflows/CI_rosco-compile.yml b/.github/workflows/CI_rosco-compile.yml index 3e4e70c3..26d1fdd4 100644 --- a/.github/workflows/CI_rosco-compile.yml +++ b/.github/workflows/CI_rosco-compile.yml @@ -15,21 +15,26 @@ jobs: strategy: fail-fast: true matrix: - os: ["ubuntu-latest", "macOS-latest", "windows-latest"] + os: ["ubuntu-latest", "windows-latest" , "macOS-latest"] python-version: ["3.9"] steps: - name: Checkout repository uses: actions/checkout@v3 - - name: Setup environment + - name: Install conda/mamba uses: conda-incubator/setup-miniconda@v2 + # https://github.com/marketplace/actions/setup-miniconda with: - miniconda-version: "latest" - channels: conda-forge, general + # To use mamba, uncomment here, comment out the miniforge line + mamba-version: "*" + # miniforge-version: "latest" auto-update-conda: true - python-version: 3.9 + python-version: ${{ matrix.python-version }} environment-file: environment.yml + activate-environment: test + auto-activate-base: false + miniforge-variant: Mambaforge # Install ROSCO toolbox - name: Install ROSCO toolbox diff --git a/.github/workflows/CI_rosco-pytools.yml b/.github/workflows/CI_rosco-pytools.yml index 178bc730..76bc5e21 100644 --- a/.github/workflows/CI_rosco-pytools.yml +++ b/.github/workflows/CI_rosco-pytools.yml @@ -15,7 +15,7 @@ jobs: strategy: fail-fast: true matrix: - os: ["ubuntu-latest", "macOS-latest", "windows-latest"] + os: ["ubuntu-latest", "windows-latest", "macOS-latest"] python-version: ["3.9"] defaults: run: @@ -27,14 +27,19 @@ jobs: with: submodules: recursive - - name: Setup environment + - name: Install conda/mamba uses: conda-incubator/setup-miniconda@v2 + # https://github.com/marketplace/actions/setup-miniconda with: - miniconda-version: "latest" - channels: conda-forge, general + # To use mamba, uncomment here, comment out the miniforge line + mamba-version: "*" + # miniforge-version: "latest" auto-update-conda: true - python-version: 3.9 + python-version: ${{ matrix.python-version }} environment-file: environment.yml + activate-environment: test + auto-activate-base: false + miniforge-variant: Mambaforge # Install dependencies of ROSCO toolbox @@ -83,14 +88,19 @@ jobs: with: submodules: recursive - - name: Setup environment + - name: Install conda/mamba uses: conda-incubator/setup-miniconda@v2 + # https://github.com/marketplace/actions/setup-miniconda with: - miniconda-version: "latest" - channels: conda-forge, general + # To use mamba, uncomment here, comment out the miniforge line + mamba-version: "*" + # miniforge-version: "latest" auto-update-conda: true - python-version: 3.9 + python-version: ${{ matrix.python-version }} environment-file: environment.yml + activate-environment: test + auto-activate-base: false + miniforge-variant: Mambaforge # setup cmake - name: Setup Workspace @@ -170,14 +180,19 @@ jobs: with: submodules: recursive - - name: Setup environment + - name: Install conda/mamba uses: conda-incubator/setup-miniconda@v2 + # https://github.com/marketplace/actions/setup-miniconda with: - miniconda-version: "latest" - channels: conda-forge, general + # To use mamba, uncomment here, comment out the miniforge line + mamba-version: "*" + # miniforge-version: "latest" auto-update-conda: true - python-version: 3.9 + python-version: ${{ matrix.python-version }} environment-file: environment.yml + activate-environment: test + auto-activate-base: false + miniforge-variant: Mambaforge # Install dependencies of ROSCO toolbox diff --git a/ROSCO/src/Controllers.f90 b/ROSCO/src/Controllers.f90 index deca2d45..0920aca1 100644 --- a/ROSCO/src/Controllers.f90 +++ b/ROSCO/src/Controllers.f90 @@ -704,7 +704,7 @@ SUBROUTINE ActiveWakeControl(CntrPar, LocalVar, DebugVar) IF (CntrPar%AWC_NumModes == 1) THEN AWC_TiltYaw(2) = PI/180*CntrPar%AWC_amp(1)*cos(LocalVar%Time*2*PI*CntrPar%AWC_freq(1) + 2*CntrPar%AWC_clockangle(1)*PI/180) ENDIF - CALL ColemanTransformInverse(AWC_TiltYaw(1), AWC_TiltYaw(2), LocalVar%Azimuth, CntrPar%AWC_harmonic(Imode), 0.0, AWC_angle) + CALL ColemanTransformInverse(AWC_TiltYaw(1), AWC_TiltYaw(2), LocalVar%Azimuth, CntrPar%AWC_harmonic(Imode), REAL(0.0,DbKi), AWC_angle) DO K = 1,LocalVar%NumBl ! Loop through all blades, apply AWC_angle LocalVar%PitCom(K) = LocalVar%PitCom(K) + AWC_angle(K) @@ -775,7 +775,7 @@ SUBROUTINE CableControl(avrSWAP, CntrPar, LocalVar, objInst, ErrVar) DO I_GROUP = 1, CntrPar%CC_Group_N ! Get Actuated deltaL - LocalVar%CC_ActuatedDL(I_GROUP) = SecLPFilter_Vel(LocalVar%CC_DesiredL(I_GROUP),LocalVar%DT,2*PI/CntrPar%CC_ActTau,1.0, & + LocalVar%CC_ActuatedDL(I_GROUP) = SecLPFilter_Vel(LocalVar%CC_DesiredL(I_GROUP),LocalVar%DT,2*PI/CntrPar%CC_ActTau,REAL(1.0,DbKi), & LocalVar%FP,LocalVar%iStatus,LocalVar%restart,objInst%instSecLPFV) ! Integrate From 0e800947d8044728ef34488a86aca81ab68e6474 Mon Sep 17 00:00:00 2001 From: dzalkind <65573423+dzalkind@users.noreply.github.com> Date: Tue, 17 Oct 2023 10:39:57 -0600 Subject: [PATCH 125/224] Update api_change.rst formatting --- docs/source/api_change.rst | 96 ++++++++++++++++++++------------------ 1 file changed, 51 insertions(+), 45 deletions(-) diff --git a/docs/source/api_change.rst b/docs/source/api_change.rst index 6bde8d85..cca1b010 100644 --- a/docs/source/api_change.rst +++ b/docs/source/api_change.rst @@ -11,60 +11,66 @@ Thus, be sure to implement each in order so that subsequent line numbers are cor 2.8.0 to develop ------------------------------- -Gain scheduling of floating feedback -- The floating feedback gain can be scheduled on the low pass filtered wind speed signal. Note that Fl_Kp can now be an array. -- Control all three blade pitch inputs in open loop -- Rotor position control of azimuth position with PID (RP_Gains) control inputs +**Gain scheduling of floating feedback** -New torque control mode settings -- VS_ControlMode determines how the generator speed set point is determined: using the WSE or (P/K)^(1/3) -- VS_ConstPower determines whether constant power is used +* The floating feedback gain can be scheduled on the low pass filtered wind speed signal. Note that Fl_Kp can now be an array. +* Control all three blade pitch inputs in open loop +* Rotor position control of azimuth position with PID (RP_Gains) control inputs -Multiple notch filters -- Users can list any number of notch filters and apply them to either the generator speed and/or tower top accelleration signal based on their index +**New torque control mode settings** -Power reference control via generator speed set points -- With this feature, enabled with `PRC_Mode`, a user can prescribe a set of generator speed set points (`PRC_GenSpeeds`) vs. the estimated wind speed (`PRC_WindSpeeds`), which can be used to avoid certain natural frequencies or implement a soft cut-out scheme. -- A low pass filter with frequency `PRC_LPF_Freq` is used to filter the wind speed estimate. A lower value increases the stability of the generator speed reference signal. +* VS_ControlMode determines how the generator speed set point is determined: using the WSE or (P/K)^(1/3) +* VS_ConstPower determines whether constant power is used -====== ================= ====================================================================================================================================================================================================== +**Multiple notch filters** + +* Users can list any number of notch filters and apply them to either the generator speed and/or tower top accelleration signal based on their index + +**Power reference control via generator speed set points** + +* With this feature, enabled with `PRC_Mode`, a user can prescribe a set of generator speed set points (`PRC_GenSpeeds`) vs. the estimated wind speed (`PRC_WindSpeeds`), which can be used to avoid certain natural frequencies or implement a soft cut-out scheme. +* A low pass filter with frequency `PRC_LPF_Freq` is used to filter the wind speed estimate. A lower value increases the stability of the generator speed reference signal. + +====== ======================= =============================================================================================================================================================================================================================================================== Removed in ROSCO develop ----------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- -Line Input Name Example Value -====== ================= ====================================================================================================================================================================================================== -11 F_NotchType 2 ! F_NotchType - Notch on the measured generator speed and/or tower fore-aft motion (for floating) {0: disable, 1: generator speed, 2: tower-top fore-aft motion, 3: generator speed and tower-top fore-aft motion} -35 F_NotchCornerFreq 3.35500 ! F_NotchCornerFreq - Natural frequency of the notch filter, [rad/s] -36 F_NotchBetaNumDen 0.000000 0.250000 ! F_NotchBetaNumDen - Two notch damping values (numerator and denominator, resp) - determines the width and depth of the notch, [-] -====== ================= ====================================================================================================================================================================================================== +------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- +Line Input Name Example Value +====== ======================= =============================================================================================================================================================================================================================================================== +11 F_NotchType 2 ! F_NotchType - Notch on the measured generator speed and/or tower fore-aft motion (for floating) {0: disable, 1: generator speed, 2: tower-top fore-aft motion, 3: generator speed and tower-top fore-aft motion} +35 F_NotchCornerFreq 3.35500 ! F_NotchCornerFreq - Natural frequency of the notch filter, [rad/s] +36 F_NotchBetaNumDen 0.000000 0.250000 ! F_NotchBetaNumDen - Two notch damping values (numerator and denominator, resp) - determines the width and depth of the notch, [-] +====== ======================= =============================================================================================================================================================================================================================================================== -====== ================= ====================================================================================================================================================================================================== +====== ======================= =============================================================================================================================================================================================================================================================== New in ROSCO develop ----------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- -Line Input Name Example Value -====== ================= ====================================================================================================================================================================================================== -13 VS_ConstPower 0 ! VS_ConstPower - Do constant power torque control, where above rated torque varies, 0 for constant torque} -17 PRC_Mode 0 ! PRC_Mode - Power reference tracking mode{0: use standard rotor speed set points, 1: use PRC rotor speed setpoints} -36 F_NumNotchFilts 1 ! F_NumNotchFilts - Number of notch filters placed on sensors -37 F_NotchFreqs 3.3550 ! F_NotchFreqs - Natural frequency of the notch filters. Array with length F_NumNotchFilts -38 F_NotchBetaNum 0.0000 ! F_NotchBetaNum - Damping value of numerator (determines the width of notch). Array with length F_NumNotchFilts, [-] -39 F_NotchBetaDen 0.2500 ! F_NotchBetaDen - Damping value of denominator (determines the depth of notch). Array with length F_NumNotchFilts, [-] -40 F_GenSpdNotch_N 0 ! F_GenSpdNotch_N - Number of notch filters on generator speed -41 F_GenSpdNotch_Ind 0 ! F_GenSpdNotch_Ind - Indices of notch filters on generator speed -42 F_TwrTopNotch_N 1 ! F_TwrTopNotch_N - Number of notch filters on tower top acceleration signal -43 F_TwrTopNotch_Ind 1 ! F_TwrTopNotch_Ind - Indices of notch filters on tower top acceleration signal -90 VS_PwrFiltF 0.3140 ! VS_PwrFiltF - Low pass filter on power used to determine generator speed set point. Only used in VS_ControlMode = 3. -96 PRC_Section !------- POWER REFERENCE TRACKING -------------------------------------- -97 PRC_n 2 ! PRC_n - Number of elements in PRC_WindSpeeds and PRC_GenSpeeds array -98 PRC_LPF_Freq 0.07854 ! PRC_LPF_Freq - Frequency of the low pass filter on the wind speed estimate used to set PRC_GenSpeeds [rad/s] -99 PRC_WindSpeeds 3.0000 25.0000 ! PRC_WindSpeeds - Array of wind speeds used in rotor speed vs. wind speed lookup table [m/s] -100 PRC_GenSpeeds 0.7917 0.7917 ! PRC_GenSpeeds - Array of generator speeds corresponding to PRC_WindSpeeds [rad/s] +------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- +Line Input Name Example Value +====== ======================= =============================================================================================================================================================================================================================================================== +13 VS_ConstPower 0 ! VS_ConstPower - Do constant power torque control, where above rated torque varies, 0 for constant torque} +17 PRC_Mode 0 ! PRC_Mode - Power reference tracking mode{0: use standard rotor speed set points, 1: use PRC rotor speed setpoints} +36 F_NumNotchFilts 1 ! F_NumNotchFilts - Number of notch filters placed on sensors +37 F_NotchFreqs 3.3550 ! F_NotchFreqs - Natural frequency of the notch filters. Array with length F_NumNotchFilts +38 F_NotchBetaNum 0.0000 ! F_NotchBetaNum - Damping value of numerator (determines the width of notch). Array with length F_NumNotchFilts, [-] +39 F_NotchBetaDen 0.2500 ! F_NotchBetaDen - Damping value of denominator (determines the depth of notch). Array with length F_NumNotchFilts, [-] +40 F_GenSpdNotch_N 0 ! F_GenSpdNotch_N - Number of notch filters on generator speed +41 F_GenSpdNotch_Ind 0 ! F_GenSpdNotch_Ind - Indices of notch filters on generator speed +42 F_TwrTopNotch_N 1 ! F_TwrTopNotch_N - Number of notch filters on tower top acceleration signal +43 F_TwrTopNotch_Ind 1 ! F_TwrTopNotch_Ind - Indices of notch filters on tower top acceleration signal +90 VS_PwrFiltF 0.3140 ! VS_PwrFiltF - Low pass filter on power used to determine generator speed set point. Only used in VS_ControlMode = 3. +96 PRC_Section !------- POWER REFERENCE TRACKING -------------------------------------- +97 PRC_n 2 ! PRC_n - Number of elements in PRC_WindSpeeds and PRC_GenSpeeds array +98 PRC_LPF_Freq 0.07854 ! PRC_LPF_Freq - Frequency of the low pass filter on the wind speed estimate used to set PRC_GenSpeeds [rad/s] +99 PRC_WindSpeeds 3.0000 25.0000 ! PRC_WindSpeeds - Array of wind speeds used in rotor speed vs. wind speed lookup table [m/s] +100 PRC_GenSpeeds 0.7917 0.7917 ! PRC_GenSpeeds - Array of generator speeds corresponding to PRC_WindSpeeds [rad/s] 101 Empty Line -140 Fl_n 1 ! Fl_n - Number of Fl_Kp gains in gain scheduling, optional with default of 1 -142 Fl_U 0.0000 ! Fl_U - Wind speeds for scheduling Fl_Kp, optional if Fl_Kp is single value [m/s] -156 Ind_Azimuth 0 ! Ind_Azimuth - The column in OL_Filename that contains the desired azimuth position in rad (used if OL_Mode = 2) -157 RP_Gains 0.0000 0.0000 0.0000 0.0000 ! RP_Gains - PID gains and Tf of derivative for rotor position control (used if OL_Mode = 2) -====== ================= ====================================================================================================================================================================================================== +140 Fl_n 1 ! Fl_n - Number of Fl_Kp gains in gain scheduling, optional with default of 1 +142 Fl_U 0.0000 ! Fl_U - Wind speeds for scheduling Fl_Kp, optional if Fl_Kp is single value [m/s] +156 Ind_Azimuth 0 ! Ind_Azimuth - The column in OL_Filename that contains the desired azimuth position in rad (used if OL_Mode = 2) +157 RP_Gains 0.0000 0.0000 0.0000 0.0000 ! RP_Gains - PID gains and Tf of derivative for rotor position control (used if OL_Mode = 2) +====== ======================= =============================================================================================================================================================================================================================================================== + + ====== ================= ====================================================================================================================================================================================================== Changed in ROSCO develop From f2a624db172bd4b474e7f88b298eaaa8c7e5fe26 Mon Sep 17 00:00:00 2001 From: dzalkind <65573423+dzalkind@users.noreply.github.com> Date: Tue, 17 Oct 2023 10:42:27 -0600 Subject: [PATCH 126/224] Update .readthedocs.yaml with build.os --- .readthedocs.yaml | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/.readthedocs.yaml b/.readthedocs.yaml index ad4f1512..98a7d535 100644 --- a/.readthedocs.yaml +++ b/.readthedocs.yaml @@ -5,6 +5,10 @@ # Required version: 2 +# Add build os (and other options) +build: + os: ubuntu-22.04 + # Build documentation in the docs/ directory with Sphinx sphinx: builder: html From 6f1ccfa3306528b7c741b213638811a353395bf4 Mon Sep 17 00:00:00 2001 From: dzalkind <65573423+dzalkind@users.noreply.github.com> Date: Tue, 17 Oct 2023 10:48:15 -0600 Subject: [PATCH 127/224] Update .readthedocs.yaml with other build options --- .readthedocs.yaml | 5 +++++ 1 file changed, 5 insertions(+) diff --git a/.readthedocs.yaml b/.readthedocs.yaml index 98a7d535..3a7e9841 100644 --- a/.readthedocs.yaml +++ b/.readthedocs.yaml @@ -8,6 +8,11 @@ version: 2 # Add build os (and other options) build: os: ubuntu-22.04 + tools: + python: "3.12" + nodejs: "18" + rust: "1.64" + golang: "1.19" # Build documentation in the docs/ directory with Sphinx sphinx: From 80973fe16b250c656a5118a5a10f309330bbfcfa Mon Sep 17 00:00:00 2001 From: dzalkind <65573423+dzalkind@users.noreply.github.com> Date: Tue, 17 Oct 2023 10:55:59 -0600 Subject: [PATCH 128/224] Update .readthedocs.yaml with python 3.9 --- .readthedocs.yaml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.readthedocs.yaml b/.readthedocs.yaml index 3a7e9841..f3f2d8c3 100644 --- a/.readthedocs.yaml +++ b/.readthedocs.yaml @@ -9,7 +9,7 @@ version: 2 build: os: ubuntu-22.04 tools: - python: "3.12" + python: "3.9" nodejs: "18" rust: "1.64" golang: "1.19" From 04d3f52847cc0b769c6a18f18e0689839e1f840c Mon Sep 17 00:00:00 2001 From: dzalkind <65573423+dzalkind@users.noreply.github.com> Date: Tue, 17 Oct 2023 11:42:09 -0600 Subject: [PATCH 129/224] Update .readthedocs.yaml with new python version --- .readthedocs.yaml | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/.readthedocs.yaml b/.readthedocs.yaml index f3f2d8c3..54b5ab55 100644 --- a/.readthedocs.yaml +++ b/.readthedocs.yaml @@ -9,10 +9,10 @@ version: 2 build: os: ubuntu-22.04 tools: - python: "3.9" - nodejs: "18" - rust: "1.64" - golang: "1.19" + python: 3.7 + # nodejs: "18" + # rust: "1.64" + # golang: "1.19" # Build documentation in the docs/ directory with Sphinx sphinx: From c4790340da606d5d500366de263c1c8f52d272f8 Mon Sep 17 00:00:00 2001 From: dzalkind <65573423+dzalkind@users.noreply.github.com> Date: Tue, 17 Oct 2023 11:44:34 -0600 Subject: [PATCH 130/224] Update .readthedocs.yaml with another python version --- .readthedocs.yaml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.readthedocs.yaml b/.readthedocs.yaml index 54b5ab55..0e182989 100644 --- a/.readthedocs.yaml +++ b/.readthedocs.yaml @@ -9,7 +9,7 @@ version: 2 build: os: ubuntu-22.04 tools: - python: 3.7 + python: "mambaforge-22.9" # nodejs: "18" # rust: "1.64" # golang: "1.19" From 328d29e7dc20503ad904e9db8a2fcb3a45959e30 Mon Sep 17 00:00:00 2001 From: dzalkind <65573423+dzalkind@users.noreply.github.com> Date: Tue, 17 Oct 2023 11:45:36 -0600 Subject: [PATCH 131/224] Update .readthedocs.yaml with version key --- .readthedocs.yaml | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/.readthedocs.yaml b/.readthedocs.yaml index 0e182989..c377c1f3 100644 --- a/.readthedocs.yaml +++ b/.readthedocs.yaml @@ -9,7 +9,8 @@ version: 2 build: os: ubuntu-22.04 tools: - python: "mambaforge-22.9" + python: + version: "mambaforge-22.9" # nodejs: "18" # rust: "1.64" # golang: "1.19" From 8693d4ba49dd46ddaab6616e645edebf986bcd49 Mon Sep 17 00:00:00 2001 From: dzalkind <65573423+dzalkind@users.noreply.github.com> Date: Tue, 17 Oct 2023 11:47:10 -0600 Subject: [PATCH 132/224] Update .readthedocs.yaml --- .readthedocs.yaml | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/.readthedocs.yaml b/.readthedocs.yaml index c377c1f3..c06f22d4 100644 --- a/.readthedocs.yaml +++ b/.readthedocs.yaml @@ -9,8 +9,8 @@ version: 2 build: os: ubuntu-22.04 tools: - python: - version: "mambaforge-22.9" + python: "mambaforge-22.9" + # version: "mambaforge-22.9" # nodejs: "18" # rust: "1.64" # golang: "1.19" From dd01047c5ba1b6cf26454f446702135600c3feaf Mon Sep 17 00:00:00 2001 From: dzalkind <65573423+dzalkind@users.noreply.github.com> Date: Tue, 17 Oct 2023 11:49:41 -0600 Subject: [PATCH 133/224] Update .readthedocs.yaml remove old python version --- .readthedocs.yaml | 4 +--- 1 file changed, 1 insertion(+), 3 deletions(-) diff --git a/.readthedocs.yaml b/.readthedocs.yaml index c06f22d4..66971b94 100644 --- a/.readthedocs.yaml +++ b/.readthedocs.yaml @@ -9,8 +9,7 @@ version: 2 build: os: ubuntu-22.04 tools: - python: "mambaforge-22.9" - # version: "mambaforge-22.9" + python: "3.8" # nodejs: "18" # rust: "1.64" # golang: "1.19" @@ -27,7 +26,6 @@ formats: # Optionally set the version of Python and requirements required to build your docs python: - version: 3.8 install: - requirements: docs/requirements.txt - method: pip From a610e55eb508b2d516fb3e778fc24585b5b6080f Mon Sep 17 00:00:00 2001 From: dzalkind <65573423+dzalkind@users.noreply.github.com> Date: Fri, 27 Oct 2023 09:55:20 -0600 Subject: [PATCH 134/224] Better Open Loop Control Error Catching (#273) * FOCAL Updates (#64) * Update headers * fix bullets * make uppercase * Update turbine.py (#56) * Update turbine.py This add several lines for fixing the problem of repeated maximum values in the performance tables. This will cause the error (' the length of x and y is different.') of 'interpolate.interp1d.' * Add comments and catch when there are multiple optimal pitch angles Co-authored-by: dzalkind * increment version * Update for OpenFAST v3.0.0 * Update for OpenFAST v3.0.0 * Install OF3.0.0 for tests * update for OF v3.0.0 * add publish to pypi on release * Update to ROSCO v2.3.0 * Update Testing (#58) * Update scripts to run on eagle * Update IEA-15MW semi example: use peak shaving w/ ps_percen=0.8 * Add comparison plots to testing scripts * Update submit script for testing * Update for latest eagle runs * Add future to install dependencies * add TMax to self, define tmin in print_results * run tests in CI * generic ROSCO path * default to overwrite * fix path * import platform * separate run_testing * cleanup, specify lite test * don't run testing in after examples, oops. Co-authored-by: nikhar-abbas <40865984+nikhar-abbas@users.noreply.github.com> Co-authored-by: Nikhar Abbas * increment version * Update for OpenFAST v3.0.0 * Install OF3.0.0 for tests * update for OF v3.0.0 * add publish to pypi on release * Update to ROSCO v2.3.0 * Increment Version, OF3.0 (#57) * increment version * Update for OpenFAST v3.0.0 * Install OF3.0.0 for tests * update for OF v3.0.0 * add publish to pypi on release * Update to ROSCO v2.3.0 * increment version * Update for OpenFAST v3.0.0 * Install OF3.0.0 for tests * update for OF v3.0.0 * add publish to pypi on release * Update to ROSCO v2.3.0 * add ROSCO without submodule * move ROSCO source to ROSCO folder * Move cmake-related files to ROSCO * Add back pesky ErrVar * Remove parameters_files * Merge ROSCO and _toolbox gitignore * Fix .gitignore * Remove Examples/DISCON.IN from git * Fix and point example_01 to Tune_Cases/ * Update verbiage around using ofTools vs. weis * Fix and point example_04 to Tune_Cases/ * Clean up example_06 * Clean up example_07 * Only check FlpCornerFreq if using Flp control, fixes example 05 * Make example_04 consistent with others * Let example_05 run independently from 04 * Clean up example_05, wind files * Add schema and update empty tuning yaml inputs, not connected yet * Integrate schema into turbine, controller, and examples * Only check Fl filter parameters if Fl_Mode > 0, fix example_05 * bump version to 2.3 * Compile ROSCO from ROSCO dir * Rename to CI_rosco * Add omega vs. windspeed functionality * Fix tests: 5MW U_pc and 06 example dir * Make _Toolbox vs_minspeed in rotor frame to match ROSCO * Revert ServoDyn change * change rotor speed constraint to be epsilon * rename for clarity * docs major refresh * fix FA_AccF units in debug file * docs that build locally * Deallocate arrays in ROSCO, check in example_05 * Clean up comments * remove gitmodules * furo theme * furo in requirements * move readthedocs config file, remove furo import in conf.py * add docs requirements file * typo * move index out of source folder * trying to get furo to work * import date * fix versions and titles, cleanup readthedocs requirements * typo fix, remove extras * more cleanup * bump version * no furo extension, "hack" to load RT version * proper toctree paths * specify method * add mock modules * fix typos * update python install requirements * running locally * move index to main docs dir again * update to build locally * error during warnings * automated version * cleanup * remove old docs * re-add docs * simplify * fix figure path * try alabaster * remove archived docs * Add omega vs. windspeed functionality * Fix tests: 5MW U_pc and 06 example dir * more detailed sp.optimize settings * run MBC3 in parallel * restructure driver, run initialization doe for tuning * Try new dlclose function * Update example_05 to run simple simulation twice and check result * Revert deallocation stuff * Close discon library after every sim run * Test examples on macOS and windows * Run examples instead of testing on other platforms * Skip examples in windows for now * update paths and yaml load funciton * Skip mac testing of examples * provide default U_pc for single omega/zeta case * allow for float or list-like pc tuning inputs * Change name in setup.py * WE_Vw unit fix * Pass through kp_float, if desired * Minor fixes: schema error and InputReader defaults * cleeanup for improved stability * check for doe_logs as string in load_DOE * major restructure for rsched_driver class * cleanup verbosity * run serial by default * load_parallel as linturb_option * specific IEA15MW yaml for multi omega * remove unused module imports * fix error message types * lin_file as input * add comments on inputs to LinearTurbineModel init method * remove relative file paths * provide OpenFAST linearizations for IEA15MW UMaineSemi * put plotting in specific function * fix WE_lambda units * add self in on a few necessary variables * creaete example 12 for robust scheduling * try a few mbc3 locations for import * allow list-like or numpy arrays for omega_pc and zeta_pc schedules * create and use recorder setup function * Pass Through Kp_float (#57) * Pass through kp_float, if desired * Minor fixes: schema error and InputReader defaults * fix setup_recorder to work for optimization driver too * Allow pass through of Kp_float = 0 * cleanup om problems, update om0 calc * doe levels as input * negative k_float to account for OF conventions * cleanup print statements * variable name cleanup, use calculated k_float * Add defaults to omega_,zeta_ pc and vs, allow to be numbers * use standard tuning k_float as IC * formatting update * update problem setup methods * cleanup add_dv, enable adding design variables after problem is setup * change optimization step size * more setup restructure * update verbosity * use sphinx-rtd-theme * master doc and sphinx rtd theme * index back to root folder * only ignore install folders * remove hidden toctree * furo theme * update paths * convert rt version to string * update sphinx settings * move conf * furo theme * Mostly a docs update (#61) * rename for clarity * docs major refresh * fix FA_AccF units in debug file * docs that build locally * remove gitmodules * furo theme * furo in requirements * move readthedocs config file, remove furo import in conf.py * add docs requirements file * typo * move index out of source folder * trying to get furo to work * import date * fix versions and titles, cleanup readthedocs requirements * typo fix, remove extras * more cleanup * bump version * no furo extension, "hack" to load RT version * proper toctree paths * specify method * add mock modules * fix typos * update python install requirements * running locally * move index to main docs dir again * update to build locally * error during warnings * automated version * cleanup * remove old docs * re-add docs * simplify * fix figure path * try alabaster * remove archived docs * use sphinx-rtd-theme * master doc and sphinx rtd theme * index back to root folder * only ignore install folders * remove hidden toctree * furo theme * update paths * convert rt version to string * update sphinx settings * move conf * furo theme * Pass through Kp_float = 0 (#59) * Pass through kp_float, if desired * Minor fixes: schema error and InputReader defaults * Allow pass through of Kp_float = 0 * Add flp parameters to schema * Change Fl_Mode default to 0 * Add defaults to omega_,zeta_ pc and vs, allow to be numbers * Allow single pitch tuning values in code, default U_pc to 0 * use nac acceleration for floating feedback * Fix TSR saturation for region 2.5operation * Modify system for constant power operation * Only modify pole for constant power above-rated * Remove GenEff from K calc * Update tuning, use constant power * use load_rosco_yaml * constant power * Fix broken tests * Include Fl_Mode=2 for nacelle pitching feedback * Add FOCAL inputs - hpf on floating feedback - lpf on wind speed estimator - associated schema updates * Set notch and check frequencies when Fl_Mode = 1 (fixes bug) * Skip filter step if there's an error * Update IEA-15MW test case DISCON with focal inputs * Allow Fl_Mode = 2 in ROSCO * Pass through lpf frequency * Add FOCAL tuning yaml * Set Cp contour number of levels * Add FOCAL params to various writers * Update/tune focal yaml * Add scripts for running FAST, tuning various parameters and cases * Add notebook for FAST plotting * Set up step case for testing * Change doubles to C_doubles * Define real and integer kinds, assign to all of ROSCO * Add ADJUSTL to DISCON error message * Fix Fl_Mode == 2 * Fix Fl_Mode == 2 again * Call yaw, flap, and debug only if enabled in DISOCN.IN * Make avrSWAP a ReKi and set constant kinds * Add DISCONs for testing - revert this later * Fix DISCON comparison, before DISCON's were overwritten by model * Rename DEBUG2.dbg to RootName.dbg2 * Update TestCase DISCONs to new input file * Add API change page in docs * Add link to API change on main page * Fix table headers * Fix title underlines * Fix tables again * Fix tables again * Fix version numbering in docs * Simplify FAST_directory in run_FAST * Versioning (#65) * use sphinx-rtd-theme * master doc and sphinx rtd theme * index back to root folder * only ignore install folders * remove hidden toctree * furo theme * update paths * convert rt version to string * update sphinx settings * move conf * furo theme * remove git versioning from cmake * use hard coded rosco_version * update intro write method * set nowrap for intel compilers * Add transfer of error message and clear message after each call * update install instructions * Catch nans in ROSCO at end of WSE * fix conda install typo * cleanup docs * Rename DEBUG2.dbg to RootName.dbg2 * Fix Fl_Mode == 2 * Fix Fl_Mode == 2 again * Allow Fl_Mode = 2 in ROSCO * Set notch and check frequencies when Fl_Mode = 1 (fixes bug) * Update FOCAL tuning yaml * Update TSR * Clean up and doc fix * Remove publish to pypi * Define all constant inputs to functions with kind typing * Generate Test_Case/ inputs automatically * Fix IEA15 DISCON path * Fix example 11 paths * Auto-generate tuning input yaml using schema * Add toolbox_input to doc index * Add toctree * Re-name title of toolbox_input Co-authored-by: Nikhar Abbas Co-authored-by: Xianping Du <38188001+Seager1989@users.noreply.github.com> Co-authored-by: nikhar-abbas <40865984+nikhar-abbas@users.noreply.github.com> * update listcheck method for numpy arrays * Open Loop Control (#98) * create rosco types yaml * Add more descriptions, add integer_c default, cleanup * updates for allocatability and shapes * python scripts to write ROSCO_types.f90 * reemove superfulous modules * use types from ROSCO registry * create rosco types yaml * Add more descriptions, add integer_c default, cleanup * updates for allocatability and shapes * python scripts to write ROSCO_types.f90 * reemove superfulous modules * use types from ROSCO registry * Saturate inputs to WSE. Needs some TLC, but seems to work * Reduce saturation limits on speed, torque * Re-organize, set saturation limits. Working at 3 m/s * Initial add of OL control to ROSCO: builds * Update DISCONs with open loop inputs * Fix file reading for OL_Filename * Add open loop control generation and file writing * Use DISCON_dict for more manageable DISCON file writing * Add open loop example, fix constant timeseries * Make open loop example generate power * Handle relative paths and calling from outside the run directory: - Some helper functions borrowed from OpenFAST, f/ext_control - Updated file writing * Clean up: versions, print statements * Fix SysFiles paths in CMakeLists * Tidy up Ext_DLL names * More Ext_DLL name tidying * Test write_registry.py * Update for OL Control * Move preprocessor lines * add zenodo DOI * Regenerated Types * fix shape * revert filepath change * give all types a size, ProcAddr size = 3 * update types * test registry in compile step * specify default shell * update write_registry path * remove default shell * Document API changes, provide OL input example * Fix example 14 (yaw input) * Add error catching to yaw control * Tidy up OL_Input Reading: error catching, generalize * More yaw control fixes, to model * Checkout develop CMakeLists for ROSCO * Update DISCON.INs for TestCases/ * Revert "Checkout develop CMakeLists for ROSCO" This reverts commit 87a491359d73806e3aaa59b4cfdc00f2838875df. * Revert windows cmake stuff to develop * Fix CMake again * Revert "Revert windows cmake stuff to develop" This reverts commit 39df122449b0e2055f2e12e3ce38a0c010c7bd91. * Make last cmake fix - hopefully Co-authored-by: Nikhar Abbas * Convert WE saved variables to WE type * Put restart flag in localvars * Use saved filter params from LocalVar * save pitcomt last * Move IPC saved variables to localvars * Saved pi controller variables to localvar * Save RootMyb_Last to localvar * ROSCO_IO - initial commit. Include restart and debug functions * Use ROSCO IO and call restart functions * Remove debug from function.f90 * Save ACC Infile info * update for restart capabilities * add rosco_io with restart and debug functions * cleanup debug call * use registry generate types and IO * delete DFController * fix timestep mismatch * remove unnecessaray istatus check * close files * add reg test for restart * add restart option to run_openfast * add testing to CI, ignore generate files * fix fastcall * remove extra commas * specify gfortran-10 * testing flag cleanup * Use lv_strings to generate debug output * Revert "testing flag cleanup" This reverts commit 6f295563832413e96347acd82716f9aadac6d46c. * Revert "specify gfortran-10" This reverts commit 4c3154491523bcd542133ca2bce5803cdc94523f. * minor cleanup * Use kind from constants * Add some comments for clarity * put debug in if statements * separate reg tests from oother tests * Fl_Mode>0 * Remove hard coded values * Add filtered signals and WE_Vw to debug varrs * cd for regtest * Check logging level before calling debug * add fl_pitcom and pc_minpit to debugvars * Turn runFAST into a class * Refactor/simplify CaseLibrary * Restart & registry (#99) * Convert WE saved variables to WE type * Put restart flag in localvars * Use saved filter params from LocalVar * save pitcomt last * Move IPC saved variables to localvars * Saved pi controller variables to localvar * Save RootMyb_Last to localvar * ROSCO_IO - initial commit. Include restart and debug functions * Use ROSCO IO and call restart functions * Remove debug from function.f90 * Save ACC Infile info * update for restart capabilities * add rosco_io with restart and debug functions * cleanup debug call * use registry generate types and IO * delete DFController * fix timestep mismatch * remove unnecessaray istatus check * close files * add reg test for restart * add restart option to run_openfast * add testing to CI, ignore generate files * fix fastcall * remove extra commas * specify gfortran-10 * testing flag cleanup * Use lv_strings to generate debug output * Revert "testing flag cleanup" This reverts commit 6f295563832413e96347acd82716f9aadac6d46c. * Revert "specify gfortran-10" This reverts commit 4c3154491523bcd542133ca2bce5803cdc94523f. * minor cleanup * Use kind from constants * Add some comments for clarity * put debug in if statements * separate reg tests from oother tests * Fl_Mode>0 * Remove hard coded values * Add filtered signals and WE_Vw to debug varrs * cd for regtest * Check logging level before calling debug * add fl_pitcom and pc_minpit to debugvars Co-authored-by: dzalkind * Implement initial pitch actuator * Set up steps case * Break up if statement in open loop pitch (#100) * Break up if statement in open loop pitch * Make torque and yaw consistent with pitch: can start after some time * add bld edgewise freq to robust dict_inputs * Add actuator variable * Print first time step in debug outs * Fix FOCAL yaml * Set actuator to 0.25 Hz bandwidth * Fix ccrotor inputs (#104) * remove interpolation of blade chord and twist * rename aerodynblade inputs * Update surface and DISCON.INs * Fix performance table paths * Allow default inputs (#110) * Allow defaults for AeroDyn inputs * Allow AeroDyn inputs to be floats, too * ipc (#105) * remove interpolation of blade chord and twist * rename aerodynblade inputs * Update surface and DISCON.INs * Fix performance table paths * Add proportional control and cleanup IPC * Add IPC and filtered RootMyc to registry * Better logic for filtering RootMOOP and fix notch filter slopes bug * Add cyclic flap conrol * Fix comments in ColemanTransformInverse * Addd IPC_KP to DISCON.IN * Error checking foro flp or ipc * add mutichannel plotting with tuples * add CMakeFiles to gitignore * Add IPC_KP to api changes * numerical qualifiers for error handling * add IPC gains to schema for pass-through ability * fix variable names * fix ipc gain printing bug * make sure IPC_KP is positive * Update Polars to point to coord files * ignore dbg2 files * Add IEA15MW_OL.yaml * update coord reader/writer * expand pitch_initial to 30 degrees * Add example 13 for IPC * Update cp surfaces and DISCONS * add examples to readme * cleanup and streaamline run_examples * Add IPC tuning vars * Allow IPC to command pitch value below peak shaving saturation limit * shorten simulation time * Fix Material parameter path * Update DISCONs again * Fix OL_Input reading * Set wind speed, rotor speed IC in example 14 * Debug OL reading * Add more debugging lines * Add more debugging lines 2 * Clean up, hone in on debug call * Disable logging level * Update discons - resolve conflict * Print when finished with ROSCO * add control packageg * Use PriPath and RootName to name dbg files * Print AvrSWAP * Revert "Use PriPath and RootName to name dbg files" This reverts commit 062fcaa55b3bf42d44f8a3f163aa883ab9552412. * Disable other examples * Print OL inputs * Allow logging level 3 * Print OL inputs * Make example shorter * Print more stuf * Print shape * Revert "Print OL inputs" This reverts commit 8e2a642bb35e46850f579ca4e69ca6d6fc93f4cc. * Update ROSCO Simulink model with IPC example * refactor flap tuning for normalization methods * improved flap controller filtering * delete extra F_FlpCornerFrerq * Update inputs, reader, and writer for OF 3.1.0 * Make sigma default interp type for multi_sigma * Use openfast 3.1.0 in CI * Fix leak...maybe * Use OF 3.1.0 in testing * Use gfotran for compile * Clean up print statements * Re-enable all examples * Update NREL-5MW AD file * Only check airfoil controls if more than one table * Update BAR models * Revert "Use gfotran for compile" This reverts commit 5a6e2b7e30287a09a09781e2ba12f9b578132e1f. * Install pyFAST for CI * Fix some paths in ex12 * Disable example 12 * Fix example 12 linear path, re-enable * Skip compilers install for mac * Try gfortran-9, no compilers * Try gfortran-10, no compilers * Skip windows compile in pytools * Re-enable windows, use gfortran as FC * Unset FC in windows * Set environment for windows when dependencies installed * Try setting environment in installation * Put conditional env setting in correct place * Try in setup again * Break up tasks: Windows vs. not * Update DISCONs * Update docs with new variables * Add example documentation * Update ROSCO Simulink model for 3.1.0 * Make IEA model float again * Reduce IEA timestep * Match DT to checkpoint time Co-authored-by: dzalkind * Increment version number * Bladed docs (#116) * Added image of Bladed control screen setup * Delete Bladed control screen.png * Adding image of Bladed control screen * Add files via upload * Minor edit 1 * Minor change 2 * Minor change 3 * Minor change 4 * Change 6 * Change 7 * Change 8 * Minor change 9 Co-authored-by: nikhar-abbas <40865984+nikhar-abbas@users.noreply.github.com> Co-authored-by: WillC-DNV <100850534+WillC-DNV@users.noreply.github.com> * Update version in API change docs * Bladed readthedocs (#117) * Added image of Bladed control screen setup * Delete Bladed control screen.png * Adding image of Bladed control screen * Add files via upload * Minor edit 1 * Minor change 2 * Minor change 3 * Minor change 4 * Change 6 * Change 7 * Change 8 * Minor change 9 * Tinker with characters in bladed instructions * Add bladed instructions to index * Change bladed toctree label * Do underline stuff * Make toctree label same as file * Remove colons from headers Co-authored-by: nikhar-abbas <40865984+nikhar-abbas@users.noreply.github.com> Co-authored-by: WillC-DNV <100850534+WillC-DNV@users.noreply.github.com> * Update docs to reflect CI process * Regenerate types, IO with registry * Update registry so first timestep is printed * Update inverted notch to move frequency properly * Saturate inv notch corner frequency at 0 * Add tower damper mode flag * Add Azimuth tracking controller in Simulink * Always enable GenDOF, add options for simp_step * Add sweep for IPC gains and FA damper * Fix NumCoords in FAST_writer * sigma + ipc (#125) * cleanup api change table * Update inverted notch to move frequency properly * Saturate inv notch corner frequency at 0 * add sigma function * Use IPC_Vramp for IPC cut-in * Add IPC_Vramp DISCON inputs * update registry * Update DISCONs * Update docs for API change * Fix IPC_Vramp data type * update comments Co-authored-by: dzalkind * Add turbulent case to runFAST/CaseLibrary * Add peak shaving sweep function * Increase default IPC_IntSat, make input parameter in future * Flip Ct and Cq table allocation * Flip Ct and Cq table allocation (#130) * Regen types * Remove print statements used for debugging * Update input files: IEA model has pitch actuator * Add back flap control (no idea when it was deleted) * Update discons, docs with API change * Add user-defined hh case * Fix AddF0 and RayleighDamp in FAST_reader * Pitch Actuator and IPC updates (#123) * Convert WE saved variables to WE type * Put restart flag in localvars * Use saved filter params from LocalVar * save pitcomt last * Move IPC saved variables to localvars * Saved pi controller variables to localvar * Save RootMyb_Last to localvar * ROSCO_IO - initial commit. Include restart and debug functions * Use ROSCO IO and call restart functions * Remove debug from function.f90 * Save ACC Infile info * update for restart capabilities * add rosco_io with restart and debug functions * cleanup debug call * use registry generate types and IO * delete DFController * fix timestep mismatch * remove unnecessaray istatus check * close files * add reg test for restart * add restart option to run_openfast * add testing to CI, ignore generate files * fix fastcall * remove extra commas * specify gfortran-10 * testing flag cleanup * Use lv_strings to generate debug output * Revert "testing flag cleanup" This reverts commit 6f295563832413e96347acd82716f9aadac6d46c. * Revert "specify gfortran-10" This reverts commit 4c3154491523bcd542133ca2bce5803cdc94523f. * minor cleanup * Use kind from constants * Add some comments for clarity * put debug in if statements * separate reg tests from oother tests * Fl_Mode>0 * Remove hard coded values * Add filtered signals and WE_Vw to debug varrs * cd for regtest * Check logging level before calling debug * add fl_pitcom and pc_minpit to debugvars * Turn runFAST into a class * Refactor/simplify CaseLibrary * Implement initial pitch actuator * Set up steps case * Add actuator variable * Print first time step in debug outs * Fix FOCAL yaml * Set actuator to 0.25 Hz bandwidth * ROSCO 2.5.0 (#115) * FOCAL Updates (#64) * Update headers * fix bullets * make uppercase * Update turbine.py (#56) * Update turbine.py This add several lines for fixing the problem of repeated maximum values in the performance tables. This will cause the error (' the length of x and y is different.') of 'interpolate.interp1d.' * Add comments and catch when there are multiple optimal pitch angles Co-authored-by: dzalkind * increment version * Update for OpenFAST v3.0.0 * Update for OpenFAST v3.0.0 * Install OF3.0.0 for tests * update for OF v3.0.0 * add publish to pypi on release * Update to ROSCO v2.3.0 * Update Testing (#58) * Update scripts to run on eagle * Update IEA-15MW semi example: use peak shaving w/ ps_percen=0.8 * Add comparison plots to testing scripts * Update submit script for testing * Update for latest eagle runs * Add future to install dependencies * add TMax to self, define tmin in print_results * run tests in CI * generic ROSCO path * default to overwrite * fix path * import platform * separate run_testing * cleanup, specify lite test * don't run testing in after examples, oops. Co-authored-by: nikhar-abbas <40865984+nikhar-abbas@users.noreply.github.com> Co-authored-by: Nikhar Abbas * increment version * Update for OpenFAST v3.0.0 * Install OF3.0.0 for tests * update for OF v3.0.0 * add publish to pypi on release * Update to ROSCO v2.3.0 * Increment Version, OF3.0 (#57) * increment version * Update for OpenFAST v3.0.0 * Install OF3.0.0 for tests * update for OF v3.0.0 * add publish to pypi on release * Update to ROSCO v2.3.0 * increment version * Update for OpenFAST v3.0.0 * Install OF3.0.0 for tests * update for OF v3.0.0 * add publish to pypi on release * Update to ROSCO v2.3.0 * add ROSCO without submodule * move ROSCO source to ROSCO folder * Move cmake-related files to ROSCO * Add back pesky ErrVar * Remove parameters_files * Merge ROSCO and _toolbox gitignore * Fix .gitignore * Remove Examples/DISCON.IN from git * Fix and point example_01 to Tune_Cases/ * Update verbiage around using ofTools vs. weis * Fix and point example_04 to Tune_Cases/ * Clean up example_06 * Clean up example_07 * Only check FlpCornerFreq if using Flp control, fixes example 05 * Make example_04 consistent with others * Let example_05 run independently from 04 * Clean up example_05, wind files * Add schema and update empty tuning yaml inputs, not connected yet * Integrate schema into turbine, controller, and examples * Only check Fl filter parameters if Fl_Mode > 0, fix example_05 * bump version to 2.3 * Compile ROSCO from ROSCO dir * Rename to CI_rosco * Add omega vs. windspeed functionality * Fix tests: 5MW U_pc and 06 example dir * Make _Toolbox vs_minspeed in rotor frame to match ROSCO * Revert ServoDyn change * change rotor speed constraint to be epsilon * rename for clarity * docs major refresh * fix FA_AccF units in debug file * docs that build locally * Deallocate arrays in ROSCO, check in example_05 * Clean up comments * remove gitmodules * furo theme * furo in requirements * move readthedocs config file, remove furo import in conf.py * add docs requirements file * typo * move index out of source folder * trying to get furo to work * import date * fix versions and titles, cleanup readthedocs requirements * typo fix, remove extras * more cleanup * bump version * no furo extension, "hack" to load RT version * proper toctree paths * specify method * add mock modules * fix typos * update python install requirements * running locally * move index to main docs dir again * update to build locally * error during warnings * automated version * cleanup * remove old docs * re-add docs * simplify * fix figure path * try alabaster * remove archived docs * Add omega vs. windspeed functionality * Fix tests: 5MW U_pc and 06 example dir * more detailed sp.optimize settings * run MBC3 in parallel * restructure driver, run initialization doe for tuning * Try new dlclose function * Update example_05 to run simple simulation twice and check result * Revert deallocation stuff * Close discon library after every sim run * Test examples on macOS and windows * Run examples instead of testing on other platforms * Skip examples in windows for now * update paths and yaml load funciton * Skip mac testing of examples * provide default U_pc for single omega/zeta case * allow for float or list-like pc tuning inputs * Change name in setup.py * WE_Vw unit fix * Pass through kp_float, if desired * Minor fixes: schema error and InputReader defaults * cleeanup for improved stability * check for doe_logs as string in load_DOE * major restructure for rsched_driver class * cleanup verbosity * run serial by default * load_parallel as linturb_option * specific IEA15MW yaml for multi omega * remove unused module imports * fix error message types * lin_file as input * add comments on inputs to LinearTurbineModel init method * remove relative file paths * provide OpenFAST linearizations for IEA15MW UMaineSemi * put plotting in specific function * fix WE_lambda units * add self in on a few necessary variables * creaete example 12 for robust scheduling * try a few mbc3 locations for import * allow list-like or numpy arrays for omega_pc and zeta_pc schedules * create and use recorder setup function * Pass Through Kp_float (#57) * Pass through kp_float, if desired * Minor fixes: schema error and InputReader defaults * fix setup_recorder to work for optimization driver too * Allow pass through of Kp_float = 0 * cleanup om problems, update om0 calc * doe levels as input * negative k_float to account for OF conventions * cleanup print statements * variable name cleanup, use calculated k_float * Add defaults to omega_,zeta_ pc and vs, allow to be numbers * use standard tuning k_float as IC * formatting update * update problem setup methods * cleanup add_dv, enable adding design variables after problem is setup * change optimization step size * more setup restructure * update verbosity * use sphinx-rtd-theme * master doc and sphinx rtd theme * index back to root folder * only ignore install folders * remove hidden toctree * furo theme * update paths * convert rt version to string * update sphinx settings * move conf * furo theme * Mostly a docs update (#61) * rename for clarity * docs major refresh * fix FA_AccF units in debug file * docs that build locally * remove gitmodules * furo theme * furo in requirements * move readthedocs config file, remove furo import in conf.py * add docs requirements file * typo * move index out of source folder * trying to get furo to work * import date * fix versions and titles, cleanup readthedocs requirements * typo fix, remove extras * more cleanup * bump version * no furo extension, "hack" to load RT version * proper toctree paths * specify method * add mock modules * fix typos * update python install requirements * running locally * move index to main docs dir again * update to build locally * error during warnings * automated version * cleanup * remove old docs * re-add docs * simplify * fix figure path * try alabaster * remove archived docs * use sphinx-rtd-theme * master doc and sphinx rtd theme * index back to root folder * only ignore install folders * remove hidden toctree * furo theme * update paths * convert rt version to string * update sphinx settings * move conf * furo theme * Pass through Kp_float = 0 (#59) * Pass through kp_float, if desired * Minor fixes: schema error and InputReader defaults * Allow pass through of Kp_float = 0 * Add flp parameters to schema * Change Fl_Mode default to 0 * Add defaults to omega_,zeta_ pc and vs, allow to be numbers * Allow single pitch tuning values in code, default U_pc to 0 * use nac acceleration for floating feedback * Fix TSR saturation for region 2.5operation * Modify system for constant power operation * Only modify pole for constant power above-rated * Remove GenEff from K calc * Update tuning, use constant power * use load_rosco_yaml * constant power * Fix broken tests * Include Fl_Mode=2 for nacelle pitching feedback * Add FOCAL inputs - hpf on floating feedback - lpf on wind speed estimator - associated schema updates * Set notch and check frequencies when Fl_Mode = 1 (fixes bug) * Skip filter step if there's an error * Update IEA-15MW test case DISCON with focal inputs * Allow Fl_Mode = 2 in ROSCO * Pass through lpf frequency * Add FOCAL tuning yaml * Set Cp contour number of levels * Add FOCAL params to various writers * Update/tune focal yaml * Add scripts for running FAST, tuning various parameters and cases * Add notebook for FAST plotting * Set up step case for testing * Change doubles to C_doubles * Define real and integer kinds, assign to all of ROSCO * Add ADJUSTL to DISCON error message * Fix Fl_Mode == 2 * Fix Fl_Mode == 2 again * Call yaw, flap, and debug only if enabled in DISOCN.IN * Make avrSWAP a ReKi and set constant kinds * Add DISCONs for testing - revert this later * Fix DISCON comparison, before DISCON's were overwritten by model * Rename DEBUG2.dbg to RootName.dbg2 * Update TestCase DISCONs to new input file * Add API change page in docs * Add link to API change on main page * Fix table headers * Fix title underlines * Fix tables again * Fix tables again * Fix version numbering in docs * Simplify FAST_directory in run_FAST * Versioning (#65) * use sphinx-rtd-theme * master doc and sphinx rtd theme * index back to root folder * only ignore install folders * remove hidden toctree * furo theme * update paths * convert rt version to string * update sphinx settings * move conf * furo theme * remove git versioning from cmake * use hard coded rosco_version * update intro write method * set nowrap for intel compilers * Add transfer of error message and clear message after each call * update install instructions * Catch nans in ROSCO at end of WSE * fix conda install typo * cleanup docs * Rename DEBUG2.dbg to RootName.dbg2 * Fix Fl_Mode == 2 * Fix Fl_Mode == 2 again * Allow Fl_Mode = 2 in ROSCO * Set notch and check frequencies when Fl_Mode = 1 (fixes bug) * Update FOCAL tuning yaml * Update TSR * Clean up and doc fix * Remove publish to pypi * Define all constant inputs to functions with kind typing * Generate Test_Case/ inputs automatically * Fix IEA15 DISCON path * Fix example 11 paths * Auto-generate tuning input yaml using schema * Add toolbox_input to doc index * Add toctree * Re-name title of toolbox_input Co-authored-by: Nikhar Abbas Co-authored-by: Xianping Du <38188001+Seager1989@users.noreply.github.com> Co-authored-by: nikhar-abbas <40865984+nikhar-abbas@users.noreply.github.com> * update listcheck method for numpy arrays * Open Loop Control (#98) * create rosco types yaml * Add more descriptions, add integer_c default, cleanup * updates for allocatability and shapes * python scripts to write ROSCO_types.f90 * reemove superfulous modules * use types from ROSCO registry * create rosco types yaml * Add more descriptions, add integer_c default, cleanup * updates for allocatability and shapes * python scripts to write ROSCO_types.f90 * reemove superfulous modules * use types from ROSCO registry * Saturate inputs to WSE. Needs some TLC, but seems to work * Reduce saturation limits on speed, torque * Re-organize, set saturation limits. Working at 3 m/s * Initial add of OL control to ROSCO: builds * Update DISCONs with open loop inputs * Fix file reading for OL_Filename * Add open loop control generation and file writing * Use DISCON_dict for more manageable DISCON file writing * Add open loop example, fix constant timeseries * Make open loop example generate power * Handle relative paths and calling from outside the run directory: - Some helper functions borrowed from OpenFAST, f/ext_control - Updated file writing * Clean up: versions, print statements * Fix SysFiles paths in CMakeLists * Tidy up Ext_DLL names * More Ext_DLL name tidying * Test write_registry.py * Update for OL Control * Move preprocessor lines * add zenodo DOI * Regenerated Types * fix shape * revert filepath change * give all types a size, ProcAddr size = 3 * update types * test registry in compile step * specify default shell * update write_registry path * remove default shell * Document API changes, provide OL input example * Fix example 14 (yaw input) * Add error catching to yaw control * Tidy up OL_Input Reading: error catching, generalize * More yaw control fixes, to model * Checkout develop CMakeLists for ROSCO * Update DISCON.INs for TestCases/ * Revert "Checkout develop CMakeLists for ROSCO" This reverts commit 87a491359d73806e3aaa59b4cfdc00f2838875df. * Revert windows cmake stuff to develop * Fix CMake again * Revert "Revert windows cmake stuff to develop" This reverts commit 39df122449b0e2055f2e12e3ce38a0c010c7bd91. * Make last cmake fix - hopefully Co-authored-by: Nikhar Abbas * Restart & registry (#99) * Convert WE saved variables to WE type * Put restart flag in localvars * Use saved filter params from LocalVar * save pitcomt last * Move IPC saved variables to localvars * Saved pi controller variables to localvar * Save RootMyb_Last to localvar * ROSCO_IO - initial commit. Include restart and debug functions * Use ROSCO IO and call restart functions * Remove debug from function.f90 * Save ACC Infile info * update for restart capabilities * add rosco_io with restart and debug functions * cleanup debug call * use registry generate types and IO * delete DFController * fix timestep mismatch * remove unnecessaray istatus check * close files * add reg test for restart * add restart option to run_openfast * add testing to CI, ignore generate files * fix fastcall * remove extra commas * specify gfortran-10 * testing flag cleanup * Use lv_strings to generate debug output * Revert "testing flag cleanup" This reverts commit 6f295563832413e96347acd82716f9aadac6d46c. * Revert "specify gfortran-10" This reverts commit 4c3154491523bcd542133ca2bce5803cdc94523f. * minor cleanup * Use kind from constants * Add some comments for clarity * put debug in if statements * separate reg tests from oother tests * Fl_Mode>0 * Remove hard coded values * Add filtered signals and WE_Vw to debug varrs * cd for regtest * Check logging level before calling debug * add fl_pitcom and pc_minpit to debugvars Co-authored-by: dzalkind * Break up if statement in open loop pitch (#100) * Break up if statement in open loop pitch * Make torque and yaw consistent with pitch: can start after some time * add bld edgewise freq to robust dict_inputs * Fix ccrotor inputs (#104) * remove interpolation of blade chord and twist * rename aerodynblade inputs * Update surface and DISCON.INs * Fix performance table paths * Allow default inputs (#110) * Allow defaults for AeroDyn inputs * Allow AeroDyn inputs to be floats, too * ipc (#105) * remove interpolation of blade chord and twist * rename aerodynblade inputs * Update surface and DISCON.INs * Fix performance table paths * Add proportional control and cleanup IPC * Add IPC and filtered RootMyc to registry * Better logic for filtering RootMOOP and fix notch filter slopes bug * Add cyclic flap conrol * Fix comments in ColemanTransformInverse * Addd IPC_KP to DISCON.IN * Error checking foro flp or ipc * add mutichannel plotting with tuples * add CMakeFiles to gitignore * Add IPC_KP to api changes * numerical qualifiers for error handling * add IPC gains to schema for pass-through ability * fix variable names * fix ipc gain printing bug * make sure IPC_KP is positive * Update Polars to point to coord files * ignore dbg2 files * Add IEA15MW_OL.yaml * update coord reader/writer * expand pitch_initial to 30 degrees * Add example 13 for IPC * Update cp surfaces and DISCONS * add examples to readme * cleanup and streaamline run_examples * Add IPC tuning vars * Allow IPC to command pitch value below peak shaving saturation limit * shorten simulation time * Fix Material parameter path * Update DISCONs again * Fix OL_Input reading * Set wind speed, rotor speed IC in example 14 * Debug OL reading * Add more debugging lines * Add more debugging lines 2 * Clean up, hone in on debug call * Disable logging level * Update discons - resolve conflict * Print when finished with ROSCO * add control packageg * Use PriPath and RootName to name dbg files * Print AvrSWAP * Revert "Use PriPath and RootName to name dbg files" This reverts commit 062fcaa55b3bf42d44f8a3f163aa883ab9552412. * Disable other examples * Print OL inputs * Allow logging level 3 * Print OL inputs * Make example shorter * Print more stuf * Print shape * Revert "Print OL inputs" This reverts commit 8e2a642bb35e46850f579ca4e69ca6d6fc93f4cc. * Update ROSCO Simulink model with IPC example * refactor flap tuning for normalization methods * improved flap controller filtering * delete extra F_FlpCornerFrerq * Update inputs, reader, and writer for OF 3.1.0 * Make sigma default interp type for multi_sigma * Use openfast 3.1.0 in CI * Fix leak...maybe * Use OF 3.1.0 in testing * Use gfotran for compile * Clean up print statements * Re-enable all examples * Update NREL-5MW AD file * Only check airfoil controls if more than one table * Update BAR models * Revert "Use gfotran for compile" This reverts commit 5a6e2b7e30287a09a09781e2ba12f9b578132e1f. * Install pyFAST for CI * Fix some paths in ex12 * Disable example 12 * Fix example 12 linear path, re-enable * Skip compilers install for mac * Try gfortran-9, no compilers * Try gfortran-10, no compilers * Skip windows compile in pytools * Re-enable windows, use gfortran as FC * Unset FC in windows * Set environment for windows when dependencies installed * Try setting environment in installation * Put conditional env setting in correct place * Try in setup again * Break up tasks: Windows vs. not * Update DISCONs * Update docs with new variables * Add example documentation * Update ROSCO Simulink model for 3.1.0 * Make IEA model float again * Reduce IEA timestep * Match DT to checkpoint time Co-authored-by: dzalkind * Increment version number * Bladed docs (#116) * Added image of Bladed control screen setup * Delete Bladed control screen.png * Adding image of Bladed control screen * Add files via upload * Minor edit 1 * Minor change 2 * Minor change 3 * Minor change 4 * Change 6 * Change 7 * Change 8 * Minor change 9 Co-authored-by: nikhar-abbas <40865984+nikhar-abbas@users.noreply.github.com> Co-authored-by: WillC-DNV <100850534+WillC-DNV@users.noreply.github.com> * Update version in API change docs * Bladed readthedocs (#117) * Added image of Bladed control screen setup * Delete Bladed control screen.png * Adding image of Bladed control screen * Add files via upload * Minor edit 1 * Minor change 2 * Minor change 3 * Minor change 4 * Change 6 * Change 7 * Change 8 * Minor change 9 * Tinker with characters in bladed instructions * Add bladed instructions to index * Change bladed toctree label * Do underline stuff * Make toctree label same as file * Remove colons from headers Co-authored-by: nikhar-abbas <40865984+nikhar-abbas@users.noreply.github.com> Co-authored-by: WillC-DNV <100850534+WillC-DNV@users.noreply.github.com> * Update docs to reflect CI process Co-authored-by: Nikhar Abbas Co-authored-by: Xianping Du <38188001+Seager1989@users.noreply.github.com> Co-authored-by: nikhar-abbas <40865984+nikhar-abbas@users.noreply.github.com> Co-authored-by: WillC-DNV <100850534+WillC-DNV@users.noreply.github.com> * Fixed wrong formatting of list items (#122) extra newline required between list elements * Regenerate types, IO with registry * Update registry so first timestep is printed * Update inverted notch to move frequency properly * Saturate inv notch corner frequency at 0 * Add tower damper mode flag * Flip Ct and Cq table allocation * Regen types * Remove print statements used for debugging * Update input files: IEA model has pitch actuator * Add back flap control (no idea when it was deleted) * Update discons, docs with API change Co-authored-by: nikhar-abbas <40865984+nikhar-abbas@users.noreply.github.com> Co-authored-by: Nikhar Abbas Co-authored-by: Xianping Du <38188001+Seager1989@users.noreply.github.com> Co-authored-by: WillC-DNV <100850534+WillC-DNV@users.noreply.github.com> Co-authored-by: Gustavo Hylander <74593034+ghylander@users.noreply.github.com> * Add max_torque_factor for constant power control, flexible upper limit * Make update discons relative to tuning yaml * Update AddF0 and NumCoords in FAST_reader/writer * Remove matlab/rotor position control stuff * Add OpenFAST channels that Simulink reads (#135) * RAAW Updates (#133) * Convert WE saved variables to WE type * Put restart flag in localvars * Use saved filter params from LocalVar * save pitcomt last * Move IPC saved variables to localvars * Saved pi controller variables to localvar * Save RootMyb_Last to localvar * ROSCO_IO - initial commit. Include restart and debug functions * Use ROSCO IO and call restart functions * Remove debug from function.f90 * Save ACC Infile info * update for restart capabilities * add rosco_io with restart and debug functions * cleanup debug call * use registry generate types and IO * delete DFController * fix timestep mismatch * remove unnecessaray istatus check * close files * add reg test for restart * add restart option to run_openfast * add testing to CI, ignore generate files * fix fastcall * remove extra commas * specify gfortran-10 * testing flag cleanup * Use lv_strings to generate debug output * Revert "testing flag cleanup" This reverts commit 6f295563832413e96347acd82716f9aadac6d46c. * Revert "specify gfortran-10" This reverts commit 4c3154491523bcd542133ca2bce5803cdc94523f. * minor cleanup * Use kind from constants * Add some comments for clarity * put debug in if statements * separate reg tests from oother tests * Fl_Mode>0 * Remove hard coded values * Add filtered signals and WE_Vw to debug varrs * cd for regtest * Check logging level before calling debug * add fl_pitcom and pc_minpit to debugvars * Turn runFAST into a class * Refactor/simplify CaseLibrary * Implement initial pitch actuator * Set up steps case * Add actuator variable * Print first time step in debug outs * Fix FOCAL yaml * Set actuator to 0.25 Hz bandwidth * ROSCO 2.5.0 (#115) * FOCAL Updates (#64) * Update headers * fix bullets * make uppercase * Update turbine.py (#56) * Update turbine.py This add several lines for fixing the problem of repeated maximum values in the performance tables. This will cause the error (' the length of x and y is different.') of 'interpolate.interp1d.' * Add comments and catch when there are multiple optimal pitch angles Co-authored-by: dzalkind * increment version * Update for OpenFAST v3.0.0 * Update for OpenFAST v3.0.0 * Install OF3.0.0 for tests * update for OF v3.0.0 * add publish to pypi on release * Update to ROSCO v2.3.0 * Update Testing (#58) * Update scripts to run on eagle * Update IEA-15MW semi example: use peak shaving w/ ps_percen=0.8 * Add comparison plots to testing scripts * Update submit script for testing * Update for latest eagle runs * Add future to install dependencies * add TMax to self, define tmin in print_results * run tests in CI * generic ROSCO path * default to overwrite * fix path * import platform * separate run_testing * cleanup, specify lite test * don't run testing in after examples, oops. Co-authored-by: nikhar-abbas <40865984+nikhar-abbas@users.noreply.github.com> Co-authored-by: Nikhar Abbas * increment version * Update for OpenFAST v3.0.0 * Install OF3.0.0 for tests * update for OF v3.0.0 * add publish to pypi on release * Update to ROSCO v2.3.0 * Increment Version, OF3.0 (#57) * increment version * Update for OpenFAST v3.0.0 * Install OF3.0.0 for tests * update for OF v3.0.0 * add publish to pypi on release * Update to ROSCO v2.3.0 * increment version * Update for OpenFAST v3.0.0 * Install OF3.0.0 for tests * update for OF v3.0.0 * add publish to pypi on release * Update to ROSCO v2.3.0 * add ROSCO without submodule * move ROSCO source to ROSCO folder * Move cmake-related files to ROSCO * Add back pesky ErrVar * Remove parameters_files * Merge ROSCO and _toolbox gitignore * Fix .gitignore * Remove Examples/DISCON.IN from git * Fix and point example_01 to Tune_Cases/ * Update verbiage around using ofTools vs. weis * Fix and point example_04 to Tune_Cases/ * Clean up example_06 * Clean up example_07 * Only check FlpCornerFreq if using Flp control, fixes example 05 * Make example_04 consistent with others * Let example_05 run independently from 04 * Clean up example_05, wind files * Add schema and update empty tuning yaml inputs, not connected yet * Integrate schema into turbine, controller, and examples * Only check Fl filter parameters if Fl_Mode > 0, fix example_05 * bump version to 2.3 * Compile ROSCO from ROSCO dir * Rename to CI_rosco * Add omega vs. windspeed functionality * Fix tests: 5MW U_pc and 06 example dir * Make _Toolbox vs_minspeed in rotor frame to match ROSCO * Revert ServoDyn change * change rotor speed constraint to be epsilon * rename for clarity * docs major refresh * fix FA_AccF units in debug file * docs that build locally * Deallocate arrays in ROSCO, check in example_05 * Clean up comments * remove gitmodules * furo theme * furo in requirements * move readthedocs config file, remove furo import in conf.py * add docs requirements file * typo * move index out of source folder * trying to get furo to work * import date * fix versions and titles, cleanup readthedocs requirements * typo fix, remove extras * more cleanup * bump version * no furo extension, "hack" to load RT version * proper toctree paths * specify method * add mock modules * fix typos * update python install requirements * running locally * move index to main docs dir again * update to build locally * error during warnings * automated version * cleanup * remove old docs * re-add docs * simplify * fix figure path * try alabaster * remove archived docs * Add omega vs. windspeed functionality * Fix tests: 5MW U_pc and 06 example dir * more detailed sp.optimize settings * run MBC3 in parallel * restructure driver, run initialization doe for tuning * Try new dlclose function * Update example_05 to run simple simulation twice and check result * Revert deallocation stuff * Close discon library after every sim run * Test examples on macOS and windows * Run examples instead of testing on other platforms * Skip examples in windows for now * update paths and yaml load funciton * Skip mac testing of examples * provide default U_pc for single omega/zeta case * allow for float or list-like pc tuning inputs * Change name in setup.py * WE_Vw unit fix * Pass through kp_float, if desired * Minor fixes: schema error and InputReader defaults * cleeanup for improved stability * check for doe_logs as string in load_DOE * major restructure for rsched_driver class * cleanup verbosity * run serial by default * load_parallel as linturb_option * specific IEA15MW yaml for multi omega * remove unused module imports * fix error message types * lin_file as input * add comments on inputs to LinearTurbineModel init method * remove relative file paths * provide OpenFAST linearizations for IEA15MW UMaineSemi * put plotting in specific function * fix WE_lambda units * add self in on a few necessary variables * creaete example 12 for robust scheduling * try a few mbc3 locations for import * allow list-like or numpy arrays for omega_pc and zeta_pc schedules * create and use recorder setup function * Pass Through Kp_float (#57) * Pass through kp_float, if desired * Minor fixes: schema error and InputReader defaults * fix setup_recorder to work for optimization driver too * Allow pass through of Kp_float = 0 * cleanup om problems, update om0 calc * doe levels as input * negative k_float to account for OF conventions * cleanup print statements * variable name cleanup, use calculated k_float * Add defaults to omega_,zeta_ pc and vs, allow to be numbers * use standard tuning k_float as IC * formatting update * update problem setup methods * cleanup add_dv, enable adding design variables after problem is setup * change optimization step size * more setup restructure * update verbosity * use sphinx-rtd-theme * master doc and sphinx rtd theme * index back to root folder * only ignore install folders * remove hidden toctree * furo theme * update paths * convert rt version to string * update sphinx settings * move conf * furo theme * Mostly a docs update (#61) * rename for clarity * docs major refresh * fix FA_AccF units in debug file * docs that build locally * remove gitmodules * furo theme * furo in requirements * move readthedocs config file, remove furo import in conf.py * add docs requirements file * typo * move index out of source folder * trying to get furo to work * import date * fix versions and titles, cleanup readthedocs requirements * typo fix, remove extras * more cleanup * bump version * no furo extension, "hack" to load RT version * proper toctree paths * specify method * add mock modules * fix typos * update python install requirements * running locally * move index to main docs dir again * update to build locally * error during warnings * automated version * cleanup * remove old docs * re-add docs * simplify * fix figure path * try alabaster * remove archived docs * use sphinx-rtd-theme * master doc and sphinx rtd theme * index back to root folder * only ignore install folders * remove hidden toctree * furo theme * update paths * convert rt version to string * update sphinx settings * move conf * furo theme * Pass through Kp_float = 0 (#59) * Pass through kp_float, if desired * Minor fixes: schema error and InputReader defaults * Allow pass through of Kp_float = 0 * Add flp parameters to schema * Change Fl_Mode default to 0 * Add defaults to omega_,zeta_ pc and vs, allow to be numbers * Allow single pitch tuning values in code, default U_pc to 0 * use nac acceleration for floating feedback * Fix TSR saturation for region 2.5operation * Modify system for constant power operation * Only modify pole for constant power above-rated * Remove GenEff from K calc * Update tuning, use constant power * use load_rosco_yaml * constant power * Fix broken tests * Include Fl_Mode=2 for nacelle pitching feedback * Add FOCAL inputs - hpf on floating feedback - lpf on wind speed estimator - associated schema updates * Set notch and check frequencies when Fl_Mode = 1 (fixes bug) * Skip filter step if there's an error * Update IEA-15MW test case DISCON with focal inputs * Allow Fl_Mode = 2 in ROSCO * Pass through lpf frequency * Add FOCAL tuning yaml * Set Cp contour number of levels * Add FOCAL params to various writers * Update/tune focal yaml * Add scripts for running FAST, tuning various parameters and cases * Add notebook for FAST plotting * Set up step case for testing * Change doubles to C_doubles * Define real and integer kinds, assign to all of ROSCO * Add ADJUSTL to DISCON error message * Fix Fl_Mode == 2 * Fix Fl_Mode == 2 again * Call yaw, flap, and debug only if enabled in DISOCN.IN * Make avrSWAP a ReKi and set constant kinds * Add DISCONs for testing - revert this later * Fix DISCON comparison, before DISCON's were overwritten by model * Rename DEBUG2.dbg to RootName.dbg2 * Update TestCase DISCONs to new input file * Add API change page in docs * Add link to API change on main page * Fix table headers * Fix title underlines * Fix tables again * Fix tables again * Fix version numbering in docs * Simplify FAST_directory in run_FAST * Versioning (#65) * use sphinx-rtd-theme * master doc and sphinx rtd theme * index back to root folder * only ignore install folders * remove hidden toctree * furo theme * update paths * convert rt version to string * update sphinx settings * move conf * furo theme * remove git versioning from cmake * use hard coded rosco_version * update intro write method * set nowrap for intel compilers * Add transfer of error message and clear message after each call * update install instructions * Catch nans in ROSCO at end of WSE * fix conda install typo * cleanup docs * Rename DEBUG2.dbg to RootName.dbg2 * Fix Fl_Mode == 2 * Fix Fl_Mode == 2 again * Allow Fl_Mode = 2 in ROSCO * Set notch and check frequencies when Fl_Mode = 1 (fixes bug) * Update FOCAL tuning yaml * Update TSR * Clean up and doc fix * Remove publish to pypi * Define all constant inputs to functions with kind typing * Generate Test_Case/ inputs automatically * Fix IEA15 DISCON path * Fix example 11 paths * Auto-generate tuning input yaml using schema * Add toolbox_input to doc index * Add toctree * Re-name title of toolbox_input Co-authored-by: Nikhar Abbas Co-authored-by: Xianping Du <38188001+Seager1989@users.noreply.github.com> Co-authored-by: nikhar-abbas <40865984+nikhar-abbas@users.noreply.github.com> * update listcheck method for numpy arrays * Open Loop Control (#98) * create rosco types yaml * Add more descriptions, add integer_c default, cleanup * updates for allocatability and shapes * python scripts to write ROSCO_types.f90 * reemove superfulous modules * use types from ROSCO registry * create rosco types yaml * Add more descriptions, add integer_c default, cleanup * updates for allocatability and shapes * python scripts to write ROSCO_types.f90 * reemove superfulous modules * use types from ROSCO registry * Saturate inputs to WSE. Needs some TLC, but seems to work * Reduce saturation limits on speed, torque * Re-organize, set saturation limits. Working at 3 m/s * Initial add of OL control to ROSCO: builds * Update DISCONs with open loop inputs * Fix file reading for OL_Filename * Add open loop control generation and file writing * Use DISCON_dict for more manageable DISCON file writing * Add open loop example, fix constant timeseries * Make open loop example generate power * Handle relative paths and calling from outside the run directory: - Some helper functions borrowed from OpenFAST, f/ext_control - Updated file writing * Clean up: versions, print statements * Fix SysFiles paths in CMakeLists * Tidy up Ext_DLL names * More Ext_DLL name tidying * Test write_registry.py * Update for OL Control * Move preprocessor lines * add zenodo DOI * Regenerated Types * fix shape * revert filepath change * give all types a size, ProcAddr size = 3 * update types * test registry in compile step * specify default shell * update write_registry path * remove default shell * Document API changes, provide OL input example * Fix example 14 (yaw input) * Add error catching to yaw control * Tidy up OL_Input Reading: error catching, generalize * More yaw control fixes, to model * Checkout develop CMakeLists for ROSCO * Update DISCON.INs for TestCases/ * Revert "Checkout develop CMakeLists for ROSCO" This reverts commit 87a491359d73806e3aaa59b4cfdc00f2838875df. * Revert windows cmake stuff to develop * Fix CMake again * Revert "Revert windows cmake stuff to develop" This reverts commit 39df122449b0e2055f2e12e3ce38a0c010c7bd91. * Make last cmake fix - hopefully Co-authored-by: Nikhar Abbas * Restart & registry (#99) * Convert WE saved variables to WE type * Put restart flag in localvars * Use saved filter params from LocalVar * save pitcomt last * Move IPC saved variables to localvars * Saved pi controller variables to localvar * Save RootMyb_Last to localvar * ROSCO_IO - initial commit. Include restart and debug functions * Use ROSCO IO and call restart functions * Remove debug from function.f90 * Save ACC Infile info * update for restart capabilities * add rosco_io with restart and debug functions * cleanup debug call * use registry generate types and IO * delete DFController * fix timestep mismatch * remove unnecessaray istatus check * close files * add reg test for restart * add restart option to run_openfast * add testing to CI, ignore generate files * fix fastcall * remove extra commas * specify gfortran-10 * testing flag cleanup * Use lv_strings to generate debug output * Revert "testing flag cleanup" This reverts commit 6f295563832413e96347acd82716f9aadac6d46c. * Revert "specify gfortran-10" This reverts commit 4c3154491523bcd542133ca2bce5803cdc94523f. * minor cleanup * Use kind from constants * Add some comments for clarity * put debug in if statements * separate reg tests from oother tests * Fl_Mode>0 * Remove hard coded values * Add filtered signals and WE_Vw to debug varrs * cd for regtest * Check logging level before calling debug * add fl_pitcom and pc_minpit to debugvars Co-authored-by: dzalkind * Break up if statement in open loop pitch (#100) * Break up if statement in open loop pitch * Make torque and yaw consistent with pitch: can start after some time * add bld edgewise freq to robust dict_inputs * Fix ccrotor inputs (#104) * remove interpolation of blade chord and twist * rename aerodynblade inputs * Update surface and DISCON.INs * Fix performance table paths * Allow default inputs (#110) * Allow defaults for AeroDyn inputs * Allow AeroDyn inputs to be floats, too * ipc (#105) * remove interpolation of blade chord and twist * rename aerodynblade inputs * Update surface and DISCON.INs * Fix performance table paths * Add proportional control and cleanup IPC * Add IPC and filtered RootMyc to registry * Better logic for filtering RootMOOP and fix notch filter slopes bug * Add cyclic flap conrol * Fix comments in ColemanTransformInverse * Addd IPC_KP to DISCON.IN * Error checking foro flp or ipc * add mutichannel plotting with tuples * add CMakeFiles to gitignore * Add IPC_KP to api changes * numerical qualifiers for error handling * add IPC gains to schema for pass-through ability * fix variable names * fix ipc gain printing bug * make sure IPC_KP is positive * Update Polars to point to coord files * ignore dbg2 files * Add IEA15MW_OL.yaml * update coord reader/writer * expand pitch_initial to 30 degrees * Add example 13 for IPC * Update cp surfaces and DISCONS * add examples to readme * cleanup and streaamline run_examples * Add IPC tuning vars * Allow IPC to command pitch value below peak shaving saturation limit * shorten simulation time * Fix Material parameter path * Update DISCONs again * Fix OL_Input reading * Set wind speed, rotor speed IC in example 14 * Debug OL reading * Add more debugging lines * Add more debugging lines 2 * Clean up, hone in on debug call * Disable logging level * Update discons - resolve conflict * Print when finished with ROSCO * add control packageg * Use PriPath and RootName to name dbg files * Print AvrSWAP * Revert "Use PriPath and RootName to name dbg files" This reverts commit 062fcaa55b3bf42d44f8a3f163aa883ab9552412. * Disable other examples * Print OL inputs * Allow logging level 3 * Print OL inputs * Make example shorter * Print more stuf * Print shape * Revert "Print OL inputs" This reverts commit 8e2a642bb35e46850f579ca4e69ca6d6fc93f4cc. * Update ROSCO Simulink model with IPC example * refactor flap tuning for normalization methods * improved flap controller filtering * delete extra F_FlpCornerFrerq * Update inputs, reader, and writer for OF 3.1.0 * Make sigma default interp type for multi_sigma * Use openfast 3.1.0 in CI * Fix leak...maybe * Use OF 3.1.0 in testing * Use gfotran for compile * Clean up print statements * Re-enable all examples * Update NREL-5MW AD file * Only check airfoil controls if more than one table * Update BAR models * Revert "Use gfotran for compile" This reverts commit 5a6e2b7e30287a09a09781e2ba12f9b578132e1f. * Install pyFAST for CI * Fix some paths in ex12 * Disable example 12 * Fix example 12 linear path, re-enable * Skip compilers install for mac * Try gfortran-9, no compilers * Try gfortran-10, no compilers * Skip windows compile in pytools * Re-enable windows, use gfortran as FC * Unset FC in windows * Set environment for windows when dependencies installed * Try setting environment in installation * Put conditional env setting in correct place * Try in setup again * Break up tasks: Windows vs. not * Update DISCONs * Update docs with new variables * Add example documentation * Update ROSCO Simulink model for 3.1.0 * Make IEA model float again * Reduce IEA timestep * Match DT to checkpoint time Co-authored-by: dzalkind * Increment version number * Bladed docs (#116) * Added image of Bladed control screen setup * Delete Bladed control screen.png * Adding image of Bladed control screen * Add files via upload * Minor edit 1 * Minor change 2 * Minor change 3 * Minor change 4 * Change 6 * Change 7 * Change 8 * Minor change 9 Co-authored-by: nikhar-abbas <40865984+nikhar-abbas@users.noreply.github.com> Co-authored-by: WillC-DNV <100850534+WillC-DNV@users.noreply.github.com> * Update version in API change docs * Bladed readthedocs (#117) * Added image of Bladed control screen setup * Delete Bladed control screen.png * Adding image of Bladed control screen * Add files via upload * Minor edit 1 * Minor change 2 * Minor change 3 * Minor change 4 * Change 6 * Change 7 * Change 8 * Minor change 9 * Tinker with characters in bladed instructions * Add bladed instructions to index * Change bladed toctree label * Do underline stuff * Make toctree label same as file * Remove colons from headers Co-authored-by: nikhar-abbas <40865984+nikhar-abbas@users.noreply.github.com> Co-authored-by: WillC-DNV <100850534+WillC-DNV@users.noreply.github.com> * Update docs to reflect CI process Co-authored-by: Nikhar Abbas Co-authored-by: Xianping Du <38188001+Seager1989@users.noreply.github.com> Co-authored-by: nikhar-abbas <40865984+nikhar-abbas@users.noreply.github.com> Co-authored-by: WillC-DNV <100850534+WillC-DNV@users.noreply.github.com> * Fixed wrong formatting of list items (#122) extra newline required between list elements * Regenerate types, IO with registry * Update registry so first timestep is printed * Update inverted notch to move frequency properly * Saturate inv notch corner frequency at 0 * Add tower damper mode flag * Add Azimuth tracking controller in Simulink * Always enable GenDOF, add options for simp_step * Add sweep for IPC gains and FA damper * Fix NumCoords in FAST_writer * Add turbulent case to runFAST/CaseLibrary * Add peak shaving sweep function * Increase default IPC_IntSat, make input parameter in future * Flip Ct and Cq table allocation (#129) * Flip Ct and Cq table allocation * Regen types * Remove print statements used for debugging * Update input files: IEA model has pitch actuator * Add back flap control (no idea when it was deleted) * Update discons, docs with API change * Add user-defined hh case * Fix AddF0 and RayleighDamp in FAST_reader * Add max_torque_factor for constant power control, flexible upper limit * Make update discons relative to tuning yaml * Update AddF0 and NumCoords in FAST_reader/writer * Remove matlab/rotor position control stuff Co-authored-by: nikhar-abbas <40865984+nikhar-abbas@users.noreply.github.com> Co-authored-by: Nikhar Abbas Co-authored-by: Xianping Du <38188001+Seager1989@users.noreply.github.com> Co-authored-by: WillC-DNV <100850534+WillC-DNV@users.noreply.github.com> Co-authored-by: Gustavo Hylander <74593034+ghylander@users.noreply.github.com> * Pass through (#136) * Convert WE saved variables to WE type * Put restart flag in localvars * Use saved filter params from LocalVar * save pitcomt last * Move IPC saved variables to localvars * Saved pi controller variables to localvar * Save RootMyb_Last to localvar * ROSCO_IO - initial commit. Include restart and debug functions * Use ROSCO IO and call restart functions * Remove debug from function.f90 * Save ACC Infile info * update for restart capabilities * add rosco_io with restart and debug functions * cleanup debug call * use registry generate types and IO * delete DFController * fix timestep mismatch * remove unnecessaray istatus check * close files * add reg test for restart * add restart option to run_openfast * add testing to CI, ignore generate files * fix fastcall * remove extra commas * specify gfortran-10 * testing flag cleanup * Use lv_strings to generate debug output * Revert "testing flag cleanup" This reverts commit 6f295563832413e96347acd82716f9aadac6d46c. * Revert "specify gfortran-10" This reverts commit 4c3154491523bcd542133ca2bce5803cdc94523f. * minor cleanup * Use kind from constants * Add some comments for clarity * put debug in if statements * separate reg tests from oother tests * Fl_Mode>0 * Remove hard coded values * Add filtered signals and WE_Vw to debug varrs * cd for regtest * Check logging level before calling debug * add fl_pitcom and pc_minpit to debugvars * Turn runFAST into a class * Refactor/simplify CaseLibrary * Implement initial pitch actuator * Set up steps case * Add actuator variable * Print first time step in debug outs * Fix FOCAL yaml * Set actuator to 0.25 Hz bandwidth * ROSCO 2.5.0 (#115) * FOCAL Updates (#64) * Update headers * fix bullets * make uppercase * Update turbine.py (#56) * Update turbine.py This add several lines for fixing the problem of repeated maximum values in the performance tables. This will cause the error (' the length of x and y is different.') of 'interpolate.interp1d.' * Add comments and catch when there are multiple optimal pitch angles Co-authored-by: dzalkind * increment version * Update for OpenFAST v3.0.0 * Update for OpenFAST v3.0.0 * Install OF3.0.0 for tests * update for OF v3.0.0 * add publish to pypi on release * Update to ROSCO v2.3.0 * Update Testing (#58) * Update scripts to run on eagle * Update IEA-15MW semi example: use peak shaving w/ ps_percen=0.8 * Add comparison plots to testing scripts * Update submit script for testing * Update for latest eagle runs * Add future to install dependencies * add TMax to self, define tmin in print_results * run tests in CI * generic ROSCO path * default to overwrite * fix path * import platform * separate run_testing * cleanup, specify lite test * don't run testing in after examples, oops. Co-authored-by: nikhar-abbas <40865984+nikhar-abbas@users.noreply.github.com> Co-authored-by: Nikhar Abbas * increment version * Update for OpenFAST v3.0.0 * Install OF3.0.0 for tests * update for OF v3.0.0 * add publish to pypi on release * Update to ROSCO v2.3.0 * Increment Version, OF3.0 (#57) * increment version * Update for OpenFAST v3.0.0 * Install OF3.0.0 for tests * update for OF v3.0.0 * add publish to pypi on release * Update to ROSCO v2.3.0 * increment version * Update for OpenFAST v3.0.0 * Install OF3.0.0 for tests * update for OF v3.0.0 * add publish to pypi on release * Update to ROSCO v2.3.0 * add ROSCO without submodule * move ROSCO source to ROSCO folder * Move cmake-related files to ROSCO * Add back pesky ErrVar * Remove parameters_files * Merge ROSCO and _toolbox gitignore * Fix .gitignore * Remove Examples/DISCON.IN from git * Fix and point example_01 to Tune_Cases/ * Update verbiage around using ofTools vs. weis * Fix and point example_04 to Tune_Cases/ * Clean up example_06 * Clean up example_07 * Only check FlpCornerFreq if using Flp control, fixes example 05 * Make example_04 consistent with others * Let example_05 run independently from 04 * Clean up example_05, wind files * Add schema and update empty tuning yaml inputs, not connected yet * Integrate schema into turbine, controller, and examples * Only check Fl filter parameters if Fl_Mode > 0, fix example_05 * bump version to 2.3 * Compile ROSCO from ROSCO dir * Rename to CI_rosco * Add omega vs. windspeed functionality * Fix tests: 5MW U_pc and 06 example dir * Make _Toolbox vs_minspeed in rotor frame to match ROSCO * Revert ServoDyn change * change rotor speed constraint to be epsilon * rename for clarity * docs major refresh * fix FA_AccF units in debug file * docs that build locally * Deallocate arrays in ROSCO, check in example_05 * Clean up comments * remove gitmodules * furo theme * furo in requirements * move readthedocs config file, remove furo import in conf.py * add docs requirements file * typo * move index out of source folder * trying to get furo to work * import date * fix versions and titles, cleanup readthedocs requirements * typo fix, remove extras * more cleanup * bump version * no furo extension, "hack" to load RT version * proper toctree paths * specify method * add mock modules * fix typos * update python install requirements * running locally * move index to main docs dir again * update to build locally * error during warnings * automated version * cleanup * remove old docs * re-add docs * simplify * fix figure path * try alabaster * remove archived docs * Add omega vs. windspeed functionality * Fix tests: 5MW U_pc and 06 example dir * more detailed sp.optimize settings * run MBC3 in parallel * restructure driver, run initialization doe for tuning * Try new dlclose function * Update example_05 to run simple simulation twice and check result * Revert deallocation stuff * Close discon library after every sim run * Test examples on macOS and windows * Run examples instead of testing on other platforms * Skip examples in windows for now * update paths and yaml load funciton * Skip mac testing of examples * provide default U_pc for single omega/zeta case * allow for float or list-like pc tuning inputs * Change name in setup.py * WE_Vw unit fix * Pass through kp_float, if desired * Minor fixes: schema error and InputReader defaults * cleeanup for improved stability * check for doe_logs as string in load_DOE * major restructure for rsched_driver class * cleanup verbosity * run serial by default * load_parallel as linturb_option * specific IEA15MW yaml for multi omega * remove unused module imports * fix error message types * lin_file as input * add comments on inputs to LinearTurbineModel init method * remove relative file paths * provide OpenFAST linearizations for IEA15MW UMaineSemi * put plotting in specific function * fix WE_lambda units * add self in on a few necessary variables * creaete example 12 for robust scheduling * try a few mbc3 locations for import * allow list-like or numpy arrays for omega_pc and zeta_pc schedules * create and use recorder setup function * Pass Through Kp_float (#57) * Pass through kp_float, if desired * Minor fixes: schema error and InputReader defaults * fix setup_recorder to work for optimization driver too * Allow pass through of Kp_float = 0 * cleanup om problems, update om0 calc * doe levels as input * negative k_float to account for OF conventions * cleanup print statements * variable name cleanup, use calculated k_float * Add defaults to omega_,zeta_ pc and vs, allow to be numbers * use standard tuning k_float as IC * formatting update * update problem setup methods * cleanup add_dv, enable adding design variables after problem is setup * change optimization step size * more setup restructure * update verbosity * use sphinx-rtd-theme * master doc and sphinx rtd theme * index back to root folder * only ignore install folders * remove hidden toctree * furo theme * update paths * convert rt version to string * update sphinx settings * move conf * furo theme * Mostly a docs update (#61) * rename for clarity * docs major refresh * fix FA_AccF units in debug file * docs that build locally * remove gitmodules * furo theme * furo in requirements * move readthedocs config file, remove furo import in conf.py * add docs requirements file * typo * move index out of source folder * trying to get furo to work * import date * fix versions and titles, cleanup readthedocs requirements * typo fix, remove extras * more cleanup * bump version * no furo extension, "hack" to load RT version * proper toctree paths * specify method * add mock modules * fix typos * update python install requirements * running locally * move index to main docs dir again * update to build locally * error during warnings * automated version * cleanup * remove old docs * re-add docs * simplify * fix figure path * try alabaster * remove archived docs * use sphinx-rtd-theme * master doc and sphinx rtd theme * index back to root folder * only ignore install folders * remove hidden toctree * furo theme * update paths * convert rt version to string * update sphinx settings * move conf * furo theme * Pass through Kp_float = 0 (#59) * Pass through kp_float, if desired * Minor fixes: schema error and InputReader defaults * Allow pass through of Kp_float = 0 * Add flp parameters to schema * Change Fl_Mode default to 0 * Add defaults to omega_,zeta_ pc and vs, allow to be numbers * Allow single pitch tuning values in code, default U_pc to 0 * use nac acceleration for floating feedback * Fix TSR saturation for region 2.5operation * Modify system for constant power operation * Only modify pole for constant power above-rated * Remove GenEff from K calc * Update tuning, use constant power * use load_rosco_yaml * constant power * Fix broken tests * Include Fl_Mode=2 for nacelle pitching feedback * Add FOCAL inputs - hpf on floating feedback - lpf on wind speed estimator - associated schema updates * Set notch and check frequencies when Fl_Mode = 1 (fixes bug) * Skip filter step if there's an error * Update IEA-15MW test case DISCON with focal inputs * Allow Fl_Mode = 2 in ROSCO * Pass through lpf frequency * Add FOCAL tuning yaml * Set Cp contour number of levels * Add FOCAL params to various writers * Update/tune focal yaml * Add scripts for running FAST, tuning various parameters and cases * Add notebook for FAST plotting * Set up step case for testing * Change doubles to C_doubles * Define real and integer kinds, assign to all of ROSCO * Add ADJUSTL to DISCON error message * Fix Fl_Mode == 2 * Fix Fl_Mode == 2 again * Call yaw, flap, and debug only if enabled in DISOCN.IN * Make avrSWAP a ReKi and set constant kinds * Add DISCONs for testing - revert this later * Fix DISCON comparison, before DISCON's were overwritten by model * Rename DEBUG2.dbg to RootName.dbg2 * Update TestCase DISCONs to new input file * Add API change page in docs * Add link to API change on main page * Fix table headers * Fix title underlines * Fix tables again * Fix tables again * Fix version numbering in docs * Simplify FAST_directory in run_FAST * Versioning (#65) * use sphinx-rtd-theme * master doc and sphinx rtd theme * index back to root folder * only ignore install folders * remove hidden toctree * furo theme * update paths * convert rt version to string * update sphinx settings * move conf * furo theme * remove git versioning from cmake * use hard coded rosco_version * update intro write method * set nowrap for intel compilers * Add transfer of error message and clear message after each call * update install instructions * Catch nans in ROSCO at end of WSE * fix conda install typo * cleanup docs * Rename DEBUG2.dbg to RootName.dbg2 * Fix Fl_Mode == 2 * Fix Fl_Mode == 2 again * Allow Fl_Mode = 2 in ROSCO * Set notch and check frequencies when Fl_Mode = 1 (fixes bug) * Update FOCAL tuning yaml * Update TSR * Clean up and doc fix * Remove publish to pypi * Define all constant inputs to functions with kind typing * Generate Test_Case/ inputs automatically * Fix IEA15 DISCON path * Fix example 11 paths * Auto-generate tuning input yaml using schema * Add toolbox_input to doc index * Add toctree * Re-name title of toolbox_input Co-authored-by: Nikhar Abbas Co-authored-by: Xianping Du <38188001+Seager1989@users.noreply.github.com> Co-authored-by: nikhar-abbas <40865984+nikhar-abbas@users.noreply.github.com> * update listcheck method for numpy arrays * Open Loop Control (#98) * create rosco types yaml * Add more descriptions, add integer_c default, cleanup * updates for allocatability and shapes * python scripts to write ROSCO_types.f90 * reemove superfulous modules * use types from ROSCO registry * create rosco types yaml * Add more descriptions, add integer_c default, cleanup * updates for allocatability and shapes * python scripts to write ROSCO_types.f90 * reemove superfulous modules * use types from ROSCO registry * Saturate inputs to WSE. Needs some TLC, but seems to work * Reduce saturation limits on speed, torque * Re-organize, set saturation limits. Working at 3 m/s * Initial add of OL control to ROSCO: builds * Update DISCONs with open loop inputs * Fix file reading for OL_Filename * Add open loop control generation and file writing * Use DISCON_dict for more manageable DISCON file writing * Add open loop example, fix constant timeseries * Make open loop example generate power * Handle relative paths and calling from outside the run directory: - Some helper functions borrowed from OpenFAST, f/ext_control - Updated file writing * Clean up: versions, print statements * Fix SysFiles paths in CMakeLists * Tidy up Ext_DLL names * More Ext_DLL name tidying * Test write_registry.py * Update for OL Control * Move preprocessor lines * add zenodo DOI * Regenerated Types * fix shape * revert filepath change * give all types a size, ProcAddr size = 3 * update types * test registry in compile step * specify default shell * update write_registry path * remove default shell * Document API changes, provide OL input example * Fix example 14 (yaw input) * Add error catching to yaw control * Tidy up OL_Input Reading: error catching, generalize * More yaw control fixes, to model * Checkout develop CMakeLists for ROSCO * Update DISCON.INs for TestCases/ * Revert "Checkout develop CMakeLists for ROSCO" This reverts commit 87a491359d73806e3aaa59b4cfdc00f2838875df. * Revert windows cmake stuff to develop * Fix CMake again * Revert "Revert windows cmake stuff to develop" This reverts commit 39df122449b0e2055f2e12e3ce38a0c010c7bd91. * Make last cmake fix - hopefully Co-authored-by: Nikhar Abbas * Restart & registry (#99) * Convert WE saved variables to WE type * Put restart flag in localvars * Use saved filter params from LocalVar * save pitcomt last * Move IPC saved variables to localvars * Saved pi controller variables to localvar * Save RootMyb_Last to localvar * ROSCO_IO - initial commit. Include restart and debug functions * Use ROSCO IO and call restart functions * Remove debug from function.f90 * Save ACC Infile info * update for restart capabilities * add rosco_io with restart and debug functions * cleanup debug call * use registry generate types and IO * delete DFController * fix timestep mismatch * remove unnecessaray istatus check * close files * add reg test for restart * add restart option to run_openfast * add testing to CI, ignore generate files * fix fastcall * remove extra commas * specify gfortran-10 * testing flag cleanup * Use lv_strings to generate debug output * Revert "testing flag cleanup" This reverts commit 6f295563832413e96347acd82716f9aadac6d46c. * Revert "specify gfortran-10" This reverts commit 4c3154491523bcd542133ca2bce5803cdc94523f. * minor cleanup * Use kind from constants * Add some comments for clarity * put debug in if statements * separate reg tests from oother tests * Fl_Mode>0 * Remove hard coded values * Add filtered signals and WE_Vw to debug varrs * cd for regtest * Check logging level before calling debug * add fl_pitcom and pc_minpit to debugvars Co-authored-by: dzalkind * Break up if statement in open loop pitch (#100) * Break up if statement in open loop pitch * Make torque and yaw consistent with pitch: can start after some time * add bld edgewise freq to robust dict_inputs * Fix ccrotor inputs (#104) * remove interpolation of blade chord and twist * rename aerodynblade inputs * Update surface and DISCON.INs * Fix performance table paths * Allow default inputs (#110) * Allow defaults for AeroDyn inputs * Allow AeroDyn inputs to be floats, too * ipc (#105) * remove interpolation of blade chord and twist * rename aerodynblade inputs * Update surface and DISCON.INs * Fix performance table paths * Add proportional control and cleanup IPC * Add IPC and filtered RootMyc to registry * Better logic for filtering RootMOOP and fix notch filter slopes bug * Add cyclic flap conrol * Fix comments in ColemanTransformInverse * Addd IPC_KP to DISCON.IN * Error checking foro flp or ipc * add mutichannel plotting with tuples * add CMakeFiles to gitignore * Add IPC_KP to api changes * numerical qualifiers for error handling * add IPC gains to schema for pass-through ability * fix variable names * fix ipc gain printing bug * make sure IPC_KP is positive * Update Polars to point to coord files * ignore dbg2 files * Add IEA15MW_OL.yaml * update coord reader/writer * expand pitch_initial to 30 degrees * Add example 13 for IPC * Update cp surfaces and DISCONS * add examples to readme * cleanup and streaamline run_examples * Add IPC tuning vars * Allow IPC to command pitch value below peak shaving saturation limit * shorten simulation time * Fix Material parameter path * Update DISCONs again * Fix OL_Input reading * Set wind speed, rotor speed IC in example 14 * Debug OL reading * Add more debugging lines * Add more debugging lines 2 * Clean up, hone in on debug call * Disable logging level * Update discons - resolve conflict * Print when finished with ROSCO * add control packageg * Use PriPath and RootName to name dbg files * Print AvrSWAP * Revert "Use PriPath and RootName to name dbg files" This reverts commit 062fcaa55b3bf42d44f8a3f163aa883ab9552412. * Disable other examples * Print OL inputs * Allow logging level 3 * Print OL inputs * Make example shorter * Print more stuf * Print shape * Revert "Print OL inputs" This reverts commit 8e2a642bb35e46850f579ca4e69ca6d6fc93f4cc. * Update ROSCO Simulink model with IPC example * refactor flap tuning for normalization methods * improved flap controller filtering * delete extra F_FlpCornerFrerq * Update inputs, reader, and writer for OF 3.1.0 * Make sigma default interp type for multi_sigma * Use openfast 3.1.0 in CI * Fix leak...maybe * Use OF 3.1.0 in testing * Use gfotran for compile * Clean up print statements * Re-enable all examples * Update NREL-5MW AD file * Only check airfoil controls if more than one table * Update BAR models * Revert "Use gfotran for compile" This reverts commit 5a6e2b7e30287a09a09781e2ba12f9b578132e1f. * Install pyFAST for CI * Fix some paths in ex12 * Disable example 12 * Fix example 12 linear path, re-enable * Skip compilers install for mac * Try gfortran-9, no compilers * Try gfortran-10, no compilers * Skip windows compile in pytools * Re-enable windows, use gfortran as FC * Unset FC in windows * Set environment for windows when dependencies installed * Try setting environment in installation * Put conditional env setting in correct place * Try in setup again * Break up tasks: Windows vs. not * Update DISCONs * Update docs with new variables * Add example documentation * Update ROSCO Simulink model for 3.1.0 * Make IEA model float again * Reduce IEA timestep * Match DT to checkpoint time Co-authored-by: dzalkind * Increment version number * Bladed docs (#116) * Added image of Bladed control screen setup * Delete Bladed control screen.png * Adding image of Bladed control screen * Add files via upload * Minor edit 1 * Minor change 2 * Minor change 3 * Minor change 4 * Change 6 * Change 7 * Change 8 * Minor change 9 Co-authored-by: nikhar-abbas <40865984+nikhar-abbas@users.noreply.github.com> Co-authored-by: WillC-DNV <100850534+WillC-DNV@users.noreply.github.com> * Update version in API change docs * Bladed readthedocs (#117) * Added image of Bladed control screen setup * Delete Bladed control screen.png * Adding image of Bladed control screen * Add files via upload * Minor edit 1 * Minor change 2 * Minor change 3 * Minor change 4 * Change 6 * Change 7 * Change 8 * Minor change 9 * Tinker with characters in bladed instructions * Add bladed instructions to index * Change bladed toctree label * Do underline stuff * Make toctree label same as file * Remove colons from headers Co-authored-by: nikhar-abbas <40865984+nikhar-abbas@users.noreply.github.com> Co-authored-by: WillC-DNV <100850534+WillC-DNV@users.noreply.github.com> * Update docs to reflect CI process Co-authored-by: Nikhar Abbas Co-authored-by: Xianping Du <38188001+Seager1989@users.noreply.github.com> Co-authored-by: nikhar-abbas <40865984+nikhar-abbas@users.noreply.github.com> Co-authored-by: WillC-DNV <100850534+WillC-DNV@users.noreply.github.com> * Fixed wrong formatting of list items (#122) extra newline required between list elements * Regenerate types, IO with registry * Update registry so first timestep is printed * Update inverted notch to move frequency properly * Saturate inv notch corner frequency at 0 * Add tower damper mode flag * Add Azimuth tracking controller in Simulink * Always enable GenDOF, add options for simp_step * Add sweep for IPC gains and FA damper * Fix NumCoords in FAST_writer * Add turbulent case to runFAST/CaseLibrary * Add peak shaving sweep function * Increase default IPC_IntSat, make input parameter in future * Flip Ct and Cq table allocation (#129) * Flip Ct and Cq table allocation * Regen types * Remove print statements used for debugging * Update input files: IEA model has pitch actuator * Add back flap control (no idea when it was deleted) * Update discons, docs with API change * Add user-defined hh case * Fix AddF0 and RayleighDamp in FAST_reader * Add max_torque_factor for constant power control, flexible upper limit * Make update discons relative to tuning yaml * Update AddF0 and NumCoords in FAST_reader/writer * Remove matlab/rotor position control stuff * Add initial DISCON pass through schema * Add TODO items for pull requests * Add initial pass through capability, example * Add PassThrough example yaml * Make cp filename relative to FAST_directory throughout * Remove brackets, regen input docs * Add to PassThrough example yaml * Add example 15 to testing, fix yaml * Tidy comments in CaseLibrary Co-authored-by: nikhar-abbas <40865984+nikhar-abbas@users.noreply.github.com> Co-authored-by: Nikhar Abbas Co-authored-by: Xianping Du <38188001+Seager1989@users.noreply.github.com> Co-authored-by: WillC-DNV <100850534+WillC-DNV@users.noreply.github.com> Co-authored-by: Gustavo Hylander <74593034+ghylander@users.noreply.github.com> * Add ExtControl manually from f/ext_control, compiling * Fix c_float type in registry, building * Update DISCON writer, fix reader * Add example for running Ext control, running * Max example actually call extdll, update inputs, running * Add ExtControl module! * Add ROSCO_Helpers, GetNewUnit, shorten ReadSetParameters, Functions * Update write_registry with GetNewUnit * Add open loop IPC * Robust control updates (#139) * change default interp type * improve nested MPI handling * fix cl bug, sm calc more robust, allow single plant for interp * add load from pickle capabilites * add re-try logic * save v_above_rated to controller object * fix BAR cp_ct_cq surface path * update discons * remove rogue DISCON * Pass case_inputs and rosco_dll to runFAST object * Set default T_max in power_curve case * Add rotor position control example * Add inputs for Azimuth index and rotor pos gains * Set up OL IPC example, working, refactor OL setup in RT * External Control Interface (#141) * Add ExtControl manually from f/ext_control, compiling * Fix Cp plots * Update multiple discons * Make FAST_Directory relative to yaml * Set control to ROSCO, sweep max torque * Fix c_float type in registry, building * Update DISCON writer, fix reader * Add example for running Ext control, running * Max example actually call extdll, update inputs, running * Add ExtControl module! * Add ROSCO_Helpers, GetNewUnit, shorten ReadSetParameters, Functions * Update write_registry with GetNewUnit * Tidy up RootName: remove hard-coded index * Close Cp file, fixes checkpoint test * Clean up examples, add 16 to CI testing * Change regtest name in CI * Update DISCONs * Add API change documentation * Add summary of API changes, finish external interface * Tidy code, point to location for using ExtDLL * F/zmq (#145) * cleanup api change table * zeromq client and f90 files - initia lcommit * add zmq install reqs * remove yaw-by-ipc * typo fix * add zeroMQ interface to registry and source - enable zeroMQ for yaw control * cleanup to compile, move ZMQ_Mode to flags, write DISCONS * only set ZMQ_Client if flag is enabled * fix bug in discons * minor updates and add sim with wind direction * change to dict inputs for control interface * add zmq example * Revert "remove yaw-by-ipc" This reverts commit 2ca2859884313aa6d8fdd217a7fede73802a5fcf. * Enable Yaw-by-ipc again * update and execute zeromq example * add zmq to dependencies * sudo for apt-get * libzmq3-dev typo * setup cmake * rename example 16 to 17 * read empty line * update types, regen discons * fix build path * remove non-ubuntu examples, type in cmake command * Set ROSCO=True * typo fix and update DISCONs * document API changes * newlines and in-text code * updated removed inputs, fix intext code syntax * run example 17 * Add description to example 17 * zeromq -> pyzmq, cleanup * better table for new/modified/removed * fix real(8) * cleanup zmqVar conventions and uses. Call zmq using a time period * Update DISCONS * run all examples * Fix Y_uSwitch description * update comm address example * execute with runpy instead of importlib * move zmq interface classes to control_interface * Properly shutdown ZMQ interface * add IEA15MW_ExtInterface.yaml * Incorporate runFAST stuff from WEIS, clean up * Remove specific rosco_dll * Publish artifacts from examples * Clean up examples following runFAST business * move archive artifacts * Fix build dir in example 17 * Switch install/develop in pytools CI * archive even if exampless fail * add zmq build instructions * cleanup and rename sim * Remove BITS_IN_ADDR stuff * Pass case_inputs and rosco_dll to runFAST object * Pass correct DLL_FileName for external control * Tidy example 15 commenting Co-authored-by: dzalkind * Tidy up OL_Mode * Add unwrap function, working on OL target * Set azimuth ol_timeseries in radians * Move example number * Add default Ind_Azimuth, regen DISCONs * Tidy merge, building * Calculate azimuth error * Make PID control, building * Add collective blade pitch signal for WSE, shutdown * Clean up merge: two sigma functions, finish adding collective BP * Use IPC always in IEA-15MW case * Add IPC_SatMode input * Force IPC_SatMode to be an int in writer * Fix IPC_SatMode cherry pick * Fix IPC_SatMode/IntSat description, update DISCONs * Add new IPC_SatModes * Fix ******s in dbg files * Move example 18 to 19 (rotor position control) * Tidy up types, regen Types, IO, DISCONs * Make openfast_exe an attribute * Update and run example_19 * Set up PID control for GenTqAz, working in steady * Set up turbulence example * Rate limit blade pitch on first time step * Initialize AzBuffer * Fix open loop IPC * Add SCADA to example_19, needs tuning * Fix PID, tune gains for RAAW, working * Sync OF tools with WEIS * Add DT_Out to ROSCO to downsample debug files * Update user defined controller parameters deep in control_param dict * Update discons, registry * Move BlPitchC -> BlPitchCMeas(ured) * Update registry description * Remove old update_discons * Start DISCON_dict with schema defaults * Allow DEFAULT in read_DISCON * Set up baseline cases in example_19 * Set up sweep cases in run_FAST * Fix bug in FAST_writer * Rename example * Complete merge, building * Get openfast read/write from 3.4 * Fix error message in dbl read * Update example number for output file * Change default DT_Out to 0 * Remove raaw example parts * Update discons * Give new model, relative path for example * Regen registry * Tidy up indices, example running * Remove old update_discons * Clean up print statements * Clean up rpc example * Change name of rpc example * Tidy up paths in RPC example * Fix original open loop set up * Fix OL file writing for Cable/StC * Fix OL indices again * Remove duplicate PF_Mode * Regen registry files, discons * Clean up cable control example * Add RPC example to CI * Remove duplicate AWC inputs from registry * Clean up open loop yaw control * Clean up AWC implementation again * Regen registry * Revert AWC controller * Allow defaults for DT_Out, LoggingLevel * Clean up run_FAST * Update input writer, inputs * Document API changes * Fix relative Cp filepaths * Move all CntrPar%* assignments to ReadControlParameterFileSub Otherwise, they are lost in restarts * Write dbg3 only at DT_Out * Tidy up examples * Pass fst_vt from runFAST properly * Change AFAeroMod only in DLC 1.4 sims * Saturate lower limit of WSE initialization * Give max() proper inputs * Do a light clean up * Revert moordyn * Remove duplicate import * Clean up types * Saturate values too large for fortran write format * Fix example 25 output folder * Update docs to use python 3.9 * Add Tf for derivative term of RPC * Let user_hh inputs be different lengths * Use Fst Dens and KinVisc * Regen registry, DISCONs * Control yaw in open loop with OL_Mode 2 * Declare dummy partials in robust_scheduling * Check for error/return after trying to read OL_Filename * Try python 3.11 * Use python 3.11 throughout * Debug robust_tuning * Debug some more * Remove openmdao recorders * Debug better * Add more print statements * Print more stuff * Print in interp_matrix * Fix matrix_3D * Use older python-toolbox * Revert debugging attempts * Make output directory if it doesn't exist * Add error catch when OL IPC is enabled but IPC not enabled in ServoDyn * Enable all examples, print time to execute better --------- Co-authored-by: Nikhar Abbas Co-authored-by: Xianping Du <38188001+Seager1989@users.noreply.github.com> Co-authored-by: nikhar-abbas <40865984+nikhar-abbas@users.noreply.github.com> Co-authored-by: WillC-DNV <100850534+WillC-DNV@users.noreply.github.com> Co-authored-by: Gustavo Hylander <74593034+ghylander@users.noreply.github.com> --- Examples/11_robust_tuning.py | 1 + Examples/test_examples.py | 2 +- ROSCO/src/Controllers.f90 | 2 +- ROSCO/src/ReadSetParameters.f90 | 10 ++++++++- ROSCO_toolbox/ofTools/case_gen/CaseLibrary.py | 21 ++++++++++++------- 5 files changed, 25 insertions(+), 11 deletions(-) diff --git a/Examples/11_robust_tuning.py b/Examples/11_robust_tuning.py index 30693419..4b07629c 100644 --- a/Examples/11_robust_tuning.py +++ b/Examples/11_robust_tuning.py @@ -45,6 +45,7 @@ def run_example(): # Path options example_out_dir = os.path.join(os.path.dirname(os.path.abspath(__file__)), 'examples_out') + os.makedirs(example_out_dir,exist_ok=True) output_name = '11_robust_scheduling' path_options = {'output_dir': example_out_dir, 'output_name': output_name diff --git a/Examples/test_examples.py b/Examples/test_examples.py index 8c3ef7d4..9a6c95ed 100644 --- a/Examples/test_examples.py +++ b/Examples/test_examples.py @@ -54,7 +54,7 @@ def execute_script(fscript): # Use runpy to execute examples s = time() runpy.run_path(os.path.realpath(fullpath), run_name='__main__') - print(time() - s, "seconds to run") + print(f"{fscript} took {time() - s} seconds to run") class TestExamples(unittest.TestCase): diff --git a/ROSCO/src/Controllers.f90 b/ROSCO/src/Controllers.f90 index 0920aca1..e05f9add 100644 --- a/ROSCO/src/Controllers.f90 +++ b/ROSCO/src/Controllers.f90 @@ -408,7 +408,7 @@ SUBROUTINE YawRateControl(avrSWAP, CntrPar, LocalVar, objInst, zmqVar, DebugVar, ! If using open loop yaw rate control, overwrite controlled output ! Open loop yaw rate control - control input in rad/s - IF ((CntrPar%OL_Mode == 1) .AND. (CntrPar%Ind_YawRate > 0)) THEN + IF ((CntrPar%OL_Mode > 0) .AND. (CntrPar%Ind_YawRate > 0)) THEN IF (LocalVar%Time >= CntrPar%OL_Breakpoints(1)) THEN avrSWAP(48) = interp1d(CntrPar%OL_Breakpoints,CntrPar%OL_YawRate,LocalVar%Time, ErrVar) ENDIF diff --git a/ROSCO/src/ReadSetParameters.f90 b/ROSCO/src/ReadSetParameters.f90 index 7df23a84..ef2efaa2 100644 --- a/ROSCO/src/ReadSetParameters.f90 +++ b/ROSCO/src/ReadSetParameters.f90 @@ -657,6 +657,9 @@ SUBROUTINE ReadControlParameterFileSub(CntrPar, LocalVar, zmqVar, accINFILE, acc CALL GetNewUnit(UnOpenLoop, ErrVar) CALL Read_OL_Input(CntrPar%OL_Filename,UnOpenLoop,OL_Count,CntrPar%OL_Channels, ErrVar) + IF (ErrVar%aviFAIL < 0) THEN + RETURN + ENDIF CntrPar%OL_Breakpoints = CntrPar%OL_Channels(:,CntrPar%Ind_Breakpoint) @@ -1392,7 +1395,12 @@ SUBROUTINE CheckInputs(LocalVar, CntrPar, avrSWAP, ErrVar, size_avcMSG) ErrVar%ErrMsg = 'Pitch angle actuator not requested.' ENDIF - IF (NINT(avrSWAP(28)) == 0 .AND. ((CntrPar%IPC_ControlMode > 0) .OR. (CntrPar%Y_ControlMode > 1))) THEN + IF ((NINT(avrSWAP(28)) == 0) .AND. & + ((CntrPar%IPC_ControlMode > 0) .OR. & + (CntrPar%Y_ControlMode > 1) .OR. & + (CntrPar%Ind_BldPitch(2) > 0) .OR. & + (CntrPar%Ind_BldPitch(3) > 0) & + )) THEN ErrVar%aviFAIL = -1 ErrVar%ErrMsg = 'IPC enabled, but Ptch_Cntrl in ServoDyn has a value of 0. Set it to 1 for individual pitch control.' ENDIF diff --git a/ROSCO_toolbox/ofTools/case_gen/CaseLibrary.py b/ROSCO_toolbox/ofTools/case_gen/CaseLibrary.py index ee7b34e6..bc22598b 100644 --- a/ROSCO_toolbox/ofTools/case_gen/CaseLibrary.py +++ b/ROSCO_toolbox/ofTools/case_gen/CaseLibrary.py @@ -333,21 +333,26 @@ def user_hh(**wind_case_opts): ''' Uniform, hub-height wind file Expected inputs: - TMax TODO: someday make all TMaxs TMax - wind_inputs (list of string wind inputs filenames) + TMax (float or array) of simulation TMax + wind_filenames (list of string wind inputs filenames) ''' - if 'TMax' in wind_case_opts: - TMax = wind_case_opts['TMax'] - else: - TMax = 720 + # Default is 720 for all cases + TMax = wind_case_opts.get('TMax', 720) if 'wind_filenames' not in wind_case_opts: - raise Exception('Define wind_filenames when using turb_bts case generator') + raise Exception('Define wind_filenames when using user_hh case generator') + + # Make into array + if not hasattr(TMax,'__len__'): + TMax = len(wind_case_opts['wind_filenames']) * [TMax] + + + # wind inflow case_inputs = base_op_case() - case_inputs[("Fst","TMax")] = {'vals':[TMax], 'group':0} + case_inputs[("Fst","TMax")] = {'vals':TMax, 'group':1} case_inputs[("InflowWind","WindType")] = {'vals':[2], 'group':0} case_inputs[("InflowWind","Filename_Uni")] = {'vals':wind_case_opts['wind_filenames'], 'group':1} From c75738eee4ab4864e1c9d344ce2cfc0dd80f272d Mon Sep 17 00:00:00 2001 From: mvanv <92317608+mvanv@users.noreply.github.com> Date: Mon, 6 Nov 2023 22:00:01 +0100 Subject: [PATCH 135/224] Modified ZeroMQ interface to include pitch offsets (#261) * Modified ZeroMQ interface to include pitch setpoints * Fixed zeromq time limit issue * Fixed simulation restart bug when using zeromq * Light formatting changes * Remove specific ZeroMQ data structure, add to LocalVars, rename * Full remove ZMQ_Variables * Tidy NREL5MW tuning yaml and control_interface * Raise exception in control_interface if DLL returns an error * Fix name of debug file * Combine ZMQ examples, check outputs * Check ZMQ update period based on simulation update period * Initialize ZMQ local vars * Make tuning yaml, zmq example consistent with others * Update DISCONs * Let DISCON in control_interface be initialized even if there's an error * Remove extra zmq example --------- Co-authored-by: dzalkind --- Examples/17_zeromq_interface.py | 59 ++++++++++++++++--- ROSCO/rosco_registry/rosco_types.yaml | 16 ++--- ROSCO/rosco_registry/write_registry.py | 5 +- ROSCO/src/Controllers.f90 | 10 ++-- ROSCO/src/DISCON.F90 | 17 +++--- ROSCO/src/ROSCO_Helpers.f90 | 2 +- ROSCO/src/ROSCO_IO.f90 | 29 +++++---- ROSCO/src/ROSCO_Types.f90 | 7 +-- ROSCO/src/ReadSetParameters.f90 | 22 +++---- ROSCO/src/ZeroMQInterface.f90 | 14 +++-- ROSCO_toolbox/control_interface.py | 28 +++++---- ROSCO_toolbox/controller.py | 3 +- ROSCO_toolbox/inputs/toolbox_schema.yaml | 5 ++ ROSCO_toolbox/utilities.py | 4 +- Test_Cases/BAR_10/BAR_10_DISCON.IN | 4 +- .../DISCON-UMaineSemi.IN | 4 +- Test_Cases/MHK_RM1/MHK_RM1_DISCON.IN | 4 +- Test_Cases/NREL-5MW/DISCON.IN | 4 +- .../NREL_2p8_127/NREL-2p8-127_DISCON.IN | 4 +- Tune_Cases/NREL2p8.yaml | 1 + 20 files changed, 151 insertions(+), 91 deletions(-) diff --git a/Examples/17_zeromq_interface.py b/Examples/17_zeromq_interface.py index ae8a34ae..c74e2699 100644 --- a/Examples/17_zeromq_interface.py +++ b/Examples/17_zeromq_interface.py @@ -18,25 +18,44 @@ from ROSCO_toolbox import sim as ROSCO_sim from ROSCO_toolbox import turbine as ROSCO_turbine from ROSCO_toolbox import controller as ROSCO_controller +from ROSCO_toolbox.ofTools.fast_io import output_processing import numpy as np import multiprocessing as mp +TIME_CHECK = 30 +DESIRED_YAW_OFFSET = 20 +DESIRED_PITCH_OFFSET = np.deg2rad(2) * np.sin(0.1 * TIME_CHECK) + np.deg2rad(2) + def run_zmq(): connect_zmq = True - s = turbine_zmq_server(network_address="tcp://*:5555", timeout=10.0, verbose=True) + s = turbine_zmq_server(network_address="tcp://*:5555", timeout=10.0) while connect_zmq: # Get latest measurements from ROSCO measurements = s.get_measurements() # Decide new control input based on measurements + + # Yaw set point current_time = measurements['Time'] if current_time <= 10.0: yaw_setpoint = 0.0 else: - yaw_setpoint = 20.0 + yaw_setpoint = DESIRED_YAW_OFFSET + + # Pitch offset + if current_time >= 10.0: + col_pitch_command = np.deg2rad(2) * np.sin(0.1 * current_time) + np.deg2rad(2) # Implement dynamic induction control + else: + col_pitch_command = 0.0 + + # Send new commands back to ROSCO + pitch_command = 3 * [0] + pitch_command[0] = col_pitch_command + pitch_command[1] = col_pitch_command + pitch_command[2] = col_pitch_command - # Send new setpoints back to ROSCO - s.send_setpoints(nacelleHeading=yaw_setpoint) + # Send new setpoints back to ROSCO + s.send_setpoints(bladePitch=pitch_command, nacelleHeading=yaw_setpoint) if measurements['iStatus'] == -1: connect_zmq = False @@ -56,6 +75,7 @@ def sim_rosco(): # Enable ZeroMQ & yaw control controller_params['Y_ControlMode'] = 1 controller_params['ZMQ_Mode'] = 1 + controller_params['ZMQ_UpdatePeriod'] = 0.025 # Specify controller dynamic library path and name this_dir = os.path.dirname(os.path.abspath(__file__)) @@ -76,7 +96,7 @@ def sim_rosco(): # Load turbine data from OpenFAST and rotor performance text file cp_filename = os.path.join( - tune_dir, path_params['FAST_directory'], path_params['rotor_performance_filename']) + tune_dir, path_params['rotor_performance_filename']) turbine.load_from_fast( path_params['FAST_InputFile'], os.path.join(tune_dir, path_params['FAST_directory']), @@ -84,11 +104,14 @@ def sim_rosco(): ) # Tune controller + controller_params['LoggingLevel'] = 2 controller = ROSCO_controller.Controller(controller_params) controller.tune_controller(turbine) # Write parameter input file - param_filename = os.path.join(this_dir, 'DISCON_zmq.IN') + sim_dir = os.path.join(example_out_dir,'17_ZeroMQ') + os.makedirs(sim_dir,exist_ok=True) + param_filename = os.path.join(sim_dir, 'DISCON_zmq.IN') write_DISCON( turbine, controller, param_file=param_filename, @@ -97,7 +120,11 @@ def sim_rosco(): # Load controller library - controller_int = ROSCO_ci.ControllerInterface(lib_name, param_filename=param_filename, sim_name='sim-zmq') + controller_int = ROSCO_ci.ControllerInterface( + lib_name, + param_filename=param_filename, + sim_name=os.path.join(sim_dir,'sim-zmq') + ) # Load the simulator sim = ROSCO_sim.Sim(turbine, controller_int) @@ -121,8 +148,24 @@ def sim_rosco(): if False: plt.show() else: - plt.savefig(os.path.join(example_out_dir, '16_NREL5MW_zmqYaw.png')) + plt.savefig(os.path.join(example_out_dir, '17_NREL5MW_ZMQ.png')) + + # Check that info is passed to ROSCO + op = output_processing.output_processing() + local_vars = op.load_fast_out([os.path.join(sim_dir,'sim-zmq.RO.dbg2')], tmin=0) + fig, axs = plt.subplots(2,1) + axs[0].plot(local_vars[0]['Time'],local_vars[0]['ZMQ_YawOffset']) + axs[1].plot(local_vars[0]['Time'],local_vars[0]['ZMQ_PitOffset']) + + if False: + plt.show() + else: + plt.savefig(os.path.join(example_out_dir, '17_NREL5MW_ZMQ_Setpoints.png')) + # Spot check input at time = 30 sec. + ind_30 = local_vars[0]['Time'] == TIME_CHECK + np.testing.assert_almost_equal(local_vars[0]['ZMQ_YawOffset'][ind_30], DESIRED_YAW_OFFSET) + np.testing.assert_almost_equal(local_vars[0]['ZMQ_PitOffset'][ind_30], DESIRED_PITCH_OFFSET, decimal=3) if __name__ == "__main__": p1 = mp.Process(target=run_zmq) diff --git a/ROSCO/rosco_registry/rosco_types.yaml b/ROSCO/rosco_registry/rosco_types.yaml index 21738501..f9a8ba51 100644 --- a/ROSCO/rosco_registry/rosco_types.yaml +++ b/ROSCO/rosco_registry/rosco_types.yaml @@ -1264,6 +1264,13 @@ LocalVariables: <<: *complex description: Complex angle for each blade, sum of modes? size: 3 + ZMQ_YawOffset: + <<: *real + description: Yaw offsety command, [rad] + ZMQ_PitOffset: + <<: *real + size: 3 + description: Pitch command offset provided by ZeroMQ WE: <<: *derived_type id: WE @@ -1443,14 +1450,7 @@ ExtDLL_Type: size: 3 length: 1024 description: The name of the procedure in the DLL that will be called. - -ZMQ_Variables: - ZMQ_Flag: - <<: *logical - description: Flag if we're using zeroMQ at all (0-False, 1-True) - Yaw_Offset: - <<: *real - description: Yaw offsety command, [rad] + ExtControlType: avrSWAP: diff --git a/ROSCO/rosco_registry/write_registry.py b/ROSCO/rosco_registry/write_registry.py index eeaa38a8..e8ede870 100644 --- a/ROSCO/rosco_registry/write_registry.py +++ b/ROSCO/rosco_registry/write_registry.py @@ -118,13 +118,12 @@ def write_roscoio(yfile): # ------------------------------------------------ # ------------ ReadRestartFile ------------------ # ------------------------------------------------ - file.write('SUBROUTINE ReadRestartFile(avrSWAP, LocalVar, CntrPar, objInst, PerfData, RootName, size_avcOUTNAME, zmqVar, ErrVar)\n') + file.write('SUBROUTINE ReadRestartFile(avrSWAP, LocalVar, CntrPar, objInst, PerfData, RootName, size_avcOUTNAME, ErrVar)\n') file.write(" TYPE(LocalVariables), INTENT(INOUT) :: LocalVar\n") file.write(" TYPE(ControlParameters), INTENT(INOUT) :: CntrPar\n") file.write(" TYPE(ObjectInstances), INTENT(INOUT) :: objInst\n") file.write(" TYPE(PerformanceData), INTENT(INOUT) :: PerfData\n") file.write(" TYPE(ErrorVariables), INTENT(INOUT) :: ErrVar\n") - file.write(" TYPE(ZMQ_Variables), INTENT(INOUT) :: zmqVar\n") file.write(" REAL(ReKi), INTENT(IN) :: avrSWAP(*)\n") file.write(" INTEGER(IntKi), INTENT(IN) :: size_avcOUTNAME\n") file.write(" CHARACTER(size_avcOUTNAME-1), INTENT(IN) :: RootName \n") @@ -163,7 +162,7 @@ def write_roscoio(yfile): file.write(' Close ( Un )\n') file.write(' ENDIF\n') file.write(' ! Read Parameter files\n') - file.write(' CALL ReadControlParameterFileSub(CntrPar, LocalVar, zmqVar, LocalVar%ACC_INFILE, LocalVar%ACC_INFILE_SIZE, RootName, ErrVar)\n') + file.write(' CALL ReadControlParameterFileSub(CntrPar, LocalVar, LocalVar%ACC_INFILE, LocalVar%ACC_INFILE_SIZE, RootName, ErrVar)\n') file.write(' IF (CntrPar%WE_Mode > 0) THEN\n') file.write(' CALL READCpFile(CntrPar, PerfData, ErrVar)\n') file.write(' ENDIF\n') diff --git a/ROSCO/src/Controllers.f90 b/ROSCO/src/Controllers.f90 index e05f9add..89786ff0 100644 --- a/ROSCO/src/Controllers.f90 +++ b/ROSCO/src/Controllers.f90 @@ -109,6 +109,9 @@ SUBROUTINE PitchControl(avrSWAP, CntrPar, LocalVar, objInst, DebugVar, ErrVar) IF (CntrPar%IPC_SatMode == 1) THEN LocalVar%PitCom(K) = saturate(LocalVar%PitCom(K), LocalVar%PC_MinPit, CntrPar%PC_MaxPit) END IF + + ! Add ZeroMQ pitch commands + LocalVar%PitCom(K) = LocalVar%PitCom(K) + LocalVar%ZMQ_PitOffset(K) ! Rate limit LocalVar%PitCom(K) = ratelimit(LocalVar%PitCom(K), CntrPar%PC_MinRat, CntrPar%PC_MaxRat, LocalVar%DT, LocalVar%restart, LocalVar%rlP,objInst%instRL,LocalVar%BlPitch(K)) ! Saturate the overall command of blade K using the pitch rate limit @@ -299,14 +302,14 @@ SUBROUTINE VariableSpeedControl(avrSWAP, CntrPar, LocalVar, objInst, ErrVar) END SUBROUTINE VariableSpeedControl !------------------------------------------------------------------------------------------------------------------------------- - SUBROUTINE YawRateControl(avrSWAP, CntrPar, LocalVar, objInst, zmqVar, DebugVar, ErrVar) + SUBROUTINE YawRateControl(avrSWAP, CntrPar, LocalVar, objInst, DebugVar, ErrVar) ! Yaw rate controller ! Y_ControlMode = 0, No yaw control ! Y_ControlMode = 1, Yaw rate control using yaw drive ! TODO: Lots of R2D->D2R, this should be cleaned up. ! TODO: The constant offset implementation is sort of circular here as a setpoint is already being defined in SetVariablesSetpoints. This could also use cleanup - USE ROSCO_Types, ONLY : ControlParameters, LocalVariables, ObjectInstances, DebugVariables, ErrorVariables, ZMQ_Variables + USE ROSCO_Types, ONLY : ControlParameters, LocalVariables, ObjectInstances, DebugVariables, ErrorVariables REAL(ReKi), INTENT(INOUT) :: avrSWAP(*) ! The swap array, used to pass data to, and receive data from, the DLL controller. @@ -315,7 +318,6 @@ SUBROUTINE YawRateControl(avrSWAP, CntrPar, LocalVar, objInst, zmqVar, DebugVar, TYPE(ObjectInstances), INTENT(INOUT) :: objInst TYPE(DebugVariables), INTENT(INOUT) :: DebugVar TYPE(ErrorVariables), INTENT(INOUT) :: ErrVar - TYPE(ZMQ_Variables), INTENT(INOUT) :: zmqVar ! Allocate Variables REAL(DbKi), SAVE :: NacVaneOffset ! For offset control @@ -344,7 +346,7 @@ SUBROUTINE YawRateControl(avrSWAP, CntrPar, LocalVar, objInst, zmqVar, DebugVar, ! Compute/apply offset IF (CntrPar%ZMQ_Mode == 1) THEN - NacVaneOffset = zmqVar%Yaw_Offset + NacVaneOffset = LocalVar%ZMQ_YawOffset ELSE NacVaneOffset = CntrPar%Y_MErrSet ! (deg) # Offset from setpoint ENDIF diff --git a/ROSCO/src/DISCON.F90 b/ROSCO/src/DISCON.F90 index 836cca07..c9563de5 100644 --- a/ROSCO/src/DISCON.F90 +++ b/ROSCO/src/DISCON.F90 @@ -49,7 +49,7 @@ SUBROUTINE DISCON(avrSWAP, aviFAIL, accINFILE, avcOUTNAME, avcMSG) BIND (C, NAME CHARACTER(KIND=C_CHAR), INTENT(IN ) :: accINFILE(NINT(avrSWAP(50))) ! The name of the parameter input file CHARACTER(KIND=C_CHAR), INTENT(IN ) :: avcOUTNAME(NINT(avrSWAP(51))) ! OUTNAME (Simulation RootName) CHARACTER(KIND=C_CHAR), INTENT(INOUT) :: avcMSG(NINT(avrSWAP(49))) ! MESSAGE (Message from DLL to simulation code [ErrMsg]) The message which will be displayed by the calling program if aviFAIL <> 0. -CHARACTER(SIZE(avcOUTNAME)-1) :: RootName ! a Fortran version of the input C string (not considered an array here) [subtract 1 for the C null-character] +CHARACTER(SIZE(avcOUTNAME)) :: RootName ! a Fortran version of the input C string (not considered an array here) [subtract 1 for the C null-character] CHARACTER(SIZE(avcMSG)-1) :: ErrMsg ! a Fortran version of the C string argument (not considered an array here) [subtract 1 for the C null-character] TYPE(ControlParameters), SAVE :: CntrPar @@ -58,7 +58,6 @@ SUBROUTINE DISCON(avrSWAP, aviFAIL, accINFILE, avcOUTNAME, avcMSG) BIND (C, NAME TYPE(PerformanceData), SAVE :: PerfData TYPE(DebugVariables), SAVE :: DebugVar TYPE(ErrorVariables), SAVE :: ErrVar -TYPE(ZMQ_Variables), SAVE :: zmqVar TYPE(ExtControlType), SAVE :: ExtDLL @@ -72,7 +71,7 @@ SUBROUTINE DISCON(avrSWAP, aviFAIL, accINFILE, avcOUTNAME, avcMSG) BIND (C, NAME ! Check for restart IF ( (NINT(avrSWAP(1)) == -9) .AND. (aviFAIL >= 0)) THEN ! Read restart files - CALL ReadRestartFile(avrSWAP, LocalVar, CntrPar, objInst, PerfData, RootName, SIZE(avcOUTNAME), zmqVar, ErrVar) + CALL ReadRestartFile(avrSWAP, LocalVar, CntrPar, objInst, PerfData, RootName, SIZE(avcOUTNAME), ErrVar) IF ( CntrPar%LoggingLevel > 0 ) THEN CALL Debug(LocalVar, CntrPar, DebugVar, ErrVar, avrSWAP, RootName, SIZE(avcOUTNAME)) END IF @@ -82,7 +81,7 @@ SUBROUTINE DISCON(avrSWAP, aviFAIL, accINFILE, avcOUTNAME, avcMSG) BIND (C, NAME CALL ReadAvrSWAP(avrSWAP, LocalVar, CntrPar) ! Set Control Parameters -CALL SetParameters(avrSWAP, accINFILE, SIZE(avcMSG), CntrPar, LocalVar, objInst, PerfData, zmqVar, RootName, ErrVar) +CALL SetParameters(avrSWAP, accINFILE, SIZE(avcMSG), CntrPar, LocalVar, objInst, PerfData, RootName, ErrVar) ! Call external controller, if desired IF (CntrPar%Ext_Mode > 0 .AND. ErrVar%aviFAIL >= 0) THEN @@ -97,8 +96,8 @@ SUBROUTINE DISCON(avrSWAP, aviFAIL, accINFILE, avcOUTNAME, avcMSG) BIND (C, NAME IF ((LocalVar%iStatus == -8) .AND. (ErrVar%aviFAIL >= 0)) THEN ! Write restart files CALL WriteRestartFile(LocalVar, CntrPar, ErrVar, objInst, RootName, SIZE(avcOUTNAME)) ENDIF - IF (zmqVar%ZMQ_Flag) THEN - CALL UpdateZeroMQ(LocalVar, CntrPar, zmqVar, ErrVar) + IF (CntrPar%ZMQ_Mode > 0) THEN + CALL UpdateZeroMQ(LocalVar, CntrPar, ErrVar) ENDIF CALL WindSpeedEstimator(LocalVar, CntrPar, objInst, PerfData, DebugVar, ErrVar) @@ -109,7 +108,7 @@ SUBROUTINE DISCON(avrSWAP, aviFAIL, accINFILE, avcOUTNAME, avcMSG) BIND (C, NAME CALL PitchControl(avrSWAP, CntrPar, LocalVar, objInst, DebugVar, ErrVar) IF (CntrPar%Y_ControlMode > 0) THEN - CALL YawRateControl(avrSWAP, CntrPar, LocalVar, objInst, zmqVar, DebugVar, ErrVar) + CALL YawRateControl(avrSWAP, CntrPar, LocalVar, objInst, DebugVar, ErrVar) END IF IF (CntrPar%Flp_Mode > 0) THEN @@ -129,8 +128,8 @@ SUBROUTINE DISCON(avrSWAP, aviFAIL, accINFILE, avcOUTNAME, avcMSG) BIND (C, NAME IF ( CntrPar%LoggingLevel > 0 ) THEN CALL Debug(LocalVar, CntrPar, DebugVar, ErrVar, avrSWAP, RootName, SIZE(avcOUTNAME)) END IF -ELSEIF ((LocalVar%iStatus == -1) .AND. (zmqVar%ZMQ_Flag)) THEN - CALL UpdateZeroMQ(LocalVar, CntrPar, zmqVar, ErrVar) +ELSEIF ((LocalVar%iStatus == -1) .AND. (CntrPar%ZMQ_Mode > 0)) THEN + CALL UpdateZeroMQ(LocalVar, CntrPar, ErrVar) END IF diff --git a/ROSCO/src/ROSCO_Helpers.f90 b/ROSCO/src/ROSCO_Helpers.f90 index 1b0f1c70..68209ce9 100644 --- a/ROSCO/src/ROSCO_Helpers.f90 +++ b/ROSCO/src/ROSCO_Helpers.f90 @@ -943,7 +943,7 @@ SUBROUTINE ParseDbAry_Opt ( FileLines, ParamName, Ary, AryLen, FileName, ErrVar, ENDIF Ary = 0 ! Default of allocatable arrays is 0 for now - PRINT *, "ROSCO Warning: Did not find correct size"//TRIM( ParamName )//" in input file. Using default value of [", Ary, "]" + PRINT *, "ROSCO Warning: Did not find correct size "//TRIM( ParamName )//" in input file. Using default value of [", Ary, "]" ENDIF IF (FoundLine) THEN diff --git a/ROSCO/src/ROSCO_IO.f90 b/ROSCO/src/ROSCO_IO.f90 index 1b4e2c4c..d1863954 100644 --- a/ROSCO/src/ROSCO_IO.f90 +++ b/ROSCO/src/ROSCO_IO.f90 @@ -17,7 +17,7 @@ SUBROUTINE WriteRestartFile(LocalVar, CntrPar, ErrVar, objInst, RootName, size_a TYPE(ObjectInstances), INTENT(INOUT) :: objInst TYPE(ErrorVariables), INTENT(INOUT) :: ErrVar INTEGER(IntKi), INTENT(IN) :: size_avcOUTNAME - CHARACTER(size_avcOUTNAME-1), INTENT(IN) :: RootName + CHARACTER(size_avcOUTNAME), INTENT(IN) :: RootName INTEGER(IntKi) :: Un ! I/O unit for pack/unpack (checkpoint & restart) INTEGER(IntKi) :: I ! Generic index. @@ -220,6 +220,10 @@ SUBROUTINE WriteRestartFile(LocalVar, CntrPar, ErrVar, objInst, RootName, size_a WRITE( Un, IOSTAT=ErrStat) LocalVar%AWC_complexangle(1) WRITE( Un, IOSTAT=ErrStat) LocalVar%AWC_complexangle(2) WRITE( Un, IOSTAT=ErrStat) LocalVar%AWC_complexangle(3) + WRITE( Un, IOSTAT=ErrStat) LocalVar%ZMQ_YawOffset + WRITE( Un, IOSTAT=ErrStat) LocalVar%ZMQ_PitOffset(1) + WRITE( Un, IOSTAT=ErrStat) LocalVar%ZMQ_PitOffset(2) + WRITE( Un, IOSTAT=ErrStat) LocalVar%ZMQ_PitOffset(3) WRITE( Un, IOSTAT=ErrStat) LocalVar%WE%om_r WRITE( Un, IOSTAT=ErrStat) LocalVar%WE%v_t WRITE( Un, IOSTAT=ErrStat) LocalVar%WE%v_m @@ -292,13 +296,12 @@ SUBROUTINE WriteRestartFile(LocalVar, CntrPar, ErrVar, objInst, RootName, size_a END SUBROUTINE WriteRestartFile -SUBROUTINE ReadRestartFile(avrSWAP, LocalVar, CntrPar, objInst, PerfData, RootName, size_avcOUTNAME, zmqVar, ErrVar) +SUBROUTINE ReadRestartFile(avrSWAP, LocalVar, CntrPar, objInst, PerfData, RootName, size_avcOUTNAME, ErrVar) TYPE(LocalVariables), INTENT(INOUT) :: LocalVar TYPE(ControlParameters), INTENT(INOUT) :: CntrPar TYPE(ObjectInstances), INTENT(INOUT) :: objInst TYPE(PerformanceData), INTENT(INOUT) :: PerfData TYPE(ErrorVariables), INTENT(INOUT) :: ErrVar - TYPE(ZMQ_Variables), INTENT(INOUT) :: zmqVar REAL(ReKi), INTENT(IN) :: avrSWAP(*) INTEGER(IntKi), INTENT(IN) :: size_avcOUTNAME CHARACTER(size_avcOUTNAME-1), INTENT(IN) :: RootName @@ -505,6 +508,10 @@ SUBROUTINE ReadRestartFile(avrSWAP, LocalVar, CntrPar, objInst, PerfData, RootNa READ( Un, IOSTAT=ErrStat) LocalVar%AWC_complexangle(1) READ( Un, IOSTAT=ErrStat) LocalVar%AWC_complexangle(2) READ( Un, IOSTAT=ErrStat) LocalVar%AWC_complexangle(3) + READ( Un, IOSTAT=ErrStat) LocalVar%ZMQ_YawOffset + READ( Un, IOSTAT=ErrStat) LocalVar%ZMQ_PitOffset(1) + READ( Un, IOSTAT=ErrStat) LocalVar%ZMQ_PitOffset(2) + READ( Un, IOSTAT=ErrStat) LocalVar%ZMQ_PitOffset(3) READ( Un, IOSTAT=ErrStat) LocalVar%WE%om_r READ( Un, IOSTAT=ErrStat) LocalVar%WE%v_t READ( Un, IOSTAT=ErrStat) LocalVar%WE%v_m @@ -575,7 +582,7 @@ SUBROUTINE ReadRestartFile(avrSWAP, LocalVar, CntrPar, objInst, PerfData, RootNa Close ( Un ) ENDIF ! Read Parameter files - CALL ReadControlParameterFileSub(CntrPar, LocalVar, zmqVar, LocalVar%ACC_INFILE, LocalVar%ACC_INFILE_SIZE, RootName, ErrVar) + CALL ReadControlParameterFileSub(CntrPar, LocalVar, LocalVar%ACC_INFILE, LocalVar%ACC_INFILE_SIZE, RootName, ErrVar) IF (CntrPar%WE_Mode > 0) THEN CALL READCpFile(CntrPar, PerfData, ErrVar) ENDIF @@ -598,7 +605,7 @@ SUBROUTINE Debug(LocalVar, CntrPar, DebugVar, ErrVar, avrSWAP, RootName, size_av INTEGER(IntKi), SAVE :: UnDb2 ! I/O unit for the debugging information, avrSWAP INTEGER(IntKi), SAVE :: UnDb3 ! I/O unit for the debugging information, avrSWAP REAL(ReKi), INTENT(INOUT) :: avrSWAP(*) ! The swap array, used to pass data to, and receive data from, the DLL controller. - CHARACTER(size_avcOUTNAME-1), INTENT(IN) :: RootName ! a Fortran version of the input C string (not considered an array here) [subtract 1 for the C null-character] + CHARACTER(size_avcOUTNAME), INTENT(IN) :: RootName ! a Fortran version of the input C string (not considered an array here) [subtract 1 for the C null-character] CHARACTER(200) :: Version ! git version of ROSCO CHARACTER(15), ALLOCATABLE :: DebugOutStrings(:), DebugOutUnits(:) @@ -651,7 +658,7 @@ SUBROUTINE Debug(LocalVar, CntrPar, DebugVar, ErrVar, avrSWAP, RootName, size_av '[rad/s]', '[rad/s]', '[m/s]', '[rad]', '[rad]', & '[N/A]', '[N/A]', '[N/A]', '[N/A]', '[rad/s]', & '[deg]', '[deg]', '[deg]', '[N/A]'] - nLocalVars = 112 + nLocalVars = 114 Allocate(LocalVarOutData(nLocalVars)) Allocate(LocalVarOutStrings(nLocalVars)) LocalVarOutData(1) = LocalVar%iStatus @@ -766,6 +773,8 @@ SUBROUTINE Debug(LocalVar, CntrPar, DebugVar, ErrVar, avrSWAP, RootName, size_av LocalVarOutData(110) = LocalVar%RootMyb_Last(1) LocalVarOutData(111) = LocalVar%ACC_INFILE_SIZE LocalVarOutData(112) = LocalVar%AWC_complexangle(1) + LocalVarOutData(113) = LocalVar%ZMQ_YawOffset + LocalVarOutData(114) = LocalVar%ZMQ_PitOffset(1) LocalVarOutStrings = [CHARACTER(15) :: 'iStatus', 'Time', 'DT', 'n_DT', 'Time_Last', & 'VS_GenPwr', 'VS_GenPwrF', 'GenSpeed', 'RotSpeed', 'NacHeading', & 'NacVane', 'HorWindV', 'rootMOOP', 'rootMOOPF', 'BlPitch', & @@ -788,7 +797,7 @@ SUBROUTINE Debug(LocalVar, CntrPar, DebugVar, ErrVar, avrSWAP, RootName, size_av 'PtfmRVX', 'PtfmRVY', 'PtfmRVZ', 'PtfmTAX', 'PtfmTAY', & 'PtfmTAZ', 'PtfmRAX', 'PtfmRAY', 'PtfmRAZ', 'CC_DesiredL', & 'CC_ActuatedL', 'CC_ActuatedDL', 'StC_Input', 'Flp_Angle', 'RootMyb_Last', & - 'ACC_INFILE_SIZE', 'AWC_complexangle'] + 'ACC_INFILE_SIZE', 'AWC_complexangle', 'ZMQ_YawOffset', 'ZMQ_PitOffset'] ! Initialize debug file IF ((LocalVar%iStatus == 0) .OR. (LocalVar%iStatus == -9)) THEN ! .TRUE. if we're on the first call to the DLL IF (CntrPar%LoggingLevel > 0) THEN @@ -803,8 +812,8 @@ SUBROUTINE Debug(LocalVar, CntrPar, DebugVar, ErrVar, avrSWAP, RootName, size_av CALL GetNewUnit(UnDb2, ErrVar) OPEN(unit=UnDb2, FILE=TRIM(RootName)//'.RO.dbg2') WRITE(UnDb2, *) 'Generated on '//CurDate()//' at '//CurTime()//' using ROSCO-'//TRIM(rosco_version) - WRITE(UnDb2, '(113(a20,TR5:))') 'Time', LocalVarOutStrings - WRITE(UnDb2, '(113(a20,TR5:))') + WRITE(UnDb2, '(115(a20,TR5:))') 'Time', LocalVarOutStrings + WRITE(UnDb2, '(115(a20,TR5:))') END IF IF (CntrPar%LoggingLevel > 2) THEN @@ -867,7 +876,7 @@ SUBROUTINE Debug(LocalVar, CntrPar, DebugVar, ErrVar, avrSWAP, RootName, size_av END DO ! Write debug files - FmtDat = "(F20.5,TR5,112(ES20.5E2,TR5:))" ! The format of the debugging data + FmtDat = "(F20.5,TR5,114(ES20.5E2,TR5:))" ! The format of the debugging data IF ( MOD(LocalVar%n_DT, CntrPar%n_DT_Out) == 0) THEN IF(CntrPar%LoggingLevel > 0) THEN WRITE (UnDb, TRIM(FmtDat)) LocalVar%Time, DebugOutData diff --git a/ROSCO/src/ROSCO_Types.f90 b/ROSCO/src/ROSCO_Types.f90 index 363e2e7a..3cdf7355 100644 --- a/ROSCO/src/ROSCO_Types.f90 +++ b/ROSCO/src/ROSCO_Types.f90 @@ -356,6 +356,8 @@ MODULE ROSCO_Types CHARACTER, DIMENSION(:), ALLOCATABLE :: ACC_INFILE ! Parameter input filename LOGICAL :: restart ! Restart flag COMPLEX(DbKi) :: AWC_complexangle(3) ! Complex angle for each blade, sum of modes? + REAL(DbKi) :: ZMQ_YawOffset ! Yaw offsety command, [rad] + REAL(DbKi) :: ZMQ_PitOffset(3) ! Pitch command offset provided by ZeroMQ TYPE(WE) :: WE ! Wind speed estimator parameters derived type TYPE(FilterParameters) :: FP ! Filter parameters derived type TYPE(piParams) :: piP ! PI parameters derived type @@ -423,11 +425,6 @@ MODULE ROSCO_Types CHARACTER(1024) :: ProcName(3) = "" ! The name of the procedure in the DLL that will be called. END TYPE ExtDLL_Type -TYPE, PUBLIC :: ZMQ_Variables - LOGICAL :: ZMQ_Flag ! Flag if we're using zeroMQ at all (0-False, 1-True) - REAL(DbKi) :: Yaw_Offset ! Yaw offsety command, [rad] -END TYPE ZMQ_Variables - TYPE, PUBLIC :: ExtControlType REAL(ReKi), DIMENSION(:), ALLOCATABLE :: avrSWAP ! The swap array- used to pass data to and from the DLL controller [see Bladed DLL documentation] END TYPE ExtControlType diff --git a/ROSCO/src/ReadSetParameters.f90 b/ROSCO/src/ReadSetParameters.f90 index ef2efaa2..05f3d4b3 100644 --- a/ROSCO/src/ReadSetParameters.f90 +++ b/ROSCO/src/ReadSetParameters.f90 @@ -26,7 +26,7 @@ MODULE ReadSetParameters ! ----------------------------------------------------------------------------------- ! Read avrSWAP array passed from ServoDyn SUBROUTINE ReadAvrSWAP(avrSWAP, LocalVar, CntrPar) - USE ROSCO_Types, ONLY : LocalVariables, ZMQ_Variables + USE ROSCO_Types, ONLY : LocalVariables REAL(ReKi), INTENT(INOUT) :: avrSWAP(*) ! The swap array, used to pass data to, and receive data from, the DLL controller. TYPE(LocalVariables), INTENT(INOUT) :: LocalVar @@ -120,9 +120,9 @@ SUBROUTINE ReadAvrSWAP(avrSWAP, LocalVar, CntrPar) END SUBROUTINE ReadAvrSWAP ! ----------------------------------------------------------------------------------- ! Define parameters for control actions - SUBROUTINE SetParameters(avrSWAP, accINFILE, size_avcMSG, CntrPar, LocalVar, objInst, PerfData, zmqVar, RootName, ErrVar) + SUBROUTINE SetParameters(avrSWAP, accINFILE, size_avcMSG, CntrPar, LocalVar, objInst, PerfData, RootName, ErrVar) - USE ROSCO_Types, ONLY : ControlParameters, LocalVariables, ObjectInstances, PerformanceData, ErrorVariables, ZMQ_Variables + USE ROSCO_Types, ONLY : ControlParameters, LocalVariables, ObjectInstances, PerformanceData, ErrorVariables REAL(ReKi), INTENT(INOUT) :: avrSWAP(*) ! The swap array, used to pass data to, and receive data from, the DLL controller. CHARACTER(C_CHAR), INTENT(IN ) :: accINFILE(NINT(avrSWAP(50))) ! The name of the parameter input file @@ -132,7 +132,6 @@ SUBROUTINE SetParameters(avrSWAP, accINFILE, size_avcMSG, CntrPar, LocalVar, obj TYPE(LocalVariables), INTENT(INOUT) :: LocalVar TYPE(ObjectInstances), INTENT(INOUT) :: objInst TYPE(PerformanceData), INTENT(INOUT) :: PerfData - TYPE(ZMQ_Variables), INTENT(INOUT) :: zmqVar TYPE(ErrorVariables), INTENT(INOUT) :: ErrVar CHARACTER(NINT(avrSWAP(50))-1), INTENT(IN) :: RootName @@ -196,7 +195,7 @@ SUBROUTINE SetParameters(avrSWAP, accINFILE, size_avcMSG, CntrPar, LocalVar, obj LocalVar%ACC_INFILE = accINFILE ! Read Control Parameter File - CALL ReadControlParameterFileSub(CntrPar, LocalVar, zmqVar, accINFILE, NINT(avrSWAP(50)), RootName, ErrVar) + CALL ReadControlParameterFileSub(CntrPar, LocalVar, accINFILE, NINT(avrSWAP(50)), RootName, ErrVar) ! If there's been an file reading error, don't continue ! Add RoutineName to error message IF (ErrVar%aviFAIL < 0) THEN @@ -233,6 +232,9 @@ SUBROUTINE SetParameters(avrSWAP, accINFILE, size_avcMSG, CntrPar, LocalVar, obj LocalVar%CC_ActuatedL = 0 LocalVar%CC_ActuatedDL = 0 LocalVar%StC_Input = 0 + + LocalVar%ZMQ_YawOffset = 0 + LocalVar%ZMQ_PitOffset = 0 ! Check validity of input parameters: CALL CheckInputs(LocalVar, CntrPar, avrSWAP, ErrVar, size_avcMSG) @@ -241,11 +243,6 @@ SUBROUTINE SetParameters(avrSWAP, accINFILE, size_avcMSG, CntrPar, LocalVar, obj IF (ErrVar%aviFAIL < 0) THEN ErrVar%ErrMsg = RoutineName//':'//TRIM(ErrVar%ErrMsg) ENDIF - - ! Check if we're using zeromq - IF (CntrPar%ZMQ_Mode == 1) THEN ! add .OR. statements as more functionality is built in - zmqVar%ZMQ_Flag = .TRUE. - ENDIF ENDIF @@ -254,16 +251,15 @@ END SUBROUTINE SetParameters ! ----------------------------------------------------------------------------------- ! Read all constant control parameters from DISCON.IN parameter file ! Also, all computed CntrPar%* parameters should be computed in this subroutine - SUBROUTINE ReadControlParameterFileSub(CntrPar, LocalVar, zmqVar, accINFILE, accINFILE_size, RootName, ErrVar)!, accINFILE_size) + SUBROUTINE ReadControlParameterFileSub(CntrPar, LocalVar, accINFILE, accINFILE_size, RootName, ErrVar)!, accINFILE_size) USE, INTRINSIC :: ISO_C_Binding - USE ROSCO_Types, ONLY : ControlParameters, ErrorVariables, ZMQ_Variables, LocalVariables + USE ROSCO_Types, ONLY : ControlParameters, ErrorVariables, LocalVariables INTEGER(IntKi) :: accINFILE_size ! size of DISCON input filename CHARACTER(accINFILE_size), INTENT(IN ) :: accINFILE(accINFILE_size) ! DISCON input filename TYPE(ControlParameters), INTENT(INOUT) :: CntrPar ! Control parameter type TYPE(LocalVariables), INTENT(INOUT) :: LocalVar ! Control parameter type TYPE(ErrorVariables), INTENT(INOUT) :: ErrVar ! Control parameter type - TYPE(ZMQ_Variables), INTENT(INOUT) :: zmqVar ! Control parameter type CHARACTER(accINFILE_size), INTENT(IN) :: RootName diff --git a/ROSCO/src/ZeroMQInterface.f90 b/ROSCO/src/ZeroMQInterface.f90 index 88ea2ecf..4b824772 100644 --- a/ROSCO/src/ZeroMQInterface.f90 +++ b/ROSCO/src/ZeroMQInterface.f90 @@ -4,12 +4,11 @@ module ZeroMQInterface ! CONTAINS - SUBROUTINE UpdateZeroMQ(LocalVar, CntrPar, zmqVar, ErrVar) - USE ROSCO_Types, ONLY : LocalVariables, ControlParameters, ZMQ_Variables, ErrorVariables + SUBROUTINE UpdateZeroMQ(LocalVar, CntrPar, ErrVar) + USE ROSCO_Types, ONLY : LocalVariables, ControlParameters, ErrorVariables IMPLICIT NONE TYPE(LocalVariables), INTENT(INOUT) :: LocalVar TYPE(ControlParameters), INTENT(INOUT) :: CntrPar - TYPE(ZMQ_Variables), INTENT(INOUT) :: zmqVar TYPE(ErrorVariables), INTENT(INOUT) :: ErrVar character(256) :: zmq_address @@ -29,9 +28,9 @@ subroutine zmq_client(zmq_address, measurements, setpoints) bind(C, name="zmq_cl end subroutine zmq_client end interface #endif - + ! Communicate if threshold has been reached - IF ((MODULO(LocalVar%Time, CntrPar%ZMQ_UpdatePeriod) == 0) .OR. (LocalVar%iStatus == -1)) THEN + IF (ABS(MODULO(LocalVar%Time, CntrPar%ZMQ_UpdatePeriod)) < LocalVar%DT * CntrPar%ZMQ_UpdatePeriod .OR. LocalVar%iStatus == -1) THEN ! Collect measurements to be sent to ZeroMQ server turbine_measurements(1) = LocalVar%iStatus turbine_measurements(2) = LocalVar%Time @@ -68,7 +67,10 @@ end subroutine zmq_client ! write (*,*) "ZeroMQInterface: pitch 1 setpoint from ssc: ", setpoints(3) ! write (*,*) "ZeroMQInterface: pitch 2 setpoint from ssc: ", setpoints(4) ! write (*,*) "ZeroMQInterface: pitch 3 setpoint from ssc: ", setpoints(5) - zmqVar%Yaw_Offset = setpoints(2) + LocalVar%ZMQ_YawOffset = setpoints(2) + LocalVar%ZMQ_PitOffset(1) = setpoints(3) + LocalVar%ZMQ_PitOffset(2) = setpoints(4) + LocalVar%ZMQ_PitOffset(3) = setpoints(5) ENDIF diff --git a/ROSCO_toolbox/control_interface.py b/ROSCO_toolbox/control_interface.py index 84a3f369..83252218 100644 --- a/ROSCO_toolbox/control_interface.py +++ b/ROSCO_toolbox/control_interface.py @@ -57,8 +57,11 @@ def __init__(self, lib_name, param_filename='DISCON.IN', **kwargs): setattr(self, k, w) except: pass - - self.init_discon() + + try: + self.init_discon() + except ValueError: + pass def init_discon(self): @@ -90,25 +93,28 @@ def init_discon(self): # Code this as first call self.avrSWAP[0] = 0 - # Put some values in - self.avrSWAP[58] = self.char_buffer - self.avrSWAP[49] = len(self.param_name) - self.avrSWAP[50] = self.char_buffer - self.avrSWAP[51] = self.char_buffer - # Initialize DISCON and related self.aviFAIL = c_int32() # 1 self.accINFILE = self.param_name.encode('utf-8') - self.avcOUTNAME = (self.sim_name + '.RO.dbg').encode('utf-8') + self.avcOUTNAME = (self.sim_name ).encode('utf-8') self.avcMSG = create_string_buffer(1000) self.discon.DISCON.argtypes = [POINTER(c_float), POINTER(c_int32), c_char_p, c_char_p, c_char_p] # (all defined by ctypes) + # Put some values in + self.avrSWAP[48] = self.char_buffer + self.avrSWAP[49] = len(self.param_name) + self.avrSWAP[50] = len(self.avcOUTNAME) + self.avrSWAP[51] = self.char_buffer + # Run DISCON self.call_discon() # Code as not first run now that DISCON has been initialized self.avrSWAP[0] = 1 + if self.aviFAIL.value < 0: + raise ValueError('ROSCO dynamic library has returned an error') + def call_discon(self): ''' @@ -450,8 +456,8 @@ def send_setpoints(self, genTorque=0.0, nacelleHeading=0.0, Parameters: ----------- - genTorques: float - Generator torque setpoint + genTorque: float + Generator torque setpoint (note that this is currently unused by ROSCO) nacelleHeadings: float Nacelle heading setpoint bladePitchAngles: List (len=3) diff --git a/ROSCO_toolbox/controller.py b/ROSCO_toolbox/controller.py index 335bcd54..8e3fee38 100644 --- a/ROSCO_toolbox/controller.py +++ b/ROSCO_toolbox/controller.py @@ -95,7 +95,8 @@ def __init__(self, controller_params): self.Ki_ipc1p = controller_params['IPC_Ki1p'] self.Kp_ipc2p = controller_params['IPC_Kp2p'] self.Ki_ipc2p = controller_params['IPC_Kp2p'] - self.IPC_Vramp = controller_params['IPC_Vramp'] + self.IPC_Vramp = controller_params['IPC_Vramp'] + self.ZMQ_UpdatePeriod = controller_params['ZMQ_UpdatePeriod'] # Optional parameters without defaults if self.Flp_Mode > 0: diff --git a/ROSCO_toolbox/inputs/toolbox_schema.yaml b/ROSCO_toolbox/inputs/toolbox_schema.yaml index f06eb576..cebb30fd 100644 --- a/ROSCO_toolbox/inputs/toolbox_schema.yaml +++ b/ROSCO_toolbox/inputs/toolbox_schema.yaml @@ -203,6 +203,11 @@ properties: maximum: 1 default: 0 description: ZMQ Mode (0 - ZMQ Inteface, 1 - ZMQ for yaw control) + ZMQ_UpdatePeriod: + type: number + minimum: 0 + default: 2 + description: Call ZeroMQ every [x] seconds, [s] PA_Mode: type: number minimum: 0 diff --git a/ROSCO_toolbox/utilities.py b/ROSCO_toolbox/utilities.py index 06906703..b68e23dd 100644 --- a/ROSCO_toolbox/utilities.py +++ b/ROSCO_toolbox/utilities.py @@ -275,7 +275,7 @@ def write_DISCON(turbine, controller, param_file='DISCON.IN', txt_filename='Cp_C file.write('\n') file.write('!------- ZeroMQ Interface ---------------------------------------------------------\n') file.write('"{}" ! ZMQ_CommAddress - Communication address for ZMQ server, (e.g. "tcp://localhost:5555") \n'.format(rosco_vt['ZMQ_CommAddress'])) - file.write('{:<11d} ! ZMQ_UpdatePeriod - Call ZeroMQ every [x] seconds, [s]\n'.format(int(rosco_vt['ZMQ_UpdatePeriod']))) + file.write('{:<11f} ! ZMQ_UpdatePeriod - Call ZeroMQ every [x] seconds, [s]\n'.format(rosco_vt['ZMQ_UpdatePeriod'])) file.write('\n') file.write('!------- Cable Control ---------------------------------------------------------\n') file.write('{:<11d} ! CC_Group_N - {}\n'.format(len(rosco_vt['CC_GroupIndex']), input_descriptions['CC_Group_N'])) @@ -615,7 +615,7 @@ def DISCON_dict(turbine, controller, txt_filename=None): DISCON_dict['PF_Offsets'] = [0.,0.,0.] # ------- Zero-MQ ------- DISCON_dict['ZMQ_CommAddress'] = "tcp://localhost:5555" - DISCON_dict['ZMQ_UpdatePeriod'] = 2 + DISCON_dict['ZMQ_UpdatePeriod'] = controller.ZMQ_UpdatePeriod # Add pass through here for param, value in controller.controller_params['DISCON'].items(): diff --git a/Test_Cases/BAR_10/BAR_10_DISCON.IN b/Test_Cases/BAR_10/BAR_10_DISCON.IN index bb950f78..841b6272 100644 --- a/Test_Cases/BAR_10/BAR_10_DISCON.IN +++ b/Test_Cases/BAR_10/BAR_10_DISCON.IN @@ -1,5 +1,5 @@ ! Controller parameter input file for the BAR_10 wind turbine -! - File written using ROSCO version 2.8.0 controller tuning logic on 09/26/23 +! - File written using ROSCO version 2.8.0 controller tuning logic on 10/18/23 !------- SIMULATION CONTROL ------------------------------------------------------------ 1 ! LoggingLevel - {0: write no debug files, 1: write standard output .dbg-file, 2: LoggingLevel 1 + ROSCO LocalVars (.dbg2) 3: LoggingLevel 2 + complete avrSWAP-array (.dbg3)} @@ -180,7 +180,7 @@ !------- ZeroMQ Interface --------------------------------------------------------- "tcp://localhost:5555" ! ZMQ_CommAddress - Communication address for ZMQ server, (e.g. "tcp://localhost:5555") -2 ! ZMQ_UpdatePeriod - Call ZeroMQ every [x] seconds, [s] +2.000000 ! ZMQ_UpdatePeriod - Call ZeroMQ every [x] seconds, [s] !------- Cable Control --------------------------------------------------------- 1 ! CC_Group_N - Number of cable control groups diff --git a/Test_Cases/IEA-15-240-RWT-UMaineSemi/DISCON-UMaineSemi.IN b/Test_Cases/IEA-15-240-RWT-UMaineSemi/DISCON-UMaineSemi.IN index 3e5abc22..1f0f571b 100644 --- a/Test_Cases/IEA-15-240-RWT-UMaineSemi/DISCON-UMaineSemi.IN +++ b/Test_Cases/IEA-15-240-RWT-UMaineSemi/DISCON-UMaineSemi.IN @@ -1,5 +1,5 @@ ! Controller parameter input file for the IEA-15-240-RWT-UMaineSemi wind turbine -! - File written using ROSCO version 2.8.0 controller tuning logic on 09/26/23 +! - File written using ROSCO version 2.8.0 controller tuning logic on 10/18/23 !------- SIMULATION CONTROL ------------------------------------------------------------ 2 ! LoggingLevel - {0: write no debug files, 1: write standard output .dbg-file, 2: LoggingLevel 1 + ROSCO LocalVars (.dbg2) 3: LoggingLevel 2 + complete avrSWAP-array (.dbg3)} @@ -180,7 +180,7 @@ !------- ZeroMQ Interface --------------------------------------------------------- "tcp://localhost:5555" ! ZMQ_CommAddress - Communication address for ZMQ server, (e.g. "tcp://localhost:5555") -2 ! ZMQ_UpdatePeriod - Call ZeroMQ every [x] seconds, [s] +2.000000 ! ZMQ_UpdatePeriod - Call ZeroMQ every [x] seconds, [s] !------- Cable Control --------------------------------------------------------- 1 ! CC_Group_N - Number of cable control groups diff --git a/Test_Cases/MHK_RM1/MHK_RM1_DISCON.IN b/Test_Cases/MHK_RM1/MHK_RM1_DISCON.IN index 52972e56..704f4409 100644 --- a/Test_Cases/MHK_RM1/MHK_RM1_DISCON.IN +++ b/Test_Cases/MHK_RM1/MHK_RM1_DISCON.IN @@ -1,5 +1,5 @@ ! Controller parameter input file for the MHK_RM1_Floating wind turbine -! - File written using ROSCO version 2.8.0 controller tuning logic on 09/26/23 +! - File written using ROSCO version 2.8.0 controller tuning logic on 10/18/23 !------- SIMULATION CONTROL ------------------------------------------------------------ 2 ! LoggingLevel - {0: write no debug files, 1: write standard output .dbg-file, 2: LoggingLevel 1 + ROSCO LocalVars (.dbg2) 3: LoggingLevel 2 + complete avrSWAP-array (.dbg3)} @@ -180,7 +180,7 @@ !------- ZeroMQ Interface --------------------------------------------------------- "tcp://localhost:5555" ! ZMQ_CommAddress - Communication address for ZMQ server, (e.g. "tcp://localhost:5555") -2 ! ZMQ_UpdatePeriod - Call ZeroMQ every [x] seconds, [s] +2.000000 ! ZMQ_UpdatePeriod - Call ZeroMQ every [x] seconds, [s] !------- Cable Control --------------------------------------------------------- 1 ! CC_Group_N - Number of cable control groups diff --git a/Test_Cases/NREL-5MW/DISCON.IN b/Test_Cases/NREL-5MW/DISCON.IN index 0acc523a..7c4aacb1 100644 --- a/Test_Cases/NREL-5MW/DISCON.IN +++ b/Test_Cases/NREL-5MW/DISCON.IN @@ -1,5 +1,5 @@ ! Controller parameter input file for the NREL-5MW wind turbine -! - File written using ROSCO version 2.8.0 controller tuning logic on 09/26/23 +! - File written using ROSCO version 2.8.0 controller tuning logic on 10/18/23 !------- SIMULATION CONTROL ------------------------------------------------------------ 1 ! LoggingLevel - {0: write no debug files, 1: write standard output .dbg-file, 2: LoggingLevel 1 + ROSCO LocalVars (.dbg2) 3: LoggingLevel 2 + complete avrSWAP-array (.dbg3)} @@ -180,7 +180,7 @@ !------- ZeroMQ Interface --------------------------------------------------------- "tcp://localhost:5555" ! ZMQ_CommAddress - Communication address for ZMQ server, (e.g. "tcp://localhost:5555") -2 ! ZMQ_UpdatePeriod - Call ZeroMQ every [x] seconds, [s] +2.000000 ! ZMQ_UpdatePeriod - Call ZeroMQ every [x] seconds, [s] !------- Cable Control --------------------------------------------------------- 1 ! CC_Group_N - Number of cable control groups diff --git a/Test_Cases/NREL_2p8_127/NREL-2p8-127_DISCON.IN b/Test_Cases/NREL_2p8_127/NREL-2p8-127_DISCON.IN index c2b5a765..229e388f 100644 --- a/Test_Cases/NREL_2p8_127/NREL-2p8-127_DISCON.IN +++ b/Test_Cases/NREL_2p8_127/NREL-2p8-127_DISCON.IN @@ -1,5 +1,5 @@ ! Controller parameter input file for the NREL-2p8-127 wind turbine -! - File written using ROSCO version 2.8.0 controller tuning logic on 09/26/23 +! - File written using ROSCO version 2.8.0 controller tuning logic on 10/18/23 !------- SIMULATION CONTROL ------------------------------------------------------------ 2 ! LoggingLevel - {0: write no debug files, 1: write standard output .dbg-file, 2: LoggingLevel 1 + ROSCO LocalVars (.dbg2) 3: LoggingLevel 2 + complete avrSWAP-array (.dbg3)} @@ -180,7 +180,7 @@ !------- ZeroMQ Interface --------------------------------------------------------- "tcp://localhost:5555" ! ZMQ_CommAddress - Communication address for ZMQ server, (e.g. "tcp://localhost:5555") -2 ! ZMQ_UpdatePeriod - Call ZeroMQ every [x] seconds, [s] +2.000000 ! ZMQ_UpdatePeriod - Call ZeroMQ every [x] seconds, [s] !------- Cable Control --------------------------------------------------------- 1 ! CC_Group_N - Number of cable control groups diff --git a/Tune_Cases/NREL2p8.yaml b/Tune_Cases/NREL2p8.yaml index be0f4387..c1562a83 100644 --- a/Tune_Cases/NREL2p8.yaml +++ b/Tune_Cases/NREL2p8.yaml @@ -25,6 +25,7 @@ controller_params: TD_Mode: 0 PwC_Mode: 0 ZMQ_Mode: 0 + ZMQ_UpdatePeriod: 2 PA_Mode: 0 Ext_Mode: 0 U_pc: [12] From 6ceb155ce2f28872d4e5e9fbbb7c729dcee7e5aa Mon Sep 17 00:00:00 2001 From: dzalkind Date: Wed, 27 Mar 2024 14:08:31 -0600 Subject: [PATCH 136/224] Add initial torque/speed power controllers --- .../rosco_registry/rosco_types.yaml | 40 ++++++- rosco/controller/src/ControllerBlocks.f90 | 47 ++++++-- rosco/controller/src/Controllers.f90 | 7 +- rosco/controller/src/ROSCO_IO.f90 | 109 ++++++++++-------- rosco/controller/src/ROSCO_Types.f90 | 13 ++- rosco/controller/src/ReadSetParameters.f90 | 9 ++ rosco/toolbox/inputs/toolbox_schema.yaml | 34 +++++- rosco/toolbox/utilities.py | 7 ++ 8 files changed, 197 insertions(+), 69 deletions(-) diff --git a/rosco/controller/rosco_registry/rosco_types.yaml b/rosco/controller/rosco_registry/rosco_types.yaml index 6f888f81..58b57b84 100644 --- a/rosco/controller/rosco_registry/rosco_types.yaml +++ b/rosco/controller/rosco_registry/rosco_types.yaml @@ -334,6 +334,9 @@ ControlParameters: PRC_Mode: <<: *integer description: Power reference tracking mode, 0- use standard rotor speed set points, 1- use PRC rotor speed setpoints + PRC_Comm: + <<: *integer + description: Power reference communication mode, 0- use constant DISCON inputs, 1- use open loop inputs, 2- use ZMQ inputs PRC_WindSpeeds: <<: *real description: Array of wind speeds used in rotor speed vs. wind speed lookup table @@ -348,6 +351,28 @@ ControlParameters: PRC_LPF_Freq: <<: *real description: Frequency of the low pass filter on the wind speed estimate used to set PRC_GenSpeeds [rad/s] + PRC_R_Torque: + <<: *real + description: Power rating through changing the rated torque, default is 1, effective above rated [-] + PRC_R_Speed: + <<: *real + description: Power rating through changing the rated generator speed, default is 1, effective above rated [-] + PRC_R_Pitch: + <<: *real + description: Power rating through changing the fine pitch angle, default is 1, effective below rated [-] + PRC_Table_n: + <<: *integer + description: Number of elements in PRC_R to _Pitch table + PRC_Pitch_Table: + <<: *real + allocatable: True + description: Table of fine pitch versus PRC_R_Table, length should be PRC_Table_n [rad] + PRC_R_Table: + <<: *real + allocatable: True + description: Table of turbine rating versus fine pitch (PRC_Pitch_Table), length should be PRC_Table_n, default is 1 [-] + + # Wind Speed Estimator WE_Mode: @@ -1077,9 +1102,6 @@ LocalVariables: PC_PitComT: <<: *real description: Total command pitch based on the sum of the proportional and integral terms [rad]. - PC_PitComT: - <<: *real - description: Collective pitch commmand from PI control [rad]. PC_PitComT_Last: <<: *real description: Last total command pitch based on the sum of the proportional and integral terms [rad]. @@ -1202,6 +1224,18 @@ LocalVariables: PRC_WSE_F: <<: *real description: Filtered wind speed estimate for power reference control + PRC_R_Speed: + <<: *real + description: Instantaneous PRC_R_Speed + PRC_R_Torque: + <<: *real + description: Instantaneous PRC_R_Torque + PRC_R_Pitch: + <<: *real + description: Instantaneous PRC_R_Pitch + PRC_R_Total: + <<: *real + description: Instantaneous PRC_R_Total SD: <<: *logical description: Shutdown, .FALSE. if inactive, .TRUE. if active diff --git a/rosco/controller/src/ControllerBlocks.f90 b/rosco/controller/src/ControllerBlocks.f90 index be9e6400..89ca8525 100644 --- a/rosco/controller/src/ControllerBlocks.f90 +++ b/rosco/controller/src/ControllerBlocks.f90 @@ -35,15 +35,38 @@ SUBROUTINE ComputeVariablesSetpoints(CntrPar, LocalVar, objInst, DebugVar, ErrVa TYPE(ErrorVariables), INTENT(INOUT) :: ErrVar - ! ----- Pitch controller speed and power error ----- - - ! Power reference tracking generator speed - IF (CntrPar%PRC_Mode == 1) THEN - LocalVar%PRC_WSE_F = LPFilter(LocalVar%WE_Vw, LocalVar%DT,CntrPar%PRC_LPF_Freq, LocalVar%FP, LocalVar%iStatus, LocalVar%restart, objInst%instLPF) - LocalVar%PC_RefSpd_PRC = interp1d(CntrPar%PRC_WindSpeeds,CntrPar%PRC_GenSpeeds,LocalVar%PRC_WSE_F,ErrVar) + ! Set up power reference + IF (CntrPar%PRC_Mode == 1) THEN ! Using power reference control + IF (CntrPar%PRC_Comm == 0) THEN ! Constant, from DISCON + LocalVar%PRC_R_Speed = CntrPar%PRC_R_Speed + LocalVar%PRC_R_Torque = CntrPar%PRC_R_Torque + LocalVar%PRC_R_Pitch = CntrPar%PRC_R_Pitch + + ELSEIF (CntrPar%PRC_Comm == 1) THEN ! Open loop + ! TODO + + ELSEIF (CntrPar%PRC_Comm == 2) THEN ! ZeroMQ + ! TODO + ! Check when ZMQ is called, should be before this! + + ENDIF + ELSE - LocalVar%PC_RefSpd_PRC = CntrPar%PC_RefSpd + LocalVar%PRC_R_Speed = 1.0_DbKi + LocalVar%PRC_R_Torque = 1.0_DbKi + LocalVar%PRC_R_Pitch = 1.0_DbKi ENDIF + + ! Change pitch reference speed + LocalVar%PC_RefSpd_PRC = CntrPar%PC_RefSpd * LocalVar%PRC_R_Speed + + ! Power reference tracking generator speed + ! IF (CntrPar%PRC_Mode == 1) THEN + ! LocalVar%PRC_WSE_F = LPFilter(LocalVar%WE_Vw, LocalVar%DT,CntrPar%PRC_LPF_Freq, LocalVar%FP, LocalVar%iStatus, LocalVar%restart, objInst%instLPF) + ! LocalVar%PC_RefSpd_PRC = interp1d(CntrPar%PRC_WindSpeeds,CntrPar%PRC_GenSpeeds,LocalVar%PRC_WSE_F,ErrVar) + ! ELSE + ! LocalVar%PC_RefSpd_PRC = CntrPar%PC_RefSpd + ! ENDIF ! Implement setpoint smoothing IF (LocalVar%SS_DelOmegaF < 0) THEN @@ -76,12 +99,12 @@ SUBROUTINE ComputeVariablesSetpoints(CntrPar, LocalVar, objInst, DebugVar, ErrVa END IF ! Saturate torque reference speed between min speed and rated speed - LocalVar%VS_RefSpd = saturate(LocalVar%VS_RefSpd,CntrPar%VS_MinOMSpd, CntrPar%VS_RefSpd) + LocalVar%VS_RefSpd = saturate(LocalVar%VS_RefSpd,CntrPar%VS_MinOMSpd, CntrPar%VS_RefSpd * LocalVar%PRC_R_Speed) - ! Implement power reference rotor speed (overwrites above), convert to generator speed - IF (CntrPar%PRC_Mode == 1) THEN - LocalVar%VS_RefSpd = interp1d(CntrPar%PRC_WindSpeeds,CntrPar%PRC_GenSpeeds,LocalVar%WE_Vw_F,ErrVar) - ENDIF + ! ! Implement power reference rotor speed (overwrites above), convert to generator speed + ! IF (CntrPar%PRC_Mode == 1) THEN + ! LocalVar%VS_RefSpd = interp1d(CntrPar%PRC_WindSpeeds,CntrPar%PRC_GenSpeeds,LocalVar%WE_Vw_F,ErrVar) + ! ENDIF ! Implement setpoint smoothing IF (LocalVar%SS_DelOmegaF > 0) THEN diff --git a/rosco/controller/src/Controllers.f90 b/rosco/controller/src/Controllers.f90 index a32c391c..189ddd3c 100644 --- a/rosco/controller/src/Controllers.f90 +++ b/rosco/controller/src/Controllers.f90 @@ -207,17 +207,16 @@ SUBROUTINE VariableSpeedControl(avrSWAP, CntrPar, LocalVar, objInst, ErrVar) ! -------- Variable-Speed Torque Controller -------- ! Define max torque IF (LocalVar%VS_State == 4) THEN - LocalVar%VS_MaxTq = CntrPar%VS_RtTq + LocalVar%VS_MaxTq = CntrPar%VS_RtTq * LocalVar%PRC_R_Torque ELSE - ! VS_MaxTq = CntrPar%VS_MaxTq ! NJA: May want to boost max torque - LocalVar%VS_MaxTq = CntrPar%VS_RtTq + LocalVar%VS_MaxTq = CntrPar%VS_RtTq * LocalVar%PRC_R_Torque ENDIF ! Optimal Tip-Speed-Ratio tracking controller IF ((CntrPar%VS_ControlMode == 2) .OR. (CntrPar%VS_ControlMode == 3)) THEN ! Constant Power, update VS_MaxTq IF (CntrPar%VS_ConstPower == 1) THEN - LocalVar%VS_MaxTq = min((CntrPar%VS_RtPwr/(CntrPar%VS_GenEff/100.0))/LocalVar%GenSpeedF, CntrPar%VS_MaxTq) + LocalVar%VS_MaxTq = min((CntrPar%VS_RtPwr * LocalVar%PRC_R_Torque /(CntrPar%VS_GenEff/100.0))/LocalVar%GenSpeedF, CntrPar%VS_MaxTq) END IF ! PI controller diff --git a/rosco/controller/src/ROSCO_IO.f90 b/rosco/controller/src/ROSCO_IO.f90 index a4f44283..0dc6e08c 100644 --- a/rosco/controller/src/ROSCO_IO.f90 +++ b/rosco/controller/src/ROSCO_IO.f90 @@ -144,6 +144,10 @@ SUBROUTINE WriteRestartFile(LocalVar, CntrPar, ErrVar, objInst, RootName, size_a WRITE( Un, IOSTAT=ErrStat) LocalVar%WE_VwIdot WRITE( Un, IOSTAT=ErrStat) LocalVar%VS_LastGenTrqF WRITE( Un, IOSTAT=ErrStat) LocalVar%PRC_WSE_F + WRITE( Un, IOSTAT=ErrStat) LocalVar%PRC_R_Speed + WRITE( Un, IOSTAT=ErrStat) LocalVar%PRC_R_Torque + WRITE( Un, IOSTAT=ErrStat) LocalVar%PRC_R_Pitch + WRITE( Un, IOSTAT=ErrStat) LocalVar%PRC_R_Total WRITE( Un, IOSTAT=ErrStat) LocalVar%SD WRITE( Un, IOSTAT=ErrStat) LocalVar%Fl_PitCom WRITE( Un, IOSTAT=ErrStat) LocalVar%NACIMU_FA_AccF @@ -446,6 +450,10 @@ SUBROUTINE ReadRestartFile(avrSWAP, LocalVar, CntrPar, objInst, PerfData, RootNa READ( Un, IOSTAT=ErrStat) LocalVar%WE_VwIdot READ( Un, IOSTAT=ErrStat) LocalVar%VS_LastGenTrqF READ( Un, IOSTAT=ErrStat) LocalVar%PRC_WSE_F + READ( Un, IOSTAT=ErrStat) LocalVar%PRC_R_Speed + READ( Un, IOSTAT=ErrStat) LocalVar%PRC_R_Torque + READ( Un, IOSTAT=ErrStat) LocalVar%PRC_R_Pitch + READ( Un, IOSTAT=ErrStat) LocalVar%PRC_R_Total READ( Un, IOSTAT=ErrStat) LocalVar%SD READ( Un, IOSTAT=ErrStat) LocalVar%Fl_PitCom READ( Un, IOSTAT=ErrStat) LocalVar%NACIMU_FA_AccF @@ -692,7 +700,7 @@ SUBROUTINE Debug(LocalVar, CntrPar, DebugVar, ErrVar, avrSWAP, RootName, size_av '[N/A]', '[N/A]', '[N/A]', '[N/A]', '[rad/s]', & '[deg]', '[deg]', '[deg]', '[N/A]', '[rad/s]', & '[rad/s]'] - nLocalVars = 124 + nLocalVars = 128 Allocate(LocalVarOutData(nLocalVars)) Allocate(LocalVarOutStrings(nLocalVars)) LocalVarOutData(1) = LocalVar%iStatus @@ -783,42 +791,46 @@ SUBROUTINE Debug(LocalVar, CntrPar, DebugVar, ErrVar, avrSWAP, RootName, size_av LocalVarOutData(86) = LocalVar%WE_VwIdot LocalVarOutData(87) = LocalVar%VS_LastGenTrqF LocalVarOutData(88) = LocalVar%PRC_WSE_F - LocalVarOutData(89) = LocalVar%Fl_PitCom - LocalVarOutData(90) = LocalVar%NACIMU_FA_AccF - LocalVarOutData(91) = LocalVar%FA_AccF - LocalVarOutData(92) = LocalVar%FA_Hist - LocalVarOutData(93) = LocalVar%TRA_LastRefSpd - LocalVarOutData(94) = LocalVar%VS_RefSpeed - LocalVarOutData(95) = LocalVar%PtfmTDX - LocalVarOutData(96) = LocalVar%PtfmTDY - LocalVarOutData(97) = LocalVar%PtfmTDZ - LocalVarOutData(98) = LocalVar%PtfmRDX - LocalVarOutData(99) = LocalVar%PtfmRDY - LocalVarOutData(100) = LocalVar%PtfmRDZ - LocalVarOutData(101) = LocalVar%PtfmTVX - LocalVarOutData(102) = LocalVar%PtfmTVY - LocalVarOutData(103) = LocalVar%PtfmTVZ - LocalVarOutData(104) = LocalVar%PtfmRVX - LocalVarOutData(105) = LocalVar%PtfmRVY - LocalVarOutData(106) = LocalVar%PtfmRVZ - LocalVarOutData(107) = LocalVar%PtfmTAX - LocalVarOutData(108) = LocalVar%PtfmTAY - LocalVarOutData(109) = LocalVar%PtfmTAZ - LocalVarOutData(110) = LocalVar%PtfmRAX - LocalVarOutData(111) = LocalVar%PtfmRAY - LocalVarOutData(112) = LocalVar%PtfmRAZ - LocalVarOutData(113) = LocalVar%CC_DesiredL(1) - LocalVarOutData(114) = LocalVar%CC_ActuatedL(1) - LocalVarOutData(115) = LocalVar%CC_ActuatedDL(1) - LocalVarOutData(116) = LocalVar%StC_Input(1) - LocalVarOutData(117) = LocalVar%Flp_Angle(1) - LocalVarOutData(118) = LocalVar%RootMyb_Last(1) - LocalVarOutData(119) = LocalVar%ACC_INFILE_SIZE - LocalVarOutData(120) = LocalVar%AWC_complexangle(1) - LocalVarOutData(121) = LocalVar%ZMQ_ID - LocalVarOutData(122) = LocalVar%ZMQ_YawOffset - LocalVarOutData(123) = LocalVar%ZMQ_TorqueOffset - LocalVarOutData(124) = LocalVar%ZMQ_PitOffset(1) + LocalVarOutData(89) = LocalVar%PRC_R_Speed + LocalVarOutData(90) = LocalVar%PRC_R_Torque + LocalVarOutData(91) = LocalVar%PRC_R_Pitch + LocalVarOutData(92) = LocalVar%PRC_R_Total + LocalVarOutData(93) = LocalVar%Fl_PitCom + LocalVarOutData(94) = LocalVar%NACIMU_FA_AccF + LocalVarOutData(95) = LocalVar%FA_AccF + LocalVarOutData(96) = LocalVar%FA_Hist + LocalVarOutData(97) = LocalVar%TRA_LastRefSpd + LocalVarOutData(98) = LocalVar%VS_RefSpeed + LocalVarOutData(99) = LocalVar%PtfmTDX + LocalVarOutData(100) = LocalVar%PtfmTDY + LocalVarOutData(101) = LocalVar%PtfmTDZ + LocalVarOutData(102) = LocalVar%PtfmRDX + LocalVarOutData(103) = LocalVar%PtfmRDY + LocalVarOutData(104) = LocalVar%PtfmRDZ + LocalVarOutData(105) = LocalVar%PtfmTVX + LocalVarOutData(106) = LocalVar%PtfmTVY + LocalVarOutData(107) = LocalVar%PtfmTVZ + LocalVarOutData(108) = LocalVar%PtfmRVX + LocalVarOutData(109) = LocalVar%PtfmRVY + LocalVarOutData(110) = LocalVar%PtfmRVZ + LocalVarOutData(111) = LocalVar%PtfmTAX + LocalVarOutData(112) = LocalVar%PtfmTAY + LocalVarOutData(113) = LocalVar%PtfmTAZ + LocalVarOutData(114) = LocalVar%PtfmRAX + LocalVarOutData(115) = LocalVar%PtfmRAY + LocalVarOutData(116) = LocalVar%PtfmRAZ + LocalVarOutData(117) = LocalVar%CC_DesiredL(1) + LocalVarOutData(118) = LocalVar%CC_ActuatedL(1) + LocalVarOutData(119) = LocalVar%CC_ActuatedDL(1) + LocalVarOutData(120) = LocalVar%StC_Input(1) + LocalVarOutData(121) = LocalVar%Flp_Angle(1) + LocalVarOutData(122) = LocalVar%RootMyb_Last(1) + LocalVarOutData(123) = LocalVar%ACC_INFILE_SIZE + LocalVarOutData(124) = LocalVar%AWC_complexangle(1) + LocalVarOutData(125) = LocalVar%ZMQ_ID + LocalVarOutData(126) = LocalVar%ZMQ_YawOffset + LocalVarOutData(127) = LocalVar%ZMQ_TorqueOffset + LocalVarOutData(128) = LocalVar%ZMQ_PitOffset(1) LocalVarOutStrings = [CHARACTER(15) :: 'iStatus', 'Time', 'DT', 'n_DT', 'Time_Last', & 'VS_GenPwr', 'VS_GenPwrF', 'GenSpeed', 'RotSpeed', 'NacHeading', & 'NacVane', 'HorWindV', 'rootMOOP', 'rootMOOPF', 'BlPitch', & @@ -836,14 +848,15 @@ SUBROUTINE Debug(LocalVar, CntrPar, DebugVar, ErrVar, avrSWAP, RootName, size_av 'SS_DelOmegaF', 'TestType', 'Kp_Float', 'VS_MaxTq', 'VS_LastGenTrq', & 'VS_LastGenPwr', 'VS_MechGenPwr', 'VS_SpdErrAr', 'VS_SpdErrBr', 'VS_SpdErr', & 'VS_State', 'VS_Rgn3Pitch', 'WE_Vw', 'WE_Vw_F', 'WE_VwI', & - 'WE_VwIdot', 'VS_LastGenTrqF', 'PRC_WSE_F', 'Fl_PitCom', 'NACIMU_FA_AccF', & - 'FA_AccF', 'FA_Hist', 'TRA_LastRefSpd', 'VS_RefSpeed', 'PtfmTDX', & - 'PtfmTDY', 'PtfmTDZ', 'PtfmRDX', 'PtfmRDY', 'PtfmRDZ', & - 'PtfmTVX', 'PtfmTVY', 'PtfmTVZ', 'PtfmRVX', 'PtfmRVY', & - 'PtfmRVZ', 'PtfmTAX', 'PtfmTAY', 'PtfmTAZ', 'PtfmRAX', & - 'PtfmRAY', 'PtfmRAZ', 'CC_DesiredL', 'CC_ActuatedL', 'CC_ActuatedDL', & - 'StC_Input', 'Flp_Angle', 'RootMyb_Last', 'ACC_INFILE_SIZE', 'AWC_complexangle', & - 'ZMQ_ID', 'ZMQ_YawOffset', 'ZMQ_TorqueOffset', 'ZMQ_PitOffset'] + 'WE_VwIdot', 'VS_LastGenTrqF', 'PRC_WSE_F', 'PRC_R_Speed', 'PRC_R_Torque', & + 'PRC_R_Pitch', 'PRC_R_Total', 'Fl_PitCom', 'NACIMU_FA_AccF', 'FA_AccF', & + 'FA_Hist', 'TRA_LastRefSpd', 'VS_RefSpeed', 'PtfmTDX', 'PtfmTDY', & + 'PtfmTDZ', 'PtfmRDX', 'PtfmRDY', 'PtfmRDZ', 'PtfmTVX', & + 'PtfmTVY', 'PtfmTVZ', 'PtfmRVX', 'PtfmRVY', 'PtfmRVZ', & + 'PtfmTAX', 'PtfmTAY', 'PtfmTAZ', 'PtfmRAX', 'PtfmRAY', & + 'PtfmRAZ', 'CC_DesiredL', 'CC_ActuatedL', 'CC_ActuatedDL', 'StC_Input', & + 'Flp_Angle', 'RootMyb_Last', 'ACC_INFILE_SIZE', 'AWC_complexangle', 'ZMQ_ID', & + 'ZMQ_YawOffset', 'ZMQ_TorqueOffset', 'ZMQ_PitOffset'] ! Initialize debug file IF ((LocalVar%iStatus == 0) .OR. (LocalVar%iStatus == -9)) THEN ! .TRUE. if we're on the first call to the DLL IF (CntrPar%LoggingLevel > 0) THEN @@ -858,8 +871,8 @@ SUBROUTINE Debug(LocalVar, CntrPar, DebugVar, ErrVar, avrSWAP, RootName, size_av CALL GetNewUnit(UnDb2, ErrVar) OPEN(unit=UnDb2, FILE=TRIM(RootName)//'.RO.dbg2') WRITE(UnDb2, *) 'Generated on '//CurDate()//' at '//CurTime()//' using ROSCO-'//TRIM(rosco_version) - WRITE(UnDb2, '(125(a20,TR5:))') 'Time', LocalVarOutStrings - WRITE(UnDb2, '(125(a20,TR5:))') + WRITE(UnDb2, '(129(a20,TR5:))') 'Time', LocalVarOutStrings + WRITE(UnDb2, '(129(a20,TR5:))') END IF IF (CntrPar%LoggingLevel > 2) THEN @@ -922,7 +935,7 @@ SUBROUTINE Debug(LocalVar, CntrPar, DebugVar, ErrVar, avrSWAP, RootName, size_av END DO ! Write debug files - FmtDat = "(F20.5,TR5,124(ES20.5E2,TR5:))" ! The format of the debugging data + FmtDat = "(F20.5,TR5,128(ES20.5E2,TR5:))" ! The format of the debugging data IF ( MOD(LocalVar%n_DT, CntrPar%n_DT_Out) == 0) THEN IF(CntrPar%LoggingLevel > 0) THEN WRITE (UnDb, TRIM(FmtDat)) LocalVar%Time, DebugOutData diff --git a/rosco/controller/src/ROSCO_Types.f90 b/rosco/controller/src/ROSCO_Types.f90 index 64385192..6badfdc0 100644 --- a/rosco/controller/src/ROSCO_Types.f90 +++ b/rosco/controller/src/ROSCO_Types.f90 @@ -83,10 +83,17 @@ MODULE ROSCO_Types REAL(DbKi) :: SS_VSGain ! Variable speed torque controller setpoint smoother gain, [-]. REAL(DbKi) :: SS_PCGain ! Collective pitch controller setpoint smoother gain, [-]. INTEGER(IntKi) :: PRC_Mode ! Power reference tracking mode, 0- use standard rotor speed set points, 1- use PRC rotor speed setpoints + INTEGER(IntKi) :: PRC_Comm ! Power reference communication mode, 0- use constant DISCON inputs, 1- use open loop inputs, 2- use ZMQ inputs REAL(DbKi), DIMENSION(:), ALLOCATABLE :: PRC_WindSpeeds ! Array of wind speeds used in rotor speed vs. wind speed lookup table REAL(DbKi), DIMENSION(:), ALLOCATABLE :: PRC_GenSpeeds ! Array of rotor speeds corresponding to PRC_WindSpeeds INTEGER(IntKi) :: PRC_n ! Number of elements in PRC_WindSpeeds and PRC_GenSpeeds array REAL(DbKi) :: PRC_LPF_Freq ! Frequency of the low pass filter on the wind speed estimate used to set PRC_GenSpeeds [rad/s] + REAL(DbKi) :: PRC_R_Torque ! Power rating through changing the rated torque, default is 1, effective above rated [-] + REAL(DbKi) :: PRC_R_Speed ! Power rating through changing the rated generator speed, default is 1, effective above rated [-] + REAL(DbKi) :: PRC_R_Pitch ! Power rating through changing the fine pitch angle, default is 1, effective below rated [-] + INTEGER(IntKi) :: PRC_Table_n ! Number of elements in PRC_R to _Pitch table + REAL(DbKi), DIMENSION(:), ALLOCATABLE :: PRC_Pitch_Table ! Table of fine pitch versus PRC_R_Table, length should be PRC_Table_n [rad] + REAL(DbKi), DIMENSION(:), ALLOCATABLE :: PRC_R_Table ! Table of turbine rating versus fine pitch (PRC_Pitch_Table), length should be PRC_Table_n, default is 1 [-] INTEGER(IntKi) :: WE_Mode ! Wind speed estimator mode {0 - One-second low pass filtered hub height wind speed, 1 - Imersion and Invariance Estimator (Ortega et al.) REAL(DbKi) :: WE_BladeRadius ! Blade length [m] INTEGER(IntKi) :: WE_CP_n ! Amount of parameters in the Cp array @@ -296,7 +303,7 @@ MODULE ROSCO_Types REAL(DbKi) :: PC_TF ! First-order filter parameter for derivative action REAL(DbKi) :: PC_MaxPit ! Maximum pitch setting in pitch controller (variable) [rad]. REAL(DbKi) :: PC_MinPit ! Minimum pitch setting in pitch controller (variable) [rad]. - REAL(DbKi) :: PC_PitComT ! Collective pitch commmand from PI control [rad]. + REAL(DbKi) :: PC_PitComT ! Total command pitch based on the sum of the proportional and integral terms [rad]. REAL(DbKi) :: PC_PitComT_Last ! Last total command pitch based on the sum of the proportional and integral terms [rad]. REAL(DbKi) :: PC_PitComTF ! Filtered Total command pitch based on the sum of the proportional and integral terms [rad]. REAL(DbKi) :: PC_PitComT_IPC(3) ! Total command pitch based on the sum of the proportional and integral terms, including IPC term [rad]. @@ -336,6 +343,10 @@ MODULE ROSCO_Types REAL(DbKi) :: WE_VwIdot ! Differentiated integrated wind speed quantity for estimation [m/s] REAL(DbKi) :: VS_LastGenTrqF ! Differentiated integrated wind speed quantity for estimation [m/s] REAL(DbKi) :: PRC_WSE_F ! Filtered wind speed estimate for power reference control + REAL(DbKi) :: PRC_R_Speed ! Instantaneous PRC_R_Speed + REAL(DbKi) :: PRC_R_Torque ! Instantaneous PRC_R_Torque + REAL(DbKi) :: PRC_R_Pitch ! Instantaneous PRC_R_Pitch + REAL(DbKi) :: PRC_R_Total ! Instantaneous PRC_R_Total LOGICAL :: SD ! Shutdown, .FALSE. if inactive, .TRUE. if active REAL(DbKi) :: Fl_PitCom ! Shutdown, .FALSE. if inactive, .TRUE. if active REAL(DbKi) :: NACIMU_FA_AccF ! None diff --git a/rosco/controller/src/ReadSetParameters.f90 b/rosco/controller/src/ReadSetParameters.f90 index 131b6581..60a61110 100644 --- a/rosco/controller/src/ReadSetParameters.f90 +++ b/rosco/controller/src/ReadSetParameters.f90 @@ -440,6 +440,15 @@ SUBROUTINE ReadControlParameterFileSub(CntrPar, LocalVar, accINFILE, accINFILE_s IF (ErrVar%aviFAIL < 0) RETURN !------------ POWER REFERENCE TRACKING SETPOINTS -------------- + CALL ParseInput(FileLines, 'PRC_Comm', CntrPar%PRC_Comm, accINFILE(1), ErrVar, CntrPar%PRC_Mode .NE. 1, UnEc) + CALL ParseInput(FileLines, 'PRC_R_Torque', CntrPar%PRC_R_Torque, accINFILE(1), ErrVar, (CntrPar%PRC_Mode .NE. 1) .OR. (CntrPar%PRC_Comm .NE. 0), UnEc) + CALL ParseInput(FileLines, 'PRC_R_Speed', CntrPar%PRC_R_Speed, accINFILE(1), ErrVar, (CntrPar%PRC_Mode .NE. 1) .OR. (CntrPar%PRC_Comm .NE. 0), UnEc) + CALL ParseInput(FileLines, 'PRC_R_Pitch', CntrPar%PRC_R_Pitch, accINFILE(1), ErrVar, (CntrPar%PRC_Mode .NE. 1) .OR. (CntrPar%PRC_Comm .NE. 0), UnEc) + CALL ParseInput(FileLines, 'PRC_Table_n', CntrPar%PRC_Table_n, accINFILE(1), ErrVar, (CntrPar%PRC_Mode .NE. 1) .OR. (CntrPar%PRC_R_Pitch == 1.0), UnEc) + CALL ParseAry(FileLines, 'PRC_R_Table', CntrPar%PRC_R_Table, CntrPar%PRC_Table_n, accINFILE(1), ErrVar, (CntrPar%PRC_Mode .NE. 1) .OR. (CntrPar%PRC_R_Pitch == 1.0), UnEc) + CALL ParseAry(FileLines, 'PRC_Pitch_Table', CntrPar%PRC_Pitch_Table, CntrPar%PRC_Table_n, accINFILE(1), ErrVar, (CntrPar%PRC_Mode .NE. 1) .OR. (CntrPar%PRC_R_Pitch == 1.0), UnEc) + + ! These need to be adapted CALL ParseInput(FileLines, 'PRC_n', CntrPar%PRC_n, accINFILE(1), ErrVar, CntrPar%PRC_Mode == 0) CALL ParseInput(FileLines, 'PRC_LPF_Freq', CntrPar%PRC_LPF_Freq, accINFILE(1), ErrVar, CntrPar%PRC_Mode == 0) CALL ParseAry( FileLines, 'PRC_WindSpeeds', CntrPar%PRC_WindSpeeds, CntrPar%PRC_n, accINFILE(1), ErrVar, CntrPar%PRC_Mode == 0) diff --git a/rosco/toolbox/inputs/toolbox_schema.yaml b/rosco/toolbox/inputs/toolbox_schema.yaml index 44573ae1..31627154 100644 --- a/rosco/toolbox/inputs/toolbox_schema.yaml +++ b/rosco/toolbox/inputs/toolbox_schema.yaml @@ -843,9 +843,41 @@ properties: type: number description: Frequency of the low pass filter on the wind speed estimate used to set PRC_GenSpeeds [rad/s] default: 0.078539 - PRC_n: + PRC_n: # figure out what to do with this! type: number description: Number of elements in PRC_WindSpeeds and PRC_GenSpeeds array + PRC_Comm: + type: number + description: Power reference communication mode, 0- use constant DISCON inputs, 1- use open loop inputs, 2- use ZMQ inputs + default: 0 + PRC_R_Torque: + type: number + description: Constant power rating through changing the rated torque, used if PRC_Comm = 0, default is 1, effective above rated [-] + default: 1 + PRC_R_Speed: + type: number + description: Constant power rating through changing the rated generator speed, used if PRC_Comm = 0, default is 1, effective above rated [-] + default: 1 + PRC_R_Pitch: + type: number + description: Constant power rating through changing the fine pitch angle, used if PRC_Comm = 0, default is 1, effective below rated [-] + default: 1 + PRC_Table_n: + type: number + description: Number of elements in PRC_R to _Pitch table + default: 1 + PRC_Pitch_Table: + type: array + items: + type: number + description: Table of fine pitch versus PRC_R_Table, length should be PRC_Table_n [rad] + default: [0] + PRC_R_Table: + type: array + items: + type: number + description: Table of turbine rating versus fine pitch (PRC_Pitch_Table), length should be PRC_Table_n, default is 1 [-] + default: [1] TRA_ExclSpeed: type: number minimum: 0 diff --git a/rosco/toolbox/utilities.py b/rosco/toolbox/utilities.py index 15e4d550..65a4ba58 100644 --- a/rosco/toolbox/utilities.py +++ b/rosco/toolbox/utilities.py @@ -184,6 +184,13 @@ def write_DISCON(turbine, controller, param_file='DISCON.IN', txt_filename='Cp_C file.write('{:<13.5f} ! SS_PCGain - Collective pitch controller setpoint smoother gain, [-].\n'.format(rosco_vt['SS_PCGain'])) file.write('\n') file.write('!------- POWER REFERENCE TRACKING --------------------------------------\n') + file.write('{:<11d} ! PRC_Comm - {}\n'.format(int(rosco_vt['PRC_Comm']), input_descriptions["PRC_Comm"])) + file.write('{:<13.5f} ! PRC_R_Torque - {}\n'.format(float(rosco_vt['PRC_R_Torque']), input_descriptions["PRC_R_Torque"])) + file.write('{:<13.5f} ! PRC_R_Speed - {}\n'.format(float(rosco_vt['PRC_R_Speed']), input_descriptions["PRC_R_Speed"])) + file.write('{:<13.5f} ! PRC_R_Pitch - {}\n'.format(float(rosco_vt['PRC_R_Pitch']), input_descriptions["PRC_R_Pitch"])) + file.write('{:<11d} ! PRC_Table_n - {}\n'.format(int(rosco_vt['PRC_Table_n']), input_descriptions["PRC_Table_n"])) + file.write('{} ! PRC_R_Table - {}\n'.format(write_array(rosco_vt["PRC_R_Table"]), input_descriptions["PRC_R_Table"])) + file.write('{} ! PRC_Pitch_Table - {}\n'.format(write_array(rosco_vt["PRC_Pitch_Table"]), input_descriptions["PRC_Pitch_Table"])) file.write('{:<11d} ! PRC_n - Number of elements in PRC_WindSpeeds and PRC_GenSpeeds array\n'.format(int(rosco_vt['PRC_n']))) file.write('{:<13.5f} ! PRC_LPF_Freq - {}\n'.format(float(rosco_vt['PRC_LPF_Freq']), input_descriptions["PRC_LPF_Freq"])) file.write('{} ! PRC_WindSpeeds - {}\n'.format(write_array(rosco_vt["PRC_WindSpeeds"]), input_descriptions["PRC_WindSpeeds"])) From 3a5c59a1370ef01e85081d5fc7dfba8f4f297526 Mon Sep 17 00:00:00 2001 From: dzalkind Date: Thu, 28 Mar 2024 13:18:12 -0600 Subject: [PATCH 137/224] Add power control via pitch --- .../rosco_registry/rosco_types.yaml | 6 + rosco/controller/src/ControllerBlocks.f90 | 16 ++- rosco/controller/src/ROSCO_IO.f90 | 103 ++++++++++-------- rosco/controller/src/ROSCO_Types.f90 | 2 + rosco/toolbox/controller.py | 18 +++ rosco/toolbox/inputs/toolbox_schema.yaml | 6 +- 6 files changed, 96 insertions(+), 55 deletions(-) diff --git a/rosco/controller/rosco_registry/rosco_types.yaml b/rosco/controller/rosco_registry/rosco_types.yaml index 58b57b84..eb31f067 100644 --- a/rosco/controller/rosco_registry/rosco_types.yaml +++ b/rosco/controller/rosco_registry/rosco_types.yaml @@ -1236,6 +1236,12 @@ LocalVariables: PRC_R_Total: <<: *real description: Instantaneous PRC_R_Total + PRC_Min_Pitch: + <<: *real + description: Instantaneous PRC_Min_Pitch + PS_Min_Pitch: + <<: *real + description: Instantaneous peak shaving SD: <<: *logical description: Shutdown, .FALSE. if inactive, .TRUE. if active diff --git a/rosco/controller/src/ControllerBlocks.f90 b/rosco/controller/src/ControllerBlocks.f90 index 89ca8525..a3555422 100644 --- a/rosco/controller/src/ControllerBlocks.f90 +++ b/rosco/controller/src/ControllerBlocks.f90 @@ -51,10 +51,14 @@ SUBROUTINE ComputeVariablesSetpoints(CntrPar, LocalVar, objInst, DebugVar, ErrVa ENDIF + ! Set min pitch for power control, will be combined with peak shaving min pitch + LocalVar%PRC_Min_Pitch = interp1d(CntrPar%PRC_R_Table,CntrPar%PRC_Pitch_Table,LocalVar%PRC_R_Pitch, ErrVar) + ELSE LocalVar%PRC_R_Speed = 1.0_DbKi LocalVar%PRC_R_Torque = 1.0_DbKi LocalVar%PRC_R_Pitch = 1.0_DbKi + LocalVar%PRC_Min_Pitch = CntrPar%PC_FinePit ENDIF ! Change pitch reference speed @@ -412,8 +416,9 @@ END SUBROUTINE SetpointSmoother !------------------------------------------------------------------------------------------------------------------------------- REAL(DbKi) FUNCTION PitchSaturation(LocalVar, CntrPar, objInst, DebugVar, ErrVar) ! PitchSaturation defines a minimum blade pitch angle based on a lookup table provided by DISCON.IN - ! SS_Mode = 0, No setpoint smoothing - ! SS_Mode = 1, Implement pitch saturation + ! Minimum pitch for power control also happens here + + USE ROSCO_Types, ONLY : LocalVariables, ControlParameters, ObjectInstances, DebugVariables, ErrorVariables IMPLICIT NONE ! Inputs @@ -425,8 +430,11 @@ REAL(DbKi) FUNCTION PitchSaturation(LocalVar, CntrPar, objInst, DebugVar, ErrVar CHARACTER(*), PARAMETER :: RoutineName = 'PitchSaturation' - ! Define minimum blade pitch angle as a function of estimated wind speed - PitchSaturation = interp1d(CntrPar%PS_WindSpeeds, CntrPar%PS_BldPitchMin, LocalVar%WE_Vw_F, ErrVar) + ! Define minimum blade pitch angle for peak shaving as a function of estimated wind speed + LocalVar%PS_Min_Pitch = interp1d(CntrPar%PS_WindSpeeds, CntrPar%PS_BldPitchMin, LocalVar%WE_Vw_F, ErrVar) + + ! Total min pitch limit is greater of peak shaving and power control pitch + PitchSaturation = max(LocalVar%PS_Min_Pitch, LocalVar%PRC_Min_Pitch) ! Add RoutineName to error message IF (ErrVar%aviFAIL < 0) THEN diff --git a/rosco/controller/src/ROSCO_IO.f90 b/rosco/controller/src/ROSCO_IO.f90 index 0dc6e08c..8706e34b 100644 --- a/rosco/controller/src/ROSCO_IO.f90 +++ b/rosco/controller/src/ROSCO_IO.f90 @@ -148,6 +148,8 @@ SUBROUTINE WriteRestartFile(LocalVar, CntrPar, ErrVar, objInst, RootName, size_a WRITE( Un, IOSTAT=ErrStat) LocalVar%PRC_R_Torque WRITE( Un, IOSTAT=ErrStat) LocalVar%PRC_R_Pitch WRITE( Un, IOSTAT=ErrStat) LocalVar%PRC_R_Total + WRITE( Un, IOSTAT=ErrStat) LocalVar%PRC_Min_Pitch + WRITE( Un, IOSTAT=ErrStat) LocalVar%PS_Min_Pitch WRITE( Un, IOSTAT=ErrStat) LocalVar%SD WRITE( Un, IOSTAT=ErrStat) LocalVar%Fl_PitCom WRITE( Un, IOSTAT=ErrStat) LocalVar%NACIMU_FA_AccF @@ -454,6 +456,8 @@ SUBROUTINE ReadRestartFile(avrSWAP, LocalVar, CntrPar, objInst, PerfData, RootNa READ( Un, IOSTAT=ErrStat) LocalVar%PRC_R_Torque READ( Un, IOSTAT=ErrStat) LocalVar%PRC_R_Pitch READ( Un, IOSTAT=ErrStat) LocalVar%PRC_R_Total + READ( Un, IOSTAT=ErrStat) LocalVar%PRC_Min_Pitch + READ( Un, IOSTAT=ErrStat) LocalVar%PS_Min_Pitch READ( Un, IOSTAT=ErrStat) LocalVar%SD READ( Un, IOSTAT=ErrStat) LocalVar%Fl_PitCom READ( Un, IOSTAT=ErrStat) LocalVar%NACIMU_FA_AccF @@ -700,7 +704,7 @@ SUBROUTINE Debug(LocalVar, CntrPar, DebugVar, ErrVar, avrSWAP, RootName, size_av '[N/A]', '[N/A]', '[N/A]', '[N/A]', '[rad/s]', & '[deg]', '[deg]', '[deg]', '[N/A]', '[rad/s]', & '[rad/s]'] - nLocalVars = 128 + nLocalVars = 130 Allocate(LocalVarOutData(nLocalVars)) Allocate(LocalVarOutStrings(nLocalVars)) LocalVarOutData(1) = LocalVar%iStatus @@ -795,42 +799,44 @@ SUBROUTINE Debug(LocalVar, CntrPar, DebugVar, ErrVar, avrSWAP, RootName, size_av LocalVarOutData(90) = LocalVar%PRC_R_Torque LocalVarOutData(91) = LocalVar%PRC_R_Pitch LocalVarOutData(92) = LocalVar%PRC_R_Total - LocalVarOutData(93) = LocalVar%Fl_PitCom - LocalVarOutData(94) = LocalVar%NACIMU_FA_AccF - LocalVarOutData(95) = LocalVar%FA_AccF - LocalVarOutData(96) = LocalVar%FA_Hist - LocalVarOutData(97) = LocalVar%TRA_LastRefSpd - LocalVarOutData(98) = LocalVar%VS_RefSpeed - LocalVarOutData(99) = LocalVar%PtfmTDX - LocalVarOutData(100) = LocalVar%PtfmTDY - LocalVarOutData(101) = LocalVar%PtfmTDZ - LocalVarOutData(102) = LocalVar%PtfmRDX - LocalVarOutData(103) = LocalVar%PtfmRDY - LocalVarOutData(104) = LocalVar%PtfmRDZ - LocalVarOutData(105) = LocalVar%PtfmTVX - LocalVarOutData(106) = LocalVar%PtfmTVY - LocalVarOutData(107) = LocalVar%PtfmTVZ - LocalVarOutData(108) = LocalVar%PtfmRVX - LocalVarOutData(109) = LocalVar%PtfmRVY - LocalVarOutData(110) = LocalVar%PtfmRVZ - LocalVarOutData(111) = LocalVar%PtfmTAX - LocalVarOutData(112) = LocalVar%PtfmTAY - LocalVarOutData(113) = LocalVar%PtfmTAZ - LocalVarOutData(114) = LocalVar%PtfmRAX - LocalVarOutData(115) = LocalVar%PtfmRAY - LocalVarOutData(116) = LocalVar%PtfmRAZ - LocalVarOutData(117) = LocalVar%CC_DesiredL(1) - LocalVarOutData(118) = LocalVar%CC_ActuatedL(1) - LocalVarOutData(119) = LocalVar%CC_ActuatedDL(1) - LocalVarOutData(120) = LocalVar%StC_Input(1) - LocalVarOutData(121) = LocalVar%Flp_Angle(1) - LocalVarOutData(122) = LocalVar%RootMyb_Last(1) - LocalVarOutData(123) = LocalVar%ACC_INFILE_SIZE - LocalVarOutData(124) = LocalVar%AWC_complexangle(1) - LocalVarOutData(125) = LocalVar%ZMQ_ID - LocalVarOutData(126) = LocalVar%ZMQ_YawOffset - LocalVarOutData(127) = LocalVar%ZMQ_TorqueOffset - LocalVarOutData(128) = LocalVar%ZMQ_PitOffset(1) + LocalVarOutData(93) = LocalVar%PRC_Min_Pitch + LocalVarOutData(94) = LocalVar%PS_Min_Pitch + LocalVarOutData(95) = LocalVar%Fl_PitCom + LocalVarOutData(96) = LocalVar%NACIMU_FA_AccF + LocalVarOutData(97) = LocalVar%FA_AccF + LocalVarOutData(98) = LocalVar%FA_Hist + LocalVarOutData(99) = LocalVar%TRA_LastRefSpd + LocalVarOutData(100) = LocalVar%VS_RefSpeed + LocalVarOutData(101) = LocalVar%PtfmTDX + LocalVarOutData(102) = LocalVar%PtfmTDY + LocalVarOutData(103) = LocalVar%PtfmTDZ + LocalVarOutData(104) = LocalVar%PtfmRDX + LocalVarOutData(105) = LocalVar%PtfmRDY + LocalVarOutData(106) = LocalVar%PtfmRDZ + LocalVarOutData(107) = LocalVar%PtfmTVX + LocalVarOutData(108) = LocalVar%PtfmTVY + LocalVarOutData(109) = LocalVar%PtfmTVZ + LocalVarOutData(110) = LocalVar%PtfmRVX + LocalVarOutData(111) = LocalVar%PtfmRVY + LocalVarOutData(112) = LocalVar%PtfmRVZ + LocalVarOutData(113) = LocalVar%PtfmTAX + LocalVarOutData(114) = LocalVar%PtfmTAY + LocalVarOutData(115) = LocalVar%PtfmTAZ + LocalVarOutData(116) = LocalVar%PtfmRAX + LocalVarOutData(117) = LocalVar%PtfmRAY + LocalVarOutData(118) = LocalVar%PtfmRAZ + LocalVarOutData(119) = LocalVar%CC_DesiredL(1) + LocalVarOutData(120) = LocalVar%CC_ActuatedL(1) + LocalVarOutData(121) = LocalVar%CC_ActuatedDL(1) + LocalVarOutData(122) = LocalVar%StC_Input(1) + LocalVarOutData(123) = LocalVar%Flp_Angle(1) + LocalVarOutData(124) = LocalVar%RootMyb_Last(1) + LocalVarOutData(125) = LocalVar%ACC_INFILE_SIZE + LocalVarOutData(126) = LocalVar%AWC_complexangle(1) + LocalVarOutData(127) = LocalVar%ZMQ_ID + LocalVarOutData(128) = LocalVar%ZMQ_YawOffset + LocalVarOutData(129) = LocalVar%ZMQ_TorqueOffset + LocalVarOutData(130) = LocalVar%ZMQ_PitOffset(1) LocalVarOutStrings = [CHARACTER(15) :: 'iStatus', 'Time', 'DT', 'n_DT', 'Time_Last', & 'VS_GenPwr', 'VS_GenPwrF', 'GenSpeed', 'RotSpeed', 'NacHeading', & 'NacVane', 'HorWindV', 'rootMOOP', 'rootMOOPF', 'BlPitch', & @@ -849,14 +855,15 @@ SUBROUTINE Debug(LocalVar, CntrPar, DebugVar, ErrVar, avrSWAP, RootName, size_av 'VS_LastGenPwr', 'VS_MechGenPwr', 'VS_SpdErrAr', 'VS_SpdErrBr', 'VS_SpdErr', & 'VS_State', 'VS_Rgn3Pitch', 'WE_Vw', 'WE_Vw_F', 'WE_VwI', & 'WE_VwIdot', 'VS_LastGenTrqF', 'PRC_WSE_F', 'PRC_R_Speed', 'PRC_R_Torque', & - 'PRC_R_Pitch', 'PRC_R_Total', 'Fl_PitCom', 'NACIMU_FA_AccF', 'FA_AccF', & - 'FA_Hist', 'TRA_LastRefSpd', 'VS_RefSpeed', 'PtfmTDX', 'PtfmTDY', & - 'PtfmTDZ', 'PtfmRDX', 'PtfmRDY', 'PtfmRDZ', 'PtfmTVX', & - 'PtfmTVY', 'PtfmTVZ', 'PtfmRVX', 'PtfmRVY', 'PtfmRVZ', & - 'PtfmTAX', 'PtfmTAY', 'PtfmTAZ', 'PtfmRAX', 'PtfmRAY', & - 'PtfmRAZ', 'CC_DesiredL', 'CC_ActuatedL', 'CC_ActuatedDL', 'StC_Input', & - 'Flp_Angle', 'RootMyb_Last', 'ACC_INFILE_SIZE', 'AWC_complexangle', 'ZMQ_ID', & - 'ZMQ_YawOffset', 'ZMQ_TorqueOffset', 'ZMQ_PitOffset'] + 'PRC_R_Pitch', 'PRC_R_Total', 'PRC_Min_Pitch', 'PS_Min_Pitch', 'Fl_PitCom', & + 'NACIMU_FA_AccF', 'FA_AccF', 'FA_Hist', 'TRA_LastRefSpd', 'VS_RefSpeed', & + 'PtfmTDX', 'PtfmTDY', 'PtfmTDZ', 'PtfmRDX', 'PtfmRDY', & + 'PtfmRDZ', 'PtfmTVX', 'PtfmTVY', 'PtfmTVZ', 'PtfmRVX', & + 'PtfmRVY', 'PtfmRVZ', 'PtfmTAX', 'PtfmTAY', 'PtfmTAZ', & + 'PtfmRAX', 'PtfmRAY', 'PtfmRAZ', 'CC_DesiredL', 'CC_ActuatedL', & + 'CC_ActuatedDL', 'StC_Input', 'Flp_Angle', 'RootMyb_Last', 'ACC_INFILE_SIZE', & + 'AWC_complexangle', 'ZMQ_ID', 'ZMQ_YawOffset', 'ZMQ_TorqueOffset', 'ZMQ_PitOffset' & + ] ! Initialize debug file IF ((LocalVar%iStatus == 0) .OR. (LocalVar%iStatus == -9)) THEN ! .TRUE. if we're on the first call to the DLL IF (CntrPar%LoggingLevel > 0) THEN @@ -871,8 +878,8 @@ SUBROUTINE Debug(LocalVar, CntrPar, DebugVar, ErrVar, avrSWAP, RootName, size_av CALL GetNewUnit(UnDb2, ErrVar) OPEN(unit=UnDb2, FILE=TRIM(RootName)//'.RO.dbg2') WRITE(UnDb2, *) 'Generated on '//CurDate()//' at '//CurTime()//' using ROSCO-'//TRIM(rosco_version) - WRITE(UnDb2, '(129(a20,TR5:))') 'Time', LocalVarOutStrings - WRITE(UnDb2, '(129(a20,TR5:))') + WRITE(UnDb2, '(131(a20,TR5:))') 'Time', LocalVarOutStrings + WRITE(UnDb2, '(131(a20,TR5:))') END IF IF (CntrPar%LoggingLevel > 2) THEN @@ -935,7 +942,7 @@ SUBROUTINE Debug(LocalVar, CntrPar, DebugVar, ErrVar, avrSWAP, RootName, size_av END DO ! Write debug files - FmtDat = "(F20.5,TR5,128(ES20.5E2,TR5:))" ! The format of the debugging data + FmtDat = "(F20.5,TR5,130(ES20.5E2,TR5:))" ! The format of the debugging data IF ( MOD(LocalVar%n_DT, CntrPar%n_DT_Out) == 0) THEN IF(CntrPar%LoggingLevel > 0) THEN WRITE (UnDb, TRIM(FmtDat)) LocalVar%Time, DebugOutData diff --git a/rosco/controller/src/ROSCO_Types.f90 b/rosco/controller/src/ROSCO_Types.f90 index 6badfdc0..66ca3506 100644 --- a/rosco/controller/src/ROSCO_Types.f90 +++ b/rosco/controller/src/ROSCO_Types.f90 @@ -347,6 +347,8 @@ MODULE ROSCO_Types REAL(DbKi) :: PRC_R_Torque ! Instantaneous PRC_R_Torque REAL(DbKi) :: PRC_R_Pitch ! Instantaneous PRC_R_Pitch REAL(DbKi) :: PRC_R_Total ! Instantaneous PRC_R_Total + REAL(DbKi) :: PRC_Min_Pitch ! Instantaneous PRC_Min_Pitch + REAL(DbKi) :: PS_Min_Pitch ! Instantaneous peak shaving LOGICAL :: SD ! Shutdown, .FALSE. if inactive, .TRUE. if active REAL(DbKi) :: Fl_PitCom ! Shutdown, .FALSE. if inactive, .TRUE. if active REAL(DbKi) :: NACIMU_FA_AccF ! None diff --git a/rosco/toolbox/controller.py b/rosco/toolbox/controller.py index 9b78cce5..bffe3259 100644 --- a/rosco/toolbox/controller.py +++ b/rosco/toolbox/controller.py @@ -381,6 +381,23 @@ def tune_controller(self, turbine): self.ps.peak_shaving(self, turbine) self.ps.min_pitch_saturation(self,turbine) + # --- Power control --- + + PRC_Table_n = self.controller_params['DISCON']['PRC_Table_n'] + pitch_range = np.linspace(self.min_pitch,self.max_pitch, num=100) # radians + + # Cp at optimal TSR + Cp_TSR_opt = turbine.Cp.interp_surface(pitch_range,turbine.Cp.TSR_opt) + + # Solve for pitch that decreases Cp by R_range using linear interpolation + R_range = np.linspace(0,1,num=PRC_Table_n) + Cp_R = R_range * turbine.Cp.max + pitch_R = np.interp(Cp_R,np.flip(Cp_TSR_opt),np.flip(pitch_range)) # need to flip because interp wants xp to be increasing + + # Save values back to DISCON dict + self.controller_params['DISCON']['PRC_R_Table'] = R_range + self.controller_params['DISCON']['PRC_Pitch_Table'] = pitch_R + # --- Floating feedback term --- if self.Fl_Mode >= 1: # Floating feedback @@ -476,6 +493,7 @@ def tune_controller(self, turbine): if 'f_lpf_cornerfreq' in self.controller_params['filter_params']: self.f_lpf_cornerfreq = self.controller_params['filter_params']['f_lpf_cornerfreq'] + def tune_flap_controller(self,turbine): ''' Tune controller for distributed aerodynamic control diff --git a/rosco/toolbox/inputs/toolbox_schema.yaml b/rosco/toolbox/inputs/toolbox_schema.yaml index 31627154..0b29464f 100644 --- a/rosco/toolbox/inputs/toolbox_schema.yaml +++ b/rosco/toolbox/inputs/toolbox_schema.yaml @@ -865,19 +865,19 @@ properties: PRC_Table_n: type: number description: Number of elements in PRC_R to _Pitch table - default: 1 + default: 20 PRC_Pitch_Table: type: array items: type: number description: Table of fine pitch versus PRC_R_Table, length should be PRC_Table_n [rad] - default: [0] + default: [0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0] PRC_R_Table: type: array items: type: number description: Table of turbine rating versus fine pitch (PRC_Pitch_Table), length should be PRC_Table_n, default is 1 [-] - default: [1] + default: [1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1] TRA_ExclSpeed: type: number minimum: 0 From f846f17e2711d44c01bdead1ae69a634dceced66 Mon Sep 17 00:00:00 2001 From: David Stockhouse Date: Thu, 9 May 2024 15:55:17 -0600 Subject: [PATCH 138/224] Initial implementation of fixed blade pitch control for MHK turbines. A generic power curve can be specified by the user, and the toolbox generates an operating schedule for generator speed and torque. The configuration options will be changed and integrated into VS and PC controller options. --- Examples/29_marine_hydro_fbp.py | 139 ++++++++++++++++++ .../MHK_RM1/MHK_RM1_Floating_ElastoDyn.dat | 6 +- Examples/Tune_Cases/RM1_MHK_FBP.yaml | 73 +++++++++ rosco/controller/src/ControllerBlocks.f90 | 21 ++- rosco/controller/src/Controllers.f90 | 43 ++++-- rosco/controller/src/ROSCO_IO.f90 | 4 +- rosco/controller/src/ROSCO_Types.f90 | 8 +- rosco/controller/src/ReadSetParameters.f90 | 35 +++-- rosco/toolbox/controller.py | 127 ++++++++++++---- rosco/toolbox/inputs/toolbox_schema.yaml | 34 ++++- rosco/toolbox/utilities.py | 13 ++ 11 files changed, 436 insertions(+), 67 deletions(-) create mode 100644 Examples/29_marine_hydro_fbp.py create mode 100644 Examples/Tune_Cases/RM1_MHK_FBP.yaml diff --git a/Examples/29_marine_hydro_fbp.py b/Examples/29_marine_hydro_fbp.py new file mode 100644 index 00000000..08a6764d --- /dev/null +++ b/Examples/29_marine_hydro_fbp.py @@ -0,0 +1,139 @@ +''' +----------- 26_marine_hydro ------------------------ +Run openfast with ROSCO and a MHK turbine +----------------------------------------------- + + +''' + +import os +from rosco.toolbox.ofTools.case_gen.run_FAST import run_FAST_ROSCO +from rosco.toolbox.ofTools.case_gen import CaseLibrary as cl +from rosco.toolbox.ofTools.fast_io import output_processing +from rosco.toolbox import controller as ROSCO_controller +from rosco.toolbox import turbine as ROSCO_turbine +from rosco.toolbox.utilities import write_DISCON +from rosco.toolbox.inputs.validation import load_rosco_yaml +import matplotlib.pyplot as plt + +''' +Run MHK turbine in OpenFAST with ROSCO torque controller + + +''' + + +#directories +this_dir = os.path.dirname(os.path.abspath(__file__)) +rosco_dir = os.path.dirname(this_dir) +example_out_dir = os.path.join(this_dir,'examples_out') +os.makedirs(example_out_dir,exist_ok=True) + +def main(): + + # Input yaml and output directory + parameter_filename = os.path.join(this_dir,'Tune_Cases/RM1_MHK_FBP.yaml') + run_dir = os.path.join(example_out_dir,'29_MHK/0_baseline') + os.makedirs(run_dir,exist_ok=True) + + inps = load_rosco_yaml(parameter_filename) + path_params = inps['path_params'] + turbine_params = inps['turbine_params'] + controller_params = inps['controller_params'] + + # Instantiate turbine, controller, and file processing classes + turbine = ROSCO_turbine.Turbine(turbine_params) + controller = ROSCO_controller.Controller(controller_params) + + # Load turbine data from OpenFAST and rotor performance text file + cp_filename = os.path.join(this_dir,path_params['rotor_performance_filename']) + turbine.load_from_fast( + path_params['FAST_InputFile'], + os.path.join(this_dir,path_params['FAST_directory']), + rot_source='txt',txt_filename= cp_filename + ) + + # Tune controller + controller.tune_controller(turbine) + + # Write parameter input file + param_file = os.path.join(run_dir,'DISCON.IN') + write_DISCON(turbine, + controller, + param_file=param_file, + txt_filename=cp_filename + ) + + # # Plot operating schedule + # fig, ax = plt.subplots(2,2,constrained_layout=True,sharex=True) + # ax = ax.flatten() + # ax[0].plot(controller.v[len(controller.v_below_rated)+1:], controller.omega_pc_U) + # ax[0].set_ylabel('omega_pc') + + # ax[1].plot(controller.v[len(controller.v_below_rated)+1:], controller.zeta_pc_U) + # ax[1].set_ylabel('zeta_pc') + + # ax[2].plot(controller.v[len(controller.v_below_rated)+1:], controller.pc_gain_schedule.Kp) + # ax[2].set_xlabel('Wind Speed') + # ax[2].set_ylabel('Proportional Gain') + + # ax[3].plot(controller.v[len(controller.v_below_rated)+1:], controller.pc_gain_schedule.Ki) + # ax[3].set_xlabel('Wind Speed') + # ax[3].set_ylabel('Integral Gain') + + # plt.suptitle('Pitch Controller Gains') + + + # simulation set up + r = run_FAST_ROSCO() + r.tuning_yaml = parameter_filename + # r.wind_case_fcn = cl.simp_step # single step wind input + r.wind_case_fcn = cl.power_curve + r.wind_case_opts = { + 'U': [3.5], + 'TMax': 100.0, + } + r.case_inputs = {} + # r.fst_vt = reader.fst_vt + # r.controller_params = controller_params + r.save_dir = run_dir + r.rosco_dir = rosco_dir + + r.run_FAST() + + op = output_processing.output_processing() + fast_out = op.load_fast_out([os.path.join(run_dir,'RM1_MHK_FBP/power_curve/base/RM1_MHK_FBP_0.out')], tmin=0) + fig, axs = plt.subplots(4,1) + axs[0].plot(fast_out[0]['Time'],fast_out[0]['Wind1VelX'],label='Flow Speed') + axs[1].plot(fast_out[0]['Time'],fast_out[0]['GenSpeed'],label='Gen Speed') + axs[2].plot(fast_out[0]['Time'],fast_out[0]['GenTq'],label='Gen Torque') + axs[3].plot(fast_out[0]['Time'],fast_out[0]['GenPwr'],label='Gen Power') + + + # op = output_processing.output_processing() + # op2 = output_processing.output_processing() + + # md_out = op.load_fast_out([os.path.join(run_dir,'IEA15MW_cable/power_curve/base/IEA15MW_cable_0.MD.Line1.out')], tmin=0) + # local_vars = op2.load_fast_out([os.path.join(run_dir,'IEA15MW_cable/power_curve/base/IEA15MW_cable_0.RO.dbg2')], tmin=0) + + # fig, axs = plt.subplots(4,1) + # axs[0].plot(local_vars[0]['Time'],local_vars[0]['CC_DesiredL'],label='CC_DesiredL') + # axs[1].plot(local_vars[0]['Time'],local_vars[0]['CC_ActuatedL'],label='CC_ActuatedL') + # axs[2].plot(local_vars[0]['Time'],local_vars[0]['CC_ActuatedDL'],label='CC_ActuatedDL') + # axs[3].plot(md_out[0]['Time'],md_out[0]['Seg20Lst'],label='Seg20Lst') + + # [a.legend() for a in axs] + # [a.grid() for a in axs] + + # if False: + # plt.show() + # else: + # plt.savefig(os.path.join(example_out_dir,'22_cable_control.png')) + + # # Check that the last segment of line 1 shrinks by 10 m + # # np.testing.assert_almost_equal(md_out[0]['Seg20Lst'][-1] - md_out[0]['Seg20Lst'][0], line_ends[0], 2) + + + +if __name__=="__main__": + main() diff --git a/Examples/Test_Cases/MHK_RM1/MHK_RM1_Floating_ElastoDyn.dat b/Examples/Test_Cases/MHK_RM1/MHK_RM1_Floating_ElastoDyn.dat index 5a79e239..207ffc39 100644 --- a/Examples/Test_Cases/MHK_RM1/MHK_RM1_Floating_ElastoDyn.dat +++ b/Examples/Test_Cases/MHK_RM1/MHK_RM1_Floating_ElastoDyn.dat @@ -25,9 +25,9 @@ True PtfmYDOF - Platform yaw rotation DOF (flag) ---------------------- INITIAL CONDITIONS -------------------------------------- 0 OoPDefl - Initial out-of-plane blade-tip displacement (meters) 0 IPDefl - Initial in-plane blade-tip deflection (meters) - 10 BlPitch(1) - Blade 1 initial pitch (degrees) - 10 BlPitch(2) - Blade 2 initial pitch (degrees) - 10 BlPitch(3) - Blade 3 initial pitch (degrees) [unused for 2 blades] + 0 BlPitch(1) - Blade 1 initial pitch (degrees) + 0 BlPitch(2) - Blade 2 initial pitch (degrees) + 0 BlPitch(3) - Blade 3 initial pitch (degrees) [unused for 2 blades] 0 TeetDefl - Initial or fixed teeter angle (degrees) [unused for 3 blades] 0 Azimuth - Initial azimuth angle for blade 1 (degrees) 11.50 RotSpeed - Initial or fixed rotor speed (rpm) diff --git a/Examples/Tune_Cases/RM1_MHK_FBP.yaml b/Examples/Tune_Cases/RM1_MHK_FBP.yaml new file mode 100644 index 00000000..752e23d8 --- /dev/null +++ b/Examples/Tune_Cases/RM1_MHK_FBP.yaml @@ -0,0 +1,73 @@ +--- # ---------------------NREL Generic controller tuning input file ------------------- + # Written for use with ROSCO_Toolbox tuning procedures + # Turbine: RM1 Marine Turbine +# ------------------------------ OpenFAST PATH DEFINITIONS ------------------------------ +path_params: + FAST_InputFile: 'MHK_RM1_Floating.fst' # Name of *.fst file + FAST_directory: '../Test_Cases/MHK_RM1' # Main OpenFAST model directory, where the *.fst lives + # Optional + rotor_performance_filename: '../Test_Cases/MHK_RM1/MHK_RM1_Cp_Ct_Cq.txt' # Filename for rotor performance text file (if it has been generated by ccblade already) + +# -------------------------------- TURBINE PARAMETERS ----------------------------------- +turbine_params: + rotor_inertia: 92169 # Rotor inertia [kg m^2], {Available in Elastodyn .sum file} + rated_rotor_speed: 1.204 # 11.5 rpm # Rated rotor speed [rad/s] + v_min: 0.5 # Cut-in wind speed [m/s] + v_rated: 2.0 # Rated wind speed [m/s] + v_max: 4.0 # Cut-out wind speed [m/s], -- Does not need to be exact (JUST ASSUME FOR NOW) + max_pitch_rate: 0.1745 # Maximum blade pitch rate [rad/s] + max_torque_rate: 1500000. # Maximum torque rate [Nm/s], {~1/4 VS_RtTq/s} + rated_power: 500000 # Rated Power [W] + bld_edgewise_freq: 60.2831853 # Blade edgewise first natural frequency [rad/s] + bld_flapwise_freq: 0.0 # Blade flapwise first natural frequency [rad/s] + reynolds_ref: 8e6 + # Optional + # TSR_operational: # None # Desired below-rated operational tip speed ratio (Cp-maximizing TSR is used if not defined) +#------------------------------- CONTROLLER PARAMETERS ---------------------------------- +controller_params: + # Controller flags + LoggingLevel: 2 # {0: write no debug files, 1: write standard output .dbg-file, 2: write standard output .dbg-file and complete avrSWAP-array .dbg2-file + F_LPFType: 1 # {1: first-order low-pass filter, 2: second-order low-pass filter}, [rad/s] (currently filters generator speed and pitch control signals) + F_NotchType: 1 # Notch filter on generator speed and/or tower fore-aft motion (for floating) {0: disable, 1: generator speed, 2: tower-top fore-aft motion, 3: generator speed and tower-top fore-aft motion} + IPC_ControlMode: 0 # Turn Individual Pitch Control (IPC) for fatigue load reductions (pitch contribution) {0: off, 1: 1P reductions, 2: 1P+2P reductions} + VS_ControlMode: 4 # Generator torque control mode in above rated conditions {0: constant torque, 1: constant power, 2: TSR tracking PI control} + VS_ConstPower: 0 # Generator torque control mode in above rated conditions {0: constant torque, 1: constant power, 2: TSR tracking PI control} + PC_ControlMode: 0 # Blade pitch control mode {0: No pitch, fix to fine pitch, 1: active PI blade pitch control} + Y_ControlMode: 0 # Yaw control mode {0: no yaw control, 1: yaw rate control, 2: yaw-by-IPC} + SS_Mode: 1 # Setpoint Smoother mode {0: no setpoint smoothing, 1: introduce setpoint smoothing} + WE_Mode: 0 # Wind speed estimator mode {0: One-second low pass filtered hub height wind speed, 1: Immersion and Invariance Estimator (Ortega et al.)} + PS_Mode: 0 # Pitch saturation mode {0: no pitch saturation, 1: peak shaving, 2: Cp-maximizing pitch saturation, 3: peak shaving and Cp-maximizing pitch saturation} + SD_Mode: 0 # Shutdown mode {0: no shutdown procedure, 1: pitch to max pitch at shutdown} + Fl_Mode: 1 # Floating specific feedback mode {0: no nacelle velocity feedback, 1: nacelle velocity feedback} + Flp_Mode: 0 # Flap control mode {0: no flap control, 1: steady state flap angle, 2: Proportional flap control} + # Controller parameters + U_pc: [2.3,2.5] + interp_type: sigma + zeta_pc: [0.7,0.7] # Pitch controller desired damping ratio [-] + omega_pc: [0.9,0.9] # Pitch controller desired natural frequency [rad/s] + zeta_vs: 1.0 # Torque controller desired damping ratio [-] + omega_vs: 0.8 # Torque controller desired natural frequency [rad/s] + twr_freq: 3.3404 # Tower natural frequency [rad/s] # 0.4499 (old value) 3.3404(new value) + # twr_freq: 0.061009 # 2P + ptfm_freq: 0.6613 # Platform natural frequency [rad/s] (OC4Hywind Parameters, here) 0.2325 (old value) 0.6613879263 (new value) + # Optional + ps_percent: 0.80 # Percent peak shaving [%, <= 1 ], {default = 80%} + sd_maxpit: 0.4363 # Maximum blade pitch angle to initiate shutdown [rad], {default = bld pitch at v_max} + Kp_float: -0.3897 + max_torque_factor: 5 + FBP_ref_mode: 1 + FBP_P_mode: 0 + FBP_U: [2.0, 4.0] + FBP_P: [1.0, 1.0] + DISCON: + F_NumNotchFilts: 0 + F_NotchFreqs: [1.0, 2.4200] # 2P + F_NotchBetaNum: [0.0, 0.0] + F_NotchBetaDen: [0.25, 0.25] + F_GenSpdNotch_N: 0 + F_GenSpdNotch_Ind: [1,2] + F_TwrTopNotch_N: 0 + F_TwrTopNotch_Ind: [1,2] + F_NotchCornerFreq_GS: [2.42] + F_FlHighPassFreq: 1.5 + VS_PwrFiltF: 0.05 diff --git a/rosco/controller/src/ControllerBlocks.f90 b/rosco/controller/src/ControllerBlocks.f90 index be9e6400..02b9a9c1 100644 --- a/rosco/controller/src/ControllerBlocks.f90 +++ b/rosco/controller/src/ControllerBlocks.f90 @@ -34,6 +34,7 @@ SUBROUTINE ComputeVariablesSetpoints(CntrPar, LocalVar, objInst, DebugVar, ErrVa TYPE(DebugVariables), INTENT(INOUT) :: DebugVar TYPE(ErrorVariables), INTENT(INOUT) :: ErrVar + REAL(DbKi) :: VS_RefSpdRaw ! Temporary variable for applying LPF to the reference speed after it is generated ! ----- Pitch controller speed and power error ----- @@ -62,8 +63,22 @@ SUBROUTINE ComputeVariablesSetpoints(CntrPar, LocalVar, objInst, DebugVar, ErrVa IF (CntrPar%VS_ControlMode == 2) THEN LocalVar%VS_RefSpd_TSR = (CntrPar%VS_TSRopt * LocalVar%We_Vw_F / CntrPar%WE_BladeRadius) * CntrPar%WE_GearboxRatio ELSEIF (CntrPar%VS_ControlMode == 3) THEN - LocalVar%VS_GenPwrF = LPFilter(LocalVar%VS_GenPwr, LocalVar%DT,CntrPar%VS_PwrFiltF, LocalVar%FP, LocalVar%iStatus, LocalVar%restart, objInst%instLPF) - LocalVar%VS_RefSpd_TSR = (LocalVar%VS_GenPwrF/CntrPar%VS_Rgn2K)**(1./3.) ! Genspeed reference that doesnt depend on wind speed estimate (https://doi.org/10.2172/1259805) + LocalVar%VS_GenPwrF = LPFilter(LocalVar%VS_GenPwr, LocalVar%DT, CntrPar%VS_PwrFiltF, LocalVar%FP, LocalVar%iStatus, LocalVar%restart, objInst%instLPF) + LocalVar%VS_RefSpd_TSR = (LocalVar%VS_GenPwrF/CntrPar%VS_Rgn2K)**(1./3.) ! Genspeed reference that doesn't depend on wind speed estimate (https://doi.org/10.2172/1259805) + ELSEIF (CntrPar%VS_ControlMode == 4) THEN + IF (CntrPar%FBP_RefMode == 0) THEN + ! Use WSE to look up speed reference + VS_RefSpdRaw = interp1d(CntrPar%FBP_U, CntrPar%FBP_Omega, LocalVar%WE_Vw, ErrVar) + ELSEIF (CntrPar%FBP_RefMode == 1) THEN + ! Use LocalVar%GenTq or LocalVar%GenTqMeas, Omega must be expressed as a function of Tau + VS_RefSpdRaw = interp1d(CntrPar%FBP_Tau, CntrPar%FBP_Omega, LocalVar%GenTq, ErrVar) + ENDIF + + ! VS_RefSpdRaw = (LocalVar%GenTq/CntrPar%VS_Rgn2K)**(1./2.) ! WSE-independent below-rated generator speed reference based on torque instead of power + ! VS_RefSpdRaw = min(VS_RefSpdRaw, (CntrPar%VS_RtPwr/(CntrPar%VS_GenEff/100.0))/LocalVar%GenTq) ! Above-rated underspeed reference + ! VS_RefSpdRaw = min(VS_RefSpdRaw, CntrPar%VS_RefSpd) ! Saturate to rated speed + + LocalVar%VS_RefSpd_TSR = LPFilter(VS_RefSpdRaw, LocalVar%DT, CntrPar%VS_PwrFiltF, LocalVar%FP, LocalVar%iStatus, LocalVar%restart, objInst%instLPF) ELSE LocalVar%VS_RefSpd_TSR = CntrPar%VS_RefSpd ENDIF @@ -97,7 +112,7 @@ SUBROUTINE ComputeVariablesSetpoints(CntrPar, LocalVar, objInst, DebugVar, ErrVa LocalVar%VS_RefSpd = max(LocalVar%VS_RefSpd, CntrPar%VS_MinOmSpd) ! Reference error - IF ((CntrPar%VS_ControlMode == 2) .OR. (CntrPar%VS_ControlMode == 3)) THEN + IF ((CntrPar%VS_ControlMode == 2) .OR. (CntrPar%VS_ControlMode == 3) .OR. (CntrPar%VS_ControlMode == 4)) THEN LocalVar%VS_SpdErr = LocalVar%VS_RefSpd - LocalVar%GenSpeedF ENDIF diff --git a/rosco/controller/src/Controllers.f90 b/rosco/controller/src/Controllers.f90 index a32c391c..9fe102eb 100644 --- a/rosco/controller/src/Controllers.f90 +++ b/rosco/controller/src/Controllers.f90 @@ -50,15 +50,27 @@ SUBROUTINE PitchControl(avrSWAP, CntrPar, LocalVar, objInst, DebugVar, ErrVar) LocalVar%PC_MaxPit = CntrPar%PC_FinePit END IF - ! Compute (interpolate) the gains based on previously commanded blade pitch angles and lookup table: - LocalVar%PC_KP = interp1d(CntrPar%PC_GS_angles, CntrPar%PC_GS_KP, LocalVar%PC_PitComTF, ErrVar) ! Proportional gain - LocalVar%PC_KI = interp1d(CntrPar%PC_GS_angles, CntrPar%PC_GS_KI, LocalVar%PC_PitComTF, ErrVar) ! Integral gain - LocalVar%PC_KD = interp1d(CntrPar%PC_GS_angles, CntrPar%PC_GS_KD, LocalVar%PC_PitComTF, ErrVar) ! Derivative gain - LocalVar%PC_TF = interp1d(CntrPar%PC_GS_angles, CntrPar%PC_GS_TF, LocalVar%PC_PitComTF, ErrVar) ! TF gains (derivative filter) !NJA - need to clarify - - ! Compute the collective pitch command associated with the proportional and integral gains: - LocalVar%PC_PitComT = PIController(LocalVar%PC_SpdErr, LocalVar%PC_KP, LocalVar%PC_KI, LocalVar%PC_MinPit, LocalVar%PC_MaxPit, LocalVar%DT, LocalVar%BlPitch(1), LocalVar%piP, LocalVar%restart, objInst%instPI) - DebugVar%PC_PICommand = LocalVar%PC_PitComT + IF (CntrPar%VS_ControlMode .NE. 4) THEN + ! Compute (interpolate) the gains based on previously commanded blade pitch angles and lookup table: + LocalVar%PC_KP = interp1d(CntrPar%PC_GS_angles, CntrPar%PC_GS_KP, LocalVar%PC_PitComTF, ErrVar) ! Proportional gain + LocalVar%PC_KI = interp1d(CntrPar%PC_GS_angles, CntrPar%PC_GS_KI, LocalVar%PC_PitComTF, ErrVar) ! Integral gain + LocalVar%PC_KD = interp1d(CntrPar%PC_GS_angles, CntrPar%PC_GS_KD, LocalVar%PC_PitComTF, ErrVar) ! Derivative gain + LocalVar%PC_TF = interp1d(CntrPar%PC_GS_angles, CntrPar%PC_GS_TF, LocalVar%PC_PitComTF, ErrVar) ! TF gains (derivative filter) !NJA - need to clarify + + ! Compute the collective pitch command associated with the proportional and integral gains: + LocalVar%PC_PitComT = PIController(LocalVar%PC_SpdErr, LocalVar%PC_KP, LocalVar%PC_KI, LocalVar%PC_MinPit, LocalVar%PC_MaxPit, LocalVar%DT, LocalVar%BlPitch(1), LocalVar%piP, LocalVar%restart, objInst%instPI) + DebugVar%PC_PICommand = LocalVar%PC_PitComT + ELSE + ! Avoid the need to interpolate and compute gains for fixed-pitch control + LocalVar%PC_KP = 0.0 + LocalVar%PC_KI = 0.0 + LocalVar%PC_KD = 0.0 + LocalVar%PC_TF = 0.0 + + LocalVar%PC_PitComT = CntrPar%PC_FinePit + DebugVar%PC_PICommand = LocalVar%PC_PitComT + ENDIF + ! Find individual pitch control contribution IF ((CntrPar%IPC_ControlMode >= 1) .OR. (CntrPar%Y_ControlMode == 2)) THEN CALL IPC(CntrPar, LocalVar, objInst, DebugVar, ErrVar) @@ -203,7 +215,7 @@ SUBROUTINE VariableSpeedControl(avrSWAP, CntrPar, LocalVar, objInst, ErrVar) CHARACTER(*), PARAMETER :: RoutineName = 'VariableSpeedControl' ! Allocate Variables - + ! -------- Variable-Speed Torque Controller -------- ! Define max torque IF (LocalVar%VS_State == 4) THEN @@ -212,14 +224,19 @@ SUBROUTINE VariableSpeedControl(avrSWAP, CntrPar, LocalVar, objInst, ErrVar) ! VS_MaxTq = CntrPar%VS_MaxTq ! NJA: May want to boost max torque LocalVar%VS_MaxTq = CntrPar%VS_RtTq ENDIF - + ! Optimal Tip-Speed-Ratio tracking controller - IF ((CntrPar%VS_ControlMode == 2) .OR. (CntrPar%VS_ControlMode == 3)) THEN + IF ((CntrPar%VS_ControlMode == 2) .OR. (CntrPar%VS_ControlMode == 3) .OR. (CntrPar%VS_ControlMode == 4)) THEN ! Constant Power, update VS_MaxTq IF (CntrPar%VS_ConstPower == 1) THEN LocalVar%VS_MaxTq = min((CntrPar%VS_RtPwr/(CntrPar%VS_GenEff/100.0))/LocalVar%GenSpeedF, CntrPar%VS_MaxTq) END IF + IF (CntrPar%VS_ControlMode == 4) THEN + ! DBS: In the future, look into combining FBP with constant power + LocalVar%VS_MaxTq = CntrPar%VS_MaxTq + END IF + ! PI controller LocalVar%GenTq = PIController( & LocalVar%VS_SpdErr, & @@ -228,7 +245,7 @@ SUBROUTINE VariableSpeedControl(avrSWAP, CntrPar, LocalVar, objInst, ErrVar) CntrPar%VS_MinTq, LocalVar%VS_MaxTq, & LocalVar%DT, LocalVar%VS_LastGenTrq, LocalVar%piP, LocalVar%restart, objInst%instPI) LocalVar%GenTq = saturate(LocalVar%GenTq, CntrPar%VS_MinTq, LocalVar%VS_MaxTq) - + ! K*Omega^2 control law with PI torque control in transition regions ELSEIF (CntrPar%VS_ControlMode == 1) THEN ! Update PI loops for region 1.5 and 2.5 PI control diff --git a/rosco/controller/src/ROSCO_IO.f90 b/rosco/controller/src/ROSCO_IO.f90 index e5f037d5..ab1ec3ea 100644 --- a/rosco/controller/src/ROSCO_IO.f90 +++ b/rosco/controller/src/ROSCO_IO.f90 @@ -82,7 +82,6 @@ SUBROUTINE WriteRestartFile(LocalVar, CntrPar, ErrVar, objInst, RootName, size_a WRITE( Un, IOSTAT=ErrStat) LocalVar%PC_RefSpd_SS WRITE( Un, IOSTAT=ErrStat) LocalVar%PC_RefSpd_PRC WRITE( Un, IOSTAT=ErrStat) LocalVar%RotSpeedF - WRITE( Un, IOSTAT=ErrStat) LocalVar%PC_RefSpd WRITE( Un, IOSTAT=ErrStat) LocalVar%GenSpeedF WRITE( Un, IOSTAT=ErrStat) LocalVar%GenTq WRITE( Un, IOSTAT=ErrStat) LocalVar%GenTqMeas @@ -385,7 +384,6 @@ SUBROUTINE ReadRestartFile(avrSWAP, LocalVar, CntrPar, objInst, PerfData, RootNa READ( Un, IOSTAT=ErrStat) LocalVar%PC_RefSpd_SS READ( Un, IOSTAT=ErrStat) LocalVar%PC_RefSpd_PRC READ( Un, IOSTAT=ErrStat) LocalVar%RotSpeedF - READ( Un, IOSTAT=ErrStat) LocalVar%PC_RefSpd READ( Un, IOSTAT=ErrStat) LocalVar%GenSpeedF READ( Un, IOSTAT=ErrStat) LocalVar%GenTq READ( Un, IOSTAT=ErrStat) LocalVar%GenTqMeas @@ -947,4 +945,4 @@ SUBROUTINE Debug(LocalVar, CntrPar, DebugVar, ErrVar, avrSWAP, RootName, size_av ENDIF END SUBROUTINE Debug -END MODULE ROSCO_IO \ No newline at end of file +END MODULE ROSCO_IO diff --git a/rosco/controller/src/ROSCO_Types.f90 b/rosco/controller/src/ROSCO_Types.f90 index 6d9d80a4..fbf73281 100644 --- a/rosco/controller/src/ROSCO_Types.f90 +++ b/rosco/controller/src/ROSCO_Types.f90 @@ -79,6 +79,11 @@ MODULE ROSCO_Types REAL(DbKi), DIMENSION(:), ALLOCATABLE :: VS_KI ! Integral gain for generator PI torque controller, used in the transitional 2.5 region REAL(DbKi) :: VS_TSRopt ! Power-maximizing region 2 tip-speed ratio [rad] REAL(DbKi) :: VS_PwrFiltF ! Cut-off frequency of filter on generator power for power-based tsr tracking control + INTEGER(IntKi) :: FBP_RefMode ! Fixed blade pitch reference interpolation mode (0 for WSE, 1 for torque feedback) + INTEGER(IntKi) :: FBP_n ! Amount of fixed blade pitch operating schedule table entries + REAL(DbKi), DIMENSION(:), ALLOCATABLE :: FBP_U ! FBP Operating-schedule table - Wind speeds + REAL(DbKi), DIMENSION(:), ALLOCATABLE :: FBP_Omega ! FBP Operating-schedule table - Generator speeds + REAL(DbKi), DIMENSION(:), ALLOCATABLE :: FBP_Tau ! FBP Operating-schedule table - Generator torques INTEGER(IntKi) :: SS_Mode ! Setpoint Smoother mode {0 - no setpoint smoothing, 1 - introduce setpoint smoothing} REAL(DbKi) :: SS_VSGain ! Variable speed torque controller setpoint smoother gain, [-]. REAL(DbKi) :: SS_PCGain ! Collective pitch controller setpoint smoother gain, [-]. @@ -284,7 +289,6 @@ MODULE ROSCO_Types REAL(DbKi) :: PC_RefSpd_SS ! Generator speed set point of pitch controller after setpoint smoothing [rad/s] REAL(DbKi) :: PC_RefSpd_PRC ! Generator speed set point of pitch controller after power ref control [rad/s] REAL(DbKi) :: RotSpeedF ! Filtered LSS (generator) speed [rad/s]. - REAL(DbKi) :: PC_RefSpd ! Generator speed set point of pitch controller [rad/s] REAL(DbKi) :: GenSpeedF ! Filtered HSS (generator) speed [rad/s]. REAL(DbKi) :: GenTq ! Electrical generator torque, [Nm]. REAL(DbKi) :: GenTqMeas ! Measured generator torque [Nm] @@ -449,4 +453,4 @@ MODULE ROSCO_Types REAL(ReKi), DIMENSION(:), ALLOCATABLE :: avrSWAP ! The swap array- used to pass data to and from the DLL controller [see Bladed DLL documentation] END TYPE ExtControlType -END MODULE ROSCO_Types \ No newline at end of file +END MODULE ROSCO_Types diff --git a/rosco/controller/src/ReadSetParameters.f90 b/rosco/controller/src/ReadSetParameters.f90 index 131b6581..619e1dd9 100644 --- a/rosco/controller/src/ReadSetParameters.f90 +++ b/rosco/controller/src/ReadSetParameters.f90 @@ -221,22 +221,27 @@ SUBROUTINE SetParameters(avrSWAP, accINFILE, size_avcMSG, CntrPar, LocalVar, obj ! Setpoint Smoother initialization to zero LocalVar%SS_DelOmegaF = 0 - ! Generator Torque at K omega^2 or rated - IF (LocalVar%GenSpeed > 0.98 * CntrPar%PC_RefSpd) THEN - LocalVar%GenTq = CntrPar%VS_RtTq + IF (CntrPar%VS_ControlMode < 4) THEN + ! Generator Torque at K omega^2 or rated + IF (LocalVar%GenSpeed > 0.98 * CntrPar%PC_RefSpd) THEN + LocalVar%GenTq = CntrPar%VS_RtTq + ELSE + LocalVar%GenTq = min(CntrPar%VS_RtTq, CntrPar%VS_Rgn2K*LocalVar%GenSpeed*LocalVar%GenSpeed) + ENDIF ELSE - LocalVar%GenTq = min(CntrPar%VS_RtTq, CntrPar%VS_Rgn2K*LocalVar%GenSpeed*LocalVar%GenSpeed) - ENDIF - LocalVar%VS_LastGenTrq = LocalVar%GenTq + ! Set torque initial condition based on operating schedule at current wind speed + LocalVar%GenTq = interp1d(CntrPar%FBP_U, CntrPar%FBP_Tau, LocalVar%HorWindV, ErrVar) + ENDIF + LocalVar%VS_LastGenTrq = LocalVar%GenTq LocalVar%VS_MaxTq = CntrPar%VS_MaxTq LocalVar%VS_GenPwr = LocalVar%GenTq * LocalVar%GenSpeed - + ! Initialize variables LocalVar%CC_DesiredL = 0 LocalVar%CC_ActuatedL = 0 LocalVar%CC_ActuatedDL = 0 LocalVar%StC_Input = 0 - + LocalVar%ZMQ_YawOffset = 0 LocalVar%ZMQ_PitOffset = 0 LocalVar%ZMQ_ID = CntrPar%ZMQ_ID @@ -431,7 +436,15 @@ SUBROUTINE ReadControlParameterFileSub(CntrPar, LocalVar, accINFILE, accINFILE_s CALL ParseAry( FileLines, 'VS_KP', CntrPar%VS_KP, CntrPar%VS_n, accINFILE(1), ErrVar, .FALSE., UnEc) CALL ParseAry( FileLines, 'VS_KI', CntrPar%VS_KI, CntrPar%VS_n, accINFILE(1), ErrVar, .FALSE., UnEc) CALL ParseInput(FileLines, 'VS_TSRopt', CntrPar%VS_TSRopt, accINFILE(1), ErrVar, CntrPar%VS_ControlMode < 2, UnEc) - CALL ParseInput(FileLines, 'VS_PwrFiltF', CntrPar%VS_PwrFiltF, accINFILE(1), ErrVar, CntrPar%VS_ControlMode .NE. 3, UnEc) + CALL ParseInput(FileLines, 'VS_PwrFiltF', CntrPar%VS_PwrFiltF, accINFILE(1), ErrVar, CntrPar%VS_ControlMode < 3, UnEc) + IF (ErrVar%aviFAIL < 0) RETURN + + !------------ Fixed-Pitch Region 3 Control ------------ + CALL ParseInput(FileLines, 'FBP_RefMode', CntrPar%FBP_RefMode, accINFILE(1), ErrVar, CntrPar%VS_ControlMode < 4, UnEc) + CALL ParseInput(FileLines, 'FBP_n', CntrPar%FBP_n, accINFILE(1), ErrVar, CntrPar%VS_ControlMode < 4, UnEc) + CALL ParseAry( FileLines, 'FBP_U', CntrPar%FBP_U, CntrPar%FBP_n, accINFILE(1), ErrVar, CntrPar%VS_ControlMode < 4, UnEc) + CALL ParseAry( FileLines, 'FBP_Omega', CntrPar%FBP_Omega, CntrPar%FBP_n, accINFILE(1), ErrVar, CntrPar%VS_ControlMode < 4, UnEc) + CALL ParseAry( FileLines, 'FBP_Tau', CntrPar%FBP_Tau, CntrPar%FBP_n, accINFILE(1), ErrVar, CntrPar%VS_ControlMode < 4, UnEc) IF (ErrVar%aviFAIL < 0) RETURN !------- Setpoint Smoother -------------------------------- @@ -888,7 +901,7 @@ SUBROUTINE CheckInputs(LocalVar, CntrPar, avrSWAP, ErrVar, size_avcMSG) ENDIF ! VS_ControlMode - IF ((CntrPar%VS_ControlMode < 0) .OR. (CntrPar%VS_ControlMode > 3)) THEN + IF ((CntrPar%VS_ControlMode < 0) .OR. (CntrPar%VS_ControlMode > 4)) THEN ErrVar%aviFAIL = -1 ErrVar%ErrMsg = 'VS_ControlMode must be 0, 1, 2, or 3.' ENDIF @@ -1044,7 +1057,7 @@ SUBROUTINE CheckInputs(LocalVar, CntrPar, avrSWAP, ErrVar, size_avcMSG) ENDIF ! PC_GS_angles - IF (.NOT. NonDecreasing(CntrPar%PC_GS_angles)) THEN + IF (CntrPar%PC_ControlMode .NE. 0 .AND. .NOT. NonDecreasing(CntrPar%PC_GS_angles)) THEN ErrVar%aviFAIL = -1 ErrVar%ErrMsg = 'PC_GS_angles must be non-decreasing' ENDIF diff --git a/rosco/toolbox/controller.py b/rosco/toolbox/controller.py index 9b78cce5..2d0e3a67 100644 --- a/rosco/toolbox/controller.py +++ b/rosco/toolbox/controller.py @@ -100,6 +100,19 @@ def __init__(self, controller_params): self.ZMQ_UpdatePeriod = controller_params['ZMQ_UpdatePeriod'] # Optional parameters without defaults + if self.VS_ControlMode == 4: + try: + self.fbp_ref_mode = controller_params['FBP_ref_mode'] + self.fbp_P_mode = controller_params['FBP_P_mode'] + self.fbp_U = controller_params['FBP_U'] # Should we set this default based on rated speed? + self.fbp_P = controller_params['FBP_P'] + except: + raise Exception( + 'rosco.toolbox:controller: FBP options (FBP_ref_mode) must be set if VS_ControlMode == 4') + else: + self.fbp_ref_mode = 0 + + if self.Flp_Mode > 0: try: self.flp_kp_norm = controller_params['flp_kp_norm'] @@ -215,20 +228,49 @@ def tune_controller(self, turbine): v_above_rated = np.linspace(turbine.v_rated,turbine.v_max, num=self.PC_GS_n+1) # above rated v = np.concatenate((v_below_rated, v_above_rated)) - # separate TSRs by operations regions - TSR_below_rated = [min(turbine.TSR_operational, rated_rotor_speed*R/v) for v in v_below_rated] # below rated - TSR_above_rated = rated_rotor_speed*R/v_above_rated # above rated - TSR_op = np.concatenate((TSR_below_rated, TSR_above_rated)) # operational TSRs + if self.VS_ControlMode < 4: + # separate TSRs by operations regions + TSR_below_rated = [min(turbine.TSR_operational, rated_rotor_speed*R/v) for v in v_below_rated] # below rated + TSR_above_rated = rated_rotor_speed*R/v_above_rated # above rated + TSR_op = np.concatenate((TSR_below_rated, TSR_above_rated)) # operational TSRs + + # Find expected operational Cp values + Cp_above_rated = turbine.Cp.interp_surface(0,TSR_above_rated[0]) # Cp during rated operation (not optimal). Assumes cut-in bld pitch to be 0 + Cp_op_br = np.ones(len(v_below_rated)) * turbine.Cp.max # below rated + Cp_op_ar = Cp_above_rated * (TSR_above_rated/TSR_rated)**3 # above rated + Cp_op = np.concatenate((Cp_op_br, Cp_op_ar)) # operational CPs to linearize around + + else: + # Check if blade pitch control disabled (may be implemented to work concurrently in the future) + if self.PC_ControlMode != 0: + raise Exception("PC_ControlMode must be 0 when VS_ControlMode == 4") + if self.VS_ConstPower != 0: + raise Exception("VS_ConstPower must be 0 when VS_ControlMode == 4") + + # Begin with user-defined power curve + f_P_user_defined = interpolate.interp1d(self.fbp_U, self.fbp_P, fill_value=(self.fbp_P[0], self.fbp_P[-1]), bounds_error=False) + P_user_defined = f_P_user_defined(v) + if self.fbp_P_mode == 0: + P_user_defined *= turbine.rated_power + P_max = 0.5 * turbine.rho * np.pi*turbine.rotor_radius**2 * turbine.Cp.max * v**3 * turbine.GBoxEff/100 * turbine.GenEff/100 + P_op = np.min([P_user_defined, P_max], axis=0) + Cp_op = P_op / P_max * turbine.Cp.max + Cp_op_br = Cp_op[:len(v_below_rated)] + Cp_op_ar = Cp_op[len(v_below_rated):] + + # Identify TSR matching the Cp values + Cp_FBP = np.ndarray.flatten(turbine.Cp.interp_surface(0, turbine.TSR_initial)) # all Cp values for fine blade pitch (assumed 0) + Cp_maxidx = Cp_FBP.argmax() + Cp_op = np.clip(Cp_op, np.min(Cp_FBP[Cp_maxidx:]), np.max(Cp_FBP[Cp_maxidx:])) # saturate Cp values to be on Cp surface # Find maximum Cp value for this TSR + f_cp_TSR = interpolate.interp1d(Cp_FBP[:Cp_maxidx+1], turbine.TSR_initial[:Cp_maxidx+1]) # interpolate function for Cp(tsr) values + TSR_op = f_cp_TSR(Cp_op) + TSR_op_br = TSR_op[:len(v_below_rated)] + TSR_op_ar = TSR_op[len(v_below_rated):] - # Find expected operational Cp values - Cp_above_rated = turbine.Cp.interp_surface(0,TSR_above_rated[0]) # Cp during rated operation (not optimal). Assumes cut-in bld pitch to be 0 - Cp_op_br = np.ones(len(v_below_rated)) * turbine.Cp.max # below rated - Cp_op_ar = Cp_above_rated * (TSR_above_rated/TSR_rated)**3 # above rated - Cp_op = np.concatenate((Cp_op_br, Cp_op_ar)) # operational CPs to linearize around - pitch_initial_rad = turbine.pitch_initial_rad - TSR_initial = turbine.TSR_initial # initialize variables + pitch_initial_rad = turbine.pitch_initial_rad + TSR_initial = turbine.TSR_initial pitch_op = np.empty(len(TSR_op)) dCp_beta = np.empty(len(TSR_op)) dCp_TSR = np.empty(len(TSR_op)) @@ -239,41 +281,62 @@ def tune_controller(self, turbine): # ------------- Find Linearized State "Matrices" ------------- # # At each operating point for i in range(len(TSR_op)): - # Find pitch angle as a function of expected operating CP for each TSR operating point - Cp_TSR = np.ndarray.flatten(turbine.Cp.interp_surface(turbine.pitch_initial_rad, TSR_op[i])) # all Cp values for a given tsr - Cp_maxidx = Cp_TSR.argmax() - Cp_op[i] = np.clip(Cp_op[i], np.min(Cp_TSR[Cp_maxidx:]), np.max(Cp_TSR[Cp_maxidx:])) # saturate Cp values to be on Cp surface # Find maximum Cp value for this TSR - f_cp_pitch = interpolate.interp1d(Cp_TSR[Cp_maxidx:],pitch_initial_rad[Cp_maxidx:]) # interpolate function for Cp(tsr) values - - # expected operational blade pitch values. Saturates by min_pitch if it exists - if v[i] <= turbine.v_rated and isinstance(self.min_pitch, float): # Below rated & defined min_pitch - pitch_op[i] = min(self.min_pitch, f_cp_pitch(Cp_op[i])) - elif isinstance(self.min_pitch, float): # above rated & defined min_pitch - pitch_op[i] = max(self.min_pitch, f_cp_pitch(Cp_op[i])) - else: # no defined minimum pitch schedule - pitch_op[i] = f_cp_pitch(Cp_op[i]) + + if self.VS_ControlMode < 4: + # Find pitch angle as a function of expected operating CP for each TSR operating point + Cp_TSR = np.ndarray.flatten(turbine.Cp.interp_surface(turbine.pitch_initial_rad, TSR_op[i])) # all Cp values for a given tsr + Cp_maxidx = Cp_TSR.argmax() + Cp_op[i] = np.clip(Cp_op[i], np.min(Cp_TSR[Cp_maxidx:]), np.max(Cp_TSR[Cp_maxidx:])) # saturate Cp values to be on Cp surface # Find maximum Cp value for this TSR + f_cp_pitch = interpolate.interp1d(Cp_TSR[Cp_maxidx:],pitch_initial_rad[Cp_maxidx:]) # interpolate function for Cp(tsr) values + + # expected operational blade pitch values. Saturates by min_pitch if it exists + if v[i] <= turbine.v_rated and isinstance(self.min_pitch, float): # Below rated & defined min_pitch + pitch_op[i] = min(self.min_pitch, f_cp_pitch(Cp_op[i])) + elif isinstance(self.min_pitch, float): # above rated & defined min_pitch + pitch_op[i] = max(self.min_pitch, f_cp_pitch(Cp_op[i])) + else: # no defined minimum pitch schedule + pitch_op[i] = f_cp_pitch(Cp_op[i]) + else: + if isinstance(self.min_pitch, float): + pitch_op[i] = self.min_pitch + else: + # Take optimal pitch from Cp surface + pitch_op[i] = turbine.pitch_initial_rad[turbine.Cp.max_ind[1]] # Calculate Cp Surface gradients dCp_beta[i], dCp_TSR[i] = turbine.Cp.interp_gradient(pitch_op[i],TSR_op[i]) dCt_beta[i], dCt_TSR[i] = turbine.Ct.interp_gradient(pitch_op[i],TSR_op[i]) - + # Thrust Ct_TSR = np.ndarray.flatten(turbine.Ct.interp_surface(turbine.pitch_initial_rad, TSR_op[i])) # all Cp values for a given tsr f_ct = interpolate.interp1d(pitch_initial_rad,Ct_TSR) Ct_op[i] = f_ct(pitch_op[i]) Ct_op[i] = np.clip(Ct_op[i], np.min(Ct_TSR), np.max(Ct_TSR)) # saturate Ct values to be on Ct surface - # Define minimum pitch saturation to be at Cp-maximizing pitch angle if not specifically defined if not isinstance(self.min_pitch, float): self.min_pitch = pitch_op[0] + # Compute generator speed and torque operating schedule + P_op = 0.5 * turbine.rho * np.pi*turbine.rotor_radius**2 * Cp_op * v**3 * turbine.GBoxEff/100 * turbine.GenEff/100 + if self.VS_ControlMode < 4: + omega_op = np.maximum(np.minimum(turbine.rated_rotor_speed, TSR_op*v/R), self.vs_minspd) + else: + omega_op = np.maximum(TSR_op*v/R, self.vs_minspd) + omega_gen_op = omega_op * Ng + + tau_op = P_op / omega_gen_op / (turbine.GBoxEff/100 * turbine.GenEff/100) + # Check if maximum torque leaves enough leeway to control the system + if np.max(tau_op) > turbine.max_torque: # turbine.max_torque * 1.2 + print('WARNING: Torque operating schedule is above maximum generator torque and may not be realizable within saturation limits.') + + # Full Cx surface gradients dCp_dbeta = dCp_beta/np.diff(pitch_initial_rad)[0] dCp_dTSR = dCp_TSR/np.diff(TSR_initial)[0] dCt_dbeta = dCt_beta/np.diff(pitch_initial_rad)[0] dCt_dTSR = dCt_TSR/np.diff(TSR_initial)[0] - + # Linearized system derivatives, equations from https://wes.copernicus.org/articles/7/53/2022/wes-7-53-2022.pdf dtau_dbeta = Ng/2*rho*Ar*R*(1/TSR_op)*dCp_dbeta*v**2 # (26) dtau_dlambda = Ng/2*rho*Ar*R*v**2*(1/(TSR_op**2))*(dCp_dTSR*TSR_op - Cp_op) # (7) @@ -322,7 +385,10 @@ def tune_controller(self, turbine): self.pc_gain_schedule = ControllerTypes() self.pc_gain_schedule.second_order_PI(self.zeta_pc_U, self.omega_pc_U,A_pc,B_beta[-len(v_above_rated)+1:],linearize=True,v=v_above_rated[1:]) self.vs_gain_schedule = ControllerTypes() - self.vs_gain_schedule.second_order_PI(self.zeta_vs, self.omega_vs,A_vs,B_tau[0:len(v_below_rated)],linearize=False,v=v_below_rated) + if self.VS_ControlMode < 4: + self.vs_gain_schedule.second_order_PI(self.zeta_vs, self.omega_vs,A_vs,B_tau[0:len(v_below_rated)],linearize=False,v=v_below_rated) + else: + self.vs_gain_schedule.second_order_PI(self.zeta_vs, self.omega_vs,A,B_tau,linearize=False,v=v) # -- Find K for Komega_g^2 -- self.vs_rgn2K = (pi*rho*R**5.0 * turbine.Cp.max * turbine.GBoxEff/100 * turbine.GenEff/100) / \ @@ -361,7 +427,10 @@ def tune_controller(self, turbine): self.B_beta = B_beta self.B_tau = B_tau self.B_wind = B_wind - self.omega_op = np.maximum(np.minimum(turbine.rated_rotor_speed, TSR_op*v/R), self.vs_minspd) + self.omega_op = omega_op + self.omega_gen_op = omega_gen_op + self.tau_op = tau_op + self.power_op = P_op self.Pi_omega = Pi_omega self.Pi_beta = Pi_beta self.Pi_wind = Pi_wind diff --git a/rosco/toolbox/inputs/toolbox_schema.yaml b/rosco/toolbox/inputs/toolbox_schema.yaml index 44573ae1..5ddfe7eb 100644 --- a/rosco/toolbox/inputs/toolbox_schema.yaml +++ b/rosco/toolbox/inputs/toolbox_schema.yaml @@ -128,7 +128,7 @@ properties: VS_ControlMode: type: number minimum: 0 - maximum: 3 + maximum: 4 default: 2 description: Generator torque control mode in above rated conditions (0- no torque control, 1- k*omega^2 with PI transitions, 2- WSE TSR Tracking, 3- Power-based TSR Tracking) VS_ConstPower: @@ -434,6 +434,34 @@ properties: description: Factor on VS_Rgn2K to increase/decrease optimal torque control gain, default is 1. Sometimes environmental conditions or differences in BEM solvers necessitate this change. default: 1 minimum: 0 + FBP_ref_mode: + type: number + description: Method of identifying operating point reference during operation (0- Use WSE, 1- Use filtered torque signal) + minimum: 0 + maximum: 1 + FBP_P_mode: + type: number + description: Interpretation mode for P_FBP (0- scale relative to rated power, 1- absolute power) + default: 0 + minimum: 0 + maximum: 1 + FBP_U: + type: array + description: List of wind speeds to schedule user-defined power curve for fixed blade pitch (FBP) control in Region 3 + unit: m/s + items: + type: number + minimum: 0 + uniqueItems: True + default: [12] + FBP_P: + type: [array,number] + description: List of points defining power curve for fixed blade pitch (FBP) control in Region 3, relative or absolute based on FBP_mode + unit: none + items: + type: number + minimum: 0 + default: [1.0] filter_params: type: object @@ -570,8 +598,8 @@ properties: VS_ControlMode: type: number minimum: 0 - maximum: 3 - description: Generator torque control mode in above rated conditions (0- no torque control, 1- k*omega^2 with PI transitions, 2- WSE TSR Tracking, 3- Power-based TSR Tracking) + maximum: 4 + description: Generator torque control mode in above rated conditions (0- no torque control, 1- k*omega^2 with PI transitions, 2- WSE TSR Tracking, 3- Power-based TSR Tracking, 4- Torque-based TSR tracking in Region 2 + torque control with user-defined power curve in Region 3) VS_ConstPower: type: number minimum: 0 diff --git a/rosco/toolbox/utilities.py b/rosco/toolbox/utilities.py index c9332720..78b8f0e6 100644 --- a/rosco/toolbox/utilities.py +++ b/rosco/toolbox/utilities.py @@ -182,6 +182,13 @@ def write_DISCON(turbine, controller, param_file='DISCON.IN', txt_filename='Cp_C file.write('{:<13.2f} ! VS_TSRopt - {}\n'.format(float(rosco_vt['VS_TSRopt']),input_descriptions['VS_TSRopt'])) file.write('{:<014.5f} ! VS_PwrFiltF - {}\n'.format(float(rosco_vt['VS_PwrFiltF']),input_descriptions['VS_PwrFiltF'])) file.write('\n') + file.write('!------- FIXED PITCH REGION 3 TORQUE CONTROL ------------------------------------------------\n') + file.write('{:<11d} ! FBP_RefMode - Reference control mode (0 - Use wind speed estimator, 1 - Use torque feedback)\n'.format(int(rosco_vt['FBP_RefMode']))) + file.write('{:<11d} ! FBP_n - Number of gain-scheduling table entries\n'.format(int(rosco_vt['FBP_n']))) + file.write('{} ! FBP_U - Operating schedule table: Wind speeds [m/s].\n'.format(''.join('{:<4.6f} '.format(rosco_vt['FBP_U'][i]) for i in range(len(rosco_vt['FBP_U']))))) + file.write('{} ! FBP_Omega - Operating schedule table: Generator speeds [rad/s].\n'.format(''.join('{:<4.6f} '.format(rosco_vt['FBP_Omega'][i]) for i in range(len(rosco_vt['FBP_Omega']))))) + file.write('{} ! FBP_Tau - Operating schedule table: Generator torques [N m].\n'.format(''.join('{:<4.6f} '.format(rosco_vt['FBP_Tau'][i]) for i in range(len(rosco_vt['FBP_Tau']))))) + file.write('\n') file.write('!------- SETPOINT SMOOTHER ---------------------------------------------\n') file.write('{:<13.5f} ! SS_VSGain - Variable speed torque controller setpoint smoother gain, [-].\n'.format(rosco_vt['SS_VSGain'])) file.write('{:<13.5f} ! SS_PCGain - Collective pitch controller setpoint smoother gain, [-].\n'.format(rosco_vt['SS_PCGain'])) @@ -555,6 +562,12 @@ def DISCON_dict(turbine, controller, txt_filename=None): DISCON_dict['VS_KP'] = controller.vs_gain_schedule.Kp[-1] DISCON_dict['VS_KI'] = controller.vs_gain_schedule.Ki[-1] DISCON_dict['VS_TSRopt'] = turbine.TSR_operational + # ------- FIXED BLADE PITCH TORQUE CONTROL ------- + DISCON_dict['FBP_RefMode'] = controller.fbp_ref_mode + DISCON_dict['FBP_n'] = len(controller.v) + DISCON_dict['FBP_U'] = controller.v + DISCON_dict['FBP_Omega'] = controller.omega_gen_op + DISCON_dict['FBP_Tau'] = controller.tau_op # ------- SETPOINT SMOOTHER ------- DISCON_dict['SS_VSGain'] = controller.ss_vsgain DISCON_dict['SS_PCGain'] = controller.ss_pcgain From 748d9750e629c64af421e8f54a2c7b5bd02ebc9a Mon Sep 17 00:00:00 2001 From: dzalkind Date: Fri, 10 May 2024 10:23:30 -0600 Subject: [PATCH 139/224] Remove extra test_cases --- Test_Cases/MHK_RM1/Airfoils/NACA6_0240.dat | 560 - .../MHK_RM1/Airfoils/NACA6_0240_coords.txt | 47 - Test_Cases/MHK_RM1/Airfoils/NACA6_0247.dat | 560 - .../MHK_RM1/Airfoils/NACA6_0247_coords.txt | 47 - Test_Cases/MHK_RM1/Airfoils/NACA6_0259.dat | 560 - .../MHK_RM1/Airfoils/NACA6_0259_coords.txt | 47 - Test_Cases/MHK_RM1/Airfoils/NACA6_0276.dat | 560 - .../MHK_RM1/Airfoils/NACA6_0276_coords.txt | 47 - Test_Cases/MHK_RM1/Airfoils/NACA6_0329.dat | 560 - .../MHK_RM1/Airfoils/NACA6_0329_coords.txt | 47 - Test_Cases/MHK_RM1/Airfoils/NACA6_0444.dat | 560 - .../MHK_RM1/Airfoils/NACA6_0444_coords.txt | 47 - Test_Cases/MHK_RM1/Airfoils/NACA6_0629.dat | 560 - .../MHK_RM1/Airfoils/NACA6_0629_coords.txt | 47 - Test_Cases/MHK_RM1/Airfoils/NACA6_0864.dat | 560 - .../MHK_RM1/Airfoils/NACA6_0864_coords.txt | 47 - Test_Cases/MHK_RM1/Airfoils/NACA6_1000.dat | 108 - .../MHK_RM1/Airfoils/NACA6_1000_coords.txt | 47 - .../MHK_RM1/MHK_RM1_AeroDyn15_Blade.dat | 38 - Test_Cases/MHK_RM1/MHK_RM1_Cp_Ct_Cq.txt | 99 - Test_Cases/MHK_RM1/MHK_RM1_DISCON.IN | 192 - .../MHK_RM1/MHK_RM1_ElastoDyn_Blade.dat | 107 - .../MHK_RM1/MHK_RM1_ElastoDyn_Tower.dat | 52 - Test_Cases/MHK_RM1/MHK_RM1_Floating.1 | 4220 ------- Test_Cases/MHK_RM1/MHK_RM1_Floating.3 | 10080 ---------------- Test_Cases/MHK_RM1/MHK_RM1_Floating.fst | 71 - Test_Cases/MHK_RM1/MHK_RM1_Floating.hst | 36 - .../MHK_RM1/MHK_RM1_Floating_AeroDyn15.dat | 123 - .../MHK_RM1/MHK_RM1_Floating_ElastoDyn.dat | 134 - .../MHK_RM1/MHK_RM1_Floating_HydroDyn.dat | 207 - .../MHK_RM1/MHK_RM1_Floating_InflowWind.dat | 69 - .../MHK_RM1/MHK_RM1_Floating_MoorDyn.dat | 58 - Test_Cases/MHK_RM1/MHK_RM1_ServoDyn.dat | 111 - 33 files changed, 20608 deletions(-) delete mode 100644 Test_Cases/MHK_RM1/Airfoils/NACA6_0240.dat delete mode 100644 Test_Cases/MHK_RM1/Airfoils/NACA6_0240_coords.txt delete mode 100644 Test_Cases/MHK_RM1/Airfoils/NACA6_0247.dat delete mode 100644 Test_Cases/MHK_RM1/Airfoils/NACA6_0247_coords.txt delete mode 100644 Test_Cases/MHK_RM1/Airfoils/NACA6_0259.dat delete mode 100644 Test_Cases/MHK_RM1/Airfoils/NACA6_0259_coords.txt delete mode 100644 Test_Cases/MHK_RM1/Airfoils/NACA6_0276.dat delete mode 100644 Test_Cases/MHK_RM1/Airfoils/NACA6_0276_coords.txt delete mode 100644 Test_Cases/MHK_RM1/Airfoils/NACA6_0329.dat delete mode 100644 Test_Cases/MHK_RM1/Airfoils/NACA6_0329_coords.txt delete mode 100644 Test_Cases/MHK_RM1/Airfoils/NACA6_0444.dat delete mode 100644 Test_Cases/MHK_RM1/Airfoils/NACA6_0444_coords.txt delete mode 100644 Test_Cases/MHK_RM1/Airfoils/NACA6_0629.dat delete mode 100644 Test_Cases/MHK_RM1/Airfoils/NACA6_0629_coords.txt delete mode 100644 Test_Cases/MHK_RM1/Airfoils/NACA6_0864.dat delete mode 100644 Test_Cases/MHK_RM1/Airfoils/NACA6_0864_coords.txt delete mode 100644 Test_Cases/MHK_RM1/Airfoils/NACA6_1000.dat delete mode 100644 Test_Cases/MHK_RM1/Airfoils/NACA6_1000_coords.txt delete mode 100644 Test_Cases/MHK_RM1/MHK_RM1_AeroDyn15_Blade.dat delete mode 100644 Test_Cases/MHK_RM1/MHK_RM1_Cp_Ct_Cq.txt delete mode 100644 Test_Cases/MHK_RM1/MHK_RM1_DISCON.IN delete mode 100644 Test_Cases/MHK_RM1/MHK_RM1_ElastoDyn_Blade.dat delete mode 100644 Test_Cases/MHK_RM1/MHK_RM1_ElastoDyn_Tower.dat delete mode 100644 Test_Cases/MHK_RM1/MHK_RM1_Floating.1 delete mode 100644 Test_Cases/MHK_RM1/MHK_RM1_Floating.3 delete mode 100644 Test_Cases/MHK_RM1/MHK_RM1_Floating.fst delete mode 100644 Test_Cases/MHK_RM1/MHK_RM1_Floating.hst delete mode 100644 Test_Cases/MHK_RM1/MHK_RM1_Floating_AeroDyn15.dat delete mode 100644 Test_Cases/MHK_RM1/MHK_RM1_Floating_ElastoDyn.dat delete mode 100644 Test_Cases/MHK_RM1/MHK_RM1_Floating_HydroDyn.dat delete mode 100644 Test_Cases/MHK_RM1/MHK_RM1_Floating_InflowWind.dat delete mode 100644 Test_Cases/MHK_RM1/MHK_RM1_Floating_MoorDyn.dat delete mode 100644 Test_Cases/MHK_RM1/MHK_RM1_ServoDyn.dat diff --git a/Test_Cases/MHK_RM1/Airfoils/NACA6_0240.dat b/Test_Cases/MHK_RM1/Airfoils/NACA6_0240.dat deleted file mode 100644 index 94b36abc..00000000 --- a/Test_Cases/MHK_RM1/Airfoils/NACA6_0240.dat +++ /dev/null @@ -1,560 +0,0 @@ -! ------------ AirfoilInfo v1.01.x Input File ---------------------------------- -! NACA6_0240 airfoil, data based on values used for the design of the RM1 tidal current turbine. -! line -! line -! ------------------------------------------------------------------------------ -"default" InterpOrd ! Interpolation order to use for quasi-steady table lookup {1=linear; 3=cubic spline; "default"} [default=1] - 1.0 NonDimArea ! The non-dimensional area of the airfoil (area/chord^2) (set to 1.0 if unsure or unneeded) -@"NACA6_0240_coords.txt" NumCoords ! The number of coordinates in the airfoil shape file. Set to zero if coordinates not included. -"unused" BL_file ! The file name including the boundary layer characteristics of the profile. Ignored if the aeroacoustic module is not called. - 7 NumTabs ! Number of airfoil tables in this file. -! ------------------------------------------------------------------------------ -! data for table 1 -! ------------------------------------------------------------------------------ - 2.0 Re ! Reynolds number in millions - 0 UserProp ! User property (control) setting -False InclUAdata ! Is unsteady aerodynamics data included in this table? If TRUE, then include 30 UA coefficients below this line -!........................................ -! Table of aerodynamics coefficients - 72 NumAlf ! Number of data lines in the following table -! Alpha Cl Cd Cpmin -! (deg) (-) (-) (-) - -180 0.0000 0.0100 -1 - -170 0.3120 0.0100 -1 - -160 0.6240 0.0706 -1 - -150 0.9360 0.2428 -1 - -140 0.7699 0.4549 -1 - -130 0.6312 0.6818 -1 - -120 0.4861 0.8973 -1 - -110 0.3275 1.0763 -1 - -100 0.1610 1.1983 -1 - -90 0.0000 1.2500 -1 - -80 -0.1610 1.1983 -1 - -70 -0.3275 1.0763 -1 - -60 -0.4861 0.8973 -1 - -50 -0.6312 0.6818 -1 - -40 -0.7699 0.4549 -1 - -30 -0.9360 0.2428 -1 - -20 -0.6782 0.1306 -1 - -10 -0.6006 0.0183 -2.3658 - -9 -0.5703 0.0150 -2.1354 - -8 -0.5401 0.0124 -1.9128 - -7 -0.4863 0.0111 -1.6564 - -6 -0.3911 0.0101 -1.4075 - -5 -0.2829 0.0093 -1.2098 - -4 -0.1699 0.0086 -1.0246 - -3 -0.0547 0.0076 -0.9055 - -2 0.0671 0.0074 -0.9047 - -1 0.1884 0.0073 -0.9888 - 0 0.3092 0.0074 -1.0777 - 1 0.4307 0.0074 -1.1694 - 2 0.5503 0.0076 -1.2608 - 3 0.6677 0.0078 -1.3557 - 4 0.7807 0.0082 -1.4512 - 5 0.8921 0.0086 -1.5561 - 6 0.9830 0.0097 -1.6648 - 7 1.0196 0.0114 -1.7468 - 8 1.0527 0.0137 -1.8733 - 9 1.0932 0.0166 -2.0257 - 10 1.1352 0.0200 -2.1849 - 11 1.1432 0.0259 -2.3027 - 12 1.1730 0.0313 -2.5537 - 13 1.1826 0.0392 -2.7674 - 14 1.2087 0.0464 -3.0323 - 15 1.2272 0.0550 -3.2908 - 16 1.2557 0.0634 -3.5959 - 17 1.2806 0.0725 -3.9100 - 18 1.3037 0.0825 -4.2419 - 19 1.3252 0.0930 -4.5743 - 20 1.3439 0.1043 -4.9173 - 21 1.3613 0.1159 -5.2685 - 22 1.3809 0.1271 -5.6456 - 23 1.3894 0.1401 -5.9876 - 24 1.3961 0.1532 -6.3248 - 25 1.3970 0.1669 -6.6429 - 26 1.3922 0.1814 -6.9151 - 28 1.3673 0.2112 -7.3108 - 29 1.3488 0.2278 -7.4112 - 30 1.3371 0.2428 -7.5348 - 40 1.0999 0.4549 -1 - 50 0.9017 0.6818 -1 - 60 0.6944 0.8973 -1 - 70 0.4678 1.0763 -1 - 80 0.2300 1.1983 -1 - 90 0.0000 1.2500 -1 - 100 -0.1610 1.1983 -1 - 110 -0.3275 1.0763 -1 - 120 -0.4861 0.8973 -1 - 130 -0.6312 0.6818 -1 - 140 -0.7699 0.4549 -1 - 150 -0.9360 0.2428 -1 - 160 -0.6240 0.0706 -1 - 170 -0.3120 0.0100 -1 - 180 0.0000 0.0100 -1 -! ------------------------------------------------------------------------------ -! data for table 2 -! ------------------------------------------------------------------------------ - 4.0 Re ! Reynolds number in millions - 0 UserProp ! User property (control) setting -False InclUAdata ! Is unsteady aerodynamics data included in this table? If TRUE, then include 30 UA coefficients below this line -!........................................ -! Table of aerodynamics coefficients - 69 NumAlf ! Number of data lines in the following table -! Alpha Cl Cd Cpmin -! (deg) (-) (-) (-) - -180 0.0000 0.0100 -1 - -170 0.3270 0.0100 -1 - -160 0.6541 0.0587 -1 - -150 0.9811 0.2318 -1 - -140 0.7974 0.4451 -1 - -130 0.6474 0.6736 -1 - -120 0.4948 0.8909 -1 - -110 0.3312 1.0719 -1 - -100 0.1619 1.1961 -1 - -90 0.0000 1.2500 -1 - -80 -0.1619 1.1961 -1 - -70 -0.3312 1.0719 -1 - -60 -0.4948 0.8909 -1 - -50 -0.6474 0.6736 -1 - -40 -0.7974 0.4451 -1 - -30 -0.9811 0.2318 -1 - -20 -0.7169 0.1237 -1 - -10 -0.6467 0.0156 -2.4629 - -9 -0.5996 0.0132 -2.1912 - -8 -0.5801 0.0111 -1.9816 - -7 -0.4950 0.0100 -1.6720 - -6 -0.3910 0.0092 -1.4078 - -5 -0.2810 0.0085 -1.2080 - -4 -0.1639 0.0080 -1.0184 - -3 -0.0454 0.0073 -0.8991 - -1 0.1982 0.0065 -0.9945 - 0 0.3213 0.0064 -1.0853 - 1 0.4423 0.0066 -1.1768 - 2 0.5645 0.0066 -1.2701 - 5 0.8977 0.0083 -1.5589 - 6 0.9769 0.0097 -1.6615 - 7 1.0311 0.0109 -1.7560 - 9 1.1327 0.0147 -2.0745 - 10 1.1526 0.0188 -2.2074 - 11 1.1873 0.0230 -2.3877 - 12 1.2028 0.0291 -2.6164 - 13 1.2313 0.0351 -2.8768 - 14 1.2601 0.0417 -3.1622 - 15 1.2941 0.0485 -3.4718 - 16 1.3216 0.0564 -3.7920 - 17 1.3498 0.0647 -4.1401 - 18 1.3733 0.0740 -4.4868 - 19 1.3966 0.0838 -4.8430 - 20 1.4115 0.0951 -5.1959 - 21 1.4270 0.1066 -5.5559 - 22 1.4404 0.1187 -5.9301 - 23 1.4449 0.1319 -6.2704 - 24 1.4587 0.1437 -6.6837 - 25 1.4594 0.1573 -7.0264 - 26 1.4601 0.1706 -7.3616 - 27 1.4562 0.1845 -7.6585 - 28 1.4482 0.1989 -7.9116 - 29 1.4181 0.2163 -7.9793 - 30 1.4016 0.2318 -8.1104 - 40 1.1391 0.4451 -1 - 50 0.9249 0.6736 -1 - 60 0.7068 0.8909 -1 - 70 0.4731 1.0719 -1 - 80 0.2313 1.1961 -1 - 90 0.0000 1.2500 -1 - 100 -0.1619 1.1961 -1 - 110 -0.3312 1.0719 -1 - 120 -0.4948 0.8909 -1 - 130 -0.6474 0.6736 -1 - 140 -0.7974 0.4451 -1 - 150 -0.9811 0.2318 -1 - 160 -0.6541 0.0587 -1 - 170 -0.3270 0.0100 -1 - 180 0.0000 0.0100 -1 -! ------------------------------------------------------------------------------ -! data for table 3 -! ------------------------------------------------------------------------------ - 6.0 Re ! Reynolds number in millions - 0 UserProp ! User property (control) setting -False InclUAdata ! Is unsteady aerodynamics data included in this table? If TRUE, then include 30 UA coefficients below this line -!........................................ -! Table of aerodynamics coefficients - 71 NumAlf ! Number of data lines in the following table -! Alpha Cl Cd Cpmin -! (deg) (-) (-) (-) - -180 0.0000 0.0100 -1 - -170 0.3392 0.0100 -1 - -160 0.6784 0.0496 -1 - -150 1.0176 0.2235 -1 - -140 0.8196 0.4377 -1 - -130 0.6605 0.6674 -1 - -120 0.5018 0.8861 -1 - -110 0.3342 1.0686 -1 - -100 0.1627 1.1945 -1 - -90 0.0000 1.2500 -1 - -80 -0.1627 1.1945 -1 - -70 -0.3342 1.0686 -1 - -60 -0.5018 0.8861 -1 - -50 -0.6605 0.6674 -1 - -40 -0.8196 0.4377 -1 - -30 -1.0176 0.2235 -1 - -20 -0.7445 0.1188 -1 - -10 -0.6733 0.0141 -2.5188 - -9 -0.6311 0.0119 -2.2492 - -8 -0.5908 0.0105 -2.0003 - -7 -0.4967 0.0096 -1.6748 - -6 -0.3927 0.0088 -1.4104 - -5 -0.2789 0.0081 -1.2057 - -4 -0.1611 0.0077 -1.0152 - -3 -0.0419 0.0072 -0.8970 - -2 0.0793 0.0064 -0.9117 - -1 0.2025 0.0061 -0.9971 - 0 0.3254 0.0061 -1.0876 - 1 0.4490 0.0061 -1.1811 - 2 0.5682 0.0064 -1.2727 - 4 0.7966 0.0073 -1.4660 - 5 0.8946 0.0084 -1.5586 - 6 0.9801 0.0096 -1.6568 - 7 1.0446 0.0105 -1.7694 - 8 1.1065 0.0117 -1.9317 - 9 1.1411 0.0142 -2.0844 - 10 1.1776 0.0175 -2.2415 - 11 1.2014 0.0220 -2.4154 - 12 1.2315 0.0270 -2.6770 - 13 1.2585 0.0329 -2.9389 - 14 1.2967 0.0387 -3.2543 - 15 1.3269 0.0455 -3.5636 - 16 1.3566 0.0529 -3.8959 - 17 1.3838 0.0611 -4.2519 - 19 1.4278 0.0800 -4.9627 - 20 1.4607 0.0886 -5.3962 - 21 1.4730 0.1002 -5.7535 - 22 1.4807 0.1128 -6.1201 - 23 1.4853 0.1259 -6.4786 - 24 1.4917 0.1388 -6.8685 - 25 1.4944 0.1520 -7.2354 - 26 1.4918 0.1657 -7.5648 - 27 1.4848 0.1800 -7.8540 - 28 1.4765 0.1943 -8.1190 - 29 1.4665 0.2087 -8.3538 - 30 1.4537 0.2235 -8.5446 - 40 1.1708 0.4377 -1 - 50 0.9436 0.6674 -1 - 60 0.7169 0.8861 -1 - 70 0.4775 1.0686 -1 - 80 0.2324 1.1945 -1 - 90 0.0000 1.2500 -1 - 100 -0.1627 1.1945 -1 - 110 -0.3342 1.0686 -1 - 120 -0.5018 0.8861 -1 - 130 -0.6605 0.6674 -1 - 140 -0.8196 0.4377 -1 - 150 -1.0176 0.2235 -1 - 160 -0.6784 0.0496 -1 - 170 -0.3392 0.0100 -1 - 180 0.0000 0.0100 -1 -! ------------------------------------------------------------------------------ -! data for table 4 -! ------------------------------------------------------------------------------ - 8.0 Re ! Reynolds number in millions - 0 UserProp ! User property (control) setting -False InclUAdata ! Is unsteady aerodynamics data included in this table? If TRUE, then include 30 UA coefficients below this line -!........................................ -! Table of aerodynamics coefficients - 62 NumAlf ! Number of data lines in the following table -! Alpha Cl Cd Cpmin -! (deg) (-) (-) (-) - -180 0.0000 0.0100 -1 - -170 0.4065 0.0100 -1 - -160 0.8130 0.0656 -1 - -150 0.9585 0.2382 -1 - -140 0.7836 0.4508 -1 - -130 0.6393 0.6784 -1 - -120 0.4904 0.8946 -1 - -110 0.3293 1.0744 -1 - -100 0.1615 1.1974 -1 - -90 0.0000 1.2500 -1 - -80 -0.1615 1.1974 -1 - -70 -0.3293 1.0744 -1 - -60 -0.4904 0.8946 -1 - -50 -0.6393 0.6784 -1 - -40 -0.7836 0.4508 -1 - -30 -0.9585 0.2382 -1 - -20 -0.8400 0.1070 -1 - -10 -0.6835 0.0136 -2.5481 - -9 -0.6551 0.0110 -2.2945 - -8 -0.5990 0.0100 -2.0149 - -5 -0.2785 0.0079 -1.2051 - -4 -0.1605 0.0074 -1.0146 - -3 -0.0396 0.0070 -0.8858 - -2 0.0815 0.0064 -0.9130 - -1 0.2046 0.0060 -0.9981 - 0 0.3288 0.0059 -1.0898 - 1 0.4505 0.0059 -1.1819 - 2 0.5696 0.0062 -1.2742 - 3 0.6869 0.0066 -1.3692 - 4 0.7958 0.0074 -1.4563 - 6 0.9864 0.0094 -1.6557 - 7 1.0636 0.0101 -1.7862 - 8 1.1217 0.0112 -1.9495 - 9 1.1532 0.0137 -2.0998 - 11 1.2140 0.0213 -2.4399 - 12 1.2522 0.0256 -2.7207 - 13 1.2922 0.0304 -3.0194 - 15 1.3624 0.0423 -3.6630 - 16 1.3922 0.0494 -4.0053 - 17 1.4225 0.0570 -4.3795 - 18 1.4431 0.0660 -4.7296 - 19 1.4663 0.0753 -5.1108 - 20 1.4819 0.0860 -5.4818 - 22 1.4994 0.1103 -6.2066 - 25 1.5113 0.1495 -7.3351 - 26 1.5098 0.1631 -7.6774 - 30 1.3693 0.2382 -6.1797 - 40 1.1195 0.4508 -1 - 50 0.9133 0.6784 -1 - 60 0.7006 0.8946 -1 - 70 0.4705 1.0744 -1 - 80 0.2307 1.1974 -1 - 90 0.0000 1.2500 -1 - 100 -0.1615 1.1974 -1 - 110 -0.3293 1.0744 -1 - 120 -0.4904 0.8946 -1 - 130 -0.6393 0.6784 -1 - 140 -0.7836 0.4508 -1 - 150 -0.9585 0.2382 -1 - 160 -0.8130 0.0656 -1 - 170 -0.4065 0.0100 -1 - 180 0.0000 0.0100 -1 -! ------------------------------------------------------------------------------ -! data for table 5 -! ------------------------------------------------------------------------------ - 10.0 Re ! Reynolds number in millions - 0 UserProp ! User property (control) setting -False InclUAdata ! Is unsteady aerodynamics data included in this table? If TRUE, then include 30 UA coefficients below this line -!........................................ -! Table of aerodynamics coefficients - 67 NumAlf ! Number of data lines in the following table -! Alpha Cl Cd Cpmin -! (deg) (-) (-) (-) - -180 0.0000 0.0100 -1 - -170 0.3508 0.0100 -1 - -160 0.7017 0.0400 -1 - -150 1.0525 0.2147 -1 - -140 0.8408 0.4299 -1 - -130 0.6731 0.6609 -1 - -120 0.5085 0.8810 -1 - -110 0.3371 1.0651 -1 - -100 0.1634 1.1927 -1 - -90 0.0000 1.2500 -1 - -80 -0.1634 1.1927 -1 - -70 -0.3371 1.0651 -1 - -60 -0.5085 0.8810 -1 - -50 -0.6731 0.6609 -1 - -40 -0.8408 0.4299 -1 - -30 -1.0525 0.2147 -1 - -20 -0.7646 0.1141 -1 - -10 -0.6811 0.0135 -2.5243 - -9 -0.6851 0.0106 -2.3544 - -8 -0.6061 0.0097 -2.0276 - -6 -0.3941 0.0082 -1.4146 - -4 -0.1596 0.0072 -1.0137 - -3 -0.0388 0.0069 -0.8871 - -2 0.0830 0.0064 -0.9138 - -1 0.2067 0.0059 -0.9994 - 0 0.3302 0.0058 -1.0906 - 1 0.4512 0.0059 -1.1825 - 2 0.5700 0.0062 -1.2762 - 4 0.7938 0.0075 -1.4517 - 5 0.8930 0.0085 -1.5475 - 6 0.9896 0.0093 -1.6620 - 7 1.0843 0.0099 -1.8045 - 8 1.1285 0.0111 -1.9571 - 9 1.1695 0.0131 -2.1205 - 10 1.1873 0.0169 -2.2387 - 11 1.2351 0.0201 -2.4820 - 12 1.2707 0.0244 -2.7598 - 13 1.3094 0.0292 -3.0601 - 14 1.3479 0.0345 -3.3831 - 16 1.4132 0.0475 -4.0705 - 17 1.4381 0.0554 -4.4302 - 18 1.4631 0.0639 -4.7988 - 19 1.4825 0.0734 -5.1723 - 20 1.4971 0.0841 -5.5428 - 21 1.5047 0.0960 -5.8916 - 24 1.5435 0.1310 -7.1532 - 25 1.5472 0.1439 -7.5449 - 26 1.5476 0.1572 -7.9128 - 27 1.5436 0.1707 -8.246 - 28 1.5338 0.1849 -8.5292 - 29 1.5197 0.1997 -8.7629 - 30 1.5036 0.2147 -8.9588 - 40 1.2012 0.4299 -1 - 50 0.9615 0.6609 -1 - 60 0.7265 0.8810 -1 - 70 0.4816 1.0651 -1 - 80 0.2334 1.1927 -1 - 90 0.0000 1.2500 -1 - 100 -0.1634 1.1927 -1 - 110 -0.3371 1.0651 -1 - 120 -0.5085 0.8810 -1 - 130 -0.6731 0.6609 -1 - 140 -0.8408 0.4299 -1 - 150 -1.0525 0.2147 -1 - 160 -0.7017 0.0400 -1 - 170 -0.3508 0.0100 -1 - 180 0.0000 0.0100 -1 -! ------------------------------------------------------------------------------ -! data for table 6 -! ------------------------------------------------------------------------------ - 12.0 Re ! Reynolds number in millions - 0 UserProp ! User property (control) setting -False InclUAdata ! Is unsteady aerodynamics data included in this table? If TRUE, then include 30 UA coefficients below this line -!........................................ -! Table of aerodynamics coefficients - 68 NumAlf ! Number of data lines in the following table -! Alpha Cl Cd Cpmin -! (deg) (-) (-) (-) - -180 0.0000 0.0100 -1 - -170 0.3695 0.0100 -1 - -160 0.7389 0.0433 -1 - -150 1.0447 0.2176 -1 - -140 0.8361 0.4326 -1 - -130 0.6703 0.6631 -1 - -120 0.5070 0.8827 -1 - -110 0.3365 1.0663 -1 - -100 0.1632 1.1933 -1 - -90 0.0000 1.2500 -1 - -80 -0.1632 1.1933 -1 - -70 -0.3365 1.0663 -1 - -60 -0.5070 0.8827 -1 - -50 -0.6703 0.6631 -1 - -40 -0.8361 0.4326 -1 - -30 -1.0447 0.2176 -1 - -20 -0.7942 0.1103 -1 - -10 -0.6944 0.0129 -2.5538 - -7 -0.5051 0.0088 -1.6890 - -6 -0.3931 0.0082 -1.4033 - -5 -0.2781 0.0075 -1.2051 - -4 -0.1595 0.0071 -1.0133 - -3 -0.0379 0.0068 -0.8899 - -2 0.0846 0.0064 -0.9146 - -1 0.2078 0.0058 -1.0002 - 0 0.3310 0.0058 -1.0908 - 1 0.4519 0.0058 -1.1833 - 2 0.5708 0.0061 -1.2722 - 3 0.6863 0.0066 -1.3593 - 4 0.7943 0.0074 -1.4554 - 5 0.8937 0.0084 -1.5503 - 6 0.9965 0.0090 -1.6685 - 7 1.0919 0.0097 -1.8120 - 8 1.1354 0.0109 -1.9652 - 10 1.2027 0.0161 -2.2646 - 11 1.2478 0.0194 -2.5076 - 12 1.2911 0.0232 -2.8034 - 13 1.3319 0.0276 -3.1135 - 14 1.3618 0.0335 -3.4179 - 15 1.3958 0.0395 -3.7559 - 17 1.4529 0.0540 -4.4787 - 18 1.4764 0.0625 -4.8444 - 19 1.4956 0.0720 -5.2221 - 20 1.5053 0.0831 -5.5750 - 22 1.5459 0.1037 -6.4227 - 23 1.5538 0.1161 -6.8324 - 24 1.5595 0.1287 -7.2408 - 25 1.5622 0.1418 -7.6314 - 26 1.5612 0.1552 -7.9964 - 27 1.5539 0.1691 -8.3139 - 28 1.5433 0.1835 -8.595 - 29 1.5306 0.1980 -8.8443 - 30 1.4925 0.2176 -8.363771554 - 40 1.1944 0.4326 -1 - 50 0.9575 0.6631 -1 - 60 0.7243 0.8827 -1 - 70 0.4807 1.0663 -1 - 80 0.2332 1.1933 -1 - 90 0.0000 1.2500 -1 - 100 -0.1632 1.1933 -1 - 110 -0.3365 1.0663 -1 - 120 -0.5070 0.8827 -1 - 130 -0.6703 0.6631 -1 - 140 -0.8361 0.4326 -1 - 150 -1.0447 0.2176 -1 - 160 -0.7389 0.0433 -1 - 170 -0.3695 0.0100 -1 - 180 0.0000 0.0100 -1 -! ------------------------------------------------------------------------------ -! data for table 7 -! ------------------------------------------------------------------------------ - 14.0 Re ! Reynolds number in millions - 0 UserProp ! User property (control) setting -False InclUAdata ! Is unsteady aerodynamics data included in this table? If TRUE, then include 30 UA coefficients below this line -!........................................ -! Table of aerodynamics coefficients - 64 NumAlf ! Number of data lines in the following table -! Alpha Cl Cd Cpmin -! (deg) (-) (-) (-) - -180 0.0000 0.0100 -1 - -170 0.3561 0.0100 -1 - -160 0.7121 0.0361 -1 - -150 1.0682 0.2110 -1 - -140 0.8504 0.4267 -1 - -130 0.6787 0.6582 -1 - -120 0.5115 0.8789 -1 - -110 0.3384 1.0637 -1 - -100 0.1637 1.1919 -1 - -90 0.0000 1.2500 -1 - -80 -0.1637 1.1919 -1 - -70 -0.3384 1.0637 -1 - -60 -0.5115 0.8789 -1 - -50 -0.6787 0.6582 -1 - -40 -0.8504 0.4267 -1 - -30 -1.0682 0.2110 -1 - -20 -0.7818 0.1117 -1 - -10 -0.7078 0.0124 -2.5820 - -9 -0.6882 0.0105 -2.3471 - -8 -0.6127 0.0092 -2.0403 - -6 -0.3930 0.0081 -1.4009 - -5 -0.2780 0.0074 -1.2048 - -4 -0.1594 0.0069 -1.0132 - -3 -0.0371 0.0067 -0.8903 - -2 0.0857 0.0063 -0.9153 - -1 0.2083 0.0058 -1.0004 - 0 0.3320 0.0057 -1.0916 - 1 0.4508 0.0059 -1.1835 - 2 0.5707 0.0061 -1.2714 - 3 0.6849 0.0067 -1.3575 - 5 0.8968 0.0083 -1.5536 - 6 0.9995 0.0090 -1.6719 - 7 1.0994 0.0095 -1.8194 - 8 1.1396 0.0107 -1.9697 - 11 1.2595 0.0188 -2.5308 - 12 1.3027 0.0225 -2.8278 - 14 1.3829 0.0318 -3.4708 - 16 1.4381 0.0453 -4.1475 - 18 1.4876 0.0613 -4.8828 - 21 1.5477 0.0904 -6.0795 - 22 1.5578 0.1021 -6.4768 - 23 1.5668 0.1143 -6.8990 - 24 1.5715 0.1270 -7.3058 - 25 1.5731 0.1402 -7.6939 - 26 1.5686 0.1540 -8.0423 - 27 1.5615 0.1680 -8.3631 - 28 1.5521 0.1821 -8.6566 - 29 1.5406 0.1964 -8.9183 - 30 1.5260 0.2110 -9.1387 - 40 1.2148 0.4267 -1 - 50 0.9696 0.6582 -1 - 60 0.7308 0.8789 -1 - 70 0.4835 1.0637 -1 - 80 0.2339 1.1919 -1 - 90 0.0000 1.2500 -1 - 100 -0.1637 1.1919 -1 - 110 -0.3384 1.0637 -1 - 120 -0.5115 0.8789 -1 - 130 -0.6787 0.6582 -1 - 140 -0.8504 0.4267 -1 - 150 -1.0682 0.2110 -1 - 160 -0.7121 0.0361 -1 - 170 -0.3561 0.0100 -1 - 180 0.0000 0.0100 -1 \ No newline at end of file diff --git a/Test_Cases/MHK_RM1/Airfoils/NACA6_0240_coords.txt b/Test_Cases/MHK_RM1/Airfoils/NACA6_0240_coords.txt deleted file mode 100644 index 99568655..00000000 --- a/Test_Cases/MHK_RM1/Airfoils/NACA6_0240_coords.txt +++ /dev/null @@ -1,47 +0,0 @@ - 40 NumCoords ! The number of coordinates in the airfoil shape file (including an extra coordinate for airfoil reference). Set to zero if coordinates not included. -! ......... x-y coordinates are next if NumCoords > 0 ............. -! x-y coordinate of airfoil reference -! x/c y/c - 0.25 0 -! coordinates of airfoil shape -! NACA6_0240 Airfoil -! x/c y/c - 0.000000 0.000000 - 0.001740 0.009990 - 0.009990 0.025540 - 0.026840 0.043840 - 0.085380 0.081830 - 0.126020 0.098890 - 0.173070 0.113700 - 0.225630 0.125450 - 0.343100 0.136890 - 0.405650 0.135010 - 0.469030 0.128320 - 0.532130 0.117850 - 0.653880 0.089820 - 0.711010 0.074320 - 0.764750 0.059150 - 0.814500 0.045100 - 0.899560 0.022380 - 0.933650 0.014140 - 0.961390 0.007980 - 0.982280 0.002440 - 0.982280 0.001830 - 0.961390 0.002090 - 0.933510 0.000850 - 0.859090 -0.008040 - 0.813820 -0.016050 - 0.764090 -0.026350 - 0.710600 -0.038510 - 0.594970 -0.065500 - 0.534160 -0.078430 - 0.472340 -0.089680 - 0.410300 -0.098140 - 0.289530 -0.102840 - 0.233070 -0.098960 - 0.180640 -0.091900 - 0.133180 -0.082080 - 0.056790 -0.055970 - 0.029750 -0.040380 - 0.011270 -0.024430 - 0.000000 0.000000 \ No newline at end of file diff --git a/Test_Cases/MHK_RM1/Airfoils/NACA6_0247.dat b/Test_Cases/MHK_RM1/Airfoils/NACA6_0247.dat deleted file mode 100644 index 116e81c9..00000000 --- a/Test_Cases/MHK_RM1/Airfoils/NACA6_0247.dat +++ /dev/null @@ -1,560 +0,0 @@ -! ------------ AirfoilInfo v1.01.x Input File ---------------------------------- -! NACA6_0247 airfoil, data based on values used for the design of the RM1 tidal current turbine. -! line -! line -! ------------------------------------------------------------------------------ -"default" InterpOrd ! Interpolation order to use for quasi-steady table lookup {1=linear; 3=cubic spline; "default"} [default=1] - 1.0 NonDimArea ! The non-dimensional area of the airfoil (area/chord^2) (set to 1.0 if unsure or unneeded) -@"NACA6_0247_coords.txt" NumCoords ! The number of coordinates in the airfoil shape file. Set to zero if coordinates not included. -"unused" BL_file ! The file name including the boundary layer characteristics of the profile. Ignored if the aeroacoustic module is not called. - 7 NumTabs ! Number of airfoil tables in this file. -! ------------------------------------------------------------------------------ -! data for table 1 -! ------------------------------------------------------------------------------ - 2.000 Re ! Reynolds number in millions - 0 UserProp ! User property (control) setting -False InclUAdata ! Is unsteady aerodynamics data included in this table? If TRUE, then include 30 UA coefficients below this line -!........................................ -! Table of aerodynamics coefficients - 72 NumAlf ! Number of data lines in the following table -! Alpha Cl Cd Cpmin -! (deg) (-) (-) (-) - -180.000 0.0000 0.0127 -1.0184 - -170.000 0.3091 0.0127 -1.0184 - -160.000 0.6183 0.0727 -1.0184 - -150.000 0.9274 0.2433 -1.0184 - -140.000 0.7628 0.4535 -1.0184 - -130.000 0.6254 0.6783 -1.0184 - -120.000 0.4816 0.8918 -1.0184 - -110.000 0.3245 1.0691 -1.0184 - -100.000 0.1595 1.1900 -1.0184 - -90.000 0.0000 1.2413 -1.0184 - -80.000 -0.1595 1.1900 -1.0184 - -70.000 -0.3245 1.0691 -1.0184 - -60.000 -0.4816 0.8918 -1.0184 - -50.000 -0.6254 0.6783 -1.0184 - -40.000 -0.7628 0.4535 -1.0184 - -30.000 -0.9274 0.2433 -1.0184 - -20.000 -0.6720 0.1322 -1.0184 - -10.000 -0.5951 0.0209 -2.3716 - -9.000 -0.5650 0.0176 -2.1434 - -8.000 -0.5351 0.0150 -1.9228 - -7.000 -0.4818 0.0138 -1.6688 - -6.000 -0.3875 0.0128 -1.4222 - -5.000 -0.2803 0.0120 -1.2263 - -4.000 -0.1683 0.0113 -1.0428 - -3.000 -0.0542 0.0103 -0.9248 - -2.000 0.0665 0.0101 -0.9240 - -1.000 0.1867 0.0100 -1.0073 - 0.000 0.3064 0.0101 -1.0954 - 1.000 0.4267 0.0101 -1.1863 - 2.000 0.5452 0.0103 -1.2768 - 3.000 0.6616 0.0105 -1.3708 - 4.000 0.7735 0.0109 -1.4655 - 5.000 0.8839 0.0113 -1.5694 - 6.000 0.9739 0.0124 -1.6771 - 7.000 1.0102 0.0141 -1.7583 - 8.000 1.0430 0.0163 -1.8837 - 9.000 1.0831 0.0192 -2.0347 - 10.000 1.1247 0.0226 -2.1924 - 11.000 1.1327 0.0284 -2.3091 - 12.000 1.1622 0.0338 -2.5578 - 13.000 1.1717 0.0416 -2.7695 - 14.000 1.1976 0.0487 -3.0320 - 15.000 1.2159 0.0573 -3.2881 - 16.000 1.2441 0.0656 -3.5904 - 17.000 1.2688 0.0746 -3.9016 - 18.000 1.2917 0.0845 -4.2305 - 19.000 1.3130 0.0949 -4.5598 - 20.000 1.3315 0.1061 -4.8996 - 21.000 1.3488 0.1176 -5.2476 - 22.000 1.3682 0.1287 -5.6212 - 23.000 1.3766 0.1416 -5.9601 - 24.000 1.3832 0.1546 -6.2942 - 25.000 1.3841 0.1681 -6.6093 - 26.000 1.3794 0.1825 -6.8790 - 28.000 1.3547 0.2120 -7.2711 - 29.000 1.3364 0.2285 -7.3706 - 30.000 1.3248 0.2433 -7.4930 - 40.000 1.0898 0.4535 -1.0184 - 50.000 0.8934 0.6783 -1.0184 - 60.000 0.6880 0.8918 -1.0184 - 70.000 0.4635 1.0691 -1.0184 - 80.000 0.2279 1.1900 -1.0184 - 90.000 0.0000 1.2413 -1.0184 - 100.000 -0.1595 1.1900 -1.0184 - 110.000 -0.3245 1.0691 -1.0184 - 120.000 -0.4816 0.8918 -1.0184 - 130.000 -0.6254 0.6783 -1.0184 - 140.000 -0.7628 0.4535 -1.0184 - 150.000 -0.9274 0.2433 -1.0184 - 160.000 -0.6183 0.0727 -1.0184 - 170.000 -0.3091 0.0127 -1.0184 - 180.000 0.0000 0.0127 -1.0184 -! ------------------------------------------------------------------------------ -! data for table 2 -! ------------------------------------------------------------------------------ - 4.000 Re ! Reynolds number in millions - 0 UserProp ! User property (control) setting -False InclUAdata ! Is unsteady aerodynamics data included in this table? If TRUE, then include 30 UA coefficients below this line -!........................................ -! Table of aerodynamics coefficients - 69 NumAlf ! Number of data lines in the following table -! Alpha Cl Cd Cpmin -! (deg) (-) (-) (-) - -180.000 0.0000 0.0161 -1.0184 - -170.000 0.3240 0.0161 -1.0184 - -160.000 0.6481 0.0643 -1.0184 - -150.000 0.9721 0.2358 -1.0184 - -140.000 0.7901 0.4472 -1.0184 - -130.000 0.6414 0.6736 -1.0184 - -120.000 0.4902 0.8889 -1.0184 - -110.000 0.3281 1.0682 -1.0184 - -100.000 0.1604 1.1913 -1.0184 - -90.000 0.0000 1.2447 -1.0184 - -80.000 -0.1604 1.1913 -1.0184 - -70.000 -0.3281 1.0682 -1.0184 - -60.000 -0.4902 0.8889 -1.0184 - -50.000 -0.6414 0.6736 -1.0184 - -40.000 -0.7901 0.4472 -1.0184 - -30.000 -0.9721 0.2358 -1.0184 - -20.000 -0.7103 0.1287 -1.0184 - -10.000 -0.6407 0.0216 -2.4678 - -9.000 -0.5941 0.0192 -2.1986 - -8.000 -0.5748 0.0172 -1.9910 - -7.000 -0.4904 0.0161 -1.6842 - -6.000 -0.3874 0.0153 -1.4225 - -5.000 -0.2784 0.0146 -1.2245 - -4.000 -0.1624 0.0141 -1.0367 - -3.000 -0.0450 0.0134 -0.9185 - -1.000 0.1964 0.0126 -1.0130 - 0.000 0.3183 0.0125 -1.1029 - 1.000 0.4382 0.0127 -1.1936 - 2.000 0.5593 0.0127 -1.2860 - 5.000 0.8894 0.0144 -1.5722 - 6.000 0.9679 0.0158 -1.6738 - 7.000 1.0216 0.0170 -1.7675 - 9.000 1.1223 0.0207 -2.0830 - 10.000 1.1420 0.0248 -2.2147 - 11.000 1.1764 0.0290 -2.3933 - 12.000 1.1917 0.0350 -2.6199 - 13.000 1.2200 0.0409 -2.8779 - 14.000 1.2485 0.0475 -3.1607 - 15.000 1.2822 0.0542 -3.4675 - 16.000 1.3094 0.0621 -3.7847 - 17.000 1.3374 0.0703 -4.1296 - 18.000 1.3607 0.0795 -4.4731 - 19.000 1.3837 0.0892 -4.8260 - 20.000 1.3985 0.1004 -5.1757 - 21.000 1.4139 0.1118 -5.5324 - 22.000 1.4271 0.1238 -5.9031 - 23.000 1.4316 0.1369 -6.2403 - 24.000 1.4453 0.1485 -6.6498 - 25.000 1.4460 0.1620 -6.9893 - 26.000 1.4467 0.1752 -7.3214 - 27.000 1.4428 0.1890 -7.6156 - 28.000 1.4349 0.2032 -7.8664 - 29.000 1.4050 0.2205 -7.9334 - 30.000 1.3887 0.2358 -8.0633 - 40.000 1.1286 0.4472 -1.0184 - 50.000 0.9164 0.6736 -1.0184 - 60.000 0.7003 0.8889 -1.0184 - 70.000 0.4687 1.0682 -1.0184 - 80.000 0.2292 1.1913 -1.0184 - 90.000 0.0000 1.2447 -1.0184 - 100.000 -0.1604 1.1913 -1.0184 - 110.000 -0.3281 1.0682 -1.0184 - 120.000 -0.4902 0.8889 -1.0184 - 130.000 -0.6414 0.6736 -1.0184 - 140.000 -0.7901 0.4472 -1.0184 - 150.000 -0.9721 0.2358 -1.0184 - 160.000 -0.6481 0.0643 -1.0184 - 170.000 -0.3240 0.0161 -1.0184 - 180.000 0.0000 0.0161 -1.0184 -! ------------------------------------------------------------------------------ -! data for table 3 -! ------------------------------------------------------------------------------ - 6.000 Re ! Reynolds number in millions - 0 UserProp ! User property (control) setting -False InclUAdata ! Is unsteady aerodynamics data included in this table? If TRUE, then include 30 UA coefficients below this line -!........................................ -! Table of aerodynamics coefficients - 71 NumAlf ! Number of data lines in the following table -! Alpha Cl Cd Cpmin -! (deg) (-) (-) (-) - -180.000 0.0000 0.0164 -1.0184 - -170.000 0.3361 0.0164 -1.0184 - -160.000 0.6722 0.0556 -1.0184 - -150.000 1.0082 0.2279 -1.0184 - -140.000 0.8121 0.4401 -1.0184 - -130.000 0.6544 0.6677 -1.0184 - -120.000 0.4972 0.8844 -1.0184 - -110.000 0.3311 1.0652 -1.0184 - -100.000 0.1612 1.1899 -1.0184 - -90.000 0.0000 1.2449 -1.0184 - -80.000 -0.1612 1.1899 -1.0184 - -70.000 -0.3311 1.0652 -1.0184 - -60.000 -0.4972 0.8844 -1.0184 - -50.000 -0.6544 0.6677 -1.0184 - -40.000 -0.8121 0.4401 -1.0184 - -30.000 -1.0082 0.2279 -1.0184 - -20.000 -0.7376 0.1242 -1.0184 - -10.000 -0.6671 0.0204 -2.5232 - -9.000 -0.6253 0.0182 -2.2561 - -8.000 -0.5854 0.0169 -2.0095 - -7.000 -0.4921 0.0160 -1.6870 - -6.000 -0.3891 0.0152 -1.4250 - -5.000 -0.2763 0.0145 -1.2222 - -4.000 -0.1596 0.0141 -1.0335 - -3.000 -0.0415 0.0136 -0.9164 - -2.000 0.0786 0.0128 -0.9309 - -1.000 0.2006 0.0125 -1.0155 - 0.000 0.3224 0.0125 -1.1052 - 1.000 0.4449 0.0125 -1.1979 - 2.000 0.5630 0.0128 -1.2886 - 4.000 0.7893 0.0137 -1.4801 - 5.000 0.8864 0.0148 -1.5719 - 6.000 0.9711 0.0160 -1.6692 - 7.000 1.0350 0.0169 -1.7807 - 8.000 1.0963 0.0180 -1.9415 - 9.000 1.1306 0.0205 -2.0928 - 10.000 1.1668 0.0238 -2.2485 - 11.000 1.1903 0.0282 -2.4208 - 12.000 1.2202 0.0332 -2.6800 - 13.000 1.2469 0.0390 -2.9395 - 14.000 1.2848 0.0448 -3.2520 - 15.000 1.3147 0.0515 -3.5584 - 16.000 1.3441 0.0589 -3.8876 - 17.000 1.3711 0.0670 -4.2404 - 19.000 1.4146 0.0857 -4.9446 - 20.000 1.4472 0.0942 -5.3741 - 21.000 1.4594 0.1057 -5.7281 - 22.000 1.4671 0.1182 -6.0914 - 23.000 1.4716 0.1312 -6.4466 - 24.000 1.4780 0.1440 -6.8329 - 25.000 1.4806 0.1570 -7.1964 - 26.000 1.4781 0.1706 -7.5228 - 27.000 1.4711 0.1848 -7.8093 - 28.000 1.4629 0.1990 -8.0719 - 29.000 1.4530 0.2132 -8.3045 - 30.000 1.4403 0.2279 -8.4935 - 40.000 1.1600 0.4401 -1.0184 - 50.000 0.9349 0.6677 -1.0184 - 60.000 0.7103 0.8844 -1.0184 - 70.000 0.4731 1.0652 -1.0184 - 80.000 0.2303 1.1899 -1.0184 - 90.000 0.0000 1.2449 -1.0184 - 100.000 -0.1612 1.1899 -1.0184 - 110.000 -0.3311 1.0652 -1.0184 - 120.000 -0.4972 0.8844 -1.0184 - 130.000 -0.6544 0.6677 -1.0184 - 140.000 -0.8121 0.4401 -1.0184 - 150.000 -1.0082 0.2279 -1.0184 - 160.000 -0.6722 0.0556 -1.0184 - 170.000 -0.3361 0.0164 -1.0184 - 180.000 0.0000 0.0164 -1.0184 -! ------------------------------------------------------------------------------ -! data for table 4 -! ------------------------------------------------------------------------------ - 8.000 Re ! Reynolds number in millions - 0 UserProp ! User property (control) setting -False InclUAdata ! Is unsteady aerodynamics data included in this table? If TRUE, then include 30 UA coefficients below this line -!........................................ -! Table of aerodynamics coefficients - 62 NumAlf ! Number of data lines in the following table -! Alpha Cl Cd Cpmin -! (deg) (-) (-) (-) - -180.000 0.0000 0.0164 -1.0184 - -170.000 0.4028 0.0164 -1.0184 - -160.000 0.8055 0.0714 -1.0184 - -150.000 0.9497 0.2425 -1.0184 - -140.000 0.7764 0.4531 -1.0184 - -130.000 0.6334 0.6786 -1.0184 - -120.000 0.4859 0.8928 -1.0184 - -110.000 0.3263 1.0710 -1.0184 - -100.000 0.1600 1.1928 -1.0184 - -90.000 0.0000 1.2449 -1.0184 - -80.000 -0.1600 1.1928 -1.0184 - -70.000 -0.3263 1.0710 -1.0184 - -60.000 -0.4859 0.8928 -1.0184 - -50.000 -0.6334 0.6786 -1.0184 - -40.000 -0.7764 0.4531 -1.0184 - -30.000 -0.9497 0.2425 -1.0184 - -20.000 -0.8323 0.1125 -1.0184 - -10.000 -0.6772 0.0199 -2.5523 - -9.000 -0.6491 0.0173 -2.3010 - -8.000 -0.5935 0.0164 -2.0240 - -5.000 -0.2759 0.0143 -1.2216 - -4.000 -0.1590 0.0138 -1.0329 - -3.000 -0.0392 0.0134 -0.9053 - -2.000 0.0807 0.0128 -0.9322 - -1.000 0.2027 0.0124 -1.0165 - 0.000 0.3258 0.0123 -1.1074 - 1.000 0.4464 0.0123 -1.1986 - 2.000 0.5644 0.0126 -1.2901 - 3.000 0.6806 0.0130 -1.3842 - 4.000 0.7885 0.0138 -1.4705 - 6.000 0.9773 0.0158 -1.6681 - 7.000 1.0538 0.0165 -1.7974 - 8.000 1.1114 0.0175 -1.9592 - 9.000 1.1426 0.0200 -2.1081 - 11.000 1.2028 0.0276 -2.4451 - 12.000 1.2407 0.0318 -2.7233 - 13.000 1.2803 0.0366 -3.0192 - 15.000 1.3499 0.0484 -3.6569 - 16.000 1.3794 0.0554 -3.9960 - 17.000 1.4094 0.0629 -4.3668 - 18.000 1.4298 0.0718 -4.7137 - 19.000 1.4528 0.0811 -5.0914 - 20.000 1.4683 0.0917 -5.4589 - 22.000 1.4856 0.1157 -6.1771 - 25.000 1.4974 0.1546 -7.2952 - 26.000 1.4959 0.1680 -7.6343 - 30.000 1.3567 0.2425 -6.1504 - 40.000 1.1092 0.4531 -1.0184 - 50.000 0.9049 0.6786 -1.0184 - 60.000 0.6941 0.8928 -1.0184 - 70.000 0.4662 1.0710 -1.0184 - 80.000 0.2286 1.1928 -1.0184 - 90.000 0.0000 1.2449 -1.0184 - 100.000 -0.1600 1.1928 -1.0184 - 110.000 -0.3263 1.0710 -1.0184 - 120.000 -0.4859 0.8928 -1.0184 - 130.000 -0.6334 0.6786 -1.0184 - 140.000 -0.7764 0.4531 -1.0184 - 150.000 -0.9497 0.2425 -1.0184 - 160.000 -0.8055 0.0714 -1.0184 - 170.000 -0.4028 0.0164 -1.0184 - 180.000 0.0000 0.0164 -1.0184 -! ------------------------------------------------------------------------------ -! data for table 5 -! ------------------------------------------------------------------------------ - 10.000 Re ! Reynolds number in millions - 0 UserProp ! User property (control) setting -False InclUAdata ! Is unsteady aerodynamics data included in this table? If TRUE, then include 30 UA coefficients below this line -!........................................ -! Table of aerodynamics coefficients - 67 NumAlf ! Number of data lines in the following table -! Alpha Cl Cd Cpmin -! (deg) (-) (-) (-) - -180.000 0.0000 0.0164 -1.0184 - -170.000 0.3476 0.0164 -1.0184 - -160.000 0.6952 0.0461 -1.0184 - -150.000 1.0428 0.2192 -1.0184 - -140.000 0.8331 0.4324 -1.0184 - -130.000 0.6669 0.6613 -1.0184 - -120.000 0.5038 0.8793 -1.0184 - -110.000 0.3340 1.0617 -1.0184 - -100.000 0.1619 1.1882 -1.0184 - -90.000 0.0000 1.2449 -1.0184 - -80.000 -0.1619 1.1882 -1.0184 - -70.000 -0.3340 1.0617 -1.0184 - -60.000 -0.5038 0.8793 -1.0184 - -50.000 -0.6669 0.6613 -1.0184 - -40.000 -0.8331 0.4324 -1.0184 - -30.000 -1.0428 0.2192 -1.0184 - -20.000 -0.7576 0.1195 -1.0184 - -10.000 -0.6748 0.0198 -2.5287 - -9.000 -0.6788 0.0169 -2.3603 - -8.000 -0.6005 0.0161 -2.0366 - -6.000 -0.3905 0.0146 -1.4292 - -4.000 -0.1581 0.0136 -1.0320 - -3.000 -0.0384 0.0133 -0.9066 - -2.000 0.0822 0.0128 -0.9330 - -1.000 0.2048 0.0123 -1.0178 - 0.000 0.3272 0.0122 -1.1082 - 1.000 0.4470 0.0123 -1.1992 - 2.000 0.5647 0.0126 -1.2921 - 4.000 0.7865 0.0139 -1.4660 - 5.000 0.8848 0.0149 -1.5609 - 6.000 0.9805 0.0157 -1.6743 - 7.000 1.0743 0.0163 -1.8155 - 8.000 1.1181 0.0174 -1.9667 - 9.000 1.1587 0.0194 -2.1286 - 10.000 1.1764 0.0232 -2.2457 - 11.000 1.2237 0.0264 -2.4868 - 12.000 1.2590 0.0306 -2.7620 - 13.000 1.2973 0.0354 -3.0595 - 14.000 1.3355 0.0406 -3.3796 - 16.000 1.4002 0.0535 -4.0606 - 17.000 1.4249 0.0613 -4.4170 - 18.000 1.4496 0.0698 -4.7822 - 19.000 1.4688 0.0792 -5.1523 - 20.000 1.4833 0.0898 -5.5194 - 21.000 1.4908 0.1016 -5.8650 - 24.000 1.5293 0.1362 -7.1149 - 25.000 1.5329 0.1490 -7.5030 - 26.000 1.5333 0.1622 -7.8676 - 27.000 1.5294 0.1756 -8.1977 - 28.000 1.5197 0.1896 -8.4783 - 29.000 1.5057 0.2043 -8.7098 - 30.000 1.4898 0.2192 -8.9039 - 40.000 1.1901 0.4324 -1.0184 - 50.000 0.9526 0.6613 -1.0184 - 60.000 0.7198 0.8793 -1.0184 - 70.000 0.4772 1.0617 -1.0184 - 80.000 0.2313 1.1882 -1.0184 - 90.000 0.0000 1.2449 -1.0184 - 100.000 -0.1619 1.1882 -1.0184 - 110.000 -0.3340 1.0617 -1.0184 - 120.000 -0.5038 0.8793 -1.0184 - 130.000 -0.6669 0.6613 -1.0184 - 140.000 -0.8331 0.4324 -1.0184 - 150.000 -1.0428 0.2192 -1.0184 - 160.000 -0.6952 0.0461 -1.0184 - 170.000 -0.3476 0.0164 -1.0184 - 180.000 0.0000 0.0164 -1.0184 -! ------------------------------------------------------------------------------ -! data for table 6 -! ------------------------------------------------------------------------------ - 12.000 Re ! Reynolds number in millions - 0 UserProp ! User property (control) setting -False InclUAdata ! Is unsteady aerodynamics data included in this table? If TRUE, then include 30 UA coefficients below this line -!........................................ -! Table of aerodynamics coefficients - 68 NumAlf ! Number of data lines in the following table -! Alpha Cl Cd Cpmin -! (deg) (-) (-) (-) - -180.000 0.0000 0.0164 -1.0184 - -170.000 0.3661 0.0164 -1.0184 - -160.000 0.7321 0.0493 -1.0184 - -150.000 1.0351 0.2220 -1.0184 - -140.000 0.8284 0.4351 -1.0184 - -130.000 0.6641 0.6634 -1.0184 - -120.000 0.5023 0.8810 -1.0184 - -110.000 0.3334 1.0629 -1.0184 - -100.000 0.1617 1.1888 -1.0184 - -90.000 0.0000 1.2449 -1.0184 - -80.000 -0.1617 1.1888 -1.0184 - -70.000 -0.3334 1.0629 -1.0184 - -60.000 -0.5023 0.8810 -1.0184 - -50.000 -0.6641 0.6634 -1.0184 - -40.000 -0.8284 0.4351 -1.0184 - -30.000 -1.0351 0.2220 -1.0184 - -20.000 -0.7869 0.1157 -1.0184 - -10.000 -0.6880 0.0192 -2.5579 - -7.000 -0.5004 0.0152 -1.7011 - -6.000 -0.3895 0.0146 -1.4180 - -5.000 -0.2755 0.0139 -1.2216 - -4.000 -0.1580 0.0135 -1.0316 - -3.000 -0.0376 0.0132 -0.9093 - -2.000 0.0838 0.0128 -0.9338 - -1.000 0.2059 0.0122 -1.0186 - 0.000 0.3280 0.0122 -1.1084 - 1.000 0.4477 0.0122 -1.2000 - 2.000 0.5655 0.0125 -1.2881 - 3.000 0.6800 0.0130 -1.3744 - 4.000 0.7870 0.0138 -1.4696 - 5.000 0.8855 0.0148 -1.5637 - 6.000 0.9873 0.0154 -1.6808 - 7.000 1.0818 0.0161 -1.8229 - 8.000 1.1249 0.0172 -1.9747 - 10.000 1.1916 0.0224 -2.2714 - 11.000 1.2363 0.0257 -2.5121 - 12.000 1.2792 0.0294 -2.8052 - 13.000 1.3196 0.0338 -3.1125 - 14.000 1.3493 0.0396 -3.4141 - 15.000 1.3829 0.0456 -3.7489 - 17.000 1.4395 0.0600 -4.4651 - 18.000 1.4628 0.0684 -4.8274 - 19.000 1.4818 0.0778 -5.2016 - 20.000 1.4914 0.0888 -5.5513 - 22.000 1.5317 0.1092 -6.3912 - 23.000 1.5395 0.1215 -6.7971 - 24.000 1.5451 0.1340 -7.2017 - 25.000 1.5478 0.1469 -7.5887 - 26.000 1.5468 0.1602 -7.9504 - 27.000 1.5396 0.1740 -8.2650 - 28.000 1.5291 0.1883 -8.5435 - 29.000 1.5165 0.2026 -8.7905 - 30.000 1.4788 0.2220 -8.3144 - 40.000 1.1834 0.4351 -1.0184 - 50.000 0.9487 0.6634 -1.0184 - 60.000 0.7176 0.8810 -1.0184 - 70.000 0.4763 1.0629 -1.0184 - 80.000 0.2311 1.1888 -1.0184 - 90.000 0.0000 1.2449 -1.0184 - 100.000 -0.1617 1.1888 -1.0184 - 110.000 -0.3334 1.0629 -1.0184 - 120.000 -0.5023 0.8810 -1.0184 - 130.000 -0.6641 0.6634 -1.0184 - 140.000 -0.8284 0.4351 -1.0184 - 150.000 -1.0351 0.2220 -1.0184 - 160.000 -0.7321 0.0493 -1.0184 - 170.000 -0.3661 0.0164 -1.0184 - 180.000 0.0000 0.0164 -1.0184 -! ------------------------------------------------------------------------------ -! data for table 7 -! ------------------------------------------------------------------------------ - 14.000 Re ! Reynolds number in millions - 0 UserProp ! User property (control) setting -False InclUAdata ! Is unsteady aerodynamics data included in this table? If TRUE, then include 30 UA coefficients below this line -!........................................ -! Table of aerodynamics coefficients - 64 NumAlf ! Number of data lines in the following table -! Alpha Cl Cd Cpmin -! (deg) (-) (-) (-) - -180.000 0.0000 0.0164 -1.0184 - -170.000 0.3528 0.0164 -1.0184 - -160.000 0.7055 0.0422 -1.0184 - -150.000 1.0584 0.2155 -1.0184 - -140.000 0.8426 0.4292 -1.0184 - -130.000 0.6724 0.6586 -1.0184 - -120.000 0.5068 0.8773 -1.0184 - -110.000 0.3353 1.0604 -1.0184 - -100.000 0.1622 1.1874 -1.0184 - -90.000 0.0000 1.2449 -1.0184 - -80.000 -0.1622 1.1874 -1.0184 - -70.000 -0.3353 1.0604 -1.0184 - -60.000 -0.5068 0.8773 -1.0184 - -50.000 -0.6724 0.6586 -1.0184 - -40.000 -0.8426 0.4292 -1.0184 - -30.000 -1.0584 0.2155 -1.0184 - -20.000 -0.7746 0.1171 -1.0184 - -10.000 -0.7013 0.0187 -2.5858 - -9.000 -0.6819 0.0169 -2.3531 - -8.000 -0.6071 0.0156 -2.0491 - -6.000 -0.3894 0.0145 -1.4156 - -5.000 -0.2754 0.0138 -1.2213 - -4.000 -0.1579 0.0133 -1.0315 - -3.000 -0.0368 0.0131 -0.9097 - -2.000 0.0849 0.0127 -0.9345 - -1.000 0.2064 0.0122 -1.0188 - 0.000 0.3289 0.0121 -1.1092 - 1.000 0.4466 0.0123 -1.2002 - 2.000 0.5654 0.0125 -1.2873 - 3.000 0.6786 0.0131 -1.3726 - 5.000 0.8885 0.0147 -1.5669 - 6.000 0.9903 0.0154 -1.6841 - 7.000 1.0893 0.0159 -1.8303 - 8.000 1.1291 0.0170 -1.9792 - 11.000 1.2479 0.0251 -2.5351 - 12.000 1.2907 0.0287 -2.8294 - 14.000 1.3702 0.0380 -3.4665 - 16.000 1.4249 0.0513 -4.1369 - 18.000 1.4739 0.0672 -4.8655 - 21.000 1.5334 0.0960 -6.0511 - 22.000 1.5435 0.1076 -6.4448 - 23.000 1.5524 0.1197 -6.8631 - 24.000 1.5570 0.1323 -7.2661 - 25.000 1.5586 0.1454 -7.6507 - 26.000 1.5542 0.1590 -7.9959 - 27.000 1.5471 0.1729 -8.3137 - 28.000 1.5378 0.1869 -8.6045 - 29.000 1.5264 0.2010 -8.8638 - 30.000 1.5119 0.2155 -9.0822 - 40.000 1.2036 0.4292 -1.0184 - 50.000 0.9607 0.6586 -1.0184 - 60.000 0.7241 0.8773 -1.0184 - 70.000 0.4790 1.0604 -1.0184 - 80.000 0.2317 1.1874 -1.0184 - 90.000 0.0000 1.2449 -1.0184 - 100.000 -0.1622 1.1874 -1.0184 - 110.000 -0.3353 1.0604 -1.0184 - 120.000 -0.5068 0.8773 -1.0184 - 130.000 -0.6724 0.6586 -1.0184 - 140.000 -0.8426 0.4292 -1.0184 - 150.000 -1.0584 0.2155 -1.0184 - 160.000 -0.7055 0.0422 -1.0184 - 170.000 -0.3528 0.0164 -1.0184 - 180.000 0.0000 0.0164 -1.0184 \ No newline at end of file diff --git a/Test_Cases/MHK_RM1/Airfoils/NACA6_0247_coords.txt b/Test_Cases/MHK_RM1/Airfoils/NACA6_0247_coords.txt deleted file mode 100644 index 76becdc1..00000000 --- a/Test_Cases/MHK_RM1/Airfoils/NACA6_0247_coords.txt +++ /dev/null @@ -1,47 +0,0 @@ - 40 NumCoords ! The number of coordinates in the airfoil shape file (including an extra coordinate for airfoil reference). Set to zero if coordinates not included. -! ......... x-y coordinates are next if NumCoords > 0 ............. -! x-y coordinate of airfoil reference -! x/c y/c - 0.25 0 -! coordinates of airfoil shape -! NACA6_0247 Airfoil -! x/c y/c - 0.000000 0.000000 - 0.006819 0.021573 - 0.027091 0.045571 - 0.060263 0.070519 - 0.105430 0.093593 - 0.161359 0.113695 - 0.226526 0.129332 - 0.299152 0.139084 - 0.377257 0.140958 - 0.458710 0.134375 - 0.541290 0.120926 - 0.622743 0.102688 - 0.700848 0.081979 - 0.773474 0.061268 - 0.838641 0.042604 - 0.894570 0.027238 - 0.939737 0.015604 - 0.972909 0.007552 - 0.993181 0.002511 - 1.000000 0.000000 - 0.993181 -0.000009 - 0.972909 0.000021 - 0.939737 -0.001786 - 0.894570 -0.006851 - 0.838641 -0.015998 - 0.773474 -0.029320 - 0.700848 -0.046093 - 0.622743 -0.064559 - 0.541290 -0.082348 - 0.458710 -0.096978 - 0.377257 -0.106009 - 0.299152 -0.107583 - 0.226526 -0.102345 - 0.161359 -0.091881 - 0.105430 -0.077436 - 0.060263 -0.059906 - 0.027091 -0.040088 - 0.006819 -0.019333 - 0.000000 0.000000 \ No newline at end of file diff --git a/Test_Cases/MHK_RM1/Airfoils/NACA6_0259.dat b/Test_Cases/MHK_RM1/Airfoils/NACA6_0259.dat deleted file mode 100644 index 2122f139..00000000 --- a/Test_Cases/MHK_RM1/Airfoils/NACA6_0259.dat +++ /dev/null @@ -1,560 +0,0 @@ -! ------------ AirfoilInfo v1.01.x Input File ---------------------------------- -! NACA6_0259 airfoil, data based on values used for the design of the RM1 tidal current turbine. -! line -! line -! ------------------------------------------------------------------------------ -"default" InterpOrd ! Interpolation order to use for quasi-steady table lookup {1=linear; 3=cubic spline; "default"} [default=1] - 1.0 NonDimArea ! The non-dimensional area of the airfoil (area/chord^2) (set to 1.0 if unsure or unneeded) -@"NACA6_0259_coords.txt" NumCoords ! The number of coordinates in the airfoil shape file. Set to zero if coordinates not included. -"unused" BL_file ! The file name including the boundary layer characteristics of the profile. Ignored if the aeroacoustic module is not called. - 7 NumTabs ! Number of airfoil tables in this file. -! ------------------------------------------------------------------------------ -! data for table 1 -! ------------------------------------------------------------------------------ - 2.000 Re ! Reynolds number in millions - 0 UserProp ! User property (control) setting -False InclUAdata ! Is unsteady aerodynamics data included in this table? If TRUE, then include 30 UA coefficients below this line -!........................................ -! Table of aerodynamics coefficients - 72 NumAlf ! Number of data lines in the following table -! Alpha Cl Cd Cpmin -! (deg) (-) (-) (-) - -180.000 0.0000 0.0173 -1.0500 - -170.000 0.3042 0.0173 -1.0500 - -160.000 0.6084 0.0763 -1.0500 - -150.000 0.9126 0.2442 -1.0500 - -140.000 0.7507 0.4510 -1.0500 - -130.000 0.6154 0.6723 -1.0500 - -120.000 0.4739 0.8824 -1.0500 - -110.000 0.3193 1.0569 -1.0500 - -100.000 0.1570 1.1758 -1.0500 - -90.000 0.0000 1.2263 -1.0500 - -80.000 -0.1570 1.1758 -1.0500 - -70.000 -0.3193 1.0569 -1.0500 - -60.000 -0.4739 0.8824 -1.0500 - -50.000 -0.6154 0.6723 -1.0500 - -40.000 -0.7507 0.4510 -1.0500 - -30.000 -0.9126 0.2442 -1.0500 - -20.000 -0.6612 0.1348 -1.0500 - -10.000 -0.5856 0.0253 -2.3817 - -9.000 -0.5560 0.0221 -2.1570 - -8.000 -0.5266 0.0196 -1.9400 - -7.000 -0.4741 0.0183 -1.6900 - -6.000 -0.3813 0.0173 -1.4473 - -5.000 -0.2758 0.0166 -1.2546 - -4.000 -0.1657 0.0159 -1.0740 - -3.000 -0.0533 0.0149 -0.9579 - -2.000 0.0654 0.0147 -0.9571 - -1.000 0.1837 0.0146 -1.0391 - 0.000 0.3015 0.0147 -1.1258 - 1.000 0.4199 0.0147 -1.2152 - 2.000 0.5365 0.0149 -1.3043 - 3.000 0.6510 0.0151 -1.3968 - 4.000 0.7612 0.0155 -1.4899 - 5.000 0.8698 0.0159 -1.5922 - 6.000 0.9584 0.0170 -1.6982 - 7.000 0.9941 0.0186 -1.7781 - 8.000 1.0264 0.0209 -1.9015 - 9.000 1.0659 0.0237 -2.0501 - 10.000 1.1068 0.0270 -2.2053 - 11.000 1.1146 0.0328 -2.3201 - 12.000 1.1437 0.0380 -2.5649 - 13.000 1.1530 0.0457 -2.7732 - 14.000 1.1785 0.0527 -3.0315 - 15.000 1.1965 0.0611 -3.2835 - 16.000 1.2243 0.0693 -3.5810 - 17.000 1.2486 0.0782 -3.8873 - 18.000 1.2711 0.0879 -4.2109 - 19.000 1.2921 0.0982 -4.5349 - 20.000 1.3103 0.1092 -4.8694 - 21.000 1.3273 0.1205 -5.2118 - 22.000 1.3464 0.1314 -5.5795 - 23.000 1.3547 0.1441 -5.9129 - 24.000 1.3612 0.1569 -6.2417 - 25.000 1.3621 0.1702 -6.5518 - 26.000 1.3574 0.1844 -6.8172 - 28.000 1.3331 0.2134 -7.2030 - 29.000 1.3151 0.2296 -7.3009 - 30.000 1.3037 0.2442 -7.4214 - 40.000 1.0724 0.4510 -1.0500 - 50.000 0.8792 0.6723 -1.0500 - 60.000 0.6770 0.8824 -1.0500 - 70.000 0.4561 1.0569 -1.0500 - 80.000 0.2243 1.1758 -1.0500 - 90.000 0.0000 1.2263 -1.0500 - 100.000 -0.1570 1.1758 -1.0500 - 110.000 -0.3193 1.0569 -1.0500 - 120.000 -0.4739 0.8824 -1.0500 - 130.000 -0.6154 0.6723 -1.0500 - 140.000 -0.7507 0.4510 -1.0500 - 150.000 -0.9126 0.2442 -1.0500 - 160.000 -0.6084 0.0763 -1.0500 - 170.000 -0.3042 0.0173 -1.0500 - 180.000 0.0000 0.0173 -1.0500 -! ------------------------------------------------------------------------------ -! data for table 2 -! ------------------------------------------------------------------------------ - 4.000 Re ! Reynolds number in millions - 0 UserProp ! User property (control) setting -False InclUAdata ! Is unsteady aerodynamics data included in this table? If TRUE, then include 30 UA coefficients below this line -!........................................ -! Table of aerodynamics coefficients - 69 NumAlf ! Number of data lines in the following table -! Alpha Cl Cd Cpmin -! (deg) (-) (-) (-) - -180.000 0.0000 0.0265 -1.0500 - -170.000 0.3188 0.0265 -1.0500 - -160.000 0.6377 0.0740 -1.0500 - -150.000 0.9566 0.2428 -1.0500 - -140.000 0.7775 0.4507 -1.0500 - -130.000 0.6312 0.6735 -1.0500 - -120.000 0.4824 0.8854 -1.0500 - -110.000 0.3229 1.0619 -1.0500 - -100.000 0.1579 1.1829 -1.0500 - -90.000 0.0000 1.2355 -1.0500 - -80.000 -0.1579 1.1829 -1.0500 - -70.000 -0.3229 1.0619 -1.0500 - -60.000 -0.4824 0.8854 -1.0500 - -50.000 -0.6312 0.6735 -1.0500 - -40.000 -0.7775 0.4507 -1.0500 - -30.000 -0.9566 0.2428 -1.0500 - -20.000 -0.6990 0.1374 -1.0500 - -10.000 -0.6305 0.0320 -2.4763 - -9.000 -0.5846 0.0296 -2.2114 - -8.000 -0.5656 0.0276 -2.0071 - -7.000 -0.4826 0.0265 -1.7052 - -6.000 -0.3812 0.0257 -1.4476 - -5.000 -0.2740 0.0250 -1.2528 - -4.000 -0.1598 0.0246 -1.0679 - -3.000 -0.0443 0.0239 -0.9516 - -1.000 0.1932 0.0231 -1.0446 - 0.000 0.3133 0.0230 -1.1332 - 1.000 0.4312 0.0232 -1.2224 - 2.000 0.5504 0.0232 -1.3133 - 5.000 0.8753 0.0248 -1.5949 - 6.000 0.9525 0.0262 -1.6950 - 7.000 1.0053 0.0274 -1.7871 - 9.000 1.1044 0.0311 -2.0976 - 10.000 1.1238 0.0351 -2.2272 - 11.000 1.1576 0.0392 -2.4030 - 12.000 1.1727 0.0451 -2.6260 - 13.000 1.2005 0.0510 -2.8799 - 14.000 1.2286 0.0574 -3.1581 - 15.000 1.2617 0.0640 -3.4600 - 16.000 1.2886 0.0717 -3.7722 - 17.000 1.3161 0.0798 -4.1116 - 18.000 1.3390 0.0889 -4.4496 - 19.000 1.3617 0.0985 -4.7969 - 20.000 1.3762 0.1095 -5.1410 - 21.000 1.3913 0.1207 -5.4920 - 22.000 1.4044 0.1325 -5.8568 - 23.000 1.4088 0.1454 -6.1886 - 24.000 1.4222 0.1569 -6.5916 - 25.000 1.4229 0.1701 -6.9257 - 26.000 1.4236 0.1831 -7.2526 - 27.000 1.4198 0.1966 -7.5420 - 28.000 1.4120 0.2107 -7.7888 - 29.000 1.3826 0.2276 -7.8548 - 30.000 1.3666 0.2428 -7.9826 - 40.000 1.1106 0.4507 -1.0500 - 50.000 0.9018 0.6735 -1.0500 - 60.000 0.6891 0.8854 -1.0500 - 70.000 0.4613 1.0619 -1.0500 - 80.000 0.2255 1.1829 -1.0500 - 90.000 0.0000 1.2355 -1.0500 - 100.000 -0.1579 1.1829 -1.0500 - 110.000 -0.3229 1.0619 -1.0500 - 120.000 -0.4824 0.8854 -1.0500 - 130.000 -0.6312 0.6735 -1.0500 - 140.000 -0.7775 0.4507 -1.0500 - 150.000 -0.9566 0.2428 -1.0500 - 160.000 -0.6377 0.0740 -1.0500 - 170.000 -0.3188 0.0265 -1.0500 - 180.000 0.0000 0.0265 -1.0500 -! ------------------------------------------------------------------------------ -! data for table 3 -! ------------------------------------------------------------------------------ - 6.000 Re ! Reynolds number in millions - 0 UserProp ! User property (control) setting -False InclUAdata ! Is unsteady aerodynamics data included in this table? If TRUE, then include 30 UA coefficients below this line -!........................................ -! Table of aerodynamics coefficients - 71 NumAlf ! Number of data lines in the following table -! Alpha Cl Cd Cpmin -! (deg) (-) (-) (-) - -180.000 0.0000 0.0273 -1.0500 - -170.000 0.3307 0.0273 -1.0500 - -160.000 0.6614 0.0659 -1.0500 - -150.000 0.9922 0.2354 -1.0500 - -140.000 0.7991 0.4443 -1.0500 - -130.000 0.6440 0.6682 -1.0500 - -120.000 0.4893 0.8814 -1.0500 - -110.000 0.3258 1.0594 -1.0500 - -100.000 0.1586 1.1821 -1.0500 - -90.000 0.0000 1.2363 -1.0500 - -80.000 -0.1586 1.1821 -1.0500 - -70.000 -0.3258 1.0594 -1.0500 - -60.000 -0.4893 0.8814 -1.0500 - -50.000 -0.6440 0.6682 -1.0500 - -40.000 -0.7991 0.4443 -1.0500 - -30.000 -0.9922 0.2354 -1.0500 - -20.000 -0.7259 0.1333 -1.0500 - -10.000 -0.6565 0.0312 -2.5308 - -9.000 -0.6153 0.0291 -2.2680 - -8.000 -0.5760 0.0277 -2.0253 - -7.000 -0.4843 0.0269 -1.7079 - -6.000 -0.3829 0.0261 -1.4501 - -5.000 -0.2719 0.0254 -1.2506 - -4.000 -0.1571 0.0250 -1.0648 - -3.000 -0.0409 0.0245 -0.9496 - -2.000 0.0773 0.0237 -0.9639 - -1.000 0.1974 0.0234 -1.0472 - 0.000 0.3173 0.0234 -1.1354 - 1.000 0.4378 0.0234 -1.2266 - 2.000 0.5540 0.0237 -1.3159 - 4.000 0.7767 0.0246 -1.5044 - 5.000 0.8722 0.0257 -1.5946 - 6.000 0.9556 0.0269 -1.6904 - 7.000 1.0185 0.0277 -1.8002 - 8.000 1.0788 0.0289 -1.9584 - 9.000 1.1126 0.0313 -2.1073 - 10.000 1.1482 0.0346 -2.2605 - 11.000 1.1714 0.0390 -2.4300 - 12.000 1.2007 0.0438 -2.6851 - 13.000 1.2270 0.0496 -2.9404 - 14.000 1.2643 0.0552 -3.2479 - 15.000 1.2937 0.0619 -3.5495 - 16.000 1.3227 0.0691 -3.8735 - 17.000 1.3492 0.0771 -4.2206 - 19.000 1.3921 0.0955 -4.9136 - 20.000 1.4242 0.1039 -5.3363 - 21.000 1.4362 0.1152 -5.6847 - 22.000 1.4437 0.1275 -6.0421 - 23.000 1.4482 0.1403 -6.3916 - 24.000 1.4544 0.1528 -6.7718 - 25.000 1.4570 0.1657 -7.1295 - 26.000 1.4545 0.1791 -7.4507 - 27.000 1.4477 0.1930 -7.7327 - 28.000 1.4396 0.2069 -7.9910 - 29.000 1.4298 0.2210 -8.2200 - 30.000 1.4174 0.2354 -8.4060 - 40.000 1.1415 0.4443 -1.0500 - 50.000 0.9200 0.6682 -1.0500 - 60.000 0.6990 0.8814 -1.0500 - 70.000 0.4656 1.0594 -1.0500 - 80.000 0.2266 1.1821 -1.0500 - 90.000 0.0000 1.2363 -1.0500 - 100.000 -0.1586 1.1821 -1.0500 - 110.000 -0.3258 1.0594 -1.0500 - 120.000 -0.4893 0.8814 -1.0500 - 130.000 -0.6440 0.6682 -1.0500 - 140.000 -0.7991 0.4443 -1.0500 - 150.000 -0.9922 0.2354 -1.0500 - 160.000 -0.6614 0.0659 -1.0500 - 170.000 -0.3307 0.0273 -1.0500 - 180.000 0.0000 0.0273 -1.0500 -! ------------------------------------------------------------------------------ -! data for table 4 -! ------------------------------------------------------------------------------ - 8.000 Re ! Reynolds number in millions - 0 UserProp ! User property (control) setting -False InclUAdata ! Is unsteady aerodynamics data included in this table? If TRUE, then include 30 UA coefficients below this line -!........................................ -! Table of aerodynamics coefficients - 62 NumAlf ! Number of data lines in the following table -! Alpha Cl Cd Cpmin -! (deg) (-) (-) (-) - -180.000 0.0000 0.0273 -1.0500 - -170.000 0.3963 0.0273 -1.0500 - -160.000 0.7927 0.0815 -1.0500 - -150.000 0.9345 0.2497 -1.0500 - -140.000 0.7640 0.4570 -1.0500 - -130.000 0.6233 0.6789 -1.0500 - -120.000 0.4781 0.8897 -1.0500 - -110.000 0.3211 1.0650 -1.0500 - -100.000 0.1575 1.1850 -1.0500 - -90.000 0.0000 1.2363 -1.0500 - -80.000 -0.1575 1.1850 -1.0500 - -70.000 -0.3211 1.0650 -1.0500 - -60.000 -0.4781 0.8897 -1.0500 - -50.000 -0.6233 0.6789 -1.0500 - -40.000 -0.7640 0.4570 -1.0500 - -30.000 -0.9345 0.2497 -1.0500 - -20.000 -0.8190 0.1218 -1.0500 - -10.000 -0.6664 0.0308 -2.5594 - -9.000 -0.6387 0.0282 -2.3121 - -8.000 -0.5840 0.0273 -2.0395 - -5.000 -0.2715 0.0252 -1.2500 - -4.000 -0.1565 0.0247 -1.0642 - -3.000 -0.0386 0.0243 -0.9387 - -2.000 0.0795 0.0237 -0.9652 - -1.000 0.1995 0.0234 -1.0481 - 0.000 0.3206 0.0233 -1.1376 - 1.000 0.4392 0.0233 -1.2274 - 2.000 0.5554 0.0235 -1.3173 - 3.000 0.6697 0.0239 -1.4100 - 4.000 0.7759 0.0247 -1.4949 - 6.000 0.9617 0.0267 -1.6893 - 7.000 1.0370 0.0273 -1.8165 - 8.000 1.0937 0.0284 -1.9758 - 9.000 1.1244 0.0309 -2.1223 - 11.000 1.1836 0.0383 -2.4539 - 12.000 1.2209 0.0425 -2.7277 - 13.000 1.2599 0.0471 -3.0189 - 15.000 1.3283 0.0587 -3.6464 - 16.000 1.3574 0.0657 -3.9802 - 17.000 1.3869 0.0731 -4.3450 - 18.000 1.4070 0.0819 -4.6864 - 19.000 1.4296 0.0909 -5.0580 - 20.000 1.4449 0.1014 -5.4198 - 22.000 1.4619 0.1250 -6.1264 - 25.000 1.4735 0.1633 -7.2267 - 26.000 1.4721 0.1765 -7.5605 - 30.000 1.3351 0.2497 -6.1002 - 40.000 1.0915 0.4570 -1.0500 - 50.000 0.8905 0.6789 -1.0500 - 60.000 0.6831 0.8897 -1.0500 - 70.000 0.4587 1.0650 -1.0500 - 80.000 0.2249 1.1850 -1.0500 - 90.000 0.0000 1.2363 -1.0500 - 100.000 -0.1575 1.1850 -1.0500 - 110.000 -0.3211 1.0650 -1.0500 - 120.000 -0.4781 0.8897 -1.0500 - 130.000 -0.6233 0.6789 -1.0500 - 140.000 -0.7640 0.4570 -1.0500 - 150.000 -0.9345 0.2497 -1.0500 - 160.000 -0.7927 0.0815 -1.0500 - 170.000 -0.3963 0.0273 -1.0500 - 180.000 0.0000 0.0273 -1.0500 -! ------------------------------------------------------------------------------ -! data for table 5 -! ------------------------------------------------------------------------------ - 10.000 Re ! Reynolds number in millions - 0 UserProp ! User property (control) setting -False InclUAdata ! Is unsteady aerodynamics data included in this table? If TRUE, then include 30 UA coefficients below this line -!........................................ -! Table of aerodynamics coefficients - 67 NumAlf ! Number of data lines in the following table -! Alpha Cl Cd Cpmin -! (deg) (-) (-) (-) - -180.000 0.0000 0.0273 -1.0500 - -170.000 0.3420 0.0273 -1.0500 - -160.000 0.6842 0.0565 -1.0500 - -150.000 1.0262 0.2268 -1.0500 - -140.000 0.8198 0.4367 -1.0500 - -130.000 0.6563 0.6619 -1.0500 - -120.000 0.4958 0.8765 -1.0500 - -110.000 0.3287 1.0560 -1.0500 - -100.000 0.1593 1.1804 -1.0500 - -90.000 0.0000 1.2363 -1.0500 - -80.000 -0.1593 1.1804 -1.0500 - -70.000 -0.3287 1.0560 -1.0500 - -60.000 -0.4958 0.8765 -1.0500 - -50.000 -0.6563 0.6619 -1.0500 - -40.000 -0.8198 0.4367 -1.0500 - -30.000 -1.0262 0.2268 -1.0500 - -20.000 -0.7455 0.1287 -1.0500 - -10.000 -0.6641 0.0307 -2.5362 - -9.000 -0.6680 0.0278 -2.3705 - -8.000 -0.5909 0.0270 -2.0519 - -6.000 -0.3842 0.0255 -1.4542 - -4.000 -0.1556 0.0245 -1.0634 - -3.000 -0.0378 0.0242 -0.9399 - -2.000 0.0809 0.0237 -0.9660 - -1.000 0.2015 0.0233 -1.0494 - 0.000 0.3219 0.0232 -1.1383 - 1.000 0.4399 0.0233 -1.2279 - 2.000 0.5557 0.0235 -1.3193 - 4.000 0.7740 0.0248 -1.4904 - 5.000 0.8707 0.0258 -1.5838 - 6.000 0.9649 0.0266 -1.6955 - 7.000 1.0572 0.0272 -1.8344 - 8.000 1.1003 0.0283 -1.9832 - 9.000 1.1403 0.0303 -2.1425 - 10.000 1.1576 0.0340 -2.2577 - 11.000 1.2042 0.0371 -2.4950 - 12.000 1.2389 0.0413 -2.7658 - 13.000 1.2767 0.0460 -3.0586 - 14.000 1.3142 0.0511 -3.3735 - 16.000 1.3779 0.0638 -4.0437 - 17.000 1.4021 0.0715 -4.3944 - 18.000 1.4265 0.0798 -4.7538 - 19.000 1.4454 0.0891 -5.1180 - 20.000 1.4597 0.0995 -5.4792 - 21.000 1.4671 0.1111 -5.8193 - 24.000 1.5049 0.1452 -7.0494 - 25.000 1.5085 0.1578 -7.4313 - 26.000 1.5089 0.1708 -7.7900 - 27.000 1.5050 0.1839 -8.1148 - 28.000 1.4955 0.1978 -8.3910 - 29.000 1.4817 0.2122 -8.6188 - 30.000 1.4660 0.2268 -8.8098 - 40.000 1.1712 0.4367 -1.0500 - 50.000 0.9375 0.6619 -1.0500 - 60.000 0.7083 0.8765 -1.0500 - 70.000 0.4696 1.0560 -1.0500 - 80.000 0.2276 1.1804 -1.0500 - 90.000 0.0000 1.2363 -1.0500 - 100.000 -0.1593 1.1804 -1.0500 - 110.000 -0.3287 1.0560 -1.0500 - 120.000 -0.4958 0.8765 -1.0500 - 130.000 -0.6563 0.6619 -1.0500 - 140.000 -0.8198 0.4367 -1.0500 - 150.000 -1.0262 0.2268 -1.0500 - 160.000 -0.6842 0.0565 -1.0500 - 170.000 -0.3420 0.0273 -1.0500 - 180.000 0.0000 0.0273 -1.0500 -! ------------------------------------------------------------------------------ -! data for table 6 -! ------------------------------------------------------------------------------ - 12.000 Re ! Reynolds number in millions - 0 UserProp ! User property (control) setting -False InclUAdata ! Is unsteady aerodynamics data included in this table? If TRUE, then include 30 UA coefficients below this line -!........................................ -! Table of aerodynamics coefficients - 68 NumAlf ! Number of data lines in the following table -! Alpha Cl Cd Cpmin -! (deg) (-) (-) (-) - -180.000 0.0000 0.0273 -1.0500 - -170.000 0.3603 0.0273 -1.0500 - -160.000 0.7204 0.0597 -1.0500 - -150.000 1.0186 0.2297 -1.0500 - -140.000 0.8152 0.4393 -1.0500 - -130.000 0.6535 0.6640 -1.0500 - -120.000 0.4943 0.8781 -1.0500 - -110.000 0.3281 1.0571 -1.0500 - -100.000 0.1591 1.1810 -1.0500 - -90.000 0.0000 1.2363 -1.0500 - -80.000 -0.1591 1.1810 -1.0500 - -70.000 -0.3281 1.0571 -1.0500 - -60.000 -0.4943 0.8781 -1.0500 - -50.000 -0.6535 0.6640 -1.0500 - -40.000 -0.8152 0.4393 -1.0500 - -30.000 -1.0186 0.2297 -1.0500 - -20.000 -0.7743 0.1250 -1.0500 - -10.000 -0.6770 0.0301 -2.5650 - -7.000 -0.4925 0.0261 -1.7218 - -6.000 -0.3833 0.0255 -1.4432 - -5.000 -0.2711 0.0248 -1.2500 - -4.000 -0.1555 0.0244 -1.0630 - -3.000 -0.0370 0.0241 -0.9427 - -2.000 0.0825 0.0237 -0.9667 - -1.000 0.2026 0.0232 -1.0502 - 0.000 0.3227 0.0232 -1.1385 - 1.000 0.4406 0.0232 -1.2287 - 2.000 0.5565 0.0234 -1.3154 - 3.000 0.6691 0.0239 -1.4003 - 4.000 0.7744 0.0247 -1.4940 - 5.000 0.8714 0.0257 -1.5865 - 6.000 0.9716 0.0263 -1.7018 - 7.000 1.0646 0.0270 -1.8417 - 8.000 1.1070 0.0281 -1.9911 - 10.000 1.1726 0.0332 -2.2830 - 11.000 1.2166 0.0364 -2.5199 - 12.000 1.2588 0.0401 -2.8083 - 13.000 1.2986 0.0444 -3.1107 - 14.000 1.3278 0.0502 -3.4075 - 15.000 1.3609 0.0560 -3.7370 - 17.000 1.4166 0.0702 -4.4417 - 18.000 1.4395 0.0784 -4.7983 - 19.000 1.4582 0.0877 -5.1665 - 20.000 1.4677 0.0985 -5.5106 - 22.000 1.5073 0.1186 -6.3371 - 23.000 1.5150 0.1307 -6.7366 - 24.000 1.5205 0.1430 -7.1348 - 25.000 1.5231 0.1558 -7.5156 - 26.000 1.5222 0.1688 -7.8715 - 27.000 1.5151 0.1824 -8.1811 - 28.000 1.5047 0.1964 -8.4551 - 29.000 1.4923 0.2106 -8.6982 - 30.000 1.4552 0.2297 -8.2297 - 40.000 1.1645 0.4393 -1.0500 - 50.000 0.9336 0.6640 -1.0500 - 60.000 0.7062 0.8781 -1.0500 - 70.000 0.4687 1.0571 -1.0500 - 80.000 0.2274 1.1810 -1.0500 - 90.000 0.0000 1.2363 -1.0500 - 100.000 -0.1591 1.1810 -1.0500 - 110.000 -0.3281 1.0571 -1.0500 - 120.000 -0.4943 0.8781 -1.0500 - 130.000 -0.6535 0.6640 -1.0500 - 140.000 -0.8152 0.4393 -1.0500 - 150.000 -1.0186 0.2297 -1.0500 - 160.000 -0.7204 0.0597 -1.0500 - 170.000 -0.3603 0.0273 -1.0500 - 180.000 0.0000 0.0273 -1.0500 -! ------------------------------------------------------------------------------ -! data for table 7 -! ------------------------------------------------------------------------------ - 14.000 Re ! Reynolds number in millions - 0 UserProp ! User property (control) setting -False InclUAdata ! Is unsteady aerodynamics data included in this table? If TRUE, then include 30 UA coefficients below this line -!........................................ -! Table of aerodynamics coefficients - 64 NumAlf ! Number of data lines in the following table -! Alpha Cl Cd Cpmin -! (deg) (-) (-) (-) - -180.000 0.0000 0.0273 -1.0500 - -170.000 0.3472 0.0273 -1.0500 - -160.000 0.6943 0.0527 -1.0500 - -150.000 1.0415 0.2232 -1.0500 - -140.000 0.8291 0.4335 -1.0500 - -130.000 0.6617 0.6592 -1.0500 - -120.000 0.4987 0.8744 -1.0500 - -110.000 0.3299 1.0546 -1.0500 - -100.000 0.1596 1.1796 -1.0500 - -90.000 0.0000 1.2363 -1.0500 - -80.000 -0.1596 1.1796 -1.0500 - -70.000 -0.3299 1.0546 -1.0500 - -60.000 -0.4987 0.8744 -1.0500 - -50.000 -0.6617 0.6592 -1.0500 - -40.000 -0.8291 0.4335 -1.0500 - -30.000 -1.0415 0.2232 -1.0500 - -20.000 -0.7623 0.1264 -1.0500 - -10.000 -0.6901 0.0296 -2.5924 - -9.000 -0.6710 0.0277 -2.3634 - -8.000 -0.5974 0.0265 -2.0643 - -6.000 -0.3832 0.0254 -1.4409 - -5.000 -0.2711 0.0247 -1.2497 - -4.000 -0.1554 0.0242 -1.0629 - -3.000 -0.0362 0.0240 -0.9430 - -2.000 0.0836 0.0236 -0.9674 - -1.000 0.2031 0.0232 -1.0504 - 0.000 0.3237 0.0231 -1.1393 - 1.000 0.4395 0.0233 -1.2289 - 2.000 0.5564 0.0234 -1.3146 - 3.000 0.6678 0.0240 -1.3986 - 5.000 0.8744 0.0256 -1.5898 - 6.000 0.9745 0.0263 -1.7051 - 7.000 1.0719 0.0268 -1.8489 - 8.000 1.1111 0.0279 -1.9955 - 11.000 1.2280 0.0358 -2.5425 - 12.000 1.2701 0.0394 -2.8321 - 14.000 1.3483 0.0485 -3.4590 - 16.000 1.4021 0.0617 -4.1188 - 18.000 1.4504 0.0773 -4.8357 - 21.000 1.5090 0.1056 -6.0025 - 22.000 1.5189 0.1170 -6.3899 - 23.000 1.5276 0.1289 -6.8015 - 24.000 1.5322 0.1413 -7.1982 - 25.000 1.5338 0.1542 -7.5766 - 26.000 1.5294 0.1677 -7.9162 - 27.000 1.5225 0.1813 -8.2290 - 28.000 1.5133 0.1950 -8.5152 - 29.000 1.5021 0.2090 -8.7703 - 30.000 1.4878 0.2232 -8.9852 - 40.000 1.1844 0.4335 -1.0500 - 50.000 0.9454 0.6592 -1.0500 - 60.000 0.7125 0.8744 -1.0500 - 70.000 0.4714 1.0546 -1.0500 - 80.000 0.2281 1.1796 -1.0500 - 90.000 0.0000 1.2363 -1.0500 - 100.000 -0.1596 1.1796 -1.0500 - 110.000 -0.3299 1.0546 -1.0500 - 120.000 -0.4987 0.8744 -1.0500 - 130.000 -0.6617 0.6592 -1.0500 - 140.000 -0.8291 0.4335 -1.0500 - 150.000 -1.0415 0.2232 -1.0500 - 160.000 -0.6943 0.0527 -1.0500 - 170.000 -0.3472 0.0273 -1.0500 - 180.000 0.0000 0.0273 -1.0500 \ No newline at end of file diff --git a/Test_Cases/MHK_RM1/Airfoils/NACA6_0259_coords.txt b/Test_Cases/MHK_RM1/Airfoils/NACA6_0259_coords.txt deleted file mode 100644 index 94bdcf9e..00000000 --- a/Test_Cases/MHK_RM1/Airfoils/NACA6_0259_coords.txt +++ /dev/null @@ -1,47 +0,0 @@ - 40 NumCoords ! The number of coordinates in the airfoil shape file (including an extra coordinate for airfoil reference). Set to zero if coordinates not included. -! ......... x-y coordinates are next if NumCoords > 0 ............. -! x-y coordinate of airfoil reference -! x/c y/c - 0.25 0 -! coordinates of airfoil shape -! NACA6_0259 Airfoil -! x/c y/c - 0.000000 0.000000 - 0.006819 0.022584 - 0.027091 0.047510 - 0.060263 0.073301 - 0.105430 0.097140 - 0.161359 0.117917 - 0.226526 0.134137 - 0.299152 0.144379 - 0.377257 0.146668 - 0.458710 0.140419 - 0.541290 0.127194 - 0.622743 0.109034 - 0.700848 0.088223 - 0.773474 0.067204 - 0.838641 0.048007 - 0.894570 0.031887 - 0.939737 0.019298 - 0.972909 0.010124 - 0.993181 0.003839 - 1.000000 0.000000 - 0.993181 -0.001378 - 0.972909 -0.002676 - 0.939737 -0.005710 - 0.894570 -0.011838 - 0.838641 -0.021843 - 0.773474 -0.035786 - 0.700848 -0.052933 - 0.622743 -0.071538 - 0.541290 -0.089257 - 0.458710 -0.103644 - 0.377257 -0.112299 - 0.299152 -0.113402 - 0.226526 -0.107598 - 0.161359 -0.096465 - 0.105430 -0.081252 - 0.060263 -0.062864 - 0.027091 -0.042119 - 0.006819 -0.020381 - 0.000000 0.000000 \ No newline at end of file diff --git a/Test_Cases/MHK_RM1/Airfoils/NACA6_0276.dat b/Test_Cases/MHK_RM1/Airfoils/NACA6_0276.dat deleted file mode 100644 index 05644926..00000000 --- a/Test_Cases/MHK_RM1/Airfoils/NACA6_0276.dat +++ /dev/null @@ -1,560 +0,0 @@ -! ------------ AirfoilInfo v1.01.x Input File ---------------------------------- -! NACA6_0276 airfoil, data based on values used for the design of the RM1 tidal current turbine. -! line -! line -! ------------------------------------------------------------------------------ -"default" InterpOrd ! Interpolation order to use for quasi-steady table lookup {1=linear; 3=cubic spline; "default"} [default=1] - 1.0 NonDimArea ! The non-dimensional area of the airfoil (area/chord^2) (set to 1.0 if unsure or unneeded) -@"NACA6_0276_coords.txt" NumCoords ! The number of coordinates in the airfoil shape file. Set to zero if coordinates not included. -"unused" BL_file ! The file name including the boundary layer characteristics of the profile. Ignored if the aeroacoustic module is not called. - 7 NumTabs ! Number of airfoil tables in this file. -! ------------------------------------------------------------------------------ -! data for table 1 -! ------------------------------------------------------------------------------ - 2.000 Re ! Reynolds number in millions - 0 UserProp ! User property (control) setting -False InclUAdata ! Is unsteady aerodynamics data included in this table? If TRUE, then include 30 UA coefficients below this line -!........................................ -! Table of aerodynamics coefficients - 72 NumAlf ! Number of data lines in the following table -! Alpha Cl Cd Cpmin -! (deg) (-) (-) (-) - -180.000 0.0000 0.0237 -1.0947 - -170.000 0.2972 0.0237 -1.0947 - -160.000 0.5944 0.0815 -1.0947 - -150.000 0.8917 0.2455 -1.0947 - -140.000 0.7334 0.4476 -1.0947 - -130.000 0.6013 0.6637 -1.0947 - -120.000 0.4631 0.8690 -1.0947 - -110.000 0.3120 1.0395 -1.0947 - -100.000 0.1534 1.1557 -1.0947 - -90.000 0.0000 1.2050 -1.0947 - -80.000 -0.1534 1.1557 -1.0947 - -70.000 -0.3120 1.0395 -1.0947 - -60.000 -0.4631 0.8690 -1.0947 - -50.000 -0.6013 0.6637 -1.0947 - -40.000 -0.7334 0.4476 -1.0947 - -30.000 -0.8917 0.2455 -1.0947 - -20.000 -0.6461 0.1386 -1.0947 - -10.000 -0.5722 0.0316 -2.3958 - -9.000 -0.5433 0.0285 -2.1764 - -8.000 -0.5145 0.0260 -1.9643 - -7.000 -0.4633 0.0248 -1.7200 - -6.000 -0.3726 0.0238 -1.4829 - -5.000 -0.2695 0.0231 -1.2946 - -4.000 -0.1619 0.0224 -1.1182 - -3.000 -0.0521 0.0215 -1.0047 - -2.000 0.0639 0.0213 -1.0040 - -1.000 0.1795 0.0212 -1.0841 - 0.000 0.2946 0.0213 -1.1688 - 1.000 0.4103 0.0213 -1.2561 - 2.000 0.5242 0.0215 -1.3432 - 3.000 0.6361 0.0216 -1.4336 - 4.000 0.7437 0.0220 -1.5246 - 5.000 0.8498 0.0224 -1.6245 - 6.000 0.9364 0.0235 -1.7280 - 7.000 0.9713 0.0251 -1.8062 - 8.000 1.0028 0.0273 -1.9267 - 9.000 1.0414 0.0300 -2.0719 - 10.000 1.0814 0.0333 -2.2235 - 11.000 1.0890 0.0389 -2.3357 - 12.000 1.1174 0.0440 -2.5748 - 13.000 1.1266 0.0516 -2.7784 - 14.000 1.1514 0.0584 -3.0308 - 15.000 1.1691 0.0666 -3.2770 - 16.000 1.1962 0.0746 -3.5677 - 17.000 1.2199 0.0833 -3.8669 - 18.000 1.2419 0.0928 -4.1831 - 19.000 1.2624 0.1028 -4.4997 - 20.000 1.2802 0.1136 -4.8265 - 21.000 1.2968 0.1246 -5.1610 - 22.000 1.3155 0.1353 -5.5203 - 23.000 1.3236 0.1477 -5.8461 - 24.000 1.3300 0.1602 -6.1673 - 25.000 1.3308 0.1732 -6.4703 - 26.000 1.3263 0.1870 -6.7296 - 28.000 1.3025 0.2154 -7.1066 - 29.000 1.2849 0.2312 -7.2022 - 30.000 1.2738 0.2455 -7.3200 - 40.000 1.0478 0.4476 -1.0947 - 50.000 0.8590 0.6637 -1.0947 - 60.000 0.6615 0.8690 -1.0947 - 70.000 0.4456 1.0395 -1.0947 - 80.000 0.2191 1.1557 -1.0947 - 90.000 0.0000 1.2050 -1.0947 - 100.000 -0.1534 1.1557 -1.0947 - 110.000 -0.3120 1.0395 -1.0947 - 120.000 -0.4631 0.8690 -1.0947 - 130.000 -0.6013 0.6637 -1.0947 - 140.000 -0.7334 0.4476 -1.0947 - 150.000 -0.8917 0.2455 -1.0947 - 160.000 -0.5944 0.0815 -1.0947 - 170.000 -0.2972 0.0237 -1.0947 - 180.000 0.0000 0.0237 -1.0947 -! ------------------------------------------------------------------------------ -! data for table 2 -! ------------------------------------------------------------------------------ - 4.000 Re ! Reynolds number in millions - 0 UserProp ! User property (control) setting -False InclUAdata ! Is unsteady aerodynamics data included in this table? If TRUE, then include 30 UA coefficients below this line -!........................................ -! Table of aerodynamics coefficients - 69 NumAlf ! Number of data lines in the following table -! Alpha Cl Cd Cpmin -! (deg) (-) (-) (-) - -180.000 0.0000 0.0413 -1.0947 - -170.000 0.3115 0.0413 -1.0947 - -160.000 0.6231 0.0877 -1.0947 - -150.000 0.9346 0.2526 -1.0947 - -140.000 0.7596 0.4558 -1.0947 - -130.000 0.6167 0.6734 -1.0947 - -120.000 0.4714 0.8804 -1.0947 - -110.000 0.3155 1.0529 -1.0947 - -100.000 0.1542 1.1712 -1.0947 - -90.000 0.0000 1.2225 -1.0947 - -80.000 -0.1542 1.1712 -1.0947 - -70.000 -0.3155 1.0529 -1.0947 - -60.000 -0.4714 0.8804 -1.0947 - -50.000 -0.6167 0.6734 -1.0947 - -40.000 -0.7596 0.4558 -1.0947 - -30.000 -0.9346 0.2526 -1.0947 - -20.000 -0.6829 0.1496 -1.0947 - -10.000 -0.6161 0.0466 -2.4883 - -9.000 -0.5712 0.0443 -2.2295 - -8.000 -0.5526 0.0423 -2.0298 - -7.000 -0.4716 0.0413 -1.7349 - -6.000 -0.3725 0.0405 -1.4832 - -5.000 -0.2677 0.0398 -1.2929 - -4.000 -0.1561 0.0394 -1.1123 - -3.000 -0.0432 0.0387 -0.9986 - -1.000 0.1888 0.0379 -1.0895 - 0.000 0.3061 0.0378 -1.1760 - 1.000 0.4213 0.0380 -1.2632 - 2.000 0.5378 0.0380 -1.3520 - 5.000 0.8552 0.0396 -1.6272 - 6.000 0.9306 0.0410 -1.7249 - 7.000 0.9823 0.0421 -1.8149 - 9.000 1.0790 0.0457 -2.1183 - 10.000 1.0980 0.0496 -2.2449 - 11.000 1.1311 0.0536 -2.4167 - 12.000 1.1458 0.0595 -2.6346 - 13.000 1.1730 0.0652 -2.8826 - 14.000 1.2004 0.0715 -3.1545 - 15.000 1.2328 0.0779 -3.4495 - 16.000 1.2590 0.0855 -3.7545 - 17.000 1.2859 0.0934 -4.0861 - 18.000 1.3082 0.1022 -4.4164 - 19.000 1.3304 0.1116 -4.7557 - 20.000 1.3446 0.1223 -5.0919 - 21.000 1.3594 0.1333 -5.4348 - 22.000 1.3722 0.1448 -5.7913 - 23.000 1.3765 0.1574 -6.1155 - 24.000 1.3896 0.1686 -6.5092 - 25.000 1.3903 0.1816 -6.8357 - 26.000 1.3909 0.1943 -7.1550 - 27.000 1.3872 0.2075 -7.4378 - 28.000 1.3796 0.2212 -7.6789 - 29.000 1.3509 0.2378 -7.7434 - 30.000 1.3352 0.2526 -7.8683 - 40.000 1.0851 0.4558 -1.0947 - 50.000 0.8811 0.6734 -1.0947 - 60.000 0.6733 0.8804 -1.0947 - 70.000 0.4507 1.0529 -1.0947 - 80.000 0.2203 1.1712 -1.0947 - 90.000 0.0000 1.2225 -1.0947 - 100.000 -0.1542 1.1712 -1.0947 - 110.000 -0.3155 1.0529 -1.0947 - 120.000 -0.4714 0.8804 -1.0947 - 130.000 -0.6167 0.6734 -1.0947 - 140.000 -0.7596 0.4558 -1.0947 - 150.000 -0.9346 0.2526 -1.0947 - 160.000 -0.6231 0.0877 -1.0947 - 170.000 -0.3115 0.0413 -1.0947 - 180.000 0.0000 0.0413 -1.0947 -! ------------------------------------------------------------------------------ -! data for table 3 -! ------------------------------------------------------------------------------ - 6.000 Re ! Reynolds number in millions - 0 UserProp ! User property (control) setting -False InclUAdata ! Is unsteady aerodynamics data included in this table? If TRUE, then include 30 UA coefficients below this line -!........................................ -! Table of aerodynamics coefficients - 71 NumAlf ! Number of data lines in the following table -! Alpha Cl Cd Cpmin -! (deg) (-) (-) (-) - -180.000 0.0000 0.0427 -1.0947 - -170.000 0.3231 0.0427 -1.0947 - -160.000 0.6463 0.0804 -1.0947 - -150.000 0.9694 0.2461 -1.0947 - -140.000 0.7808 0.4501 -1.0947 - -130.000 0.6292 0.6689 -1.0947 - -120.000 0.4780 0.8773 -1.0947 - -110.000 0.3184 1.0511 -1.0947 - -100.000 0.1550 1.1711 -1.0947 - -90.000 0.0000 1.2239 -1.0947 - -80.000 -0.1550 1.1711 -1.0947 - -70.000 -0.3184 1.0511 -1.0947 - -60.000 -0.4780 0.8773 -1.0947 - -50.000 -0.6292 0.6689 -1.0947 - -40.000 -0.7808 0.4501 -1.0947 - -30.000 -0.9694 0.2461 -1.0947 - -20.000 -0.7092 0.1463 -1.0947 - -10.000 -0.6414 0.0466 -2.5416 - -9.000 -0.6012 0.0445 -2.2848 - -8.000 -0.5628 0.0432 -2.0477 - -7.000 -0.4732 0.0423 -1.7376 - -6.000 -0.3741 0.0415 -1.4857 - -5.000 -0.2657 0.0409 -1.2907 - -4.000 -0.1535 0.0405 -1.1092 - -3.000 -0.0399 0.0400 -0.9966 - -2.000 0.0755 0.0393 -1.0106 - -1.000 0.1929 0.0390 -1.0920 - 0.000 0.3100 0.0390 -1.1782 - 1.000 0.4277 0.0390 -1.2673 - 2.000 0.5413 0.0393 -1.3545 - 4.000 0.7589 0.0401 -1.5387 - 5.000 0.8522 0.0412 -1.6269 - 6.000 0.9337 0.0423 -1.7204 - 7.000 0.9951 0.0432 -1.8277 - 8.000 1.0541 0.0443 -1.9823 - 9.000 1.0870 0.0467 -2.1278 - 10.000 1.1218 0.0498 -2.2774 - 11.000 1.1445 0.0541 -2.4431 - 12.000 1.1732 0.0589 -2.6923 - 13.000 1.1989 0.0645 -2.9418 - 14.000 1.2353 0.0700 -3.2423 - 15.000 1.2640 0.0765 -3.5369 - 16.000 1.2923 0.0836 -3.8535 - 17.000 1.3183 0.0914 -4.1926 - 19.000 1.3602 0.1094 -4.8697 - 20.000 1.3915 0.1176 -5.2827 - 21.000 1.4032 0.1286 -5.6231 - 22.000 1.4106 0.1406 -5.9723 - 23.000 1.4149 0.1531 -6.3138 - 24.000 1.4210 0.1654 -6.6853 - 25.000 1.4236 0.1780 -7.0348 - 26.000 1.4211 0.1910 -7.3486 - 27.000 1.4145 0.2046 -7.6241 - 28.000 1.4066 0.2183 -7.8765 - 29.000 1.3970 0.2320 -8.1002 - 30.000 1.3848 0.2461 -8.2820 - 40.000 1.1153 0.4501 -1.0947 - 50.000 0.8989 0.6689 -1.0947 - 60.000 0.6829 0.8773 -1.0947 - 70.000 0.4549 1.0511 -1.0947 - 80.000 0.2214 1.1711 -1.0947 - 90.000 0.0000 1.2239 -1.0947 - 100.000 -0.1550 1.1711 -1.0947 - 110.000 -0.3184 1.0511 -1.0947 - 120.000 -0.4780 0.8773 -1.0947 - 130.000 -0.6292 0.6689 -1.0947 - 140.000 -0.7808 0.4501 -1.0947 - 150.000 -0.9694 0.2461 -1.0947 - 160.000 -0.6463 0.0804 -1.0947 - 170.000 -0.3231 0.0427 -1.0947 - 180.000 0.0000 0.0427 -1.0947 -! ------------------------------------------------------------------------------ -! data for table 4 -! ------------------------------------------------------------------------------ - 8.000 Re ! Reynolds number in millions - 0 UserProp ! User property (control) setting -False InclUAdata ! Is unsteady aerodynamics data included in this table? If TRUE, then include 30 UA coefficients below this line -!........................................ -! Table of aerodynamics coefficients - 62 NumAlf ! Number of data lines in the following table -! Alpha Cl Cd Cpmin -! (deg) (-) (-) (-) - -180.000 0.0000 0.0427 -1.0947 - -170.000 0.3872 0.0427 -1.0947 - -160.000 0.7745 0.0957 -1.0947 - -150.000 0.9131 0.2601 -1.0947 - -140.000 0.7465 0.4626 -1.0947 - -130.000 0.6090 0.6794 -1.0947 - -120.000 0.4672 0.8854 -1.0947 - -110.000 0.3137 1.0567 -1.0947 - -100.000 0.1539 1.1738 -1.0947 - -90.000 0.0000 1.2239 -1.0947 - -80.000 -0.1539 1.1738 -1.0947 - -70.000 -0.3137 1.0567 -1.0947 - -60.000 -0.4672 0.8854 -1.0947 - -50.000 -0.6090 0.6794 -1.0947 - -40.000 -0.7465 0.4626 -1.0947 - -30.000 -0.9131 0.2601 -1.0947 - -20.000 -0.8002 0.1351 -1.0947 - -10.000 -0.6511 0.0461 -2.5695 - -9.000 -0.6241 0.0436 -2.3279 - -8.000 -0.5706 0.0427 -2.0616 - -5.000 -0.2653 0.0407 -1.2901 - -4.000 -0.1529 0.0402 -1.1086 - -3.000 -0.0377 0.0398 -0.9859 - -2.000 0.0776 0.0393 -1.0119 - -1.000 0.1949 0.0389 -1.0929 - 0.000 0.3132 0.0388 -1.1803 - 1.000 0.4292 0.0388 -1.2680 - 2.000 0.5426 0.0391 -1.3559 - 3.000 0.6544 0.0394 -1.4464 - 4.000 0.7581 0.0402 -1.5294 - 6.000 0.9397 0.0421 -1.7194 - 7.000 1.0132 0.0428 -1.8437 - 8.000 1.0686 0.0438 -1.9993 - 9.000 1.0986 0.0462 -2.1424 - 11.000 1.1565 0.0534 -2.4664 - 12.000 1.1929 0.0575 -2.7339 - 13.000 1.2310 0.0621 -3.0185 - 15.000 1.2979 0.0735 -3.6316 - 16.000 1.3263 0.0802 -3.9577 - 17.000 1.3551 0.0875 -4.3142 - 18.000 1.3747 0.0960 -4.6477 - 19.000 1.3968 0.1049 -5.0108 - 20.000 1.4117 0.1151 -5.3642 - 22.000 1.4284 0.1382 -6.0547 - 25.000 1.4397 0.1756 -7.1298 - 26.000 1.4383 0.1885 -7.4558 - 30.000 1.3044 0.2601 -6.0291 - 40.000 1.0665 0.4626 -1.0947 - 50.000 0.8700 0.6794 -1.0947 - 60.000 0.6674 0.8854 -1.0947 - 70.000 0.4482 1.0567 -1.0947 - 80.000 0.2198 1.1738 -1.0947 - 90.000 0.0000 1.2239 -1.0947 - 100.000 -0.1539 1.1738 -1.0947 - 110.000 -0.3137 1.0567 -1.0947 - 120.000 -0.4672 0.8854 -1.0947 - 130.000 -0.6090 0.6794 -1.0947 - 140.000 -0.7465 0.4626 -1.0947 - 150.000 -0.9131 0.2601 -1.0947 - 160.000 -0.7745 0.0957 -1.0947 - 170.000 -0.3872 0.0427 -1.0947 - 180.000 0.0000 0.0427 -1.0947 -! ------------------------------------------------------------------------------ -! data for table 5 -! ------------------------------------------------------------------------------ - 10.000 Re ! Reynolds number in millions - 0 UserProp ! User property (control) setting -False InclUAdata ! Is unsteady aerodynamics data included in this table? If TRUE, then include 30 UA coefficients below this line -!........................................ -! Table of aerodynamics coefficients - 67 NumAlf ! Number of data lines in the following table -! Alpha Cl Cd Cpmin -! (deg) (-) (-) (-) - -180.000 0.0000 0.0427 -1.0947 - -170.000 0.3342 0.0427 -1.0947 - -160.000 0.6685 0.0713 -1.0947 - -150.000 1.0026 0.2377 -1.0947 - -140.000 0.8010 0.4427 -1.0947 - -130.000 0.6412 0.6628 -1.0947 - -120.000 0.4844 0.8724 -1.0947 - -110.000 0.3211 1.0478 -1.0947 - -100.000 0.1557 1.1694 -1.0947 - -90.000 0.0000 1.2239 -1.0947 - -80.000 -0.1557 1.1694 -1.0947 - -70.000 -0.3211 1.0478 -1.0947 - -60.000 -0.4844 0.8724 -1.0947 - -50.000 -0.6412 0.6628 -1.0947 - -40.000 -0.8010 0.4427 -1.0947 - -30.000 -1.0026 0.2377 -1.0947 - -20.000 -0.7284 0.1419 -1.0947 - -10.000 -0.6488 0.0460 -2.5468 - -9.000 -0.6526 0.0433 -2.3850 - -8.000 -0.5774 0.0424 -2.0737 - -6.000 -0.3754 0.0410 -1.4897 - -4.000 -0.1520 0.0400 -1.1078 - -3.000 -0.0370 0.0397 -0.9872 - -2.000 0.0791 0.0393 -1.0126 - -1.000 0.1969 0.0388 -1.0942 - 0.000 0.3146 0.0387 -1.1810 - 1.000 0.4298 0.0388 -1.2686 - 2.000 0.5430 0.0391 -1.3579 - 4.000 0.7562 0.0403 -1.5250 - 5.000 0.8507 0.0413 -1.6163 - 6.000 0.9427 0.0420 -1.7254 - 7.000 1.0329 0.0426 -1.8611 - 8.000 1.0750 0.0437 -2.0065 - 9.000 1.1141 0.0456 -2.1622 - 10.000 1.1311 0.0493 -2.2748 - 11.000 1.1766 0.0523 -2.5065 - 12.000 1.2105 0.0564 -2.7712 - 13.000 1.2474 0.0610 -3.0573 - 14.000 1.2841 0.0660 -3.3650 - 16.000 1.3463 0.0784 -4.0198 - 17.000 1.3700 0.0859 -4.3625 - 18.000 1.3938 0.0940 -4.7136 - 19.000 1.4123 0.1031 -5.0694 - 20.000 1.4262 0.1133 -5.4224 - 21.000 1.4334 0.1246 -5.7546 - 24.000 1.4704 0.1580 -6.9565 - 25.000 1.4739 0.1702 -7.3296 - 26.000 1.4743 0.1829 -7.6801 - 27.000 1.4705 0.1958 -7.9975 - 28.000 1.4611 0.2093 -8.2673 - 29.000 1.4477 0.2234 -8.4899 - 30.000 1.4324 0.2377 -8.6765 - 40.000 1.1443 0.4427 -1.0947 - 50.000 0.9160 0.6628 -1.0947 - 60.000 0.6921 0.8724 -1.0947 - 70.000 0.4588 1.0478 -1.0947 - 80.000 0.2223 1.1694 -1.0947 - 90.000 0.0000 1.2239 -1.0947 - 100.000 -0.1557 1.1694 -1.0947 - 110.000 -0.3211 1.0478 -1.0947 - 120.000 -0.4844 0.8724 -1.0947 - 130.000 -0.6412 0.6628 -1.0947 - 140.000 -0.8010 0.4427 -1.0947 - 150.000 -1.0026 0.2377 -1.0947 - 160.000 -0.6685 0.0713 -1.0947 - 170.000 -0.3342 0.0427 -1.0947 - 180.000 0.0000 0.0427 -1.0947 -! ------------------------------------------------------------------------------ -! data for table 6 -! ------------------------------------------------------------------------------ - 12.000 Re ! Reynolds number in millions - 0 UserProp ! User property (control) setting -False InclUAdata ! Is unsteady aerodynamics data included in this table? If TRUE, then include 30 UA coefficients below this line -!........................................ -! Table of aerodynamics coefficients - 68 NumAlf ! Number of data lines in the following table -! Alpha Cl Cd Cpmin -! (deg) (-) (-) (-) - -180.000 0.0000 0.0427 -1.0947 - -170.000 0.3520 0.0427 -1.0947 - -160.000 0.7039 0.0744 -1.0947 - -150.000 0.9952 0.2405 -1.0947 - -140.000 0.7965 0.4453 -1.0947 - -130.000 0.6385 0.6648 -1.0947 - -120.000 0.4830 0.8740 -1.0947 - -110.000 0.3206 1.0489 -1.0947 - -100.000 0.1555 1.1699 -1.0947 - -90.000 0.0000 1.2239 -1.0947 - -80.000 -0.1555 1.1699 -1.0947 - -70.000 -0.3206 1.0489 -1.0947 - -60.000 -0.4830 0.8740 -1.0947 - -50.000 -0.6385 0.6648 -1.0947 - -40.000 -0.7965 0.4453 -1.0947 - -30.000 -0.9952 0.2405 -1.0947 - -20.000 -0.7566 0.1382 -1.0947 - -10.000 -0.6615 0.0454 -2.5749 - -7.000 -0.4812 0.0415 -1.7511 - -6.000 -0.3745 0.0410 -1.4789 - -5.000 -0.2649 0.0403 -1.2901 - -4.000 -0.1519 0.0399 -1.1074 - -3.000 -0.0361 0.0396 -0.9899 - -2.000 0.0806 0.0393 -1.0134 - -1.000 0.1980 0.0387 -1.0949 - 0.000 0.3153 0.0387 -1.1812 - 1.000 0.4305 0.0387 -1.2694 - 2.000 0.5438 0.0390 -1.3540 - 3.000 0.6538 0.0394 -1.4370 - 4.000 0.7567 0.0402 -1.5286 - 5.000 0.8514 0.0412 -1.6190 - 6.000 0.9493 0.0417 -1.7316 - 7.000 1.0402 0.0424 -1.8683 - 8.000 1.0816 0.0435 -2.0142 - 10.000 1.1457 0.0485 -2.2994 - 11.000 1.1887 0.0516 -2.5309 - 12.000 1.2299 0.0553 -2.8127 - 13.000 1.2688 0.0595 -3.1081 - 14.000 1.2973 0.0651 -3.3981 - 15.000 1.3297 0.0708 -3.7201 - 17.000 1.3841 0.0846 -4.4087 - 18.000 1.4065 0.0927 -4.7570 - 19.000 1.4248 0.1017 -5.1168 - 20.000 1.4340 0.1123 -5.4530 - 22.000 1.4727 0.1319 -6.2606 - 23.000 1.4802 0.1438 -6.6509 - 24.000 1.4856 0.1558 -7.0399 - 25.000 1.4882 0.1682 -7.4120 - 26.000 1.4872 0.1810 -7.7597 - 27.000 1.4803 0.1942 -8.0622 - 28.000 1.4702 0.2080 -8.3300 - 29.000 1.4581 0.2218 -8.5675 - 30.000 1.4218 0.2405 -8.1097 - 40.000 1.1378 0.4453 -1.0947 - 50.000 0.9121 0.6648 -1.0947 - 60.000 0.6900 0.8740 -1.0947 - 70.000 0.4579 1.0489 -1.0947 - 80.000 0.2222 1.1699 -1.0947 - 90.000 0.0000 1.2239 -1.0947 - 100.000 -0.1555 1.1699 -1.0947 - 110.000 -0.3206 1.0489 -1.0947 - 120.000 -0.4830 0.8740 -1.0947 - 130.000 -0.6385 0.6648 -1.0947 - 140.000 -0.7965 0.4453 -1.0947 - 150.000 -0.9952 0.2405 -1.0947 - 160.000 -0.7039 0.0744 -1.0947 - 170.000 -0.3520 0.0427 -1.0947 - 180.000 0.0000 0.0427 -1.0947 -! ------------------------------------------------------------------------------ -! data for table 7 -! ------------------------------------------------------------------------------ - 14.000 Re ! Reynolds number in millions - 0 UserProp ! User property (control) setting -False InclUAdata ! Is unsteady aerodynamics data included in this table? If TRUE, then include 30 UA coefficients below this line -!........................................ -! Table of aerodynamics coefficients - 64 NumAlf ! Number of data lines in the following table -! Alpha Cl Cd Cpmin -! (deg) (-) (-) (-) - -180.000 0.0000 0.0427 -1.0947 - -170.000 0.3392 0.0427 -1.0947 - -160.000 0.6784 0.0675 -1.0947 - -150.000 1.0176 0.2342 -1.0947 - -140.000 0.8101 0.4396 -1.0947 - -130.000 0.6466 0.6602 -1.0947 - -120.000 0.4873 0.8704 -1.0947 - -110.000 0.3224 1.0465 -1.0947 - -100.000 0.1559 1.1686 -1.0947 - -90.000 0.0000 1.2239 -1.0947 - -80.000 -0.1559 1.1686 -1.0947 - -70.000 -0.3224 1.0465 -1.0947 - -60.000 -0.4873 0.8704 -1.0947 - -50.000 -0.6466 0.6602 -1.0947 - -40.000 -0.8101 0.4396 -1.0947 - -30.000 -1.0176 0.2342 -1.0947 - -20.000 -0.7448 0.1396 -1.0947 - -10.000 -0.6743 0.0450 -2.6018 - -9.000 -0.6556 0.0432 -2.3780 - -8.000 -0.5837 0.0419 -2.0858 - -6.000 -0.3744 0.0409 -1.4766 - -5.000 -0.2648 0.0402 -1.2898 - -4.000 -0.1518 0.0397 -1.1073 - -3.000 -0.0353 0.0395 -0.9902 - -2.000 0.0816 0.0392 -1.0140 - -1.000 0.1984 0.0387 -1.0951 - 0.000 0.3163 0.0386 -1.1820 - 1.000 0.4294 0.0388 -1.2695 - 2.000 0.5437 0.0390 -1.3533 - 3.000 0.6525 0.0395 -1.4353 - 5.000 0.8543 0.0411 -1.6221 - 6.000 0.9522 0.0417 -1.7348 - 7.000 1.0473 0.0422 -1.8753 - 8.000 1.0856 0.0434 -2.0185 - 11.000 1.1998 0.0511 -2.5530 - 12.000 1.2410 0.0546 -2.8360 - 14.000 1.3174 0.0635 -3.4485 - 16.000 1.3700 0.0763 -4.0931 - 18.000 1.4171 0.0916 -4.7936 - 21.000 1.4744 0.1193 -5.9336 - 22.000 1.4840 0.1304 -6.3121 - 23.000 1.4926 0.1420 -6.7143 - 24.000 1.4971 0.1541 -7.1018 - 25.000 1.4986 0.1667 -7.4716 - 26.000 1.4943 0.1799 -7.8035 - 27.000 1.4875 0.1932 -8.1091 - 28.000 1.4786 0.2066 -8.3887 - 29.000 1.4676 0.2203 -8.6380 - 30.000 1.4537 0.2342 -8.8479 - 40.000 1.1573 0.4396 -1.0947 - 50.000 0.9237 0.6602 -1.0947 - 60.000 0.6962 0.8704 -1.0947 - 70.000 0.4606 1.0465 -1.0947 - 80.000 0.2228 1.1686 -1.0947 - 90.000 0.0000 1.2239 -1.0947 - 100.000 -0.1559 1.1686 -1.0947 - 110.000 -0.3224 1.0465 -1.0947 - 120.000 -0.4873 0.8704 -1.0947 - 130.000 -0.6466 0.6602 -1.0947 - 140.000 -0.8101 0.4396 -1.0947 - 150.000 -1.0176 0.2342 -1.0947 - 160.000 -0.6784 0.0675 -1.0947 - 170.000 -0.3392 0.0427 -1.0947 - 180.000 0.0000 0.0427 -1.0947 \ No newline at end of file diff --git a/Test_Cases/MHK_RM1/Airfoils/NACA6_0276_coords.txt b/Test_Cases/MHK_RM1/Airfoils/NACA6_0276_coords.txt deleted file mode 100644 index c2553444..00000000 --- a/Test_Cases/MHK_RM1/Airfoils/NACA6_0276_coords.txt +++ /dev/null @@ -1,47 +0,0 @@ - 40 NumCoords ! The number of coordinates in the airfoil shape file (including an extra coordinate for airfoil reference). Set to zero if coordinates not included. -! ......... x-y coordinates are next if NumCoords > 0 ............. -! x-y coordinate of airfoil reference -! x/c y/c - 0.25 0 -! coordinates of airfoil shape -! NACA6_0276 Airfoil -! x/c y/c - 0.000000 0.000000 - 0.006819 0.024017 - 0.027091 0.050261 - 0.060263 0.077244 - 0.105430 0.102168 - 0.161359 0.123903 - 0.226526 0.140948 - 0.299152 0.151887 - 0.377257 0.154763 - 0.458710 0.148989 - 0.541290 0.136081 - 0.622743 0.118030 - 0.700848 0.097075 - 0.773474 0.075618 - 0.838641 0.055666 - 0.894570 0.038477 - 0.939737 0.024535 - 0.972909 0.013769 - 0.993181 0.005721 - 1.000000 0.000000 - 0.993181 -0.003319 - 0.972909 -0.006500 - 0.939737 -0.011272 - 0.894570 -0.018909 - 0.838641 -0.030129 - 0.773474 -0.044953 - 0.700848 -0.062630 - 0.622743 -0.081432 - 0.541290 -0.099052 - 0.458710 -0.113095 - 0.377257 -0.121217 - 0.299152 -0.121652 - 0.226526 -0.115046 - 0.161359 -0.102964 - 0.105430 -0.086660 - 0.060263 -0.067057 - 0.027091 -0.044998 - 0.006819 -0.021867 - 0.000000 0.000000 \ No newline at end of file diff --git a/Test_Cases/MHK_RM1/Airfoils/NACA6_0329.dat b/Test_Cases/MHK_RM1/Airfoils/NACA6_0329.dat deleted file mode 100644 index b975b05e..00000000 --- a/Test_Cases/MHK_RM1/Airfoils/NACA6_0329.dat +++ /dev/null @@ -1,560 +0,0 @@ -! ------------ AirfoilInfo v1.01.x Input File ---------------------------------- -! NACA6_0329 airfoil, data based on values used for the design of the RM1 tidal current turbine. -! line -! line -! ------------------------------------------------------------------------------ -"default" InterpOrd ! Interpolation order to use for quasi-steady table lookup {1=linear; 3=cubic spline; "default"} [default=1] - 1.0 NonDimArea ! The non-dimensional area of the airfoil (area/chord^2) (set to 1.0 if unsure or unneeded) -@"NACA6_0329_coords.txt" NumCoords ! The number of coordinates in the airfoil shape file. Set to zero if coordinates not included. -"unused" BL_file ! The file name including the boundary layer characteristics of the profile. Ignored if the aeroacoustic module is not called. - 7 NumTabs ! Number of airfoil tables in this file. -! ------------------------------------------------------------------------------ -! data for table 1 -! ------------------------------------------------------------------------------ - 2.000 Re ! Reynolds number in millions - 0 UserProp ! User property (control) setting -False InclUAdata ! Is unsteady aerodynamics data included in this table? If TRUE, then include 30 UA coefficients below this line -!........................................ -! Table of aerodynamics coefficients - 72 NumAlf ! Number of data lines in the following table -! Alpha Cl Cd Cpmin -! (deg) (-) (-) (-) - -180.000 0.0000 0.0440 -1.2342 - -170.000 0.2755 0.0440 -1.2342 - -160.000 0.5509 0.0975 -1.2342 - -150.000 0.8264 0.2495 -1.2342 - -140.000 0.6797 0.4368 -1.2342 - -130.000 0.5573 0.6371 -1.2342 - -120.000 0.4292 0.8274 -1.2342 - -110.000 0.2891 0.9854 -1.2342 - -100.000 0.1421 1.0931 -1.2342 - -90.000 0.0000 1.1387 -1.2342 - -80.000 -0.1421 1.0931 -1.2342 - -70.000 -0.2891 0.9854 -1.2342 - -60.000 -0.4292 0.8274 -1.2342 - -50.000 -0.5573 0.6371 -1.2342 - -40.000 -0.6797 0.4368 -1.2342 - -30.000 -0.8264 0.2495 -1.2342 - -20.000 -0.5988 0.1504 -1.2342 - -10.000 -0.5303 0.0513 -2.4401 - -9.000 -0.5035 0.0484 -2.2366 - -8.000 -0.4769 0.0461 -2.0401 - -7.000 -0.4294 0.0449 -1.8137 - -6.000 -0.3453 0.0440 -1.5940 - -5.000 -0.2498 0.0433 -1.4194 - -4.000 -0.1500 0.0427 -1.2559 - -3.000 -0.0483 0.0418 -1.1508 - -2.000 0.0592 0.0417 -1.1501 - -1.000 0.1663 0.0416 -1.2243 - 0.000 0.2730 0.0417 -1.3028 - 1.000 0.3803 0.0417 -1.3838 - 2.000 0.4859 0.0418 -1.4645 - 3.000 0.5895 0.0420 -1.5483 - 4.000 0.6893 0.0424 -1.6326 - 5.000 0.7876 0.0427 -1.7252 - 6.000 0.8679 0.0437 -1.8212 - 7.000 0.9002 0.0452 -1.8936 - 8.000 0.9294 0.0472 -2.0052 - 9.000 0.9652 0.0498 -2.1398 - 10.000 1.0023 0.0528 -2.2804 - 11.000 1.0093 0.0580 -2.3844 - 12.000 1.0356 0.0628 -2.6060 - 13.000 1.0441 0.0697 -2.7946 - 14.000 1.0672 0.0761 -3.0285 - 15.000 1.0835 0.0837 -3.2567 - 16.000 1.1087 0.0911 -3.5261 - 17.000 1.1306 0.0991 -3.8034 - 18.000 1.1510 0.1080 -4.0965 - 19.000 1.1700 0.1172 -4.3899 - 20.000 1.1865 0.1272 -4.6928 - 21.000 1.2019 0.1375 -5.0028 - 22.000 1.2192 0.1473 -5.3358 - 23.000 1.2267 0.1588 -5.6377 - 24.000 1.2326 0.1704 -5.9354 - 25.000 1.2334 0.1825 -6.2163 - 26.000 1.2292 0.1953 -6.4566 - 28.000 1.2072 0.2216 -6.8060 - 29.000 1.1908 0.2363 -6.8946 - 30.000 1.1805 0.2495 -7.0038 - 40.000 0.9711 0.4368 -1.2342 - 50.000 0.7961 0.6371 -1.2342 - 60.000 0.6131 0.8274 -1.2342 - 70.000 0.4130 0.9854 -1.2342 - 80.000 0.2031 1.0931 -1.2342 - 90.000 0.0000 1.1387 -1.2342 - 100.000 -0.1421 1.0931 -1.2342 - 110.000 -0.2891 0.9854 -1.2342 - 120.000 -0.4292 0.8274 -1.2342 - 130.000 -0.5573 0.6371 -1.2342 - 140.000 -0.6797 0.4368 -1.2342 - 150.000 -0.8264 0.2495 -1.2342 - 160.000 -0.5509 0.0975 -1.2342 - 170.000 -0.2755 0.0440 -1.2342 - 180.000 0.0000 0.0440 -1.2342 -! ------------------------------------------------------------------------------ -! data for table 2 -! ------------------------------------------------------------------------------ - 4.000 Re ! Reynolds number in millions - 0 UserProp ! User property (control) setting -False InclUAdata ! Is unsteady aerodynamics data included in this table? If TRUE, then include 30 UA coefficients below this line -!........................................ -! Table of aerodynamics coefficients - 69 NumAlf ! Number of data lines in the following table -! Alpha Cl Cd Cpmin -! (deg) (-) (-) (-) - -180.000 0.0000 0.0873 -1.2342 - -170.000 0.2887 0.0873 -1.2342 - -160.000 0.5775 0.1303 -1.2342 - -150.000 0.8662 0.2831 -1.2342 - -140.000 0.7040 0.4714 -1.2342 - -130.000 0.5716 0.6732 -1.2342 - -120.000 0.4369 0.8650 -1.2342 - -110.000 0.2924 1.0248 -1.2342 - -100.000 0.1429 1.1345 -1.2342 - -90.000 0.0000 1.1821 -1.2342 - -80.000 -0.1429 1.1345 -1.2342 - -70.000 -0.2924 1.0248 -1.2342 - -60.000 -0.4369 0.8650 -1.2342 - -50.000 -0.5716 0.6732 -1.2342 - -40.000 -0.7040 0.4714 -1.2342 - -30.000 -0.8662 0.2831 -1.2342 - -20.000 -0.6329 0.1877 -1.2342 - -10.000 -0.5710 0.0922 -2.5258 - -9.000 -0.5294 0.0901 -2.2859 - -8.000 -0.5122 0.0883 -2.1009 - -7.000 -0.4370 0.0873 -1.8275 - -6.000 -0.3452 0.0866 -1.5943 - -5.000 -0.2481 0.0860 -1.4179 - -4.000 -0.1447 0.0855 -1.2505 - -3.000 -0.0401 0.0849 -1.1451 - -1.000 0.1750 0.0842 -1.2294 - 0.000 0.2837 0.0841 -1.3095 - 1.000 0.3905 0.0843 -1.3903 - 2.000 0.4984 0.0843 -1.4727 - 5.000 0.7926 0.0858 -1.7277 - 6.000 0.8625 0.0870 -1.8182 - 7.000 0.9104 0.0881 -1.9017 - 9.000 1.0001 0.0914 -2.1829 - 10.000 1.0176 0.0951 -2.3002 - 11.000 1.0483 0.0988 -2.4594 - 12.000 1.0619 0.1042 -2.6613 - 13.000 1.0871 0.1095 -2.8912 - 14.000 1.1125 0.1153 -3.1432 - 15.000 1.1426 0.1213 -3.4165 - 16.000 1.1668 0.1283 -3.6993 - 17.000 1.1917 0.1356 -4.0066 - 18.000 1.2125 0.1438 -4.3127 - 19.000 1.2331 0.1524 -4.6272 - 20.000 1.2462 0.1624 -4.9387 - 21.000 1.2599 0.1726 -5.2566 - 22.000 1.2717 0.1833 -5.5870 - 23.000 1.2757 0.1949 -5.8874 - 24.000 1.2879 0.2053 -6.2523 - 25.000 1.2885 0.2173 -6.5549 - 26.000 1.2891 0.2291 -6.8508 - 27.000 1.2857 0.2414 -7.1130 - 28.000 1.2786 0.2541 -7.3364 - 29.000 1.2520 0.2694 -7.3962 - 30.000 1.2375 0.2831 -7.5119 - 40.000 1.0057 0.4714 -1.2342 - 50.000 0.8166 0.6732 -1.2342 - 60.000 0.6240 0.8650 -1.2342 - 70.000 0.4177 1.0248 -1.2342 - 80.000 0.2042 1.1345 -1.2342 - 90.000 0.0000 1.1821 -1.2342 - 100.000 -0.1429 1.1345 -1.2342 - 110.000 -0.2924 1.0248 -1.2342 - 120.000 -0.4369 0.8650 -1.2342 - 130.000 -0.5716 0.6732 -1.2342 - 140.000 -0.7040 0.4714 -1.2342 - 150.000 -0.8662 0.2831 -1.2342 - 160.000 -0.5775 0.1303 -1.2342 - 170.000 -0.2887 0.0873 -1.2342 - 180.000 0.0000 0.0873 -1.2342 -! ------------------------------------------------------------------------------ -! data for table 3 -! ------------------------------------------------------------------------------ - 6.000 Re ! Reynolds number in millions - 0 UserProp ! User property (control) setting -False InclUAdata ! Is unsteady aerodynamics data included in this table? If TRUE, then include 30 UA coefficients below this line -!........................................ -! Table of aerodynamics coefficients - 71 NumAlf ! Number of data lines in the following table -! Alpha Cl Cd Cpmin -! (deg) (-) (-) (-) - -180.000 0.0000 0.0908 -1.2342 - -170.000 0.2995 0.0908 -1.2342 - -160.000 0.5990 0.1258 -1.2342 - -150.000 0.8984 0.2793 -1.2342 - -140.000 0.7236 0.4684 -1.2342 - -130.000 0.5832 0.6712 -1.2342 - -120.000 0.4430 0.8643 -1.2342 - -110.000 0.2951 1.0254 -1.2342 - -100.000 0.1436 1.1366 -1.2342 - -90.000 0.0000 1.1856 -1.2342 - -80.000 -0.1436 1.1366 -1.2342 - -70.000 -0.2951 1.0254 -1.2342 - -60.000 -0.4430 0.8643 -1.2342 - -50.000 -0.5832 0.6712 -1.2342 - -40.000 -0.7236 0.4684 -1.2342 - -30.000 -0.8984 0.2793 -1.2342 - -20.000 -0.6573 0.1869 -1.2342 - -10.000 -0.5945 0.0944 -2.5752 - -9.000 -0.5572 0.0925 -2.3371 - -8.000 -0.5216 0.0912 -2.1174 - -7.000 -0.4385 0.0904 -1.8300 - -6.000 -0.3467 0.0897 -1.5966 - -5.000 -0.2462 0.0891 -1.4158 - -4.000 -0.1422 0.0888 -1.2476 - -3.000 -0.0370 0.0883 -1.1433 - -2.000 0.0700 0.0876 -1.1563 - -1.000 0.1788 0.0874 -1.2317 - 0.000 0.2873 0.0874 -1.3116 - 1.000 0.3964 0.0874 -1.3941 - 2.000 0.5017 0.0876 -1.4750 - 4.000 0.7033 0.0884 -1.6456 - 5.000 0.7898 0.0894 -1.7274 - 6.000 0.8653 0.0904 -1.8141 - 7.000 0.9223 0.0912 -1.9135 - 8.000 0.9769 0.0923 -2.0568 - 9.000 1.0075 0.0945 -2.1916 - 10.000 1.0397 0.0974 -2.3303 - 11.000 1.0607 0.1014 -2.4839 - 12.000 1.0873 0.1058 -2.7148 - 13.000 1.1111 0.1110 -2.9461 - 14.000 1.1448 0.1161 -3.2245 - 15.000 1.1715 0.1221 -3.4976 - 16.000 1.1977 0.1287 -3.7910 - 17.000 1.2217 0.1359 -4.1053 - 19.000 1.2606 0.1526 -4.7329 - 20.000 1.2896 0.1602 -5.1156 - 21.000 1.3005 0.1704 -5.4311 - 22.000 1.3073 0.1816 -5.7547 - 23.000 1.3114 0.1931 -6.0712 - 24.000 1.3170 0.2045 -6.4155 - 25.000 1.3194 0.2162 -6.7394 - 26.000 1.3171 0.2283 -7.0302 - 27.000 1.3109 0.2409 -7.2856 - 28.000 1.3036 0.2535 -7.5195 - 29.000 1.2948 0.2662 -7.7268 - 30.000 1.2835 0.2793 -7.8953 - 40.000 1.0337 0.4684 -1.2342 - 50.000 0.8331 0.6712 -1.2342 - 60.000 0.6329 0.8643 -1.2342 - 70.000 0.4216 1.0254 -1.2342 - 80.000 0.2052 1.1366 -1.2342 - 90.000 0.0000 1.1856 -1.2342 - 100.000 -0.1436 1.1366 -1.2342 - 110.000 -0.2951 1.0254 -1.2342 - 120.000 -0.4430 0.8643 -1.2342 - 130.000 -0.5832 0.6712 -1.2342 - 140.000 -0.7236 0.4684 -1.2342 - 150.000 -0.8984 0.2793 -1.2342 - 160.000 -0.5990 0.1258 -1.2342 - 170.000 -0.2995 0.0908 -1.2342 - 180.000 0.0000 0.0908 -1.2342 -! ------------------------------------------------------------------------------ -! data for table 4 -! ------------------------------------------------------------------------------ - 8.000 Re ! Reynolds number in millions - 0 UserProp ! User property (control) setting -False InclUAdata ! Is unsteady aerodynamics data included in this table? If TRUE, then include 30 UA coefficients below this line -!........................................ -! Table of aerodynamics coefficients - 62 NumAlf ! Number of data lines in the following table -! Alpha Cl Cd Cpmin -! (deg) (-) (-) (-) - -180.000 0.0000 0.0908 -1.2342 - -170.000 0.3589 0.0908 -1.2342 - -160.000 0.7178 0.1399 -1.2342 - -150.000 0.8463 0.2923 -1.2342 - -140.000 0.6918 0.4800 -1.2342 - -130.000 0.5644 0.6809 -1.2342 - -120.000 0.4330 0.8718 -1.2342 - -110.000 0.2907 1.0306 -1.2342 - -100.000 0.1426 1.1392 -1.2342 - -90.000 0.0000 1.1856 -1.2342 - -80.000 -0.1426 1.1392 -1.2342 - -70.000 -0.2907 1.0306 -1.2342 - -60.000 -0.4330 0.8718 -1.2342 - -50.000 -0.5644 0.6809 -1.2342 - -40.000 -0.6918 0.4800 -1.2342 - -30.000 -0.8463 0.2923 -1.2342 - -20.000 -0.7416 0.1764 -1.2342 - -10.000 -0.6035 0.0940 -2.6010 - -9.000 -0.5784 0.0917 -2.3771 - -8.000 -0.5289 0.0908 -2.1303 - -5.000 -0.2459 0.0889 -1.4153 - -4.000 -0.1417 0.0885 -1.2471 - -3.000 -0.0350 0.0882 -1.1334 - -2.000 0.0720 0.0876 -1.1574 - -1.000 0.1806 0.0873 -1.2325 - 0.000 0.2903 0.0872 -1.3135 - 1.000 0.3977 0.0872 -1.3948 - 2.000 0.5029 0.0874 -1.4763 - 3.000 0.6065 0.0878 -1.5602 - 4.000 0.7026 0.0885 -1.6371 - 6.000 0.8709 0.0903 -1.8131 - 7.000 0.9390 0.0909 -1.9283 - 8.000 0.9903 0.0919 -2.0725 - 9.000 1.0182 0.0941 -2.2052 - 11.000 1.0718 0.1008 -2.5055 - 12.000 1.1056 0.1046 -2.7534 - 13.000 1.1409 0.1088 -3.0171 - 15.000 1.2029 0.1193 -3.5854 - 16.000 1.2292 0.1256 -3.8876 - 17.000 1.2559 0.1323 -4.2180 - 18.000 1.2741 0.1402 -4.5271 - 19.000 1.2946 0.1485 -4.8636 - 20.000 1.3084 0.1579 -5.1912 - 22.000 1.3238 0.1794 -5.8311 - 25.000 1.3343 0.2140 -6.8274 - 26.000 1.3330 0.2260 -7.1297 - 30.000 1.2089 0.2923 -5.8073 - 40.000 0.9884 0.4800 -1.2342 - 50.000 0.8063 0.6809 -1.2342 - 60.000 0.6186 0.8718 -1.2342 - 70.000 0.4154 1.0306 -1.2342 - 80.000 0.2037 1.1392 -1.2342 - 90.000 0.0000 1.1856 -1.2342 - 100.000 -0.1426 1.1392 -1.2342 - 110.000 -0.2907 1.0306 -1.2342 - 120.000 -0.4330 0.8718 -1.2342 - 130.000 -0.5644 0.6809 -1.2342 - 140.000 -0.6918 0.4800 -1.2342 - 150.000 -0.8463 0.2923 -1.2342 - 160.000 -0.7178 0.1399 -1.2342 - 170.000 -0.3589 0.0908 -1.2342 - 180.000 0.0000 0.0908 -1.2342 -! ------------------------------------------------------------------------------ -! data for table 5 -! ------------------------------------------------------------------------------ - 10.000 Re ! Reynolds number in millions - 0 UserProp ! User property (control) setting -False InclUAdata ! Is unsteady aerodynamics data included in this table? If TRUE, then include 30 UA coefficients below this line -!........................................ -! Table of aerodynamics coefficients - 67 NumAlf ! Number of data lines in the following table -! Alpha Cl Cd Cpmin -! (deg) (-) (-) (-) - -180.000 0.0000 0.0908 -1.2342 - -170.000 0.3097 0.0908 -1.2342 - -160.000 0.6195 0.1173 -1.2342 - -150.000 0.9292 0.2715 -1.2342 - -140.000 0.7423 0.4615 -1.2342 - -130.000 0.5943 0.6655 -1.2342 - -120.000 0.4490 0.8598 -1.2342 - -110.000 0.2976 1.0223 -1.2342 - -100.000 0.1443 1.1350 -1.2342 - -90.000 0.0000 1.1856 -1.2342 - -80.000 -0.1443 1.1350 -1.2342 - -70.000 -0.2976 1.0223 -1.2342 - -60.000 -0.4490 0.8598 -1.2342 - -50.000 -0.5943 0.6655 -1.2342 - -40.000 -0.7423 0.4615 -1.2342 - -30.000 -0.9292 0.2715 -1.2342 - -20.000 -0.6751 0.1827 -1.2342 - -10.000 -0.6013 0.0939 -2.5800 - -9.000 -0.6049 0.0913 -2.4300 - -8.000 -0.5351 0.0905 -2.1415 - -6.000 -0.3479 0.0892 -1.6003 - -4.000 -0.1409 0.0883 -1.2463 - -3.000 -0.0343 0.0881 -1.1345 - -2.000 0.0733 0.0876 -1.1581 - -1.000 0.1825 0.0872 -1.2337 - 0.000 0.2915 0.0871 -1.3142 - 1.000 0.3984 0.0872 -1.3953 - 2.000 0.5032 0.0874 -1.4781 - 4.000 0.7008 0.0886 -1.6330 - 5.000 0.7884 0.0895 -1.7176 - 6.000 0.8737 0.0902 -1.8187 - 7.000 0.9573 0.0907 -1.9445 - 8.000 0.9963 0.0918 -2.0792 - 9.000 1.0325 0.0935 -2.2235 - 10.000 1.0483 0.0969 -2.3279 - 11.000 1.0905 0.0997 -2.5427 - 12.000 1.1219 0.1035 -2.7879 - 13.000 1.1561 0.1078 -3.0531 - 14.000 1.1901 0.1124 -3.3382 - 16.000 1.2477 0.1239 -3.9451 - 17.000 1.2697 0.1309 -4.2627 - 18.000 1.2918 0.1384 -4.5882 - 19.000 1.3089 0.1468 -4.9179 - 20.000 1.3218 0.1562 -5.2450 - 21.000 1.3285 0.1667 -5.5530 - 24.000 1.3627 0.1976 -6.6668 - 25.000 1.3660 0.2090 -7.0127 - 26.000 1.3664 0.2208 -7.3375 - 27.000 1.3628 0.2327 -7.6317 - 28.000 1.3542 0.2452 -7.8817 - 29.000 1.3417 0.2583 -8.0880 - 30.000 1.3275 0.2715 -8.2610 - 40.000 1.0605 0.4615 -1.2342 - 50.000 0.8489 0.6655 -1.2342 - 60.000 0.6414 0.8598 -1.2342 - 70.000 0.4252 1.0223 -1.2342 - 80.000 0.2061 1.1350 -1.2342 - 90.000 0.0000 1.1856 -1.2342 - 100.000 -0.1443 1.1350 -1.2342 - 110.000 -0.2976 1.0223 -1.2342 - 120.000 -0.4490 0.8598 -1.2342 - 130.000 -0.5943 0.6655 -1.2342 - 140.000 -0.7423 0.4615 -1.2342 - 150.000 -0.9292 0.2715 -1.2342 - 160.000 -0.6195 0.1173 -1.2342 - 170.000 -0.3097 0.0908 -1.2342 - 180.000 0.0000 0.0908 -1.2342 -! ------------------------------------------------------------------------------ -! data for table 6 -! ------------------------------------------------------------------------------ - 12.000 Re ! Reynolds number in millions - 0 UserProp ! User property (control) setting -False InclUAdata ! Is unsteady aerodynamics data included in this table? If TRUE, then include 30 UA coefficients below this line -!........................................ -! Table of aerodynamics coefficients - 68 NumAlf ! Number of data lines in the following table -! Alpha Cl Cd Cpmin -! (deg) (-) (-) (-) - -180.000 0.0000 0.0908 -1.2342 - -170.000 0.3262 0.0908 -1.2342 - -160.000 0.6524 0.1202 -1.2342 - -150.000 0.9224 0.2741 -1.2342 - -140.000 0.7382 0.4639 -1.2342 - -130.000 0.5918 0.6674 -1.2342 - -120.000 0.4476 0.8613 -1.2342 - -110.000 0.2971 1.0234 -1.2342 - -100.000 0.1441 1.1355 -1.2342 - -90.000 0.0000 1.1856 -1.2342 - -80.000 -0.1441 1.1355 -1.2342 - -70.000 -0.2971 1.0234 -1.2342 - -60.000 -0.4476 0.8613 -1.2342 - -50.000 -0.5918 0.6674 -1.2342 - -40.000 -0.7382 0.4639 -1.2342 - -30.000 -0.9224 0.2741 -1.2342 - -20.000 -0.7012 0.1794 -1.2342 - -10.000 -0.6131 0.0934 -2.6061 - -7.000 -0.4460 0.0897 -1.8425 - -6.000 -0.3471 0.0892 -1.5903 - -5.000 -0.2455 0.0886 -1.4153 - -4.000 -0.1408 0.0882 -1.2460 - -3.000 -0.0335 0.0880 -1.1370 - -2.000 0.0747 0.0876 -1.1588 - -1.000 0.1835 0.0871 -1.2344 - 0.000 0.2922 0.0871 -1.3144 - 1.000 0.3990 0.0871 -1.3960 - 2.000 0.5040 0.0874 -1.4745 - 3.000 0.6059 0.0878 -1.5514 - 4.000 0.7013 0.0885 -1.6363 - 5.000 0.7890 0.0894 -1.7201 - 6.000 0.8798 0.0899 -1.8244 - 7.000 0.9640 0.0905 -1.9511 - 8.000 1.0024 0.0916 -2.0864 - 10.000 1.0619 0.0962 -2.3507 - 11.000 1.1017 0.0991 -2.5653 - 12.000 1.1399 0.1025 -2.8264 - 13.000 1.1759 0.1063 -3.1002 - 14.000 1.2023 0.1116 -3.3690 - 15.000 1.2323 0.1168 -3.6674 - 17.000 1.2828 0.1297 -4.3055 - 18.000 1.3035 0.1372 -4.6284 - 19.000 1.3205 0.1455 -4.9619 - 20.000 1.3290 0.1553 -5.2735 - 22.000 1.3649 0.1735 -6.0219 - 23.000 1.3718 0.1845 -6.3836 - 24.000 1.3769 0.1956 -6.7442 - 25.000 1.3793 0.2072 -7.0890 - 26.000 1.3784 0.2190 -7.4113 - 27.000 1.3719 0.2313 -7.6916 - 28.000 1.3626 0.2440 -7.9398 - 29.000 1.3514 0.2568 -8.1599 - 30.000 1.3177 0.2741 -7.7356 - 40.000 1.0545 0.4639 -1.2342 - 50.000 0.8454 0.6674 -1.2342 - 60.000 0.6395 0.8613 -1.2342 - 70.000 0.4244 1.0234 -1.2342 - 80.000 0.2059 1.1355 -1.2342 - 90.000 0.0000 1.1856 -1.2342 - 100.000 -0.1441 1.1355 -1.2342 - 110.000 -0.2971 1.0234 -1.2342 - 120.000 -0.4476 0.8613 -1.2342 - 130.000 -0.5918 0.6674 -1.2342 - 140.000 -0.7382 0.4639 -1.2342 - 150.000 -0.9224 0.2741 -1.2342 - 160.000 -0.6524 0.1202 -1.2342 - 170.000 -0.3262 0.0908 -1.2342 - 180.000 0.0000 0.0908 -1.2342 -! ------------------------------------------------------------------------------ -! data for table 7 -! ------------------------------------------------------------------------------ - 14.000 Re ! Reynolds number in millions - 0 UserProp ! User property (control) setting -False InclUAdata ! Is unsteady aerodynamics data included in this table? If TRUE, then include 30 UA coefficients below this line -!........................................ -! Table of aerodynamics coefficients - 64 NumAlf ! Number of data lines in the following table -! Alpha Cl Cd Cpmin -! (deg) (-) (-) (-) - -180.000 0.0000 0.0908 -1.2342 - -170.000 0.3144 0.0908 -1.2342 - -160.000 0.6287 0.1138 -1.2342 - -150.000 0.9431 0.2683 -1.2342 - -140.000 0.7508 0.4587 -1.2342 - -130.000 0.5992 0.6631 -1.2342 - -120.000 0.4516 0.8579 -1.2342 - -110.000 0.2988 1.0211 -1.2342 - -100.000 0.1445 1.1343 -1.2342 - -90.000 0.0000 1.1856 -1.2342 - -80.000 -0.1445 1.1343 -1.2342 - -70.000 -0.2988 1.0211 -1.2342 - -60.000 -0.4516 0.8579 -1.2342 - -50.000 -0.5992 0.6631 -1.2342 - -40.000 -0.7508 0.4587 -1.2342 - -30.000 -0.9431 0.2683 -1.2342 - -20.000 -0.6902 0.1806 -1.2342 - -10.000 -0.6249 0.0929 -2.6310 - -9.000 -0.6076 0.0912 -2.4236 - -8.000 -0.5409 0.0901 -2.1527 - -6.000 -0.3470 0.0891 -1.5882 - -5.000 -0.2454 0.0885 -1.4150 - -4.000 -0.1407 0.0881 -1.2459 - -3.000 -0.0328 0.0879 -1.1374 - -2.000 0.0757 0.0875 -1.1594 - -1.000 0.1839 0.0871 -1.2346 - 0.000 0.2931 0.0870 -1.3151 - 1.000 0.3980 0.0872 -1.3962 - 2.000 0.5039 0.0874 -1.4738 - 3.000 0.6047 0.0879 -1.5498 - 5.000 0.7918 0.0893 -1.7230 - 6.000 0.8825 0.0899 -1.8274 - 7.000 0.9707 0.0904 -1.9577 - 8.000 1.0061 0.0914 -2.0904 - 11.000 1.1120 0.0986 -2.5857 - 12.000 1.1501 0.1018 -2.8480 - 14.000 1.2210 0.1100 -3.4157 - 16.000 1.2697 0.1220 -4.0131 - 18.000 1.3134 0.1361 -4.6623 - 21.000 1.3665 0.1618 -5.7189 - 22.000 1.3754 0.1721 -6.0696 - 23.000 1.3833 0.1829 -6.4424 - 24.000 1.3875 0.1941 -6.8016 - 25.000 1.3889 0.2058 -7.1442 - 26.000 1.3849 0.2179 -7.4518 - 27.000 1.3786 0.2303 -7.7351 - 28.000 1.3703 0.2427 -7.9942 - 29.000 1.3602 0.2554 -8.2252 - 30.000 1.3473 0.2683 -8.4198 - 40.000 1.0725 0.4587 -1.2342 - 50.000 0.8561 0.6631 -1.2342 - 60.000 0.6452 0.8579 -1.2342 - 70.000 0.4269 1.0211 -1.2342 - 80.000 0.2065 1.1343 -1.2342 - 90.000 0.0000 1.1856 -1.2342 - 100.000 -0.1445 1.1343 -1.2342 - 110.000 -0.2988 1.0211 -1.2342 - 120.000 -0.4516 0.8579 -1.2342 - 130.000 -0.5992 0.6631 -1.2342 - 140.000 -0.7508 0.4587 -1.2342 - 150.000 -0.9431 0.2683 -1.2342 - 160.000 -0.6287 0.1138 -1.2342 - 170.000 -0.3144 0.0908 -1.2342 - 180.000 0.0000 0.0908 -1.2342 \ No newline at end of file diff --git a/Test_Cases/MHK_RM1/Airfoils/NACA6_0329_coords.txt b/Test_Cases/MHK_RM1/Airfoils/NACA6_0329_coords.txt deleted file mode 100644 index 00d5ebe9..00000000 --- a/Test_Cases/MHK_RM1/Airfoils/NACA6_0329_coords.txt +++ /dev/null @@ -1,47 +0,0 @@ - 40 NumCoords ! The number of coordinates in the airfoil shape file (including an extra coordinate for airfoil reference). Set to zero if coordinates not included. -! ......... x-y coordinates are next if NumCoords > 0 ............. -! x-y coordinate of airfoil reference -! x/c y/c - 0.25 0 -! coordinates of airfoil shape -! NACA6_0329 Airfoil -! x/c y/c - 0.000000 0.000000 - 0.006819 0.028484 - 0.027091 0.058831 - 0.060263 0.089532 - 0.105430 0.117836 - 0.161359 0.142554 - 0.226526 0.162174 - 0.299152 0.175281 - 0.377257 0.179988 - 0.458710 0.175693 - 0.541290 0.163772 - 0.622743 0.146064 - 0.700848 0.124660 - 0.773474 0.101839 - 0.838641 0.079535 - 0.894570 0.059015 - 0.939737 0.040853 - 0.972909 0.025130 - 0.993181 0.011587 - 1.000000 0.000000 - 0.993181 -0.009368 - 0.972909 -0.018416 - 0.939737 -0.028604 - 0.894570 -0.040942 - 0.838641 -0.055950 - 0.773474 -0.073518 - 0.700848 -0.092848 - 0.622743 -0.112264 - 0.541290 -0.129574 - 0.458710 -0.142543 - 0.377257 -0.149007 - 0.299152 -0.147357 - 0.226526 -0.138252 - 0.161359 -0.123216 - 0.105430 -0.103514 - 0.060263 -0.080124 - 0.027091 -0.053971 - 0.006819 -0.026499 - 0.000000 0.000000 \ No newline at end of file diff --git a/Test_Cases/MHK_RM1/Airfoils/NACA6_0444.dat b/Test_Cases/MHK_RM1/Airfoils/NACA6_0444.dat deleted file mode 100644 index 1957eb43..00000000 --- a/Test_Cases/MHK_RM1/Airfoils/NACA6_0444.dat +++ /dev/null @@ -1,560 +0,0 @@ -! ------------ AirfoilInfo v1.01.x Input File ---------------------------------- -! NACA6_0444 airfoil, data based on values used for the design of the RM1 tidal current turbine. -! line -! line -! ------------------------------------------------------------------------------ -"default" InterpOrd ! Interpolation order to use for quasi-steady table lookup {1=linear; 3=cubic spline; "default"} [default=1] - 1.0 NonDimArea ! The non-dimensional area of the airfoil (area/chord^2) (set to 1.0 if unsure or unneeded) -@"NACA6_0444_coords.txt" NumCoords ! The number of coordinates in the airfoil shape file. Set to zero if coordinates not included. -"unused" BL_file ! The file name including the boundary layer characteristics of the profile. Ignored if the aeroacoustic module is not called. - 7 NumTabs ! Number of airfoil tables in this file. -! ------------------------------------------------------------------------------ -! data for table 1 -! ------------------------------------------------------------------------------ - 2.000 Re ! Reynolds number in millions - 0 UserProp ! User property (control) setting -False InclUAdata ! Is unsteady aerodynamics data included in this table? If TRUE, then include 30 UA coefficients below this line -!........................................ -! Table of aerodynamics coefficients - 72 NumAlf ! Number of data lines in the following table -! Alpha Cl Cd Cpmin -! (deg) (-) (-) (-) - -180.000 0.0000 0.0878 -1.5368 - -170.000 0.2283 0.0878 -1.5368 - -160.000 0.4565 0.1322 -1.5368 - -150.000 0.6848 0.2582 -1.5368 - -140.000 0.5632 0.4133 -1.5368 - -130.000 0.4618 0.5793 -1.5368 - -120.000 0.3556 0.7370 -1.5368 - -110.000 0.2396 0.8679 -1.5368 - -100.000 0.1178 0.9572 -1.5368 - -90.000 0.0000 0.9950 -1.5368 - -80.000 -0.1178 0.9572 -1.5368 - -70.000 -0.2396 0.8679 -1.5368 - -60.000 -0.3556 0.7370 -1.5368 - -50.000 -0.4618 0.5793 -1.5368 - -40.000 -0.5632 0.4133 -1.5368 - -30.000 -0.6848 0.2582 -1.5368 - -20.000 -0.4962 0.1761 -1.5368 - -10.000 -0.4394 0.0939 -2.5360 - -9.000 -0.4172 0.0915 -2.3675 - -8.000 -0.3951 0.0896 -2.2046 - -7.000 -0.3558 0.0886 -2.0171 - -6.000 -0.2861 0.0879 -1.8350 - -5.000 -0.2070 0.0873 -1.6903 - -4.000 -0.1243 0.0868 -1.5548 - -3.000 -0.0400 0.0861 -1.4677 - -2.000 0.0491 0.0859 -1.4671 - -1.000 0.1378 0.0859 -1.5286 - 0.000 0.2262 0.0859 -1.5937 - 1.000 0.3151 0.0859 -1.6608 - 2.000 0.4026 0.0861 -1.7276 - 3.000 0.4885 0.0862 -1.7971 - 4.000 0.5711 0.0865 -1.8669 - 5.000 0.6526 0.0868 -1.9437 - 6.000 0.7191 0.0876 -2.0232 - 7.000 0.7459 0.0889 -2.0832 - 8.000 0.7701 0.0905 -2.1757 - 9.000 0.7998 0.0927 -2.2872 - 10.000 0.8305 0.0952 -2.4037 - 11.000 0.8363 0.0995 -2.4899 - 12.000 0.8581 0.1034 -2.6735 - 13.000 0.8652 0.1092 -2.8298 - 14.000 0.8843 0.1145 -3.0236 - 15.000 0.8978 0.1208 -3.2127 - 16.000 0.9186 0.1269 -3.4359 - 17.000 0.9369 0.1336 -3.6657 - 18.000 0.9538 0.1409 -3.9085 - 19.000 0.9695 0.1486 -4.1517 - 20.000 0.9832 0.1568 -4.4027 - 21.000 0.9959 0.1653 -4.6596 - 22.000 1.0102 0.1735 -4.9355 - 23.000 1.0165 0.1830 -5.1857 - 24.000 1.0214 0.1926 -5.4324 - 25.000 1.0220 0.2026 -5.6651 - 26.000 1.0185 0.2132 -5.8642 - 28.000 1.0003 0.2350 -6.1537 - 29.000 0.9868 0.2472 -6.2271 - 30.000 0.9782 0.2582 -6.3176 - 40.000 0.8047 0.4133 -1.5368 - 50.000 0.6597 0.5793 -1.5368 - 60.000 0.5080 0.7370 -1.5368 - 70.000 0.3422 0.8679 -1.5368 - 80.000 0.1683 0.9572 -1.5368 - 90.000 0.0000 0.9950 -1.5368 - 100.000 -0.1178 0.9572 -1.5368 - 110.000 -0.2396 0.8679 -1.5368 - 120.000 -0.3556 0.7370 -1.5368 - 130.000 -0.4618 0.5793 -1.5368 - 140.000 -0.5632 0.4133 -1.5368 - 150.000 -0.6848 0.2582 -1.5368 - 160.000 -0.4565 0.1322 -1.5368 - 170.000 -0.2283 0.0878 -1.5368 - 180.000 0.0000 0.0878 -1.5368 -! ------------------------------------------------------------------------------ -! data for table 2 -! ------------------------------------------------------------------------------ - 4.000 Re ! Reynolds number in millions - 0 UserProp ! User property (control) setting -False InclUAdata ! Is unsteady aerodynamics data included in this table? If TRUE, then include 30 UA coefficients below this line -!........................................ -! Table of aerodynamics coefficients - 69 NumAlf ! Number of data lines in the following table -! Alpha Cl Cd Cpmin -! (deg) (-) (-) (-) - -180.000 0.0000 0.1872 -1.5368 - -170.000 0.2392 0.1872 -1.5368 - -160.000 0.4785 0.2228 -1.5368 - -150.000 0.7178 0.3494 -1.5368 - -140.000 0.5834 0.5055 -1.5368 - -130.000 0.4736 0.6726 -1.5368 - -120.000 0.3620 0.8316 -1.5368 - -110.000 0.2423 0.9640 -1.5368 - -100.000 0.1184 1.0549 -1.5368 - -90.000 0.0000 1.0943 -1.5368 - -80.000 -0.1184 1.0549 -1.5368 - -70.000 -0.2423 0.9640 -1.5368 - -60.000 -0.3620 0.8316 -1.5368 - -50.000 -0.4736 0.6726 -1.5368 - -40.000 -0.5834 0.5055 -1.5368 - -30.000 -0.7178 0.3494 -1.5368 - -20.000 -0.5245 0.2703 -1.5368 - -10.000 -0.4731 0.1913 -2.6071 - -9.000 -0.4387 0.1895 -2.4083 - -8.000 -0.4244 0.1880 -2.2550 - -7.000 -0.3621 0.1872 -2.0285 - -6.000 -0.2860 0.1866 -1.8352 - -5.000 -0.2056 0.1861 -1.6890 - -4.000 -0.1199 0.1857 -1.5503 - -3.000 -0.0332 0.1852 -1.4630 - -1.000 0.1450 0.1846 -1.5328 - 0.000 0.2351 0.1845 -1.5992 - 1.000 0.3236 0.1847 -1.6662 - 2.000 0.4130 0.1847 -1.7344 - 5.000 0.6567 0.1859 -1.9457 - 6.000 0.7147 0.1869 -2.0208 - 7.000 0.7543 0.1878 -2.0899 - 9.000 0.8287 0.1906 -2.3229 - 10.000 0.8432 0.1936 -2.4202 - 11.000 0.8686 0.1967 -2.5521 - 12.000 0.8799 0.2011 -2.7194 - 13.000 0.9008 0.2055 -2.9099 - 14.000 0.9219 0.2103 -3.1187 - 15.000 0.9467 0.2153 -3.3452 - 16.000 0.9669 0.2211 -3.5794 - 17.000 0.9875 0.2272 -3.8341 - 18.000 1.0047 0.2340 -4.0877 - 19.000 1.0217 0.2411 -4.3483 - 20.000 1.0326 0.2494 -4.6065 - 21.000 1.0440 0.2578 -4.8698 - 22.000 1.0538 0.2667 -5.1436 - 23.000 1.0571 0.2763 -5.3926 - 24.000 1.0672 0.2850 -5.6949 - 25.000 1.0677 0.2949 -5.9456 - 26.000 1.0682 0.3046 -6.1909 - 27.000 1.0653 0.3148 -6.4081 - 28.000 1.0595 0.3254 -6.5932 - 29.000 1.0375 0.3381 -6.6428 - 30.000 1.0254 0.3494 -6.7387 - 40.000 0.8333 0.5055 -1.5368 - 50.000 0.6766 0.6726 -1.5368 - 60.000 0.5171 0.8316 -1.5368 - 70.000 0.3461 0.9640 -1.5368 - 80.000 0.1692 1.0549 -1.5368 - 90.000 0.0000 1.0943 -1.5368 - 100.000 -0.1184 1.0549 -1.5368 - 110.000 -0.2423 0.9640 -1.5368 - 120.000 -0.3620 0.8316 -1.5368 - 130.000 -0.4736 0.6726 -1.5368 - 140.000 -0.5834 0.5055 -1.5368 - 150.000 -0.7178 0.3494 -1.5368 - 160.000 -0.4785 0.2228 -1.5368 - 170.000 -0.2392 0.1872 -1.5368 - 180.000 0.0000 0.1872 -1.5368 -! ------------------------------------------------------------------------------ -! data for table 3 -! ------------------------------------------------------------------------------ - 6.000 Re ! Reynolds number in millions - 0 UserProp ! User property (control) setting -False InclUAdata ! Is unsteady aerodynamics data included in this table? If TRUE, then include 30 UA coefficients below this line -!........................................ -! Table of aerodynamics coefficients - 71 NumAlf ! Number of data lines in the following table -! Alpha Cl Cd Cpmin -! (deg) (-) (-) (-) - -180.000 0.0000 0.1952 -1.5368 - -170.000 0.2482 0.1952 -1.5368 - -160.000 0.4963 0.2242 -1.5368 - -150.000 0.7445 0.3514 -1.5368 - -140.000 0.5996 0.5081 -1.5368 - -130.000 0.4832 0.6762 -1.5368 - -120.000 0.3671 0.8361 -1.5368 - -110.000 0.2445 0.9697 -1.5368 - -100.000 0.1190 1.0618 -1.5368 - -90.000 0.0000 1.1024 -1.5368 - -80.000 -0.1190 1.0618 -1.5368 - -70.000 -0.2445 0.9697 -1.5368 - -60.000 -0.3671 0.8361 -1.5368 - -50.000 -0.4832 0.6762 -1.5368 - -40.000 -0.5996 0.5081 -1.5368 - -30.000 -0.7445 0.3514 -1.5368 - -20.000 -0.5447 0.2748 -1.5368 - -10.000 -0.4926 0.1982 -2.6480 - -9.000 -0.4617 0.1966 -2.4507 - -8.000 -0.4322 0.1956 -2.2686 - -7.000 -0.3634 0.1949 -2.0305 - -6.000 -0.2873 0.1943 -1.8371 - -5.000 -0.2040 0.1938 -1.6873 - -4.000 -0.1179 0.1935 -1.5480 - -3.000 -0.0307 0.1932 -1.4615 - -2.000 0.0580 0.1926 -1.4722 - -1.000 0.1481 0.1924 -1.5347 - 0.000 0.2381 0.1924 -1.6009 - 1.000 0.3285 0.1924 -1.6693 - 2.000 0.4157 0.1926 -1.7363 - 4.000 0.5828 0.1932 -1.8778 - 5.000 0.6545 0.1940 -1.9455 - 6.000 0.7170 0.1949 -2.0173 - 7.000 0.7642 0.1956 -2.0997 - 8.000 0.8095 0.1965 -2.2185 - 9.000 0.8348 0.1983 -2.3302 - 10.000 0.8615 0.2007 -2.4451 - 11.000 0.8789 0.2040 -2.5723 - 12.000 0.9009 0.2076 -2.7637 - 13.000 0.9207 0.2120 -2.9553 - 14.000 0.9486 0.2162 -3.1860 - 15.000 0.9707 0.2212 -3.4123 - 16.000 0.9925 0.2266 -3.6554 - 17.000 1.0124 0.2326 -3.9159 - 19.000 1.0445 0.2464 -4.4359 - 20.000 1.0686 0.2527 -4.7530 - 21.000 1.0776 0.2612 -5.0144 - 22.000 1.0832 0.2704 -5.2826 - 23.000 1.0866 0.2800 -5.5449 - 24.000 1.0913 0.2894 -5.8301 - 25.000 1.0933 0.2991 -6.0985 - 26.000 1.0914 0.3091 -6.3395 - 27.000 1.0862 0.3196 -6.5511 - 28.000 1.0802 0.3300 -6.7450 - 29.000 1.0729 0.3406 -6.9167 - 30.000 1.0635 0.3514 -7.0563 - 40.000 0.8565 0.5081 -1.5368 - 50.000 0.6903 0.6762 -1.5368 - 60.000 0.5245 0.8361 -1.5368 - 70.000 0.3493 0.9697 -1.5368 - 80.000 0.1700 1.0618 -1.5368 - 90.000 0.0000 1.1024 -1.5368 - 100.000 -0.1190 1.0618 -1.5368 - 110.000 -0.2445 0.9697 -1.5368 - 120.000 -0.3671 0.8361 -1.5368 - 130.000 -0.4832 0.6762 -1.5368 - 140.000 -0.5996 0.5081 -1.5368 - 150.000 -0.7445 0.3514 -1.5368 - 160.000 -0.4963 0.2242 -1.5368 - 170.000 -0.2482 0.1952 -1.5368 - 180.000 0.0000 0.1952 -1.5368 -! ------------------------------------------------------------------------------ -! data for table 4 -! ------------------------------------------------------------------------------ - 8.000 Re ! Reynolds number in millions - 0 UserProp ! User property (control) setting -False InclUAdata ! Is unsteady aerodynamics data included in this table? If TRUE, then include 30 UA coefficients below this line -!........................................ -! Table of aerodynamics coefficients - 62 NumAlf ! Number of data lines in the following table -! Alpha Cl Cd Cpmin -! (deg) (-) (-) (-) - -180.000 0.0000 0.1952 -1.5368 - -170.000 0.2974 0.1952 -1.5368 - -160.000 0.5948 0.2359 -1.5368 - -150.000 0.7012 0.3622 -1.5368 - -140.000 0.5733 0.5177 -1.5368 - -130.000 0.4677 0.6842 -1.5368 - -120.000 0.3588 0.8424 -1.5368 - -110.000 0.2409 0.9739 -1.5368 - -100.000 0.1181 1.0639 -1.5368 - -90.000 0.0000 1.1024 -1.5368 - -80.000 -0.1181 1.0639 -1.5368 - -70.000 -0.2409 0.9739 -1.5368 - -60.000 -0.3588 0.8424 -1.5368 - -50.000 -0.4677 0.6842 -1.5368 - -40.000 -0.5733 0.5177 -1.5368 - -30.000 -0.7012 0.3622 -1.5368 - -20.000 -0.6145 0.2662 -1.5368 - -10.000 -0.5000 0.1978 -2.6694 - -9.000 -0.4793 0.1959 -2.4839 - -8.000 -0.4382 0.1952 -2.2793 - -5.000 -0.2037 0.1937 -1.6869 - -4.000 -0.1174 0.1933 -1.5475 - -3.000 -0.0290 0.1930 -1.4533 - -2.000 0.0596 0.1926 -1.4732 - -1.000 0.1497 0.1923 -1.5355 - 0.000 0.2405 0.1922 -1.6025 - 1.000 0.3296 0.1922 -1.6699 - 2.000 0.4167 0.1924 -1.7374 - 3.000 0.5025 0.1927 -1.8069 - 4.000 0.5822 0.1933 -1.8707 - 6.000 0.7216 0.1948 -2.0165 - 7.000 0.7781 0.1953 -2.1120 - 8.000 0.8206 0.1961 -2.2315 - 9.000 0.8437 0.1979 -2.3414 - 11.000 0.8881 0.2035 -2.5902 - 12.000 0.9161 0.2066 -2.7957 - 13.000 0.9453 0.2101 -3.0142 - 15.000 0.9967 0.2188 -3.4850 - 16.000 1.0185 0.2240 -3.7355 - 17.000 1.0407 0.2296 -4.0092 - 18.000 1.0557 0.2362 -4.2653 - 19.000 1.0727 0.2430 -4.5442 - 20.000 1.0841 0.2508 -4.8156 - 22.000 1.0969 0.2686 -5.3459 - 25.000 1.1056 0.2973 -6.1715 - 26.000 1.1045 0.3072 -6.4219 - 30.000 1.0018 0.3622 -5.3262 - 40.000 0.8190 0.5177 -1.5368 - 50.000 0.6682 0.6842 -1.5368 - 60.000 0.5125 0.8424 -1.5368 - 70.000 0.3442 0.9739 -1.5368 - 80.000 0.1688 1.0639 -1.5368 - 90.000 0.0000 1.1024 -1.5368 - 100.000 -0.1181 1.0639 -1.5368 - 110.000 -0.2409 0.9739 -1.5368 - 120.000 -0.3588 0.8424 -1.5368 - 130.000 -0.4677 0.6842 -1.5368 - 140.000 -0.5733 0.5177 -1.5368 - 150.000 -0.7012 0.3622 -1.5368 - 160.000 -0.5948 0.2359 -1.5368 - 170.000 -0.2974 0.1952 -1.5368 - 180.000 0.0000 0.1952 -1.5368 -! ------------------------------------------------------------------------------ -! data for table 5 -! ------------------------------------------------------------------------------ - 10.000 Re ! Reynolds number in millions - 0 UserProp ! User property (control) setting -False InclUAdata ! Is unsteady aerodynamics data included in this table? If TRUE, then include 30 UA coefficients below this line -!........................................ -! Table of aerodynamics coefficients - 67 NumAlf ! Number of data lines in the following table -! Alpha Cl Cd Cpmin -! (deg) (-) (-) (-) - -180.000 0.0000 0.1952 -1.5368 - -170.000 0.2566 0.1952 -1.5368 - -160.000 0.5133 0.2172 -1.5368 - -150.000 0.7700 0.3450 -1.5368 - -140.000 0.6151 0.5024 -1.5368 - -130.000 0.4924 0.6714 -1.5368 - -120.000 0.3720 0.8324 -1.5368 - -110.000 0.2466 0.9671 -1.5368 - -100.000 0.1195 1.0604 -1.5368 - -90.000 0.0000 1.1024 -1.5368 - -80.000 -0.1195 1.0604 -1.5368 - -70.000 -0.2466 0.9671 -1.5368 - -60.000 -0.3720 0.8324 -1.5368 - -50.000 -0.4924 0.6714 -1.5368 - -40.000 -0.6151 0.5024 -1.5368 - -30.000 -0.7700 0.3450 -1.5368 - -20.000 -0.5594 0.2714 -1.5368 - -10.000 -0.4983 0.1978 -2.6520 - -9.000 -0.5012 0.1956 -2.5277 - -8.000 -0.4434 0.1950 -2.2886 - -6.000 -0.2883 0.1939 -1.8402 - -4.000 -0.1168 0.1932 -1.5469 - -3.000 -0.0284 0.1929 -1.4542 - -2.000 0.0607 0.1926 -1.4738 - -1.000 0.1512 0.1922 -1.5364 - 0.000 0.2416 0.1921 -1.6031 - 1.000 0.3301 0.1922 -1.6704 - 2.000 0.4170 0.1924 -1.7389 - 4.000 0.5807 0.1934 -1.8673 - 5.000 0.6533 0.1941 -1.9374 - 6.000 0.7240 0.1947 -2.0211 - 7.000 0.7933 0.1951 -2.1254 - 8.000 0.8256 0.1960 -2.2370 - 9.000 0.8556 0.1975 -2.3566 - 10.000 0.8686 0.2003 -2.4430 - 11.000 0.9036 0.2026 -2.6210 - 12.000 0.9296 0.2057 -2.8243 - 13.000 0.9579 0.2093 -3.0440 - 14.000 0.9861 0.2131 -3.2803 - 16.000 1.0339 0.2226 -3.7832 - 17.000 1.0521 0.2284 -4.0463 - 18.000 1.0704 0.2346 -4.3160 - 19.000 1.0846 0.2416 -4.5892 - 20.000 1.0952 0.2494 -4.8603 - 21.000 1.1008 0.2581 -5.1154 - 24.000 1.1292 0.2837 -6.0384 - 25.000 1.1319 0.2932 -6.3250 - 26.000 1.1322 0.3029 -6.5941 - 27.000 1.1293 0.3128 -6.8379 - 28.000 1.1221 0.3232 -7.0450 - 29.000 1.1118 0.3340 -7.2160 - 30.000 1.1000 0.3450 -7.3593 - 40.000 0.8788 0.5024 -1.5368 - 50.000 0.7034 0.6714 -1.5368 - 60.000 0.5315 0.8324 -1.5368 - 70.000 0.3523 0.9671 -1.5368 - 80.000 0.1708 1.0604 -1.5368 - 90.000 0.0000 1.1024 -1.5368 - 100.000 -0.1195 1.0604 -1.5368 - 110.000 -0.2466 0.9671 -1.5368 - 120.000 -0.3720 0.8324 -1.5368 - 130.000 -0.4924 0.6714 -1.5368 - 140.000 -0.6151 0.5024 -1.5368 - 150.000 -0.7700 0.3450 -1.5368 - 160.000 -0.5133 0.2172 -1.5368 - 170.000 -0.2566 0.1952 -1.5368 - 180.000 0.0000 0.1952 -1.5368 -! ------------------------------------------------------------------------------ -! data for table 6 -! ------------------------------------------------------------------------------ - 12.000 Re ! Reynolds number in millions - 0 UserProp ! User property (control) setting -False InclUAdata ! Is unsteady aerodynamics data included in this table? If TRUE, then include 30 UA coefficients below this line -!........................................ -! Table of aerodynamics coefficients - 68 NumAlf ! Number of data lines in the following table -! Alpha Cl Cd Cpmin -! (deg) (-) (-) (-) - -180.000 0.0000 0.1952 -1.5368 - -170.000 0.2703 0.1952 -1.5368 - -160.000 0.5406 0.2196 -1.5368 - -150.000 0.7643 0.3471 -1.5368 - -140.000 0.6117 0.5044 -1.5368 - -130.000 0.4904 0.6730 -1.5368 - -120.000 0.3709 0.8337 -1.5368 - -110.000 0.2462 0.9680 -1.5368 - -100.000 0.1194 1.0609 -1.5368 - -90.000 0.0000 1.1024 -1.5368 - -80.000 -0.1194 1.0609 -1.5368 - -70.000 -0.2462 0.9680 -1.5368 - -60.000 -0.3709 0.8337 -1.5368 - -50.000 -0.4904 0.6730 -1.5368 - -40.000 -0.6117 0.5044 -1.5368 - -30.000 -0.7643 0.3471 -1.5368 - -20.000 -0.5810 0.2686 -1.5368 - -10.000 -0.5080 0.1973 -2.6736 - -7.000 -0.3695 0.1943 -2.0409 - -6.000 -0.2876 0.1939 -1.8319 - -5.000 -0.2035 0.1934 -1.6869 - -4.000 -0.1167 0.1931 -1.5466 - -3.000 -0.0277 0.1929 -1.4563 - -2.000 0.0619 0.1926 -1.4744 - -1.000 0.1520 0.1921 -1.5370 - 0.000 0.2422 0.1921 -1.6033 - 1.000 0.3306 0.1921 -1.6709 - 2.000 0.4176 0.1924 -1.7360 - 3.000 0.5021 0.1927 -1.7997 - 4.000 0.5811 0.1933 -1.8700 - 5.000 0.6538 0.1940 -1.9394 - 6.000 0.7290 0.1945 -2.0259 - 7.000 0.7988 0.1950 -2.1309 - 8.000 0.8306 0.1959 -2.2430 - 10.000 0.8799 0.1997 -2.4620 - 11.000 0.9129 0.2021 -2.6398 - 12.000 0.9445 0.2049 -2.8562 - 13.000 0.9744 0.2081 -3.0830 - 14.000 0.9963 0.2124 -3.3057 - 15.000 1.0211 0.2168 -3.5530 - 17.000 1.0629 0.2274 -4.0818 - 18.000 1.0801 0.2336 -4.3493 - 19.000 1.0941 0.2406 -4.6256 - 20.000 1.1012 0.2487 -4.8838 - 22.000 1.1309 0.2638 -5.5040 - 23.000 1.1367 0.2728 -5.8037 - 24.000 1.1409 0.2820 -6.1025 - 25.000 1.1429 0.2916 -6.3882 - 26.000 1.1421 0.3014 -6.6553 - 27.000 1.1368 0.3116 -6.8875 - 28.000 1.1290 0.3221 -7.0932 - 29.000 1.1198 0.3327 -7.2756 - 30.000 1.0919 0.3471 -6.9240 - 40.000 0.8738 0.5044 -1.5368 - 50.000 0.7005 0.6730 -1.5368 - 60.000 0.5299 0.8337 -1.5368 - 70.000 0.3517 0.9680 -1.5368 - 80.000 0.1706 1.0609 -1.5368 - 90.000 0.0000 1.1024 -1.5368 - 100.000 -0.1194 1.0609 -1.5368 - 110.000 -0.2462 0.9680 -1.5368 - 120.000 -0.3709 0.8337 -1.5368 - 130.000 -0.4904 0.6730 -1.5368 - 140.000 -0.6117 0.5044 -1.5368 - 150.000 -0.7643 0.3471 -1.5368 - 160.000 -0.5406 0.2196 -1.5368 - 170.000 -0.2703 0.1952 -1.5368 - 180.000 0.0000 0.1952 -1.5368 -! ------------------------------------------------------------------------------ -! data for table 7 -! ------------------------------------------------------------------------------ - 14.000 Re ! Reynolds number in millions - 0 UserProp ! User property (control) setting -False InclUAdata ! Is unsteady aerodynamics data included in this table? If TRUE, then include 30 UA coefficients below this line -!........................................ -! Table of aerodynamics coefficients - 64 NumAlf ! Number of data lines in the following table -! Alpha Cl Cd Cpmin -! (deg) (-) (-) (-) - -180.000 0.0000 0.1952 -1.5368 - -170.000 0.2605 0.1952 -1.5368 - -160.000 0.5210 0.2143 -1.5368 - -150.000 0.7815 0.3423 -1.5368 - -140.000 0.6221 0.5001 -1.5368 - -130.000 0.4965 0.6694 -1.5368 - -120.000 0.3742 0.8309 -1.5368 - -110.000 0.2476 0.9661 -1.5368 - -100.000 0.1198 1.0599 -1.5368 - -90.000 0.0000 1.1024 -1.5368 - -80.000 -0.1198 1.0599 -1.5368 - -70.000 -0.2476 0.9661 -1.5368 - -60.000 -0.3742 0.8309 -1.5368 - -50.000 -0.4965 0.6694 -1.5368 - -40.000 -0.6221 0.5001 -1.5368 - -30.000 -0.7815 0.3423 -1.5368 - -20.000 -0.5719 0.2696 -1.5368 - -10.000 -0.5178 0.1970 -2.6942 - -9.000 -0.5035 0.1956 -2.5224 - -8.000 -0.4482 0.1946 -2.2979 - -6.000 -0.2875 0.1938 -1.8301 - -5.000 -0.2034 0.1933 -1.6867 - -4.000 -0.1166 0.1929 -1.5465 - -3.000 -0.0271 0.1928 -1.4566 - -2.000 0.0627 0.1925 -1.4749 - -1.000 0.1524 0.1921 -1.5371 - 0.000 0.2429 0.1921 -1.6039 - 1.000 0.3298 0.1922 -1.6711 - 2.000 0.4175 0.1924 -1.7354 - 3.000 0.5011 0.1928 -1.7984 - 5.000 0.6561 0.1940 -1.9418 - 6.000 0.7312 0.1945 -2.0284 - 7.000 0.8043 0.1948 -2.1363 - 8.000 0.8337 0.1957 -2.2463 - 11.000 0.9214 0.2016 -2.6567 - 12.000 0.9530 0.2044 -2.8740 - 14.000 1.0117 0.2112 -3.3444 - 16.000 1.0521 0.2210 -3.8395 - 18.000 1.0883 0.2327 -4.3774 - 21.000 1.1323 0.2540 -5.2529 - 22.000 1.1397 0.2626 -5.5436 - 23.000 1.1462 0.2715 -5.8524 - 24.000 1.1497 0.2808 -6.1500 - 25.000 1.1508 0.2905 -6.4340 - 26.000 1.1476 0.3006 -6.6888 - 27.000 1.1424 0.3108 -6.9235 - 28.000 1.1355 0.3211 -7.1382 - 29.000 1.1271 0.3316 -7.3297 - 30.000 1.1164 0.3423 -7.4909 - 40.000 0.8887 0.5001 -1.5368 - 50.000 0.7093 0.6694 -1.5368 - 60.000 0.5346 0.8309 -1.5368 - 70.000 0.3537 0.9661 -1.5368 - 80.000 0.1711 1.0599 -1.5368 - 90.000 0.0000 1.1024 -1.5368 - 100.000 -0.1198 1.0599 -1.5368 - 110.000 -0.2476 0.9661 -1.5368 - 120.000 -0.3742 0.8309 -1.5368 - 130.000 -0.4965 0.6694 -1.5368 - 140.000 -0.6221 0.5001 -1.5368 - 150.000 -0.7815 0.3423 -1.5368 - 160.000 -0.5210 0.2143 -1.5368 - 170.000 -0.2605 0.1952 -1.5368 - 180.000 0.0000 0.1952 -1.5368 \ No newline at end of file diff --git a/Test_Cases/MHK_RM1/Airfoils/NACA6_0444_coords.txt b/Test_Cases/MHK_RM1/Airfoils/NACA6_0444_coords.txt deleted file mode 100644 index 690c1efd..00000000 --- a/Test_Cases/MHK_RM1/Airfoils/NACA6_0444_coords.txt +++ /dev/null @@ -1,47 +0,0 @@ - 40 NumCoords ! The number of coordinates in the airfoil shape file (including an extra coordinate for airfoil reference). Set to zero if coordinates not included. -! ......... x-y coordinates are next if NumCoords > 0 ............. -! x-y coordinate of airfoil reference -! x/c y/c - 0.25 0 -! coordinates of airfoil shape -! NACA6_0444 Airfoil -! x/c y/c - 0.000000 0.000000 - 0.006819 0.038173 - 0.027091 0.077420 - 0.060263 0.116187 - 0.105430 0.151821 - 0.161359 0.183011 - 0.226526 0.208215 - 0.299152 0.226025 - 0.377257 0.234704 - 0.458710 0.233617 - 0.541290 0.223836 - 0.622743 0.206871 - 0.700848 0.184493 - 0.773474 0.158713 - 0.838641 0.131307 - 0.894570 0.103562 - 0.939737 0.076248 - 0.972909 0.049770 - 0.993181 0.024310 - 1.000000 0.000000 - 0.993181 -0.022489 - 0.972909 -0.044262 - 0.939737 -0.066198 - 0.894570 -0.088734 - 0.838641 -0.111957 - 0.773474 -0.135477 - 0.700848 -0.158393 - 0.622743 -0.179140 - 0.541290 -0.195779 - 0.458710 -0.206420 - 0.377257 -0.209286 - 0.299152 -0.203115 - 0.226526 -0.188588 - 0.161359 -0.167145 - 0.105430 -0.140070 - 0.060263 -0.108468 - 0.027091 -0.073433 - 0.006819 -0.036544 - 0.000000 0.000000 \ No newline at end of file diff --git a/Test_Cases/MHK_RM1/Airfoils/NACA6_0629.dat b/Test_Cases/MHK_RM1/Airfoils/NACA6_0629.dat deleted file mode 100644 index c6856a16..00000000 --- a/Test_Cases/MHK_RM1/Airfoils/NACA6_0629.dat +++ /dev/null @@ -1,560 +0,0 @@ -! ------------ AirfoilInfo v1.01.x Input File ---------------------------------- -! NACA6_0629 airfoil, data based on values used for the design of the RM1 tidal current turbine. -! line -! line -! ------------------------------------------------------------------------------ -"default" InterpOrd ! Interpolation order to use for quasi-steady table lookup {1=linear; 3=cubic spline; "default"} [default=1] - 1.0 NonDimArea ! The non-dimensional area of the airfoil (area/chord^2) (set to 1.0 if unsure or unneeded) -@"NACA6_0629_coords.txt" NumCoords ! The number of coordinates in the airfoil shape file. Set to zero if coordinates not included. -"unused" BL_file ! The file name including the boundary layer characteristics of the profile. Ignored if the aeroacoustic module is not called. - 7 NumTabs ! Number of airfoil tables in this file. -! ------------------------------------------------------------------------------ -! data for table 1 -! ------------------------------------------------------------------------------ - 2.000 Re ! Reynolds number in millions - 0 UserProp ! User property (control) setting -False InclUAdata ! Is unsteady aerodynamics data included in this table? If TRUE, then include 30 UA coefficients below this line -!........................................ -! Table of aerodynamics coefficients - 72 NumAlf ! Number of data lines in the following table -! Alpha Cl Cd Cpmin -! (deg) (-) (-) (-) - -180.000 0.0000 0.1584 -2.0237 - -170.000 0.1523 0.1584 -2.0237 - -160.000 0.3046 0.1880 -2.0237 - -150.000 0.4569 0.2721 -2.0237 - -140.000 0.3758 0.3756 -2.0237 - -130.000 0.3081 0.4864 -2.0237 - -120.000 0.2373 0.5916 -2.0237 - -110.000 0.1599 0.6790 -2.0237 - -100.000 0.0786 0.7385 -2.0237 - -90.000 0.0000 0.7637 -2.0237 - -80.000 -0.0786 0.7385 -2.0237 - -70.000 -0.1599 0.6790 -2.0237 - -60.000 -0.2373 0.5916 -2.0237 - -50.000 -0.3081 0.4864 -2.0237 - -40.000 -0.3758 0.3756 -2.0237 - -30.000 -0.4569 0.2721 -2.0237 - -20.000 -0.3311 0.2173 -2.0237 - -10.000 -0.2932 0.1625 -2.6904 - -9.000 -0.2784 0.1609 -2.5779 - -8.000 -0.2637 0.1596 -2.4693 - -7.000 -0.2374 0.1590 -2.3441 - -6.000 -0.1909 0.1585 -2.2226 - -5.000 -0.1381 0.1581 -2.1261 - -4.000 -0.0829 0.1578 -2.0357 - -3.000 -0.0267 0.1573 -1.9776 - -2.000 0.0328 0.1572 -1.9772 - -1.000 0.0920 0.1571 -2.0182 - 0.000 0.1509 0.1572 -2.0616 - 1.000 0.2102 0.1572 -2.1064 - 2.000 0.2686 0.1573 -2.1510 - 3.000 0.3259 0.1574 -2.1973 - 4.000 0.3811 0.1576 -2.2439 - 5.000 0.4355 0.1578 -2.2951 - 6.000 0.4799 0.1583 -2.3482 - 7.000 0.4977 0.1591 -2.3882 - 8.000 0.5139 0.1602 -2.4500 - 9.000 0.5337 0.1617 -2.5244 - 10.000 0.5542 0.1633 -2.6021 - 11.000 0.5581 0.1662 -2.6596 - 12.000 0.5726 0.1688 -2.7821 - 13.000 0.5773 0.1727 -2.8865 - 14.000 0.5900 0.1762 -3.0158 - 15.000 0.5991 0.1804 -3.1420 - 16.000 0.6130 0.1845 -3.2909 - 17.000 0.6251 0.1889 -3.4442 - 18.000 0.6364 0.1938 -3.6062 - 19.000 0.6469 0.1990 -3.7685 - 20.000 0.6560 0.2045 -3.9359 - 21.000 0.6645 0.2101 -4.1074 - 22.000 0.6741 0.2156 -4.2915 - 23.000 0.6782 0.2219 -4.4584 - 24.000 0.6815 0.2283 -4.6230 - 25.000 0.6820 0.2350 -4.7783 - 26.000 0.6796 0.2421 -4.9112 - 28.000 0.6675 0.2567 -5.1044 - 29.000 0.6584 0.2648 -5.1534 - 30.000 0.6527 0.2721 -5.2137 - 40.000 0.5369 0.3756 -2.0237 - 50.000 0.4402 0.4864 -2.0237 - 60.000 0.3390 0.5916 -2.0237 - 70.000 0.2284 0.6790 -2.0237 - 80.000 0.1123 0.7385 -2.0237 - 90.000 0.0000 0.7637 -2.0237 - 100.000 -0.0786 0.7385 -2.0237 - 110.000 -0.1599 0.6790 -2.0237 - 120.000 -0.2373 0.5916 -2.0237 - 130.000 -0.3081 0.4864 -2.0237 - 140.000 -0.3758 0.3756 -2.0237 - 150.000 -0.4569 0.2721 -2.0237 - 160.000 -0.3046 0.1880 -2.0237 - 170.000 -0.1523 0.1584 -2.0237 - 180.000 0.0000 0.1584 -2.0237 -! ------------------------------------------------------------------------------ -! data for table 2 -! ------------------------------------------------------------------------------ - 4.000 Re ! Reynolds number in millions - 0 UserProp ! User property (control) setting -False InclUAdata ! Is unsteady aerodynamics data included in this table? If TRUE, then include 30 UA coefficients below this line -!........................................ -! Table of aerodynamics coefficients - 69 NumAlf ! Number of data lines in the following table -! Alpha Cl Cd Cpmin -! (deg) (-) (-) (-) - -180.000 0.0000 0.3478 -2.0237 - -170.000 0.1596 0.3478 -2.0237 - -160.000 0.3193 0.3716 -2.0237 - -150.000 0.4789 0.4561 -2.0237 - -140.000 0.3893 0.5602 -2.0237 - -130.000 0.3160 0.6718 -2.0237 - -120.000 0.2415 0.7778 -2.0237 - -110.000 0.1617 0.8662 -2.0237 - -100.000 0.0790 0.9268 -2.0237 - -90.000 0.0000 0.9531 -2.0237 - -80.000 -0.0790 0.9268 -2.0237 - -70.000 -0.1617 0.8662 -2.0237 - -60.000 -0.2415 0.7778 -2.0237 - -50.000 -0.3160 0.6718 -2.0237 - -40.000 -0.3893 0.5602 -2.0237 - -30.000 -0.4789 0.4561 -2.0237 - -20.000 -0.3500 0.4033 -2.0237 - -10.000 -0.3157 0.3505 -2.7378 - -9.000 -0.2927 0.3494 -2.6052 - -8.000 -0.2832 0.3484 -2.5029 - -7.000 -0.2416 0.3478 -2.3517 - -6.000 -0.1909 0.3474 -2.2228 - -5.000 -0.1372 0.3471 -2.1252 - -4.000 -0.0800 0.3468 -2.0327 - -3.000 -0.0222 0.3465 -1.9744 - -1.000 0.0968 0.3461 -2.0210 - 0.000 0.1568 0.3461 -2.0653 - 1.000 0.2159 0.3462 -2.1100 - 2.000 0.2756 0.3462 -2.1555 - 5.000 0.4382 0.3470 -2.2965 - 6.000 0.4769 0.3477 -2.3466 - 7.000 0.5033 0.3483 -2.3927 - 9.000 0.5529 0.3501 -2.5482 - 10.000 0.5627 0.3521 -2.6131 - 11.000 0.5796 0.3542 -2.7011 - 12.000 0.5872 0.3571 -2.8127 - 13.000 0.6011 0.3601 -2.9399 - 14.000 0.6151 0.3633 -3.0792 - 15.000 0.6317 0.3666 -3.2303 - 16.000 0.6451 0.3705 -3.3866 - 17.000 0.6589 0.3745 -3.5565 - 18.000 0.6704 0.3791 -3.7258 - 19.000 0.6818 0.3838 -3.8997 - 20.000 0.6890 0.3894 -4.0719 - 21.000 0.6966 0.3950 -4.2477 - 22.000 0.7031 0.4009 -4.4304 - 23.000 0.7053 0.4073 -4.5965 - 24.000 0.7121 0.4131 -4.7982 - 25.000 0.7124 0.4197 -4.9655 - 26.000 0.7128 0.4262 -5.1291 - 27.000 0.7109 0.4330 -5.2741 - 28.000 0.7070 0.4400 -5.3976 - 29.000 0.6923 0.4485 -5.4307 - 30.000 0.6842 0.4561 -5.4947 - 40.000 0.5561 0.5602 -2.0237 - 50.000 0.4515 0.6718 -2.0237 - 60.000 0.3450 0.7778 -2.0237 - 70.000 0.2309 0.8662 -2.0237 - 80.000 0.1129 0.9268 -2.0237 - 90.000 0.0000 0.9531 -2.0237 - 100.000 -0.0790 0.9268 -2.0237 - 110.000 -0.1617 0.8662 -2.0237 - 120.000 -0.2415 0.7778 -2.0237 - 130.000 -0.3160 0.6718 -2.0237 - 140.000 -0.3893 0.5602 -2.0237 - 150.000 -0.4789 0.4561 -2.0237 - 160.000 -0.3193 0.3716 -2.0237 - 170.000 -0.1596 0.3478 -2.0237 - 180.000 0.0000 0.3478 -2.0237 -! ------------------------------------------------------------------------------ -! data for table 3 -! ------------------------------------------------------------------------------ - 6.000 Re ! Reynolds number in millions - 0 UserProp ! User property (control) setting -False InclUAdata ! Is unsteady aerodynamics data included in this table? If TRUE, then include 30 UA coefficients below this line -!........................................ -! Table of aerodynamics coefficients - 71 NumAlf ! Number of data lines in the following table -! Alpha Cl Cd Cpmin -! (deg) (-) (-) (-) - -180.000 0.0000 0.3632 -2.0237 - -170.000 0.1656 0.3632 -2.0237 - -160.000 0.3312 0.3825 -2.0237 - -150.000 0.4967 0.4674 -2.0237 - -140.000 0.4001 0.5720 -2.0237 - -130.000 0.3224 0.6841 -2.0237 - -120.000 0.2450 0.7908 -2.0237 - -110.000 0.1631 0.8799 -2.0237 - -100.000 0.0794 0.9414 -2.0237 - -90.000 0.0000 0.9685 -2.0237 - -80.000 -0.0794 0.9414 -2.0237 - -70.000 -0.1631 0.8799 -2.0237 - -60.000 -0.2450 0.7908 -2.0237 - -50.000 -0.3224 0.6841 -2.0237 - -40.000 -0.4001 0.5720 -2.0237 - -30.000 -0.4967 0.4674 -2.0237 - -20.000 -0.3634 0.4163 -2.0237 - -10.000 -0.3287 0.3652 -2.7651 - -9.000 -0.3081 0.3641 -2.6335 - -8.000 -0.2884 0.3634 -2.5120 - -7.000 -0.2425 0.3630 -2.3531 - -6.000 -0.1917 0.3626 -2.2240 - -5.000 -0.1361 0.3622 -2.1241 - -4.000 -0.0786 0.3620 -2.0311 - -3.000 -0.0205 0.3618 -1.9734 - -2.000 0.0387 0.3614 -1.9806 - -1.000 0.0989 0.3613 -2.0223 - 0.000 0.1588 0.3613 -2.0664 - 1.000 0.2192 0.3613 -2.1121 - 2.000 0.2774 0.3614 -2.1568 - 4.000 0.3889 0.3619 -2.2512 - 5.000 0.4367 0.3624 -2.2964 - 6.000 0.4784 0.3630 -2.3443 - 7.000 0.5099 0.3634 -2.3993 - 8.000 0.5401 0.3640 -2.4785 - 9.000 0.5570 0.3652 -2.5530 - 10.000 0.5749 0.3668 -2.6297 - 11.000 0.5865 0.3690 -2.7146 - 12.000 0.6012 0.3715 -2.8423 - 13.000 0.6143 0.3743 -2.9702 - 14.000 0.6330 0.3772 -3.1241 - 15.000 0.6477 0.3805 -3.2751 - 16.000 0.6622 0.3841 -3.4373 - 17.000 0.6755 0.3881 -3.6111 - 19.000 0.6970 0.3973 -3.9581 - 20.000 0.7131 0.4015 -4.1697 - 21.000 0.7191 0.4072 -4.3441 - 22.000 0.7228 0.4134 -4.5231 - 23.000 0.7251 0.4197 -4.6981 - 24.000 0.7282 0.4260 -4.8884 - 25.000 0.7295 0.4325 -5.0675 - 26.000 0.7282 0.4392 -5.2283 - 27.000 0.7248 0.4462 -5.3695 - 28.000 0.7208 0.4531 -5.4989 - 29.000 0.7159 0.4602 -5.6135 - 30.000 0.7096 0.4674 -5.7066 - 40.000 0.5715 0.5720 -2.0237 - 50.000 0.4606 0.6841 -2.0237 - 60.000 0.3500 0.7908 -2.0237 - 70.000 0.2331 0.8799 -2.0237 - 80.000 0.1134 0.9414 -2.0237 - 90.000 0.0000 0.9685 -2.0237 - 100.000 -0.0794 0.9414 -2.0237 - 110.000 -0.1631 0.8799 -2.0237 - 120.000 -0.2450 0.7908 -2.0237 - 130.000 -0.3224 0.6841 -2.0237 - 140.000 -0.4001 0.5720 -2.0237 - 150.000 -0.4967 0.4674 -2.0237 - 160.000 -0.3312 0.3825 -2.0237 - 170.000 -0.1656 0.3632 -2.0237 - 180.000 0.0000 0.3632 -2.0237 -! ------------------------------------------------------------------------------ -! data for table 4 -! ------------------------------------------------------------------------------ - 8.000 Re ! Reynolds number in millions - 0 UserProp ! User property (control) setting -False InclUAdata ! Is unsteady aerodynamics data included in this table? If TRUE, then include 30 UA coefficients below this line -!........................................ -! Table of aerodynamics coefficients - 62 NumAlf ! Number of data lines in the following table -! Alpha Cl Cd Cpmin -! (deg) (-) (-) (-) - -180.000 0.0000 0.3632 -2.0237 - -170.000 0.1984 0.3632 -2.0237 - -160.000 0.3969 0.3903 -2.0237 - -150.000 0.4679 0.4746 -2.0237 - -140.000 0.3825 0.5784 -2.0237 - -130.000 0.3121 0.6895 -2.0237 - -120.000 0.2394 0.7950 -2.0237 - -110.000 0.1608 0.8828 -2.0237 - -100.000 0.0788 0.9428 -2.0237 - -90.000 0.0000 0.9685 -2.0237 - -80.000 -0.0788 0.9428 -2.0237 - -70.000 -0.1608 0.8828 -2.0237 - -60.000 -0.2394 0.7950 -2.0237 - -50.000 -0.3121 0.6895 -2.0237 - -40.000 -0.3825 0.5784 -2.0237 - -30.000 -0.4679 0.4746 -2.0237 - -20.000 -0.4101 0.4105 -2.0237 - -10.000 -0.3337 0.3649 -2.7794 - -9.000 -0.3198 0.3637 -2.6556 - -8.000 -0.2924 0.3632 -2.5191 - -5.000 -0.1360 0.3621 -2.1238 - -4.000 -0.0783 0.3619 -2.0308 - -3.000 -0.0193 0.3617 -1.9679 - -2.000 0.0398 0.3614 -1.9812 - -1.000 0.0999 0.3612 -2.0228 - 0.000 0.1605 0.3612 -2.0675 - 1.000 0.2199 0.3612 -2.1125 - 2.000 0.2781 0.3613 -2.1575 - 3.000 0.3353 0.3615 -2.2039 - 4.000 0.3885 0.3619 -2.2464 - 6.000 0.4815 0.3629 -2.3438 - 7.000 0.5192 0.3632 -2.4075 - 8.000 0.5476 0.3638 -2.4872 - 9.000 0.5629 0.3650 -2.5606 - 11.000 0.5926 0.3687 -2.7266 - 12.000 0.6113 0.3708 -2.8637 - 13.000 0.6308 0.3731 -3.0095 - 15.000 0.6651 0.3789 -3.3236 - 16.000 0.6796 0.3824 -3.4907 - 17.000 0.6944 0.3861 -3.6734 - 18.000 0.7045 0.3905 -3.8443 - 19.000 0.7158 0.3950 -4.0304 - 20.000 0.7234 0.4003 -4.2115 - 22.000 0.7319 0.4121 -4.5653 - 25.000 0.7378 0.4313 -5.1162 - 26.000 0.7370 0.4379 -5.2833 - 30.000 0.6684 0.4746 -4.5522 - 40.000 0.5465 0.5784 -2.0237 - 50.000 0.4458 0.6895 -2.0237 - 60.000 0.3420 0.7950 -2.0237 - 70.000 0.2297 0.8828 -2.0237 - 80.000 0.1126 0.9428 -2.0237 - 90.000 0.0000 0.9685 -2.0237 - 100.000 -0.0788 0.9428 -2.0237 - 110.000 -0.1608 0.8828 -2.0237 - 120.000 -0.2394 0.7950 -2.0237 - 130.000 -0.3121 0.6895 -2.0237 - 140.000 -0.3825 0.5784 -2.0237 - 150.000 -0.4679 0.4746 -2.0237 - 160.000 -0.3969 0.3903 -2.0237 - 170.000 -0.1984 0.3632 -2.0237 - 180.000 0.0000 0.3632 -2.0237 -! ------------------------------------------------------------------------------ -! data for table 5 -! ------------------------------------------------------------------------------ - 10.000 Re ! Reynolds number in millions - 0 UserProp ! User property (control) setting -False InclUAdata ! Is unsteady aerodynamics data included in this table? If TRUE, then include 30 UA coefficients below this line -!........................................ -! Table of aerodynamics coefficients - 67 NumAlf ! Number of data lines in the following table -! Alpha Cl Cd Cpmin -! (deg) (-) (-) (-) - -180.000 0.0000 0.3632 -2.0237 - -170.000 0.1712 0.3632 -2.0237 - -160.000 0.3425 0.3778 -2.0237 - -150.000 0.5138 0.4631 -2.0237 - -140.000 0.4104 0.5681 -2.0237 - -130.000 0.3286 0.6809 -2.0237 - -120.000 0.2482 0.7884 -2.0237 - -110.000 0.1646 0.8782 -2.0237 - -100.000 0.0798 0.9405 -2.0237 - -90.000 0.0000 0.9685 -2.0237 - -80.000 -0.0798 0.9405 -2.0237 - -70.000 -0.1646 0.8782 -2.0237 - -60.000 -0.2482 0.7884 -2.0237 - -50.000 -0.3286 0.6809 -2.0237 - -40.000 -0.4104 0.5681 -2.0237 - -30.000 -0.5138 0.4631 -2.0237 - -20.000 -0.3732 0.4140 -2.0237 - -10.000 -0.3325 0.3649 -2.7678 - -9.000 -0.3344 0.3635 -2.6848 - -8.000 -0.2959 0.3630 -2.5253 - -6.000 -0.1924 0.3623 -2.2261 - -4.000 -0.0779 0.3618 -2.0304 - -3.000 -0.0189 0.3617 -1.9686 - -2.000 0.0405 0.3614 -1.9816 - -1.000 0.1009 0.3612 -2.0234 - 0.000 0.1612 0.3611 -2.0679 - 1.000 0.2203 0.3612 -2.1128 - 2.000 0.2782 0.3613 -2.1585 - 4.000 0.3875 0.3620 -2.2442 - 5.000 0.4359 0.3624 -2.2910 - 6.000 0.4831 0.3628 -2.3468 - 7.000 0.5293 0.3631 -2.4164 - 8.000 0.5509 0.3637 -2.4909 - 9.000 0.5709 0.3647 -2.5707 - 10.000 0.5796 0.3665 -2.6284 - 11.000 0.6029 0.3681 -2.7471 - 12.000 0.6203 0.3702 -2.8827 - 13.000 0.6392 0.3725 -3.0293 - 14.000 0.6580 0.3751 -3.1870 - 16.000 0.6899 0.3815 -3.5226 - 17.000 0.7020 0.3853 -3.6982 - 18.000 0.7142 0.3895 -3.8781 - 19.000 0.7237 0.3941 -4.0604 - 20.000 0.7308 0.3993 -4.2413 - 21.000 0.7345 0.4052 -4.4116 - 24.000 0.7535 0.4222 -5.0274 - 25.000 0.7553 0.4285 -5.2186 - 26.000 0.7555 0.4350 -5.3982 - 27.000 0.7535 0.4416 -5.5609 - 28.000 0.7487 0.4485 -5.6991 - 29.000 0.7419 0.4558 -5.8132 - 30.000 0.7340 0.4631 -5.9088 - 40.000 0.5864 0.5681 -2.0237 - 50.000 0.4694 0.6809 -2.0237 - 60.000 0.3546 0.7884 -2.0237 - 70.000 0.2351 0.8782 -2.0237 - 80.000 0.1139 0.9405 -2.0237 - 90.000 0.0000 0.9685 -2.0237 - 100.000 -0.0798 0.9405 -2.0237 - 110.000 -0.1646 0.8782 -2.0237 - 120.000 -0.2482 0.7884 -2.0237 - 130.000 -0.3286 0.6809 -2.0237 - 140.000 -0.4104 0.5681 -2.0237 - 150.000 -0.5138 0.4631 -2.0237 - 160.000 -0.3425 0.3778 -2.0237 - 170.000 -0.1712 0.3632 -2.0237 - 180.000 0.0000 0.3632 -2.0237 -! ------------------------------------------------------------------------------ -! data for table 6 -! ------------------------------------------------------------------------------ - 12.000 Re ! Reynolds number in millions - 0 UserProp ! User property (control) setting -False InclUAdata ! Is unsteady aerodynamics data included in this table? If TRUE, then include 30 UA coefficients below this line -!........................................ -! Table of aerodynamics coefficients - 68 NumAlf ! Number of data lines in the following table -! Alpha Cl Cd Cpmin -! (deg) (-) (-) (-) - -180.000 0.0000 0.3632 -2.0237 - -170.000 0.1804 0.3632 -2.0237 - -160.000 0.3607 0.3794 -2.0237 - -150.000 0.5100 0.4645 -2.0237 - -140.000 0.4081 0.5695 -2.0237 - -130.000 0.3272 0.6820 -2.0237 - -120.000 0.2475 0.7892 -2.0237 - -110.000 0.1643 0.8788 -2.0237 - -100.000 0.0797 0.9408 -2.0237 - -90.000 0.0000 0.9685 -2.0237 - -80.000 -0.0797 0.9408 -2.0237 - -70.000 -0.1643 0.8788 -2.0237 - -60.000 -0.2475 0.7892 -2.0237 - -50.000 -0.3272 0.6820 -2.0237 - -40.000 -0.4081 0.5695 -2.0237 - -30.000 -0.5100 0.4645 -2.0237 - -20.000 -0.3877 0.4121 -2.0237 - -10.000 -0.3390 0.3646 -2.7822 - -7.000 -0.2466 0.3626 -2.3600 - -6.000 -0.1919 0.3623 -2.2206 - -5.000 -0.1358 0.3620 -2.1238 - -4.000 -0.0779 0.3618 -2.0302 - -3.000 -0.0185 0.3616 -1.9699 - -2.000 0.0413 0.3614 -1.9820 - -1.000 0.1014 0.3611 -2.0238 - 0.000 0.1616 0.3611 -2.0680 - 1.000 0.2206 0.3611 -2.1132 - 2.000 0.2786 0.3613 -2.1566 - 3.000 0.3350 0.3615 -2.1991 - 4.000 0.3877 0.3619 -2.2460 - 5.000 0.4363 0.3624 -2.2923 - 6.000 0.4864 0.3627 -2.3500 - 7.000 0.5330 0.3630 -2.4201 - 8.000 0.5543 0.3636 -2.4949 - 10.000 0.5871 0.3661 -2.6410 - 11.000 0.6091 0.3678 -2.7596 - 12.000 0.6303 0.3696 -2.9040 - 13.000 0.6502 0.3718 -3.0554 - 14.000 0.6648 0.3746 -3.2040 - 15.000 0.6814 0.3776 -3.3690 - 17.000 0.7092 0.3846 -3.7218 - 18.000 0.7207 0.3888 -3.9004 - 19.000 0.7301 0.3934 -4.0847 - 20.000 0.7348 0.3989 -4.2570 - 22.000 0.7546 0.4089 -4.6708 - 23.000 0.7585 0.4150 -4.8708 - 24.000 0.7613 0.4211 -5.0702 - 25.000 0.7626 0.4275 -5.2609 - 26.000 0.7621 0.4341 -5.4390 - 27.000 0.7585 0.4408 -5.5940 - 28.000 0.7534 0.4479 -5.7312 - 29.000 0.7472 0.4549 -5.8529 - 30.000 0.7286 0.4645 -5.6184 - 40.000 0.5831 0.5695 -2.0237 - 50.000 0.4674 0.6820 -2.0237 - 60.000 0.3536 0.7892 -2.0237 - 70.000 0.2347 0.8788 -2.0237 - 80.000 0.1138 0.9408 -2.0237 - 90.000 0.0000 0.9685 -2.0237 - 100.000 -0.0797 0.9408 -2.0237 - 110.000 -0.1643 0.8788 -2.0237 - 120.000 -0.2475 0.7892 -2.0237 - 130.000 -0.3272 0.6820 -2.0237 - 140.000 -0.4081 0.5695 -2.0237 - 150.000 -0.5100 0.4645 -2.0237 - 160.000 -0.3607 0.3794 -2.0237 - 170.000 -0.1804 0.3632 -2.0237 - 180.000 0.0000 0.3632 -2.0237 -! ------------------------------------------------------------------------------ -! data for table 7 -! ------------------------------------------------------------------------------ - 14.000 Re ! Reynolds number in millions - 0 UserProp ! User property (control) setting -False InclUAdata ! Is unsteady aerodynamics data included in this table? If TRUE, then include 30 UA coefficients below this line -!........................................ -! Table of aerodynamics coefficients - 64 NumAlf ! Number of data lines in the following table -! Alpha Cl Cd Cpmin -! (deg) (-) (-) (-) - -180.000 0.0000 0.3632 -2.0237 - -170.000 0.1738 0.3632 -2.0237 - -160.000 0.3476 0.3759 -2.0237 - -150.000 0.5215 0.4613 -2.0237 - -140.000 0.4151 0.5666 -2.0237 - -130.000 0.3313 0.6796 -2.0237 - -120.000 0.2497 0.7873 -2.0237 - -110.000 0.1652 0.8775 -2.0237 - -100.000 0.0799 0.9401 -2.0237 - -90.000 0.0000 0.9685 -2.0237 - -80.000 -0.0799 0.9401 -2.0237 - -70.000 -0.1652 0.8775 -2.0237 - -60.000 -0.2497 0.7873 -2.0237 - -50.000 -0.3313 0.6796 -2.0237 - -40.000 -0.4151 0.5666 -2.0237 - -30.000 -0.5215 0.4613 -2.0237 - -20.000 -0.3816 0.4128 -2.0237 - -10.000 -0.3455 0.3643 -2.7960 - -9.000 -0.3360 0.3634 -2.6813 - -8.000 -0.2991 0.3628 -2.5315 - -6.000 -0.1918 0.3622 -2.2194 - -5.000 -0.1357 0.3619 -2.1237 - -4.000 -0.0778 0.3617 -2.0301 - -3.000 -0.0181 0.3616 -1.9701 - -2.000 0.0418 0.3614 -1.9823 - -1.000 0.1017 0.3611 -2.0239 - 0.000 0.1621 0.3611 -2.0684 - 1.000 0.2201 0.3612 -2.1133 - 2.000 0.2786 0.3613 -2.1562 - 3.000 0.3343 0.3616 -2.1982 - 5.000 0.4378 0.3623 -2.2939 - 6.000 0.4879 0.3627 -2.3517 - 7.000 0.5367 0.3629 -2.4237 - 8.000 0.5563 0.3635 -2.4971 - 11.000 0.6148 0.3675 -2.7710 - 12.000 0.6359 0.3693 -2.9159 - 14.000 0.6751 0.3738 -3.2298 - 16.000 0.7020 0.3804 -3.5602 - 18.000 0.7262 0.3882 -3.9191 - 21.000 0.7555 0.4024 -4.5033 - 22.000 0.7605 0.4081 -4.6972 - 23.000 0.7648 0.4141 -4.9033 - 24.000 0.7671 0.4203 -5.1019 - 25.000 0.7679 0.4267 -5.2914 - 26.000 0.7657 0.4335 -5.4614 - 27.000 0.7623 0.4403 -5.6180 - 28.000 0.7577 0.4472 -5.7613 - 29.000 0.7521 0.4542 -5.8891 - 30.000 0.7449 0.4613 -5.9967 - 40.000 0.5930 0.5666 -2.0237 - 50.000 0.4733 0.6796 -2.0237 - 60.000 0.3567 0.7873 -2.0237 - 70.000 0.2360 0.8775 -2.0237 - 80.000 0.1142 0.9401 -2.0237 - 90.000 0.0000 0.9685 -2.0237 - 100.000 -0.0799 0.9401 -2.0237 - 110.000 -0.1652 0.8775 -2.0237 - 120.000 -0.2497 0.7873 -2.0237 - 130.000 -0.3313 0.6796 -2.0237 - 140.000 -0.4151 0.5666 -2.0237 - 150.000 -0.5215 0.4613 -2.0237 - 160.000 -0.3476 0.3759 -2.0237 - 170.000 -0.1738 0.3632 -2.0237 - 180.000 0.0000 0.3632 -2.0237 \ No newline at end of file diff --git a/Test_Cases/MHK_RM1/Airfoils/NACA6_0629_coords.txt b/Test_Cases/MHK_RM1/Airfoils/NACA6_0629_coords.txt deleted file mode 100644 index 0384c9cb..00000000 --- a/Test_Cases/MHK_RM1/Airfoils/NACA6_0629_coords.txt +++ /dev/null @@ -1,47 +0,0 @@ - 40 NumCoords ! The number of coordinates in the airfoil shape file (including an extra coordinate for airfoil reference). Set to zero if coordinates not included. -! ......... x-y coordinates are next if NumCoords > 0 ............. -! x-y coordinate of airfoil reference -! x/c y/c - 0.25 0 -! coordinates of airfoil shape -! NACA6_0629 Airfoil -! x/c y/c - 0.000000 0.000000 - 0.006819 0.053204 - 0.027091 0.106260 - 0.060263 0.157538 - 0.105430 0.204545 - 0.161359 0.245774 - 0.226526 0.279641 - 0.299152 0.304748 - 0.377257 0.319589 - 0.458710 0.323479 - 0.541290 0.317019 - 0.622743 0.301206 - 0.700848 0.277317 - 0.773474 0.246947 - 0.838641 0.211626 - 0.894570 0.172671 - 0.939737 0.131160 - 0.972909 0.087998 - 0.993181 0.044048 - 1.000000 0.000000 - 0.993181 -0.042845 - 0.972909 -0.084360 - 0.939737 -0.124522 - 0.894570 -0.162878 - 0.838641 -0.198845 - 0.773474 -0.231600 - 0.700848 -0.260079 - 0.622743 -0.282891 - 0.541290 -0.298488 - 0.458710 -0.305516 - 0.377257 -0.302801 - 0.299152 -0.289617 - 0.226526 -0.266678 - 0.161359 -0.235296 - 0.105430 -0.196784 - 0.060263 -0.152440 - 0.027091 -0.103626 - 0.006819 -0.052128 - 0.000000 0.000000 \ No newline at end of file diff --git a/Test_Cases/MHK_RM1/Airfoils/NACA6_0864.dat b/Test_Cases/MHK_RM1/Airfoils/NACA6_0864.dat deleted file mode 100644 index d9dc199d..00000000 --- a/Test_Cases/MHK_RM1/Airfoils/NACA6_0864.dat +++ /dev/null @@ -1,560 +0,0 @@ -! ------------ AirfoilInfo v1.01.x Input File ---------------------------------- -! NACA6_0864 airfoil, data based on values used for the design of the RM1 tidal current turbine. -! line -! line -! ------------------------------------------------------------------------------ -"default" InterpOrd ! Interpolation order to use for quasi-steady table lookup {1=linear; 3=cubic spline; "default"} [default=1] - 1.0 NonDimArea ! The non-dimensional area of the airfoil (area/chord^2) (set to 1.0 if unsure or unneeded) -@"NACA6_0864_coords.txt" NumCoords ! The number of coordinates in the airfoil shape file. Set to zero if coordinates not included. -"unused" BL_file ! The file name including the boundary layer characteristics of the profile. Ignored if the aeroacoustic module is not called. - 7 NumTabs ! Number of airfoil tables in this file. -! ------------------------------------------------------------------------------ -! data for table 1 -! ------------------------------------------------------------------------------ - 2.000 Re ! Reynolds number in millions - 0 UserProp ! User property (control) setting -False InclUAdata ! Is unsteady aerodynamics data included in this table? If TRUE, then include 30 UA coefficients below this line -!........................................ -! Table of aerodynamics coefficients - 72 NumAlf ! Number of data lines in the following table -! Alpha Cl Cd Cpmin -! (deg) (-) (-) (-) - -180.000 0.0000 0.2481 -2.6421 - -170.000 0.0558 0.2481 -2.6421 - -160.000 0.1117 0.2589 -2.6421 - -150.000 0.1675 0.2898 -2.6421 - -140.000 0.1378 0.3277 -2.6421 - -130.000 0.1130 0.3683 -2.6421 - -120.000 0.0870 0.4069 -2.6421 - -110.000 0.0586 0.4389 -2.6421 - -100.000 0.0288 0.4607 -2.6421 - -90.000 0.0000 0.4700 -2.6421 - -80.000 -0.0288 0.4607 -2.6421 - -70.000 -0.0586 0.4389 -2.6421 - -60.000 -0.0870 0.4069 -2.6421 - -50.000 -0.1130 0.3683 -2.6421 - -40.000 -0.1378 0.3277 -2.6421 - -30.000 -0.1675 0.2898 -2.6421 - -20.000 -0.1214 0.2697 -2.6421 - -10.000 -0.1075 0.2496 -2.8865 - -9.000 -0.1021 0.2490 -2.8453 - -8.000 -0.0966 0.2485 -2.8054 - -7.000 -0.0870 0.2483 -2.7596 - -6.000 -0.0700 0.2481 -2.7150 - -5.000 -0.0506 0.2480 -2.6796 - -4.000 -0.0304 0.2479 -2.6465 - -3.000 -0.0098 0.2477 -2.6252 - -2.000 0.0120 0.2476 -2.6251 - -1.000 0.0337 0.2476 -2.6401 - 0.000 0.0553 0.2476 -2.6560 - 1.000 0.0771 0.2476 -2.6724 - 2.000 0.0985 0.2477 -2.6888 - 3.000 0.1195 0.2477 -2.7058 - 4.000 0.1397 0.2478 -2.7228 - 5.000 0.1596 0.2479 -2.7416 - 6.000 0.1759 0.2481 -2.7611 - 7.000 0.1825 0.2484 -2.7757 - 8.000 0.1884 0.2488 -2.7984 - 9.000 0.1956 0.2493 -2.8257 - 10.000 0.2031 0.2499 -2.8541 - 11.000 0.2046 0.2510 -2.8752 - 12.000 0.2099 0.2519 -2.9201 - 13.000 0.2116 0.2533 -2.9584 - 14.000 0.2163 0.2546 -3.0058 - 15.000 0.2196 0.2562 -3.0520 - 16.000 0.2247 0.2577 -3.1066 - 17.000 0.2292 0.2593 -3.1628 - 18.000 0.2333 0.2611 -3.2222 - 19.000 0.2371 0.2630 -3.2817 - 20.000 0.2405 0.2650 -3.3431 - 21.000 0.2436 0.2671 -3.4059 - 22.000 0.2471 0.2691 -3.4734 - 23.000 0.2486 0.2714 -3.5346 - 24.000 0.2498 0.2737 -3.5950 - 25.000 0.2500 0.2762 -3.6519 - 26.000 0.2491 0.2788 -3.7006 - 28.000 0.2447 0.2841 -3.7714 - 29.000 0.2414 0.2871 -3.7894 - 30.000 0.2393 0.2898 -3.8115 - 40.000 0.1968 0.3277 -2.6421 - 50.000 0.1614 0.3683 -2.6421 - 60.000 0.1243 0.4069 -2.6421 - 70.000 0.0837 0.4389 -2.6421 - 80.000 0.0412 0.4607 -2.6421 - 90.000 0.0000 0.4700 -2.6421 - 100.000 -0.0288 0.4607 -2.6421 - 110.000 -0.0586 0.4389 -2.6421 - 120.000 -0.0870 0.4069 -2.6421 - 130.000 -0.1130 0.3683 -2.6421 - 140.000 -0.1378 0.3277 -2.6421 - 150.000 -0.1675 0.2898 -2.6421 - 160.000 -0.1117 0.2589 -2.6421 - 170.000 -0.0558 0.2481 -2.6421 - 180.000 0.0000 0.2481 -2.6421 -! ------------------------------------------------------------------------------ -! data for table 2 -! ------------------------------------------------------------------------------ - 4.000 Re ! Reynolds number in millions - 0 UserProp ! User property (control) setting -False InclUAdata ! Is unsteady aerodynamics data included in this table? If TRUE, then include 30 UA coefficients below this line -!........................................ -! Table of aerodynamics coefficients - 69 NumAlf ! Number of data lines in the following table -! Alpha Cl Cd Cpmin -! (deg) (-) (-) (-) - -180.000 0.0000 0.5519 -2.6421 - -170.000 0.0585 0.5519 -2.6421 - -160.000 0.1170 0.5606 -2.6421 - -150.000 0.1756 0.5916 -2.6421 - -140.000 0.1427 0.6298 -2.6421 - -130.000 0.1159 0.6706 -2.6421 - -120.000 0.0885 0.7095 -2.6421 - -110.000 0.0593 0.7419 -2.6421 - -100.000 0.0290 0.7641 -2.6421 - -90.000 0.0000 0.7738 -2.6421 - -80.000 -0.0290 0.7641 -2.6421 - -70.000 -0.0593 0.7419 -2.6421 - -60.000 -0.0885 0.7095 -2.6421 - -50.000 -0.1159 0.6706 -2.6421 - -40.000 -0.1427 0.6298 -2.6421 - -30.000 -0.1756 0.5916 -2.6421 - -20.000 -0.1283 0.5722 -2.6421 - -10.000 -0.1157 0.5529 -2.9039 - -9.000 -0.1073 0.5525 -2.8553 - -8.000 -0.1038 0.5521 -2.8178 - -7.000 -0.0886 0.5519 -2.7624 - -6.000 -0.0700 0.5518 -2.7151 - -5.000 -0.0503 0.5516 -2.6793 - -4.000 -0.0293 0.5515 -2.6454 - -3.000 -0.0081 0.5514 -2.6240 - -1.000 0.0355 0.5513 -2.6411 - 0.000 0.0575 0.5513 -2.6574 - 1.000 0.0791 0.5513 -2.6737 - 2.000 0.1010 0.5513 -2.6904 - 5.000 0.1606 0.5516 -2.7421 - 6.000 0.1748 0.5518 -2.7605 - 7.000 0.1845 0.5521 -2.7774 - 9.000 0.2027 0.5527 -2.8344 - 10.000 0.2063 0.5535 -2.8582 - 11.000 0.2125 0.5542 -2.8904 - 12.000 0.2152 0.5553 -2.9314 - 13.000 0.2203 0.5564 -2.9780 - 14.000 0.2255 0.5576 -3.0290 - 15.000 0.2316 0.5588 -3.0844 - 16.000 0.2365 0.5602 -3.1417 - 17.000 0.2415 0.5617 -3.2040 - 18.000 0.2457 0.5633 -3.2661 - 19.000 0.2499 0.5651 -3.3298 - 20.000 0.2526 0.5671 -3.3930 - 21.000 0.2554 0.5692 -3.4574 - 22.000 0.2578 0.5713 -3.5243 - 23.000 0.2586 0.5737 -3.5852 - 24.000 0.2610 0.5758 -3.6592 - 25.000 0.2612 0.5783 -3.7205 - 26.000 0.2613 0.5806 -3.7805 - 27.000 0.2606 0.5831 -3.8336 - 28.000 0.2592 0.5857 -3.8789 - 29.000 0.2538 0.5888 -3.8910 - 30.000 0.2508 0.5916 -3.9145 - 40.000 0.2038 0.6298 -2.6421 - 50.000 0.1655 0.6706 -2.6421 - 60.000 0.1265 0.7095 -2.6421 - 70.000 0.0847 0.7419 -2.6421 - 80.000 0.0414 0.7641 -2.6421 - 90.000 0.0000 0.7738 -2.6421 - 100.000 -0.0290 0.7641 -2.6421 - 110.000 -0.0593 0.7419 -2.6421 - 120.000 -0.0885 0.7095 -2.6421 - 130.000 -0.1159 0.6706 -2.6421 - 140.000 -0.1427 0.6298 -2.6421 - 150.000 -0.1756 0.5916 -2.6421 - 160.000 -0.1170 0.5606 -2.6421 - 170.000 -0.0585 0.5519 -2.6421 - 180.000 0.0000 0.5519 -2.6421 -! ------------------------------------------------------------------------------ -! data for table 3 -! ------------------------------------------------------------------------------ - 6.000 Re ! Reynolds number in millions - 0 UserProp ! User property (control) setting -False InclUAdata ! Is unsteady aerodynamics data included in this table? If TRUE, then include 30 UA coefficients below this line -!........................................ -! Table of aerodynamics coefficients - 71 NumAlf ! Number of data lines in the following table -! Alpha Cl Cd Cpmin -! (deg) (-) (-) (-) - -180.000 0.0000 0.5765 -2.6421 - -170.000 0.0607 0.5765 -2.6421 - -160.000 0.1214 0.5836 -2.6421 - -150.000 0.1821 0.6147 -2.6421 - -140.000 0.1467 0.6531 -2.6421 - -130.000 0.1182 0.6942 -2.6421 - -120.000 0.0898 0.7333 -2.6421 - -110.000 0.0598 0.7660 -2.6421 - -100.000 0.0291 0.7885 -2.6421 - -90.000 0.0000 0.7984 -2.6421 - -80.000 -0.0291 0.7885 -2.6421 - -70.000 -0.0598 0.7660 -2.6421 - -60.000 -0.0898 0.7333 -2.6421 - -50.000 -0.1182 0.6942 -2.6421 - -40.000 -0.1467 0.6531 -2.6421 - -30.000 -0.1821 0.6147 -2.6421 - -20.000 -0.1332 0.5960 -2.6421 - -10.000 -0.1205 0.5773 -2.9139 - -9.000 -0.1129 0.5769 -2.8656 - -8.000 -0.1057 0.5766 -2.8211 - -7.000 -0.0889 0.5765 -2.7629 - -6.000 -0.0703 0.5763 -2.7155 - -5.000 -0.0499 0.5762 -2.6789 - -4.000 -0.0288 0.5761 -2.6448 - -3.000 -0.0075 0.5760 -2.6237 - -2.000 0.0142 0.5759 -2.6263 - -1.000 0.0362 0.5758 -2.6416 - 0.000 0.0582 0.5758 -2.6578 - 1.000 0.0803 0.5758 -2.6745 - 2.000 0.1017 0.5759 -2.6909 - 4.000 0.1425 0.5760 -2.7255 - 5.000 0.1601 0.5762 -2.7421 - 6.000 0.1754 0.5765 -2.7596 - 7.000 0.1869 0.5766 -2.7798 - 8.000 0.1980 0.5768 -2.8088 - 9.000 0.2042 0.5773 -2.8362 - 10.000 0.2107 0.5779 -2.8643 - 11.000 0.2150 0.5787 -2.8954 - 12.000 0.2204 0.5796 -2.9422 - 13.000 0.2252 0.5806 -2.9891 - 14.000 0.2320 0.5817 -3.0455 - 15.000 0.2374 0.5829 -3.1009 - 16.000 0.2428 0.5842 -3.1603 - 17.000 0.2476 0.5857 -3.2240 - 19.000 0.2555 0.5891 -3.3512 - 20.000 0.2614 0.5906 -3.4288 - 21.000 0.2636 0.5927 -3.4927 - 22.000 0.2650 0.5949 -3.5583 - 23.000 0.2658 0.5973 -3.6225 - 24.000 0.2669 0.5996 -3.6923 - 25.000 0.2674 0.6019 -3.7579 - 26.000 0.2670 0.6044 -3.8169 - 27.000 0.2657 0.6069 -3.8686 - 28.000 0.2642 0.6095 -3.9160 - 29.000 0.2624 0.6121 -3.9580 - 30.000 0.2601 0.6147 -3.9922 - 40.000 0.2095 0.6531 -2.6421 - 50.000 0.1689 0.6942 -2.6421 - 60.000 0.1283 0.7333 -2.6421 - 70.000 0.0854 0.7660 -2.6421 - 80.000 0.0416 0.7885 -2.6421 - 90.000 0.0000 0.7984 -2.6421 - 100.000 -0.0291 0.7885 -2.6421 - 110.000 -0.0598 0.7660 -2.6421 - 120.000 -0.0898 0.7333 -2.6421 - 130.000 -0.1182 0.6942 -2.6421 - 140.000 -0.1467 0.6531 -2.6421 - 150.000 -0.1821 0.6147 -2.6421 - 160.000 -0.1214 0.5836 -2.6421 - 170.000 -0.0607 0.5765 -2.6421 - 180.000 0.0000 0.5765 -2.6421 -! ------------------------------------------------------------------------------ -! data for table 4 -! ------------------------------------------------------------------------------ - 8.000 Re ! Reynolds number in millions - 0 UserProp ! User property (control) setting -False InclUAdata ! Is unsteady aerodynamics data included in this table? If TRUE, then include 30 UA coefficients below this line -!........................................ -! Table of aerodynamics coefficients - 62 NumAlf ! Number of data lines in the following table -! Alpha Cl Cd Cpmin -! (deg) (-) (-) (-) - -180.000 0.0000 0.5765 -2.6421 - -170.000 0.0727 0.5765 -2.6421 - -160.000 0.1455 0.5865 -2.6421 - -150.000 0.1715 0.6174 -2.6421 - -140.000 0.1402 0.6554 -2.6421 - -130.000 0.1144 0.6961 -2.6421 - -120.000 0.0878 0.7348 -2.6421 - -110.000 0.0589 0.7670 -2.6421 - -100.000 0.0289 0.7890 -2.6421 - -90.000 0.0000 0.7984 -2.6421 - -80.000 -0.0289 0.7890 -2.6421 - -70.000 -0.0589 0.7670 -2.6421 - -60.000 -0.0878 0.7348 -2.6421 - -50.000 -0.1144 0.6961 -2.6421 - -40.000 -0.1402 0.6554 -2.6421 - -30.000 -0.1715 0.6174 -2.6421 - -20.000 -0.1503 0.5939 -2.6421 - -10.000 -0.1223 0.5772 -2.9191 - -9.000 -0.1172 0.5767 -2.8738 - -8.000 -0.1072 0.5765 -2.8237 - -5.000 -0.0498 0.5762 -2.6788 - -4.000 -0.0287 0.5761 -2.6447 - -3.000 -0.0071 0.5760 -2.6217 - -2.000 0.0146 0.5759 -2.6265 - -1.000 0.0366 0.5758 -2.6418 - 0.000 0.0588 0.5758 -2.6582 - 1.000 0.0806 0.5758 -2.6747 - 2.000 0.1019 0.5758 -2.6912 - 3.000 0.1229 0.5759 -2.7082 - 4.000 0.1424 0.5761 -2.7238 - 6.000 0.1765 0.5764 -2.7594 - 7.000 0.1903 0.5765 -2.7828 - 8.000 0.2007 0.5767 -2.8120 - 9.000 0.2064 0.5772 -2.8389 - 11.000 0.2172 0.5785 -2.8998 - 12.000 0.2241 0.5793 -2.9500 - 13.000 0.2312 0.5802 -3.0035 - 15.000 0.2438 0.5823 -3.1186 - 16.000 0.2491 0.5836 -3.1799 - 17.000 0.2546 0.5849 -3.2469 - 18.000 0.2582 0.5865 -3.3095 - 19.000 0.2624 0.5882 -3.3777 - 20.000 0.2652 0.5901 -3.4441 - 22.000 0.2683 0.5945 -3.5738 - 25.000 0.2704 0.6015 -3.7758 - 26.000 0.2702 0.6039 -3.8370 - 30.000 0.2450 0.6174 -3.5690 - 40.000 0.2003 0.6554 -2.6421 - 50.000 0.1634 0.6961 -2.6421 - 60.000 0.1254 0.7348 -2.6421 - 70.000 0.0842 0.7670 -2.6421 - 80.000 0.0413 0.7890 -2.6421 - 90.000 0.0000 0.7984 -2.6421 - 100.000 -0.0289 0.7890 -2.6421 - 110.000 -0.0589 0.7670 -2.6421 - 120.000 -0.0878 0.7348 -2.6421 - 130.000 -0.1144 0.6961 -2.6421 - 140.000 -0.1402 0.6554 -2.6421 - 150.000 -0.1715 0.6174 -2.6421 - 160.000 -0.1455 0.5865 -2.6421 - 170.000 -0.0727 0.5765 -2.6421 - 180.000 0.0000 0.5765 -2.6421 -! ------------------------------------------------------------------------------ -! data for table 5 -! ------------------------------------------------------------------------------ - 10.000 Re ! Reynolds number in millions - 0 UserProp ! User property (control) setting -False InclUAdata ! Is unsteady aerodynamics data included in this table? If TRUE, then include 30 UA coefficients below this line -!........................................ -! Table of aerodynamics coefficients - 67 NumAlf ! Number of data lines in the following table -! Alpha Cl Cd Cpmin -! (deg) (-) (-) (-) - -180.000 0.0000 0.5765 -2.6421 - -170.000 0.0628 0.5765 -2.6421 - -160.000 0.1256 0.5819 -2.6421 - -150.000 0.1883 0.6132 -2.6421 - -140.000 0.1505 0.6517 -2.6421 - -130.000 0.1204 0.6930 -2.6421 - -120.000 0.0910 0.7324 -2.6421 - -110.000 0.0603 0.7653 -2.6421 - -100.000 0.0292 0.7882 -2.6421 - -90.000 0.0000 0.7984 -2.6421 - -80.000 -0.0292 0.7882 -2.6421 - -70.000 -0.0603 0.7653 -2.6421 - -60.000 -0.0910 0.7324 -2.6421 - -50.000 -0.1204 0.6930 -2.6421 - -40.000 -0.1505 0.6517 -2.6421 - -30.000 -0.1883 0.6132 -2.6421 - -20.000 -0.1368 0.5952 -2.6421 - -10.000 -0.1219 0.5772 -2.9149 - -9.000 -0.1226 0.5766 -2.8845 - -8.000 -0.1085 0.5765 -2.8260 - -6.000 -0.0705 0.5762 -2.7163 - -4.000 -0.0286 0.5760 -2.6446 - -3.000 -0.0069 0.5760 -2.6219 - -2.000 0.0149 0.5759 -2.6267 - -1.000 0.0370 0.5758 -2.6420 - 0.000 0.0591 0.5758 -2.6583 - 1.000 0.0807 0.5758 -2.6748 - 2.000 0.1020 0.5758 -2.6915 - 4.000 0.1420 0.5761 -2.7229 - 5.000 0.1598 0.5763 -2.7401 - 6.000 0.1771 0.5764 -2.7606 - 7.000 0.1940 0.5765 -2.7861 - 8.000 0.2019 0.5767 -2.8134 - 9.000 0.2093 0.5771 -2.8426 - 10.000 0.2125 0.5778 -2.8638 - 11.000 0.2210 0.5783 -2.9073 - 12.000 0.2274 0.5791 -2.9570 - 13.000 0.2343 0.5800 -3.0108 - 14.000 0.2412 0.5809 -3.0686 - 16.000 0.2529 0.5832 -3.1916 - 17.000 0.2573 0.5847 -3.2559 - 18.000 0.2618 0.5862 -3.3219 - 19.000 0.2653 0.5879 -3.3887 - 20.000 0.2679 0.5898 -3.4550 - 21.000 0.2693 0.5919 -3.5174 - 24.000 0.2762 0.5982 -3.7432 - 25.000 0.2769 0.6005 -3.8133 - 26.000 0.2769 0.6029 -3.8791 - 27.000 0.2762 0.6053 -3.9388 - 28.000 0.2745 0.6078 -3.9894 - 29.000 0.2719 0.6105 -4.0313 - 30.000 0.2691 0.6132 -4.0663 - 40.000 0.2150 0.6517 -2.6421 - 50.000 0.1721 0.6930 -2.6421 - 60.000 0.1300 0.7324 -2.6421 - 70.000 0.0862 0.7653 -2.6421 - 80.000 0.0418 0.7882 -2.6421 - 90.000 0.0000 0.7984 -2.6421 - 100.000 -0.0292 0.7882 -2.6421 - 110.000 -0.0603 0.7653 -2.6421 - 120.000 -0.0910 0.7324 -2.6421 - 130.000 -0.1204 0.6930 -2.6421 - 140.000 -0.1505 0.6517 -2.6421 - 150.000 -0.1883 0.6132 -2.6421 - 160.000 -0.1256 0.5819 -2.6421 - 170.000 -0.0628 0.5765 -2.6421 - 180.000 0.0000 0.5765 -2.6421 -! ------------------------------------------------------------------------------ -! data for table 6 -! ------------------------------------------------------------------------------ - 12.000 Re ! Reynolds number in millions - 0 UserProp ! User property (control) setting -False InclUAdata ! Is unsteady aerodynamics data included in this table? If TRUE, then include 30 UA coefficients below this line -!........................................ -! Table of aerodynamics coefficients - 68 NumAlf ! Number of data lines in the following table -! Alpha Cl Cd Cpmin -! (deg) (-) (-) (-) - -180.000 0.0000 0.5765 -2.6421 - -170.000 0.0661 0.5765 -2.6421 - -160.000 0.1322 0.5825 -2.6421 - -150.000 0.1869 0.6137 -2.6421 - -140.000 0.1496 0.6521 -2.6421 - -130.000 0.1199 0.6934 -2.6421 - -120.000 0.0907 0.7327 -2.6421 - -110.000 0.0602 0.7655 -2.6421 - -100.000 0.0292 0.7883 -2.6421 - -90.000 0.0000 0.7984 -2.6421 - -80.000 -0.0292 0.7883 -2.6421 - -70.000 -0.0602 0.7655 -2.6421 - -60.000 -0.0907 0.7327 -2.6421 - -50.000 -0.1199 0.6934 -2.6421 - -40.000 -0.1496 0.6521 -2.6421 - -30.000 -0.1869 0.6137 -2.6421 - -20.000 -0.1421 0.5945 -2.6421 - -10.000 -0.1243 0.5770 -2.9202 - -7.000 -0.0904 0.5763 -2.7654 - -6.000 -0.0703 0.5762 -2.7143 - -5.000 -0.0498 0.5761 -2.6788 - -4.000 -0.0285 0.5760 -2.6445 - -3.000 -0.0068 0.5760 -2.6224 - -2.000 0.0151 0.5759 -2.6268 - -1.000 0.0372 0.5758 -2.6421 - 0.000 0.0592 0.5758 -2.6584 - 1.000 0.0809 0.5758 -2.6749 - 2.000 0.1021 0.5758 -2.6908 - 3.000 0.1228 0.5759 -2.7064 - 4.000 0.1421 0.5761 -2.7236 - 5.000 0.1599 0.5762 -2.7406 - 6.000 0.1783 0.5763 -2.7617 - 7.000 0.1954 0.5765 -2.7874 - 8.000 0.2032 0.5767 -2.8148 - 10.000 0.2152 0.5776 -2.8684 - 11.000 0.2233 0.5782 -2.9119 - 12.000 0.2310 0.5789 -2.9648 - 13.000 0.2383 0.5797 -3.0203 - 14.000 0.2437 0.5807 -3.0748 - 15.000 0.2498 0.5818 -3.1353 - 17.000 0.2600 0.5844 -3.2646 - 18.000 0.2642 0.5859 -3.3301 - 19.000 0.2676 0.5876 -3.3976 - 20.000 0.2694 0.5896 -3.4608 - 22.000 0.2766 0.5933 -3.6125 - 23.000 0.2780 0.5955 -3.6858 - 24.000 0.2791 0.5978 -3.7589 - 25.000 0.2796 0.6001 -3.8288 - 26.000 0.2794 0.6025 -3.8941 - 27.000 0.2781 0.6050 -3.9509 - 28.000 0.2762 0.6076 -4.0012 - 29.000 0.2739 0.6102 -4.0458 - 30.000 0.2671 0.6137 -3.9598 - 40.000 0.2137 0.6521 -2.6421 - 50.000 0.1713 0.6934 -2.6421 - 60.000 0.1296 0.7327 -2.6421 - 70.000 0.0860 0.7655 -2.6421 - 80.000 0.0417 0.7883 -2.6421 - 90.000 0.0000 0.7984 -2.6421 - 100.000 -0.0292 0.7883 -2.6421 - 110.000 -0.0602 0.7655 -2.6421 - 120.000 -0.0907 0.7327 -2.6421 - 130.000 -0.1199 0.6934 -2.6421 - 140.000 -0.1496 0.6521 -2.6421 - 150.000 -0.1869 0.6137 -2.6421 - 160.000 -0.1322 0.5825 -2.6421 - 170.000 -0.0661 0.5765 -2.6421 - 180.000 0.0000 0.5765 -2.6421 -! ------------------------------------------------------------------------------ -! data for table 7 -! ------------------------------------------------------------------------------ - 14.000 Re ! Reynolds number in millions - 0 UserProp ! User property (control) setting -False InclUAdata ! Is unsteady aerodynamics data included in this table? If TRUE, then include 30 UA coefficients below this line -!........................................ -! Table of aerodynamics coefficients - 64 NumAlf ! Number of data lines in the following table -! Alpha Cl Cd Cpmin -! (deg) (-) (-) (-) - -180.000 0.0000 0.5765 -2.6421 - -170.000 0.0637 0.5765 -2.6421 - -160.000 0.1274 0.5812 -2.6421 - -150.000 0.1912 0.6125 -2.6421 - -140.000 0.1522 0.6511 -2.6421 - -130.000 0.1215 0.6925 -2.6421 - -120.000 0.0915 0.7320 -2.6421 - -110.000 0.0606 0.7651 -2.6421 - -100.000 0.0293 0.7880 -2.6421 - -90.000 0.0000 0.7984 -2.6421 - -80.000 -0.0293 0.7880 -2.6421 - -70.000 -0.0606 0.7651 -2.6421 - -60.000 -0.0915 0.7320 -2.6421 - -50.000 -0.1215 0.6925 -2.6421 - -40.000 -0.1522 0.6511 -2.6421 - -30.000 -0.1912 0.6125 -2.6421 - -20.000 -0.1399 0.5947 -2.6421 - -10.000 -0.1267 0.5770 -2.9252 - -9.000 -0.1232 0.5766 -2.8832 - -8.000 -0.1096 0.5764 -2.8283 - -6.000 -0.0703 0.5762 -2.7138 - -5.000 -0.0497 0.5761 -2.6788 - -4.000 -0.0285 0.5760 -2.6445 - -3.000 -0.0066 0.5759 -2.6225 - -2.000 0.0153 0.5759 -2.6269 - -1.000 0.0373 0.5758 -2.6422 - 0.000 0.0594 0.5758 -2.6585 - 1.000 0.0807 0.5758 -2.6749 - 2.000 0.1021 0.5758 -2.6907 - 3.000 0.1226 0.5759 -2.7061 - 5.000 0.1605 0.5762 -2.7412 - 6.000 0.1789 0.5763 -2.7623 - 7.000 0.1967 0.5764 -2.7887 - 8.000 0.2039 0.5767 -2.8156 - 11.000 0.2254 0.5781 -2.9160 - 12.000 0.2331 0.5788 -2.9692 - 14.000 0.2475 0.5804 -3.0842 - 16.000 0.2573 0.5828 -3.2053 - 18.000 0.2662 0.5857 -3.3369 - 21.000 0.2770 0.5909 -3.5511 - 22.000 0.2788 0.5930 -3.6222 - 23.000 0.2804 0.5952 -3.6977 - 24.000 0.2812 0.5975 -3.7705 - 25.000 0.2815 0.5998 -3.8400 - 26.000 0.2807 0.6023 -3.9023 - 27.000 0.2794 0.6048 -3.9597 - 28.000 0.2777 0.6073 -4.0122 - 29.000 0.2757 0.6099 -4.0591 - 30.000 0.2731 0.6125 -4.0985 - 40.000 0.2174 0.6511 -2.6421 - 50.000 0.1735 0.6925 -2.6421 - 60.000 0.1308 0.7320 -2.6421 - 70.000 0.0865 0.7651 -2.6421 - 80.000 0.0419 0.7880 -2.6421 - 90.000 0.0000 0.7984 -2.6421 - 100.000 -0.0293 0.7880 -2.6421 - 110.000 -0.0606 0.7651 -2.6421 - 120.000 -0.0915 0.7320 -2.6421 - 130.000 -0.1215 0.6925 -2.6421 - 140.000 -0.1522 0.6511 -2.6421 - 150.000 -0.1912 0.6125 -2.6421 - 160.000 -0.1274 0.5812 -2.6421 - 170.000 -0.0637 0.5765 -2.6421 - 180.000 0.0000 0.5765 -2.6421 \ No newline at end of file diff --git a/Test_Cases/MHK_RM1/Airfoils/NACA6_0864_coords.txt b/Test_Cases/MHK_RM1/Airfoils/NACA6_0864_coords.txt deleted file mode 100644 index 8a9382a1..00000000 --- a/Test_Cases/MHK_RM1/Airfoils/NACA6_0864_coords.txt +++ /dev/null @@ -1,47 +0,0 @@ - 40 NumCoords ! The number of coordinates in the airfoil shape file (including an extra coordinate for airfoil reference). Set to zero if coordinates not included. -! ......... x-y coordinates are next if NumCoords > 0 ............. -! x-y coordinate of airfoil reference -! x/c y/c - 0.25 0 -! coordinates of airfoil shape -! NACA6_0864 Airfoil -! x/c y/c - 0.000000 0.000000 - 0.006819 0.071897 - 0.027091 0.142126 - 0.060263 0.208964 - 0.105430 0.270115 - 0.161359 0.323830 - 0.226526 0.368470 - 0.299152 0.402651 - 0.377257 0.425156 - 0.458710 0.435236 - 0.541290 0.432906 - 0.622743 0.418526 - 0.700848 0.392758 - 0.773474 0.356678 - 0.838641 0.311513 - 0.894570 0.258619 - 0.939737 0.199450 - 0.972909 0.135539 - 0.993181 0.068594 - 1.000000 0.000000 - 0.993181 -0.068161 - 0.972909 -0.134227 - 0.939737 -0.197056 - 0.894570 -0.255087 - 0.838641 -0.306904 - 0.773474 -0.351143 - 0.700848 -0.386540 - 0.622743 -0.411920 - 0.541290 -0.426222 - 0.458710 -0.428757 - 0.377257 -0.419101 - 0.299152 -0.397194 - 0.226526 -0.363795 - 0.161359 -0.320050 - 0.105430 -0.267316 - 0.060263 -0.207125 - 0.027091 -0.141176 - 0.006819 -0.071509 - 0.000000 0.000000 \ No newline at end of file diff --git a/Test_Cases/MHK_RM1/Airfoils/NACA6_1000.dat b/Test_Cases/MHK_RM1/Airfoils/NACA6_1000.dat deleted file mode 100644 index 7c3e8471..00000000 --- a/Test_Cases/MHK_RM1/Airfoils/NACA6_1000.dat +++ /dev/null @@ -1,108 +0,0 @@ -! ------------ AirfoilInfo v1.01.x Input File ---------------------------------- -! NACA6_1000 airfoil, data based on values used for the design of the RM1 tidal current turbine. -! line -! line -! ------------------------------------------------------------------------------ -"default" InterpOrd ! Interpolation order to use for quasi-steady table lookup {1=linear; 3=cubic spline; "default"} [default=1] - 1.0 NonDimArea ! The non-dimensional area of the airfoil (area/chord^2) (set to 1.0 if unsure or unneeded) -@"NACA6_1000_coords.txt" NumCoords ! The number of coordinates in the airfoil shape file. Set to zero if coordinates not included. -"unused" BL_file ! The file name including the boundary layer characteristics of the profile. Ignored if the aeroacoustic module is not called. - 7 NumTabs ! Number of airfoil tables in this file. -! ------------------------------------------------------------------------------ -! data for table 1 -! ------------------------------------------------------------------------------ - 2.0 Re ! Reynolds number in millions - 0 UserProp ! User property (control) setting -False InclUAdata ! Is unsteady aerodynamics data included in this table? If TRUE, then include 30 UA coefficients below this line -!........................................ -! Table of aerodynamics coefficients - 3 NumAlf ! Number of data lines in the following table -! Alpha Cl Cd Cpmin -! (deg) (-) (-) (-) - -180.00 0.0 0.3 -3.0 - 0.00 0.0 0.3 -3.0 - 180.00 0.0 0.3 -3.0 -! ------------------------------------------------------------------------------ -! data for table 2 -! ------------------------------------------------------------------------------ - 4.0 Re ! Reynolds number in millions - 0 UserProp ! User property (control) setting -False InclUAdata ! Is unsteady aerodynamics data included in this table? If TRUE, then include 30 UA coefficients below this line -!........................................ -! Table of aerodynamics coefficients - 3 NumAlf ! Number of data lines in the following table -! Alpha Cl Cd Cpmin -! (deg) (-) (-) (-) - -180.00 0.0 0.67 -3.0 - 0.00 0.0 0.67 -3.0 - 180.00 0.0 0.67 -3.0 -! ------------------------------------------------------------------------------ -! data for table 3 -! ------------------------------------------------------------------------------ - 6.0 Re ! Reynolds number in millions - 0 UserProp ! User property (control) setting -False InclUAdata ! Is unsteady aerodynamics data included in this table? If TRUE, then include 30 UA coefficients below this line -!........................................ -! Table of aerodynamics coefficients - 3 NumAlf ! Number of data lines in the following table -! Alpha Cl Cd Cpmin -! (deg) (-) (-) (-) - -180.00 0.0 0.7 -3.0 - 0.00 0.0 0.7 -3.0 - 180.00 0.0 0.7 -3.0 -! ------------------------------------------------------------------------------ -! data for table 4 -! ------------------------------------------------------------------------------ - 8.0 Re ! Reynolds number in millions - 0 UserProp ! User property (control) setting -False InclUAdata ! Is unsteady aerodynamics data included in this table? If TRUE, then include 30 UA coefficients below this line -!........................................ -! Table of aerodynamics coefficients - 3 NumAlf ! Number of data lines in the following table -! Alpha Cl Cd Cpmin -! (deg) (-) (-) (-) - -180.00 0.0 0.7 -3.0 - 0.00 0.0 0.7 -3.0 - 180.00 0.0 0.7 -3.0 -! ------------------------------------------------------------------------------ -! data for table 5 -! ------------------------------------------------------------------------------ - 10.0 Re ! Reynolds number in millions - 0 UserProp ! User property (control) setting -False InclUAdata ! Is unsteady aerodynamics data included in this table? If TRUE, then include 30 UA coefficients below this line -!........................................ -! Table of aerodynamics coefficients - 3 NumAlf ! Number of data lines in the following table -! Alpha Cl Cd Cpmin -! (deg) (-) (-) (-) - -180.00 0.0 0.7 -3.0 - 0.00 0.0 0.7 -3.0 - 180.00 0.0 0.7 -3.0 -! ------------------------------------------------------------------------------ -! data for table 6 -! ------------------------------------------------------------------------------ - 12.0 Re ! Reynolds number in millions - 0 UserProp ! User property (control) setting -False InclUAdata ! Is unsteady aerodynamics data included in this table? If TRUE, then include 30 UA coefficients below this line -!........................................ -! Table of aerodynamics coefficients - 3 NumAlf ! Number of data lines in the following table -! Alpha Cl Cd Cpmin -! (deg) (-) (-) (-) - -180.00 0.0 0.7 -3.0 - 0.00 0.0 0.7 -3.0 - 180.00 0.0 0.7 -3.0 -! ------------------------------------------------------------------------------ -! data for table 7 -! ------------------------------------------------------------------------------ - 14.0 Re ! Reynolds number in millions - 0 UserProp ! User property (control) setting -False InclUAdata ! Is unsteady aerodynamics data included in this table? If TRUE, then include 30 UA coefficients below this line -!........................................ -! Table of aerodynamics coefficients - 3 NumAlf ! Number of data lines in the following table -! Alpha Cl Cd Cpmin -! (deg) (-) (-) (-) - -180.00 0.0 0.7 -3.0 - 0.00 0.0 0.7 -3.0 - 180.00 0.0 0.7 -3.0 \ No newline at end of file diff --git a/Test_Cases/MHK_RM1/Airfoils/NACA6_1000_coords.txt b/Test_Cases/MHK_RM1/Airfoils/NACA6_1000_coords.txt deleted file mode 100644 index e9876cf7..00000000 --- a/Test_Cases/MHK_RM1/Airfoils/NACA6_1000_coords.txt +++ /dev/null @@ -1,47 +0,0 @@ - 40 NumCoords ! The number of coordinates in the airfoil shape file (including an extra coordinate for airfoil reference). Set to zero if coordinates not included. -! ......... x-y coordinates are next if NumCoords > 0 ............. -! x-y coordinate of airfoil reference -! x/c y/c - 0.25 0 -! coordinates of airfoil shape -! NACA6_1000 Airfoil -! x/c y/c - 0.000000 0.000000 - 0.006819 0.082442 - 0.027091 0.162359 - 0.060263 0.237976 - 0.105430 0.307106 - 0.161359 0.367865 - 0.226526 0.418583 - 0.299152 0.457883 - 0.377257 0.484712 - 0.458710 0.498283 - 0.541290 0.498283 - 0.622743 0.484712 - 0.700848 0.457883 - 0.773474 0.418583 - 0.838641 0.367865 - 0.894570 0.307106 - 0.939737 0.237976 - 0.972909 0.162359 - 0.993181 0.082442 - 1.000000 0.000000 - 0.993181 -0.082442 - 0.972909 -0.162359 - 0.939737 -0.237976 - 0.894570 -0.307106 - 0.838641 -0.367865 - 0.773474 -0.418583 - 0.700848 -0.457883 - 0.622743 -0.484712 - 0.541290 -0.498283 - 0.458710 -0.498283 - 0.377257 -0.484712 - 0.299152 -0.457883 - 0.226526 -0.418583 - 0.161359 -0.367865 - 0.105430 -0.307106 - 0.060263 -0.237976 - 0.027091 -0.162359 - 0.006819 -0.082442 - 0.000000 0.000000 \ No newline at end of file diff --git a/Test_Cases/MHK_RM1/MHK_RM1_AeroDyn15_Blade.dat b/Test_Cases/MHK_RM1/MHK_RM1_AeroDyn15_Blade.dat deleted file mode 100644 index 29c7548a..00000000 --- a/Test_Cases/MHK_RM1/MHK_RM1_AeroDyn15_Blade.dat +++ /dev/null @@ -1,38 +0,0 @@ -------- AERODYN v15.00.* BLADE DEFINITION INPUT FILE ------------------------------------- -Floating MHK turbine hydrodynamic blade input properties, based on the RM1 tidal current rotor -====== Blade Properties ================================================================= -32 NumBlNds - Number of blade nodes used in the analysis (-) -BlSpn BlCrvAC BlSwpAC BlCrvAng BlTwist BlChord BlAFID BlCb BlCenBn BlCenBt -(m) (m) (m) (deg) (deg) (m) (-) (-) (m) (m) -0.000 0.00 0.00 0.00 12.86 0.800 1 0.9956 0.0000 0.2000 -0.150 0.00 0.00 0.00 12.86 0.800 1 0.9956 0.0000 0.2000 -0.450 0.00 0.00 0.00 12.86 0.894 2 0.8572 0.0023 0.2202 -0.750 0.00 0.00 0.00 12.86 1.118 3 0.6118 0.0082 0.2637 -1.050 0.00 0.00 0.00 12.86 1.386 4 0.4145 0.0153 0.3027 -1.350 0.00 0.00 0.00 12.86 1.610 5 0.2873 0.0217 0.3131 -1.650 0.00 0.00 0.00 12.86 1.704 6 0.2287 0.0250 0.2973 -1.950 0.00 0.00 0.00 11.54 1.662 7 0.2099 0.0250 0.2753 -2.250 0.00 0.00 0.00 10.44 1.619 8 0.1966 0.0247 0.2565 -2.550 0.00 0.00 0.00 9.50 1.577 9 0.1870 0.0245 0.2386 -2.850 0.00 0.00 0.00 8.71 1.534 9 0.1870 0.0238 0.2321 -3.150 0.00 0.00 0.00 8.02 1.492 9 0.1870 0.0232 0.2258 -3.450 0.00 0.00 0.00 7.43 1.450 9 0.1870 0.0225 0.2194 -3.750 0.00 0.00 0.00 6.91 1.407 9 0.1870 0.0218 0.2129 -4.050 0.00 0.00 0.00 6.45 1.365 9 0.1870 0.0212 0.2066 -4.350 0.00 0.00 0.00 6.04 1.322 9 0.1870 0.0205 0.2001 -4.650 0.00 0.00 0.00 5.68 1.279 9 0.1870 0.0198 0.1935 -4.950 0.00 0.00 0.00 5.35 1.235 9 0.1870 0.0192 0.1869 -5.250 0.00 0.00 0.00 5.05 1.192 9 0.1870 0.0185 0.1804 -5.550 0.00 0.00 0.00 4.77 1.148 9 0.1870 0.0178 0.1737 -5.850 0.00 0.00 0.00 4.51 1.103 9 0.1870 0.0171 0.1669 -6.150 0.00 0.00 0.00 4.26 1.058 9 0.1870 0.0164 0.1601 -6.450 0.00 0.00 0.00 4.03 1.012 9 0.1870 0.0157 0.1531 -6.750 0.00 0.00 0.00 3.80 0.966 9 0.1870 0.0150 0.1462 -7.050 0.00 0.00 0.00 3.57 0.920 9 0.1870 0.0143 0.1392 -7.350 0.00 0.00 0.00 3.35 0.872 9 0.1870 0.0135 0.1320 -7.650 0.00 0.00 0.00 3.13 0.824 9 0.1870 0.0128 0.1247 -7.950 0.00 0.00 0.00 2.90 0.776 9 0.1870 0.0120 0.1174 -8.250 0.00 0.00 0.00 2.67 0.726 9 0.1870 0.0113 0.1099 -8.550 0.00 0.00 0.00 2.43 0.676 9 0.1870 0.0105 0.1023 -8.850 0.00 0.00 0.00 2.18 0.626 9 0.1870 0.0097 0.0947 -9.000 0.00 0.00 0.00 2.18 0.626 9 0.1870 0.0097 0.0947 \ No newline at end of file diff --git a/Test_Cases/MHK_RM1/MHK_RM1_Cp_Ct_Cq.txt b/Test_Cases/MHK_RM1/MHK_RM1_Cp_Ct_Cq.txt deleted file mode 100644 index da7445bf..00000000 --- a/Test_Cases/MHK_RM1/MHK_RM1_Cp_Ct_Cq.txt +++ /dev/null @@ -1,99 +0,0 @@ -# ----- Rotor performance tables for the MHK_RM1_Floating wind turbine ----- -# ------------ Written on Apr-12-23 using the ROSCO toolbox ------------ - -# Pitch angle vector, 36 entries - x axis (matrix columns) (deg) --5.0 -4.0 -3.0 -2.0 -1.0 0.0 1.0 2.0 3.0 4.0 5.0 6.0 7.0 8.0 9.0 10.0 11.0 12.0 13.0 14.0 15.0 16.0 17.0 18.0 19.0 20.0 21.0 22.0 23.0 24.0 25.0 26.0 27.0 28.0 29.0 30.0 -# TSR vector, 26 entries - y axis (matrix rows) (-) -2.0 2.5 3.0 3.5 4.0 4.5 5.0 5.5 6.0 6.5 7.0 7.5 8.0 8.5 9.0 9.5 10.0 10.5 11.0 11.5 12.0 12.5 13.0 13.5 14.0 14.5 -# Wind speed vector - z axis (m/s) -2.0 - -# Power coefficient - -0.074944 0.079726 0.084378 0.088881 0.093217 0.097364 0.101301 0.105005 0.108455 0.111627 0.114499 0.117048 0.119254 0.121097 0.122559 0.123624 0.124278 0.124507 0.124300 0.123645 0.122533 0.120953 0.118899 0.116363 0.113340 0.109825 0.105817 0.101315 0.096316 0.090822 0.084833 0.078355 0.071398 0.063985 0.056154 0.047964 -0.130952 0.137109 0.142870 0.148203 0.153074 0.157453 0.161312 0.164628 0.167372 0.169517 0.171039 0.171924 0.172157 0.171726 0.170619 0.168827 0.166341 0.163154 0.159260 0.154654 0.149334 0.143297 0.136543 0.129071 0.120881 0.111975 0.102356 0.092036 0.081046 0.069441 0.057307 0.044758 0.031932 0.018970 0.006005 -0.006847 -0.195638 0.202139 0.207875 0.212814 0.216927 0.220183 0.222553 0.224026 0.224594 0.224263 0.222996 0.220777 0.217599 0.213457 0.208343 0.202253 0.195185 0.187134 0.178099 0.168078 0.157067 0.145065 0.132070 0.118086 0.103136 0.087277 0.070607 0.053271 0.035454 0.017370 -0.000779 -0.018814 -0.036579 -0.053937 -0.070772 -0.086985 -0.262033 0.267729 0.272255 0.275602 0.277770 0.278772 0.278626 0.277286 0.274722 0.270950 0.265956 0.259691 0.252150 0.243325 0.233208 0.221791 0.209065 0.195021 0.179649 0.162940 0.144884 0.125492 0.104814 0.082960 0.060099 0.036466 0.012350 -0.011952 -0.036178 -0.060102 -0.083527 -0.106282 -0.128227 -0.149248 -0.169259 -0.188203 -0.322926 0.327173 0.329927 0.331189 0.330966 0.329268 0.326118 0.321556 0.315485 0.307866 0.298685 0.287857 0.275361 0.261178 0.245286 0.227663 0.208287 0.187132 0.164179 0.139430 0.112946 0.084868 0.055418 0.024908 -0.006270 -0.037714 -0.069075 -0.100049 -0.130376 -0.159832 -0.188230 -0.215422 -0.241296 -0.265780 -0.288840 -0.310479 -0.372380 0.375319 0.376595 0.376163 0.373941 0.369893 0.364015 0.356336 0.346830 0.335323 0.321769 0.306044 0.288110 0.267928 0.245459 0.220662 0.193502 0.163952 0.132049 0.097926 0.061824 0.024095 -0.014788 -0.054287 -0.093913 -0.133250 -0.171936 -0.209660 -0.246161 -0.281224 -0.314687 -0.346436 -0.376411 -0.404602 -0.431047 -0.455838 -0.405840 0.408981 0.410112 0.409159 0.406069 0.400647 0.392786 0.382501 0.369826 0.354510 0.336432 0.315446 0.291501 0.264544 0.234524 0.201389 0.165121 0.125794 0.083613 0.038921 -0.007794 -0.055894 -0.104692 -0.153592 -0.202082 -0.249721 -0.296127 -0.340984 -0.384037 -0.425096 -0.464037 -0.500803 -0.535402 -0.567911 -0.598467 -0.627270 -0.419815 0.426133 0.429721 0.430398 0.428020 0.422533 0.413665 0.401397 0.385844 0.366737 0.343872 0.317114 0.286411 0.251710 0.212957 0.170136 0.123352 0.072872 0.019131 -0.037250 -0.095463 -0.154643 -0.214052 -0.273053 -0.331092 -0.387697 -0.442469 -0.495093 -0.545333 -0.593039 -0.638145 -0.680670 -0.720718 -0.758469 -0.794184 -0.828187 -0.416203 0.426901 0.435700 0.440694 0.441121 0.436927 0.428055 0.414373 0.396136 0.373105 0.345026 0.311802 0.273402 0.229785 0.180939 0.126984 0.068233 0.005200 -0.061381 -0.130534 -0.201181 -0.272387 -0.343354 -0.413383 -0.481873 -0.548318 -0.612312 -0.673550 -0.731832 -0.787064 -0.839260 -0.888535 -0.935107 -0.979287 -1.021467 -1.062112 -0.405435 0.418564 0.430778 0.441391 0.446693 0.445250 0.437234 0.422572 0.401692 0.374435 0.340533 0.299965 0.252737 0.198854 0.138441 0.071834 -0.000397 -0.077426 -0.158137 -0.241210 -0.325451 -0.409848 -0.493517 -0.575688 -0.655711 -0.733053 -0.807309 -0.878198 -0.945571 -1.009410 -1.069825 -1.127051 -1.181434 -1.233429 -1.283586 -1.332529 -0.390503 0.406666 0.421413 0.435076 0.446065 0.448699 0.442235 0.426873 0.403229 0.371269 0.330765 0.281798 0.224440 0.158821 0.085281 0.004419 -0.082876 -0.175390 -0.271577 -0.369910 -0.469102 -0.568030 -0.665710 -0.761300 -0.854102 -0.943564 -1.029289 -1.111036 -1.188722 -1.262423 -1.332361 -1.398905 -1.462560 -1.523949 -1.583795 -1.642861 -0.371667 0.391683 0.409587 0.425790 0.440553 0.448186 0.443843 0.427902 0.401216 0.363917 0.315877 0.257305 0.188389 0.109467 0.021145 -0.075662 -0.179678 -0.289215 -0.402371 -0.517492 -0.633155 -0.748106 -0.861259 -0.971696 -1.078673 -1.181626 -1.280179 -1.374141 -1.463512 -1.548474 -1.629388 -1.706786 -1.781347 -1.853884 -1.925308 -1.996461 -0.348976 0.373677 0.395430 0.414664 0.431984 0.444452 0.442628 0.426075 0.395932 0.352522 0.295876 0.226363 0.144361 0.050473 -0.054383 -0.168912 -0.291369 -0.419564 -0.551360 -0.684950 -0.818747 -0.951358 -1.081586 -1.208436 -1.331122 -1.449075 -1.561948 -1.669615 -1.772174 -1.869941 -1.963438 -2.053377 -2.140642 -2.226257 -2.311298 -2.396626 -0.322447 0.352671 0.378963 0.401764 0.421785 0.438064 0.438990 0.421654 0.387518 0.337104 0.270664 0.188770 0.092059 -0.018557 -0.141791 -0.275900 -0.418590 -0.567224 -0.719482 -0.873361 -1.027094 -1.179135 -1.328171 -1.473129 -1.613185 -1.747771 -1.876578 -1.999566 -2.116951 -2.229204 -2.337032 -2.441358 -2.543286 -2.644065 -2.744885 -2.846626 -0.292104 0.328674 0.360194 0.387092 0.410155 0.429464 0.433189 0.414787 0.376018 0.317600 0.240072 0.144265 0.031127 -0.098072 -0.241618 -0.397243 -0.562049 -0.733059 -0.907740 -1.083862 -1.259459 -1.432826 -1.602527 -1.767409 -1.926613 -2.079580 -2.226059 -2.366108 -2.500086 -2.628644 -2.752697 -2.873398 -2.992099 -3.110271 -3.229166 -3.349696 -0.257934 0.301688 0.339118 0.370637 0.397092 0.419035 0.425380 0.405542 0.361401 0.293886 0.203884 0.092545 -0.038828 -0.188556 -0.354435 -0.533590 -0.722527 -0.917988 -1.117178 -1.317621 -1.517135 -1.713843 -1.906181 -2.092918 -2.273163 -2.446378 -2.612385 -2.771358 -2.923825 -3.070638 -3.212946 -3.352157 -3.489890 -3.627813 -3.767210 -3.909048 -0.219932 0.271699 0.315725 0.352385 0.382573 0.407064 0.415649 0.393924 0.343586 0.265797 0.161855 0.033279 -0.118226 -0.290520 -0.480838 -0.685625 -0.900846 -1.122958 -1.348868 -1.575829 -1.801429 -2.023608 -2.240672 -2.451307 -2.654600 -2.850044 -3.037549 -3.217434 -3.390412 -3.557560 -3.720288 -3.880284 -4.039448 -4.199603 -4.362066 -4.527873 -0.178135 0.238694 0.290002 0.332317 0.366567 0.393662 0.404032 0.379897 0.322460 0.233142 0.113714 -0.033886 -0.207507 -0.404491 -0.621444 -0.854066 -1.097853 -1.348937 -1.603896 -1.859687 -2.113658 -2.363555 -2.607543 -2.844231 -3.072689 -3.292456 -3.503551 -3.706453 -3.902085 -4.091779 -4.277226 -4.460416 -4.643543 -4.828535 -5.016766 -5.209342 -0.132703 0.202667 0.261930 0.310408 0.349034 0.378811 0.390525 0.363396 0.297884 0.195706 0.059174 -0.109316 -0.307124 -0.531014 -0.776881 -1.039657 -1.314414 -1.596907 -1.883356 -2.170409 -2.455151 -2.735120 -3.008340 -3.273345 -3.529196 -3.775497 -4.012387 -4.240529 -4.461083 -4.675657 -4.886250 -5.095180 -5.304925 -5.517492 -5.734327 -5.956614 -0.084224 0.163639 0.231485 0.286625 0.329931 0.362460 0.375097 0.344332 0.269698 0.153266 -0.002060 -0.193389 -0.417541 -0.670640 -0.947787 -1.243159 -1.551402 -1.867855 -2.188355 -2.509214 -2.827235 -3.139741 -3.444611 -3.740306 -4.025892 -4.301046 -4.566051 -4.821776 -5.069639 -5.311551 -5.549845 -5.787192 -6.026332 -6.269342 -6.517755 -6.772836 -0.034952 0.121693 0.198644 0.260932 0.309208 0.344544 0.357698 0.322599 0.237730 0.105587 -0.070294 -0.286489 -0.539230 -0.823928 -1.134814 -1.465339 -1.809699 -2.162779 -2.520003 -2.877323 -3.231243 -3.578859 -3.917904 -4.246774 -4.564545 -4.870985 -5.166539 -5.452304 -5.729981 -6.001811 -6.270488 -6.539057 -6.810494 -7.086946 -7.370046 -7.661142 --0.011115 0.077127 0.163389 0.233290 0.286813 0.324991 0.338262 0.298075 0.201799 0.052429 -0.145838 -0.389008 -0.672666 -0.991441 -1.338622 -1.706972 -2.090192 -2.482680 -2.879417 -3.275962 -3.668506 -4.053914 -4.429770 -4.794407 -5.146925 -5.487194 -5.815843 -6.134218 -6.444332 -6.748781 -7.050649 -7.353371 -7.660131 -7.973156 -8.294185 -8.624661 --0.050911 0.031047 0.125717 0.203658 0.262692 0.303728 0.316707 0.270625 0.161721 -0.006451 -0.229008 -0.501339 -0.818328 -1.173745 -1.559880 -1.968838 -2.393776 -2.828568 -3.267710 -3.706353 -4.140357 -4.566348 -4.981760 -5.384866 -5.774799 -6.151551 -6.515951 -6.869621 -7.214911 -7.554801 -7.892791 -8.232723 -8.577956 -8.930816 -9.293154 -9.666511 --0.083826 -0.014210 0.085661 0.171992 0.236785 0.280676 0.292937 0.240111 0.117308 -0.071300 -0.320120 -0.623879 -0.976697 -1.371406 -1.799263 -2.251722 -2.721350 -3.201448 -3.685999 -4.169721 -4.648130 -5.117604 -5.575423 -6.019808 -6.449935 -6.865932 -7.268850 -7.660612 -8.043932 -8.422205 -8.799374 -9.179693 -9.566677 -9.962766 -10.369925 -10.789805 --0.112321 -0.056414 0.043373 0.138247 0.209032 0.255752 0.266847 0.206391 0.068370 -0.142368 -0.419492 -0.757024 -1.148255 -1.584993 -2.057449 -2.556414 -3.073813 -3.602329 -4.135402 -4.667292 -5.193160 -5.709124 -6.212312 -6.700894 -7.174100 -7.632211 -8.076523 -8.509287 -8.933609 -9.353325 -9.772854 -10.196858 -10.628998 -11.071839 -11.527466 -11.997652 --0.138289 -0.094091 -0.000597 0.102378 0.179367 0.228869 0.238326 0.169319 0.014717 -0.219903 -0.527445 -0.901172 -1.333484 -1.815079 -2.335120 -2.883708 -3.452066 -4.032220 -4.617034 -5.200293 -5.776782 -6.342352 -6.893976 -7.429778 -7.949056 -8.452259 -8.940954 -9.417741 -9.886149 -10.350489 -10.815681 -11.286791 -11.767617 -12.260864 -12.768741 -13.293158 - - -# Thrust coefficient - -0.173936 0.174545 0.175105 0.175604 0.176027 0.176357 0.176576 0.176665 0.176604 0.176373 0.175951 0.175317 0.174451 0.173333 0.171944 0.170267 0.168285 0.165982 0.163343 0.160355 0.157004 0.153277 0.149165 0.144659 0.139751 0.134439 0.128718 0.122589 0.116054 0.109113 0.101773 0.094042 0.085936 0.077488 0.068744 0.059773 -0.244110 0.244807 0.245270 0.245468 0.245368 0.244940 0.244155 0.242988 0.241410 0.239388 0.236896 0.233914 0.230421 0.226400 0.221834 0.216710 0.211014 0.204738 0.197875 0.190421 0.182376 0.173742 0.164522 0.154724 0.144354 0.133423 0.121945 0.109944 0.097467 0.084590 0.071416 0.058076 0.044718 0.031490 0.018521 0.005920 -0.329058 0.328652 0.327699 0.326163 0.324010 0.321203 0.317708 0.313503 0.308574 0.302916 0.296490 0.289274 0.281258 0.272437 0.262806 0.252366 0.241123 0.229082 0.216256 0.202654 0.188292 0.173184 0.157347 0.140807 0.123614 0.105857 0.087669 0.069222 0.050725 0.032400 0.014449 -0.002964 -0.019698 -0.035638 -0.050689 -0.064777 -0.423724 0.420631 0.416601 0.411609 0.405640 0.398694 0.390781 0.381862 0.371916 0.360960 0.348987 0.335961 0.321889 0.306782 0.290656 0.273525 0.255410 0.236329 0.216303 0.195352 0.173503 0.150806 0.127362 0.103332 0.078936 0.054443 0.030163 0.006389 -0.016641 -0.038731 -0.059724 -0.079492 -0.097938 -0.114987 -0.130589 -0.144718 -0.522708 0.515320 0.506632 0.496639 0.485349 0.472781 0.458970 0.443976 0.427746 0.410278 0.391592 0.371635 0.350431 0.328001 0.304369 0.279560 0.253599 0.226508 0.198319 0.169094 0.138969 0.108161 0.076963 0.045733 0.014882 -0.015203 -0.044217 -0.071919 -0.098118 -0.122660 -0.145431 -0.166347 -0.185356 -0.202436 -0.217593 -0.230865 -0.620986 0.607920 0.593333 0.577234 0.559606 0.540466 0.519860 0.497874 0.474551 0.449800 0.423636 0.395993 0.366897 0.336377 0.304459 0.271170 0.236538 0.200616 0.163534 0.125537 0.086962 0.048236 0.009863 -0.027633 -0.063829 -0.098403 -0.131103 -0.161729 -0.190133 -0.216204 -0.239873 -0.261109 -0.279917 -0.296336 -0.310444 -0.322349 -0.714037 0.694660 0.673585 0.650833 0.626441 0.600346 0.572544 0.543137 0.512256 0.479758 0.445598 0.409704 0.372107 0.332841 0.291934 0.249425 0.205397 0.160063 0.113768 0.066972 0.020233 -0.025799 -0.070499 -0.113396 -0.154133 -0.192434 -0.228087 -0.260935 -0.290868 -0.317827 -0.341795 -0.362800 -0.380914 -0.396253 -0.408976 -0.419282 -0.797619 0.772416 0.745286 0.716196 0.685139 0.652162 0.617157 0.580209 0.541535 0.500976 0.458403 0.413758 0.367089 0.318440 0.267859 0.215464 0.161536 0.106521 0.050989 -0.004371 -0.058762 -0.111433 -0.161837 -0.209563 -0.254300 -0.295806 -0.333907 -0.368486 -0.399482 -0.426887 -0.450748 -0.471165 -0.488287 -0.502317 -0.513506 -0.522151 -0.870407 0.839307 0.807149 0.772800 0.735851 0.696368 0.654402 0.609945 0.563343 0.514447 0.463055 0.409157 0.352830 0.294145 0.233245 0.170467 0.106342 0.041549 -0.023101 -0.086663 -0.148218 -0.207098 -0.262819 -0.315010 -0.363387 -0.407744 -0.447945 -0.483917 -0.515653 -0.543208 -0.566698 -0.586303 -0.602262 -0.614871 -0.624481 -0.631491 -0.937801 0.898777 0.859871 0.820832 0.779117 0.733820 0.685207 0.633320 0.578660 0.521127 0.460477 0.396782 0.330166 0.260796 0.189045 0.115524 0.041008 -0.033579 -0.107154 -0.178587 -0.247028 -0.311881 -0.372693 -0.429119 -0.480906 -0.527879 -0.569945 -0.607081 -0.639338 -0.666842 -0.689787 -0.708441 -0.723135 -0.734268 -0.742302 -0.747750 -1.002272 0.954818 0.907800 0.861790 0.815766 0.765455 0.710516 0.651256 0.588370 0.521837 0.451428 0.377331 0.299768 0.219135 0.136104 0.051544 -0.033517 -0.117878 -0.200191 -0.279333 -0.354544 -0.425257 -0.491041 -0.551574 -0.606630 -0.656072 -0.699848 -0.737992 -0.770621 -0.797933 -0.820208 -0.837806 -0.851169 -0.860810 -0.867314 -0.871279 -1.064598 1.008390 0.952917 0.898894 0.846816 0.792132 0.731177 0.664544 0.593190 0.517221 0.436491 0.351342 0.262208 0.169811 0.075110 -0.020766 -0.116510 -0.210609 -0.301585 -0.388416 -0.470381 -0.546930 -0.617647 -0.682232 -0.740484 -0.792304 -0.837690 -0.876733 -0.909619 -0.936626 -0.958130 -0.974602 -0.986598 -0.994763 -0.999805 -1.002335 -1.125286 1.060007 0.995803 0.933481 0.873901 0.814638 0.747903 0.673814 0.593683 0.507777 0.416109 0.319252 0.217981 0.113352 0.006598 -0.100867 -0.207420 -0.311262 -0.410956 -0.505547 -0.594326 -0.676752 -0.752421 -0.821050 -0.882469 -0.936617 -0.983541 -1.023394 -1.056440 -1.083052 -1.103712 -1.119007 -1.129628 -1.136358 -1.139998 -1.141107 -1.184710 1.110050 1.036840 0.965984 0.898504 0.833644 0.761274 0.679565 0.590284 0.493877 0.390619 0.281434 0.167495 0.050167 -0.069022 -0.188346 -0.305833 -0.419523 -0.528075 -0.630559 -0.726266 -0.814657 -0.895336 -0.968037 -1.032619 -1.089062 -1.137468 -1.178060 -1.211191 -1.237335 -1.257092 -1.271183 -1.280440 -1.285786 -1.288054 -1.287742 -1.243183 1.158809 1.076317 0.996699 0.921110 0.849734 0.771746 0.682183 0.583321 0.475803 0.360302 0.238207 0.111071 -0.019424 -0.151434 -0.282888 -0.411466 -0.535198 -0.652809 -0.763367 -0.866154 -0.960628 -1.046399 -1.123218 -1.190975 -1.249694 -1.299539 -1.340814 -1.373965 -1.399583 -1.418398 -1.431272 -1.439187 -1.443198 -1.444104 -1.442358 -1.300910 1.206519 1.114465 1.025858 0.941977 0.863452 0.779673 0.681967 0.573037 0.453771 0.325405 0.189827 0.048963 -0.095175 -0.240399 -0.384254 -0.524144 -0.658173 -0.785084 -0.903927 -1.013972 -1.114667 -1.205628 -1.286626 -1.357580 -1.418567 -1.469819 -1.511728 -1.544850 -1.569899 -1.587742 -1.599395 -1.606003 -1.608709 -1.608248 -1.605042 -1.358030 1.253357 1.151469 1.053649 0.961301 0.875262 0.785334 0.679149 0.559618 0.427966 0.286133 0.136500 -0.018634 -0.176899 -0.335733 -0.492272 -0.643762 -0.788382 -0.924861 -1.052225 -1.169720 -1.276789 -1.373051 -1.458293 -1.532476 -1.595730 -1.648366 -1.690874 -1.723926 -1.748368 -1.765221 -1.775661 -1.780996 -1.782408 -1.780566 -1.775864 -1.414606 1.299461 1.187483 1.080229 0.979241 0.885469 0.788952 0.673911 0.543212 0.398553 0.242657 0.078384 -0.091569 -0.264451 -0.437297 -0.606831 -0.770255 -0.925787 -1.072124 -1.208256 -1.333409 -1.447015 -1.548693 -1.638256 -1.715703 -1.781230 -1.835235 -1.878313 -1.911261 -1.935071 -1.950921 -1.960159 -1.964252 -1.964367 -1.961118 -1.954875 -1.470532 1.344931 1.222636 1.105728 0.995928 0.894246 0.790705 0.666394 0.523941 0.365671 0.195109 0.015606 -0.169725 -0.357724 -0.544986 -0.727861 -0.903585 -1.070368 -1.226864 -1.372026 -1.505055 -1.625365 -1.732582 -1.826543 -1.907297 -1.975112 -2.030478 -2.074103 -2.106920 -2.130075 -2.144914 -2.152966 -2.155836 -2.154640 -2.149953 -2.142116 -1.525176 1.389818 1.257032 1.130259 1.011475 0.901713 0.790737 0.656712 0.501917 0.329434 0.143594 -0.051741 -0.253016 -0.456636 -0.658718 -0.855321 -1.043728 -1.222114 -1.389084 -1.543550 -1.684675 -1.811862 -1.924743 -2.023186 -2.107295 -2.177416 -2.234138 -2.278294 -2.310959 -2.333441 -2.347264 -2.354147 -2.355801 -2.353275 -2.347110 -2.337621 -1.576091 1.434083 1.290759 1.153917 1.025975 0.907968 0.789164 0.644957 0.477240 0.289934 0.088194 -0.123583 -0.341376 -0.561121 -0.778437 -0.989180 -1.190668 -1.381024 -1.558795 -1.722840 -1.872286 -2.006525 -2.125198 -2.228212 -2.315729 -2.388179 -2.446258 -2.490931 -2.523425 -2.545218 -2.558024 -2.563754 -2.564189 -2.560306 -2.552619 -2.541411 -1.619386 1.477421 1.323881 1.176784 1.039511 0.913087 0.786080 0.631211 0.449991 0.247242 0.028971 -0.199866 -0.434753 -0.671127 -0.904104 -1.129421 -1.344401 -1.547104 -1.736007 -1.909909 -2.067905 -2.209372 -2.333972 -2.441648 -2.532629 -2.607434 -2.666876 -2.712055 -2.744361 -2.765452 -2.777239 -2.781831 -2.781036 -2.775765 -2.766503 -2.753507 -1.652707 1.518703 1.356434 1.198932 1.052154 0.917137 0.781560 0.615550 0.420232 0.201412 -0.034029 -0.280547 -0.533104 -0.786614 -1.035692 -1.276032 -1.504928 -1.720362 -1.920730 -2.104772 -2.271546 -2.420424 -2.551086 -2.663519 -2.758022 -2.835212 -2.896022 -2.941699 -2.973802 -2.994180 -3.004949 -3.008412 -3.006369 -2.999674 -2.988782 -2.973920 -1.676548 1.555748 1.388396 1.220422 1.063964 0.920174 0.775668 0.598036 0.388014 0.152485 -0.100769 -0.365591 -0.636398 -0.907545 -1.173186 -1.429010 -1.672256 -1.900808 -2.112976 -2.307439 -2.483223 -2.639696 -2.776559 -2.893846 -2.991934 -3.071540 -3.133725 -3.179893 -3.211780 -3.231435 -3.241187 -3.243526 -3.240212 -3.232052 -3.219469 -3.202660 -1.694200 1.586793 1.419603 1.241302 1.074992 0.922243 0.768461 0.578719 0.353374 0.100493 -0.171219 -0.454970 -0.744605 -1.033891 -1.316576 -1.588357 -1.846391 -2.088450 -2.312754 -2.517922 -2.702952 -2.867206 -3.010409 -3.132651 -3.234386 -3.316440 -3.380010 -3.426664 -3.458323 -3.477245 -3.485985 -3.487195 -3.482585 -3.472915 -3.458574 -3.439733 -1.707980 1.611070 1.449551 1.261610 1.085283 0.923387 0.759987 0.557635 0.316341 0.045462 -0.245357 -0.548663 -0.857703 -1.165632 -1.465857 -1.754078 -2.027339 -2.283295 -2.520073 -2.736234 -2.930745 -3.102968 -3.252655 -3.379952 -3.485399 -3.569934 -3.634900 -3.682034 -3.713454 -3.731636 -3.739365 -3.739440 -3.733504 -3.722276 -3.706107 -3.685146 - - -# Torque coefficient - -0.037472 0.039863 0.042189 0.044441 0.046608 0.048682 0.050650 0.052503 0.054227 0.055813 0.057249 0.058524 0.059627 0.060548 0.061279 0.061812 0.062139 0.062254 0.062150 0.061823 0.061266 0.060477 0.059449 0.058181 0.056670 0.054913 0.052909 0.050657 0.048158 0.045411 0.042417 0.039178 0.035699 0.031992 0.028077 0.023982 -0.052381 0.054844 0.057148 0.059281 0.061230 0.062981 0.064525 0.065851 0.066949 0.067807 0.068416 0.068770 0.068863 0.068690 0.068248 0.067531 0.066537 0.065262 0.063704 0.061862 0.059734 0.057319 0.054617 0.051628 0.048352 0.044790 0.040942 0.036815 0.032418 0.027777 0.022923 0.017903 0.012773 0.007588 0.002402 -0.002739 -0.065213 0.067380 0.069292 0.070938 0.072309 0.073394 0.074184 0.074675 0.074865 0.074754 0.074332 0.073592 0.072533 0.071152 0.069448 0.067418 0.065062 0.062378 0.059366 0.056026 0.052356 0.048355 0.044023 0.039362 0.034379 0.029092 0.023536 0.017757 0.011818 0.005790 -0.000260 -0.006271 -0.012193 -0.017979 -0.023591 -0.028995 -0.074866 0.076494 0.077787 0.078743 0.079363 0.079649 0.079608 0.079225 0.078492 0.077414 0.075987 0.074198 0.072043 0.069521 0.066631 0.063369 0.059733 0.055720 0.051328 0.046554 0.041395 0.035855 0.029947 0.023703 0.017171 0.010419 0.003529 -0.003415 -0.010337 -0.017172 -0.023865 -0.030366 -0.036636 -0.042642 -0.048360 -0.053772 -0.080732 0.081793 0.082482 0.082797 0.082742 0.082317 0.081529 0.080389 0.078871 0.076967 0.074671 0.071964 0.068840 0.065294 0.061321 0.056916 0.052072 0.046783 0.041045 0.034858 0.028237 0.021217 0.013854 0.006227 -0.001568 -0.009429 -0.017269 -0.025012 -0.032594 -0.039958 -0.047058 -0.053856 -0.060324 -0.066445 -0.072210 -0.077620 -0.082751 0.083404 0.083688 0.083592 0.083098 0.082198 0.080892 0.079186 0.077073 0.074516 0.071504 0.068010 0.064024 0.059540 0.054546 0.049036 0.043000 0.036434 0.029344 0.021761 0.013739 0.005354 -0.003286 -0.012064 -0.020870 -0.029611 -0.038208 -0.046591 -0.054702 -0.062494 -0.069930 -0.076986 -0.083647 -0.089911 -0.095788 -0.101297 -0.081168 0.081796 0.082022 0.081832 0.081214 0.080129 0.078557 0.076500 0.073965 0.070902 0.067286 0.063089 0.058300 0.052909 0.046905 0.040278 0.033024 0.025159 0.016723 0.007784 -0.001559 -0.011179 -0.020938 -0.030718 -0.040416 -0.049944 -0.059225 -0.068197 -0.076807 -0.085019 -0.092807 -0.100161 -0.107080 -0.113582 -0.119693 -0.125454 -0.076330 0.077479 0.078131 0.078254 0.077822 0.076824 0.075212 0.072981 0.070153 0.066679 0.062522 0.057657 0.052075 0.045766 0.038719 0.030934 0.022428 0.013249 0.003478 -0.006773 -0.017357 -0.028117 -0.038919 -0.049646 -0.060199 -0.070490 -0.080449 -0.090017 -0.099151 -0.107825 -0.116026 -0.123758 -0.131040 -0.137904 -0.144397 -0.150580 -0.069367 0.071150 0.072617 0.073449 0.073520 0.072821 0.071343 0.069062 0.066023 0.062184 0.057504 0.051967 0.045567 0.038298 0.030157 0.021164 0.011372 0.000867 -0.010230 -0.021756 -0.033530 -0.045398 -0.057226 -0.068897 -0.080312 -0.091386 -0.102052 -0.112258 -0.121972 -0.131177 -0.139877 -0.148089 -0.155851 -0.163214 -0.170244 -0.177019 -0.062375 0.064394 0.066274 0.067906 0.068722 0.068500 0.067267 0.065011 0.061799 0.057605 0.052390 0.046148 0.038883 0.030593 0.021299 0.011051 -0.000061 -0.011912 -0.024329 -0.037109 -0.050069 -0.063054 -0.075926 -0.088567 -0.100879 -0.112777 -0.124201 -0.135107 -0.145472 -0.155294 -0.164589 -0.173392 -0.181759 -0.189758 -0.197475 -0.205004 -0.055786 0.058095 0.060202 0.062154 0.063724 0.064100 0.063176 0.060982 0.057604 0.053038 0.047252 0.040257 0.032063 0.022689 0.012183 0.000631 -0.011839 -0.025056 -0.038797 -0.052844 -0.067015 -0.081147 -0.095101 -0.108757 -0.122015 -0.134795 -0.147041 -0.158719 -0.169817 -0.180346 -0.190337 -0.199844 -0.208937 -0.217707 -0.226256 -0.234694 -0.049556 0.052224 0.054612 0.056772 0.058740 0.059758 0.059179 0.057054 0.053496 0.048522 0.042117 0.034307 0.025119 0.014596 0.002819 -0.010088 -0.023957 -0.038562 -0.053649 -0.068999 -0.084421 -0.099747 -0.114835 -0.129559 -0.143823 -0.157550 -0.170690 -0.183219 -0.195135 -0.206463 -0.217252 -0.227571 -0.237513 -0.247185 -0.256708 -0.266195 -0.043622 0.046710 0.049429 0.051833 0.053998 0.055556 0.055329 0.053259 0.049491 0.044065 0.036985 0.028295 0.018045 0.006309 -0.006798 -0.021114 -0.036421 -0.052446 -0.068920 -0.085619 -0.102343 -0.118920 -0.135198 -0.151054 -0.166390 -0.181134 -0.195243 -0.208702 -0.221522 -0.233743 -0.245430 -0.256672 -0.267580 -0.278282 -0.288912 -0.299578 -0.037935 0.041491 0.044584 0.047266 0.049622 0.051537 0.051646 0.049606 0.045590 0.039659 0.031843 0.022208 0.010830 -0.002183 -0.016681 -0.032459 -0.049246 -0.066732 -0.084645 -0.102748 -0.120835 -0.138722 -0.156255 -0.173309 -0.189786 -0.205620 -0.220774 -0.235243 -0.249053 -0.262259 -0.274945 -0.287219 -0.299210 -0.311066 -0.322928 -0.334897 -0.032456 0.036519 0.040022 0.043010 0.045573 0.047718 0.048132 0.046087 0.041780 0.035289 0.026675 0.016029 0.003459 -0.010897 -0.026846 -0.044138 -0.062450 -0.081451 -0.100860 -0.120429 -0.139940 -0.159203 -0.178059 -0.196379 -0.214068 -0.231064 -0.247340 -0.262901 -0.277787 -0.292072 -0.305855 -0.319266 -0.332455 -0.345586 -0.358796 -0.372188 -0.027151 0.031757 0.035697 0.039014 0.041799 0.044109 0.044777 0.042689 0.038042 0.030935 0.021462 0.009742 -0.004087 -0.019848 -0.037309 -0.056167 -0.076055 -0.096630 -0.117598 -0.138697 -0.159698 -0.180404 -0.200651 -0.220307 -0.239280 -0.257514 -0.274988 -0.291722 -0.307771 -0.323225 -0.338205 -0.352859 -0.367357 -0.381875 -0.396548 -0.411479 -0.021993 0.027170 0.031573 0.035239 0.038257 0.040706 0.041565 0.039392 0.034359 0.026580 0.016186 0.003328 -0.011823 -0.029052 -0.048084 -0.068562 -0.090085 -0.112296 -0.134887 -0.157583 -0.180143 -0.202361 -0.224067 -0.245131 -0.265460 -0.285004 -0.303755 -0.321743 -0.339041 -0.355756 -0.372029 -0.388028 -0.403945 -0.419960 -0.436207 -0.452787 -0.016965 0.022733 0.027619 0.031649 0.034911 0.037492 0.038479 0.036181 0.030710 0.022204 0.010830 -0.003227 -0.019763 -0.038523 -0.059185 -0.081340 -0.104557 -0.128470 -0.152752 -0.177113 -0.201301 -0.225100 -0.248337 -0.270879 -0.292637 -0.313567 -0.333672 -0.352996 -0.371627 -0.389693 -0.407355 -0.424802 -0.442242 -0.459860 -0.477787 -0.496128 -0.012064 0.018424 0.023812 0.028219 0.031730 0.034437 0.035502 0.033036 0.027080 0.017791 0.005379 -0.009938 -0.027920 -0.048274 -0.070626 -0.094514 -0.119492 -0.145173 -0.171214 -0.197310 -0.223196 -0.248647 -0.273485 -0.297577 -0.320836 -0.343227 -0.364762 -0.385503 -0.405553 -0.425060 -0.444205 -0.463198 -0.482266 -0.501590 -0.521302 -0.541510 -0.007324 0.014229 0.020129 0.024924 0.028690 0.031518 0.032617 0.029942 0.023452 0.013327 -0.000179 -0.016816 -0.036308 -0.058317 -0.082416 -0.108101 -0.134905 -0.162422 -0.190292 -0.218192 -0.245847 -0.273021 -0.299531 -0.325244 -0.350078 -0.374004 -0.397048 -0.419285 -0.440838 -0.461874 -0.482595 -0.503234 -0.524029 -0.545160 -0.566761 -0.588942 -0.002913 0.010141 0.016554 0.021744 0.025767 0.028712 0.029808 0.026883 0.019811 0.008799 -0.005858 -0.023874 -0.044936 -0.068661 -0.094568 -0.122112 -0.150808 -0.180232 -0.210000 -0.239777 -0.269270 -0.298238 -0.326492 -0.353898 -0.380379 -0.405915 -0.430545 -0.454359 -0.477498 -0.500151 -0.522541 -0.544921 -0.567541 -0.590579 -0.614170 -0.638429 --0.000889 0.006170 0.013071 0.018663 0.022945 0.025999 0.027061 0.023846 0.016144 0.004194 -0.011667 -0.031121 -0.053813 -0.079315 -0.107090 -0.136558 -0.167215 -0.198614 -0.230353 -0.262077 -0.293480 -0.324313 -0.354382 -0.383553 -0.411754 -0.438976 -0.465267 -0.490737 -0.515547 -0.539903 -0.564052 -0.588270 -0.612810 -0.637852 -0.663535 -0.689973 --0.003916 0.002388 0.009671 0.015666 0.020207 0.023364 0.024362 0.020817 0.012440 -0.000496 -0.017616 -0.038565 -0.062948 -0.090288 -0.119991 -0.151449 -0.184137 -0.217582 -0.251362 -0.285104 -0.318489 -0.351258 -0.383212 -0.414220 -0.444215 -0.473196 -0.501227 -0.528432 -0.554993 -0.581139 -0.607138 -0.633286 -0.659843 -0.686986 -0.714858 -0.743578 --0.006209 -0.001053 0.006345 0.012740 0.017540 0.020791 0.021699 0.017786 0.008689 -0.005281 -0.023713 -0.046213 -0.072348 -0.101586 -0.133279 -0.166794 -0.201581 -0.237144 -0.273037 -0.308868 -0.344306 -0.379082 -0.412994 -0.445912 -0.477773 -0.508588 -0.538433 -0.567453 -0.595847 -0.623867 -0.651805 -0.679977 -0.708643 -0.737983 -0.768143 -0.799245 --0.008023 -0.004030 0.003098 0.009875 0.014931 0.018268 0.019060 0.014742 0.004884 -0.010169 -0.029964 -0.054073 -0.082018 -0.113214 -0.146961 -0.182601 -0.219558 -0.257309 -0.295386 -0.333378 -0.370940 -0.407795 -0.443737 -0.478635 -0.512436 -0.545158 -0.576895 -0.607806 -0.638115 -0.668095 -0.698061 -0.728347 -0.759214 -0.790846 -0.823390 -0.856975 --0.009537 -0.006489 -0.000041 0.007061 0.012370 0.015784 0.016436 0.011677 0.001015 -0.015166 -0.036375 -0.062150 -0.091964 -0.125178 -0.161043 -0.198876 -0.238074 -0.278084 -0.318416 -0.358641 -0.398399 -0.437404 -0.475447 -0.512399 -0.548211 -0.582914 -0.616617 -0.649499 -0.681803 -0.713827 -0.745909 -0.778399 -0.811560 -0.845577 -0.880603 -0.916770 - diff --git a/Test_Cases/MHK_RM1/MHK_RM1_DISCON.IN b/Test_Cases/MHK_RM1/MHK_RM1_DISCON.IN deleted file mode 100644 index 704f4409..00000000 --- a/Test_Cases/MHK_RM1/MHK_RM1_DISCON.IN +++ /dev/null @@ -1,192 +0,0 @@ -! Controller parameter input file for the MHK_RM1_Floating wind turbine -! - File written using ROSCO version 2.8.0 controller tuning logic on 10/18/23 - -!------- SIMULATION CONTROL ------------------------------------------------------------ -2 ! LoggingLevel - {0: write no debug files, 1: write standard output .dbg-file, 2: LoggingLevel 1 + ROSCO LocalVars (.dbg2) 3: LoggingLevel 2 + complete avrSWAP-array (.dbg3)} -0 ! DT_Out - {Time step to output .dbg* files, or 0 to match sampling period of OpenFAST} -0 ! Echo - (0 - no Echo, 1 - Echo input data to .echo) - -!------- 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 ! IPC_ControlMode - Turn Individual Pitch Control (IPC) for fatigue load reductions (pitch contribution) {0: off, 1: 1P reductions, 2: 1P+2P reductions} -3 ! VS_ControlMode - Generator torque control mode in above rated conditions (0- no torque control, 1- k*omega^2 with PI transitions, 2- WSE TSR Tracking, 3- Power-based TSR Tracking)} -1 ! VS_ConstPower - Do constant power torque control, where above rated torque varies, 0 for constant torque} -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} -0 ! PRC_Mode - Power reference tracking mode{0: use standard rotor speed set points, 1: use PRC rotor speed setpoints} -0 ! WE_Mode - Wind speed estimator mode {0: One-second low pass filtered hub height wind speed, 1: Immersion and Invariance Estimator, 2: Extended Kalman Filter} -0 ! PS_Mode - Pitch saturation mode {0: no pitch saturation, 1: implement pitch saturation} -0 ! SD_Mode - Shutdown mode {0: no shutdown procedure, 1: pitch to max pitch at shutdown} -1 ! Fl_Mode - Floating specific feedback mode {0: no nacelle velocity feedback, 1: feed back translational velocity, 2: feed back rotational veloicty} -0 ! TD_Mode - Tower damper mode {0: no tower damper, 1: feed back translational nacelle accelleration to pitch angle} -0 ! Flp_Mode - Flap control mode {0: no flap control, 1: steady state flap angle, 2: Proportional flap control, 2: Cyclic (1P) flap control} -0 ! OL_Mode - Open loop control mode {0: no open loop control, 1: open loop control vs. time, 2: rotor position control} -0 ! PA_Mode - Pitch actuator mode {0 - not used, 1 - first order filter, 2 - second order filter} -0 ! PF_Mode - Pitch fault mode {0 - not used, 1 - constant offset on one or more blades} -0 ! AWC_Mode - Active wake control {0 - not used, 1 - complex number method, 2 - Coleman transform method} -0 ! Ext_Mode - External control mode {0 - not used, 1 - call external dynamic library} -0 ! ZMQ_Mode - Fuse ZeroMQ interface {0: unused, 1: Yaw Control} -0 ! CC_Mode - Cable control mode [0- unused, 1- User defined, 2- Open loop control] -0 ! StC_Mode - Structural control mode [0- unused, 1- User defined, 2- Open loop control] - -!------- FILTERS ---------------------------------------------------------- -15.07080 ! F_LPFCornerFreq - Corner frequency (-3dB point) in the low-pass filters, [rad/s] -0.00000 ! F_LPFDamping - Damping coefficient {used only when F_FilterType = 2} [-] -2 ! F_NumNotchFilts - Number of notch filters placed on sensors -1.0000 2.4200 ! F_NotchFreqs - Natural frequency of the notch filters. Array with length F_NumNotchFilts -0.0000 0.0000 ! F_NotchBetaNum - Damping value of numerator (determines the width of notch). Array with length F_NumNotchFilts, [-] -0.2500 0.2500 ! F_NotchBetaDen - Damping value of denominator (determines the depth of notch). Array with length F_NumNotchFilts, [-] -2 ! F_GenSpdNotch_N - Number of notch filters on generator speed -1 2 ! F_GenSpdNotch_Ind - Indices of notch filters on generator speed -2 ! F_TwrTopNotch_N - Number of notch filters on tower top acceleration signal -1 2 ! F_TwrTopNotch_Ind - Indices of notch filters on tower top acceleration signal -0.62830 ! F_SSCornerFreq - Corner frequency (-3dB point) in the first order low pass filter for the setpoint smoother, [rad/s]. -0.20944 ! F_WECornerFreq - Corner frequency (-3dB point) in the first order low pass filter for the wind speed estimate [rad/s]. -0.17952 ! F_YawErr - Low pass filter corner frequency for yaw controller [rad/s]. -0.661300 1.000000 ! F_FlCornerFreq - Natural frequency and damping in the second order low pass filter of the tower-top fore-aft motion for floating feedback control [rad/s, -]. -1.50000 ! F_FlHighPassFreq - Natural frequency of first-order high-pass filter for nacelle fore-aft motion [rad/s]. -0.0000 1.0000 ! F_FlpCornerFreq - Corner frequency and damping in the second order low pass filter of the blade root bending moment for flap control - -!------- BLADE PITCH CONTROL ---------------------------------------------- -30 ! PC_GS_n - Amount of gain-scheduling table entries -0.030335 0.049075 0.063610 0.076093 0.087460 0.097196 0.106672 0.115225 0.123634 0.131302 0.139019 0.146056 0.153083 0.159873 0.166338 0.172854 0.178999 0.185046 0.191143 0.196863 0.202559 0.208301 0.213742 0.219137 0.224575 0.229836 0.234972 0.240145 0.245291 0.250200 ! PC_GS_angles - Gain-schedule table: pitch angles [rad]. --0.010178 -0.008780 -0.007625 -0.006655 -0.005829 -0.005116 -0.004495 -0.003950 -0.003467 -0.003036 -0.002650 -0.002301 -0.001984 -0.001696 -0.001432 -0.001190 -0.000966 -0.000760 -0.000568 -0.000390 -0.000225 -0.000069 0.000076 0.000212 0.000340 0.000461 0.000575 0.000682 0.000784 0.000881 ! PC_GS_KP - Gain-schedule table: pitch controller kp gains [s]. --0.005272 -0.004770 -0.004355 -0.004007 -0.003710 -0.003454 -0.003232 -0.003036 -0.002862 -0.002708 -0.002569 -0.002443 -0.002330 -0.002226 -0.002132 -0.002045 -0.001964 -0.001890 -0.001822 -0.001758 -0.001698 -0.001642 -0.001590 -0.001541 -0.001495 -0.001452 -0.001411 -0.001372 -0.001336 -0.001301 ! PC_GS_KI - Gain-schedule table: pitch controller ki gains [-]. -0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 ! PC_GS_KD - Gain-schedule table: pitch controller kd gains -0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 ! PC_GS_TF - Gain-schedule table: pitch controller tf gains (derivative filter) -1.570000000000 ! PC_MaxPit - Maximum physical pitch limit, [rad]. -0.000690000000 ! PC_MinPit - Minimum physical pitch limit, [rad]. -0.174500000000 ! PC_MaxRat - Maximum pitch rate (in absolute value) in pitch controller, [rad/s]. --0.17450000000 ! PC_MinRat - Minimum pitch rate (in absolute value) in pitch controller, [rad/s]. -63.81200000000 ! PC_RefSpd - Desired (reference) HSS speed for pitch controller, [rad/s]. -0.000690000000 ! PC_FinePit - Record 5: Below-rated pitch angle set-point, [rad] -0.017450000000 ! PC_Switch - Angle above lowest minimum pitch angle for switch, [rad] - -!------- INDIVIDUAL PITCH CONTROL ----------------------------------------- -1.600000 2.000000 ! IPC_Vramp - Start and end wind speeds for cut-in ramp function. First entry: IPC inactive, second entry: IPC fully active. [m/s] -2 ! IPC_SatMode - IPC Saturation method (0 - no saturation (except by PC_MinPit), 1 - saturate by PS_BldPitchMin, 2 - saturate sotfly (full IPC cycle) by PC_MinPit, 3 - saturate softly by PS_BldPitchMin) -0.3 ! IPC_IntSat - Integrator saturation (maximum signal amplitude contribution to pitch from IPC), [rad] -0.000e+00 0.000e+00 ! IPC_KP - Proportional gain for the individual pitch controller: first parameter for 1P reductions, second for 2P reductions, [-] -0.000e+00 0.000e+00 ! IPC_KI - Integral gain for the individual pitch controller: first parameter for 1P reductions, second for 2P reductions, [-] -0.000000 0.000000 ! 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 ------------------------------------------------ -94.40000000000 ! VS_GenEff - Generator efficiency mechanical power -> electrical power, [should match the efficiency defined in the generator properties!], [%] -8300.335630000 ! VS_ArSatTq - Above rated generator torque PI control saturation, [Nm] -1500000.000000 ! VS_MaxRat - Maximum torque rate (in absolute value) in torque controller, [Nm/s]. -12450.50344000 ! VS_MaxTq - Maximum generator torque in Region 3 (HSS side), [Nm]. -0.000000000000 ! VS_MinTq - Minimum generator torque (HSS side), [Nm]. -19.00309000000 ! VS_MinOMSpd - Minimum generator speed [rad/s] -1.142870000000 ! VS_Rgn2K - Generator torque constant in Region 2 (HSS side). Only used in VS_ControlMode = 1,3 -500000.0000000 ! VS_RtPwr - Wind turbine rated power [W] -8300.335630000 ! VS_RtTq - Rated torque, [Nm]. -63.81200000000 ! VS_RefSpd - Rated generator speed [rad/s] -1 ! VS_n - Number of generator PI torque controller gains --63.8796200000 ! VS_KP - Proportional gain for generator PI torque controller [-]. (Only used in the transitional 2.5 region if VS_ControlMode =/ 2) --84.4329000000 ! VS_KI - Integral gain for generator PI torque controller [s]. (Only used in the transitional 2.5 region if VS_ControlMode =/ 2) -7.17 ! VS_TSRopt - Power-maximizing region 2 tip-speed-ratio. Only used in VS_ControlMode = 2. -0.314000000000 ! VS_PwrFiltF - Low pass filter on power used to determine generator speed set point. Only used in VS_ControlMode = 3. - -!------- SETPOINT SMOOTHER --------------------------------------------- -1.00000 ! SS_VSGain - Variable speed torque controller setpoint smoother gain, [-]. -0.00100 ! SS_PCGain - Collective pitch controller setpoint smoother gain, [-]. - -!------- POWER REFERENCE TRACKING -------------------------------------- -2 ! PRC_n - Number of elements in PRC_WindSpeeds and PRC_GenSpeeds array -0.07854 ! PRC_LPF_Freq - Frequency of the low pass filter on the wind speed estimate used to set PRC_GenSpeeds [rad/s] -3.0000 25.0000 ! PRC_WindSpeeds - Array of wind speeds used in rotor speed vs. wind speed lookup table [m/s] -0.7917 0.7917 ! PRC_GenSpeeds - Array of generator speeds corresponding to PRC_WindSpeeds [rad/s] - -!------- WIND SPEED ESTIMATOR --------------------------------------------- -10.000 ! WE_BladeRadius - Blade length (distance from hub center to blade tip), [m] -1 ! WE_CP_n - Amount of parameters in the Cp array -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] -53.0 ! WE_GearboxRatio - Gearbox ratio [>=1], [-] -484024.50000 ! WE_Jtot - Total drivetrain inertia, including blades, hub and casted generator inertia to LSS, [kg m^2] -1025.000 ! WE_RhoAir - Air density, [kg m^-3] -"MHK_RM1_Cp_Ct_Cq.txt" ! PerfFileName - File containing rotor performance tables (Cp,Ct,Cq) (absolute path or relative to this file) -36 26 ! PerfTableSize - Size of rotor performance tables, first number refers to number of blade pitch angles, second number referse to number of tip-speed ratios -60 ! WE_FOPoles_N - Number of first-order system poles used in EKF -0.5000 0.5517 0.6034 0.6552 0.7069 0.7586 0.8103 0.8621 0.9138 0.9655 1.0172 1.0690 1.1207 1.1724 1.2241 1.2759 1.3276 1.3793 1.4310 1.4828 1.5345 1.5862 1.6379 1.6897 1.7414 1.7931 1.8448 1.8966 1.9483 2.0000 2.0333 2.0667 2.1000 2.1333 2.1667 2.2000 2.2333 2.2667 2.3000 2.3333 2.3667 2.4000 2.4333 2.4667 2.5000 2.5333 2.5667 2.6000 2.6333 2.6667 2.7000 2.7333 2.7667 2.8000 2.8333 2.8667 2.9000 2.9333 2.9667 3.0000 ! WE_FOPoles_v - Wind speeds corresponding to first-order system poles [m/s] --0.14364445 -0.15850422 -0.17336400 -0.18822377 -0.20308354 -0.21794331 -0.23280308 -0.24766285 -0.26252262 -0.27738239 -0.29224216 -0.30710193 -0.32196171 -0.33682148 -0.35168125 -0.36654102 -0.38140079 -0.39626056 -0.41112033 -0.42598010 -0.44083987 -0.45569965 -0.47055942 -0.48666545 -0.50602877 -0.52082936 -0.60274133 -0.60720589 -0.60927938 -0.55668516 0.17844923 0.15174296 0.10860051 0.05753679 0.00176535 -0.05812003 -0.11803585 -0.18146508 -0.24666701 -0.31440662 -0.38335107 -0.45418067 -0.52480063 -0.59662243 -0.67000720 -0.74481113 -0.82056059 -0.89753628 -0.97589183 -1.05446405 -1.13345094 -1.21374047 -1.29379323 -1.37507241 -1.45808464 -1.54093580 -1.62426617 -1.70957888 -1.79610923 -1.88140848 ! WE_FOPoles - First order system poles [1/s] - -!------- YAW CONTROL ------------------------------------------------------ -0.00000 ! Y_uSwitch - Wind speed to switch between Y_ErrThresh. If zero, only the second value of Y_ErrThresh is used [m/s] -4.000000 8.000000 ! Y_ErrThresh - Yaw error threshold/deadbands. Turbine begins to yaw when it passes this. If Y_uSwitch is zero, only the second value is used. [deg]. -0.00870 ! Y_Rate - Yaw rate [rad/s] -0.00000 ! Y_MErrSet - Integrator saturation (maximum signal amplitude contribution to pitch from yaw-by-IPC), [rad] -0.00000 ! Y_IPC_IntSat - Integrator saturation (maximum signal amplitude contribution to pitch from yaw-by-IPC), [rad] -0.00000 ! Y_IPC_KP - Yaw-by-IPC proportional controller gain Kp -0.00000 ! Y_IPC_KI - Yaw-by-IPC integral controller gain Ki - -!------- TOWER FORE-AFT DAMPING ------------------------------------------- --1.00000 ! FA_KI - Integral gain for the fore-aft tower damper controller [rad s/m] -0.0 ! FA_HPFCornerFreq - 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] - -!------- MINIMUM PITCH SATURATION ------------------------------------------- -60 ! PS_BldPitchMin_N - Number of values in minimum blade pitch lookup table (should equal number of values in PS_WindSpeeds and PS_BldPitchMin) -0.500 0.552 0.603 0.655 0.707 0.759 0.810 0.862 0.914 0.966 1.017 1.069 1.121 1.172 1.224 1.276 1.328 1.379 1.431 1.483 1.534 1.586 1.638 1.690 1.741 1.793 1.845 1.897 1.948 2.000 2.033 2.067 2.100 2.133 2.167 2.200 2.233 2.267 2.300 2.333 2.367 2.400 2.433 2.467 2.500 2.533 2.567 2.600 2.633 2.667 2.700 2.733 2.767 2.800 2.833 2.867 2.900 2.933 2.967 3.000 ! PS_WindSpeeds - Wind speeds corresponding to minimum blade pitch angles [m/s] -0.001 0.001 0.001 0.001 0.001 0.001 0.001 0.001 0.001 0.001 0.001 0.001 0.001 0.001 0.001 0.001 0.001 0.001 0.001 0.001 0.001 0.001 0.001 0.001 0.001 0.001 0.001 0.001 0.001 0.001 0.001 0.001 0.001 0.001 0.001 0.001 0.001 0.001 0.001 0.001 0.001 0.001 0.001 0.001 0.001 0.001 0.001 0.001 0.001 0.001 0.001 0.001 0.001 0.001 0.001 0.001 0.001 0.001 0.001 0.001 ! PS_BldPitchMin - Minimum blade pitch angles [rad] - -!------- SHUTDOWN ----------------------------------------------------------- -0.436300000000 ! SD_MaxPit - Maximum blade pitch angle to initiate shutdown, [rad] -0.418880000000 ! SD_CornerFreq - Cutoff Frequency for first order low-pass filter for blade pitch angle, [rad/s] - -!------- Floating ----------------------------------------------------------- -1 ! Fl_n - Number of Fl_Kp gains in gain scheduling, optional with default of 1 --0.3999 ! Fl_Kp - Nacelle velocity proportional feedback gain [s] -2.1000 ! Fl_U - Wind speeds for scheduling Fl_Kp, optional if Fl_Kp is single value [m/s] - -!------- FLAP ACTUATION ----------------------------------------------------- -0.000000000000 ! Flp_Angle - Initial or steady state flap angle [rad] -0.00000000e+00 ! Flp_Kp - Blade root bending moment proportional gain for flap control [s] -0.00000000e+00 ! Flp_Ki - Flap displacement integral gain for flap control [-] -0.174500000000 ! Flp_MaxPit - Maximum (and minimum) flap pitch angle [rad] - -!------- Open Loop Control ----------------------------------------------------- -"unused" ! OL_Filename - Input file with open loop timeseries (absolute path or relative to this file) -0 ! Ind_Breakpoint - The column in OL_Filename that contains the breakpoint (time if OL_Mode = 1) - 0 0 0 ! Ind_BldPitch - The columns in OL_Filename that contains the blade pitch (1,2,3) inputs in rad [array] -0 ! Ind_GenTq - The column in OL_Filename that contains the generator torque in Nm -0 ! Ind_YawRate - The column in OL_Filename that contains the yaw rate in rad/s -0 ! Ind_Azimuth - The column in OL_Filename that contains the desired azimuth position in rad (used if OL_Mode = 2) -0.0000 0.0000 0.0000 0.0000 ! RP_Gains - PID gains and Tf of derivative for rotor position control (used if OL_Mode = 2) -0 ! Ind_CableControl - The column(s) in OL_Filename that contains the cable control inputs in m [Used with CC_Mode = 2, must be the same size as CC_Group_N] -0 ! Ind_StructControl - The column(s) in OL_Filename that contains the structural control inputs [Used with StC_Mode = 2, must be the same size as StC_Group_N] - -!------- Pitch Actuator Model ----------------------------------------------------- -3.140000000000 ! PA_CornerFreq - Pitch actuator bandwidth/cut-off frequency [rad/s] -0.707000000000 ! PA_Damping - Pitch actuator damping ratio [-, unused if PA_Mode = 1] - -!------- Pitch Actuator Faults ----------------------------------------------------- -0.00000000 0.00000000 0.00000000 ! PF_Offsets - Constant blade pitch offsets for blades 1-3 [rad] - -!------- Active Wake Control ----------------------------------------------------- -1 ! AWC_NumModes - Number of user-defined AWC forcing modes -1 ! AWC_n - Azimuthal mode number(s) (i.e., the number and direction of the lobes of the wake structure) -1 ! AWC_harmonic - Harmonic(s) to apply in the AWC Inverse Coleman Transformation (only used when AWC_Mode = 2) -0.0500 ! AWC_freq - Frequency(s) of forcing mode(s) [Hz] -1.0000 ! AWC_amp - Pitch amplitude(s) of individual forcing mode(s) [deg] -0.0000 ! AWC_clockangle - Initial angle(s) of forcing mode(s) [deg] - -!------- External Controller Interface ----------------------------------------------------- -"unused" ! DLL_FileName - Name/location of the dynamic library in the Bladed-DLL format -"unused" ! DLL_InFile - Name of input file sent to the DLL (-) -"DISCON" ! DLL_ProcName - Name of procedure in DLL to be called (-) - -!------- ZeroMQ Interface --------------------------------------------------------- -"tcp://localhost:5555" ! ZMQ_CommAddress - Communication address for ZMQ server, (e.g. "tcp://localhost:5555") -2.000000 ! ZMQ_UpdatePeriod - Call ZeroMQ every [x] seconds, [s] - -!------- Cable Control --------------------------------------------------------- -1 ! CC_Group_N - Number of cable control groups -0 ! CC_GroupIndex - First index for cable control group, should correspond to deltaL -20.000000 ! CC_ActTau - Time constant for line actuator [s] - -!------- Structural Controllers --------------------------------------------------------- -1 ! StC_Group_N - Number of cable control groups -0 ! StC_GroupIndex - First index for structural control group, options specified in ServoDyn summary output diff --git a/Test_Cases/MHK_RM1/MHK_RM1_ElastoDyn_Blade.dat b/Test_Cases/MHK_RM1/MHK_RM1_ElastoDyn_Blade.dat deleted file mode 100644 index df6ab8c8..00000000 --- a/Test_Cases/MHK_RM1/MHK_RM1_ElastoDyn_Blade.dat +++ /dev/null @@ -1,107 +0,0 @@ -------- ELASTODYN V1.00.* INDIVIDUAL BLADE INPUT FILE -------------------------- -Floating MHK turbine structural blade input properties, based on the RM1 tidal current rotor ----------------------- BLADE PARAMETERS ---------------------------------------- - 75 NBlInpSt - Number of blade input stations (-) - 1 BldFlDmp(1) - Blade flap mode #1 structural damping in percent of critical (%) - 1 BldFlDmp(2) - Blade flap mode #2 structural damping in percent of critical (%) - 1 BldEdDmp(1) - Blade edge mode #1 structural damping in percent of critical (%) ----------------------- BLADE ADJUSTMENT FACTORS -------------------------------- - 1 FlStTunr(1) - Blade flapwise modal stiffness tuner, 1st mode (-) - 1 FlStTunr(2) - Blade flapwise modal stiffness tuner, 2nd mode (-) - 2.5 AdjBlMs - Factor to adjust blade mass density (-) - 1.0E-05 AdjFlSt - Factor to adjust blade flap stiffness (-) - 1.0E-05 AdjEdSt - Factor to adjust blade edge stiffness (-) ----------------------- DISTRIBUTED BLADE PROPERTIES ---------------------------- -BlFract PitchAxis StrcTwst BMassDen FlpStff EdgStff -(-) (-) (deg) (kg/m) (Nm^2) (Nm^2) -0.0000 0.5000 12.860 818.68 2.43E+14 2.52E+14 -0.0083 0.4953 12.860 833.60 2.47E+14 2.69E+14 -0.0167 0.4907 12.860 846.44 2.47E+14 2.84E+14 -0.0250 0.4860 12.860 858.68 2.46E+14 3.00E+14 -0.0333 0.4813 12.860 870.32 2.44E+14 3.15E+14 -0.0417 0.4701 12.860 900.64 2.50E+14 3.59E+14 -0.0500 0.4590 12.860 932.64 2.49E+14 4.03E+14 -0.0583 0.4478 12.860 681.32 1.70E+14 1.12E+14 -0.0667 0.4366 12.860 628.00 1.48E+14 1.11E+14 -0.0750 0.4233 12.860 575.28 1.30E+14 1.10E+14 -0.0833 0.4100 12.860 528.96 1.12E+14 1.07E+14 -0.0917 0.3967 12.860 458.92 8.82E+13 9.56E+13 -0.1000 0.3834 12.860 401.60 6.72E+13 8.55E+13 -0.1083 0.3722 12.860 411.16 6.45E+13 9.15E+13 -0.1167 0.3611 12.860 410.28 6.00E+13 9.53E+13 -0.1250 0.3499 12.860 415.36 5.62E+13 1.01E+14 -0.1333 0.3387 12.860 421.00 5.17E+13 1.06E+14 -0.1417 0.3340 12.860 421.28 4.94E+13 1.08E+14 -0.1500 0.3294 12.860 421.40 4.70E+13 1.10E+14 -0.1583 0.3247 12.860 424.96 4.45E+13 1.12E+14 -0.1667 0.3200 12.860 435.48 4.30E+13 1.16E+14 -0.1750 0.3200 12.530 428.40 4.09E+13 1.13E+14 -0.1833 0.3200 12.200 423.88 3.89E+13 1.10E+14 -0.1917 0.3200 11.870 435.68 3.84E+13 1.15E+14 -0.2000 0.3200 11.540 430.60 3.62E+13 1.12E+14 -0.2083 0.3200 11.265 434.52 3.57E+13 1.11E+14 -0.2167 0.3200 10.990 430.28 3.41E+13 1.09E+14 -0.2250 0.3200 10.715 426.04 3.26E+13 1.06E+14 -0.2333 0.3200 10.440 421.84 3.11E+13 1.03E+14 -0.2500 0.3200 9.970 415.00 2.91E+13 9.84E+13 -0.2667 0.3200 9.500 411.20 2.72E+13 9.54E+13 -0.2833 0.3200 9.105 395.88 2.54E+13 8.96E+13 -0.3000 0.3200 8.710 390.40 2.43E+13 8.59E+13 -0.3167 0.3200 8.365 377.84 2.26E+13 8.06E+13 -0.3333 0.3200 8.020 362.44 2.15E+13 7.34E+13 -0.3500 0.3200 7.725 347.48 2.00E+13 6.87E+13 -0.3667 0.3200 7.430 335.60 1.85E+13 6.42E+13 -0.3833 0.3200 7.170 330.64 1.77E+13 6.14E+13 -0.4000 0.3200 6.910 318.96 1.63E+13 5.72E+13 -0.4167 0.3200 6.680 302.84 1.50E+13 5.33E+13 -0.4333 0.3200 6.450 298.24 1.43E+13 5.09E+13 -0.4500 0.3200 6.245 287.12 1.32E+13 4.73E+13 -0.4667 0.3200 6.040 267.24 1.19E+13 4.12E+13 -0.4833 0.3200 5.860 256.68 1.09E+13 3.81E+13 -0.5000 0.3200 5.680 249.96 1.04E+13 3.62E+13 -0.5167 0.3200 5.515 239.68 9.42E+12 3.33E+13 -0.5333 0.3200 5.350 227.76 8.54E+12 3.06E+13 -0.5500 0.3200 5.200 215.64 7.73E+12 2.81E+13 -0.5667 0.3200 5.050 206.16 6.97E+12 2.58E+13 -0.5833 0.3200 4.910 188.80 6.17E+12 2.17E+13 -0.6000 0.3200 4.770 179.80 5.51E+12 1.97E+13 -0.6167 0.3200 4.640 176.28 5.19E+12 1.85E+13 -0.6333 0.3200 4.510 165.32 4.61E+12 1.68E+13 -0.6500 0.3200 4.385 156.80 4.07E+12 1.51E+13 -0.6667 0.3200 4.260 144.88 3.57E+12 1.36E+13 -0.6833 0.3200 4.145 136.80 3.11E+12 1.21E+13 -0.7000 0.3200 4.030 128.92 2.69E+12 1.08E+13 -0.7167 0.3200 3.915 119.36 2.31E+12 9.55E+12 -0.7333 0.3200 3.800 111.96 1.96E+12 8.42E+12 -0.7500 0.3200 3.685 103.00 1.65E+12 7.39E+12 -0.7667 0.3200 3.570 94.72 1.37E+12 6.45E+12 -0.7833 0.3200 3.460 87.96 1.12E+12 5.57E+12 -0.8000 0.3200 3.350 79.76 8.91E+11 4.77E+12 -0.8167 0.3200 3.240 73.52 6.93E+11 4.05E+12 -0.8333 0.3200 3.130 71.44 6.36E+11 3.72E+12 -0.8500 0.3200 3.015 64.00 4.76E+11 3.11E+12 -0.8667 0.3200 2.900 57.24 3.38E+11 2.56E+12 -0.8833 0.3200 2.785 50.36 2.19E+11 2.04E+12 -0.9000 0.3200 2.670 48.68 1.98E+11 1.84E+12 -0.9167 0.3200 2.550 47.00 1.78E+11 1.66E+12 -0.9333 0.3200 2.430 45.32 1.59E+11 1.49E+12 -0.9500 0.3200 2.305 46.76 1.98E+11 1.51E+12 -0.9667 0.3200 2.180 44.04 1.76E+11 1.34E+12 -0.9833 0.3200 2.060 42.28 1.56E+11 1.19E+12 -1.0000 0.3200 2.060 42.28 1.56E+11 1.19E+12 ----------------------- BLADE MODE SHAPES --------------------------------------- - 1.88070 BldFl1Sh(2) - Flap mode 1, coeff of x^2 --1.44580 BldFl1Sh(3) - , coeff of x^3 - 0.71967 BldFl1Sh(4) - , coeff of x^4 --0.03633 BldFl1Sh(5) - , coeff of x^5 --0.11822 BldFl1Sh(6) - , coeff of x^6 --5.52180 BldFl2Sh(2) - Flap mode 2, coeff of x^2 - 7.45710 BldFl2Sh(3) - , coeff of x^3 - 2.84170 BldFl2Sh(4) - , coeff of x^4 --3.97820 BldFl2Sh(5) - , coeff of x^5 - 0.20116 BldFl2Sh(6) - , coeff of x^6 - 2.48090 BldEdgSh(2) - Edge mode 1, coeff of x^2 --4.17160 BldEdgSh(3) - , coeff of x^3 - 5.03260 BldEdgSh(4) - , coeff of x^4 --2.86170 BldEdgSh(5) - , coeff of x^5 - 0.51983 BldEdgSh(6) - , coeff of x^6 \ No newline at end of file diff --git a/Test_Cases/MHK_RM1/MHK_RM1_ElastoDyn_Tower.dat b/Test_Cases/MHK_RM1/MHK_RM1_ElastoDyn_Tower.dat deleted file mode 100644 index 3c04a12f..00000000 --- a/Test_Cases/MHK_RM1/MHK_RM1_ElastoDyn_Tower.dat +++ /dev/null @@ -1,52 +0,0 @@ -------- ELASTODYN V1.00.* TOWER INPUT FILE ------------------------------------- -Floating MHK turbine structural tower input properties, based on the RM1 tidal current rotor ----------------------- TOWER PARAMETERS ---------------------------------------- - 11 NTwInpSt - Number of input stations to specify tower geometry - 1 TwrFADmp(1) - Tower 1st fore-aft mode structural damping ratio (%) - 1 TwrFADmp(2) - Tower 2nd fore-aft mode structural damping ratio (%) - 1 TwrSSDmp(1) - Tower 1st side-to-side mode structural damping ratio (%) - 1 TwrSSDmp(2) - Tower 2nd side-to-side mode structural damping ratio (%) ----------------------- TOWER ADJUSTMUNT FACTORS -------------------------------- - 1 FAStTunr(1) - Tower fore-aft modal stiffness tuner, 1st mode (-) - 1 FAStTunr(2) - Tower fore-aft modal stiffness tuner, 2nd mode (-) - 1 SSStTunr(1) - Tower side-to-side stiffness tuner, 1st mode (-) - 1 SSStTunr(2) - Tower side-to-side stiffness tuner, 2nd mode (-) - 1 AdjTwMa - Factor to adjust tower mass density (-) - 1.0E-03 AdjFASt - Factor to adjust tower fore-aft stiffness (-) - 1.0E-03 AdjSSSt - Factor to adjust tower side-to-side stiffness (-) ----------------------- DISTRIBUTED TOWER PROPERTIES ---------------------------- -HtFract TMassDen TwFAStif TwSSStif -(-) (kg/m) (Nm^2) (Nm^2) -0.0000000E+00 5076.39 1.27E+11 1.27E+11 -1.0000000E-01 5076.39 1.27E+11 1.27E+11 -2.0000000E-01 5076.39 1.27E+11 1.27E+11 -3.0000000E-01 5076.39 1.27E+11 1.27E+11 -4.0000000E-01 5076.39 1.27E+11 1.27E+11 -5.0000000E-01 5076.39 1.27E+11 1.27E+11 -6.0000000E-01 5076.39 1.27E+11 1.27E+11 -7.0000000E-01 5076.39 1.27E+11 1.27E+11 -8.0000000E-01 5076.39 1.27E+11 1.27E+11 -9.0000000E-01 5076.39 1.27E+11 1.27E+11 -1.0000000E+00 5076.39 1.27E+11 1.27E+11 ----------------------- TOWER FORE-AFT MODE SHAPES ------------------------------ - -5.6786 TwFAM1Sh(2) - Mode 1, coefficient of x^2 term - 41.5614 TwFAM1Sh(3) - , coefficient of x^3 term - -93.3287 TwFAM1Sh(4) - , coefficient of x^4 term - 89.2568 TwFAM1Sh(5) - , coefficient of x^5 term - -30.8109 TwFAM1Sh(6) - , coefficient of x^6 term - 0.6979 TwFAM2Sh(2) - Mode 2, coefficient of x^2 term - 1.2146 TwFAM2Sh(3) - , coefficient of x^3 term - -1.6999 TwFAM2Sh(4) - , coefficient of x^4 term - 0.8473 TwFAM2Sh(5) - , coefficient of x^5 term - -0.0599 TwFAM2Sh(6) - , coefficient of x^6 term ----------------------- TOWER SIDE-TO-SIDE MODE SHAPES -------------------------- - 0.5640 TwSSM1Sh(2) - Mode 1, coefficient of x^2 term - 4.7082 TwSSM1Sh(3) - , coefficient of x^3 term - -14.9130 TwSSM1Sh(4) - , coefficient of x^4 term - 18.2340 TwSSM1Sh(5) - , coefficient of x^5 term - -7.5932 TwSSM1Sh(6) - , coefficient of x^6 term - 0.9525 TwSSM2Sh(2) - Mode 2, coefficient of x^2 term - 0.4369 TwSSM2Sh(3) - , coefficient of x^3 term - -1.1374 TwSSM2Sh(4) - , coefficient of x^4 term - 1.1954 TwSSM2Sh(5) - , coefficient of x^5 term - -0.4474 TwSSM2Sh(6) - , coefficient of x^6 term \ No newline at end of file diff --git a/Test_Cases/MHK_RM1/MHK_RM1_Floating.1 b/Test_Cases/MHK_RM1/MHK_RM1_Floating.1 deleted file mode 100644 index c32060dc..00000000 --- a/Test_Cases/MHK_RM1/MHK_RM1_Floating.1 +++ /dev/null @@ -1,4220 +0,0 @@ - -1.000000E+00 1 1 1.999545E+03 - -1.000000E+00 1 5 -1.038155E+04 - -1.000000E+00 2 2 2.266626E+03 - -1.000000E+00 2 4 1.450345E+04 - -1.000000E+00 3 3 2.167146E+03 - -1.000000E+00 4 2 1.451960E+04 - -1.000000E+00 4 4 2.703220E+05 - -1.000000E+00 5 1 -1.039882E+04 - -1.000000E+00 5 5 8.266187E+05 - -1.000000E+00 6 6 9.046082E+05 - 0.000000E+00 1 1 1.411834E+03 - 0.000000E+00 1 5 -9.031812E+03 - 0.000000E+00 2 2 1.657916E+03 - 0.000000E+00 2 4 1.228014E+04 - 0.000000E+00 3 3 2.166489E+03 - 0.000000E+00 4 2 1.229162E+04 - 0.000000E+00 4 4 2.611510E+05 - 0.000000E+00 5 1 -9.043577E+03 - 0.000000E+00 5 5 8.192453E+05 - 0.000000E+00 6 6 6.521804E+05 - 1.000000E-01 1 1 1.647323E+03 6.332432E-04 - 1.000000E-01 1 5 -9.712987E+03 1.055422E-06 - 1.000000E-01 2 2 1.921107E+03 -6.797895E-06 - 1.000000E-01 2 4 1.298169E+04 -4.832497E-06 - 1.000000E-01 3 3 2.120432E+03 -1.464990E-06 - 1.000000E-01 4 2 1.312899E+04 2.916794E-05 - 1.000000E-01 4 4 2.638432E+05 2.756118E-05 - 1.000000E-01 5 1 -9.566795E+03 -3.792644E-03 - 1.000000E-01 5 5 8.247277E+05 -3.473593E-07 - 1.000000E-01 6 6 8.442138E+05 7.588721E+03 - 2.000000E-01 1 1 1.489483E+03 -5.117749E-03 - 2.000000E-01 1 5 -9.217624E+03 7.927747E-03 - 2.000000E-01 2 2 1.736418E+03 8.147049E-03 - 2.000000E-01 2 4 1.245268E+04 1.932775E-02 - 2.000000E-01 3 3 2.164448E+03 9.414506E-04 - 2.000000E-01 4 2 1.251272E+04 -4.435483E-02 - 2.000000E-01 4 4 2.615695E+05 -1.109551E-01 - 2.000000E-01 5 1 -9.202860E+03 1.644901E-04 - 2.000000E-01 5 5 8.194167E+05 -1.930356E-04 - 2.000000E-01 6 6 6.884296E+05 -1.733961E-01 - 3.000000E-01 1 1 1.444033E+03 6.269322E-03 - 3.000000E-01 1 5 -9.111029E+03 7.101058E-03 - 3.000000E-01 2 2 1.690542E+03 1.995744E-02 - 3.000000E-01 2 4 1.235828E+04 2.445857E-02 - 3.000000E-01 3 3 2.169583E+03 1.453299E-03 - 3.000000E-01 4 2 1.236276E+04 -1.233631E-01 - 3.000000E-01 4 4 2.614335E+05 -1.543396E-01 - 3.000000E-01 5 1 -9.125158E+03 3.700770E-04 - 3.000000E-01 5 5 8.191486E+05 -7.132935E-04 - 3.000000E-01 6 6 6.673795E+05 -4.440385E-02 - 4.000000E-01 1 1 1.425401E+03 -4.108052E-02 - 4.000000E-01 1 5 -9.064186E+03 5.634245E-02 - 4.000000E-01 2 2 1.671785E+03 -6.710615E-03 - 4.000000E-01 2 4 1.231083E+04 -6.929412E-02 - 4.000000E-01 3 3 2.166178E+03 5.495228E-03 - 4.000000E-01 4 2 1.232969E+04 -6.580804E-02 - 4.000000E-01 4 4 2.612587E+05 6.190121E-02 - 4.000000E-01 5 1 -9.060692E+03 6.707626E-03 - 4.000000E-01 5 5 8.194138E+05 -6.489989E-03 - 4.000000E-01 6 6 6.587328E+05 -1.063728E+01 - 5.000000E-01 1 1 1.414171E+03 3.453698E-01 - 5.000000E-01 1 5 -9.040007E+03 -3.437867E-01 - 5.000000E-01 2 2 1.660540E+03 3.550050E-01 - 5.000000E-01 2 4 1.228412E+04 2.817520E-01 - 5.000000E-01 3 3 2.162501E+03 2.197521E-02 - 5.000000E-01 4 2 1.229900E+04 5.180726E-03 - 5.000000E-01 4 4 2.611725E+05 8.319525E-01 - 5.000000E-01 5 1 -9.049924E+03 -4.966549E-02 - 5.000000E-01 5 5 8.193651E+05 8.510031E-02 - 5.000000E-01 6 6 6.535414E+05 1.552287E+02 - 6.000000E-01 1 1 1.405576E+03 7.597563E-02 - 6.000000E-01 1 5 -9.019186E+03 3.253367E-02 - 6.000000E-01 2 2 1.652408E+03 -6.845129E-02 - 6.000000E-01 2 4 1.226468E+04 -3.525721E-01 - 6.000000E-01 3 3 2.164061E+03 2.654704E-02 - 6.000000E-01 4 2 1.227475E+04 -2.927428E-01 - 6.000000E-01 4 4 2.610847E+05 9.614539E-01 - 6.000000E-01 5 1 -9.029830E+03 -4.355243E-05 - 6.000000E-01 5 5 8.191937E+05 -2.194798E-02 - 6.000000E-01 6 6 6.497349E+05 -5.169302E+01 - 7.000000E-01 1 1 1.395932E+03 2.687031E+00 - 7.000000E-01 1 5 -8.998733E+03 -2.345758E+00 - 7.000000E-01 2 2 1.643188E+03 2.431145E+00 - 7.000000E-01 2 4 1.224100E+04 2.120982E+00 - 7.000000E-01 3 3 2.166201E+03 5.592055E-02 - 7.000000E-01 4 2 1.225460E+04 6.609563E-01 - 7.000000E-01 4 4 2.610094E+05 3.439912E+00 - 7.000000E-01 5 1 -9.010243E+03 -4.799671E-01 - 7.000000E-01 5 5 8.189821E+05 4.613745E-01 - 7.000000E-01 6 6 6.454252E+05 1.170501E+03 - 8.000001E-01 1 1 1.384360E+03 1.642901E-01 - 8.000001E-01 1 5 -8.978327E+03 2.553241E+00 - 8.000001E-01 2 2 1.631998E+03 -1.413633E-02 - 8.000001E-01 2 4 1.221956E+04 -2.684513E+00 - 8.000001E-01 3 3 2.165785E+03 4.677046E-02 - 8.000001E-01 4 2 1.223349E+04 -4.235556E-01 - 8.000001E-01 4 4 2.609263E+05 2.081753E+00 - 8.000001E-01 5 1 -8.987876E+03 -9.826274E-03 - 8.000001E-01 5 5 8.190675E+05 -5.485277E-01 - 8.000001E-01 6 6 6.402148E+05 -3.896221E+01 - 9.000001E-01 1 1 1.378177E+03 7.398844E+00 - 9.000001E-01 1 5 -8.957874E+03 -6.925296E+00 - 9.000001E-01 2 2 1.627581E+03 5.964404E+00 - 9.000001E-01 2 4 1.220009E+04 4.984253E+00 - 9.000001E-01 3 3 2.165009E+03 1.034568E-01 - 9.000001E-01 4 2 1.220971E+04 5.667600E-01 - 9.000001E-01 4 4 2.608499E+05 7.644433E+00 - 9.000001E-01 5 1 -8.968889E+03 -1.710251E+00 - 9.000001E-01 5 5 8.189044E+05 1.618641E+00 - 9.000001E-01 6 6 6.380893E+05 2.840782E+03 - 1.000000E+00 1 1 1.362969E+03 1.615517E+00 - 1.000000E+00 1 5 -8.932901E+03 5.044086E+00 - 1.000000E+00 2 2 1.611138E+03 9.922764E-01 - 1.000000E+00 2 4 1.216958E+04 -5.591891E+00 - 1.000000E+00 3 3 2.165247E+03 2.016310E-01 - 1.000000E+00 4 2 1.218151E+04 -1.473536E+00 - 1.000000E+00 4 4 2.607715E+05 7.036344E+00 - 1.000000E+00 5 1 -8.944518E+03 -3.480948E-01 - 1.000000E+00 5 5 8.189051E+05 -1.422689E+00 - 1.000000E+00 6 6 6.303638E+05 4.558491E+02 - 1.100000E+00 1 1 1.363987E+03 -2.531477E+00 - 1.100000E+00 1 5 -8.926103E+03 6.271327E+00 - 1.100000E+00 2 2 1.611693E+03 -1.364930E+00 - 1.100000E+00 2 4 1.216229E+04 -4.610226E+00 - 1.100000E+00 3 3 2.165244E+03 2.358969E-01 - 1.100000E+00 4 2 1.216006E+04 -6.359519E+00 - 1.100000E+00 4 4 2.606747E+05 5.233872E-02 - 1.100000E+00 5 1 -8.920106E+03 1.063921E+00 - 1.100000E+00 5 5 8.188067E+05 -2.253227E+00 - 1.100000E+00 6 6 6.310228E+05 -1.073627E+03 - 1.200000E+00 1 1 1.341250E+03 1.548859E+01 - 1.200000E+00 1 5 -8.873159E+03 -6.809859E+00 - 1.200000E+00 2 2 1.586134E+03 1.391513E+01 - 1.200000E+00 2 4 1.211250E+04 4.959229E+00 - 1.200000E+00 3 3 2.164715E+03 3.401773E-01 - 1.200000E+00 4 2 1.212701E+04 3.459318E+00 - 1.200000E+00 4 4 2.605578E+05 1.085976E+01 - 1.200000E+00 5 1 -8.887145E+03 -5.441040E+00 - 1.200000E+00 5 5 8.187148E+05 2.547801E+00 - 1.200000E+00 6 6 6.198414E+05 6.079765E+03 - 1.300000E+00 1 1 1.317477E+03 1.786603E+01 - 1.300000E+00 1 5 -8.835250E+03 -4.428756E+00 - 1.300000E+00 2 2 1.567642E+03 1.936374E+01 - 1.300000E+00 2 4 1.207500E+04 -3.296340E+00 - 1.300000E+00 3 3 2.163520E+03 6.429050E-01 - 1.300000E+00 4 2 1.208866E+04 1.633794E+00 - 1.300000E+00 4 4 2.604250E+05 1.361215E+01 - 1.300000E+00 5 1 -8.846683E+03 -7.834044E+00 - 1.300000E+00 5 5 8.186024E+05 2.022286E+00 - 1.300000E+00 6 6 6.112214E+05 7.741492E+03 - 1.400000E+00 1 1 1.302752E+03 4.014243E+01 - 1.400000E+00 1 5 -8.796211E+03 -2.097240E+01 - 1.400000E+00 2 2 1.559435E+03 3.202108E+01 - 1.400000E+00 2 4 1.202891E+04 4.779904E+00 - 1.400000E+00 3 3 2.164057E+03 9.372752E-01 - 1.400000E+00 4 2 1.204261E+04 3.293264E+00 - 1.400000E+00 4 4 2.602875E+05 2.683385E+01 - 1.400000E+00 5 1 -8.809545E+03 -1.970354E+01 - 1.400000E+00 5 5 8.184987E+05 1.044662E+01 - 1.400000E+00 6 6 6.065062E+05 1.238738E+04 - 1.500000E+00 1 1 1.305815E+03 6.491683E+01 - 1.500000E+00 1 5 -8.772146E+03 -5.825910E+01 - 1.500000E+00 2 2 1.552037E+03 5.264654E+01 - 1.500000E+00 2 4 1.198437E+04 1.699949E+01 - 1.500000E+00 3 3 2.163969E+03 8.035405E-01 - 1.500000E+00 4 2 1.199230E+04 -6.595213E+00 - 1.500000E+00 4 4 2.601701E+05 4.169799E+01 - 1.500000E+00 5 1 -8.775944E+03 -3.643074E+01 - 1.500000E+00 5 5 8.183611E+05 3.319314E+01 - 1.500000E+00 6 6 6.043392E+05 1.849497E+04 - 1.600000E+00 1 1 1.252716E+03 3.327114E+01 - 1.600000E+00 1 5 -8.693517E+03 -1.871183E+01 - 1.600000E+00 2 2 1.525129E+03 4.072418E+01 - 1.600000E+00 2 4 1.192106E+04 1.475205E+01 - 1.600000E+00 3 3 2.162847E+03 2.077548E+00 - 1.600000E+00 4 2 1.193497E+04 1.744354E+01 - 1.600000E+00 4 4 2.599660E+05 2.792954E+01 - 1.600000E+00 5 1 -8.706070E+03 -2.088443E+01 - 1.600000E+00 5 5 8.181992E+05 1.237664E+01 - 1.600000E+00 6 6 5.862862E+05 1.873653E+04 - 1.700000E+00 1 1 1.263750E+03 4.159086E+01 - 1.700000E+00 1 5 -8.659005E+03 -3.006438E+01 - 1.700000E+00 2 2 1.499287E+03 5.819635E+01 - 1.700000E+00 2 4 1.187052E+04 1.416955E+01 - 1.700000E+00 3 3 2.164139E+03 8.063655E-01 - 1.700000E+00 4 2 1.188380E+04 1.460832E+01 - 1.700000E+00 4 4 2.597760E+05 4.624529E+01 - 1.700000E+00 5 1 -8.672770E+03 -2.952167E+01 - 1.700000E+00 5 5 8.180617E+05 2.236001E+01 - 1.700000E+00 6 6 5.827302E+05 2.159274E+04 - 1.800000E+00 1 1 1.189232E+03 1.561305E+02 - 1.800000E+00 1 5 -8.555380E+03 -1.342970E+02 - 1.800000E+00 2 2 1.504885E+03 9.247465E+01 - 1.800000E+00 2 4 1.178999E+04 3.150293E+01 - 1.800000E+00 3 3 2.163042E+03 1.313273E+00 - 1.800000E+00 4 2 1.180293E+04 3.034780E+01 - 1.800000E+00 4 4 2.595717E+05 6.551591E+01 - 1.800000E+00 5 1 -8.569188E+03 -1.318952E+02 - 1.800000E+00 5 5 8.178374E+05 1.150578E+02 - 1.800000E+00 6 6 5.727449E+05 3.621642E+04 - 1.900000E+00 1 1 1.226731E+03 5.598594E+01 - 1.900000E+00 1 5 -8.539219E+03 -5.221244E+01 - 1.900000E+00 2 2 1.484238E+03 6.774551E+01 - 1.900000E+00 2 4 1.170991E+04 5.493768E+01 - 1.900000E+00 3 3 2.162584E+03 1.752707E+00 - 1.900000E+00 4 2 1.172212E+04 5.261831E+01 - 1.900000E+00 4 4 2.593096E+05 8.803828E+01 - 1.900000E+00 5 1 -8.551688E+03 -5.053044E+01 - 1.900000E+00 5 5 8.176388E+05 4.843289E+01 - 1.900000E+00 6 6 5.656957E+05 3.362212E+04 - 2.000000E+00 1 1 1.087300E+03 1.198298E+02 - 2.000000E+00 1 5 -8.342403E+03 -1.376728E+02 - 2.000000E+00 2 2 1.441709E+03 1.099168E+02 - 2.000000E+00 2 4 1.162081E+04 1.143344E+02 - 2.000000E+00 3 3 2.162366E+03 1.870794E+00 - 2.000000E+00 4 2 1.163232E+04 1.028961E+02 - 2.000000E+00 4 4 2.590200E+05 1.522620E+02 - 2.000000E+00 5 1 -8.362664E+03 -1.267002E+02 - 2.000000E+00 5 5 8.172602E+05 1.471770E+02 - 2.000000E+00 6 6 5.488098E+05 5.315241E+04 - 2.100000E+00 1 1 1.255987E+03 1.175194E+02 - 2.100000E+00 1 5 -8.462438E+03 -1.145313E+02 - 2.100000E+00 2 2 1.445970E+03 1.372894E+02 - 2.100000E+00 2 4 1.156079E+04 1.278852E+02 - 2.100000E+00 3 3 2.162340E+03 2.534883E+00 - 2.100000E+00 4 2 1.157829E+04 1.415270E+02 - 2.100000E+00 4 4 2.587445E+05 1.772284E+02 - 2.100000E+00 5 1 -8.483445E+03 -1.251749E+02 - 2.100000E+00 5 5 8.172242E+05 1.242277E+02 - 2.100000E+00 6 6 5.477408E+05 5.859570E+04 - 2.200000E+00 1 1 1.161857E+03 8.277615E+01 - 2.200000E+00 1 5 -8.305616E+03 -9.694767E+01 - 2.200000E+00 2 2 1.429704E+03 1.234183E+02 - 2.200000E+00 2 4 1.147599E+04 1.348589E+02 - 2.200000E+00 3 3 2.161439E+03 4.401815E+00 - 2.200000E+00 4 2 1.149046E+04 1.381628E+02 - 2.200000E+00 4 4 2.583983E+05 2.061866E+02 - 2.200000E+00 5 1 -8.319411E+03 -9.914822E+01 - 2.200000E+00 5 5 8.168261E+05 1.187337E+02 - 2.200000E+00 6 6 5.324512E+05 5.808795E+04 - 2.300000E+00 1 1 1.015164E+03 1.006042E+02 - 2.300000E+00 1 5 -8.054513E+03 -1.371125E+02 - 2.300000E+00 2 2 1.385527E+03 1.660816E+02 - 2.300000E+00 2 4 1.133986E+04 1.926234E+02 - 2.300000E+00 3 3 2.164200E+03 5.022234E+00 - 2.300000E+00 4 2 1.135328E+04 1.947626E+02 - 2.300000E+00 4 4 2.579466E+05 2.966538E+02 - 2.300000E+00 5 1 -8.066244E+03 -1.383375E+02 - 2.300000E+00 5 5 8.162890E+05 1.932015E+02 - 2.300000E+00 6 6 5.070252E+05 7.404296E+04 - 2.400000E+00 1 1 1.214906E+03 5.852307E+02 - 2.400000E+00 1 5 -8.268893E+03 -8.177158E+02 - 2.400000E+00 2 2 1.387516E+03 1.894508E+02 - 2.400000E+00 2 4 1.122504E+04 2.547854E+02 - 2.400000E+00 3 3 2.163273E+03 2.346359E+00 - 2.400000E+00 4 2 1.123836E+04 2.560267E+02 - 2.400000E+00 4 4 2.574243E+05 4.518562E+02 - 2.400000E+00 5 1 -8.282180E+03 -8.209977E+02 - 2.400000E+00 5 5 8.163470E+05 1.156790E+03 - 2.400000E+00 6 6 5.116156E+05 1.178427E+05 - 2.500000E+00 1 1 1.246471E+03 2.142013E+02 - 2.500000E+00 1 5 -8.248199E+03 -3.329355E+02 - 2.500000E+00 2 2 1.357654E+03 2.025255E+02 - 2.500000E+00 2 4 1.107015E+04 3.476158E+02 - 2.500000E+00 3 3 2.161670E+03 2.311961E+00 - 2.500000E+00 4 2 1.108291E+04 3.480320E+02 - 2.500000E+00 4 4 2.568296E+05 7.940952E+02 - 2.500000E+00 5 1 -8.261192E+03 -3.337436E+02 - 2.500000E+00 5 5 8.160553E+05 5.377015E+02 - 2.500000E+00 6 6 5.215977E+05 1.176396E+05 - 2.600000E+00 1 1 1.152141E+03 1.682242E+02 - 2.600000E+00 1 5 -8.041700E+03 -2.895229E+02 - 2.600000E+00 2 2 1.304580E+03 2.326107E+02 - 2.600000E+00 2 4 1.090560E+04 5.031878E+02 - 2.600000E+00 3 3 2.160825E+03 3.126930E+00 - 2.600000E+00 4 2 1.091793E+04 5.049114E+02 - 2.600000E+00 4 4 2.563096E+05 1.381231E+03 - 2.600000E+00 5 1 -8.053100E+03 -2.900639E+02 - 2.600000E+00 5 5 8.154575E+05 5.286125E+02 - 2.600000E+00 6 6 5.093822E+05 1.192501E+05 - 2.700000E+00 1 1 1.035172E+03 1.608131E+02 - 2.700000E+00 1 5 -7.790863E+03 -3.237605E+02 - 2.700000E+00 2 2 1.266582E+03 3.277071E+02 - 2.700000E+00 2 4 1.085689E+04 7.817658E+02 - 2.700000E+00 3 3 2.160143E+03 4.236008E+00 - 2.700000E+00 4 2 1.086863E+04 7.819337E+02 - 2.700000E+00 4 4 2.564252E+05 2.109151E+03 - 2.700000E+00 5 1 -7.802771E+03 -3.243824E+02 - 2.700000E+00 5 5 8.147674E+05 6.867380E+02 - 2.700000E+00 6 6 4.884454E+05 1.238860E+05 - 2.799999E+00 1 1 8.628414E+02 1.778566E+02 - 2.799999E+00 1 5 -7.430020E+03 -3.774420E+02 - 2.799999E+00 2 2 1.293632E+03 3.825009E+02 - 2.799999E+00 2 4 1.088742E+04 8.311805E+02 - 2.799999E+00 3 3 2.159710E+03 5.450130E+00 - 2.799999E+00 4 2 1.089878E+04 8.314925E+02 - 2.799999E+00 4 4 2.562536E+05 1.832187E+03 - 2.799999E+00 5 1 -7.441687E+03 -3.780771E+02 - 2.799999E+00 5 5 8.138429E+05 8.621034E+02 - 2.799999E+00 6 6 4.470920E+05 1.495096E+05 - 2.899999E+00 1 1 4.788242E+02 4.073611E+02 - 2.899999E+00 1 5 -6.634616E+03 -7.981046E+02 - 2.899999E+00 2 2 1.286692E+03 4.327466E+02 - 2.899999E+00 2 4 1.075176E+04 9.386442E+02 - 2.899999E+00 3 3 2.160150E+03 7.244529E+00 - 2.899999E+00 4 2 1.076280E+04 9.389468E+02 - 2.899999E+00 4 4 2.554582E+05 2.041500E+03 - 2.899999E+00 5 1 -6.647493E+03 -7.984279E+02 - 2.899999E+00 5 5 8.120112E+05 1.683417E+03 - 2.899999E+00 6 6 4.254066E+05 2.188972E+05 - 2.999999E+00 1 1 8.676102E+02 1.330944E+03 - 2.999999E+00 1 5 -7.176687E+03 -2.660807E+03 - 2.999999E+00 2 2 1.320125E+03 4.957027E+02 - 2.999999E+00 2 4 1.069429E+04 1.124392E+03 - 2.999999E+00 3 3 2.161853E+03 8.607779E+00 - 2.999999E+00 4 2 1.070511E+04 1.124652E+03 - 2.999999E+00 4 4 2.548333E+05 2.578703E+03 - 2.999999E+00 5 1 -7.188262E+03 -2.658969E+03 - 2.999999E+00 5 5 8.124259E+05 5.464042E+03 - 2.999999E+00 6 6 4.548885E+05 2.814697E+05 - 3.099999E+00 1 1 1.489484E+03 9.715460E+02 - 3.099999E+00 1 5 -8.387819E+03 -2.143894E+03 - 3.099999E+00 2 2 1.352241E+03 4.908422E+02 - 3.099999E+00 2 4 1.064030E+04 1.206893E+03 - 3.099999E+00 3 3 2.164565E+03 8.339890E+00 - 3.099999E+00 4 2 1.065052E+04 1.207257E+03 - 3.099999E+00 4 4 2.542144E+05 3.023530E+03 - 3.099999E+00 5 1 -8.397405E+03 -2.142834E+03 - 3.099999E+00 5 5 8.144962E+05 4.911563E+03 - 3.099999E+00 6 6 4.956156E+05 3.123367E+05 - 3.199999E+00 1 1 1.552024E+03 6.866681E+02 - 3.199999E+00 1 5 -8.523776E+03 -1.651808E+03 - 3.199999E+00 2 2 1.317350E+03 4.811824E+02 - 3.199999E+00 2 4 1.045333E+04 1.308174E+03 - 3.199999E+00 3 3 2.165616E+03 5.539555E+00 - 3.199999E+00 4 2 1.046322E+04 1.308772E+03 - 3.199999E+00 4 4 2.533207E+05 3.628707E+03 - 3.199999E+00 5 1 -8.532786E+03 -1.651589E+03 - 3.199999E+00 5 5 8.144799E+05 4.254115E+03 - 3.199999E+00 6 6 5.333272E+05 3.238614E+05 - 3.299999E+00 1 1 1.519504E+03 5.044711E+02 - 3.299999E+00 1 5 -8.430406E+03 -1.328371E+03 - 3.299999E+00 2 2 1.244961E+03 5.202350E+02 - 3.299999E+00 2 4 1.019846E+04 1.549934E+03 - 3.299999E+00 3 3 2.164487E+03 3.300210E+00 - 3.299999E+00 4 2 1.020778E+04 1.550881E+03 - 3.299999E+00 4 4 2.523155E+05 4.681091E+03 - 3.299999E+00 5 1 -8.438989E+03 -1.328675E+03 - 3.299999E+00 5 5 8.139069E+05 3.954610E+03 - 3.299999E+00 6 6 5.629063E+05 3.183922E+05 - 3.399999E+00 1 1 1.429316E+03 3.587855E+02 - 3.399999E+00 1 5 -8.166790E+03 -1.082057E+03 - 3.399999E+00 2 2 1.186506E+03 6.180828E+02 - 3.399999E+00 2 4 1.000604E+04 1.949967E+03 - 3.399999E+00 3 3 2.162645E+03 2.077040E+00 - 3.399999E+00 4 2 1.001519E+04 1.951426E+03 - 3.399999E+00 4 4 2.515476E+05 6.202599E+03 - 3.399999E+00 5 1 -8.174550E+03 -1.082855E+03 - 3.399999E+00 5 5 8.128979E+05 3.939292E+03 - 3.399999E+00 6 6 5.734689E+05 2.999054E+05 - 3.499999E+00 1 1 1.253319E+03 2.631412E+02 - 3.499999E+00 1 5 -7.686133E+03 -1.006373E+03 - 3.499999E+00 2 2 1.168802E+03 7.364794E+02 - 3.499999E+00 2 4 9.936361E+03 2.405336E+03 - 3.499999E+00 3 3 2.159954E+03 2.400041E+00 - 3.499999E+00 4 2 9.945477E+03 2.407414E+03 - 3.499999E+00 4 4 2.511583E+05 7.909718E+03 - 3.499999E+00 5 1 -7.692891E+03 -1.008493E+03 - 3.499999E+00 5 5 8.114382E+05 4.566627E+03 - 3.499999E+00 6 6 5.554653E+05 2.852625E+05 - 3.599999E+00 1 1 1.035358E+03 2.876351E+02 - 3.599999E+00 1 5 -7.169593E+03 -1.269149E+03 - 3.599999E+00 2 2 1.171625E+03 8.513398E+02 - 3.599999E+00 2 4 9.931645E+03 2.860456E+03 - 3.599999E+00 3 3 2.158543E+03 4.722716E+00 - 3.599999E+00 4 2 9.940586E+03 2.863186E+03 - 3.599999E+00 4 4 2.509897E+05 9.670100E+03 - 3.599999E+00 5 1 -7.176320E+03 -1.273618E+03 - 3.599999E+00 5 5 8.102191E+05 6.195654E+03 - 3.599999E+00 6 6 5.199856E+05 2.974018E+05 - 3.699999E+00 1 1 8.653893E+02 4.021774E+02 - 3.699999E+00 1 5 -6.861894E+03 -1.715858E+03 - 3.699999E+00 2 2 1.176039E+03 9.740475E+02 - 3.699999E+00 2 4 9.947188E+03 3.355576E+03 - 3.699999E+00 3 3 2.159710E+03 6.722109E+00 - 3.699999E+00 4 2 9.956570E+03 3.358951E+03 - 3.699999E+00 4 4 2.509371E+05 1.161879E+04 - 3.699999E+00 5 1 -6.869617E+03 -1.722578E+03 - 3.699999E+00 5 5 8.099283E+05 8.157991E+03 - 3.699999E+00 6 6 4.924562E+05 3.377067E+05 - 3.799999E+00 1 1 7.344095E+02 5.368340E+02 - 3.799999E+00 1 5 -6.670849E+03 -2.110418E+03 - 3.799999E+00 2 2 1.187228E+03 1.129501E+03 - 3.799999E+00 2 4 1.001379E+04 3.962422E+03 - 3.799999E+00 3 3 2.161339E+03 6.376057E+00 - 3.799999E+00 4 2 1.002361E+04 3.966385E+03 - 3.799999E+00 4 4 2.511428E+05 1.396322E+04 - 3.799999E+00 5 1 -6.680824E+03 -2.118444E+03 - 3.799999E+00 5 5 8.101197E+05 9.580111E+03 - 3.799999E+00 6 6 4.834378E+05 3.896431E+05 - 3.899998E+00 1 1 5.949812E+02 6.974046E+02 - 3.899998E+00 1 5 -6.384929E+03 -2.498325E+03 - 3.899998E+00 2 2 1.238032E+03 1.334278E+03 - 3.899998E+00 2 4 1.024290E+04 4.716964E+03 - 3.899998E+00 3 3 2.161552E+03 5.115295E+00 - 3.899998E+00 4 2 1.025345E+04 4.721289E+03 - 3.899998E+00 4 4 2.519866E+05 1.676777E+04 - 3.899998E+00 5 1 -6.396908E+03 -2.506805E+03 - 3.899998E+00 5 5 8.099074E+05 1.060047E+04 - 3.899998E+00 6 6 4.874768E+05 4.423460E+05 - 3.999998E+00 1 1 4.450232E+02 9.303323E+02 - 3.999998E+00 1 5 -5.969588E+03 -3.085815E+03 - 3.999998E+00 2 2 1.378535E+03 1.572897E+03 - 3.999998E+00 2 4 1.078900E+04 5.550558E+03 - 3.999998E+00 3 3 2.160886E+03 4.168301E+00 - 3.999998E+00 4 2 1.080032E+04 5.554992E+03 - 3.999998E+00 4 4 2.539513E+05 1.975279E+04 - 3.999998E+00 5 1 -5.983599E+03 -3.094308E+03 - 3.999998E+00 5 5 8.089868E+05 1.202890E+04 - 3.999998E+00 6 6 4.982582E+05 4.964733E+05 - 4.099998E+00 1 1 3.213549E+02 1.272431E+03 - 4.099998E+00 1 5 -5.556480E+03 -4.045225E+03 - 4.099998E+00 2 2 1.644181E+03 1.786194E+03 - 4.099998E+00 2 4 1.175033E+04 6.261296E+03 - 4.099998E+00 3 3 2.159966E+03 3.734381E+00 - 4.099998E+00 4 2 1.176255E+04 6.265514E+03 - 4.099998E+00 4 4 2.573100E+05 2.222593E+04 - 4.099998E+00 5 1 -5.572396E+03 -4.053451E+03 - 4.099998E+00 5 5 8.077581E+05 1.462175E+04 - 4.099998E+00 6 6 5.168934E+05 5.566446E+05 - 4.199998E+00 1 1 2.837065E+02 1.745616E+03 - 4.199998E+00 1 5 -5.372986E+03 -5.475365E+03 - 4.199998E+00 2 2 2.021457E+03 1.891318E+03 - 4.199998E+00 2 4 1.306499E+04 6.578083E+03 - 4.199998E+00 3 3 2.159081E+03 3.634046E+00 - 4.199998E+00 4 2 1.307794E+04 6.581710E+03 - 4.199998E+00 4 4 2.618055E+05 2.329030E+04 - 4.199998E+00 5 1 -5.391368E+03 -5.482950E+03 - 4.199998E+00 5 5 8.070315E+05 1.884529E+04 - 4.199998E+00 6 6 5.500119E+05 6.233448E+05 - 4.299998E+00 1 1 4.283814E+02 2.352158E+03 - 4.299998E+00 1 5 -5.764863E+03 -7.385773E+03 - 4.299998E+00 2 2 2.437146E+03 1.823655E+03 - 4.299998E+00 2 4 1.447431E+04 6.295638E+03 - 4.299998E+00 3 3 2.158338E+03 3.688311E+00 - 4.299998E+00 4 2 1.448777E+04 6.298275E+03 - 4.299998E+00 4 4 2.665226E+05 2.228728E+04 - 4.299998E+00 5 1 -5.785992E+03 -7.391787E+03 - 4.299998E+00 5 5 8.080489E+05 2.478460E+04 - 4.299998E+00 6 6 6.038834E+05 6.911415E+05 - 4.399998E+00 1 1 9.079855E+02 3.018073E+03 - 4.399998E+00 1 5 -7.247806E+03 -9.523347E+03 - 4.399998E+00 2 2 2.782287E+03 1.581769E+03 - 4.399998E+00 2 4 1.560401E+04 5.428034E+03 - 4.399998E+00 3 3 2.157615E+03 3.792120E+00 - 4.399998E+00 4 2 1.561741E+04 5.429461E+03 - 4.399998E+00 4 4 2.701726E+05 1.932651E+04 - 4.399998E+00 5 1 -7.272055E+03 -9.525975E+03 - 4.399998E+00 5 5 8.125672E+05 3.159983E+04 - 4.399998E+00 6 6 6.810822E+05 7.511041E+05 - 4.499998E+00 1 1 1.844521E+03 3.468470E+03 - 4.499998E+00 1 5 -1.022216E+04 -1.098010E+04 - 4.499998E+00 2 2 2.973472E+03 1.241134E+03 - 4.499998E+00 2 4 1.617862E+04 4.252971E+03 - 4.499998E+00 3 3 2.157036E+03 3.889959E+00 - 4.499998E+00 4 2 1.619135E+04 4.253312E+03 - 4.499998E+00 4 4 2.718470E+05 1.542462E+04 - 4.499998E+00 5 1 -1.024756E+04 -1.097690E+04 - 4.499998E+00 5 5 8.219297E+05 3.629821E+04 - 4.499998E+00 6 6 7.797110E+05 7.932092E+05 - 4.599998E+00 1 1 3.006497E+03 3.288463E+03 - 4.599998E+00 1 5 -1.393009E+04 -1.040451E+04 - 4.599998E+00 2 2 3.003075E+03 9.052584E+02 - 4.599998E+00 2 4 1.619231E+04 3.134248E+03 - 4.599998E+00 3 3 2.156441E+03 3.947880E+00 - 4.599998E+00 4 2 1.620390E+04 3.133939E+03 - 4.599998E+00 4 4 2.715950E+05 1.185781E+04 - 4.599998E+00 5 1 -1.395269E+04 -1.039487E+04 - 4.599998E+00 5 5 8.336579E+05 3.448041E+04 - 4.599998E+00 6 6 8.930994E+05 8.082519E+05 - 4.699998E+00 1 1 3.794680E+03 2.495065E+03 - 4.699998E+00 1 5 -1.642829E+04 -7.858628E+03 - 4.699998E+00 2 2 2.923092E+03 6.415554E+02 - 4.699998E+00 2 4 1.584282E+04 2.298043E+03 - 4.699998E+00 3 3 2.155818E+03 3.930626E+00 - 4.699998E+00 4 2 1.585324E+04 2.297627E+03 - 4.699998E+00 4 4 2.701639E+05 9.380751E+03 - 4.699998E+00 5 1 -1.644485E+04 -7.845549E+03 - 4.699998E+00 5 5 8.414570E+05 2.637521E+04 - 4.699998E+00 6 6 1.010009E+06 7.903299E+05 - 4.799998E+00 1 1 3.985248E+03 1.611070E+03 - 4.799998E+00 1 5 -1.700283E+04 -5.037604E+03 - 4.799998E+00 2 2 2.794854E+03 4.658022E+02 - 4.799998E+00 2 4 1.535110E+04 1.786286E+03 - 4.799998E+00 3 3 2.155229E+03 3.795074E+00 - 4.799998E+00 4 2 1.536034E+04 1.786196E+03 - 4.799998E+00 4 4 2.683482E+05 8.090887E+03 - 4.799998E+00 5 1 -1.701342E+04 -5.024928E+03 - 4.799998E+00 5 5 8.430764E+05 1.747628E+04 - 4.799998E+00 6 6 1.116654E+06 7.396004E+05 - 4.899998E+00 1 1 3.827402E+03 9.634639E+02 - 4.899998E+00 1 5 -1.646776E+04 -2.990666E+03 - 4.899998E+00 2 2 2.660283E+03 3.640230E+02 - 4.899998E+00 2 4 1.486350E+04 1.538998E+03 - 4.899998E+00 3 3 2.154426E+03 3.535414E+00 - 4.899998E+00 4 2 1.487189E+04 1.539512E+03 - 4.899998E+00 4 4 2.666564E+05 7.737369E+03 - 4.899998E+00 5 1 -1.647437E+04 -2.980337E+03 - 4.899998E+00 5 5 8.411734E+05 1.114036E+04 - 4.899998E+00 6 6 1.200763E+06 6.633247E+05 - 4.999998E+00 1 1 3.566480E+03 5.624658E+02 - 4.999998E+00 1 5 -1.561565E+04 -1.741451E+03 - 4.999998E+00 2 2 2.540084E+03 3.146508E+02 - 4.999998E+00 2 4 1.444920E+04 1.473245E+03 - 4.999998E+00 3 3 2.153303E+03 3.274325E+00 - 4.999998E+00 4 2 1.445684E+04 1.474538E+03 - 4.999998E+00 4 4 2.653165E+05 8.002011E+03 - 4.999998E+00 5 1 -1.562004E+04 -1.733859E+03 - 4.999998E+00 5 5 8.383096E+05 7.408785E+03 - 4.999998E+00 6 6 1.255646E+06 5.736627E+05 - 5.099998E+00 1 1 3.311354E+03 3.283456E+02 - 5.099998E+00 1 5 -1.479400E+04 -1.026911E+03 - 5.099998E+00 2 2 2.441361E+03 2.988572E+02 - 5.099998E+00 2 4 1.412894E+04 1.518558E+03 - 5.099998E+00 3 3 2.151823E+03 3.256433E+00 - 5.099998E+00 4 2 1.413615E+04 1.520705E+03 - 5.099998E+00 4 4 2.643879E+05 8.620332E+03 - 5.099998E+00 5 1 -1.479733E+04 -1.021795E+03 - 5.099998E+00 5 5 8.355992E+05 5.414550E+03 - 5.099998E+00 6 6 1.281620E+06 4.832948E+05 - 5.199997E+00 1 1 3.093402E+03 1.941337E+02 - 5.199997E+00 1 5 -1.409953E+04 -6.287033E+02 - 5.199997E+00 2 2 2.364365E+03 3.029778E+02 - 5.199997E+00 2 4 1.389976E+04 1.624414E+03 - 5.199997E+00 3 3 2.150268E+03 3.657035E+00 - 5.199997E+00 4 2 1.390667E+04 1.627437E+03 - 5.199997E+00 4 4 2.638413E+05 9.404403E+03 - 5.199997E+00 5 1 -1.410244E+04 -6.256587E+02 - 5.199997E+00 5 5 8.333331E+05 4.449737E+03 - 5.199997E+00 6 6 1.284211E+06 4.016602E+05 - 5.299997E+00 1 1 2.915262E+03 1.179255E+02 - 5.299997E+00 1 5 -1.353667E+04 -4.115366E+02 - 5.299997E+00 2 2 2.306565E+03 3.179202E+02 - 5.299997E+00 2 4 1.374927E+04 1.757467E+03 - 5.299997E+00 3 3 2.148804E+03 4.470127E+00 - 5.299997E+00 4 2 1.375611E+04 1.761369E+03 - 5.299997E+00 4 4 2.636210E+05 1.023076E+04 - 5.299997E+00 5 1 -1.353960E+04 -4.101665E+02 - 5.299997E+00 5 5 8.315229E+05 4.081402E+03 - 5.299997E+00 6 6 1.270988E+06 3.336173E+05 - 5.399997E+00 1 1 2.771403E+03 7.535029E+01 - 5.399997E+00 1 5 -1.308473E+04 -2.980706E+02 - 5.399997E+00 2 2 2.264599E+03 3.379569E+02 - 5.399997E+00 2 4 1.366264E+04 1.896994E+03 - 5.399997E+00 3 3 2.147620E+03 5.584976E+00 - 5.399997E+00 4 2 1.366955E+04 1.901729E+03 - 5.399997E+00 4 4 2.636598E+05 1.102346E+04 - 5.399997E+00 5 1 -1.308783E+04 -2.980390E+02 - 5.399997E+00 5 5 8.301076E+05 4.066760E+03 - 5.399997E+00 6 6 1.249024E+06 2.801717E+05 - 5.499997E+00 1 1 2.654982E+03 5.237862E+01 - 5.499997E+00 1 5 -1.271948E+04 -2.452442E+02 - 5.499997E+00 2 2 2.235198E+03 3.596556E+02 - 5.499997E+00 2 4 1.362563E+04 2.030902E+03 - 5.499997E+00 3 3 2.146740E+03 6.866094E+00 - 5.499997E+00 4 2 1.363269E+04 2.036442E+03 - 5.499997E+00 4 4 2.638968E+05 1.173945E+04 - 5.499997E+00 5 1 -1.272269E+04 -2.462640E+02 - 5.499997E+00 5 5 8.290118E+05 4.272639E+03 - 5.499997E+00 6 6 1.223694E+06 2.399705E+05 - 5.599997E+00 1 1 2.559889E+03 4.090048E+01 - 5.599997E+00 1 5 -1.242047E+04 -2.296341E+02 - 5.599997E+00 2 2 2.215537E+03 3.810944E+02 - 5.599997E+00 2 4 1.362599E+04 2.152860E+03 - 5.599997E+00 3 3 2.146235E+03 8.188703E+00 - 5.599997E+00 4 2 1.363331E+04 2.159134E+03 - 5.599997E+00 4 4 2.642781E+05 1.235779E+04 - 5.599997E+00 5 1 -1.242398E+04 -2.314803E+02 - 5.599997E+00 5 5 8.281864E+05 4.624792E+03 - 5.599997E+00 6 6 1.198520E+06 2.106349E+05 - 5.699997E+00 1 1 2.481134E+03 3.622530E+01 - 5.699997E+00 1 5 -1.217205E+04 -2.390406E+02 - 5.699997E+00 2 2 2.203338E+03 4.012977E+02 - 5.699997E+00 2 4 1.365389E+04 2.260206E+03 - 5.699997E+00 3 3 2.146061E+03 9.437527E+00 - 5.699997E+00 4 2 1.366151E+04 2.267152E+03 - 5.699997E+00 4 4 2.647607E+05 1.287284E+04 - 5.699997E+00 5 1 -1.217571E+04 -2.415526E+02 - 5.699997E+00 5 5 8.276000E+05 5.077591E+03 - 5.699997E+00 6 6 1.175510E+06 1.896114E+05 - 5.799997E+00 1 1 2.414801E+03 3.571963E+01 - 5.799997E+00 1 5 -1.196363E+04 -2.675559E+02 - 5.799997E+00 2 2 2.196878E+03 4.198519E+02 - 5.799997E+00 2 4 1.370169E+04 2.352441E+03 - 5.799997E+00 3 3 2.146153E+03 1.050976E+01 - 5.799997E+00 4 2 1.370968E+04 2.360014E+03 - 5.799997E+00 4 4 2.653059E+05 1.328700E+04 - 5.799997E+00 5 1 -1.196734E+04 -2.706225E+02 - 5.799997E+00 5 5 8.272393E+05 5.595674E+03 - 5.799997E+00 6 6 1.155582E+06 1.745987E+05 - 5.899997E+00 1 1 2.357922E+03 3.801922E+01 - 5.899997E+00 1 5 -1.178885E+04 -3.124327E+02 - 5.899997E+00 2 2 2.194862E+03 4.366475E+02 - 5.899997E+00 2 4 1.376376E+04 2.430229E+03 - 5.899997E+00 3 3 2.146511E+03 1.132461E+01 - 5.899997E+00 4 2 1.377225E+04 2.438366E+03 - 5.899997E+00 4 4 2.658924E+05 1.360790E+04 - 5.899997E+00 5 1 -1.179261E+04 -3.160218E+02 - 5.899997E+00 5 5 8.270986E+05 6.141441E+03 - 5.899997E+00 6 6 1.138981E+06 1.637083E+05 - 5.999997E+00 1 1 2.308324E+03 4.254660E+01 - 5.999997E+00 1 5 -1.164482E+04 -3.718600E+02 - 5.999997E+00 2 2 2.196359E+03 4.517130E+02 - 5.999997E+00 2 4 1.383614E+04 2.494713E+03 - 5.999997E+00 3 3 2.146963E+03 1.182240E+01 - 5.999997E+00 4 2 1.384510E+04 2.503334E+03 - 5.999997E+00 4 4 2.665013E+05 1.384496E+04 - 5.999997E+00 5 1 -1.164849E+04 -3.759966E+02 - 5.999997E+00 5 5 8.271738E+05 6.672120E+03 - 5.999997E+00 6 6 1.125527E+06 1.554829E+05 - 6.099997E+00 1 1 2.264572E+03 4.916754E+01 - 6.099997E+00 1 5 -1.153115E+04 -4.434497E+02 - 6.099997E+00 2 2 2.200714E+03 4.651149E+02 - 6.099997E+00 2 4 1.391590E+04 2.547103E+03 - 6.099997E+00 3 3 2.147508E+03 1.197464E+01 - 6.099997E+00 4 2 1.392542E+04 2.556143E+03 - 6.099997E+00 4 4 2.671198E+05 1.400747E+04 - 6.099997E+00 5 1 -1.153461E+04 -4.482232E+02 - 6.099997E+00 5 5 8.274449E+05 7.137406E+03 - 6.099997E+00 6 6 1.114846E+06 1.488498E+05 - 6.199996E+00 1 1 2.225845E+03 5.791336E+01 - 6.199996E+00 1 5 -1.144855E+04 -5.233252E+02 - 6.199996E+00 2 2 2.207427E+03 4.769182E+02 - 6.199996E+00 2 4 1.400112E+04 2.588469E+03 - 6.199996E+00 3 3 2.147983E+03 1.177742E+01 - 6.199996E+00 4 2 1.401124E+04 2.597856E+03 - 6.199996E+00 4 4 2.677387E+05 1.410379E+04 - 6.199996E+00 5 1 -1.145172E+04 -5.288552E+02 - 6.199996E+00 5 5 8.278942E+05 7.486343E+03 - 6.199996E+00 6 6 1.106466E+06 1.430567E+05 - 6.299996E+00 1 1 2.191787E+03 6.876836E+01 - 6.299996E+00 1 5 -1.139713E+04 -6.060628E+02 - 6.299996E+00 2 2 2.216136E+03 4.871554E+02 - 6.299996E+00 2 4 1.409027E+04 2.619675E+03 - 6.299996E+00 3 3 2.148326E+03 1.125918E+01 - 6.299996E+00 4 2 1.410091E+04 2.629354E+03 - 6.299996E+00 4 4 2.683526E+05 1.414116E+04 - 6.299996E+00 5 1 -1.140029E+04 -6.124946E+02 - 6.299996E+00 5 5 8.284701E+05 7.676410E+03 - 6.299996E+00 6 6 1.099910E+06 1.376037E+05 - 6.399996E+00 1 1 2.162298E+03 8.153858E+01 - 6.399996E+00 1 5 -1.137579E+04 -6.853342E+02 - 6.399996E+00 2 2 2.226521E+03 4.958389E+02 - 6.399996E+00 2 4 1.418227E+04 2.641381E+03 - 6.399996E+00 3 3 2.148450E+03 1.045967E+01 - 6.399996E+00 4 2 1.419349E+04 2.651291E+03 - 6.399996E+00 4 4 2.689549E+05 1.412553E+04 - 6.399996E+00 5 1 -1.137890E+04 -6.927547E+02 - 6.399996E+00 5 5 8.291241E+05 7.681978E+03 - 6.399996E+00 6 6 1.094727E+06 1.321838E+05 - 6.499996E+00 1 1 2.137414E+03 9.581681E+01 - 6.499996E+00 1 5 -1.138117E+04 -7.549782E+02 - 6.499996E+00 2 2 2.238330E+03 5.029627E+02 - 6.499996E+00 2 4 1.427607E+04 2.654099E+03 - 6.499996E+00 3 3 2.148310E+03 9.437737E+00 - 6.499996E+00 4 2 1.428792E+04 2.664201E+03 - 6.499996E+00 4 4 2.695456E+05 1.406176E+04 - 6.499996E+00 5 1 -1.138441E+04 -7.634878E+02 - 6.499996E+00 5 5 8.297768E+05 7.499819E+03 - 6.499996E+00 6 6 1.090528E+06 1.266324E+05 - 6.599996E+00 1 1 2.117061E+03 1.110347E+02 - 6.599996E+00 1 5 -1.140839E+04 -8.100574E+02 - 6.599996E+00 2 2 2.251300E+03 5.085111E+02 - 6.599996E+00 2 4 1.437086E+04 2.658243E+03 - 6.599996E+00 3 3 2.147839E+03 8.258938E+00 - 6.599996E+00 4 2 1.438327E+04 2.668446E+03 - 6.599996E+00 4 4 2.701200E+05 1.395409E+04 - 6.599996E+00 5 1 -1.141190E+04 -8.196803E+02 - 6.599996E+00 5 5 8.303829E+05 7.147120E+03 - 6.599996E+00 6 6 1.086990E+06 1.208826E+05 - 6.699996E+00 1 1 2.101058E+03 1.265616E+02 - 6.699996E+00 1 5 -1.145151E+04 -8.475231E+02 - 6.699996E+00 2 2 2.265208E+03 5.124736E+02 - 6.699996E+00 2 4 1.446587E+04 2.654156E+03 - 6.699996E+00 3 3 2.147059E+03 6.990735E+00 - 6.699996E+00 4 2 1.447884E+04 2.664420E+03 - 6.699996E+00 4 4 2.706753E+05 1.380617E+04 - 6.699996E+00 5 1 -1.145549E+04 -8.582006E+02 - 6.699996E+00 5 5 8.309059E+05 6.657472E+03 - 6.699996E+00 6 6 1.083849E+06 1.149360E+05 - 6.799996E+00 1 1 2.089061E+03 1.418042E+02 - 6.799996E+00 1 5 -1.150458E+04 -8.662194E+02 - 6.799996E+00 2 2 2.279823E+03 5.148475E+02 - 6.799996E+00 2 4 1.456021E+04 2.642193E+03 - 6.799996E+00 3 3 2.145892E+03 5.702897E+00 - 6.799996E+00 4 2 1.457378E+04 2.652465E+03 - 6.799996E+00 4 4 2.712104E+05 1.362124E+04 - 6.799996E+00 5 1 -1.150923E+04 -8.779100E+02 - 6.799996E+00 5 5 8.313066E+05 6.069667E+03 - 6.799996E+00 6 6 1.080908E+06 1.088340E+05 - 6.899996E+00 1 1 2.080629E+03 1.562687E+02 - 6.899996E+00 1 5 -1.156227E+04 -8.666884E+02 - 6.899996E+00 2 2 2.294929E+03 5.156463E+02 - 6.899996E+00 2 4 1.465322E+04 2.622711E+03 - 6.899996E+00 3 3 2.144403E+03 4.455389E+00 - 6.899996E+00 4 2 1.466733E+04 2.632958E+03 - 6.899996E+00 4 4 2.717231E+05 1.340240E+04 - 6.899996E+00 5 1 -1.156771E+04 -8.792554E+02 - 6.899996E+00 5 5 8.315797E+05 5.424942E+03 - 6.899996E+00 6 6 1.078029E+06 1.026409E+05 - 6.999996E+00 1 1 2.075260E+03 1.695943E+02 - 6.999996E+00 1 5 -1.162010E+04 -8.505952E+02 - 6.999996E+00 2 2 2.310312E+03 5.149020E+02 - 6.999996E+00 2 4 1.474421E+04 2.596136E+03 - 6.999996E+00 3 3 2.142583E+03 3.305560E+00 - 6.999996E+00 4 2 1.475881E+04 2.606313E+03 - 6.999996E+00 4 4 2.722094E+05 1.315296E+04 - 6.999996E+00 5 1 -1.162643E+04 -8.639541E+02 - 6.999996E+00 5 5 8.317351E+05 4.758364E+03 - 6.999996E+00 6 6 1.075111E+06 9.642911E+04 - 7.099996E+00 1 1 2.072439E+03 1.815470E+02 - 7.099996E+00 1 5 -1.167486E+04 -8.202302E+02 - 7.099996E+00 2 2 2.325777E+03 5.126632E+02 - 7.099996E+00 2 4 1.483244E+04 2.562913E+03 - 7.099996E+00 3 3 2.140477E+03 2.306333E+00 - 7.099996E+00 4 2 1.484754E+04 2.572995E+03 - 7.099996E+00 4 4 2.726711E+05 1.287586E+04 - 7.099996E+00 5 1 -1.168208E+04 -8.342277E+02 - 7.099996E+00 5 5 8.317692E+05 4.099196E+03 - 7.099996E+00 6 6 1.072095E+06 9.026942E+04 - 7.199996E+00 1 1 2.071695E+03 1.920041E+02 - 7.199996E+00 1 5 -1.172426E+04 -7.781377E+02 - 7.199996E+00 2 2 2.341146E+03 5.089946E+02 - 7.199996E+00 2 4 1.491744E+04 2.523556E+03 - 7.199996E+00 3 3 2.138098E+03 1.499131E+00 - 7.199996E+00 4 2 1.493301E+04 2.533487E+03 - 7.199996E+00 4 4 2.731030E+05 1.257439E+04 - 7.199996E+00 5 1 -1.173251E+04 -7.926338E+02 - 7.199996E+00 5 5 8.317095E+05 3.469617E+03 - 7.199996E+00 6 6 1.068946E+06 8.422774E+04 - 7.299995E+00 1 1 2.072606E+03 2.009275E+02 - 7.299995E+00 1 5 -1.176687E+04 -7.268240E+02 - 7.299995E+00 2 2 2.356259E+03 5.039792E+02 - 7.299995E+00 2 4 1.499860E+04 2.478589E+03 - 7.299995E+00 3 3 2.135474E+03 9.279532E-01 - 7.299995E+00 4 2 1.501468E+04 2.488349E+03 - 7.299995E+00 4 4 2.735058E+05 1.225183E+04 - 7.299995E+00 5 1 -1.177615E+04 -7.416753E+02 - 7.299995E+00 5 5 8.315663E+05 2.884156E+03 - 7.299995E+00 6 6 1.065660E+06 7.835938E+04 - 7.399995E+00 1 1 2.074787E+03 2.083378E+02 - 7.399995E+00 1 5 -1.180199E+04 -6.685760E+02 - 7.399995E+00 2 2 2.370966E+03 4.977119E+02 - 7.399995E+00 2 4 1.507554E+04 2.428592E+03 - 7.399995E+00 3 3 2.132635E+03 6.037473E-01 - 7.399995E+00 4 2 1.509203E+04 2.438173E+03 - 7.399995E+00 4 4 2.738805E+05 1.191124E+04 - 7.399995E+00 5 1 -1.181220E+04 -6.836787E+02 - 7.399995E+00 5 5 8.313497E+05 2.351062E+03 - 7.399995E+00 6 6 1.062236E+06 7.270938E+04 - 7.499995E+00 1 1 2.077932E+03 2.142973E+02 - 7.499995E+00 1 5 -1.182921E+04 -6.054490E+02 - 7.499995E+00 2 2 2.385135E+03 4.902971E+02 - 7.499995E+00 2 4 1.514793E+04 2.374177E+03 - 7.499995E+00 3 3 2.129649E+03 5.671070E-01 - 7.499995E+00 4 2 1.516477E+04 2.383516E+03 - 7.499995E+00 4 4 2.742241E+05 1.155591E+04 - 7.499995E+00 5 1 -1.184038E+04 -6.206963E+02 - 7.499995E+00 5 5 8.310848E+05 1.877915E+03 - 7.499995E+00 6 6 1.058691E+06 6.731214E+04 - 7.599995E+00 1 1 2.081773E+03 2.188925E+02 - 7.599995E+00 1 5 -1.184871E+04 -5.391864E+02 - 7.599995E+00 2 2 2.398670E+03 4.818479E+02 - 7.599995E+00 2 4 1.521542E+04 2.315932E+03 - 7.599995E+00 3 3 2.126565E+03 8.177404E-01 - 7.599995E+00 4 2 1.523262E+04 2.325047E+03 - 7.599995E+00 4 4 2.745371E+05 1.118883E+04 - 7.599995E+00 5 1 -1.186081E+04 -5.544869E+02 - 7.599995E+00 5 5 8.307815E+05 1.463640E+03 - 7.599995E+00 6 6 1.055047E+06 6.219123E+04 - 7.699995E+00 1 1 2.086093E+03 2.222232E+02 - 7.699995E+00 1 5 -1.186067E+04 -4.712784E+02 - 7.699995E+00 2 2 2.411483E+03 4.724805E+02 - 7.699995E+00 2 4 1.527788E+04 2.254471E+03 - 7.699995E+00 3 3 2.123444E+03 1.365790E+00 - 7.699995E+00 4 2 1.529545E+04 2.263340E+03 - 7.699995E+00 4 4 2.748192E+05 1.081316E+04 - 7.699995E+00 5 1 -1.187376E+04 -4.865450E+02 - 7.699995E+00 5 5 8.304544E+05 1.108845E+03 - 7.699995E+00 6 6 1.051326E+06 5.736161E+04 - 7.799995E+00 1 1 2.090712E+03 2.243958E+02 - 7.799995E+00 1 5 -1.186565E+04 -4.029154E+02 - 7.799995E+00 2 2 2.423494E+03 4.623121E+02 - 7.799995E+00 2 4 1.533516E+04 2.190390E+03 - 7.799995E+00 3 3 2.120203E+03 2.217513E+00 - 7.799995E+00 4 2 1.535297E+04 2.198995E+03 - 7.799995E+00 4 4 2.750714E+05 1.043161E+04 - 7.799995E+00 5 1 -1.187954E+04 -4.180592E+02 - 7.799995E+00 5 5 8.301100E+05 8.121940E+02 - 7.799995E+00 6 6 1.047555E+06 5.283081E+04 - 7.899995E+00 1 1 2.095488E+03 2.255192E+02 - 7.899995E+00 1 5 -1.186409E+04 -3.351206E+02 - 7.899995E+00 2 2 2.434678E+03 4.514663E+02 - 7.899995E+00 2 4 1.538724E+04 2.124265E+03 - 7.899995E+00 3 3 2.116944E+03 3.360539E+00 - 7.899995E+00 4 2 1.540535E+04 2.132591E+03 - 7.899995E+00 4 4 2.752947E+05 1.004683E+04 - 7.899995E+00 5 1 -1.187884E+04 -3.501150E+02 - 7.899995E+00 5 5 8.297590E+05 5.689839E+02 - 7.899995E+00 6 6 1.043756E+06 4.859913E+04 - 7.999995E+00 1 1 2.100296E+03 2.256954E+02 - 7.999995E+00 1 5 -1.185661E+04 -2.686796E+02 - 7.999995E+00 2 2 2.444984E+03 4.400553E+02 - 7.999995E+00 2 4 1.543411E+04 2.056642E+03 - 7.999995E+00 3 3 2.113878E+03 4.791380E+00 - 7.999995E+00 4 2 1.545251E+04 2.064698E+03 - 7.999995E+00 4 4 2.754896E+05 9.661417E+03 - 7.999995E+00 5 1 -1.187211E+04 -2.834257E+02 - 7.999995E+00 5 5 8.294042E+05 3.772042E+02 - 7.999995E+00 6 6 1.039954E+06 4.466331E+04 - 8.099995E+00 1 1 2.105043E+03 2.250288E+02 - 8.099995E+00 1 5 -1.184374E+04 -2.042322E+02 - 8.099995E+00 2 2 2.454391E+03 4.281921E+02 - 8.099995E+00 2 4 1.547590E+04 1.988044E+03 - 8.099995E+00 3 3 2.110774E+03 6.490849E+00 - 8.099995E+00 4 2 1.549449E+04 1.995820E+03 - 8.099995E+00 4 4 2.756571E+05 9.277499E+03 - 8.099995E+00 5 1 -1.186001E+04 -2.187066E+02 - 8.099995E+00 5 5 8.290612E+05 2.299006E+02 - 8.099995E+00 6 6 1.036167E+06 4.101462E+04 - 8.199995E+00 1 1 2.109657E+03 2.236175E+02 - 8.199995E+00 1 5 -1.182620E+04 -1.422705E+02 - 8.199995E+00 2 2 2.462898E+03 4.159829E+02 - 8.199995E+00 2 4 1.551268E+04 1.918951E+03 - 8.199995E+00 3 3 2.107748E+03 8.447360E+00 - 8.199995E+00 4 2 1.553151E+04 1.926441E+03 - 8.199995E+00 4 4 2.757995E+05 8.897201E+03 - 8.199995E+00 5 1 -1.184303E+04 -1.564419E+02 - 8.199995E+00 5 5 8.287231E+05 1.246058E+02 - 8.199995E+00 6 6 1.032420E+06 3.764148E+04 - 8.299995E+00 1 1 2.114084E+03 2.215516E+02 - 8.299995E+00 1 5 -1.180446E+04 -8.315440E+01 - 8.299995E+00 2 2 2.470516E+03 4.035282E+02 - 8.299995E+00 2 4 1.554465E+04 1.849790E+03 - 8.299995E+00 3 3 2.104778E+03 1.064496E+01 - 8.299995E+00 4 2 1.556365E+04 1.857000E+03 - 8.299995E+00 4 4 2.759166E+05 8.522346E+03 - 8.299995E+00 5 1 -1.182185E+04 -9.698260E+01 - 8.299995E+00 5 5 8.284002E+05 5.721358E+01 - 8.299995E+00 6 6 1.028722E+06 3.453144E+04 - 8.399996E+00 1 1 2.118270E+03 2.189154E+02 - 8.399996E+00 1 5 -1.177912E+04 -2.715824E+01 - 8.399996E+00 2 2 2.477254E+03 3.909195E+02 - 8.399996E+00 2 4 1.557200E+04 1.780962E+03 - 8.399996E+00 3 3 2.102108E+03 1.305641E+01 - 8.399996E+00 4 2 1.559114E+04 1.787888E+03 - 8.399996E+00 4 4 2.760100E+05 8.154471E+03 - 8.399996E+00 5 1 -1.179728E+04 -4.061836E+01 - 8.399996E+00 5 5 8.280962E+05 2.171890E+01 - 8.399996E+00 6 6 1.025088E+06 3.166960E+04 - 8.499996E+00 1 1 2.122186E+03 2.157903E+02 - 8.499996E+00 1 5 -1.175079E+04 2.553195E+01 - 8.499996E+00 2 2 2.483139E+03 3.782419E+02 - 8.499996E+00 2 4 1.559496E+04 1.712812E+03 - 8.499996E+00 3 3 2.099453E+03 1.566890E+01 - 8.499996E+00 4 2 1.561420E+04 1.719462E+03 - 8.499996E+00 4 4 2.760831E+05 7.794858E+03 - 8.499996E+00 5 1 -1.176919E+04 1.244153E+01 - 8.499996E+00 5 5 8.278067E+05 1.413896E+01 - 8.499996E+00 6 6 1.021530E+06 2.904142E+04 - 8.599997E+00 1 1 2.125807E+03 2.122490E+02 - 8.599997E+00 1 5 -1.171985E+04 7.481567E+01 - 8.599997E+00 2 2 2.488220E+03 3.655711E+02 - 8.599997E+00 2 4 1.561375E+04 1.645655E+03 - 8.599997E+00 3 3 2.097045E+03 1.845528E+01 - 8.599997E+00 4 2 1.563320E+04 1.652033E+03 - 8.599997E+00 4 4 2.761368E+05 7.444747E+03 - 8.599997E+00 5 1 -1.173875E+04 6.210162E+01 - 8.599997E+00 5 5 8.275368E+05 3.248663E+01 - 8.599997E+00 6 6 1.018057E+06 2.663150E+04 - 8.699997E+00 1 1 2.129122E+03 2.083591E+02 - 8.699997E+00 1 5 -1.168679E+04 1.206401E+02 - 8.699997E+00 2 2 2.492500E+03 3.529729E+02 - 8.699997E+00 2 4 1.562877E+04 1.579750E+03 - 8.699997E+00 3 3 2.094784E+03 2.139310E+01 - 8.699997E+00 4 2 1.564822E+04 1.585861E+03 - 8.699997E+00 4 4 2.761712E+05 7.104951E+03 - 8.699997E+00 5 1 -1.170619E+04 1.083546E+02 - 8.699997E+00 5 5 8.272876E+05 7.108610E+01 - 8.699997E+00 6 6 1.014673E+06 2.442441E+04 - 8.799997E+00 1 1 2.132108E+03 2.041796E+02 - 8.799997E+00 1 5 -1.165208E+04 1.630059E+02 - 8.799997E+00 2 2 2.496054E+03 3.405104E+02 - 8.799997E+00 2 4 1.564011E+04 1.515317E+03 - 8.799997E+00 3 3 2.092668E+03 2.446405E+01 - 8.799997E+00 4 2 1.565965E+04 1.521175E+03 - 8.799997E+00 4 4 2.761891E+05 6.776250E+03 - 8.799997E+00 5 1 -1.167177E+04 1.511158E+02 - 8.799997E+00 5 5 8.270590E+05 1.277786E+02 - 8.799997E+00 6 6 1.011389E+06 2.240512E+04 - 8.899998E+00 1 1 2.134787E+03 1.997698E+02 - 8.899998E+00 1 5 -1.161606E+04 2.019601E+02 - 8.899998E+00 2 2 2.498899E+03 3.282321E+02 - 8.899998E+00 2 4 1.564816E+04 1.452547E+03 - 8.899998E+00 3 3 2.090809E+03 2.764819E+01 - 8.899998E+00 4 2 1.566773E+04 1.458146E+03 - 8.899998E+00 4 4 2.761923E+05 6.459099E+03 - 8.899998E+00 5 1 -1.163613E+04 1.904809E+02 - 8.899998E+00 5 5 8.268539E+05 1.984217E+02 - 8.899998E+00 6 6 1.008203E+06 2.055934E+04 - 8.999998E+00 1 1 2.137139E+03 1.951779E+02 - 8.999998E+00 1 5 -1.157913E+04 2.375940E+02 - 8.999998E+00 2 2 2.501099E+03 3.161833E+02 - 8.999998E+00 2 4 1.565312E+04 1.391578E+03 - 8.999998E+00 3 3 2.089147E+03 3.091510E+01 - 8.999998E+00 4 2 1.567273E+04 1.396935E+03 - 8.999998E+00 4 4 2.761813E+05 6.153932E+03 - 8.999998E+00 5 1 -1.159956E+04 2.265213E+02 - 8.999998E+00 5 5 8.266658E+05 2.798887E+02 - 8.999998E+00 6 6 1.005116E+06 1.887311E+04 - 9.099998E+00 1 1 2.139179E+03 1.904497E+02 - 9.099998E+00 1 5 -1.154158E+04 2.699872E+02 - 9.099998E+00 2 2 2.502697E+03 3.043991E+02 - 9.099998E+00 2 4 1.565532E+04 1.332532E+03 - 9.099998E+00 3 3 2.087586E+03 3.426651E+01 - 9.099998E+00 4 2 1.567497E+04 1.337655E+03 - 9.099998E+00 4 4 2.761585E+05 5.861023E+03 - 9.099998E+00 5 1 -1.156220E+04 2.593232E+02 - 9.099998E+00 5 5 8.264962E+05 3.718103E+02 - 9.099998E+00 6 6 1.002138E+06 1.733350E+04 - 9.199999E+00 1 1 2.140917E+03 1.856276E+02 - 9.199999E+00 1 5 -1.150366E+04 2.992821E+02 - 9.199999E+00 2 2 2.503735E+03 2.929104E+02 - 9.199999E+00 2 4 1.565494E+04 1.275499E+03 - 9.199999E+00 3 3 2.086263E+03 3.766659E+01 - 9.199999E+00 4 2 1.567466E+04 1.280395E+03 - 9.199999E+00 4 4 2.761253E+05 5.580450E+03 - 9.199999E+00 5 1 -1.152461E+04 2.890033E+02 - 9.199999E+00 5 5 8.263453E+05 4.689281E+02 - 9.199999E+00 6 6 9.992583E+05 1.592806E+04 - 9.299999E+00 1 1 2.142360E+03 1.807444E+02 - 9.299999E+00 1 5 -1.146577E+04 3.256198E+02 - 9.299999E+00 2 2 2.504263E+03 2.817413E+02 - 9.299999E+00 2 4 1.565232E+04 1.220524E+03 - 9.299999E+00 3 3 2.085159E+03 4.110686E+01 - 9.299999E+00 4 2 1.567206E+04 1.225203E+03 - 9.299999E+00 4 4 2.760819E+05 5.312197E+03 - 9.299999E+00 5 1 -1.148686E+04 3.157380E+02 - 9.299999E+00 5 5 8.262131E+05 5.715813E+02 - 9.299999E+00 6 6 9.964791E+05 1.464538E+04 - 9.400000E+00 1 1 2.143522E+03 1.758346E+02 - 9.400000E+00 1 5 -1.142796E+04 3.491375E+02 - 9.400000E+00 2 2 2.504321E+03 2.709106E+02 - 9.400000E+00 2 4 1.564766E+04 1.167654E+03 - 9.400000E+00 3 3 2.084164E+03 4.457240E+01 - 9.400000E+00 4 2 1.566744E+04 1.172125E+03 - 9.400000E+00 4 4 2.760290E+05 5.056130E+03 - 9.400000E+00 5 1 -1.144924E+04 3.396265E+02 - 9.400000E+00 5 5 8.260980E+05 6.765178E+02 - 9.400000E+00 6 6 9.938049E+05 1.347482E+04 - 9.500000E+00 1 1 2.144417E+03 1.709239E+02 - 9.500000E+00 1 5 -1.139042E+04 3.700067E+02 - 9.500000E+00 2 2 2.503960E+03 2.604297E+02 - 9.500000E+00 2 4 1.564121E+04 1.116898E+03 - 9.500000E+00 3 3 2.083362E+03 4.804810E+01 - 9.500000E+00 4 2 1.566090E+04 1.121167E+03 - 9.500000E+00 4 4 2.759722E+05 4.812139E+03 - 9.500000E+00 5 1 -1.141188E+04 3.608785E+02 - 9.500000E+00 5 5 8.260032E+05 7.829916E+02 - 9.500000E+00 6 6 9.912272E+05 1.240666E+04 - 9.600000E+00 1 1 2.145063E+03 1.660383E+02 - 9.600000E+00 1 5 -1.135346E+04 3.883761E+02 - 9.600000E+00 2 2 2.503218E+03 2.503093E+02 - 9.600000E+00 2 4 1.563313E+04 1.068251E+03 - 9.600000E+00 3 3 2.082737E+03 5.152150E+01 - 9.600000E+00 4 2 1.565285E+04 1.072326E+03 - 9.600000E+00 4 4 2.759075E+05 4.579906E+03 - 9.600000E+00 5 1 -1.137502E+04 3.796046E+02 - 9.600000E+00 5 5 8.259168E+05 8.892158E+02 - 9.600000E+00 6 6 9.887462E+05 1.143185E+04 - 9.700001E+00 1 1 2.145472E+03 1.611957E+02 - 9.700001E+00 1 5 -1.131713E+04 4.044158E+02 - 9.700001E+00 2 2 2.502142E+03 2.405545E+02 - 9.700001E+00 2 4 1.562367E+04 1.021697E+03 - 9.700001E+00 3 3 2.082276E+03 5.498514E+01 - 9.700001E+00 4 2 1.564341E+04 1.025586E+03 - 9.700001E+00 4 4 2.758360E+05 4.359174E+03 - 9.700001E+00 5 1 -1.133862E+04 3.960084E+02 - 9.700001E+00 5 5 8.258537E+05 9.951490E+02 - 9.700001E+00 6 6 9.863594E+05 1.054168E+04 - 9.800001E+00 1 1 2.145671E+03 1.564165E+02 - 9.800001E+00 1 5 -1.128141E+04 4.183023E+02 - 9.800001E+00 2 2 2.500755E+03 2.311662E+02 - 9.800001E+00 2 4 1.561294E+04 9.772015E+02 - 9.800001E+00 3 3 2.081937E+03 5.842216E+01 - 9.800001E+00 4 2 1.563265E+04 9.809180E+02 - 9.800001E+00 4 4 2.757614E+05 4.149600E+03 - 9.800001E+00 5 1 -1.130307E+04 4.102207E+02 - 9.800001E+00 5 5 8.257966E+05 1.098057E+03 - 9.800001E+00 6 6 9.840654E+05 9.728938E+03 - 9.900002E+00 1 1 2.145658E+03 1.517129E+02 - 9.900002E+00 1 5 -1.124661E+04 4.301864E+02 - 9.900002E+00 2 2 2.499100E+03 2.221429E+02 - 9.900002E+00 2 4 1.560114E+04 9.347197E+02 - 9.900002E+00 3 3 2.081755E+03 6.183162E+01 - 9.900002E+00 4 2 1.562081E+04 9.382680E+02 - 9.900002E+00 4 4 2.756829E+05 3.950739E+03 - 9.900002E+00 5 1 -1.126836E+04 4.224308E+02 - 9.900002E+00 5 5 8.257466E+05 1.198787E+03 - 9.900002E+00 6 6 9.818568E+05 8.986440E+03 - 1.000000E+01 1 1 2.145465E+03 1.470993E+02 - 1.000000E+01 1 5 -1.121264E+04 4.402153E+02 - 1.000000E+01 2 2 2.497211E+03 2.134834E+02 - 1.000000E+01 2 4 1.558852E+04 8.942076E+02 - 1.000000E+01 3 3 2.081736E+03 6.520229E+01 - 1.000000E+01 4 2 1.560818E+04 8.975975E+02 - 1.000000E+01 4 4 2.756025E+05 3.762234E+03 - 1.000000E+01 5 1 -1.123443E+04 4.327898E+02 - 1.000000E+01 5 5 8.257079E+05 1.295562E+03 - 1.000000E+01 6 6 9.797342E+05 8.307854E+03 - 1.010000E+01 1 1 2.145102E+03 1.425842E+02 - 1.010000E+01 1 5 -1.117965E+04 4.485279E+02 - 1.010000E+01 2 2 2.495111E+03 2.051799E+02 - 1.010000E+01 2 4 1.557513E+04 8.556025E+02 - 1.010000E+01 3 3 2.081813E+03 6.852578E+01 - 1.010000E+01 4 2 1.559459E+04 8.588407E+02 - 1.010000E+01 4 4 2.755189E+05 3.583694E+03 - 1.010000E+01 5 1 -1.120152E+04 4.414140E+02 - 1.010000E+01 5 5 8.256924E+05 1.389465E+03 - 1.010000E+01 6 6 9.776943E+05 7.687389E+03 - 1.020000E+01 1 1 2.144577E+03 1.381759E+02 - 1.020000E+01 1 5 -1.114771E+04 4.553047E+02 - 1.020000E+01 2 2 2.492841E+03 1.972271E+02 - 1.020000E+01 2 4 1.556101E+04 8.188411E+02 - 1.020000E+01 3 3 2.082054E+03 7.180158E+01 - 1.020000E+01 4 2 1.558062E+04 8.219407E+02 - 1.020000E+01 4 4 2.754333E+05 3.414641E+03 - 1.020000E+01 5 1 -1.116960E+04 4.484713E+02 - 1.020000E+01 5 5 8.256652E+05 1.478140E+03 - 1.020000E+01 6 6 9.757329E+05 7.119680E+03 - 1.030000E+01 1 1 2.143912E+03 1.338805E+02 - 1.030000E+01 1 5 -1.111675E+04 4.606376E+02 - 1.030000E+01 2 2 2.490404E+03 1.896145E+02 - 1.030000E+01 2 4 1.554646E+04 7.838583E+02 - 1.030000E+01 3 3 2.082380E+03 7.501859E+01 - 1.030000E+01 4 2 1.556596E+04 7.868245E+02 - 1.030000E+01 4 4 2.753469E+05 3.254677E+03 - 1.030000E+01 5 1 -1.113858E+04 4.540824E+02 - 1.030000E+01 5 5 8.256712E+05 1.562478E+03 - 1.030000E+01 6 6 9.738463E+05 6.599924E+03 - 1.040000E+01 1 1 2.143127E+03 1.297027E+02 - 1.040000E+01 1 5 -1.108676E+04 4.646914E+02 - 1.040000E+01 2 2 2.487852E+03 1.823339E+02 - 1.040000E+01 2 4 1.553150E+04 7.505894E+02 - 1.040000E+01 3 3 2.082812E+03 7.818211E+01 - 1.040000E+01 4 2 1.555099E+04 7.534227E+02 - 1.040000E+01 4 4 2.752601E+05 3.103319E+03 - 1.040000E+01 5 1 -1.110876E+04 4.584017E+02 - 1.040000E+01 5 5 8.256668E+05 1.642683E+03 - 1.040000E+01 6 6 9.720320E+05 6.123848E+03 - 1.050000E+01 1 1 2.142212E+03 1.256457E+02 - 1.050000E+01 1 5 -1.105802E+04 4.675668E+02 - 1.050000E+01 2 2 2.485180E+03 1.753749E+02 - 1.050000E+01 2 4 1.551622E+04 7.189579E+02 - 1.050000E+01 3 3 2.083348E+03 8.127702E+01 - 1.050000E+01 4 2 1.553561E+04 7.216663E+02 - 1.050000E+01 4 4 2.751720E+05 2.960191E+03 - 1.050000E+01 5 1 -1.107979E+04 4.615325E+02 - 1.050000E+01 5 5 8.256658E+05 1.717788E+03 - 1.050000E+01 6 6 9.702887E+05 5.687414E+03 - 1.060000E+01 1 1 2.141205E+03 1.217116E+02 - 1.060000E+01 1 5 -1.103006E+04 4.693828E+02 - 1.060000E+01 2 2 2.482431E+03 1.687262E+02 - 1.060000E+01 2 4 1.550066E+04 6.888983E+02 - 1.060000E+01 3 3 2.083969E+03 8.431265E+01 - 1.060000E+01 4 2 1.552005E+04 6.914917E+02 - 1.060000E+01 4 4 2.750842E+05 2.824860E+03 - 1.060000E+01 5 1 -1.105195E+04 4.635920E+02 - 1.060000E+01 5 5 8.256779E+05 1.788114E+03 - 1.060000E+01 6 6 9.686122E+05 5.287014E+03 - 1.070000E+01 1 1 2.140107E+03 1.179014E+02 - 1.070000E+01 1 5 -1.100345E+04 4.702292E+02 - 1.070000E+01 2 2 2.479598E+03 1.623760E+02 - 1.070000E+01 2 4 1.548502E+04 6.603346E+02 - 1.070000E+01 3 3 2.084695E+03 8.728065E+01 - 1.070000E+01 4 2 1.550429E+04 6.628145E+02 - 1.070000E+01 4 4 2.749969E+05 2.696889E+03 - 1.070000E+01 5 1 -1.102518E+04 4.646789E+02 - 1.070000E+01 5 5 8.256959E+05 1.853688E+03 - 1.070000E+01 6 6 9.669974E+05 4.919559E+03 - 1.080000E+01 1 1 2.138926E+03 1.142137E+02 - 1.080000E+01 1 5 -1.097759E+04 4.702310E+02 - 1.080000E+01 2 2 2.476715E+03 1.563144E+02 - 1.080000E+01 2 4 1.546918E+04 6.331996E+02 - 1.080000E+01 3 3 2.085490E+03 9.018382E+01 - 1.080000E+01 4 2 1.548842E+04 6.355766E+02 - 1.080000E+01 4 4 2.749096E+05 2.575933E+03 - 1.080000E+01 5 1 -1.099937E+04 4.648986E+02 - 1.080000E+01 5 5 8.257069E+05 1.914251E+03 - 1.080000E+01 6 6 9.654451E+05 4.581916E+03 - 1.090001E+01 1 1 2.137670E+03 1.106502E+02 - 1.090001E+01 1 5 -1.095299E+04 4.694513E+02 - 1.090001E+01 2 2 2.473783E+03 1.505286E+02 - 1.090001E+01 2 4 1.545333E+04 6.074255E+02 - 1.090001E+01 3 3 2.086341E+03 9.301959E+01 - 1.090001E+01 4 2 1.547258E+04 6.097039E+02 - 1.090001E+01 4 4 2.748224E+05 2.461529E+03 - 1.090001E+01 5 1 -1.097454E+04 4.643502E+02 - 1.090001E+01 5 5 8.257381E+05 1.970232E+03 - 1.090001E+01 6 6 9.639502E+05 4.271438E+03 - 1.100001E+01 1 1 2.136364E+03 1.072084E+02 - 1.100001E+01 1 5 -1.092918E+04 4.680009E+02 - 1.100001E+01 2 2 2.470831E+03 1.450070E+02 - 1.100001E+01 2 4 1.543755E+04 5.829437E+02 - 1.100001E+01 3 3 2.087261E+03 9.578189E+01 - 1.100001E+01 4 2 1.545666E+04 5.851293E+02 - 1.100001E+01 4 4 2.747374E+05 2.353424E+03 - 1.100001E+01 5 1 -1.095086E+04 4.630921E+02 - 1.100001E+01 5 5 8.257575E+05 2.021854E+03 - 1.100001E+01 6 6 9.625105E+05 3.985717E+03 - 1.110001E+01 1 1 2.134999E+03 1.038862E+02 - 1.110001E+01 1 5 -1.090647E+04 4.659317E+02 - 1.110001E+01 2 2 2.467854E+03 1.397381E+02 - 1.110001E+01 2 4 1.542175E+04 5.596920E+02 - 1.110001E+01 3 3 2.088266E+03 9.847754E+01 - 1.110001E+01 4 2 1.544090E+04 5.617880E+02 - 1.110001E+01 4 4 2.746530E+05 2.251185E+03 - 1.110001E+01 5 1 -1.092806E+04 4.612215E+02 - 1.110001E+01 5 5 8.257892E+05 2.068661E+03 - 1.110001E+01 6 6 9.611222E+05 3.722606E+03 - 1.120001E+01 1 1 2.133589E+03 1.006825E+02 - 1.120001E+01 1 5 -1.088462E+04 4.633327E+02 - 1.120001E+01 2 2 2.464867E+03 1.347108E+02 - 1.120001E+01 2 4 1.540606E+04 5.376023E+02 - 1.120001E+01 3 3 2.089307E+03 1.011065E+02 - 1.120001E+01 4 2 1.542512E+04 5.396155E+02 - 1.120001E+01 4 4 2.745692E+05 2.154438E+03 - 1.120001E+01 5 1 -1.090628E+04 4.588030E+02 - 1.120001E+01 5 5 8.258142E+05 2.111276E+03 - 1.120001E+01 6 6 9.597874E+05 3.480049E+03 - 1.130001E+01 1 1 2.132145E+03 9.759343E+01 - 1.130001E+01 1 5 -1.086372E+04 4.602499E+02 - 1.130001E+01 2 2 2.461884E+03 1.299144E+02 - 1.130001E+01 2 4 1.539056E+04 5.166194E+02 - 1.130001E+01 3 3 2.090402E+03 1.036618E+02 - 1.130001E+01 4 2 1.540961E+04 5.185527E+02 - 1.130001E+01 4 4 2.744871E+05 2.062993E+03 - 1.130001E+01 5 1 -1.088540E+04 4.559028E+02 - 1.130001E+01 5 5 8.258488E+05 2.149967E+03 - 1.130001E+01 6 6 9.584996E+05 3.256323E+03 - 1.140001E+01 1 1 2.130662E+03 9.461726E+01 - 1.140001E+01 1 5 -1.084381E+04 4.567544E+02 - 1.140001E+01 2 2 2.458892E+03 1.253371E+02 - 1.140001E+01 2 4 1.537518E+04 4.966835E+02 - 1.140001E+01 3 3 2.091546E+03 1.061545E+02 - 1.140001E+01 4 2 1.539409E+04 4.985375E+02 - 1.140001E+01 4 4 2.744073E+05 1.976416E+03 - 1.140001E+01 5 1 -1.086519E+04 4.525659E+02 - 1.140001E+01 5 5 8.258861E+05 2.184761E+03 - 1.140001E+01 6 6 9.572577E+05 3.049736E+03 - 1.150001E+01 1 1 2.129159E+03 9.174998E+01 - 1.150001E+01 1 5 -1.082464E+04 4.528948E+02 - 1.150001E+01 2 2 2.455925E+03 1.209695E+02 - 1.150001E+01 2 4 1.535997E+04 4.777368E+02 - 1.150001E+01 3 3 2.092718E+03 1.085756E+02 - 1.150001E+01 4 2 1.537888E+04 4.795195E+02 - 1.150001E+01 4 4 2.743275E+05 1.894500E+03 - 1.150001E+01 5 1 -1.084610E+04 4.488746E+02 - 1.150001E+01 5 5 8.259156E+05 2.215852E+03 - 1.150001E+01 6 6 9.560608E+05 2.858746E+03 - 1.160001E+01 1 1 2.127638E+03 8.898923E+01 - 1.160001E+01 1 5 -1.080628E+04 4.487243E+02 - 1.160001E+01 2 2 2.452972E+03 1.168008E+02 - 1.160001E+01 2 4 1.534493E+04 4.597283E+02 - 1.160001E+01 3 3 2.093933E+03 1.109317E+02 - 1.160001E+01 4 2 1.536379E+04 4.614388E+02 - 1.160001E+01 4 4 2.742490E+05 1.816965E+03 - 1.160001E+01 5 1 -1.082768E+04 4.448535E+02 - 1.160001E+01 5 5 8.259459E+05 2.243294E+03 - 1.160001E+01 6 6 9.549045E+05 2.682162E+03 - 1.170001E+01 1 1 2.126100E+03 8.633121E+01 - 1.170001E+01 1 5 -1.078880E+04 4.442795E+02 - 1.170001E+01 2 2 2.450047E+03 1.128212E+02 - 1.170001E+01 2 4 1.533011E+04 4.426050E+02 - 1.170001E+01 3 3 2.095180E+03 1.132257E+02 - 1.170001E+01 4 2 1.534890E+04 4.442519E+02 - 1.170001E+01 4 4 2.741736E+05 1.743508E+03 - 1.170001E+01 5 1 -1.081031E+04 4.405491E+02 - 1.170001E+01 5 5 8.259912E+05 2.267439E+03 - 1.170001E+01 6 6 9.537879E+05 2.518749E+03 - 1.180001E+01 1 1 2.124550E+03 8.377260E+01 - 1.180001E+01 1 5 -1.077201E+04 4.396074E+02 - 1.180001E+01 2 2 2.447151E+03 1.090218E+02 - 1.180001E+01 2 4 1.531550E+04 4.263197E+02 - 1.180001E+01 3 3 2.096469E+03 1.154567E+02 - 1.180001E+01 4 2 1.533431E+04 4.279048E+02 - 1.180001E+01 4 4 2.740985E+05 1.673901E+03 - 1.180001E+01 5 1 -1.079330E+04 4.360281E+02 - 1.180001E+01 5 5 8.260214E+05 2.288327E+03 - 1.180001E+01 6 6 9.527109E+05 2.367267E+03 - 1.190001E+01 1 1 2.122995E+03 8.131019E+01 - 1.190001E+01 1 5 -1.075599E+04 4.347395E+02 - 1.190001E+01 2 2 2.444285E+03 1.053936E+02 - 1.190001E+01 2 4 1.530115E+04 4.108290E+02 - 1.190001E+01 3 3 2.097785E+03 1.176215E+02 - 1.190001E+01 4 2 1.531993E+04 4.123534E+02 - 1.190001E+01 4 4 2.740252E+05 1.607962E+03 - 1.190001E+01 5 1 -1.077738E+04 4.312895E+02 - 1.190001E+01 5 5 8.260572E+05 2.306321E+03 - 1.190001E+01 6 6 9.516712E+05 2.226846E+03 - 1.200001E+01 1 1 2.121434E+03 7.894044E+01 - 1.200001E+01 1 5 -1.074063E+04 4.297101E+02 - 1.200001E+01 2 2 2.441449E+03 1.019280E+02 - 1.200001E+01 2 4 1.528709E+04 3.960870E+02 - 1.200001E+01 3 3 2.099118E+03 1.197286E+02 - 1.200001E+01 4 2 1.530580E+04 3.975568E+02 - 1.200001E+01 4 4 2.739543E+05 1.545426E+03 - 1.200001E+01 5 1 -1.076188E+04 4.263846E+02 - 1.200001E+01 5 5 8.260926E+05 2.321299E+03 - 1.200001E+01 6 6 9.506649E+05 2.096431E+03 - 1.210001E+01 1 1 2.119878E+03 7.666012E+01 - 1.210001E+01 1 5 -1.072603E+04 4.245444E+02 - 1.210001E+01 2 2 2.438656E+03 9.861677E+01 - 1.210001E+01 2 4 1.527324E+04 3.820515E+02 - 1.210001E+01 3 3 2.100477E+03 1.217811E+02 - 1.210001E+01 4 2 1.529188E+04 3.834702E+02 - 1.210001E+01 4 4 2.738842E+05 1.486106E+03 - 1.210001E+01 5 1 -1.074728E+04 4.213397E+02 - 1.210001E+01 5 5 8.261277E+05 2.333569E+03 - 1.210001E+01 6 6 9.496948E+05 1.975356E+03 - 1.220001E+01 1 1 2.118321E+03 7.446576E+01 - 1.220001E+01 1 5 -1.071203E+04 4.192750E+02 - 1.220001E+01 2 2 2.435906E+03 9.545207E+01 - 1.220001E+01 2 4 1.525966E+04 3.686877E+02 - 1.220001E+01 3 3 2.101841E+03 1.237651E+02 - 1.220001E+01 4 2 1.527830E+04 3.700542E+02 - 1.220001E+01 4 4 2.738165E+05 1.429824E+03 - 1.220001E+01 5 1 -1.073302E+04 4.161903E+02 - 1.220001E+01 5 5 8.261690E+05 2.343536E+03 - 1.220001E+01 6 6 9.487539E+05 1.862762E+03 - 1.230001E+01 1 1 2.116769E+03 7.235358E+01 - 1.230001E+01 1 5 -1.069859E+04 4.139212E+02 - 1.230001E+01 2 2 2.433190E+03 9.242647E+01 - 1.230001E+01 2 4 1.524637E+04 3.559544E+02 - 1.230001E+01 3 3 2.103232E+03 1.256946E+02 - 1.230001E+01 4 2 1.526485E+04 3.572729E+02 - 1.230001E+01 4 4 2.737493E+05 1.376394E+03 - 1.230001E+01 5 1 -1.071966E+04 4.109430E+02 - 1.230001E+01 5 5 8.261975E+05 2.351000E+03 - 1.230001E+01 6 6 9.478432E+05 1.758019E+03 - 1.240001E+01 1 1 2.115230E+03 7.032137E+01 - 1.240001E+01 1 5 -1.068579E+04 4.085052E+02 - 1.240001E+01 2 2 2.430518E+03 8.953334E+01 - 1.240001E+01 2 4 1.523330E+04 3.438208E+02 - 1.240001E+01 3 3 2.104630E+03 1.275721E+02 - 1.240001E+01 4 2 1.525182E+04 3.450954E+02 - 1.240001E+01 4 4 2.736838E+05 1.325624E+03 - 1.240001E+01 5 1 -1.070680E+04 4.056277E+02 - 1.240001E+01 5 5 8.262332E+05 2.356286E+03 - 1.240001E+01 6 6 9.469648E+05 1.660457E+03 - 1.250001E+01 1 1 2.113698E+03 6.836533E+01 - 1.250001E+01 1 5 -1.067347E+04 4.030426E+02 - 1.250001E+01 2 2 2.427898E+03 8.676517E+01 - 1.250001E+01 2 4 1.522051E+04 3.322523E+02 - 1.250001E+01 3 3 2.106044E+03 1.293969E+02 - 1.250001E+01 4 2 1.523901E+04 3.334811E+02 - 1.250001E+01 4 4 2.736212E+05 1.277405E+03 - 1.250001E+01 5 1 -1.069435E+04 4.002670E+02 - 1.250001E+01 5 5 8.262628E+05 2.359874E+03 - 1.250001E+01 6 6 9.461124E+05 1.569530E+03 - 1.260001E+01 1 1 2.112180E+03 6.648254E+01 - 1.260001E+01 1 5 -1.066185E+04 3.975528E+02 - 1.260001E+01 2 2 2.425312E+03 8.411627E+01 - 1.260001E+01 2 4 1.520798E+04 3.212180E+02 - 1.260001E+01 3 3 2.107452E+03 1.311695E+02 - 1.260001E+01 4 2 1.522640E+04 3.224063E+02 - 1.260001E+01 4 4 2.735586E+05 1.231549E+03 - 1.260001E+01 5 1 -1.068282E+04 3.948681E+02 - 1.260001E+01 5 5 8.263016E+05 2.361182E+03 - 1.260001E+01 6 6 9.452871E+05 1.484709E+03 - 1.270001E+01 1 1 2.110668E+03 6.466995E+01 - 1.270001E+01 1 5 -1.065067E+04 3.920472E+02 - 1.270001E+01 2 2 2.422773E+03 8.158038E+01 - 1.270001E+01 2 4 1.519573E+04 3.106885E+02 - 1.270001E+01 3 3 2.108894E+03 1.328926E+02 - 1.270001E+01 4 2 1.521411E+04 3.118379E+02 - 1.270001E+01 4 4 2.734992E+05 1.187930E+03 - 1.270001E+01 5 1 -1.067151E+04 3.894570E+02 - 1.270001E+01 5 5 8.263347E+05 2.360984E+03 - 1.270001E+01 6 6 9.444876E+05 1.405492E+03 - 1.280001E+01 1 1 2.109177E+03 6.292468E+01 - 1.280001E+01 1 5 -1.063990E+04 3.865463E+02 - 1.280001E+01 2 2 2.420291E+03 7.915163E+01 - 1.280001E+01 2 4 1.518379E+04 3.006381E+02 - 1.280001E+01 3 3 2.110333E+03 1.345651E+02 - 1.280001E+01 4 2 1.520208E+04 3.017477E+02 - 1.280001E+01 4 4 2.734404E+05 1.146440E+03 - 1.280001E+01 5 1 -1.066063E+04 3.840481E+02 - 1.280001E+01 5 5 8.263615E+05 2.359094E+03 - 1.280001E+01 6 6 9.437115E+05 1.331517E+03 - 1.290001E+01 1 1 2.107699E+03 6.124414E+01 - 1.290001E+01 1 5 -1.062966E+04 3.810516E+02 - 1.290001E+01 2 2 2.417847E+03 7.682533E+01 - 1.290001E+01 2 4 1.517203E+04 2.910394E+02 - 1.290001E+01 3 3 2.111769E+03 1.361919E+02 - 1.290001E+01 4 2 1.519037E+04 2.921137E+02 - 1.290001E+01 4 4 2.733828E+05 1.106919E+03 - 1.290001E+01 5 1 -1.065035E+04 3.786324E+02 - 1.290001E+01 5 5 8.263971E+05 2.355927E+03 - 1.290001E+01 6 6 9.429603E+05 1.262324E+03 - 1.300001E+01 1 1 2.106239E+03 5.962539E+01 - 1.300001E+01 1 5 -1.061992E+04 3.755821E+02 - 1.300001E+01 2 2 2.415445E+03 7.459554E+01 - 1.300001E+01 2 4 1.516055E+04 2.818689E+02 - 1.300001E+01 3 3 2.113217E+03 1.377701E+02 - 1.300001E+01 4 2 1.517887E+04 2.829082E+02 - 1.300001E+01 4 4 2.733258E+05 1.069281E+03 - 1.300001E+01 5 1 -1.064062E+04 3.732501E+02 - 1.300001E+01 5 5 8.264338E+05 2.351114E+03 - 1.300001E+01 6 6 9.422327E+05 1.197565E+03 - 1.310001E+01 1 1 2.104794E+03 5.806616E+01 - 1.310001E+01 1 5 -1.061043E+04 3.701445E+02 - 1.310001E+01 2 2 2.413100E+03 7.245785E+01 - 1.310001E+01 2 4 1.514936E+04 2.731026E+02 - 1.310001E+01 3 3 2.114666E+03 1.393071E+02 - 1.310001E+01 4 2 1.516762E+04 2.741091E+02 - 1.310001E+01 4 4 2.732713E+05 1.033417E+03 - 1.310001E+01 5 1 -1.063108E+04 3.678736E+02 - 1.310001E+01 5 5 8.264561E+05 2.345078E+03 - 1.310001E+01 6 6 9.415256E+05 1.136929E+03 - 1.320001E+01 1 1 2.103368E+03 5.656347E+01 - 1.320001E+01 1 5 -1.060147E+04 3.647414E+02 - 1.320001E+01 2 2 2.410791E+03 7.040732E+01 - 1.320001E+01 2 4 1.513839E+04 2.647195E+02 - 1.320001E+01 3 3 2.116120E+03 1.407977E+02 - 1.320001E+01 4 2 1.515654E+04 2.656937E+02 - 1.320001E+01 4 4 2.732178E+05 9.992125E+02 - 1.320001E+01 5 1 -1.062196E+04 3.625555E+02 - 1.320001E+01 5 5 8.264901E+05 2.337926E+03 - 1.320001E+01 6 6 9.408400E+05 1.080085E+03 - 1.330001E+01 1 1 2.101961E+03 5.511522E+01 - 1.330001E+01 1 5 -1.059288E+04 3.593916E+02 - 1.330001E+01 2 2 2.408532E+03 6.844022E+01 - 1.330001E+01 2 4 1.512766E+04 2.567007E+02 - 1.330001E+01 3 3 2.117555E+03 1.422505E+02 - 1.330001E+01 4 2 1.514582E+04 2.576465E+02 - 1.330001E+01 4 4 2.731667E+05 9.666104E+02 - 1.330001E+01 5 1 -1.061341E+04 3.572649E+02 - 1.330001E+01 5 5 8.265143E+05 2.329631E+03 - 1.330001E+01 6 6 9.401749E+05 1.026808E+03 - 1.340001E+01 1 1 2.100570E+03 5.371916E+01 - 1.340001E+01 1 5 -1.058467E+04 3.540811E+02 - 1.340001E+01 2 2 2.406317E+03 6.655184E+01 - 1.340001E+01 2 4 1.511717E+04 2.490257E+02 - 1.340001E+01 3 3 2.119003E+03 1.436666E+02 - 1.340001E+01 4 2 1.513535E+04 2.499415E+02 - 1.340001E+01 4 4 2.731150E+05 9.354659E+02 - 1.340001E+01 5 1 -1.060515E+04 3.520350E+02 - 1.340001E+01 5 5 8.265472E+05 2.320512E+03 - 1.340001E+01 6 6 9.395264E+05 9.767414E+02 - 1.350002E+01 1 1 2.099205E+03 5.237311E+01 - 1.350002E+01 1 5 -1.057670E+04 3.488342E+02 - 1.350002E+01 2 2 2.404147E+03 6.473885E+01 - 1.350002E+01 2 4 1.510695E+04 2.416740E+02 - 1.350002E+01 3 3 2.120441E+03 1.450347E+02 - 1.350002E+01 4 2 1.512504E+04 2.425639E+02 - 1.350002E+01 4 4 2.730665E+05 9.057045E+02 - 1.350002E+01 5 1 -1.059721E+04 3.468398E+02 - 1.350002E+01 5 5 8.265730E+05 2.310202E+03 - 1.350002E+01 6 6 9.388989E+05 9.297352E+02 - 1.360002E+01 1 1 2.097856E+03 5.107493E+01 - 1.360002E+01 1 5 -1.056917E+04 3.436465E+02 - 1.360002E+01 2 2 2.402019E+03 6.299704E+01 - 1.360002E+01 2 4 1.509691E+04 2.346342E+02 - 1.360002E+01 3 3 2.121882E+03 1.463661E+02 - 1.360002E+01 4 2 1.511499E+04 2.354969E+02 - 1.360002E+01 4 4 2.730179E+05 8.773123E+02 - 1.360002E+01 5 1 -1.058957E+04 3.417159E+02 - 1.360002E+01 5 5 8.265993E+05 2.299260E+03 - 1.360002E+01 6 6 9.382879E+05 8.855363E+02 - 1.370002E+01 1 1 2.096529E+03 4.982215E+01 - 1.370002E+01 1 5 -1.056192E+04 3.385222E+02 - 1.370002E+01 2 2 2.399936E+03 6.132322E+01 - 1.370002E+01 2 4 1.508712E+04 2.278861E+02 - 1.370002E+01 3 3 2.123323E+03 1.476655E+02 - 1.370002E+01 4 2 1.510520E+04 2.287258E+02 - 1.370002E+01 4 4 2.729711E+05 8.501495E+02 - 1.370002E+01 5 1 -1.058229E+04 3.366470E+02 - 1.370002E+01 5 5 8.266270E+05 2.287270E+03 - 1.370002E+01 6 6 9.376954E+05 8.439335E+02 - 1.380002E+01 1 1 2.095216E+03 4.861351E+01 - 1.380002E+01 1 5 -1.055499E+04 3.334639E+02 - 1.380002E+01 2 2 2.397894E+03 5.971392E+01 - 1.380002E+01 2 4 1.507760E+04 2.214170E+02 - 1.380002E+01 3 3 2.124749E+03 1.489263E+02 - 1.380002E+01 4 2 1.509560E+04 2.222306E+02 - 1.380002E+01 4 4 2.729254E+05 8.241840E+02 - 1.380002E+01 5 1 -1.057513E+04 3.316495E+02 - 1.380002E+01 5 5 8.266494E+05 2.275118E+03 - 1.380002E+01 6 6 9.371171E+05 8.048163E+02 - 1.390002E+01 1 1 2.093933E+03 4.744718E+01 - 1.390002E+01 1 5 -1.054833E+04 3.284787E+02 - 1.390002E+01 2 2 2.395897E+03 5.816627E+01 - 1.390002E+01 2 4 1.506825E+04 2.152124E+02 - 1.390002E+01 3 3 2.126180E+03 1.501581E+02 - 1.390002E+01 4 2 1.508624E+04 2.160014E+02 - 1.390002E+01 4 4 2.728797E+05 7.993529E+02 - 1.390002E+01 5 1 -1.056856E+04 3.267156E+02 - 1.390002E+01 5 5 8.266769E+05 2.261749E+03 - 1.390002E+01 6 6 9.365554E+05 7.679352E+02 - 1.400002E+01 1 1 2.092667E+03 4.632070E+01 - 1.400002E+01 1 5 -1.054198E+04 3.235636E+02 - 1.400002E+01 2 2 2.393941E+03 5.667736E+01 - 1.400002E+01 2 4 1.505914E+04 2.092574E+02 - 1.400002E+01 3 3 2.127597E+03 1.513539E+02 - 1.400002E+01 4 2 1.507707E+04 2.100287E+02 - 1.400002E+01 4 4 2.728362E+05 7.755717E+02 - 1.400002E+01 5 1 -1.056215E+04 3.218545E+02 - 1.400002E+01 5 5 8.266979E+05 2.248237E+03 - 1.400002E+01 6 6 9.360094E+05 7.331602E+02 - 1.410002E+01 1 1 2.091419E+03 4.523307E+01 - 1.410002E+01 1 5 -1.053582E+04 3.187205E+02 - 1.410002E+01 2 2 2.392023E+03 5.524433E+01 - 1.410002E+01 2 4 1.505023E+04 2.035427E+02 - 1.410002E+01 3 3 2.129027E+03 1.525149E+02 - 1.410002E+01 4 2 1.506817E+04 2.042896E+02 - 1.410002E+01 4 4 2.727942E+05 7.528195E+02 - 1.410002E+01 5 1 -1.055597E+04 3.170571E+02 - 1.410002E+01 5 5 8.267213E+05 2.234132E+03 - 1.410002E+01 6 6 9.354781E+05 7.003802E+02 - 1.420002E+01 1 1 2.090195E+03 4.418240E+01 - 1.420002E+01 1 5 -1.052992E+04 3.139538E+02 - 1.420002E+01 2 2 2.390145E+03 5.386454E+01 - 1.420002E+01 2 4 1.504148E+04 1.980522E+02 - 1.420002E+01 3 3 2.130434E+03 1.536453E+02 - 1.420002E+01 4 2 1.505939E+04 1.987785E+02 - 1.420002E+01 4 4 2.727521E+05 7.310227E+02 - 1.420002E+01 5 1 -1.055006E+04 3.123406E+02 - 1.420002E+01 5 5 8.267371E+05 2.219379E+03 - 1.420002E+01 6 6 9.349612E+05 6.694067E+02 - 1.430002E+01 1 1 2.088986E+03 4.316705E+01 - 1.430002E+01 1 5 -1.052431E+04 3.092633E+02 - 1.430002E+01 2 2 2.388311E+03 5.253564E+01 - 1.430002E+01 2 4 1.503297E+04 1.927776E+02 - 1.430002E+01 3 3 2.131842E+03 1.547496E+02 - 1.430002E+01 4 2 1.505086E+04 1.934848E+02 - 1.430002E+01 4 4 2.727125E+05 7.101144E+02 - 1.430002E+01 5 1 -1.054430E+04 3.076932E+02 - 1.430002E+01 5 5 8.267571E+05 2.204616E+03 - 1.430002E+01 6 6 9.344564E+05 6.401974E+02 - 1.440002E+01 1 1 2.087800E+03 4.218559E+01 - 1.440002E+01 1 5 -1.051887E+04 3.046481E+02 - 1.440002E+01 2 2 2.386503E+03 5.125491E+01 - 1.440002E+01 2 4 1.502466E+04 1.877069E+02 - 1.440002E+01 3 3 2.133250E+03 1.558226E+02 - 1.440002E+01 4 2 1.504250E+04 1.883958E+02 - 1.440002E+01 4 4 2.726728E+05 6.900616E+02 - 1.440002E+01 5 1 -1.053893E+04 3.031208E+02 - 1.440002E+01 5 5 8.267798E+05 2.189091E+03 - 1.440002E+01 6 6 9.339664E+05 6.125146E+02 - 1.450002E+01 1 1 2.086630E+03 4.123684E+01 - 1.450002E+01 1 5 -1.051367E+04 3.001110E+02 - 1.450002E+01 2 2 2.384744E+03 5.002060E+01 - 1.450002E+01 2 4 1.501651E+04 1.828318E+02 - 1.450002E+01 3 3 2.134643E+03 1.568708E+02 - 1.450002E+01 4 2 1.503431E+04 1.835009E+02 - 1.450002E+01 4 4 2.726331E+05 6.708359E+02 - 1.450002E+01 5 1 -1.053365E+04 2.986237E+02 - 1.450002E+01 5 5 8.268024E+05 2.173301E+03 - 1.450002E+01 6 6 9.334872E+05 5.863661E+02 - 1.460002E+01 1 1 2.085483E+03 4.031923E+01 - 1.460002E+01 1 5 -1.050862E+04 2.956489E+02 - 1.460002E+01 2 2 2.383020E+03 4.882990E+01 - 1.460002E+01 2 4 1.500857E+04 1.781401E+02 - 1.460002E+01 3 3 2.136024E+03 1.578860E+02 - 1.460002E+01 4 2 1.502636E+04 1.787920E+02 - 1.460002E+01 4 4 2.725966E+05 6.523698E+02 - 1.460002E+01 5 1 -1.052853E+04 2.942045E+02 - 1.460002E+01 5 5 8.268162E+05 2.157346E+03 - 1.460002E+01 6 6 9.330229E+05 5.616545E+02 - 1.470002E+01 1 1 2.084361E+03 3.943158E+01 - 1.470002E+01 1 5 -1.050388E+04 2.912632E+02 - 1.470002E+01 2 2 2.381325E+03 4.768178E+01 - 1.470002E+01 2 4 1.500078E+04 1.736267E+02 - 1.470002E+01 3 3 2.137404E+03 1.588762E+02 - 1.470002E+01 4 2 1.501855E+04 1.742603E+02 - 1.470002E+01 4 4 2.725603E+05 6.346516E+02 - 1.470002E+01 5 1 -1.052373E+04 2.898618E+02 - 1.470002E+01 5 5 8.268378E+05 2.141207E+03 - 1.470002E+01 6 6 9.325686E+05 5.382223E+02 - 1.480002E+01 1 1 2.083249E+03 3.857278E+01 - 1.480002E+01 1 5 -1.049920E+04 2.869577E+02 - 1.480002E+01 2 2 2.379666E+03 4.657336E+01 - 1.480002E+01 2 4 1.499321E+04 1.692799E+02 - 1.480002E+01 3 3 2.138773E+03 1.598436E+02 - 1.480002E+01 4 2 1.501094E+04 1.698969E+02 - 1.480002E+01 4 4 2.725249E+05 6.176179E+02 - 1.480002E+01 5 1 -1.051915E+04 2.855866E+02 - 1.480002E+01 5 5 8.268512E+05 2.124499E+03 - 1.480002E+01 6 6 9.321253E+05 5.160158E+02 - 1.490002E+01 1 1 2.082164E+03 3.774136E+01 - 1.490002E+01 1 5 -1.049480E+04 2.827262E+02 - 1.490002E+01 2 2 2.378054E+03 4.550396E+01 - 1.490002E+01 2 4 1.498577E+04 1.650944E+02 - 1.490002E+01 3 3 2.140139E+03 1.607877E+02 - 1.490002E+01 4 2 1.500344E+04 1.656964E+02 - 1.490002E+01 4 4 2.724897E+05 6.012692E+02 - 1.490002E+01 5 1 -1.051463E+04 2.813920E+02 - 1.490002E+01 5 5 8.268743E+05 2.108086E+03 - 1.490002E+01 6 6 9.316939E+05 4.950198E+02 - 1.500002E+01 1 1 2.081091E+03 3.693649E+01 - 1.500002E+01 1 5 -1.049057E+04 2.785714E+02 - 1.500002E+01 2 2 2.376464E+03 4.447095E+01 - 1.500002E+01 2 4 1.497853E+04 1.610604E+02 - 1.500002E+01 3 3 2.141480E+03 1.617033E+02 - 1.500002E+01 4 2 1.499619E+04 1.616474E+02 - 1.500002E+01 4 4 2.724553E+05 5.855309E+02 - 1.500002E+01 5 1 -1.051033E+04 2.772770E+02 - 1.500002E+01 5 5 8.268852E+05 2.091138E+03 - 1.500002E+01 6 6 9.312731E+05 4.750409E+02 - 1.510002E+01 1 1 2.080040E+03 3.615698E+01 - 1.510002E+01 1 5 -1.048644E+04 2.744925E+02 - 1.510002E+01 2 2 2.374910E+03 4.347293E+01 - 1.510002E+01 2 4 1.497140E+04 1.571724E+02 - 1.510002E+01 3 3 2.142820E+03 1.626021E+02 - 1.510002E+01 4 2 1.498905E+04 1.577446E+02 - 1.510002E+01 4 4 2.724219E+05 5.703980E+02 - 1.510002E+01 5 1 -1.050612E+04 2.732291E+02 - 1.510002E+01 5 5 8.268959E+05 2.074233E+03 - 1.510002E+01 6 6 9.308612E+05 4.561140E+02 - 1.520002E+01 1 1 2.079005E+03 3.540192E+01 - 1.520002E+01 1 5 -1.048248E+04 2.704842E+02 - 1.520002E+01 2 2 2.373389E+03 4.250876E+01 - 1.520002E+01 2 4 1.496444E+04 1.534227E+02 - 1.520002E+01 3 3 2.144167E+03 1.634731E+02 - 1.520002E+01 4 2 1.498212E+04 1.539825E+02 - 1.520002E+01 4 4 2.723893E+05 5.558321E+02 - 1.520002E+01 5 1 -1.050218E+04 2.692577E+02 - 1.520002E+01 5 5 8.269194E+05 2.057312E+03 - 1.520002E+01 6 6 9.304605E+05 4.380757E+02 - 1.530002E+01 1 1 2.077990E+03 3.467028E+01 - 1.530002E+01 1 5 -1.047869E+04 2.665553E+02 - 1.530002E+01 2 2 2.371897E+03 4.157639E+01 - 1.530002E+01 2 4 1.495767E+04 1.498059E+02 - 1.530002E+01 3 3 2.145491E+03 1.643267E+02 - 1.530002E+01 4 2 1.497529E+04 1.503531E+02 - 1.530002E+01 4 4 2.723578E+05 5.418108E+02 - 1.530002E+01 5 1 -1.049838E+04 2.653550E+02 - 1.530002E+01 5 5 8.269261E+05 2.040102E+03 - 1.530002E+01 6 6 9.300689E+05 4.209901E+02 - 1.540002E+01 1 1 2.076993E+03 3.396120E+01 - 1.540002E+01 1 5 -1.047507E+04 2.626942E+02 - 1.540002E+01 2 2 2.370436E+03 4.067495E+01 - 1.540002E+01 2 4 1.495101E+04 1.463179E+02 - 1.540002E+01 3 3 2.146810E+03 1.651566E+02 - 1.540002E+01 4 2 1.496861E+04 1.468497E+02 - 1.540002E+01 4 4 2.723265E+05 5.283426E+02 - 1.540002E+01 5 1 -1.049469E+04 2.615269E+02 - 1.540002E+01 5 5 8.269438E+05 2.023000E+03 - 1.540002E+01 6 6 9.296864E+05 4.047350E+02 - 1.550002E+01 1 1 2.076013E+03 3.327344E+01 - 1.550002E+01 1 5 -1.047153E+04 2.589065E+02 - 1.550002E+01 2 2 2.369007E+03 3.980273E+01 - 1.550002E+01 2 4 1.494455E+04 1.429486E+02 - 1.550002E+01 3 3 2.148116E+03 1.659677E+02 - 1.550002E+01 4 2 1.496212E+04 1.434692E+02 - 1.550002E+01 4 4 2.722966E+05 5.153308E+02 - 1.550002E+01 5 1 -1.049112E+04 2.577680E+02 - 1.550002E+01 5 5 8.269541E+05 2.005682E+03 - 1.550002E+01 6 6 9.293126E+05 3.892980E+02 - 1.560002E+01 1 1 2.075051E+03 3.260694E+01 - 1.560002E+01 1 5 -1.046815E+04 2.551922E+02 - 1.560002E+01 2 2 2.367606E+03 3.895897E+01 - 1.560002E+01 2 4 1.493817E+04 1.396942E+02 - 1.560002E+01 3 3 2.149407E+03 1.667584E+02 - 1.560002E+01 4 2 1.495576E+04 1.402030E+02 - 1.560002E+01 4 4 2.722664E+05 5.027727E+02 - 1.560002E+01 5 1 -1.048774E+04 2.540764E+02 - 1.560002E+01 5 5 8.269706E+05 1.988470E+03 - 1.560002E+01 6 6 9.289479E+05 3.745744E+02 - 1.570002E+01 1 1 2.074105E+03 3.196018E+01 - 1.570002E+01 1 5 -1.046487E+04 2.515442E+02 - 1.570002E+01 2 2 2.366228E+03 3.814221E+01 - 1.570002E+01 2 4 1.493197E+04 1.365507E+02 - 1.570002E+01 3 3 2.150707E+03 1.675297E+02 - 1.570002E+01 4 2 1.494948E+04 1.370478E+02 - 1.570002E+01 4 4 2.722373E+05 4.906886E+02 - 1.570002E+01 5 1 -1.048435E+04 2.504556E+02 - 1.570002E+01 5 5 8.269825E+05 1.971414E+03 - 1.570002E+01 6 6 9.285927E+05 3.605742E+02 - 1.580002E+01 1 1 2.073177E+03 3.133257E+01 - 1.580002E+01 1 5 -1.046171E+04 2.479682E+02 - 1.580002E+01 2 2 2.364879E+03 3.735137E+01 - 1.580002E+01 2 4 1.492585E+04 1.335133E+02 - 1.580002E+01 3 3 2.151987E+03 1.682820E+02 - 1.580002E+01 4 2 1.494334E+04 1.340023E+02 - 1.580002E+01 4 4 2.722095E+05 4.790283E+02 - 1.580002E+01 5 1 -1.048124E+04 2.469087E+02 - 1.580002E+01 5 5 8.269909E+05 1.953933E+03 - 1.580002E+01 6 6 9.282444E+05 3.471773E+02 - 1.590002E+01 1 1 2.072261E+03 3.072359E+01 - 1.590002E+01 1 5 -1.045869E+04 2.444564E+02 - 1.590002E+01 2 2 2.363563E+03 3.658521E+01 - 1.590002E+01 2 4 1.491990E+04 1.305775E+02 - 1.590002E+01 3 3 2.153257E+03 1.690168E+02 - 1.590002E+01 4 2 1.493744E+04 1.310534E+02 - 1.590002E+01 4 4 2.721814E+05 4.677970E+02 - 1.590002E+01 5 1 -1.047818E+04 2.434140E+02 - 1.590002E+01 5 5 8.270022E+05 1.936942E+03 - 1.590002E+01 6 6 9.279032E+05 3.344916E+02 - 1.600002E+01 1 1 2.071366E+03 3.013219E+01 - 1.600002E+01 1 5 -1.045578E+04 2.410121E+02 - 1.600002E+01 2 2 2.362272E+03 3.584298E+01 - 1.600002E+01 2 4 1.491406E+04 1.277372E+02 - 1.600002E+01 3 3 2.154517E+03 1.697373E+02 - 1.600002E+01 4 2 1.493153E+04 1.282041E+02 - 1.600002E+01 4 4 2.721539E+05 4.569208E+02 - 1.600002E+01 5 1 -1.047521E+04 2.400044E+02 - 1.600002E+01 5 5 8.270164E+05 1.919702E+03 - 1.600002E+01 6 6 9.275708E+05 3.223495E+02 - 1.610003E+01 1 1 2.070484E+03 2.955817E+01 - 1.610003E+01 1 5 -1.045294E+04 2.376343E+02 - 1.610003E+01 2 2 2.361004E+03 3.512328E+01 - 1.610003E+01 2 4 1.490836E+04 1.249913E+02 - 1.610003E+01 3 3 2.155781E+03 1.704411E+02 - 1.610003E+01 4 2 1.492584E+04 1.254452E+02 - 1.610003E+01 4 4 2.721288E+05 4.464518E+02 - 1.610003E+01 5 1 -1.047237E+04 2.366466E+02 - 1.610003E+01 5 5 8.270226E+05 1.902542E+03 - 1.610003E+01 6 6 9.272455E+05 3.107794E+02 - 1.620003E+01 1 1 2.069616E+03 2.900060E+01 - 1.620003E+01 1 5 -1.045020E+04 2.343210E+02 - 1.620003E+01 2 2 2.359761E+03 3.442596E+01 - 1.620003E+01 2 4 1.490279E+04 1.223333E+02 - 1.620003E+01 3 3 2.157026E+03 1.711245E+02 - 1.620003E+01 4 2 1.492020E+04 1.227781E+02 - 1.620003E+01 4 4 2.721026E+05 4.363372E+02 - 1.620003E+01 5 1 -1.046956E+04 2.333506E+02 - 1.620003E+01 5 5 8.270325E+05 1.885493E+03 - 1.620003E+01 6 6 9.269280E+05 2.997424E+02 - 1.630003E+01 1 1 2.068766E+03 2.845874E+01 - 1.630003E+01 1 5 -1.044763E+04 2.310678E+02 - 1.630003E+01 2 2 2.358545E+03 3.374945E+01 - 1.630003E+01 2 4 1.489730E+04 1.197599E+02 - 1.630003E+01 3 3 2.158250E+03 1.717934E+02 - 1.630003E+01 4 2 1.491471E+04 1.201951E+02 - 1.630003E+01 4 4 2.720770E+05 4.265562E+02 - 1.630003E+01 5 1 -1.046698E+04 2.301221E+02 - 1.630003E+01 5 5 8.270442E+05 1.868405E+03 - 1.630003E+01 6 6 9.266187E+05 2.891885E+02 - 1.640003E+01 1 1 2.067928E+03 2.793233E+01 - 1.640003E+01 1 5 -1.044513E+04 2.278778E+02 - 1.640003E+01 2 2 2.357353E+03 3.309323E+01 - 1.640003E+01 2 4 1.489195E+04 1.172682E+02 - 1.640003E+01 3 3 2.159478E+03 1.724470E+02 - 1.640003E+01 4 2 1.490937E+04 1.176936E+02 - 1.640003E+01 4 4 2.720522E+05 4.170867E+02 - 1.640003E+01 5 1 -1.046442E+04 2.269559E+02 - 1.640003E+01 5 5 8.270501E+05 1.851661E+03 - 1.640003E+01 6 6 9.263129E+05 2.791281E+02 - 1.650003E+01 1 1 2.067111E+03 2.742050E+01 - 1.650003E+01 1 5 -1.044264E+04 2.247480E+02 - 1.650003E+01 2 2 2.356185E+03 3.245648E+01 - 1.650003E+01 2 4 1.488669E+04 1.148537E+02 - 1.650003E+01 3 3 2.160696E+03 1.730935E+02 - 1.650003E+01 4 2 1.490406E+04 1.152725E+02 - 1.650003E+01 4 4 2.720282E+05 4.079402E+02 - 1.650003E+01 5 1 -1.046200E+04 2.238463E+02 - 1.650003E+01 5 5 8.270595E+05 1.834824E+03 - 1.650003E+01 6 6 9.260153E+05 2.694910E+02 - 1.660003E+01 1 1 2.066301E+03 2.692302E+01 - 1.660003E+01 1 5 -1.044032E+04 2.216787E+02 - 1.660003E+01 2 2 2.355030E+03 3.183842E+01 - 1.660003E+01 2 4 1.488153E+04 1.125153E+02 - 1.660003E+01 3 3 2.161904E+03 1.737168E+02 - 1.660003E+01 4 2 1.489894E+04 1.129257E+02 - 1.660003E+01 4 4 2.720042E+05 3.991012E+02 - 1.660003E+01 5 1 -1.045955E+04 2.207931E+02 - 1.660003E+01 5 5 8.270729E+05 1.817911E+03 - 1.660003E+01 6 6 9.257228E+05 2.602718E+02 - 1.670003E+01 1 1 2.065512E+03 2.643911E+01 - 1.670003E+01 1 5 -1.043803E+04 2.186671E+02 - 1.670003E+01 2 2 2.353910E+03 3.123835E+01 - 1.670003E+01 2 4 1.487652E+04 1.102490E+02 - 1.670003E+01 3 3 2.163101E+03 1.743276E+02 - 1.670003E+01 4 2 1.489390E+04 1.106499E+02 - 1.670003E+01 4 4 2.719815E+05 3.905549E+02 - 1.670003E+01 5 1 -1.045730E+04 2.178046E+02 - 1.670003E+01 5 5 8.270786E+05 1.801339E+03 - 1.670003E+01 6 6 9.254366E+05 2.514675E+02 - 1.680003E+01 1 1 2.064729E+03 2.596842E+01 - 1.680003E+01 1 5 -1.043582E+04 2.157118E+02 - 1.680003E+01 2 2 2.352802E+03 3.065560E+01 - 1.680003E+01 2 4 1.487159E+04 1.080519E+02 - 1.680003E+01 3 3 2.164293E+03 1.749266E+02 - 1.680003E+01 4 2 1.488892E+04 1.084453E+02 - 1.680003E+01 4 4 2.719588E+05 3.822675E+02 - 1.680003E+01 5 1 -1.045502E+04 2.148672E+02 - 1.680003E+01 5 5 8.270844E+05 1.784897E+03 - 1.680003E+01 6 6 9.251572E+05 2.430606E+02 - 1.690003E+01 1 1 2.063964E+03 2.551030E+01 - 1.690003E+01 1 5 -1.043371E+04 2.128134E+02 - 1.690003E+01 2 2 2.351719E+03 3.008941E+01 - 1.690003E+01 2 4 1.486673E+04 1.059205E+02 - 1.690003E+01 3 3 2.165474E+03 1.755150E+02 - 1.690003E+01 4 2 1.488408E+04 1.063057E+02 - 1.690003E+01 4 4 2.719358E+05 3.742552E+02 - 1.690003E+01 5 1 -1.045286E+04 2.119846E+02 - 1.690003E+01 5 5 8.270939E+05 1.768436E+03 - 1.690003E+01 6 6 9.248847E+05 2.349536E+02 - 1.700003E+01 1 1 2.063209E+03 2.506457E+01 - 1.700003E+01 1 5 -1.043165E+04 2.099697E+02 - 1.700003E+01 2 2 2.350652E+03 2.953933E+01 - 1.700003E+01 2 4 1.486197E+04 1.038516E+02 - 1.700003E+01 3 3 2.166653E+03 1.760840E+02 - 1.700003E+01 4 2 1.487930E+04 1.042311E+02 - 1.700003E+01 4 4 2.719141E+05 3.664562E+02 - 1.700003E+01 5 1 -1.045088E+04 2.091586E+02 - 1.700003E+01 5 5 8.271021E+05 1.752063E+03 - 1.700003E+01 6 6 9.246164E+05 2.272261E+02 - 1.710003E+01 1 1 2.062470E+03 2.463075E+01 - 1.710003E+01 1 5 -1.042968E+04 2.071769E+02 - 1.710003E+01 2 2 2.349615E+03 2.900439E+01 - 1.710003E+01 2 4 1.485737E+04 1.018465E+02 - 1.710003E+01 3 3 2.167818E+03 1.766457E+02 - 1.710003E+01 4 2 1.487468E+04 1.022170E+02 - 1.710003E+01 4 4 2.718934E+05 3.589480E+02 - 1.710003E+01 5 1 -1.044881E+04 2.063858E+02 - 1.710003E+01 5 5 8.271076E+05 1.735944E+03 - 1.710003E+01 6 6 9.243549E+05 2.198451E+02 - 1.720003E+01 1 1 2.061742E+03 2.420838E+01 - 1.720003E+01 1 5 -1.042781E+04 2.044397E+02 - 1.720003E+01 2 2 2.348598E+03 2.848452E+01 - 1.720003E+01 2 4 1.485284E+04 9.989874E+01 - 1.720003E+01 3 3 2.168974E+03 1.771941E+02 - 1.720003E+01 4 2 1.487010E+04 1.002615E+02 - 1.720003E+01 4 4 2.718733E+05 3.516508E+02 - 1.720003E+01 5 1 -1.044685E+04 2.036589E+02 - 1.720003E+01 5 5 8.271099E+05 1.719808E+03 - 1.720003E+01 6 6 9.240961E+05 2.127342E+02 - 1.730003E+01 1 1 2.061026E+03 2.379716E+01 - 1.730003E+01 1 5 -1.042594E+04 2.017511E+02 - 1.730003E+01 2 2 2.347590E+03 2.797889E+01 - 1.730003E+01 2 4 1.484834E+04 9.800805E+01 - 1.730003E+01 3 3 2.170129E+03 1.777283E+02 - 1.730003E+01 4 2 1.486565E+04 9.836308E+01 - 1.730003E+01 4 4 2.718520E+05 3.445775E+02 - 1.730003E+01 5 1 -1.044493E+04 2.009904E+02 - 1.730003E+01 5 5 8.271202E+05 1.704027E+03 - 1.730003E+01 6 6 9.238454E+05 2.059225E+02 - 1.740003E+01 1 1 2.060324E+03 2.339627E+01 - 1.740003E+01 1 5 -1.042415E+04 1.991144E+02 - 1.740003E+01 2 2 2.346608E+03 2.748712E+01 - 1.740003E+01 2 4 1.484396E+04 9.617191E+01 - 1.740003E+01 3 3 2.171259E+03 1.782491E+02 - 1.740003E+01 4 2 1.486128E+04 9.652121E+01 - 1.740003E+01 4 4 2.718323E+05 3.377369E+02 - 1.740003E+01 5 1 -1.044318E+04 1.983685E+02 - 1.740003E+01 5 5 8.271267E+05 1.688139E+03 - 1.740003E+01 6 6 9.235982E+05 1.994094E+02 - 1.750003E+01 1 1 2.059634E+03 2.300596E+01 - 1.750003E+01 1 5 -1.042243E+04 1.965280E+02 - 1.750003E+01 2 2 2.345637E+03 2.700851E+01 - 1.750003E+01 2 4 1.483970E+04 9.438749E+01 - 1.750003E+01 3 3 2.172393E+03 1.787659E+02 - 1.750003E+01 4 2 1.485691E+04 9.473090E+01 - 1.750003E+01 4 4 2.718115E+05 3.310837E+02 - 1.750003E+01 5 1 -1.044150E+04 1.957994E+02 - 1.750003E+01 5 5 8.271300E+05 1.672497E+03 - 1.750003E+01 6 6 9.233557E+05 1.931149E+02 - 1.760003E+01 1 1 2.058954E+03 2.262552E+01 - 1.760003E+01 1 5 -1.042073E+04 1.939864E+02 - 1.760003E+01 2 2 2.344687E+03 2.654274E+01 - 1.760003E+01 2 4 1.483547E+04 9.265537E+01 - 1.760003E+01 3 3 2.173507E+03 1.792697E+02 - 1.760003E+01 4 2 1.485272E+04 9.298941E+01 - 1.760003E+01 4 4 2.717932E+05 3.246413E+02 - 1.760003E+01 5 1 -1.043976E+04 1.932696E+02 - 1.760003E+01 5 5 8.271320E+05 1.657040E+03 - 1.760003E+01 6 6 9.231200E+05 1.871032E+02 - 1.770003E+01 1 1 2.058286E+03 2.225474E+01 - 1.770003E+01 1 5 -1.041911E+04 1.914942E+02 - 1.770003E+01 2 2 2.343760E+03 2.608939E+01 - 1.770003E+01 2 4 1.483137E+04 9.096959E+01 - 1.770003E+01 3 3 2.174629E+03 1.797623E+02 - 1.770003E+01 4 2 1.484857E+04 9.129957E+01 - 1.770003E+01 4 4 2.717740E+05 3.183698E+02 - 1.770003E+01 5 1 -1.043807E+04 1.907895E+02 - 1.770003E+01 5 5 8.271378E+05 1.641710E+03 - 1.770003E+01 6 6 9.228866E+05 1.813262E+02 - 1.780003E+01 1 1 2.057630E+03 2.189306E+01 - 1.780003E+01 1 5 -1.041756E+04 1.890476E+02 - 1.780003E+01 2 2 2.342843E+03 2.564802E+01 - 1.780003E+01 2 4 1.482732E+04 8.933209E+01 - 1.780003E+01 3 3 2.175732E+03 1.802451E+02 - 1.780003E+01 4 2 1.484451E+04 8.965611E+01 - 1.780003E+01 4 4 2.717548E+05 3.123017E+02 - 1.780003E+01 5 1 -1.043651E+04 1.883601E+02 - 1.780003E+01 5 5 8.271411E+05 1.626481E+03 - 1.780003E+01 6 6 9.226586E+05 1.758039E+02 - 1.790003E+01 1 1 2.056979E+03 2.154061E+01 - 1.790003E+01 1 5 -1.041605E+04 1.866453E+02 - 1.790003E+01 2 2 2.341945E+03 2.521803E+01 - 1.790003E+01 2 4 1.482331E+04 8.773805E+01 - 1.790003E+01 3 3 2.176833E+03 1.807188E+02 - 1.790003E+01 4 2 1.484051E+04 8.805619E+01 - 1.790003E+01 4 4 2.717376E+05 3.063807E+02 - 1.790003E+01 5 1 -1.043498E+04 1.859703E+02 - 1.790003E+01 5 5 8.271443E+05 1.611391E+03 - 1.790003E+01 6 6 9.224355E+05 1.704742E+02 - 1.800003E+01 1 1 2.056345E+03 2.119668E+01 - 1.800003E+01 1 5 -1.041461E+04 1.842881E+02 - 1.800003E+01 2 2 2.341061E+03 2.479934E+01 - 1.800003E+01 2 4 1.481941E+04 8.618948E+01 - 1.800003E+01 3 3 2.177930E+03 1.811826E+02 - 1.800003E+01 4 2 1.483661E+04 8.650233E+01 - 1.800003E+01 4 4 2.717198E+05 3.006520E+02 - 1.800003E+01 5 1 -1.043344E+04 1.836254E+02 - 1.800003E+01 5 5 8.271499E+05 1.596410E+03 - 1.800003E+01 6 6 9.222149E+05 1.653296E+02 - 1.810003E+01 1 1 2.055720E+03 2.086128E+01 - 1.810003E+01 1 5 -1.041317E+04 1.819731E+02 - 1.810003E+01 2 2 2.340197E+03 2.439112E+01 - 1.810003E+01 2 4 1.481561E+04 8.468084E+01 - 1.810003E+01 3 3 2.179028E+03 1.816369E+02 - 1.810003E+01 4 2 1.483279E+04 8.498753E+01 - 1.810003E+01 4 4 2.717028E+05 2.950850E+02 - 1.810003E+01 5 1 -1.043208E+04 1.813213E+02 - 1.810003E+01 5 5 8.271562E+05 1.581557E+03 - 1.810003E+01 6 6 9.220011E+05 1.603738E+02 - 1.820003E+01 1 1 2.055104E+03 2.053393E+01 - 1.820003E+01 1 5 -1.041181E+04 1.796993E+02 - 1.820003E+01 2 2 2.339348E+03 2.399349E+01 - 1.820003E+01 2 4 1.481184E+04 8.321352E+01 - 1.820003E+01 3 3 2.180094E+03 1.820844E+02 - 1.820003E+01 4 2 1.482906E+04 8.351611E+01 - 1.820003E+01 4 4 2.716851E+05 2.896564E+02 - 1.820003E+01 5 1 -1.043072E+04 1.790640E+02 - 1.820003E+01 5 5 8.271657E+05 1.567039E+03 - 1.820003E+01 6 6 9.217888E+05 1.556339E+02 - 1.830003E+01 1 1 2.054502E+03 2.021455E+01 - 1.830003E+01 1 5 -1.041048E+04 1.774697E+02 - 1.830003E+01 2 2 2.338513E+03 2.360573E+01 - 1.830003E+01 2 4 1.480814E+04 8.178493E+01 - 1.830003E+01 3 3 2.181152E+03 1.825197E+02 - 1.830003E+01 4 2 1.482531E+04 8.208099E+01 - 1.830003E+01 4 4 2.716680E+05 2.844013E+02 - 1.830003E+01 5 1 -1.042929E+04 1.768469E+02 - 1.830003E+01 5 5 8.271634E+05 1.552448E+03 - 1.830003E+01 6 6 9.215821E+05 1.510820E+02 - 1.840003E+01 1 1 2.053909E+03 1.990290E+01 - 1.840003E+01 1 5 -1.040918E+04 1.752774E+02 - 1.840003E+01 2 2 2.337692E+03 2.322764E+01 - 1.840003E+01 2 4 1.480456E+04 8.039359E+01 - 1.840003E+01 3 3 2.182225E+03 1.829501E+02 - 1.840003E+01 4 2 1.482169E+04 8.068610E+01 - 1.840003E+01 4 4 2.716522E+05 2.792823E+02 - 1.840003E+01 5 1 -1.042802E+04 1.746610E+02 - 1.840003E+01 5 5 8.271635E+05 1.538224E+03 - 1.840003E+01 6 6 9.213790E+05 1.466810E+02 - 1.850003E+01 1 1 2.053320E+03 1.959850E+01 - 1.850003E+01 1 5 -1.040793E+04 1.731259E+02 - 1.850003E+01 2 2 2.336886E+03 2.285887E+01 - 1.850003E+01 2 4 1.480099E+04 7.903979E+01 - 1.850003E+01 3 3 2.183267E+03 1.833716E+02 - 1.850003E+01 4 2 1.481814E+04 7.932382E+01 - 1.850003E+01 4 4 2.716357E+05 2.743032E+02 - 1.850003E+01 5 1 -1.042672E+04 1.725223E+02 - 1.850003E+01 5 5 8.271721E+05 1.523950E+03 - 1.850003E+01 6 6 9.211794E+05 1.424494E+02 - 1.860003E+01 1 1 2.052746E+03 1.930129E+01 - 1.860003E+01 1 5 -1.040671E+04 1.710121E+02 - 1.860003E+01 2 2 2.336096E+03 2.249916E+01 - 1.860003E+01 2 4 1.479749E+04 7.771886E+01 - 1.860003E+01 3 3 2.184322E+03 1.837843E+02 - 1.860003E+01 4 2 1.481466E+04 7.800043E+01 - 1.860003E+01 4 4 2.716191E+05 2.694428E+02 - 1.860003E+01 5 1 -1.042551E+04 1.704225E+02 - 1.860003E+01 5 5 8.271738E+05 1.509914E+03 - 1.860003E+01 6 6 9.209849E+05 1.383857E+02 - 1.870004E+01 1 1 2.052183E+03 1.901094E+01 - 1.870004E+01 1 5 -1.040557E+04 1.689366E+02 - 1.870004E+01 2 2 2.335311E+03 2.214833E+01 - 1.870004E+01 2 4 1.479409E+04 7.643378E+01 - 1.870004E+01 3 3 2.185352E+03 1.841807E+02 - 1.870004E+01 4 2 1.481118E+04 7.670943E+01 - 1.870004E+01 4 4 2.716044E+05 2.647291E+02 - 1.870004E+01 5 1 -1.042427E+04 1.683552E+02 - 1.870004E+01 5 5 8.271734E+05 1.495996E+03 - 1.870004E+01 6 6 9.207909E+05 1.344660E+02 - 1.880004E+01 1 1 2.051628E+03 1.872726E+01 - 1.880004E+01 1 5 -1.040444E+04 1.668994E+02 - 1.880004E+01 2 2 2.334550E+03 2.180602E+01 - 1.880004E+01 2 4 1.479072E+04 7.518122E+01 - 1.880004E+01 3 3 2.186382E+03 1.845765E+02 - 1.880004E+01 4 2 1.480782E+04 7.545424E+01 - 1.880004E+01 4 4 2.715896E+05 2.601515E+02 - 1.880004E+01 5 1 -1.042326E+04 1.663279E+02 - 1.880004E+01 5 5 8.271764E+05 1.482188E+03 - 1.880004E+01 6 6 9.206021E+05 1.306727E+02 - 1.890004E+01 1 1 2.051073E+03 1.845038E+01 - 1.890004E+01 1 5 -1.040334E+04 1.648945E+02 - 1.890004E+01 2 2 2.333793E+03 2.147164E+01 - 1.890004E+01 2 4 1.478741E+04 7.396050E+01 - 1.890004E+01 3 3 2.187406E+03 1.849668E+02 - 1.890004E+01 4 2 1.480450E+04 7.422672E+01 - 1.890004E+01 4 4 2.715736E+05 2.557082E+02 - 1.890004E+01 5 1 -1.042207E+04 1.643343E+02 - 1.890004E+01 5 5 8.271801E+05 1.468711E+03 - 1.890004E+01 6 6 9.204173E+05 1.270228E+02 - 1.900004E+01 1 1 2.050531E+03 1.817950E+01 - 1.900004E+01 1 5 -1.040224E+04 1.629282E+02 - 1.900004E+01 2 2 2.333057E+03 2.114543E+01 - 1.900004E+01 2 4 1.478419E+04 7.276846E+01 - 1.900004E+01 3 3 2.188413E+03 1.853446E+02 - 1.900004E+01 4 2 1.480126E+04 7.303304E+01 - 1.900004E+01 4 4 2.715604E+05 2.513305E+02 - 1.900004E+01 5 1 -1.042097E+04 1.623760E+02 - 1.900004E+01 5 5 8.271833E+05 1.455291E+03 - 1.900004E+01 6 6 9.202351E+05 1.234795E+02 - 1.910004E+01 1 1 2.050006E+03 1.791492E+01 - 1.910004E+01 1 5 -1.040121E+04 1.609936E+02 - 1.910004E+01 2 2 2.332327E+03 2.082673E+01 - 1.910004E+01 2 4 1.478098E+04 7.160725E+01 - 1.910004E+01 3 3 2.189432E+03 1.857226E+02 - 1.910004E+01 4 2 1.479808E+04 7.186718E+01 - 1.910004E+01 4 4 2.715451E+05 2.471007E+02 - 1.910004E+01 5 1 -1.041999E+04 1.604564E+02 - 1.910004E+01 5 5 8.271872E+05 1.441932E+03 - 1.910004E+01 6 6 9.200559E+05 1.201205E+02 - 1.920004E+01 1 1 2.049483E+03 1.765621E+01 - 1.920004E+01 1 5 -1.040026E+04 1.590964E+02 - 1.920004E+01 2 2 2.331615E+03 2.051542E+01 - 1.920004E+01 2 4 1.477788E+04 7.047442E+01 - 1.920004E+01 3 3 2.190425E+03 1.860850E+02 - 1.920004E+01 4 2 1.479489E+04 7.072854E+01 - 1.920004E+01 4 4 2.715305E+05 2.429766E+02 - 1.920004E+01 5 1 -1.041893E+04 1.585637E+02 - 1.920004E+01 5 5 8.271846E+05 1.428767E+03 - 1.920004E+01 6 6 9.198796E+05 1.168207E+02 - 1.930004E+01 1 1 2.048965E+03 1.740320E+01 - 1.930004E+01 1 5 -1.039924E+04 1.572290E+02 - 1.930004E+01 2 2 2.330912E+03 2.021156E+01 - 1.930004E+01 2 4 1.477479E+04 6.936960E+01 - 1.930004E+01 3 3 2.191418E+03 1.864453E+02 - 1.930004E+01 4 2 1.479185E+04 6.962022E+01 - 1.930004E+01 4 4 2.715169E+05 2.389581E+02 - 1.930004E+01 5 1 -1.041793E+04 1.567098E+02 - 1.930004E+01 5 5 8.271876E+05 1.415792E+03 - 1.930004E+01 6 6 9.197066E+05 1.136690E+02 - 1.940004E+01 1 1 2.048461E+03 1.715591E+01 - 1.940004E+01 1 5 -1.039833E+04 1.553941E+02 - 1.940004E+01 2 2 2.330222E+03 1.991453E+01 - 1.940004E+01 2 4 1.477176E+04 6.829047E+01 - 1.940004E+01 3 3 2.192412E+03 1.867998E+02 - 1.940004E+01 4 2 1.478880E+04 6.853768E+01 - 1.940004E+01 4 4 2.715025E+05 2.350184E+02 - 1.940004E+01 5 1 -1.041693E+04 1.548798E+02 - 1.940004E+01 5 5 8.271892E+05 1.402910E+03 - 1.940004E+01 6 6 9.195372E+05 1.106253E+02 - 1.950004E+01 1 1 2.047965E+03 1.691395E+01 - 1.950004E+01 1 5 -1.039738E+04 1.535927E+02 - 1.950004E+01 2 2 2.329543E+03 1.962435E+01 - 1.950004E+01 2 4 1.476878E+04 6.723826E+01 - 1.950004E+01 3 3 2.193378E+03 1.871498E+02 - 1.950004E+01 4 2 1.478586E+04 6.748221E+01 - 1.950004E+01 4 4 2.714897E+05 2.312206E+02 - 1.950004E+01 5 1 -1.041604E+04 1.530889E+02 - 1.950004E+01 5 5 8.271920E+05 1.390185E+03 - 1.950004E+01 6 6 9.193708E+05 1.076600E+02 - 1.960004E+01 1 1 2.047471E+03 1.667731E+01 - 1.960004E+01 1 5 -1.039650E+04 1.518212E+02 - 1.960004E+01 2 2 2.328873E+03 1.934076E+01 - 1.960004E+01 2 4 1.476587E+04 6.621005E+01 - 1.960004E+01 3 3 2.194353E+03 1.874906E+02 - 1.960004E+01 4 2 1.478289E+04 6.645112E+01 - 1.960004E+01 4 4 2.714757E+05 2.274843E+02 - 1.960004E+01 5 1 -1.041511E+04 1.513279E+02 - 1.960004E+01 5 5 8.271972E+05 1.377511E+03 - 1.960004E+01 6 6 9.192068E+05 1.048207E+02 - 1.970004E+01 1 1 2.046986E+03 1.644575E+01 - 1.970004E+01 1 5 -1.039560E+04 1.500790E+02 - 1.970004E+01 2 2 2.328215E+03 1.906352E+01 - 1.970004E+01 2 4 1.476300E+04 6.520600E+01 - 1.970004E+01 3 3 2.195329E+03 1.878243E+02 - 1.970004E+01 4 2 1.477999E+04 6.544521E+01 - 1.970004E+01 4 4 2.714634E+05 2.238466E+02 - 1.970004E+01 5 1 -1.041429E+04 1.495925E+02 - 1.970004E+01 5 5 8.271948E+05 1.365125E+03 - 1.970004E+01 6 6 9.190450E+05 1.020527E+02 - 1.980004E+01 1 1 2.046512E+03 1.621911E+01 - 1.980004E+01 1 5 -1.039480E+04 1.483693E+02 - 1.980004E+01 2 2 2.327573E+03 1.879211E+01 - 1.980004E+01 2 4 1.476018E+04 6.422812E+01 - 1.980004E+01 3 3 2.196280E+03 1.881516E+02 - 1.980004E+01 4 2 1.477718E+04 6.445956E+01 - 1.980004E+01 4 4 2.714500E+05 2.203193E+02 - 1.980004E+01 5 1 -1.041339E+04 1.478867E+02 - 1.980004E+01 5 5 8.271914E+05 1.352687E+03 - 1.980004E+01 6 6 9.188865E+05 9.938832E+01 - 1.990004E+01 1 1 2.046042E+03 1.599738E+01 - 1.990004E+01 1 5 -1.039398E+04 1.466865E+02 - 1.990004E+01 2 2 2.326934E+03 1.852710E+01 - 1.990004E+01 2 4 1.475738E+04 6.326960E+01 - 1.990004E+01 3 3 2.197233E+03 1.884762E+02 - 1.990004E+01 4 2 1.477441E+04 6.349908E+01 - 1.990004E+01 4 4 2.714381E+05 2.168449E+02 - 1.990004E+01 5 1 -1.041256E+04 1.462119E+02 - 1.990004E+01 5 5 8.271924E+05 1.340653E+03 - 1.990004E+01 6 6 9.187299E+05 9.683757E+01 - 2.000004E+01 1 1 2.045585E+03 1.578026E+01 - 2.000004E+01 1 5 -1.039323E+04 1.450318E+02 - 2.000004E+01 2 2 2.326304E+03 1.826778E+01 - 2.000004E+01 2 4 1.475468E+04 6.233554E+01 - 2.000004E+01 3 3 2.198189E+03 1.887917E+02 - 2.000004E+01 4 2 1.477165E+04 6.256093E+01 - 2.000004E+01 4 4 2.714253E+05 2.135000E+02 - 2.000004E+01 5 1 -1.041179E+04 1.445639E+02 - 2.000004E+01 5 5 8.271966E+05 1.328640E+03 - 2.000004E+01 6 6 9.185784E+05 9.434976E+01 - 2.010004E+01 1 1 2.045125E+03 1.556776E+01 - 2.010004E+01 1 5 -1.039244E+04 1.434056E+02 - 2.010004E+01 2 2 2.325691E+03 1.801404E+01 - 2.010004E+01 2 4 1.475198E+04 6.142097E+01 - 2.010004E+01 3 3 2.199134E+03 1.891055E+02 - 2.010004E+01 4 2 1.476897E+04 6.164350E+01 - 2.010004E+01 4 4 2.714142E+05 2.101818E+02 - 2.010004E+01 5 1 -1.041102E+04 1.429480E+02 - 2.010004E+01 5 5 8.271989E+05 1.316722E+03 - 2.010004E+01 6 6 9.184271E+05 9.191343E+01 - 2.020004E+01 1 1 2.044676E+03 1.535972E+01 - 2.020004E+01 1 5 -1.039172E+04 1.418049E+02 - 2.020004E+01 2 2 2.325084E+03 1.776595E+01 - 2.020004E+01 2 4 1.474935E+04 6.052758E+01 - 2.020004E+01 3 3 2.200063E+03 1.894135E+02 - 2.020004E+01 4 2 1.476634E+04 6.074775E+01 - 2.020004E+01 4 4 2.714013E+05 2.069709E+02 - 2.020004E+01 5 1 -1.041023E+04 1.413513E+02 - 2.020004E+01 5 5 8.272012E+05 1.305076E+03 - 2.020004E+01 6 6 9.182805E+05 8.961385E+01 - 2.030004E+01 1 1 2.044239E+03 1.515596E+01 - 2.030004E+01 1 5 -1.039100E+04 1.402321E+02 - 2.030004E+01 2 2 2.324486E+03 1.752291E+01 - 2.030004E+01 2 4 1.474676E+04 5.965457E+01 - 2.030004E+01 3 3 2.200991E+03 1.897112E+02 - 2.030004E+01 4 2 1.476376E+04 5.987170E+01 - 2.030004E+01 4 4 2.713893E+05 2.038347E+02 - 2.030004E+01 5 1 -1.040953E+04 1.397888E+02 - 2.030004E+01 5 5 8.272011E+05 1.293445E+03 - 2.030004E+01 6 6 9.181336E+05 8.735389E+01 - 2.040004E+01 1 1 2.043802E+03 1.495623E+01 - 2.040004E+01 1 5 -1.039028E+04 1.386837E+02 - 2.040004E+01 2 2 2.323908E+03 1.728514E+01 - 2.040004E+01 2 4 1.474422E+04 5.880129E+01 - 2.040004E+01 3 3 2.201927E+03 1.900100E+02 - 2.040004E+01 4 2 1.476116E+04 5.901313E+01 - 2.040004E+01 4 4 2.713787E+05 2.007744E+02 - 2.040004E+01 5 1 -1.040880E+04 1.382498E+02 - 2.040004E+01 5 5 8.271992E+05 1.281930E+03 - 2.040004E+01 6 6 9.179906E+05 8.516948E+01 - 2.050004E+01 1 1 2.043376E+03 1.476065E+01 - 2.050004E+01 1 5 -1.038959E+04 1.371617E+02 - 2.050004E+01 2 2 2.323322E+03 1.705247E+01 - 2.050004E+01 2 4 1.474168E+04 5.796666E+01 - 2.050004E+01 3 3 2.202838E+03 1.902937E+02 - 2.050004E+01 4 2 1.475862E+04 5.817687E+01 - 2.050004E+01 4 4 2.713673E+05 1.977805E+02 - 2.050004E+01 5 1 -1.040812E+04 1.367334E+02 - 2.050004E+01 5 5 8.271939E+05 1.270525E+03 - 2.050004E+01 6 6 9.178493E+05 8.307088E+01 - 2.060004E+01 1 1 2.042954E+03 1.456914E+01 - 2.060004E+01 1 5 -1.038892E+04 1.356651E+02 - 2.060004E+01 2 2 2.322754E+03 1.682451E+01 - 2.060004E+01 2 4 1.473921E+04 5.715059E+01 - 2.060004E+01 3 3 2.203731E+03 1.905823E+02 - 2.060004E+01 4 2 1.475616E+04 5.735726E+01 - 2.060004E+01 4 4 2.713563E+05 1.948603E+02 - 2.060004E+01 5 1 -1.040740E+04 1.352437E+02 - 2.060004E+01 5 5 8.271967E+05 1.259360E+03 - 2.060004E+01 6 6 9.177097E+05 8.102791E+01 - 2.070004E+01 1 1 2.042534E+03 1.438127E+01 - 2.070004E+01 1 5 -1.038830E+04 1.341935E+02 - 2.070004E+01 2 2 2.322198E+03 1.660144E+01 - 2.070004E+01 2 4 1.473680E+04 5.635143E+01 - 2.070004E+01 3 3 2.204645E+03 1.908608E+02 - 2.070004E+01 4 2 1.475372E+04 5.655698E+01 - 2.070004E+01 4 4 2.713456E+05 1.919953E+02 - 2.070004E+01 5 1 -1.040679E+04 1.337789E+02 - 2.070004E+01 5 5 8.271989E+05 1.248252E+03 - 2.070004E+01 6 6 9.175752E+05 7.903664E+01 - 2.080004E+01 1 1 2.042128E+03 1.419732E+01 - 2.080004E+01 1 5 -1.038767E+04 1.327458E+02 - 2.080004E+01 2 2 2.321642E+03 1.638292E+01 - 2.080004E+01 2 4 1.473439E+04 5.556999E+01 - 2.080004E+01 3 3 2.205545E+03 1.911388E+02 - 2.080004E+01 4 2 1.475132E+04 5.577240E+01 - 2.080004E+01 4 4 2.713351E+05 1.891891E+02 - 2.080004E+01 5 1 -1.040618E+04 1.323369E+02 - 2.080004E+01 5 5 8.272017E+05 1.237373E+03 - 2.080004E+01 6 6 9.174412E+05 7.712577E+01 - 2.090004E+01 1 1 2.041725E+03 1.401705E+01 - 2.090004E+01 1 5 -1.038704E+04 1.313200E+02 - 2.090004E+01 2 2 2.321099E+03 1.616871E+01 - 2.090004E+01 2 4 1.473205E+04 5.480648E+01 - 2.090004E+01 3 3 2.206437E+03 1.914103E+02 - 2.090004E+01 4 2 1.474894E+04 5.500297E+01 - 2.090004E+01 4 4 2.713241E+05 1.864643E+02 - 2.090004E+01 5 1 -1.040560E+04 1.309183E+02 - 2.090004E+01 5 5 8.272052E+05 1.226451E+03 - 2.090004E+01 6 6 9.173101E+05 7.527367E+01 - 2.100004E+01 1 1 2.041327E+03 1.384010E+01 - 2.100004E+01 1 5 -1.038649E+04 1.299190E+02 - 2.100004E+01 2 2 2.320566E+03 1.595914E+01 - 2.100004E+01 2 4 1.472971E+04 5.405708E+01 - 2.100004E+01 3 3 2.207311E+03 1.916773E+02 - 2.100004E+01 4 2 1.474664E+04 5.425408E+01 - 2.100004E+01 4 4 2.713145E+05 1.837754E+02 - 2.100004E+01 5 1 -1.040490E+04 1.295189E+02 - 2.100004E+01 5 5 8.272031E+05 1.215755E+03 - 2.100004E+01 6 6 9.171781E+05 7.347575E+01 - 2.110004E+01 1 1 2.040935E+03 1.366674E+01 - 2.110004E+01 1 5 -1.038594E+04 1.285374E+02 - 2.110004E+01 2 2 2.320041E+03 1.575354E+01 - 2.110004E+01 2 4 1.472747E+04 5.332546E+01 - 2.110004E+01 3 3 2.208215E+03 1.919347E+02 - 2.110004E+01 4 2 1.474433E+04 5.351843E+01 - 2.110004E+01 4 4 2.713036E+05 1.811644E+02 - 2.110004E+01 5 1 -1.040444E+04 1.281440E+02 - 2.110004E+01 5 5 8.272006E+05 1.205271E+03 - 2.110004E+01 6 6 9.170503E+05 7.173104E+01 - 2.120004E+01 1 1 2.040545E+03 1.349668E+01 - 2.120004E+01 1 5 -1.038537E+04 1.271811E+02 - 2.120004E+01 2 2 2.319518E+03 1.555222E+01 - 2.120004E+01 2 4 1.472518E+04 5.260789E+01 - 2.120004E+01 3 3 2.209068E+03 1.921973E+02 - 2.120004E+01 4 2 1.474211E+04 5.279823E+01 - 2.120004E+01 4 4 2.712929E+05 1.785933E+02 - 2.120004E+01 5 1 -1.040375E+04 1.267931E+02 - 2.120004E+01 5 5 8.272009E+05 1.194779E+03 - 2.120004E+01 6 6 9.169239E+05 7.004704E+01 - 2.130005E+01 1 1 2.040163E+03 1.333006E+01 - 2.130005E+01 1 5 -1.038483E+04 1.258438E+02 - 2.130005E+01 2 2 2.319005E+03 1.535498E+01 - 2.130005E+01 2 4 1.472300E+04 5.190788E+01 - 2.130005E+01 3 3 2.209932E+03 1.924512E+02 - 2.130005E+01 4 2 1.473989E+04 5.209476E+01 - 2.130005E+01 4 4 2.712835E+05 1.761176E+02 - 2.130005E+01 5 1 -1.040319E+04 1.254624E+02 - 2.130005E+01 5 5 8.271999E+05 1.184527E+03 - 2.130005E+01 6 6 9.168002E+05 6.840921E+01 - 2.140005E+01 1 1 2.039790E+03 1.316657E+01 - 2.140005E+01 1 5 -1.038429E+04 1.245276E+02 - 2.140005E+01 2 2 2.318509E+03 1.516140E+01 - 2.140005E+01 2 4 1.472081E+04 5.122044E+01 - 2.140005E+01 3 3 2.210812E+03 1.927012E+02 - 2.140005E+01 4 2 1.473769E+04 5.140326E+01 - 2.140005E+01 4 4 2.712734E+05 1.736811E+02 - 2.140005E+01 5 1 -1.040272E+04 1.241534E+02 - 2.140005E+01 5 5 8.271966E+05 1.174315E+03 - 2.140005E+01 6 6 9.166779E+05 6.679897E+01 - 2.150005E+01 1 1 2.039421E+03 1.300604E+01 - 2.150005E+01 1 5 -1.038382E+04 1.232327E+02 - 2.150005E+01 2 2 2.318014E+03 1.497173E+01 - 2.150005E+01 2 4 1.471868E+04 5.054661E+01 - 2.150005E+01 3 3 2.211674E+03 1.929450E+02 - 2.150005E+01 4 2 1.473557E+04 5.072710E+01 - 2.150005E+01 4 4 2.712644E+05 1.712669E+02 - 2.150005E+01 5 1 -1.040220E+04 1.228634E+02 - 2.150005E+01 5 5 8.271976E+05 1.164182E+03 - 2.150005E+01 6 6 9.165571E+05 6.528036E+01 - 2.160005E+01 1 1 2.039057E+03 1.284880E+01 - 2.160005E+01 1 5 -1.038330E+04 1.219590E+02 - 2.160005E+01 2 2 2.317519E+03 1.478582E+01 - 2.160005E+01 2 4 1.471653E+04 4.988591E+01 - 2.160005E+01 3 3 2.212511E+03 1.931867E+02 - 2.160005E+01 4 2 1.473342E+04 5.006529E+01 - 2.160005E+01 4 4 2.712549E+05 1.689041E+02 - 2.160005E+01 5 1 -1.040170E+04 1.215938E+02 - 2.160005E+01 5 5 8.272002E+05 1.154037E+03 - 2.160005E+01 6 6 9.164384E+05 6.376656E+01 - 2.170005E+01 1 1 2.038695E+03 1.269431E+01 - 2.170005E+01 1 5 -1.038282E+04 1.207042E+02 - 2.170005E+01 2 2 2.317043E+03 1.460325E+01 - 2.170005E+01 2 4 1.471450E+04 4.924081E+01 - 2.170005E+01 3 3 2.213365E+03 1.934295E+02 - 2.170005E+01 4 2 1.473132E+04 4.941448E+01 - 2.170005E+01 4 4 2.712455E+05 1.666196E+02 - 2.170005E+01 5 1 -1.040119E+04 1.203417E+02 - 2.170005E+01 5 5 8.271990E+05 1.144272E+03 - 2.170005E+01 6 6 9.163224E+05 6.229789E+01 - 2.180005E+01 1 1 2.038337E+03 1.254278E+01 - 2.180005E+01 1 5 -1.038239E+04 1.194680E+02 - 2.180005E+01 2 2 2.316567E+03 1.442472E+01 - 2.180005E+01 2 4 1.471242E+04 4.860685E+01 - 2.180005E+01 3 3 2.214200E+03 1.936623E+02 - 2.180005E+01 4 2 1.472929E+04 4.878252E+01 - 2.180005E+01 4 4 2.712359E+05 1.643719E+02 - 2.180005E+01 5 1 -1.040068E+04 1.191137E+02 - 2.180005E+01 5 5 8.271991E+05 1.134515E+03 - 2.180005E+01 6 6 9.162071E+05 6.089412E+01 - 2.190005E+01 1 1 2.037989E+03 1.239400E+01 - 2.190005E+01 1 5 -1.038188E+04 1.182522E+02 - 2.190005E+01 2 2 2.316103E+03 1.424912E+01 - 2.190005E+01 2 4 1.471041E+04 4.798604E+01 - 2.190005E+01 3 3 2.215061E+03 1.938943E+02 - 2.190005E+01 4 2 1.472726E+04 4.815831E+01 - 2.190005E+01 4 4 2.712270E+05 1.621767E+02 - 2.190005E+01 5 1 -1.040027E+04 1.179015E+02 - 2.190005E+01 5 5 8.271982E+05 1.124841E+03 - 2.190005E+01 6 6 9.160946E+05 5.951931E+01 - 2.200005E+01 1 1 2.037649E+03 1.224808E+01 - 2.200005E+01 1 5 -1.038147E+04 1.170528E+02 - 2.200005E+01 2 2 2.315639E+03 1.407682E+01 - 2.200005E+01 2 4 1.470844E+04 4.737843E+01 - 2.200005E+01 3 3 2.215873E+03 1.941264E+02 - 2.200005E+01 4 2 1.472529E+04 4.754744E+01 - 2.200005E+01 4 4 2.712183E+05 1.600185E+02 - 2.200005E+01 5 1 -1.039992E+04 1.167101E+02 - 2.200005E+01 5 5 8.271976E+05 1.115430E+03 - 2.200005E+01 6 6 9.159816E+05 5.819202E+01 - 2.210005E+01 1 1 2.037308E+03 1.210470E+01 - 2.210005E+01 1 5 -1.038102E+04 1.158736E+02 - 2.210005E+01 2 2 2.315182E+03 1.390803E+01 - 2.210005E+01 2 4 1.470646E+04 4.678249E+01 - 2.210005E+01 3 3 2.216712E+03 1.943450E+02 - 2.210005E+01 4 2 1.472329E+04 4.695055E+01 - 2.210005E+01 4 4 2.712093E+05 1.579354E+02 - 2.210005E+01 5 1 -1.039939E+04 1.155343E+02 - 2.210005E+01 5 5 8.271957E+05 1.106022E+03 - 2.210005E+01 6 6 9.158721E+05 5.688284E+01 - 2.220005E+01 1 1 2.036969E+03 1.196400E+01 - 2.220005E+01 1 5 -1.038063E+04 1.147114E+02 - 2.220005E+01 2 2 2.314739E+03 1.374230E+01 - 2.220005E+01 2 4 1.470454E+04 4.619685E+01 - 2.220005E+01 3 3 2.217524E+03 1.945665E+02 - 2.220005E+01 4 2 1.472136E+04 4.636358E+01 - 2.220005E+01 4 4 2.712004E+05 1.558597E+02 - 2.220005E+01 5 1 -1.039897E+04 1.143771E+02 - 2.220005E+01 5 5 8.271941E+05 1.096781E+03 - 2.220005E+01 6 6 9.157641E+05 5.563345E+01 - 2.230005E+01 1 1 2.036637E+03 1.182575E+01 - 2.230005E+01 1 5 -1.038026E+04 1.135683E+02 - 2.230005E+01 2 2 2.314296E+03 1.357960E+01 - 2.230005E+01 2 4 1.470264E+04 4.562354E+01 - 2.230005E+01 3 3 2.218334E+03 1.947845E+02 - 2.230005E+01 4 2 1.471949E+04 4.578807E+01 - 2.230005E+01 4 4 2.711918E+05 1.538298E+02 - 2.230005E+01 5 1 -1.039849E+04 1.132363E+02 - 2.230005E+01 5 5 8.271973E+05 1.087464E+03 - 2.230005E+01 6 6 9.156574E+05 5.442185E+01 - 2.240005E+01 1 1 2.036311E+03 1.168988E+01 - 2.240005E+01 1 5 -1.037981E+04 1.124409E+02 - 2.240005E+01 2 2 2.313863E+03 1.341987E+01 - 2.240005E+01 2 4 1.470077E+04 4.506102E+01 - 2.240005E+01 3 3 2.219161E+03 1.949962E+02 - 2.240005E+01 4 2 1.471759E+04 4.522205E+01 - 2.240005E+01 4 4 2.711828E+05 1.518387E+02 - 2.240005E+01 5 1 -1.039809E+04 1.121140E+02 - 2.240005E+01 5 5 8.271967E+05 1.078192E+03 - 2.240005E+01 6 6 9.155534E+05 5.319827E+01 - 2.250005E+01 1 1 2.035988E+03 1.155664E+01 - 2.250005E+01 1 5 -1.037943E+04 1.113303E+02 - 2.250005E+01 2 2 2.313435E+03 1.326312E+01 - 2.250005E+01 2 4 1.469893E+04 4.451097E+01 - 2.250005E+01 3 3 2.219965E+03 1.952088E+02 - 2.250005E+01 4 2 1.471570E+04 4.466977E+01 - 2.250005E+01 4 4 2.711756E+05 1.499245E+02 - 2.250005E+01 5 1 -1.039769E+04 1.110101E+02 - 2.250005E+01 5 5 8.271958E+05 1.069337E+03 - 2.250005E+01 6 6 9.154492E+05 5.207079E+01 - 2.260005E+01 1 1 2.035668E+03 1.142559E+01 - 2.260005E+01 1 5 -1.037899E+04 1.102374E+02 - 2.260005E+01 2 2 2.313012E+03 1.310918E+01 - 2.260005E+01 2 4 1.469711E+04 4.396895E+01 - 2.260005E+01 3 3 2.220759E+03 1.954165E+02 - 2.260005E+01 4 2 1.471388E+04 4.412612E+01 - 2.260005E+01 4 4 2.711669E+05 1.480203E+02 - 2.260005E+01 5 1 -1.039733E+04 1.099194E+02 - 2.260005E+01 5 5 8.271949E+05 1.060400E+03 - 2.260005E+01 6 6 9.153475E+05 5.092782E+01 - 2.270005E+01 1 1 2.035357E+03 1.129714E+01 - 2.270005E+01 1 5 -1.037867E+04 1.091581E+02 - 2.270005E+01 2 2 2.312599E+03 1.295820E+01 - 2.270005E+01 2 4 1.469534E+04 4.343785E+01 - 2.270005E+01 3 3 2.221554E+03 1.956181E+02 - 2.270005E+01 4 2 1.471213E+04 4.359325E+01 - 2.270005E+01 4 4 2.711593E+05 1.461311E+02 - 2.270005E+01 5 1 -1.039698E+04 1.088451E+02 - 2.270005E+01 5 5 8.271948E+05 1.051773E+03 - 2.270005E+01 6 6 9.152474E+05 4.985772E+01 - 2.280005E+01 1 1 2.035051E+03 1.117065E+01 - 2.280005E+01 1 5 -1.037832E+04 1.080965E+02 - 2.280005E+01 2 2 2.312185E+03 1.280977E+01 - 2.280005E+01 2 4 1.469355E+04 4.291696E+01 - 2.280005E+01 3 3 2.222362E+03 1.958172E+02 - 2.280005E+01 4 2 1.471033E+04 4.307096E+01 - 2.280005E+01 4 4 2.711515E+05 1.443114E+02 - 2.280005E+01 5 1 -1.039657E+04 1.077888E+02 - 2.280005E+01 5 5 8.271949E+05 1.042962E+03 - 2.280005E+01 6 6 9.151476E+05 4.881584E+01 - 2.290005E+01 1 1 2.034748E+03 1.104653E+01 - 2.290005E+01 1 5 -1.037800E+04 1.070498E+02 - 2.290005E+01 2 2 2.311784E+03 1.266404E+01 - 2.290005E+01 2 4 1.469180E+04 4.240533E+01 - 2.290005E+01 3 3 2.223147E+03 1.960163E+02 - 2.290005E+01 4 2 1.470862E+04 4.255819E+01 - 2.290005E+01 4 4 2.711436E+05 1.425061E+02 - 2.290005E+01 5 1 -1.039627E+04 1.067465E+02 - 2.290005E+01 5 5 8.271956E+05 1.034468E+03 - 2.290005E+01 6 6 9.150489E+05 4.774730E+01 - 2.300005E+01 1 1 2.034443E+03 1.092434E+01 - 2.300005E+01 1 5 -1.037765E+04 1.060190E+02 - 2.300005E+01 2 2 2.311383E+03 1.252069E+01 - 2.300005E+01 2 4 1.469011E+04 4.190488E+01 - 2.300005E+01 3 3 2.223921E+03 1.962105E+02 - 2.300005E+01 4 2 1.470688E+04 4.205219E+01 - 2.300005E+01 4 4 2.711359E+05 1.407608E+02 - 2.300005E+01 5 1 -1.039589E+04 1.057175E+02 - 2.300005E+01 5 5 8.271911E+05 1.025958E+03 - 2.300005E+01 6 6 9.149519E+05 4.675128E+01 - 2.310005E+01 1 1 2.034148E+03 1.080445E+01 - 2.310005E+01 1 5 -1.037733E+04 1.050034E+02 - 2.310005E+01 2 2 2.310981E+03 1.237996E+01 - 2.310005E+01 2 4 1.468841E+04 4.141182E+01 - 2.310005E+01 3 3 2.224703E+03 1.964054E+02 - 2.310005E+01 4 2 1.470514E+04 4.155864E+01 - 2.310005E+01 4 4 2.711282E+05 1.390386E+02 - 2.310005E+01 5 1 -1.039559E+04 1.047043E+02 - 2.310005E+01 5 5 8.271901E+05 1.017580E+03 - 2.310005E+01 6 6 9.148575E+05 4.576733E+01 - 2.320005E+01 1 1 2.033849E+03 1.068652E+01 - 2.320005E+01 1 5 -1.037704E+04 1.040022E+02 - 2.320005E+01 2 2 2.310599E+03 1.224202E+01 - 2.320005E+01 2 4 1.468675E+04 4.092871E+01 - 2.320005E+01 3 3 2.225478E+03 1.965968E+02 - 2.320005E+01 4 2 1.470356E+04 4.107518E+01 - 2.320005E+01 4 4 2.711210E+05 1.373338E+02 - 2.320005E+01 5 1 -1.039518E+04 1.037093E+02 - 2.320005E+01 5 5 8.271895E+05 1.009331E+03 - 2.320005E+01 6 6 9.147649E+05 4.482122E+01 - 2.330005E+01 1 1 2.033559E+03 1.057042E+01 - 2.330005E+01 1 5 -1.037676E+04 1.030166E+02 - 2.330005E+01 2 2 2.310214E+03 1.210602E+01 - 2.330005E+01 2 4 1.468507E+04 4.045424E+01 - 2.330005E+01 3 3 2.226240E+03 1.967788E+02 - 2.330005E+01 4 2 1.470188E+04 4.059764E+01 - 2.330005E+01 4 4 2.711132E+05 1.356642E+02 - 2.330005E+01 5 1 -1.039495E+04 1.027238E+02 - 2.330005E+01 5 5 8.271878E+05 1.001008E+03 - 2.330005E+01 6 6 9.146716E+05 4.388947E+01 - 2.340005E+01 1 1 2.033273E+03 1.045655E+01 - 2.340005E+01 1 5 -1.037643E+04 1.020423E+02 - 2.340005E+01 2 2 2.309837E+03 1.197268E+01 - 2.340005E+01 2 4 1.468345E+04 3.998836E+01 - 2.340005E+01 3 3 2.227008E+03 1.969655E+02 - 2.340005E+01 4 2 1.470022E+04 4.013037E+01 - 2.340005E+01 4 4 2.711061E+05 1.340341E+02 - 2.340005E+01 5 1 -1.039461E+04 1.017547E+02 - 2.340005E+01 5 5 8.271899E+05 9.931252E+02 - 2.340005E+01 6 6 9.145817E+05 4.299681E+01 - 2.350005E+01 1 1 2.032994E+03 1.034446E+01 - 2.350005E+01 1 5 -1.037612E+04 1.010847E+02 - 2.350005E+01 2 2 2.309460E+03 1.184148E+01 - 2.350005E+01 2 4 1.468187E+04 3.953109E+01 - 2.350005E+01 3 3 2.227773E+03 1.971446E+02 - 2.350005E+01 4 2 1.469865E+04 3.967077E+01 - 2.350005E+01 4 4 2.710999E+05 1.324319E+02 - 2.350005E+01 5 1 -1.039433E+04 1.007999E+02 - 2.350005E+01 5 5 8.271886E+05 9.849613E+02 - 2.350005E+01 6 6 9.144915E+05 4.211162E+01 - 2.360005E+01 1 1 2.032715E+03 1.023431E+01 - 2.360005E+01 1 5 -1.037586E+04 1.001379E+02 - 2.360005E+01 2 2 2.309094E+03 1.171263E+01 - 2.360005E+01 2 4 1.468028E+04 3.908125E+01 - 2.360005E+01 3 3 2.228521E+03 1.973266E+02 - 2.360005E+01 4 2 1.469707E+04 3.922056E+01 - 2.360005E+01 4 4 2.710927E+05 1.308755E+02 - 2.360005E+01 5 1 -1.039407E+04 9.985751E+01 - 2.360005E+01 5 5 8.271896E+05 9.771481E+02 - 2.360005E+01 6 6 9.144030E+05 4.124708E+01 - 2.370005E+01 1 1 2.032438E+03 1.012587E+01 - 2.370005E+01 1 5 -1.037555E+04 9.920699E+01 - 2.370005E+01 2 2 2.308731E+03 1.158590E+01 - 2.370005E+01 2 4 1.467874E+04 3.863985E+01 - 2.370005E+01 3 3 2.229279E+03 1.975036E+02 - 2.370005E+01 4 2 1.469549E+04 3.877715E+01 - 2.370005E+01 4 4 2.710864E+05 1.293232E+02 - 2.370005E+01 5 1 -1.039373E+04 9.892930E+01 - 2.370005E+01 5 5 8.271887E+05 9.692566E+02 - 2.370005E+01 6 6 9.143159E+05 4.041645E+01 - 2.380005E+01 1 1 2.032171E+03 1.001928E+01 - 2.380005E+01 1 5 -1.037528E+04 9.828754E+01 - 2.380005E+01 2 2 2.308376E+03 1.146121E+01 - 2.380005E+01 2 4 1.467721E+04 3.820537E+01 - 2.380005E+01 3 3 2.230031E+03 1.976775E+02 - 2.380005E+01 4 2 1.469398E+04 3.834073E+01 - 2.380005E+01 4 4 2.710787E+05 1.278101E+02 - 2.380005E+01 5 1 -1.039351E+04 9.801326E+01 - 2.380005E+01 5 5 8.271858E+05 9.615890E+02 - 2.380005E+01 6 6 9.142285E+05 3.960041E+01 - 2.390005E+01 1 1 2.031903E+03 9.914342E+00 - 2.390005E+01 1 5 -1.037502E+04 9.738152E+01 - 2.390005E+01 2 2 2.308018E+03 1.133885E+01 - 2.390005E+01 2 4 1.467568E+04 3.777906E+01 - 2.390005E+01 3 3 2.230778E+03 1.978476E+02 - 2.390005E+01 4 2 1.469244E+04 3.791449E+01 - 2.390005E+01 4 4 2.710722E+05 1.263223E+02 - 2.390005E+01 5 1 -1.039319E+04 9.711163E+01 - 2.390005E+01 5 5 8.271860E+05 9.539293E+02 - 2.390005E+01 6 6 9.141447E+05 3.882231E+01 - 2.400006E+01 1 1 2.031634E+03 9.811126E+00 - 2.400006E+01 1 5 -1.037478E+04 9.648814E+01 - 2.400006E+01 2 2 2.307672E+03 1.121838E+01 - 2.400006E+01 2 4 1.467422E+04 3.736005E+01 - 2.400006E+01 3 3 2.231508E+03 1.980149E+02 - 2.400006E+01 4 2 1.469097E+04 3.749390E+01 - 2.400006E+01 4 4 2.710653E+05 1.248615E+02 - 2.400006E+01 5 1 -1.039290E+04 9.622011E+01 - 2.400006E+01 5 5 8.271822E+05 9.463295E+02 - 2.400006E+01 6 6 9.140606E+05 3.803633E+01 - 2.410006E+01 1 1 2.031377E+03 9.709634E+00 - 2.410006E+01 1 5 -1.037453E+04 9.560735E+01 - 2.410006E+01 2 2 2.307326E+03 1.109978E+01 - 2.410006E+01 2 4 1.467273E+04 3.694786E+01 - 2.410006E+01 3 3 2.232253E+03 1.981839E+02 - 2.410006E+01 4 2 1.468944E+04 3.707983E+01 - 2.410006E+01 4 4 2.710592E+05 1.234255E+02 - 2.410006E+01 5 1 -1.039270E+04 9.534648E+01 - 2.410006E+01 5 5 8.271782E+05 9.387194E+02 - 2.410006E+01 6 6 9.139781E+05 3.730908E+01 - 2.420006E+01 1 1 2.031112E+03 9.609752E+00 - 2.420006E+01 1 5 -1.037431E+04 9.473851E+01 - 2.420006E+01 2 2 2.306985E+03 1.098335E+01 - 2.420006E+01 2 4 1.467128E+04 3.654422E+01 - 2.420006E+01 3 3 2.232986E+03 1.983488E+02 - 2.420006E+01 4 2 1.468798E+04 3.667476E+01 - 2.420006E+01 4 4 2.710523E+05 1.220480E+02 - 2.420006E+01 5 1 -1.039244E+04 9.447757E+01 - 2.420006E+01 5 5 8.271759E+05 9.313820E+02 - 2.420006E+01 6 6 9.138958E+05 3.654898E+01 - 2.430006E+01 1 1 2.030863E+03 9.511484E+00 - 2.430006E+01 1 5 -1.037415E+04 9.388129E+01 - 2.430006E+01 2 2 2.306656E+03 1.086845E+01 - 2.430006E+01 2 4 1.466984E+04 3.614560E+01 - 2.430006E+01 3 3 2.233718E+03 1.985104E+02 - 2.430006E+01 4 2 1.468658E+04 3.627436E+01 - 2.430006E+01 4 4 2.710465E+05 1.206483E+02 - 2.430006E+01 5 1 -1.039221E+04 9.362186E+01 - 2.430006E+01 5 5 8.271740E+05 9.240085E+02 - 2.430006E+01 6 6 9.138143E+05 3.586105E+01 - 2.440006E+01 1 1 2.030609E+03 9.414827E+00 - 2.440006E+01 1 5 -1.037391E+04 9.303546E+01 - 2.440006E+01 2 2 2.306322E+03 1.075568E+01 - 2.440006E+01 2 4 1.466841E+04 3.575534E+01 - 2.440006E+01 3 3 2.234436E+03 1.986674E+02 - 2.440006E+01 4 2 1.468513E+04 3.588192E+01 - 2.440006E+01 4 4 2.710398E+05 1.192928E+02 - 2.440006E+01 5 1 -1.039196E+04 9.278113E+01 - 2.440006E+01 5 5 8.271754E+05 9.168135E+02 - 2.440006E+01 6 6 9.137352E+05 3.514493E+01 - 2.450006E+01 1 1 2.030361E+03 9.319529E+00 - 2.450006E+01 1 5 -1.037363E+04 9.220276E+01 - 2.450006E+01 2 2 2.305993E+03 1.064490E+01 - 2.450006E+01 2 4 1.466702E+04 3.537190E+01 - 2.450006E+01 3 3 2.235165E+03 1.988278E+02 - 2.450006E+01 4 2 1.468375E+04 3.549681E+01 - 2.450006E+01 4 4 2.710335E+05 1.179643E+02 - 2.450006E+01 5 1 -1.039174E+04 9.194997E+01 - 2.450006E+01 5 5 8.271759E+05 9.095566E+02 - 2.450006E+01 6 6 9.136572E+05 3.445596E+01 - 2.460006E+01 1 1 2.030117E+03 9.225826E+00 - 2.460006E+01 1 5 -1.037340E+04 9.138032E+01 - 2.460006E+01 2 2 2.305668E+03 1.053581E+01 - 2.460006E+01 2 4 1.466565E+04 3.499251E+01 - 2.460006E+01 3 3 2.235873E+03 1.989822E+02 - 2.460006E+01 4 2 1.468234E+04 3.511721E+01 - 2.460006E+01 4 4 2.710272E+05 1.166416E+02 - 2.460006E+01 5 1 -1.039152E+04 9.113002E+01 - 2.460006E+01 5 5 8.271744E+05 9.025378E+02 - 2.460006E+01 6 6 9.135802E+05 3.381790E+01 - 2.470006E+01 1 1 2.029873E+03 9.133606E+00 - 2.470006E+01 1 5 -1.037318E+04 9.056837E+01 - 2.470006E+01 2 2 2.305353E+03 1.042826E+01 - 2.470006E+01 2 4 1.466428E+04 3.462143E+01 - 2.470006E+01 3 3 2.236587E+03 1.991355E+02 - 2.470006E+01 4 2 1.468099E+04 3.474391E+01 - 2.470006E+01 4 4 2.710212E+05 1.153483E+02 - 2.470006E+01 5 1 -1.039129E+04 9.032232E+01 - 2.470006E+01 5 5 8.271716E+05 8.955177E+02 - 2.470006E+01 6 6 9.135034E+05 3.313776E+01 - 2.480006E+01 1 1 2.029630E+03 9.042878E+00 - 2.480006E+01 1 5 -1.037298E+04 8.976824E+01 - 2.480006E+01 2 2 2.305035E+03 1.032270E+01 - 2.480006E+01 2 4 1.466295E+04 3.425539E+01 - 2.480006E+01 3 3 2.237302E+03 1.992867E+02 - 2.480006E+01 4 2 1.467967E+04 3.437832E+01 - 2.480006E+01 4 4 2.710157E+05 1.140821E+02 - 2.480006E+01 5 1 -1.039106E+04 8.952290E+01 - 2.480006E+01 5 5 8.271679E+05 8.886054E+02 - 2.480006E+01 6 6 9.134277E+05 3.253455E+01 - 2.490006E+01 1 1 2.029394E+03 8.953331E+00 - 2.490006E+01 1 5 -1.037281E+04 8.897883E+01 - 2.490006E+01 2 2 2.304724E+03 1.021857E+01 - 2.490006E+01 2 4 1.466162E+04 3.389667E+01 - 2.490006E+01 3 3 2.237998E+03 1.994348E+02 - 2.490006E+01 4 2 1.467831E+04 3.401699E+01 - 2.490006E+01 4 4 2.710087E+05 1.128555E+02 - 2.490006E+01 5 1 -1.039082E+04 8.874215E+01 - 2.490006E+01 5 5 8.271696E+05 8.818109E+02 - 2.490006E+01 6 6 9.133528E+05 3.192215E+01 - 2.500006E+01 1 1 2.029163E+03 8.865359E+00 - 2.500006E+01 1 5 -1.037263E+04 8.819851E+01 - 2.500006E+01 2 2 2.304419E+03 1.011612E+01 - 2.500006E+01 2 4 1.466032E+04 3.354252E+01 - 2.500006E+01 3 3 2.238706E+03 1.995865E+02 - 2.500006E+01 4 2 1.467700E+04 3.366219E+01 - 2.500006E+01 4 4 2.710033E+05 1.116153E+02 - 2.500006E+01 5 1 -1.039066E+04 8.796290E+01 - 2.500006E+01 5 5 8.271669E+05 8.751105E+02 - 2.500006E+01 6 6 9.132793E+05 3.132604E+01 - 2.510006E+01 1 1 2.028934E+03 8.778656E+00 - 2.510006E+01 1 5 -1.037237E+04 8.743025E+01 - 2.510006E+01 2 2 2.304118E+03 1.001532E+01 - 2.510006E+01 2 4 1.465900E+04 3.319426E+01 - 2.510006E+01 3 3 2.239400E+03 1.997308E+02 - 2.510006E+01 4 2 1.467571E+04 3.331283E+01 - 2.510006E+01 4 4 2.709972E+05 1.104066E+02 - 2.510006E+01 5 1 -1.039050E+04 8.719435E+01 - 2.510006E+01 5 5 8.271693E+05 8.684067E+02 - 2.510006E+01 6 6 9.132068E+05 3.071132E+01 - 2.520006E+01 1 1 2.028703E+03 8.693321E+00 - 2.520006E+01 1 5 -1.037219E+04 8.667213E+01 - 2.520006E+01 2 2 2.303819E+03 9.916179E+00 - 2.520006E+01 2 4 1.465776E+04 3.285224E+01 - 2.520006E+01 3 3 2.240094E+03 1.998740E+02 - 2.520006E+01 4 2 1.467443E+04 3.297049E+01 - 2.520006E+01 4 4 2.709916E+05 1.092366E+02 - 2.520006E+01 5 1 -1.039028E+04 8.643800E+01 - 2.520006E+01 5 5 8.271694E+05 8.618149E+02 - 2.520006E+01 6 6 9.131358E+05 3.016357E+01 - 2.530006E+01 1 1 2.028479E+03 8.609179E+00 - 2.530006E+01 1 5 -1.037204E+04 8.592427E+01 - 2.530006E+01 2 2 2.303526E+03 9.818414E+00 - 2.530006E+01 2 4 1.465649E+04 3.251585E+01 - 2.530006E+01 3 3 2.240780E+03 2.000163E+02 - 2.530006E+01 4 2 1.467319E+04 3.263248E+01 - 2.530006E+01 4 4 2.709859E+05 1.080735E+02 - 2.530006E+01 5 1 -1.039008E+04 8.569388E+01 - 2.530006E+01 5 5 8.271659E+05 8.552576E+02 - 2.530006E+01 6 6 9.130642E+05 2.958306E+01 - 2.540006E+01 1 1 2.028260E+03 8.526321E+00 - 2.540006E+01 1 5 -1.037186E+04 8.518460E+01 - 2.540006E+01 2 2 2.303233E+03 9.722049E+00 - 2.540006E+01 2 4 1.465524E+04 3.218387E+01 - 2.540006E+01 3 3 2.241477E+03 2.001544E+02 - 2.540006E+01 4 2 1.467192E+04 3.229755E+01 - 2.540006E+01 4 4 2.709805E+05 1.069268E+02 - 2.540006E+01 5 1 -1.038993E+04 8.495767E+01 - 2.540006E+01 5 5 8.271612E+05 8.487145E+02 - 2.540006E+01 6 6 9.129948E+05 2.904381E+01 - 2.550006E+01 1 1 2.028036E+03 8.444819E+00 - 2.550006E+01 1 5 -1.037168E+04 8.445553E+01 - 2.550006E+01 2 2 2.302943E+03 9.627226E+00 - 2.550006E+01 2 4 1.465403E+04 3.185727E+01 - 2.550006E+01 3 3 2.242153E+03 2.002938E+02 - 2.550006E+01 4 2 1.467067E+04 3.196987E+01 - 2.550006E+01 4 4 2.709756E+05 1.058044E+02 - 2.550006E+01 5 1 -1.038976E+04 8.422741E+01 - 2.550006E+01 5 5 8.271586E+05 8.422817E+02 - 2.550006E+01 6 6 9.129251E+05 2.850357E+01 - 2.560006E+01 1 1 2.027823E+03 8.364308E+00 - 2.560006E+01 1 5 -1.037155E+04 8.373588E+01 - 2.560006E+01 2 2 2.302657E+03 9.533985E+00 - 2.560006E+01 2 4 1.465281E+04 3.153700E+01 - 2.560006E+01 3 3 2.242827E+03 2.004348E+02 - 2.560006E+01 4 2 1.466947E+04 3.164940E+01 - 2.560006E+01 4 4 2.709701E+05 1.047038E+02 - 2.560006E+01 5 1 -1.038962E+04 8.351262E+01 - 2.560006E+01 5 5 8.271565E+05 8.359814E+02 - 2.560006E+01 6 6 9.128584E+05 2.799725E+01 - 2.570006E+01 1 1 2.027606E+03 8.285014E+00 - 2.570006E+01 1 5 -1.037137E+04 8.302389E+01 - 2.570006E+01 2 2 2.302380E+03 9.442121E+00 - 2.570006E+01 2 4 1.465162E+04 3.121981E+01 - 2.570006E+01 3 3 2.243504E+03 2.005645E+02 - 2.570006E+01 4 2 1.466828E+04 3.133272E+01 - 2.570006E+01 4 4 2.709648E+05 1.036158E+02 - 2.570006E+01 5 1 -1.038941E+04 8.280424E+01 - 2.570006E+01 5 5 8.271548E+05 8.298326E+02 - 2.570006E+01 6 6 9.127900E+05 2.749338E+01 - 2.580006E+01 1 1 2.027392E+03 8.206997E+00 - 2.580006E+01 1 5 -1.037125E+04 8.232254E+01 - 2.580006E+01 2 2 2.302102E+03 9.351472E+00 - 2.580006E+01 2 4 1.465043E+04 3.090963E+01 - 2.580006E+01 3 3 2.244165E+03 2.007012E+02 - 2.580006E+01 4 2 1.466709E+04 3.101912E+01 - 2.580006E+01 4 4 2.709602E+05 1.025484E+02 - 2.580006E+01 5 1 -1.038929E+04 8.210590E+01 - 2.580006E+01 5 5 8.271551E+05 8.235336E+02 - 2.580006E+01 6 6 9.127228E+05 2.699221E+01 - 2.590006E+01 1 1 2.027182E+03 8.130158E+00 - 2.590006E+01 1 5 -1.037112E+04 8.162987E+01 - 2.590006E+01 2 2 2.301826E+03 9.262368E+00 - 2.590006E+01 2 4 1.464928E+04 3.060220E+01 - 2.590006E+01 3 3 2.244849E+03 2.008306E+02 - 2.590006E+01 4 2 1.466592E+04 3.071286E+01 - 2.590006E+01 4 4 2.709549E+05 1.014891E+02 - 2.590006E+01 5 1 -1.038912E+04 8.141292E+01 - 2.590006E+01 5 5 8.271537E+05 8.174359E+02 - 2.590006E+01 6 6 9.126582E+05 2.651291E+01 - 2.600006E+01 1 1 2.026976E+03 8.054261E+00 - 2.600006E+01 1 5 -1.037096E+04 8.094625E+01 - 2.600006E+01 2 2 2.301557E+03 9.174356E+00 - 2.600006E+01 2 4 1.464809E+04 3.030066E+01 - 2.600006E+01 3 3 2.245509E+03 2.009578E+02 - 2.600006E+01 4 2 1.466478E+04 3.040839E+01 - 2.600006E+01 4 4 2.709496E+05 1.004428E+02 - 2.600006E+01 5 1 -1.038898E+04 8.073370E+01 - 2.600006E+01 5 5 8.271520E+05 8.113566E+02 - 2.600006E+01 6 6 9.125938E+05 2.603255E+01 - 2.610006E+01 1 1 2.026770E+03 7.979511E+00 - 2.610006E+01 1 5 -1.037085E+04 8.027102E+01 - 2.610006E+01 2 2 2.301287E+03 9.087890E+00 - 2.610006E+01 2 4 1.464696E+04 3.000399E+01 - 2.610006E+01 3 3 2.246179E+03 2.010886E+02 - 2.610006E+01 4 2 1.466362E+04 3.011195E+01 - 2.610006E+01 4 4 2.709448E+05 9.942530E+01 - 2.610006E+01 5 1 -1.038877E+04 8.006023E+01 - 2.610006E+01 5 5 8.271528E+05 8.053268E+02 - 2.610006E+01 6 6 9.125300E+05 2.558108E+01 - 2.620006E+01 1 1 2.026568E+03 7.906063E+00 - 2.620006E+01 1 5 -1.037070E+04 7.960527E+01 - 2.620006E+01 2 2 2.301020E+03 9.002596E+00 - 2.620006E+01 2 4 1.464582E+04 2.971134E+01 - 2.620006E+01 3 3 2.246840E+03 2.012124E+02 - 2.620006E+01 4 2 1.466249E+04 2.982026E+01 - 2.620006E+01 4 4 2.709401E+05 9.841453E+01 - 2.620006E+01 5 1 -1.038868E+04 7.939495E+01 - 2.620006E+01 5 5 8.271547E+05 7.993817E+02 - 2.620006E+01 6 6 9.124662E+05 2.512825E+01 - 2.630006E+01 1 1 2.026369E+03 7.833481E+00 - 2.630006E+01 1 5 -1.037054E+04 7.894700E+01 - 2.630006E+01 2 2 2.300758E+03 8.918515E+00 - 2.630006E+01 2 4 1.464473E+04 2.942456E+01 - 2.630006E+01 3 3 2.247492E+03 2.013382E+02 - 2.630006E+01 4 2 1.466139E+04 2.953014E+01 - 2.630006E+01 4 4 2.709352E+05 9.743958E+01 - 2.630006E+01 5 1 -1.038856E+04 7.873937E+01 - 2.630006E+01 5 5 8.271514E+05 7.933781E+02 - 2.630006E+01 6 6 9.124036E+05 2.467591E+01 - 2.640006E+01 1 1 2.026170E+03 7.761918E+00 - 2.640006E+01 1 5 -1.037043E+04 7.829729E+01 - 2.640006E+01 2 2 2.300500E+03 8.835664E+00 - 2.640006E+01 2 4 1.464364E+04 2.913994E+01 - 2.640006E+01 3 3 2.248145E+03 2.014608E+02 - 2.640006E+01 4 2 1.466025E+04 2.924344E+01 - 2.640006E+01 4 4 2.709298E+05 9.645932E+01 - 2.640006E+01 5 1 -1.038839E+04 7.809048E+01 - 2.640006E+01 5 5 8.271487E+05 7.876584E+02 - 2.640006E+01 6 6 9.123422E+05 2.422641E+01 - 2.650006E+01 1 1 2.025971E+03 7.691275E+00 - 2.650006E+01 1 5 -1.037028E+04 7.765542E+01 - 2.650006E+01 2 2 2.300242E+03 8.754071E+00 - 2.650006E+01 2 4 1.464257E+04 2.886089E+01 - 2.650006E+01 3 3 2.248790E+03 2.015837E+02 - 2.650006E+01 4 2 1.465918E+04 2.896592E+01 - 2.650006E+01 4 4 2.709252E+05 9.550850E+01 - 2.650006E+01 5 1 -1.038830E+04 7.745103E+01 - 2.650006E+01 5 5 8.271478E+05 7.818662E+02 - 2.650006E+01 6 6 9.122811E+05 2.380852E+01 - 2.660007E+01 1 1 2.025781E+03 7.621777E+00 - 2.660007E+01 1 5 -1.037016E+04 7.702213E+01 - 2.660007E+01 2 2 2.299993E+03 8.673573E+00 - 2.660007E+01 2 4 1.464148E+04 2.858478E+01 - 2.660007E+01 3 3 2.249433E+03 2.017079E+02 - 2.660007E+01 4 2 1.465809E+04 2.868768E+01 - 2.660007E+01 4 4 2.709197E+05 9.456152E+01 - 2.660007E+01 5 1 -1.038811E+04 7.682086E+01 - 2.660007E+01 5 5 8.271452E+05 7.761916E+02 - 2.660007E+01 6 6 9.122217E+05 2.341624E+01 - 2.670007E+01 1 1 2.025589E+03 7.553147E+00 - 2.670007E+01 1 5 -1.036999E+04 7.639590E+01 - 2.670007E+01 2 2 2.299744E+03 8.594369E+00 - 2.670007E+01 2 4 1.464042E+04 2.831405E+01 - 2.670007E+01 3 3 2.250092E+03 2.018210E+02 - 2.670007E+01 4 2 1.465705E+04 2.841756E+01 - 2.670007E+01 4 4 2.709153E+05 9.364024E+01 - 2.670007E+01 5 1 -1.038798E+04 7.619834E+01 - 2.670007E+01 5 5 8.271442E+05 7.705438E+02 - 2.670007E+01 6 6 9.121616E+05 2.302403E+01 - 2.680007E+01 1 1 2.025398E+03 7.485611E+00 - 2.680007E+01 1 5 -1.036985E+04 7.577713E+01 - 2.680007E+01 2 2 2.299498E+03 8.516093E+00 - 2.680007E+01 2 4 1.463934E+04 2.804749E+01 - 2.680007E+01 3 3 2.250717E+03 2.019380E+02 - 2.680007E+01 4 2 1.465599E+04 2.814923E+01 - 2.680007E+01 4 4 2.709104E+05 9.271354E+01 - 2.680007E+01 5 1 -1.038785E+04 7.557999E+01 - 2.680007E+01 5 5 8.271412E+05 7.649456E+02 - 2.680007E+01 6 6 9.121021E+05 2.261722E+01 - 2.690007E+01 1 1 2.025213E+03 7.418912E+00 - 2.690007E+01 1 5 -1.036984E+04 7.516774E+01 - 2.690007E+01 2 2 2.299252E+03 8.439022E+00 - 2.690007E+01 2 4 1.463833E+04 2.778351E+01 - 2.690007E+01 3 3 2.251357E+03 2.020509E+02 - 2.690007E+01 4 2 1.465495E+04 2.788507E+01 - 2.690007E+01 4 4 2.709064E+05 9.180151E+01 - 2.690007E+01 5 1 -1.038777E+04 7.497178E+01 - 2.690007E+01 5 5 8.271384E+05 7.593719E+02 - 2.690007E+01 6 6 9.120447E+05 2.221501E+01 - 2.700007E+01 1 1 2.025029E+03 7.353319E+00 - 2.700007E+01 1 5 -1.036971E+04 7.456400E+01 - 2.700007E+01 2 2 2.299008E+03 8.362997E+00 - 2.700007E+01 2 4 1.463733E+04 2.752589E+01 - 2.700007E+01 3 3 2.251990E+03 2.021681E+02 - 2.700007E+01 4 2 1.465391E+04 2.762262E+01 - 2.700007E+01 4 4 2.709012E+05 9.091588E+01 - 2.700007E+01 5 1 -1.038770E+04 7.436827E+01 - 2.700007E+01 5 5 8.271402E+05 7.539083E+02 - 2.700007E+01 6 6 9.119880E+05 2.184375E+01 - 2.710007E+01 1 1 2.024842E+03 7.288342E+00 - 2.710007E+01 1 5 -1.036959E+04 7.396838E+01 - 2.710007E+01 2 2 2.298773E+03 8.288078E+00 - 2.710007E+01 2 4 1.463628E+04 2.726971E+01 - 2.710007E+01 3 3 2.252618E+03 2.022818E+02 - 2.710007E+01 4 2 1.465294E+04 2.736761E+01 - 2.710007E+01 4 4 2.708975E+05 9.004169E+01 - 2.710007E+01 5 1 -1.038757E+04 7.377531E+01 - 2.710007E+01 5 5 8.271379E+05 7.485558E+02 - 2.710007E+01 6 6 9.119296E+05 2.146154E+01 - 2.720007E+01 1 1 2.024660E+03 7.224402E+00 - 2.720007E+01 1 5 -1.036949E+04 7.338126E+01 - 2.720007E+01 2 2 2.298535E+03 8.214152E+00 - 2.720007E+01 2 4 1.463534E+04 2.701756E+01 - 2.720007E+01 3 3 2.253254E+03 2.023945E+02 - 2.720007E+01 4 2 1.465191E+04 2.711414E+01 - 2.720007E+01 4 4 2.708927E+05 8.917516E+01 - 2.720007E+01 5 1 -1.038744E+04 7.319016E+01 - 2.720007E+01 5 5 8.271361E+05 7.432085E+02 - 2.720007E+01 6 6 9.118745E+05 2.110249E+01 - 2.730007E+01 1 1 2.024485E+03 7.161346E+00 - 2.730007E+01 1 5 -1.036944E+04 7.279700E+01 - 2.730007E+01 2 2 2.298305E+03 8.141392E+00 - 2.730007E+01 2 4 1.463432E+04 2.676848E+01 - 2.730007E+01 3 3 2.253865E+03 2.025052E+02 - 2.730007E+01 4 2 1.465092E+04 2.686798E+01 - 2.730007E+01 4 4 2.708882E+05 8.831751E+01 - 2.730007E+01 5 1 -1.038731E+04 7.260977E+01 - 2.730007E+01 5 5 8.271354E+05 7.380906E+02 - 2.730007E+01 6 6 9.118178E+05 2.074540E+01 - 2.740007E+01 1 1 2.024305E+03 7.099033E+00 - 2.740007E+01 1 5 -1.036927E+04 7.222258E+01 - 2.740007E+01 2 2 2.298073E+03 8.069516E+00 - 2.740007E+01 2 4 1.463330E+04 2.652415E+01 - 2.740007E+01 3 3 2.254494E+03 2.026157E+02 - 2.740007E+01 4 2 1.464994E+04 2.662088E+01 - 2.740007E+01 4 4 2.708835E+05 8.749374E+01 - 2.740007E+01 5 1 -1.038720E+04 7.203725E+01 - 2.740007E+01 5 5 8.271338E+05 7.327724E+02 - 2.740007E+01 6 6 9.117642E+05 2.041133E+01 - 2.750007E+01 1 1 2.024130E+03 7.037647E+00 - 2.750007E+01 1 5 -1.036916E+04 7.165567E+01 - 2.750007E+01 2 2 2.297844E+03 7.998565E+00 - 2.750007E+01 2 4 1.463234E+04 2.628375E+01 - 2.750007E+01 3 3 2.255115E+03 2.027203E+02 - 2.750007E+01 4 2 1.464895E+04 2.637799E+01 - 2.750007E+01 4 4 2.708794E+05 8.667188E+01 - 2.750007E+01 5 1 -1.038707E+04 7.146989E+01 - 2.750007E+01 5 5 8.271309E+05 7.276382E+02 - 2.750007E+01 6 6 9.117089E+05 2.006933E+01 - 2.760007E+01 1 1 2.023955E+03 6.977025E+00 - 2.760007E+01 1 5 -1.036909E+04 7.109379E+01 - 2.760007E+01 2 2 2.297618E+03 7.928640E+00 - 2.760007E+01 2 4 1.463141E+04 2.604533E+01 - 2.760007E+01 3 3 2.255740E+03 2.028272E+02 - 2.760007E+01 4 2 1.464803E+04 2.613900E+01 - 2.760007E+01 4 4 2.708758E+05 8.586026E+01 - 2.760007E+01 5 1 -1.038699E+04 7.091207E+01 - 2.760007E+01 5 5 8.271269E+05 7.225269E+02 - 2.760007E+01 6 6 9.116554E+05 1.974953E+01 - 2.770007E+01 1 1 2.023784E+03 6.917323E+00 - 2.770007E+01 1 5 -1.036900E+04 7.053949E+01 - 2.770007E+01 2 2 2.297396E+03 7.859682E+00 - 2.770007E+01 2 4 1.463049E+04 2.581096E+01 - 2.770007E+01 3 3 2.256353E+03 2.029345E+02 - 2.770007E+01 4 2 1.464711E+04 2.590321E+01 - 2.770007E+01 4 4 2.708718E+05 8.506426E+01 - 2.770007E+01 5 1 -1.038695E+04 7.036079E+01 - 2.770007E+01 5 5 8.271243E+05 7.174827E+02 - 2.770007E+01 6 6 9.116028E+05 1.942171E+01 - 2.780007E+01 1 1 2.023617E+03 6.858329E+00 - 2.780007E+01 1 5 -1.036893E+04 6.999146E+01 - 2.780007E+01 2 2 2.297175E+03 7.791627E+00 - 2.780007E+01 2 4 1.462958E+04 2.557955E+01 - 2.780007E+01 3 3 2.256959E+03 2.030356E+02 - 2.780007E+01 4 2 1.464617E+04 2.567141E+01 - 2.780007E+01 4 4 2.708678E+05 8.427245E+01 - 2.780007E+01 5 1 -1.038686E+04 6.981249E+01 - 2.780007E+01 5 5 8.271239E+05 7.124775E+02 - 2.780007E+01 6 6 9.115508E+05 1.909354E+01 - 2.790007E+01 1 1 2.023452E+03 6.800189E+00 - 2.790007E+01 1 5 -1.036882E+04 6.944979E+01 - 2.790007E+01 2 2 2.296957E+03 7.724570E+00 - 2.790007E+01 2 4 1.462867E+04 2.535101E+01 - 2.790007E+01 3 3 2.257559E+03 2.031380E+02 - 2.790007E+01 4 2 1.464524E+04 2.544406E+01 - 2.790007E+01 4 4 2.708638E+05 8.349791E+01 - 2.790007E+01 5 1 -1.038676E+04 6.927383E+01 - 2.790007E+01 5 5 8.271224E+05 7.076198E+02 - 2.790007E+01 6 6 9.114988E+05 1.877842E+01 - 2.800007E+01 1 1 2.023283E+03 6.742652E+00 - 2.800007E+01 1 5 -1.036878E+04 6.891540E+01 - 2.800007E+01 2 2 2.296742E+03 7.658345E+00 - 2.800007E+01 2 4 1.462775E+04 2.512676E+01 - 2.800007E+01 3 3 2.258170E+03 2.032396E+02 - 2.800007E+01 4 2 1.464432E+04 2.521779E+01 - 2.800007E+01 4 4 2.708600E+05 8.273849E+01 - 2.800007E+01 5 1 -1.038664E+04 6.874118E+01 - 2.800007E+01 5 5 8.271211E+05 7.025291E+02 - 2.800007E+01 6 6 9.114471E+05 1.849010E+01 - 2.810007E+01 1 1 2.023123E+03 6.686055E+00 - 2.810007E+01 1 5 -1.036874E+04 6.838612E+01 - 2.810007E+01 2 2 2.296533E+03 7.593006E+00 - 2.810007E+01 2 4 1.462683E+04 2.490490E+01 - 2.810007E+01 3 3 2.258761E+03 2.033406E+02 - 2.810007E+01 4 2 1.464339E+04 2.499499E+01 - 2.810007E+01 4 4 2.708557E+05 8.199215E+01 - 2.810007E+01 5 1 -1.038655E+04 6.821239E+01 - 2.810007E+01 5 5 8.271199E+05 6.977377E+02 - 2.810007E+01 6 6 9.113975E+05 1.816499E+01 - 2.820007E+01 1 1 2.022958E+03 6.630203E+00 - 2.820007E+01 1 5 -1.036865E+04 6.786447E+01 - 2.820007E+01 2 2 2.296320E+03 7.528441E+00 - 2.820007E+01 2 4 1.462592E+04 2.468571E+01 - 2.820007E+01 3 3 2.259373E+03 2.034409E+02 - 2.820007E+01 4 2 1.464251E+04 2.477601E+01 - 2.820007E+01 4 4 2.708516E+05 8.123376E+01 - 2.820007E+01 5 1 -1.038648E+04 6.769152E+01 - 2.820007E+01 5 5 8.271199E+05 6.929471E+02 - 2.820007E+01 6 6 9.113474E+05 1.788164E+01 - 2.830007E+01 1 1 2.022800E+03 6.574834E+00 - 2.830007E+01 1 5 -1.036855E+04 6.734870E+01 - 2.830007E+01 2 2 2.296111E+03 7.464828E+00 - 2.830007E+01 2 4 1.462505E+04 2.447008E+01 - 2.830007E+01 3 3 2.259954E+03 2.035383E+02 - 2.830007E+01 4 2 1.464161E+04 2.455857E+01 - 2.830007E+01 4 4 2.708472E+05 8.050271E+01 - 2.830007E+01 5 1 -1.038641E+04 6.717837E+01 - 2.830007E+01 5 5 8.271189E+05 6.880599E+02 - 2.830007E+01 6 6 9.112978E+05 1.759614E+01 - 2.840007E+01 1 1 2.022639E+03 6.520379E+00 - 2.840007E+01 1 5 -1.036848E+04 6.683736E+01 - 2.840007E+01 2 2 2.295906E+03 7.402006E+00 - 2.840007E+01 2 4 1.462417E+04 2.425698E+01 - 2.840007E+01 3 3 2.260552E+03 2.036387E+02 - 2.840007E+01 4 2 1.464076E+04 2.434486E+01 - 2.840007E+01 4 4 2.708432E+05 7.977916E+01 - 2.840007E+01 5 1 -1.038631E+04 6.666644E+01 - 2.840007E+01 5 5 8.271157E+05 6.834644E+02 - 2.840007E+01 6 6 9.112480E+05 1.732650E+01 - 2.850007E+01 1 1 2.022484E+03 6.466599E+00 - 2.850007E+01 1 5 -1.036837E+04 6.633269E+01 - 2.850007E+01 2 2 2.295702E+03 7.340121E+00 - 2.850007E+01 2 4 1.462332E+04 2.404779E+01 - 2.850007E+01 3 3 2.261145E+03 2.037362E+02 - 2.850007E+01 4 2 1.463989E+04 2.413595E+01 - 2.850007E+01 4 4 2.708399E+05 7.907157E+01 - 2.850007E+01 5 1 -1.038626E+04 6.616535E+01 - 2.850007E+01 5 5 8.271139E+05 6.787702E+02 - 2.850007E+01 6 6 9.112001E+05 1.703636E+01 - 2.860007E+01 1 1 2.022328E+03 6.413464E+00 - 2.860007E+01 1 5 -1.036833E+04 6.583296E+01 - 2.860007E+01 2 2 2.295498E+03 7.278941E+00 - 2.860007E+01 2 4 1.462247E+04 2.384022E+01 - 2.860007E+01 3 3 2.261726E+03 2.038280E+02 - 2.860007E+01 4 2 1.463903E+04 2.392797E+01 - 2.860007E+01 4 4 2.708364E+05 7.836884E+01 - 2.860007E+01 5 1 -1.038620E+04 6.566795E+01 - 2.860007E+01 5 5 8.271121E+05 6.740529E+02 - 2.860007E+01 6 6 9.111522E+05 1.674174E+01 - 2.870007E+01 1 1 2.022170E+03 6.361094E+00 - 2.870007E+01 1 5 -1.036829E+04 6.534035E+01 - 2.870007E+01 2 2 2.295301E+03 7.218606E+00 - 2.870007E+01 2 4 1.462165E+04 2.363672E+01 - 2.870007E+01 3 3 2.262323E+03 2.039178E+02 - 2.870007E+01 4 2 1.463819E+04 2.372230E+01 - 2.870007E+01 4 4 2.708327E+05 7.768160E+01 - 2.870007E+01 5 1 -1.038616E+04 6.517496E+01 - 2.870007E+01 5 5 8.271101E+05 6.694837E+02 - 2.870007E+01 6 6 9.111051E+05 1.650031E+01 - 2.880007E+01 1 1 2.022024E+03 6.309087E+00 - 2.880007E+01 1 5 -1.036821E+04 6.485181E+01 - 2.880007E+01 2 2 2.295105E+03 7.158854E+00 - 2.880007E+01 2 4 1.462082E+04 2.343510E+01 - 2.880007E+01 3 3 2.262901E+03 2.040123E+02 - 2.880007E+01 4 2 1.463736E+04 2.351902E+01 - 2.880007E+01 4 4 2.708287E+05 7.700045E+01 - 2.880007E+01 5 1 -1.038609E+04 6.468934E+01 - 2.880007E+01 5 5 8.271091E+05 6.650147E+02 - 2.880007E+01 6 6 9.110579E+05 1.625590E+01 - 2.890007E+01 1 1 2.021871E+03 6.258068E+00 - 2.890007E+01 1 5 -1.036815E+04 6.437022E+01 - 2.890007E+01 2 2 2.294912E+03 7.100051E+00 - 2.890007E+01 2 4 1.461996E+04 2.323535E+01 - 2.890007E+01 3 3 2.263477E+03 2.041029E+02 - 2.890007E+01 4 2 1.463655E+04 2.331953E+01 - 2.890007E+01 4 4 2.708250E+05 7.632709E+01 - 2.890007E+01 5 1 -1.038606E+04 6.420971E+01 - 2.890007E+01 5 5 8.271060E+05 6.604647E+02 - 2.890007E+01 6 6 9.110112E+05 1.598374E+01 - 2.900007E+01 1 1 2.021721E+03 6.207590E+00 - 2.900007E+01 1 5 -1.036804E+04 6.389341E+01 - 2.900007E+01 2 2 2.294715E+03 7.041935E+00 - 2.900007E+01 2 4 1.461917E+04 2.304024E+01 - 2.900007E+01 3 3 2.264055E+03 2.041899E+02 - 2.900007E+01 4 2 1.463569E+04 2.312125E+01 - 2.900007E+01 4 4 2.708212E+05 7.566386E+01 - 2.900007E+01 5 1 -1.038595E+04 6.373272E+01 - 2.900007E+01 5 5 8.271059E+05 6.560548E+02 - 2.900007E+01 6 6 9.109660E+05 1.574792E+01 - 2.910007E+01 1 1 2.021573E+03 6.157659E+00 - 2.910007E+01 1 5 -1.036800E+04 6.342225E+01 - 2.910007E+01 2 2 2.294522E+03 6.984544E+00 - 2.910007E+01 2 4 1.461833E+04 2.284501E+01 - 2.910007E+01 3 3 2.264625E+03 2.042838E+02 - 2.910007E+01 4 2 1.463491E+04 2.292676E+01 - 2.910007E+01 4 4 2.708181E+05 7.500017E+01 - 2.910007E+01 5 1 -1.038590E+04 6.326410E+01 - 2.910007E+01 5 5 8.271073E+05 6.516302E+02 - 2.910007E+01 6 6 9.109204E+05 1.547230E+01 - 2.920008E+01 1 1 2.021426E+03 6.108489E+00 - 2.920008E+01 1 5 -1.036796E+04 6.295671E+01 - 2.920008E+01 2 2 2.294335E+03 6.927901E+00 - 2.920008E+01 2 4 1.461756E+04 2.265427E+01 - 2.920008E+01 3 3 2.265196E+03 2.043726E+02 - 2.920008E+01 4 2 1.463408E+04 2.273553E+01 - 2.920008E+01 4 4 2.708147E+05 7.435568E+01 - 2.920008E+01 5 1 -1.038581E+04 6.280007E+01 - 2.920008E+01 5 5 8.271033E+05 6.472724E+02 - 2.920008E+01 6 6 9.108755E+05 1.525361E+01 - 2.930008E+01 1 1 2.021280E+03 6.059825E+00 - 2.930008E+01 1 5 -1.036789E+04 6.249568E+01 - 2.930008E+01 2 2 2.294149E+03 6.872046E+00 - 2.930008E+01 2 4 1.461680E+04 2.246572E+01 - 2.930008E+01 3 3 2.265770E+03 2.044607E+02 - 2.930008E+01 4 2 1.463332E+04 2.254597E+01 - 2.930008E+01 4 4 2.708115E+05 7.371797E+01 - 2.930008E+01 5 1 -1.038576E+04 6.234050E+01 - 2.930008E+01 5 5 8.270998E+05 6.429332E+02 - 2.930008E+01 6 6 9.108319E+05 1.502413E+01 - 2.940008E+01 1 1 2.021138E+03 6.011852E+00 - 2.940008E+01 1 5 -1.036782E+04 6.203848E+01 - 2.940008E+01 2 2 2.293958E+03 6.816762E+00 - 2.940008E+01 2 4 1.461598E+04 2.227993E+01 - 2.940008E+01 3 3 2.266332E+03 2.045479E+02 - 2.940008E+01 4 2 1.463253E+04 2.235858E+01 - 2.940008E+01 4 4 2.708084E+05 7.308825E+01 - 2.940008E+01 5 1 -1.038572E+04 6.188339E+01 - 2.940008E+01 5 5 8.270981E+05 6.387080E+02 - 2.940008E+01 6 6 9.107879E+05 1.480074E+01 - 2.950008E+01 1 1 2.020998E+03 5.964438E+00 - 2.950008E+01 1 5 -1.036776E+04 6.158921E+01 - 2.950008E+01 2 2 2.293778E+03 6.762341E+00 - 2.950008E+01 2 4 1.461521E+04 2.209564E+01 - 2.950008E+01 3 3 2.266894E+03 2.046373E+02 - 2.950008E+01 4 2 1.463177E+04 2.217491E+01 - 2.950008E+01 4 4 2.708047E+05 7.246009E+01 - 2.950008E+01 5 1 -1.038566E+04 6.143720E+01 - 2.950008E+01 5 5 8.270965E+05 6.344276E+02 - 2.950008E+01 6 6 9.107442E+05 1.456672E+01 - 2.960008E+01 1 1 2.020856E+03 5.917544E+00 - 2.960008E+01 1 5 -1.036768E+04 6.114288E+01 - 2.960008E+01 2 2 2.293596E+03 6.708459E+00 - 2.960008E+01 2 4 1.461445E+04 2.191437E+01 - 2.960008E+01 3 3 2.267466E+03 2.047225E+02 - 2.960008E+01 4 2 1.463100E+04 2.199310E+01 - 2.960008E+01 4 4 2.708009E+05 7.186835E+01 - 2.960008E+01 5 1 -1.038560E+04 6.099097E+01 - 2.960008E+01 5 5 8.270942E+05 6.302792E+02 - 2.960008E+01 6 6 9.107021E+05 1.434396E+01 - 2.970008E+01 1 1 2.020719E+03 5.871214E+00 - 2.970008E+01 1 5 -1.036767E+04 6.070256E+01 - 2.970008E+01 2 2 2.293414E+03 6.655274E+00 - 2.970008E+01 2 4 1.461368E+04 2.173527E+01 - 2.970008E+01 3 3 2.268023E+03 2.048034E+02 - 2.970008E+01 4 2 1.463019E+04 2.181270E+01 - 2.970008E+01 4 4 2.707975E+05 7.125802E+01 - 2.970008E+01 5 1 -1.038563E+04 6.055035E+01 - 2.970008E+01 5 5 8.270915E+05 6.261959E+02 - 2.970008E+01 6 6 9.106592E+05 1.412324E+01 - 2.980008E+01 1 1 2.020583E+03 5.825470E+00 - 2.980008E+01 1 5 -1.036769E+04 6.026657E+01 - 2.980008E+01 2 2 2.293240E+03 6.602677E+00 - 2.980008E+01 2 4 1.461294E+04 2.155863E+01 - 2.980008E+01 3 3 2.268576E+03 2.048897E+02 - 2.980008E+01 4 2 1.462945E+04 2.163625E+01 - 2.980008E+01 4 4 2.707938E+05 7.064493E+01 - 2.980008E+01 5 1 -1.038553E+04 6.011567E+01 - 2.980008E+01 5 5 8.270897E+05 6.220324E+02 - 2.980008E+01 6 6 9.106178E+05 1.393097E+01 - 2.990008E+01 1 1 2.020447E+03 5.780306E+00 - 2.990008E+01 1 5 -1.036763E+04 5.983643E+01 - 2.990008E+01 2 2 2.293064E+03 6.550907E+00 - 2.990008E+01 2 4 1.461221E+04 2.138336E+01 - 2.990008E+01 3 3 2.269145E+03 2.049725E+02 - 2.990008E+01 4 2 1.462872E+04 2.146172E+01 - 2.990008E+01 4 4 2.707909E+05 7.004963E+01 - 2.990008E+01 5 1 -1.038549E+04 5.968921E+01 - 2.990008E+01 5 5 8.270876E+05 6.179717E+02 - 2.990008E+01 6 6 9.105762E+05 1.371025E+01 - 3.000008E+01 1 1 2.020311E+03 5.735516E+00 - 3.000008E+01 1 5 -1.036755E+04 5.940879E+01 - 3.000008E+01 2 2 2.292889E+03 6.499515E+00 - 3.000008E+01 2 4 1.461148E+04 2.121048E+01 - 3.000008E+01 3 3 2.269689E+03 2.050517E+02 - 3.000008E+01 4 2 1.462802E+04 2.128679E+01 - 3.000008E+01 4 4 2.707882E+05 6.946275E+01 - 3.000008E+01 5 1 -1.038544E+04 5.926148E+01 - 3.000008E+01 5 5 8.270874E+05 6.139026E+02 - 3.000008E+01 6 6 9.105343E+05 1.350836E+01 - 3.010008E+01 1 1 2.020176E+03 5.691556E+00 - 3.010008E+01 1 5 -1.036749E+04 5.898837E+01 - 3.010008E+01 2 2 2.292721E+03 6.448809E+00 - 3.010008E+01 2 4 1.461075E+04 2.104004E+01 - 3.010008E+01 3 3 2.270232E+03 2.051338E+02 - 3.010008E+01 4 2 1.462729E+04 2.111545E+01 - 3.010008E+01 4 4 2.707848E+05 6.888127E+01 - 3.010008E+01 5 1 -1.038534E+04 5.883812E+01 - 3.010008E+01 5 5 8.270859E+05 6.097963E+02 - 3.010008E+01 6 6 9.104941E+05 1.329061E+01 - 3.020008E+01 1 1 2.020045E+03 5.647838E+00 - 3.020008E+01 1 5 -1.036748E+04 5.856982E+01 - 3.020008E+01 2 2 2.292547E+03 6.398825E+00 - 3.020008E+01 2 4 1.461003E+04 2.087177E+01 - 3.020008E+01 3 3 2.270784E+03 2.052098E+02 - 3.020008E+01 4 2 1.462657E+04 2.094711E+01 - 3.020008E+01 4 4 2.707821E+05 6.832902E+01 - 3.020008E+01 5 1 -1.038530E+04 5.842654E+01 - 3.020008E+01 5 5 8.270849E+05 6.059205E+02 - 3.020008E+01 6 6 9.104534E+05 1.311851E+01 - 3.030008E+01 1 1 2.019914E+03 5.604763E+00 - 3.030008E+01 1 5 -1.036745E+04 5.815787E+01 - 3.030008E+01 2 2 2.292382E+03 6.349491E+00 - 3.030008E+01 2 4 1.460933E+04 2.070590E+01 - 3.030008E+01 3 3 2.271326E+03 2.052895E+02 - 3.030008E+01 4 2 1.462586E+04 2.078091E+01 - 3.030008E+01 4 4 2.707782E+05 6.777458E+01 - 3.030008E+01 5 1 -1.038526E+04 5.801655E+01 - 3.030008E+01 5 5 8.270829E+05 6.018796E+02 - 3.030008E+01 6 6 9.104129E+05 1.291759E+01 - 3.040008E+01 1 1 2.019788E+03 5.562180E+00 - 3.040008E+01 1 5 -1.036744E+04 5.774894E+01 - 3.040008E+01 2 2 2.292213E+03 6.300581E+00 - 3.040008E+01 2 4 1.460862E+04 2.054165E+01 - 3.040008E+01 3 3 2.271875E+03 2.053652E+02 - 3.040008E+01 4 2 1.462515E+04 2.061540E+01 - 3.040008E+01 4 4 2.707755E+05 6.721703E+01 - 3.040008E+01 5 1 -1.038523E+04 5.760820E+01 - 3.040008E+01 5 5 8.270799E+05 5.981005E+02 - 3.040008E+01 6 6 9.103738E+05 1.272697E+01 - 3.050008E+01 1 1 2.019657E+03 5.520111E+00 - 3.050008E+01 1 5 -1.036739E+04 5.734531E+01 - 3.050008E+01 2 2 2.292048E+03 6.252312E+00 - 3.050008E+01 2 4 1.460792E+04 2.037868E+01 - 3.050008E+01 3 3 2.272415E+03 2.054393E+02 - 3.050008E+01 4 2 1.462445E+04 2.045273E+01 - 3.050008E+01 4 4 2.707728E+05 6.665411E+01 - 3.050008E+01 5 1 -1.038520E+04 5.720720E+01 - 3.050008E+01 5 5 8.270796E+05 5.941226E+02 - 3.050008E+01 6 6 9.103344E+05 1.254307E+01 - 3.060008E+01 1 1 2.019536E+03 5.478503E+00 - 3.060008E+01 1 5 -1.036736E+04 5.694650E+01 - 3.060008E+01 2 2 2.291885E+03 6.204667E+00 - 3.060008E+01 2 4 1.460723E+04 2.022026E+01 - 3.060008E+01 3 3 2.272950E+03 2.055196E+02 - 3.060008E+01 4 2 1.462376E+04 2.029109E+01 - 3.060008E+01 4 4 2.707699E+05 6.612585E+01 - 3.060008E+01 5 1 -1.038516E+04 5.680798E+01 - 3.060008E+01 5 5 8.270776E+05 5.904149E+02 - 3.060008E+01 6 6 9.102960E+05 1.237752E+01 - 3.070008E+01 1 1 2.019405E+03 5.437555E+00 - 3.070008E+01 1 5 -1.036729E+04 5.655041E+01 - 3.070008E+01 2 2 2.291720E+03 6.157564E+00 - 3.070008E+01 2 4 1.460656E+04 2.006185E+01 - 3.070008E+01 3 3 2.273484E+03 2.055976E+02 - 3.070008E+01 4 2 1.462307E+04 2.013314E+01 - 3.070008E+01 4 4 2.707660E+05 6.559805E+01 - 3.070008E+01 5 1 -1.038508E+04 5.641356E+01 - 3.070008E+01 5 5 8.270776E+05 5.865265E+02 - 3.070008E+01 6 6 9.102575E+05 1.220172E+01 - 3.080008E+01 1 1 2.019276E+03 5.396836E+00 - 3.080008E+01 1 5 -1.036728E+04 5.615812E+01 - 3.080008E+01 2 2 2.291559E+03 6.110959E+00 - 3.080008E+01 2 4 1.460588E+04 1.990582E+01 - 3.080008E+01 3 3 2.274016E+03 2.056712E+02 - 3.080008E+01 4 2 1.462238E+04 1.997769E+01 - 3.080008E+01 4 4 2.707626E+05 6.506673E+01 - 3.080008E+01 5 1 -1.038507E+04 5.602548E+01 - 3.080008E+01 5 5 8.270770E+05 5.828536E+02 - 3.080008E+01 6 6 9.102211E+05 1.201544E+01 - 3.090008E+01 1 1 2.019156E+03 5.356817E+00 - 3.090008E+01 1 5 -1.036729E+04 5.577095E+01 - 3.090008E+01 2 2 2.291398E+03 6.064867E+00 - 3.090008E+01 2 4 1.460524E+04 1.975068E+01 - 3.090008E+01 3 3 2.274535E+03 2.057437E+02 - 3.090008E+01 4 2 1.462171E+04 1.982124E+01 - 3.090008E+01 4 4 2.707598E+05 6.454514E+01 - 3.090008E+01 5 1 -1.038501E+04 5.563477E+01 - 3.090008E+01 5 5 8.270751E+05 5.790355E+02 - 3.090008E+01 6 6 9.101829E+05 1.183959E+01 - 3.100008E+01 1 1 2.019033E+03 5.317164E+00 - 3.100008E+01 1 5 -1.036725E+04 5.538704E+01 - 3.100008E+01 2 2 2.291246E+03 6.019514E+00 - 3.100008E+01 2 4 1.460456E+04 1.959860E+01 - 3.100008E+01 3 3 2.275073E+03 2.058216E+02 - 3.100008E+01 4 2 1.462105E+04 1.966796E+01 - 3.100008E+01 4 4 2.707573E+05 6.404614E+01 - 3.100008E+01 5 1 -1.038495E+04 5.525334E+01 - 3.100008E+01 5 5 8.270769E+05 5.755447E+02 - 3.100008E+01 6 6 9.101450E+05 1.168376E+01 - 3.110008E+01 1 1 2.018913E+03 5.277853E+00 - 3.110008E+01 1 5 -1.036723E+04 5.500767E+01 - 3.110008E+01 2 2 2.291091E+03 5.974467E+00 - 3.110008E+01 2 4 1.460391E+04 1.944839E+01 - 3.110008E+01 3 3 2.275623E+03 2.058917E+02 - 3.110008E+01 4 2 1.462045E+04 1.951746E+01 - 3.110008E+01 4 4 2.707550E+05 6.353241E+01 - 3.110008E+01 5 1 -1.038495E+04 5.487522E+01 - 3.110008E+01 5 5 8.270759E+05 5.717247E+02 - 3.110008E+01 6 6 9.101077E+05 1.152268E+01 - 3.120008E+01 1 1 2.018791E+03 5.239028E+00 - 3.120008E+01 1 5 -1.036722E+04 5.463159E+01 - 3.120008E+01 2 2 2.290933E+03 5.930074E+00 - 3.120008E+01 2 4 1.460327E+04 1.929932E+01 - 3.120008E+01 3 3 2.276146E+03 2.059699E+02 - 3.120008E+01 4 2 1.461975E+04 1.936892E+01 - 3.120008E+01 4 4 2.707526E+05 6.303081E+01 - 3.120008E+01 5 1 -1.038495E+04 5.449835E+01 - 3.120008E+01 5 5 8.270733E+05 5.683505E+02 - 3.120008E+01 6 6 9.100716E+05 1.135478E+01 - 3.130008E+01 1 1 2.018671E+03 5.200728E+00 - 3.130008E+01 1 5 -1.036720E+04 5.426095E+01 - 3.130008E+01 2 2 2.290780E+03 5.886132E+00 - 3.130008E+01 2 4 1.460259E+04 1.915292E+01 - 3.130008E+01 3 3 2.276664E+03 2.060374E+02 - 3.130008E+01 4 2 1.461911E+04 1.922163E+01 - 3.130008E+01 4 4 2.707492E+05 6.254450E+01 - 3.130008E+01 5 1 -1.038491E+04 5.413215E+01 - 3.130008E+01 5 5 8.270704E+05 5.646052E+02 - 3.130008E+01 6 6 9.100346E+05 1.118837E+01 - 3.140008E+01 1 1 2.018555E+03 5.162685E+00 - 3.140008E+01 1 5 -1.036716E+04 5.389315E+01 - 3.140008E+01 2 2 2.290628E+03 5.842745E+00 - 3.140008E+01 2 4 1.460196E+04 1.900646E+01 - 3.140008E+01 3 3 2.277192E+03 2.061052E+02 - 3.140008E+01 4 2 1.461847E+04 1.907387E+01 - 3.140008E+01 4 4 2.707464E+05 6.204185E+01 - 3.140008E+01 5 1 -1.038491E+04 5.376302E+01 - 3.140008E+01 5 5 8.270689E+05 5.611432E+02 - 3.140008E+01 6 6 9.100006E+05 1.101737E+01 - 3.150008E+01 1 1 2.018440E+03 5.125191E+00 - 3.150008E+01 1 5 -1.036712E+04 5.352942E+01 - 3.150008E+01 2 2 2.290478E+03 5.799845E+00 - 3.150008E+01 2 4 1.460136E+04 1.886304E+01 - 3.150008E+01 3 3 2.277707E+03 2.061735E+02 - 3.150008E+01 4 2 1.461787E+04 1.893100E+01 - 3.150008E+01 4 4 2.707439E+05 6.156284E+01 - 3.150008E+01 5 1 -1.038488E+04 5.339945E+01 - 3.150008E+01 5 5 8.270657E+05 5.576572E+02 - 3.150008E+01 6 6 9.099652E+05 1.087240E+01 - 3.160008E+01 1 1 2.018327E+03 5.088073E+00 - 3.160008E+01 1 5 -1.036709E+04 5.316983E+01 - 3.160008E+01 2 2 2.290333E+03 5.757326E+00 - 3.160008E+01 2 4 1.460073E+04 1.872107E+01 - 3.160008E+01 3 3 2.278215E+03 2.062425E+02 - 3.160008E+01 4 2 1.461724E+04 1.878803E+01 - 3.160008E+01 4 4 2.707412E+05 6.109447E+01 - 3.160008E+01 5 1 -1.038488E+04 5.304378E+01 - 3.160008E+01 5 5 8.270635E+05 5.541365E+02 - 3.160008E+01 6 6 9.099310E+05 1.072399E+01 - 3.170008E+01 1 1 2.018213E+03 5.051478E+00 - 3.170008E+01 1 5 -1.036707E+04 5.281169E+01 - 3.170008E+01 2 2 2.290188E+03 5.715494E+00 - 3.170008E+01 2 4 1.460011E+04 1.858160E+01 - 3.170008E+01 3 3 2.278729E+03 2.063118E+02 - 3.170008E+01 4 2 1.461665E+04 1.864968E+01 - 3.170008E+01 4 4 2.707382E+05 6.062715E+01 - 3.170008E+01 5 1 -1.038485E+04 5.268708E+01 - 3.170008E+01 5 5 8.270635E+05 5.507777E+02 - 3.170008E+01 6 6 9.098956E+05 1.056697E+01 - 3.180009E+01 1 1 2.018096E+03 5.015356E+00 - 3.180009E+01 1 5 -1.036704E+04 5.246017E+01 - 3.180009E+01 2 2 2.290042E+03 5.674034E+00 - 3.180009E+01 2 4 1.459948E+04 1.844287E+01 - 3.180009E+01 3 3 2.279241E+03 2.063776E+02 - 3.180009E+01 4 2 1.461601E+04 1.850991E+01 - 3.180009E+01 4 4 2.707358E+05 6.015704E+01 - 3.180009E+01 5 1 -1.038482E+04 5.233337E+01 - 3.180009E+01 5 5 8.270618E+05 5.472370E+02 - 3.180009E+01 6 6 9.098625E+05 1.042886E+01 - 3.190009E+01 1 1 2.017987E+03 4.979373E+00 - 3.190009E+01 1 5 -1.036703E+04 5.211030E+01 - 3.190009E+01 2 2 2.289895E+03 5.632864E+00 - 3.190009E+01 2 4 1.459887E+04 1.830628E+01 - 3.190009E+01 3 3 2.279764E+03 2.064400E+02 - 3.190009E+01 4 2 1.461540E+04 1.837126E+01 - 3.190009E+01 4 4 2.707333E+05 5.970638E+01 - 3.190009E+01 5 1 -1.038481E+04 5.198465E+01 - 3.190009E+01 5 5 8.270599E+05 5.440458E+02 - 3.190009E+01 6 6 9.098271E+05 1.028428E+01 - 3.200008E+01 1 1 2.017874E+03 4.943982E+00 - 3.200008E+01 1 5 -1.036702E+04 5.176426E+01 - 3.200008E+01 2 2 2.289757E+03 5.592231E+00 - 3.200008E+01 2 4 1.459829E+04 1.817052E+01 - 3.200008E+01 3 3 2.280292E+03 2.065081E+02 - 3.200008E+01 4 2 1.461478E+04 1.823516E+01 - 3.200008E+01 4 4 2.707302E+05 5.924137E+01 - 3.200008E+01 5 1 -1.038482E+04 5.163935E+01 - 3.200008E+01 5 5 8.270562E+05 5.406495E+02 - 3.200008E+01 6 6 9.097942E+05 1.014167E+01 - 3.210008E+01 1 1 2.017764E+03 4.908949E+00 - 3.210008E+01 1 5 -1.036700E+04 5.142149E+01 - 3.210008E+01 2 2 2.289612E+03 5.552336E+00 - 3.210008E+01 2 4 1.459767E+04 1.803678E+01 - 3.210008E+01 3 3 2.280788E+03 2.065727E+02 - 3.210008E+01 4 2 1.461417E+04 1.810139E+01 - 3.210008E+01 4 4 2.707278E+05 5.879571E+01 - 3.210008E+01 5 1 -1.038478E+04 5.129827E+01 - 3.210008E+01 5 5 8.270566E+05 5.372954E+02 - 3.210008E+01 6 6 9.097607E+05 1.001906E+01 - 3.220008E+01 1 1 2.017659E+03 4.874296E+00 - 3.220008E+01 1 5 -1.036699E+04 5.108210E+01 - 3.220008E+01 2 2 2.289474E+03 5.512514E+00 - 3.220008E+01 2 4 1.459714E+04 1.790340E+01 - 3.220008E+01 3 3 2.281296E+03 2.066397E+02 - 3.220008E+01 4 2 1.461361E+04 1.796741E+01 - 3.220008E+01 4 4 2.707253E+05 5.835419E+01 - 3.220008E+01 5 1 -1.038477E+04 5.096151E+01 - 3.220008E+01 5 5 8.270564E+05 5.340329E+02 - 3.220008E+01 6 6 9.097281E+05 9.872394E+00 - 3.230008E+01 1 1 2.017551E+03 4.839922E+00 - 3.230008E+01 1 5 -1.036698E+04 5.074788E+01 - 3.230008E+01 2 2 2.289334E+03 5.473316E+00 - 3.230008E+01 2 4 1.459653E+04 1.777277E+01 - 3.230008E+01 3 3 2.281800E+03 2.067076E+02 - 3.230008E+01 4 2 1.461301E+04 1.783599E+01 - 3.230008E+01 4 4 2.707227E+05 5.790337E+01 - 3.230008E+01 5 1 -1.038477E+04 5.062877E+01 - 3.230008E+01 5 5 8.270556E+05 5.307462E+02 - 3.230008E+01 6 6 9.096941E+05 9.739921E+00 - 3.240008E+01 1 1 2.017437E+03 4.805939E+00 - 3.240008E+01 1 5 -1.036695E+04 5.041497E+01 - 3.240008E+01 2 2 2.289196E+03 5.434473E+00 - 3.240008E+01 2 4 1.459595E+04 1.764435E+01 - 3.240008E+01 3 3 2.282287E+03 2.067744E+02 - 3.240008E+01 4 2 1.461248E+04 1.770653E+01 - 3.240008E+01 4 4 2.707203E+05 5.750328E+01 - 3.240008E+01 5 1 -1.038471E+04 5.029712E+01 - 3.240008E+01 5 5 8.270545E+05 5.275226E+02 - 3.240008E+01 6 6 9.096628E+05 9.595244E+00 - 3.250008E+01 1 1 2.017340E+03 4.772391E+00 - 3.250008E+01 1 5 -1.036696E+04 5.008792E+01 - 3.250008E+01 2 2 2.289060E+03 5.396129E+00 - 3.250008E+01 2 4 1.459537E+04 1.751562E+01 - 3.250008E+01 3 3 2.282792E+03 2.068363E+02 - 3.250008E+01 4 2 1.461189E+04 1.757891E+01 - 3.250008E+01 4 4 2.707179E+05 5.705292E+01 - 3.250008E+01 5 1 -1.038473E+04 4.996671E+01 - 3.250008E+01 5 5 8.270538E+05 5.243102E+02 - 3.250008E+01 6 6 9.096309E+05 9.462701E+00 - 3.260007E+01 1 1 2.017234E+03 4.739207E+00 - 3.260007E+01 1 5 -1.036696E+04 4.976168E+01 - 3.260007E+01 2 2 2.288923E+03 5.358119E+00 - 3.260007E+01 2 4 1.459480E+04 1.738945E+01 - 3.260007E+01 3 3 2.283295E+03 2.068985E+02 - 3.260007E+01 4 2 1.461133E+04 1.745126E+01 - 3.260007E+01 4 4 2.707153E+05 5.663148E+01 - 3.260007E+01 5 1 -1.038470E+04 4.964454E+01 - 3.260007E+01 5 5 8.270504E+05 5.211184E+02 - 3.260007E+01 6 6 9.095991E+05 9.349185E+00 - 3.270007E+01 1 1 2.017130E+03 4.706257E+00 - 3.270007E+01 1 5 -1.036695E+04 4.943787E+01 - 3.270007E+01 2 2 2.288792E+03 5.320659E+00 - 3.270007E+01 2 4 1.459423E+04 1.726386E+01 - 3.270007E+01 3 3 2.283775E+03 2.069594E+02 - 3.270007E+01 4 2 1.461072E+04 1.732748E+01 - 3.270007E+01 4 4 2.707130E+05 5.620590E+01 - 3.270007E+01 5 1 -1.038468E+04 4.932141E+01 - 3.270007E+01 5 5 8.270479E+05 5.179899E+02 - 3.270007E+01 6 6 9.095683E+05 9.226877E+00 - 3.280007E+01 1 1 2.017021E+03 4.673912E+00 - 3.280007E+01 1 5 -1.036695E+04 4.911926E+01 - 3.280007E+01 2 2 2.288657E+03 5.283504E+00 - 3.280007E+01 2 4 1.459371E+04 1.714091E+01 - 3.280007E+01 3 3 2.284278E+03 2.070224E+02 - 3.280007E+01 4 2 1.461020E+04 1.720206E+01 - 3.280007E+01 4 4 2.707109E+05 5.580116E+01 - 3.280007E+01 5 1 -1.038467E+04 4.900334E+01 - 3.280007E+01 5 5 8.270487E+05 5.147988E+02 - 3.280007E+01 6 6 9.095362E+05 9.102610E+00 - 3.290007E+01 1 1 2.016920E+03 4.641672E+00 - 3.290007E+01 1 5 -1.036695E+04 4.880312E+01 - 3.290007E+01 2 2 2.288530E+03 5.246795E+00 - 3.290007E+01 2 4 1.459318E+04 1.701746E+01 - 3.290007E+01 3 3 2.284770E+03 2.070830E+02 - 3.290007E+01 4 2 1.460967E+04 1.707979E+01 - 3.290007E+01 4 4 2.707084E+05 5.538412E+01 - 3.290007E+01 5 1 -1.038466E+04 4.868804E+01 - 3.290007E+01 5 5 8.270472E+05 5.117176E+02 - 3.290007E+01 6 6 9.095062E+05 8.964191E+00 - 3.300007E+01 1 1 2.016823E+03 4.609921E+00 - 3.300007E+01 1 5 -1.036692E+04 4.849102E+01 - 3.300007E+01 2 2 2.288396E+03 5.210488E+00 - 3.300007E+01 2 4 1.459259E+04 1.689742E+01 - 3.300007E+01 3 3 2.285267E+03 2.071416E+02 - 3.300007E+01 4 2 1.460912E+04 1.695896E+01 - 3.300007E+01 4 4 2.707057E+05 5.499294E+01 - 3.300007E+01 5 1 -1.038465E+04 4.837271E+01 - 3.300007E+01 5 5 8.270472E+05 5.086148E+02 - 3.300007E+01 6 6 9.094754E+05 8.860820E+00 - 3.310007E+01 1 1 2.016723E+03 4.578347E+00 - 3.310007E+01 1 5 -1.036692E+04 4.818066E+01 - 3.310007E+01 2 2 2.288265E+03 5.174525E+00 - 3.310007E+01 2 4 1.459206E+04 1.677721E+01 - 3.310007E+01 3 3 2.285750E+03 2.072039E+02 - 3.310007E+01 4 2 1.460856E+04 1.683876E+01 - 3.310007E+01 4 4 2.707030E+05 5.458032E+01 - 3.310007E+01 5 1 -1.038462E+04 4.806683E+01 - 3.310007E+01 5 5 8.270457E+05 5.056040E+02 - 3.310007E+01 6 6 9.094449E+05 8.742088E+00 - 3.320007E+01 1 1 2.016624E+03 4.547227E+00 - 3.320007E+01 1 5 -1.036691E+04 4.787306E+01 - 3.320007E+01 2 2 2.288140E+03 5.138874E+00 - 3.320007E+01 2 4 1.459153E+04 1.665984E+01 - 3.320007E+01 3 3 2.286236E+03 2.072601E+02 - 3.320007E+01 4 2 1.460801E+04 1.671791E+01 - 3.320007E+01 4 4 2.707005E+05 5.419601E+01 - 3.320007E+01 5 1 -1.038464E+04 4.775983E+01 - 3.320007E+01 5 5 8.270449E+05 5.025326E+02 - 3.320007E+01 6 6 9.094157E+05 8.613149E+00 - 3.330006E+01 1 1 2.016520E+03 4.516479E+00 - 3.330006E+01 1 5 -1.036689E+04 4.756926E+01 - 3.330006E+01 2 2 2.288014E+03 5.103774E+00 - 3.330006E+01 2 4 1.459101E+04 1.654124E+01 - 3.330006E+01 3 3 2.286714E+03 2.073202E+02 - 3.330006E+01 4 2 1.460747E+04 1.660173E+01 - 3.330006E+01 4 4 2.706984E+05 5.380000E+01 - 3.330006E+01 5 1 -1.038461E+04 4.745464E+01 - 3.330006E+01 5 5 8.270425E+05 4.996131E+02 - 3.330006E+01 6 6 9.093857E+05 8.524786E+00 - 3.340006E+01 1 1 2.016426E+03 4.485881E+00 - 3.340006E+01 1 5 -1.036688E+04 4.726738E+01 - 3.340006E+01 2 2 2.287889E+03 5.068748E+00 - 3.340006E+01 2 4 1.459050E+04 1.642647E+01 - 3.340006E+01 3 3 2.287211E+03 2.073812E+02 - 3.340006E+01 4 2 1.460694E+04 1.648383E+01 - 3.340006E+01 4 4 2.706957E+05 5.341031E+01 - 3.340006E+01 5 1 -1.038461E+04 4.715745E+01 - 3.340006E+01 5 5 8.270424E+05 4.966593E+02 - 3.340006E+01 6 6 9.093561E+05 8.395782E+00 - 3.350006E+01 1 1 2.016330E+03 4.455670E+00 - 3.350006E+01 1 5 -1.036687E+04 4.696966E+01 - 3.350006E+01 2 2 2.287764E+03 5.034426E+00 - 3.350006E+01 2 4 1.458995E+04 1.631194E+01 - 3.350006E+01 3 3 2.287693E+03 2.074359E+02 - 3.350006E+01 4 2 1.460639E+04 1.636994E+01 - 3.350006E+01 4 4 2.706933E+05 5.303030E+01 - 3.350006E+01 5 1 -1.038459E+04 4.685500E+01 - 3.350006E+01 5 5 8.270410E+05 4.938537E+02 - 3.350006E+01 6 6 9.093272E+05 8.291888E+00 - 3.360006E+01 1 1 2.016233E+03 4.425919E+00 - 3.360006E+01 1 5 -1.036687E+04 4.667384E+01 - 3.360006E+01 2 2 2.287640E+03 5.000275E+00 - 3.360006E+01 2 4 1.458945E+04 1.619874E+01 - 3.360006E+01 3 3 2.288165E+03 2.074917E+02 - 3.360006E+01 4 2 1.460593E+04 1.625585E+01 - 3.360006E+01 4 4 2.706908E+05 5.266426E+01 - 3.360006E+01 5 1 -1.038460E+04 4.656364E+01 - 3.360006E+01 5 5 8.270392E+05 4.909771E+02 - 3.360006E+01 6 6 9.092985E+05 8.204824E+00 - 3.370006E+01 1 1 2.016138E+03 4.396338E+00 - 3.370006E+01 1 5 -1.036684E+04 4.638142E+01 - 3.370006E+01 2 2 2.287520E+03 4.966541E+00 - 3.370006E+01 2 4 1.458894E+04 1.608651E+01 - 3.370006E+01 3 3 2.288650E+03 2.075475E+02 - 3.370006E+01 4 2 1.460541E+04 1.614312E+01 - 3.370006E+01 4 4 2.706893E+05 5.229510E+01 - 3.370006E+01 5 1 -1.038457E+04 4.627055E+01 - 3.370006E+01 5 5 8.270355E+05 4.880962E+02 - 3.370006E+01 6 6 9.092703E+05 8.084464E+00 - 3.380006E+01 1 1 2.016045E+03 4.367103E+00 - 3.380006E+01 1 5 -1.036684E+04 4.609216E+01 - 3.380006E+01 2 2 2.287403E+03 4.933120E+00 - 3.380006E+01 2 4 1.458843E+04 1.597518E+01 - 3.380006E+01 3 3 2.289120E+03 2.076039E+02 - 3.380006E+01 4 2 1.460491E+04 1.603291E+01 - 3.380006E+01 4 4 2.706877E+05 5.190708E+01 - 3.380006E+01 5 1 -1.038455E+04 4.598060E+01 - 3.380006E+01 5 5 8.270350E+05 4.853094E+02 - 3.380006E+01 6 6 9.092412E+05 7.976162E+00 - 3.390005E+01 1 1 2.015949E+03 4.338196E+00 - 3.390005E+01 1 5 -1.036685E+04 4.580481E+01 - 3.390005E+01 2 2 2.287287E+03 4.900265E+00 - 3.390005E+01 2 4 1.458795E+04 1.586637E+01 - 3.390005E+01 3 3 2.289604E+03 2.076568E+02 - 3.390005E+01 4 2 1.460442E+04 1.592403E+01 - 3.390005E+01 4 4 2.706852E+05 5.156547E+01 - 3.390005E+01 5 1 -1.038453E+04 4.569720E+01 - 3.390005E+01 5 5 8.270338E+05 4.825604E+02 - 3.390005E+01 6 6 9.092121E+05 7.871105E+00 - 3.400005E+01 1 1 2.015856E+03 4.309593E+00 - 3.400005E+01 1 5 -1.036685E+04 4.552005E+01 - 3.400005E+01 2 2 2.287164E+03 4.867426E+00 - 3.400005E+01 2 4 1.458746E+04 1.575765E+01 - 3.400005E+01 3 3 2.290076E+03 2.077110E+02 - 3.400005E+01 4 2 1.460389E+04 1.581393E+01 - 3.400005E+01 4 4 2.706827E+05 5.119024E+01 - 3.400005E+01 5 1 -1.038452E+04 4.541109E+01 - 3.400005E+01 5 5 8.270326E+05 4.797548E+02 - 3.400005E+01 6 6 9.091851E+05 7.758340E+00 - 3.410005E+01 1 1 2.015768E+03 4.281193E+00 - 3.410005E+01 1 5 -1.036686E+04 4.523862E+01 - 3.410005E+01 2 2 2.287047E+03 4.835074E+00 - 3.410005E+01 2 4 1.458695E+04 1.565111E+01 - 3.410005E+01 3 3 2.290538E+03 2.077658E+02 - 3.410005E+01 4 2 1.460339E+04 1.570616E+01 - 3.410005E+01 4 4 2.706812E+05 5.084045E+01 - 3.410005E+01 5 1 -1.038454E+04 4.513220E+01 - 3.410005E+01 5 5 8.270311E+05 4.770114E+02 - 3.410005E+01 6 6 9.091584E+05 7.683731E+00 - 3.420005E+01 1 1 2.015675E+03 4.253048E+00 - 3.420005E+01 1 5 -1.036686E+04 4.495928E+01 - 3.420005E+01 2 2 2.286929E+03 4.803030E+00 - 3.420005E+01 2 4 1.458647E+04 1.554398E+01 - 3.420005E+01 3 3 2.291025E+03 2.078207E+02 - 3.420005E+01 4 2 1.460291E+04 1.560094E+01 - 3.420005E+01 4 4 2.706788E+05 5.048122E+01 - 3.420005E+01 5 1 -1.038451E+04 4.485680E+01 - 3.420005E+01 5 5 8.270290E+05 4.742709E+02 - 3.420005E+01 6 6 9.091312E+05 7.576797E+00 - 3.430005E+01 1 1 2.015585E+03 4.225290E+00 - 3.430005E+01 1 5 -1.036684E+04 4.468171E+01 - 3.430005E+01 2 2 2.286815E+03 4.771332E+00 - 3.430005E+01 2 4 1.458599E+04 1.543985E+01 - 3.430005E+01 3 3 2.291477E+03 2.078787E+02 - 3.430005E+01 4 2 1.460240E+04 1.549469E+01 - 3.430005E+01 4 4 2.706766E+05 5.015277E+01 - 3.430005E+01 5 1 -1.038451E+04 4.457838E+01 - 3.430005E+01 5 5 8.270272E+05 4.715522E+02 - 3.430005E+01 6 6 9.091040E+05 7.477554E+00 - 3.440005E+01 1 1 2.015496E+03 4.197728E+00 - 3.440005E+01 1 5 -1.036685E+04 4.440840E+01 - 3.440005E+01 2 2 2.286698E+03 4.739777E+00 - 3.440005E+01 2 4 1.458552E+04 1.533499E+01 - 3.440005E+01 3 3 2.291962E+03 2.079289E+02 - 3.440005E+01 4 2 1.460196E+04 1.538827E+01 - 3.440005E+01 4 4 2.706739E+05 4.978912E+01 - 3.440005E+01 5 1 -1.038449E+04 4.430622E+01 - 3.440005E+01 5 5 8.270241E+05 4.688404E+02 - 3.440005E+01 6 6 9.090772E+05 7.395940E+00 - 3.450005E+01 1 1 2.015405E+03 4.170412E+00 - 3.450005E+01 1 5 -1.036687E+04 4.413768E+01 - 3.450005E+01 2 2 2.286585E+03 4.708874E+00 - 3.450005E+01 2 4 1.458503E+04 1.523254E+01 - 3.450005E+01 3 3 2.292417E+03 2.079803E+02 - 3.450005E+01 4 2 1.460149E+04 1.528508E+01 - 3.450005E+01 4 4 2.706719E+05 4.945317E+01 - 3.450005E+01 5 1 -1.038447E+04 4.403661E+01 - 3.450005E+01 5 5 8.270231E+05 4.661466E+02 - 3.450005E+01 6 6 9.090508E+05 7.301067E+00 - 3.460004E+01 1 1 2.015315E+03 4.143480E+00 - 3.460004E+01 1 5 -1.036686E+04 4.386974E+01 - 3.460004E+01 2 2 2.286471E+03 4.678228E+00 - 3.460004E+01 2 4 1.458455E+04 1.513015E+01 - 3.460004E+01 3 3 2.292882E+03 2.080340E+02 - 3.460004E+01 4 2 1.460100E+04 1.518415E+01 - 3.460004E+01 4 4 2.706701E+05 4.910672E+01 - 3.460004E+01 5 1 -1.038452E+04 4.376566E+01 - 3.460004E+01 5 5 8.270216E+05 4.635054E+02 - 3.460004E+01 6 6 9.090237E+05 7.195186E+00 - 3.470004E+01 1 1 2.015227E+03 4.116714E+00 - 3.470004E+01 1 5 -1.036687E+04 4.360286E+01 - 3.470004E+01 2 2 2.286358E+03 4.647609E+00 - 3.470004E+01 2 4 1.458411E+04 1.502911E+01 - 3.470004E+01 3 3 2.293344E+03 2.080855E+02 - 3.470004E+01 4 2 1.460052E+04 1.508169E+01 - 3.470004E+01 4 4 2.706681E+05 4.875842E+01 - 3.470004E+01 5 1 -1.038448E+04 4.350167E+01 - 3.470004E+01 5 5 8.270191E+05 4.608852E+02 - 3.470004E+01 6 6 9.089982E+05 7.106136E+00 - 3.480004E+01 1 1 2.015142E+03 4.090320E+00 - 3.480004E+01 1 5 -1.036687E+04 4.333912E+01 - 3.480004E+01 2 2 2.286249E+03 4.617640E+00 - 3.480004E+01 2 4 1.458365E+04 1.492969E+01 - 3.480004E+01 3 3 2.293805E+03 2.081361E+02 - 3.480004E+01 4 2 1.460007E+04 1.498302E+01 - 3.480004E+01 4 4 2.706668E+05 4.842900E+01 - 3.480004E+01 5 1 -1.038448E+04 4.323824E+01 - 3.480004E+01 5 5 8.270191E+05 4.582971E+02 - 3.480004E+01 6 6 9.089728E+05 7.022690E+00 - 3.490004E+01 1 1 2.015057E+03 4.064059E+00 - 3.490004E+01 1 5 -1.036686E+04 4.307823E+01 - 3.490004E+01 2 2 2.286138E+03 4.587818E+00 - 3.490004E+01 2 4 1.458317E+04 1.483146E+01 - 3.490004E+01 3 3 2.294267E+03 2.081891E+02 - 3.490004E+01 4 2 1.459957E+04 1.488393E+01 - 3.490004E+01 4 4 2.706646E+05 4.811267E+01 - 3.490004E+01 5 1 -1.038453E+04 4.297769E+01 - 3.490004E+01 5 5 8.270183E+05 4.556540E+02 - 3.490004E+01 6 6 9.089462E+05 6.917991E+00 - 3.500004E+01 1 1 2.014974E+03 4.038242E+00 - 3.500004E+01 1 5 -1.036686E+04 4.281962E+01 - 3.500004E+01 2 2 2.286031E+03 4.558277E+00 - 3.500004E+01 2 4 1.458272E+04 1.473320E+01 - 3.500004E+01 3 3 2.294720E+03 2.082394E+02 - 3.500004E+01 4 2 1.459917E+04 1.478656E+01 - 3.500004E+01 4 4 2.706616E+05 4.778054E+01 - 3.500004E+01 5 1 -1.038451E+04 4.272221E+01 - 3.500004E+01 5 5 8.270163E+05 4.531314E+02 - 3.500004E+01 6 6 9.089202E+05 6.880600E+00 - 3.510004E+01 1 1 2.014890E+03 4.012558E+00 - 3.510004E+01 1 5 -1.036687E+04 4.256192E+01 - 3.510004E+01 2 2 2.285925E+03 4.529027E+00 - 3.510004E+01 2 4 1.458226E+04 1.463627E+01 - 3.510004E+01 3 3 2.295181E+03 2.082935E+02 - 3.510004E+01 4 2 1.459873E+04 1.468997E+01 - 3.510004E+01 4 4 2.706599E+05 4.745867E+01 - 3.510004E+01 5 1 -1.038449E+04 4.246300E+01 - 3.510004E+01 5 5 8.270154E+05 4.506443E+02 - 3.510004E+01 6 6 9.088964E+05 6.768374E+00 - 3.520004E+01 1 1 2.014806E+03 3.987145E+00 - 3.520004E+01 1 5 -1.036688E+04 4.230813E+01 - 3.520004E+01 2 2 2.285819E+03 4.500180E+00 - 3.520004E+01 2 4 1.458183E+04 1.454078E+01 - 3.520004E+01 3 3 2.295638E+03 2.083421E+02 - 3.520004E+01 4 2 1.459829E+04 1.459465E+01 - 3.520004E+01 4 4 2.706578E+05 4.714349E+01 - 3.520004E+01 5 1 -1.038453E+04 4.221143E+01 - 3.520004E+01 5 5 8.270118E+05 4.480451E+02 - 3.520004E+01 6 6 9.088716E+05 6.701797E+00 - 3.530003E+01 1 1 2.014721E+03 3.961967E+00 - 3.530003E+01 1 5 -1.036688E+04 4.205690E+01 - 3.530003E+01 2 2 2.285710E+03 4.471429E+00 - 3.530003E+01 2 4 1.458140E+04 1.444557E+01 - 3.530003E+01 3 3 2.296075E+03 2.083899E+02 - 3.530003E+01 4 2 1.459782E+04 1.449875E+01 - 3.530003E+01 4 4 2.706565E+05 4.682458E+01 - 3.530003E+01 5 1 -1.038452E+04 4.196109E+01 - 3.530003E+01 5 5 8.270114E+05 4.454631E+02 - 3.530003E+01 6 6 9.088451E+05 6.628009E+00 - 3.540003E+01 1 1 2.014641E+03 3.937112E+00 - 3.540003E+01 1 5 -1.036688E+04 4.180603E+01 - 3.540003E+01 2 2 2.285606E+03 4.443066E+00 - 3.540003E+01 2 4 1.458094E+04 1.435173E+01 - 3.540003E+01 3 3 2.296527E+03 2.084387E+02 - 3.540003E+01 4 2 1.459735E+04 1.440475E+01 - 3.540003E+01 4 4 2.706543E+05 4.650591E+01 - 3.540003E+01 5 1 -1.038454E+04 4.170706E+01 - 3.540003E+01 5 5 8.270109E+05 4.429214E+02 - 3.540003E+01 6 6 9.088219E+05 6.531374E+00 - 3.550003E+01 1 1 2.014556E+03 3.912279E+00 - 3.550003E+01 1 5 -1.036689E+04 4.155991E+01 - 3.550003E+01 2 2 2.285500E+03 4.415036E+00 - 3.550003E+01 2 4 1.458051E+04 1.425879E+01 - 3.550003E+01 3 3 2.296977E+03 2.084841E+02 - 3.550003E+01 4 2 1.459695E+04 1.431260E+01 - 3.550003E+01 4 4 2.706526E+05 4.621085E+01 - 3.550003E+01 5 1 -1.038454E+04 4.146176E+01 - 3.550003E+01 5 5 8.270087E+05 4.403772E+02 - 3.550003E+01 6 6 9.087980E+05 6.446043E+00 - 3.560003E+01 1 1 2.014475E+03 3.887846E+00 - 3.560003E+01 1 5 -1.036690E+04 4.131449E+01 - 3.560003E+01 2 2 2.285396E+03 4.387096E+00 - 3.560003E+01 2 4 1.458007E+04 1.416779E+01 - 3.560003E+01 3 3 2.297422E+03 2.085316E+02 - 3.560003E+01 4 2 1.459651E+04 1.421849E+01 - 3.560003E+01 4 4 2.706507E+05 4.590120E+01 - 3.560003E+01 5 1 -1.038455E+04 4.121673E+01 - 3.560003E+01 5 5 8.270053E+05 4.379384E+02 - 3.560003E+01 6 6 9.087743E+05 6.395988E+00 - 3.570003E+01 1 1 2.014398E+03 3.863588E+00 - 3.570003E+01 1 5 -1.036689E+04 4.107110E+01 - 3.570003E+01 2 2 2.285297E+03 4.359519E+00 - 3.570003E+01 2 4 1.457967E+04 1.407619E+01 - 3.570003E+01 3 3 2.297862E+03 2.085768E+02 - 3.570003E+01 4 2 1.459609E+04 1.412744E+01 - 3.570003E+01 4 4 2.706492E+05 4.560065E+01 - 3.570003E+01 5 1 -1.038456E+04 4.097281E+01 - 3.570003E+01 5 5 8.270068E+05 4.355299E+02 - 3.570003E+01 6 6 9.087491E+05 6.296206E+00 - 3.580003E+01 1 1 2.014319E+03 3.839559E+00 - 3.580003E+01 1 5 -1.036694E+04 4.082942E+01 - 3.580003E+01 2 2 2.285198E+03 4.332125E+00 - 3.580003E+01 2 4 1.457925E+04 1.398566E+01 - 3.580003E+01 3 3 2.298314E+03 2.086242E+02 - 3.580003E+01 4 2 1.459565E+04 1.403448E+01 - 3.580003E+01 4 4 2.706472E+05 4.530075E+01 - 3.580003E+01 5 1 -1.038456E+04 4.073407E+01 - 3.580003E+01 5 5 8.270059E+05 4.330670E+02 - 3.580003E+01 6 6 9.087256E+05 6.223383E+00 - 3.590002E+01 1 1 2.014238E+03 3.815865E+00 - 3.590002E+01 1 5 -1.036691E+04 4.059029E+01 - 3.590002E+01 2 2 2.285099E+03 4.305130E+00 - 3.590002E+01 2 4 1.457883E+04 1.389585E+01 - 3.590002E+01 3 3 2.298744E+03 2.086712E+02 - 3.590002E+01 4 2 1.459520E+04 1.394486E+01 - 3.590002E+01 4 4 2.706457E+05 4.501206E+01 - 3.590002E+01 5 1 -1.038456E+04 4.049460E+01 - 3.590002E+01 5 5 8.270036E+05 4.307480E+02 - 3.590002E+01 6 6 9.087024E+05 6.137192E+00 - 3.600002E+01 1 1 2.014161E+03 3.792371E+00 - 3.600002E+01 1 5 -1.036691E+04 4.035513E+01 - 3.600002E+01 2 2 2.284994E+03 4.278384E+00 - 3.600002E+01 2 4 1.457840E+04 1.380830E+01 - 3.600002E+01 3 3 2.299196E+03 2.087150E+02 - 3.600002E+01 4 2 1.459481E+04 1.385685E+01 - 3.600002E+01 4 4 2.706433E+05 4.471947E+01 - 3.600002E+01 5 1 -1.038454E+04 4.025945E+01 - 3.600002E+01 5 5 8.270007E+05 4.284082E+02 - 3.600002E+01 6 6 9.086797E+05 6.051591E+00 - 3.610002E+01 1 1 2.014086E+03 3.769116E+00 - 3.610002E+01 1 5 -1.036692E+04 4.011861E+01 - 3.610002E+01 2 2 2.284889E+03 4.251763E+00 - 3.610002E+01 2 4 1.457801E+04 1.371976E+01 - 3.610002E+01 3 3 2.299630E+03 2.087659E+02 - 3.610002E+01 4 2 1.459439E+04 1.376857E+01 - 3.610002E+01 4 4 2.706420E+05 4.443511E+01 - 3.610002E+01 5 1 -1.038457E+04 4.002705E+01 - 3.610002E+01 5 5 8.269984E+05 4.259442E+02 - 3.610002E+01 6 6 9.086563E+05 5.992987E+00 - 3.620002E+01 1 1 2.014006E+03 3.746111E+00 - 3.620002E+01 1 5 -1.036692E+04 3.988753E+01 - 3.620002E+01 2 2 2.284796E+03 4.225507E+00 - 3.620002E+01 2 4 1.457761E+04 1.363379E+01 - 3.620002E+01 3 3 2.300075E+03 2.088064E+02 - 3.620002E+01 4 2 1.459399E+04 1.368159E+01 - 3.620002E+01 4 4 2.706406E+05 4.413845E+01 - 3.620002E+01 5 1 -1.038455E+04 3.979681E+01 - 3.620002E+01 5 5 8.269968E+05 4.236597E+02 - 3.620002E+01 6 6 9.086326E+05 5.921138E+00 - 3.630002E+01 1 1 2.013929E+03 3.723092E+00 - 3.630002E+01 1 5 -1.036695E+04 3.965751E+01 - 3.630002E+01 2 2 2.284698E+03 4.199479E+00 - 3.630002E+01 2 4 1.457719E+04 1.354688E+01 - 3.630002E+01 3 3 2.300512E+03 2.088537E+02 - 3.630002E+01 4 2 1.459358E+04 1.359741E+01 - 3.630002E+01 4 4 2.706387E+05 4.384367E+01 - 3.630002E+01 5 1 -1.038454E+04 3.956541E+01 - 3.630002E+01 5 5 8.269961E+05 4.213336E+02 - 3.630002E+01 6 6 9.086108E+05 5.842680E+00 - 3.640002E+01 1 1 2.013854E+03 3.700585E+00 - 3.640002E+01 1 5 -1.036697E+04 3.942788E+01 - 3.640002E+01 2 2 2.284603E+03 4.173742E+00 - 3.640002E+01 2 4 1.457679E+04 1.346271E+01 - 3.640002E+01 3 3 2.300946E+03 2.088989E+02 - 3.640002E+01 4 2 1.459318E+04 1.351140E+01 - 3.640002E+01 4 4 2.706373E+05 4.358760E+01 - 3.640002E+01 5 1 -1.038452E+04 3.933470E+01 - 3.640002E+01 5 5 8.269940E+05 4.189568E+02 - 3.640002E+01 6 6 9.085887E+05 5.776129E+00 - 3.650002E+01 1 1 2.013779E+03 3.678185E+00 - 3.650002E+01 1 5 -1.036697E+04 3.920206E+01 - 3.650002E+01 2 2 2.284505E+03 4.148209E+00 - 3.650002E+01 2 4 1.457640E+04 1.337872E+01 - 3.650002E+01 3 3 2.301379E+03 2.089395E+02 - 3.650002E+01 4 2 1.459278E+04 1.342655E+01 - 3.650002E+01 4 4 2.706354E+05 4.330577E+01 - 3.650002E+01 5 1 -1.038458E+04 3.911081E+01 - 3.650002E+01 5 5 8.269932E+05 4.167011E+02 - 3.650002E+01 6 6 9.085653E+05 5.710447E+00 - 3.660001E+01 1 1 2.013702E+03 3.655786E+00 - 3.660001E+01 1 5 -1.036700E+04 3.897875E+01 - 3.660001E+01 2 2 2.284407E+03 4.122929E+00 - 3.660001E+01 2 4 1.457599E+04 1.329549E+01 - 3.660001E+01 3 3 2.301822E+03 2.089806E+02 - 3.660001E+01 4 2 1.459241E+04 1.334303E+01 - 3.660001E+01 4 4 2.706338E+05 4.303092E+01 - 3.660001E+01 5 1 -1.038457E+04 3.888433E+01 - 3.660001E+01 5 5 8.269909E+05 4.144677E+02 - 3.660001E+01 6 6 9.085432E+05 5.643402E+00 - 3.670001E+01 1 1 2.013626E+03 3.633783E+00 - 3.670001E+01 1 5 -1.036702E+04 3.875596E+01 - 3.670001E+01 2 2 2.284314E+03 4.097974E+00 - 3.670001E+01 2 4 1.457557E+04 1.321278E+01 - 3.670001E+01 3 3 2.302231E+03 2.090245E+02 - 3.670001E+01 4 2 1.459203E+04 1.326114E+01 - 3.670001E+01 4 4 2.706321E+05 4.275087E+01 - 3.670001E+01 5 1 -1.038457E+04 3.866187E+01 - 3.670001E+01 5 5 8.269919E+05 4.121606E+02 - 3.670001E+01 6 6 9.085218E+05 5.589066E+00 - 3.680001E+01 1 1 2.013556E+03 3.612016E+00 - 3.680001E+01 1 5 -1.036702E+04 3.853417E+01 - 3.680001E+01 2 2 2.284221E+03 4.073206E+00 - 3.680001E+01 2 4 1.457519E+04 1.313062E+01 - 3.680001E+01 3 3 2.302670E+03 2.090670E+02 - 3.680001E+01 4 2 1.459163E+04 1.317922E+01 - 3.680001E+01 4 4 2.706300E+05 4.247728E+01 - 3.680001E+01 5 1 -1.038457E+04 3.844415E+01 - 3.680001E+01 5 5 8.269908E+05 4.100852E+02 - 3.680001E+01 6 6 9.084987E+05 5.498926E+00 - 3.690001E+01 1 1 2.013482E+03 3.590358E+00 - 3.690001E+01 1 5 -1.036704E+04 3.831614E+01 - 3.690001E+01 2 2 2.284130E+03 4.048556E+00 - 3.690001E+01 2 4 1.457481E+04 1.305051E+01 - 3.690001E+01 3 3 2.303093E+03 2.091085E+02 - 3.690001E+01 4 2 1.459121E+04 1.309833E+01 - 3.690001E+01 4 4 2.706278E+05 4.222427E+01 - 3.690001E+01 5 1 -1.038462E+04 3.822642E+01 - 3.690001E+01 5 5 8.269888E+05 4.077679E+02 - 3.690001E+01 6 6 9.084771E+05 5.438470E+00 - 3.700001E+01 1 1 2.013411E+03 3.568935E+00 - 3.700001E+01 1 5 -1.036705E+04 3.809861E+01 - 3.700001E+01 2 2 2.284034E+03 4.024170E+00 - 3.700001E+01 2 4 1.457443E+04 1.296999E+01 - 3.700001E+01 3 3 2.303524E+03 2.091532E+02 - 3.700001E+01 4 2 1.459083E+04 1.301700E+01 - 3.700001E+01 4 4 2.706268E+05 4.195294E+01 - 3.700001E+01 5 1 -1.038460E+04 3.800803E+01 - 3.700001E+01 5 5 8.269881E+05 4.056193E+02 - 3.700001E+01 6 6 9.084576E+05 5.370837E+00 - 3.710001E+01 1 1 2.013341E+03 3.547757E+00 - 3.710001E+01 1 5 -1.036708E+04 3.788406E+01 - 3.710001E+01 2 2 2.283948E+03 3.999992E+00 - 3.710001E+01 2 4 1.457402E+04 1.289058E+01 - 3.710001E+01 3 3 2.303947E+03 2.091963E+02 - 3.710001E+01 4 2 1.459046E+04 1.293688E+01 - 3.710001E+01 4 4 2.706248E+05 4.168304E+01 - 3.710001E+01 5 1 -1.038466E+04 3.779264E+01 - 3.710001E+01 5 5 8.269868E+05 4.035041E+02 - 3.710001E+01 6 6 9.084366E+05 5.309042E+00 - 3.720000E+01 1 1 2.013268E+03 3.526645E+00 - 3.720000E+01 1 5 -1.036708E+04 3.767033E+01 - 3.720000E+01 2 2 2.283854E+03 3.976116E+00 - 3.720000E+01 2 4 1.457367E+04 1.281155E+01 - 3.720000E+01 3 3 2.304385E+03 2.092408E+02 - 3.720000E+01 4 2 1.459005E+04 1.285758E+01 - 3.720000E+01 4 4 2.706232E+05 4.142688E+01 - 3.720000E+01 5 1 -1.038470E+04 3.758187E+01 - 3.720000E+01 5 5 8.269874E+05 4.013394E+02 - 3.720000E+01 6 6 9.084147E+05 5.268166E+00 - 3.730000E+01 1 1 2.013203E+03 3.505867E+00 - 3.730000E+01 1 5 -1.036710E+04 3.745911E+01 - 3.730000E+01 2 2 2.283767E+03 3.952397E+00 - 3.730000E+01 2 4 1.457329E+04 1.273373E+01 - 3.730000E+01 3 3 2.304789E+03 2.092828E+02 - 3.730000E+01 4 2 1.458973E+04 1.277789E+01 - 3.730000E+01 4 4 2.706211E+05 4.117779E+01 - 3.730000E+01 5 1 -1.038467E+04 3.736903E+01 - 3.730000E+01 5 5 8.269850E+05 3.992006E+02 - 3.730000E+01 6 6 9.083945E+05 5.198104E+00 - 3.740000E+01 1 1 2.013130E+03 3.485213E+00 - 3.740000E+01 1 5 -1.036711E+04 3.724977E+01 - 3.740000E+01 2 2 2.283678E+03 3.928882E+00 - 3.740000E+01 2 4 1.457293E+04 1.265645E+01 - 3.740000E+01 3 3 2.305208E+03 2.093207E+02 - 3.740000E+01 4 2 1.458937E+04 1.270025E+01 - 3.740000E+01 4 4 2.706199E+05 4.090831E+01 - 3.740000E+01 5 1 -1.038471E+04 3.716008E+01 - 3.740000E+01 5 5 8.269840E+05 3.971006E+02 - 3.740000E+01 6 6 9.083726E+05 5.127429E+00 - 3.750000E+01 1 1 2.013062E+03 3.464626E+00 - 3.750000E+01 1 5 -1.036713E+04 3.704184E+01 - 3.750000E+01 2 2 2.283589E+03 3.905577E+00 - 3.750000E+01 2 4 1.457256E+04 1.257989E+01 - 3.750000E+01 3 3 2.305638E+03 2.093643E+02 - 3.750000E+01 4 2 1.458899E+04 1.262277E+01 - 3.750000E+01 4 4 2.706178E+05 4.067010E+01 - 3.750000E+01 5 1 -1.038468E+04 3.695582E+01 - 3.750000E+01 5 5 8.269815E+05 3.950205E+02 - 3.750000E+01 6 6 9.083530E+05 5.055467E+00 - 3.760000E+01 1 1 2.012994E+03 3.444397E+00 - 3.760000E+01 1 5 -1.036714E+04 3.683575E+01 - 3.760000E+01 2 2 2.283505E+03 3.882526E+00 - 3.760000E+01 2 4 1.457218E+04 1.250433E+01 - 3.760000E+01 3 3 2.306049E+03 2.094059E+02 - 3.760000E+01 4 2 1.458862E+04 1.254721E+01 - 3.760000E+01 4 4 2.706166E+05 4.042308E+01 - 3.760000E+01 5 1 -1.038471E+04 3.674814E+01 - 3.760000E+01 5 5 8.269804E+05 3.929808E+02 - 3.760000E+01 6 6 9.083321E+05 5.009821E+00 - 3.770000E+01 1 1 2.012924E+03 3.424435E+00 - 3.770000E+01 1 5 -1.036716E+04 3.663164E+01 - 3.770000E+01 2 2 2.283417E+03 3.859690E+00 - 3.770000E+01 2 4 1.457186E+04 1.242942E+01 - 3.770000E+01 3 3 2.306469E+03 2.094432E+02 - 3.770000E+01 4 2 1.458825E+04 1.247189E+01 - 3.770000E+01 4 4 2.706153E+05 4.017995E+01 - 3.770000E+01 5 1 -1.038473E+04 3.654385E+01 - 3.770000E+01 5 5 8.269794E+05 3.909111E+02 - 3.770000E+01 6 6 9.083129E+05 4.935872E+00 - 3.780000E+01 1 1 2.012855E+03 3.404402E+00 - 3.780000E+01 1 5 -1.036719E+04 3.642873E+01 - 3.780000E+01 2 2 2.283328E+03 3.837123E+00 - 3.780000E+01 2 4 1.457149E+04 1.235525E+01 - 3.780000E+01 3 3 2.306896E+03 2.094768E+02 - 3.780000E+01 4 2 1.458791E+04 1.239871E+01 - 3.780000E+01 4 4 2.706136E+05 3.994192E+01 - 3.780000E+01 5 1 -1.038474E+04 3.633950E+01 - 3.780000E+01 5 5 8.269797E+05 3.887933E+02 - 3.780000E+01 6 6 9.082928E+05 4.908989E+00 - 3.789999E+01 1 1 2.012790E+03 3.384700E+00 - 3.789999E+01 1 5 -1.036722E+04 3.622715E+01 - 3.789999E+01 2 2 2.283242E+03 3.814688E+00 - 3.789999E+01 2 4 1.457112E+04 1.228125E+01 - 3.789999E+01 3 3 2.307300E+03 2.095214E+02 - 3.789999E+01 4 2 1.458755E+04 1.232306E+01 - 3.789999E+01 4 4 2.706118E+05 3.969556E+01 - 3.789999E+01 5 1 -1.038474E+04 3.613874E+01 - 3.789999E+01 5 5 8.269791E+05 3.867734E+02 - 3.789999E+01 6 6 9.082722E+05 4.846871E+00 - 3.799999E+01 1 1 2.012723E+03 3.365166E+00 - 3.799999E+01 1 5 -1.036720E+04 3.602869E+01 - 3.799999E+01 2 2 2.283159E+03 3.792426E+00 - 3.799999E+01 2 4 1.457075E+04 1.220757E+01 - 3.799999E+01 3 3 2.307712E+03 2.095591E+02 - 3.799999E+01 4 2 1.458715E+04 1.225121E+01 - 3.799999E+01 4 4 2.706106E+05 3.944532E+01 - 3.799999E+01 5 1 -1.038480E+04 3.594152E+01 - 3.799999E+01 5 5 8.269774E+05 3.848085E+02 - 3.799999E+01 6 6 9.082527E+05 4.783886E+00 - 3.809999E+01 1 1 2.012658E+03 3.345552E+00 - 3.809999E+01 1 5 -1.036724E+04 3.583174E+01 - 3.809999E+01 2 2 2.283075E+03 3.770509E+00 - 3.809999E+01 2 4 1.457042E+04 1.213552E+01 - 3.809999E+01 3 3 2.308125E+03 2.095937E+02 - 3.809999E+01 4 2 1.458683E+04 1.217951E+01 - 3.809999E+01 4 4 2.706095E+05 3.921399E+01 - 3.809999E+01 5 1 -1.038483E+04 3.574688E+01 - 3.809999E+01 5 5 8.269768E+05 3.828458E+02 - 3.809999E+01 6 6 9.082335E+05 4.741799E+00 - 3.819999E+01 1 1 2.012592E+03 3.326407E+00 - 3.819999E+01 1 5 -1.036726E+04 3.563541E+01 - 3.819999E+01 2 2 2.282995E+03 3.748651E+00 - 3.819999E+01 2 4 1.457009E+04 1.206382E+01 - 3.819999E+01 3 3 2.308525E+03 2.096333E+02 - 3.819999E+01 4 2 1.458648E+04 1.210816E+01 - 3.819999E+01 4 4 2.706083E+05 3.897776E+01 - 3.819999E+01 5 1 -1.038485E+04 3.555049E+01 - 3.819999E+01 5 5 8.269772E+05 3.807567E+02 - 3.819999E+01 6 6 9.082136E+05 4.687849E+00 - 3.829999E+01 1 1 2.012526E+03 3.307404E+00 - 3.829999E+01 1 5 -1.036724E+04 3.544145E+01 - 3.829999E+01 2 2 2.282908E+03 3.726984E+00 - 3.829999E+01 2 4 1.456975E+04 1.199241E+01 - 3.829999E+01 3 3 2.308938E+03 2.096743E+02 - 3.829999E+01 4 2 1.458615E+04 1.203561E+01 - 3.829999E+01 4 4 2.706067E+05 3.873753E+01 - 3.829999E+01 5 1 -1.038487E+04 3.535653E+01 - 3.829999E+01 5 5 8.269764E+05 3.789005E+02 - 3.829999E+01 6 6 9.081937E+05 4.622365E+00 - 3.839999E+01 1 1 2.012460E+03 3.288520E+00 - 3.839999E+01 1 5 -1.036725E+04 3.524835E+01 - 3.839999E+01 2 2 2.282827E+03 3.705519E+00 - 3.839999E+01 2 4 1.456940E+04 1.192247E+01 - 3.839999E+01 3 3 2.309349E+03 2.097117E+02 - 3.839999E+01 4 2 1.458581E+04 1.196471E+01 - 3.839999E+01 4 4 2.706051E+05 3.850977E+01 - 3.839999E+01 5 1 -1.038487E+04 3.516337E+01 - 3.839999E+01 5 5 8.269758E+05 3.769133E+02 - 3.839999E+01 6 6 9.081760E+05 4.576396E+00 - 3.849998E+01 1 1 2.012400E+03 3.269788E+00 - 3.849998E+01 1 5 -1.036728E+04 3.505717E+01 - 3.849998E+01 2 2 2.282749E+03 3.684276E+00 - 3.849998E+01 2 4 1.456908E+04 1.185255E+01 - 3.849998E+01 3 3 2.309770E+03 2.097465E+02 - 3.849998E+01 4 2 1.458546E+04 1.189483E+01 - 3.849998E+01 4 4 2.706033E+05 3.826764E+01 - 3.849998E+01 5 1 -1.038490E+04 3.497512E+01 - 3.849998E+01 5 5 8.269746E+05 3.749321E+02 - 3.849998E+01 6 6 9.081566E+05 4.542968E+00 - 3.859998E+01 1 1 2.012333E+03 3.251281E+00 - 3.859998E+01 1 5 -1.036730E+04 3.486726E+01 - 3.859998E+01 2 2 2.282667E+03 3.663255E+00 - 3.859998E+01 2 4 1.456875E+04 1.178283E+01 - 3.859998E+01 3 3 2.310175E+03 2.097849E+02 - 3.859998E+01 4 2 1.458510E+04 1.182453E+01 - 3.859998E+01 4 4 2.706021E+05 3.803108E+01 - 3.859998E+01 5 1 -1.038491E+04 3.478324E+01 - 3.859998E+01 5 5 8.269734E+05 3.729440E+02 - 3.859998E+01 6 6 9.081362E+05 4.490300E+00 - 3.869998E+01 1 1 2.012272E+03 3.232926E+00 - 3.869998E+01 1 5 -1.036729E+04 3.467992E+01 - 3.869998E+01 2 2 2.282588E+03 3.642359E+00 - 3.869998E+01 2 4 1.456842E+04 1.171539E+01 - 3.869998E+01 3 3 2.310576E+03 2.098226E+02 - 3.869998E+01 4 2 1.458475E+04 1.175802E+01 - 3.869998E+01 4 4 2.706006E+05 3.779966E+01 - 3.869998E+01 5 1 -1.038495E+04 3.459625E+01 - 3.869998E+01 5 5 8.269721E+05 3.711460E+02 - 3.869998E+01 6 6 9.081186E+05 4.421749E+00 - 3.879998E+01 1 1 2.012209E+03 3.214651E+00 - 3.879998E+01 1 5 -1.036732E+04 3.449369E+01 - 3.879998E+01 2 2 2.282503E+03 3.621585E+00 - 3.879998E+01 2 4 1.456807E+04 1.164711E+01 - 3.879998E+01 3 3 2.310982E+03 2.098570E+02 - 3.879998E+01 4 2 1.458442E+04 1.168894E+01 - 3.879998E+01 4 4 2.705990E+05 3.758459E+01 - 3.879998E+01 5 1 -1.038493E+04 3.441256E+01 - 3.879998E+01 5 5 8.269718E+05 3.691244E+02 - 3.879998E+01 6 6 9.081011E+05 4.378713E+00 - 3.889998E+01 1 1 2.012145E+03 3.196586E+00 - 3.889998E+01 1 5 -1.036732E+04 3.430721E+01 - 3.889998E+01 2 2 2.282424E+03 3.601162E+00 - 3.889998E+01 2 4 1.456774E+04 1.157895E+01 - 3.889998E+01 3 3 2.311388E+03 2.098934E+02 - 3.889998E+01 4 2 1.458407E+04 1.162211E+01 - 3.889998E+01 4 4 2.705974E+05 3.737069E+01 - 3.889998E+01 5 1 -1.038494E+04 3.422789E+01 - 3.889998E+01 5 5 8.269711E+05 3.673767E+02 - 3.889998E+01 6 6 9.080827E+05 4.334402E+00 - 3.899998E+01 1 1 2.012087E+03 3.178778E+00 - 3.899998E+01 1 5 -1.036735E+04 3.412605E+01 - 3.899998E+01 2 2 2.282347E+03 3.580716E+00 - 3.899998E+01 2 4 1.456744E+04 1.151269E+01 - 3.899998E+01 3 3 2.311785E+03 2.099304E+02 - 3.899998E+01 4 2 1.458380E+04 1.155437E+01 - 3.899998E+01 4 4 2.705961E+05 3.714309E+01 - 3.899998E+01 5 1 -1.038495E+04 3.404263E+01 - 3.899998E+01 5 5 8.269695E+05 3.653286E+02 - 3.899998E+01 6 6 9.080644E+05 4.290007E+00 - 3.909998E+01 1 1 2.012023E+03 3.160982E+00 - 3.909998E+01 1 5 -1.036734E+04 3.394199E+01 - 3.909998E+01 2 2 2.282269E+03 3.560430E+00 - 3.909998E+01 2 4 1.456711E+04 1.144674E+01 - 3.909998E+01 3 3 2.312187E+03 2.099666E+02 - 3.909998E+01 4 2 1.458347E+04 1.148686E+01 - 3.909998E+01 4 4 2.705946E+05 3.693652E+01 - 3.909998E+01 5 1 -1.038495E+04 3.386298E+01 - 3.909998E+01 5 5 8.269674E+05 3.635599E+02 - 3.909998E+01 6 6 9.080466E+05 4.254579E+00 - 3.919997E+01 1 1 2.011962E+03 3.143251E+00 - 3.919997E+01 1 5 -1.036736E+04 3.376207E+01 - 3.919997E+01 2 2 2.282194E+03 3.540502E+00 - 3.919997E+01 2 4 1.456678E+04 1.138097E+01 - 3.919997E+01 3 3 2.312580E+03 2.099987E+02 - 3.919997E+01 4 2 1.458313E+04 1.141975E+01 - 3.919997E+01 4 4 2.705932E+05 3.670096E+01 - 3.919997E+01 5 1 -1.038498E+04 3.368402E+01 - 3.919997E+01 5 5 8.269670E+05 3.616775E+02 - 3.919997E+01 6 6 9.080277E+05 4.215195E+00 - 3.929997E+01 1 1 2.011903E+03 3.125883E+00 - 3.929997E+01 1 5 -1.036737E+04 3.358359E+01 - 3.929997E+01 2 2 2.282120E+03 3.520800E+00 - 3.929997E+01 2 4 1.456644E+04 1.131631E+01 - 3.929997E+01 3 3 2.312969E+03 2.100336E+02 - 3.929997E+01 4 2 1.458281E+04 1.135574E+01 - 3.929997E+01 4 4 2.705918E+05 3.649755E+01 - 3.929997E+01 5 1 -1.038500E+04 3.350385E+01 - 3.929997E+01 5 5 8.269663E+05 3.599503E+02 - 3.929997E+01 6 6 9.080109E+05 4.157808E+00 - 3.939997E+01 1 1 2.011847E+03 3.108540E+00 - 3.939997E+01 1 5 -1.036739E+04 3.340415E+01 - 3.939997E+01 2 2 2.282038E+03 3.501162E+00 - 3.939997E+01 2 4 1.456614E+04 1.125108E+01 - 3.939997E+01 3 3 2.313376E+03 2.100708E+02 - 3.939997E+01 4 2 1.458250E+04 1.129232E+01 - 3.939997E+01 4 4 2.705904E+05 3.627639E+01 - 3.939997E+01 5 1 -1.038502E+04 3.332632E+01 - 3.939997E+01 5 5 8.269655E+05 3.581561E+02 - 3.939997E+01 6 6 9.079923E+05 4.111275E+00 - 3.949997E+01 1 1 2.011782E+03 3.091426E+00 - 3.949997E+01 1 5 -1.036741E+04 3.322937E+01 - 3.949997E+01 2 2 2.281966E+03 3.481546E+00 - 3.949997E+01 2 4 1.456584E+04 1.118835E+01 - 3.949997E+01 3 3 2.313766E+03 2.101021E+02 - 3.949997E+01 4 2 1.458219E+04 1.122677E+01 - 3.949997E+01 4 4 2.705893E+05 3.608713E+01 - 3.949997E+01 5 1 -1.038504E+04 3.315043E+01 - 3.949997E+01 5 5 8.269635E+05 3.563717E+02 - 3.949997E+01 6 6 9.079751E+05 4.073586E+00 - 3.959997E+01 1 1 2.011724E+03 3.074402E+00 - 3.959997E+01 1 5 -1.036742E+04 3.305470E+01 - 3.959997E+01 2 2 2.281890E+03 3.462407E+00 - 3.959997E+01 2 4 1.456552E+04 1.112596E+01 - 3.959997E+01 3 3 2.314161E+03 2.101375E+02 - 3.959997E+01 4 2 1.458187E+04 1.116395E+01 - 3.959997E+01 4 4 2.705877E+05 3.588458E+01 - 3.959997E+01 5 1 -1.038506E+04 3.297411E+01 - 3.959997E+01 5 5 8.269639E+05 3.546119E+02 - 3.959997E+01 6 6 9.079575E+05 4.041151E+00 - 3.969997E+01 1 1 2.011666E+03 3.057555E+00 - 3.969997E+01 1 5 -1.036745E+04 3.288111E+01 - 3.969997E+01 2 2 2.281816E+03 3.443227E+00 - 3.969997E+01 2 4 1.456520E+04 1.106171E+01 - 3.969997E+01 3 3 2.314552E+03 2.101746E+02 - 3.969997E+01 4 2 1.458156E+04 1.110115E+01 - 3.969997E+01 4 4 2.705866E+05 3.565243E+01 - 3.969997E+01 5 1 -1.038508E+04 3.280614E+01 - 3.969997E+01 5 5 8.269627E+05 3.527347E+02 - 3.969997E+01 6 6 9.079406E+05 3.996453E+00 - 3.979996E+01 1 1 2.011607E+03 3.040918E+00 - 3.979996E+01 1 5 -1.036748E+04 3.270905E+01 - 3.979996E+01 2 2 2.281746E+03 3.424165E+00 - 3.979996E+01 2 4 1.456488E+04 1.100041E+01 - 3.979996E+01 3 3 2.314941E+03 2.102100E+02 - 3.979996E+01 4 2 1.458128E+04 1.103920E+01 - 3.979996E+01 4 4 2.705856E+05 3.546384E+01 - 3.979996E+01 5 1 -1.038511E+04 3.263005E+01 - 3.979996E+01 5 5 8.269610E+05 3.510912E+02 - 3.979996E+01 6 6 9.079243E+05 3.931697E+00 - 3.989996E+01 1 1 2.011553E+03 3.024139E+00 - 3.989996E+01 1 5 -1.036750E+04 3.253902E+01 - 3.989996E+01 2 2 2.281671E+03 3.405334E+00 - 3.989996E+01 2 4 1.456459E+04 1.093907E+01 - 3.989996E+01 3 3 2.315334E+03 2.102411E+02 - 3.989996E+01 4 2 1.458096E+04 1.097808E+01 - 3.989996E+01 4 4 2.705842E+05 3.526117E+01 - 3.989996E+01 5 1 -1.038511E+04 3.246190E+01 - 3.989996E+01 5 5 8.269589E+05 3.492199E+02 - 3.989996E+01 6 6 9.079063E+05 3.901466E+00 - 3.999996E+01 1 1 2.011493E+03 3.007740E+00 - 3.999996E+01 1 5 -1.036752E+04 3.236941E+01 - 3.999996E+01 2 2 2.281596E+03 3.386753E+00 - 3.999996E+01 2 4 1.456432E+04 1.087715E+01 - 3.999996E+01 3 3 2.315724E+03 2.102723E+02 - 3.999996E+01 4 2 1.458065E+04 1.091650E+01 - 3.999996E+01 4 4 2.705826E+05 3.505007E+01 - 3.999996E+01 5 1 -1.038512E+04 3.229579E+01 - 3.999996E+01 5 5 8.269584E+05 3.475764E+02 - 3.999996E+01 6 6 9.078898E+05 3.849471E+00 - 4.009996E+01 1 1 2.011437E+03 2.991410E+00 - 4.009996E+01 1 5 -1.036753E+04 3.220149E+01 - 4.009996E+01 2 2 2.281525E+03 3.368227E+00 - 4.009996E+01 2 4 1.456400E+04 1.081634E+01 - 4.009996E+01 3 3 2.316114E+03 2.103059E+02 - 4.009996E+01 4 2 1.458038E+04 1.085643E+01 - 4.009996E+01 4 4 2.705809E+05 3.484414E+01 - 4.009996E+01 5 1 -1.038514E+04 3.212786E+01 - 4.009996E+01 5 5 8.269564E+05 3.458421E+02 - 4.009996E+01 6 6 9.078736E+05 3.824381E+00 - 4.019996E+01 1 1 2.011378E+03 2.975131E+00 - 4.019996E+01 1 5 -1.036755E+04 3.203527E+01 - 4.019996E+01 2 2 2.281455E+03 3.349832E+00 - 4.019996E+01 2 4 1.456370E+04 1.075585E+01 - 4.019996E+01 3 3 2.316508E+03 2.103378E+02 - 4.019996E+01 4 2 1.458008E+04 1.079508E+01 - 4.019996E+01 4 4 2.705806E+05 3.464214E+01 - 4.019996E+01 5 1 -1.038515E+04 3.195966E+01 - 4.019996E+01 5 5 8.269543E+05 3.441451E+02 - 4.019996E+01 6 6 9.078556E+05 3.771292E+00 - 4.029996E+01 1 1 2.011323E+03 2.959233E+00 - 4.029996E+01 1 5 -1.036756E+04 3.186870E+01 - 4.029996E+01 2 2 2.281383E+03 3.331590E+00 - 4.029996E+01 2 4 1.456340E+04 1.069608E+01 - 4.029996E+01 3 3 2.316894E+03 2.103727E+02 - 4.029996E+01 4 2 1.457977E+04 1.073504E+01 - 4.029996E+01 4 4 2.705788E+05 3.445746E+01 - 4.029996E+01 5 1 -1.038517E+04 3.179680E+01 - 4.029996E+01 5 5 8.269531E+05 3.424527E+02 - 4.029996E+01 6 6 9.078409E+05 3.741815E+00 - 4.039996E+01 1 1 2.011270E+03 2.943222E+00 - 4.039996E+01 1 5 -1.036760E+04 3.170504E+01 - 4.039996E+01 2 2 2.281312E+03 3.313582E+00 - 4.039996E+01 2 4 1.456310E+04 1.063782E+01 - 4.039996E+01 3 3 2.317275E+03 2.104019E+02 - 4.039996E+01 4 2 1.457948E+04 1.067604E+01 - 4.039996E+01 4 4 2.705776E+05 3.426579E+01 - 4.039996E+01 5 1 -1.038520E+04 3.163220E+01 - 4.039996E+01 5 5 8.269516E+05 3.407807E+02 - 4.039996E+01 6 6 9.078230E+05 3.692379E+00 - 4.049995E+01 1 1 2.011215E+03 2.927410E+00 - 4.049995E+01 1 5 -1.036761E+04 3.154235E+01 - 4.049995E+01 2 2 2.281241E+03 3.295801E+00 - 4.049995E+01 2 4 1.456282E+04 1.057935E+01 - 4.049995E+01 3 3 2.317661E+03 2.104317E+02 - 4.049995E+01 4 2 1.457920E+04 1.061816E+01 - 4.049995E+01 4 4 2.705764E+05 3.407467E+01 - 4.049995E+01 5 1 -1.038521E+04 3.146976E+01 - 4.049995E+01 5 5 8.269507E+05 3.390747E+02 - 4.049995E+01 6 6 9.078081E+05 3.641167E+00 - 4.059995E+01 1 1 2.011161E+03 2.911773E+00 - 4.059995E+01 1 5 -1.036765E+04 3.138105E+01 - 4.059995E+01 2 2 2.281172E+03 3.278031E+00 - 4.059995E+01 2 4 1.456253E+04 1.052094E+01 - 4.059995E+01 3 3 2.318038E+03 2.104649E+02 - 4.059995E+01 4 2 1.457890E+04 1.056202E+01 - 4.059995E+01 4 4 2.705752E+05 3.388414E+01 - 4.059995E+01 5 1 -1.038523E+04 3.130933E+01 - 4.059995E+01 5 5 8.269500E+05 3.374234E+02 - 4.059995E+01 6 6 9.077920E+05 3.624387E+00 - 4.069995E+01 1 1 2.011105E+03 2.896175E+00 - 4.069995E+01 1 5 -1.036766E+04 3.122051E+01 - 4.069995E+01 2 2 2.281105E+03 3.260370E+00 - 4.069995E+01 2 4 1.456222E+04 1.046322E+01 - 4.069995E+01 3 3 2.318431E+03 2.104967E+02 - 4.069995E+01 4 2 1.457862E+04 1.050220E+01 - 4.069995E+01 4 4 2.705737E+05 3.368925E+01 - 4.069995E+01 5 1 -1.038527E+04 3.115114E+01 - 4.069995E+01 5 5 8.269492E+05 3.357729E+02 - 4.069995E+01 6 6 9.077761E+05 3.580951E+00 - 4.079995E+01 1 1 2.011051E+03 2.880900E+00 - 4.079995E+01 1 5 -1.036768E+04 3.106174E+01 - 4.079995E+01 2 2 2.281037E+03 3.242859E+00 - 4.079995E+01 2 4 1.456197E+04 1.040636E+01 - 4.079995E+01 3 3 2.318805E+03 2.105277E+02 - 4.079995E+01 4 2 1.457835E+04 1.044448E+01 - 4.079995E+01 4 4 2.705726E+05 3.350297E+01 - 4.079995E+01 5 1 -1.038528E+04 3.099028E+01 - 4.079995E+01 5 5 8.269483E+05 3.340829E+02 - 4.079995E+01 6 6 9.077611E+05 3.535315E+00 - 4.089995E+01 1 1 2.010996E+03 2.865503E+00 - 4.089995E+01 1 5 -1.036770E+04 3.090385E+01 - 4.089995E+01 2 2 2.280970E+03 3.225686E+00 - 4.089995E+01 2 4 1.456167E+04 1.035017E+01 - 4.089995E+01 3 3 2.319184E+03 2.105570E+02 - 4.089995E+01 4 2 1.457807E+04 1.038748E+01 - 4.089995E+01 4 4 2.705714E+05 3.332624E+01 - 4.089995E+01 5 1 -1.038528E+04 3.082990E+01 - 4.089995E+01 5 5 8.269490E+05 3.325596E+02 - 4.089995E+01 6 6 9.077447E+05 3.518167E+00 - 4.099995E+01 1 1 2.010943E+03 2.850343E+00 - 4.099995E+01 1 5 -1.036770E+04 3.074819E+01 - 4.099995E+01 2 2 2.280899E+03 3.208411E+00 - 4.099995E+01 2 4 1.456140E+04 1.029359E+01 - 4.099995E+01 3 3 2.319558E+03 2.105878E+02 - 4.099995E+01 4 2 1.457776E+04 1.033150E+01 - 4.099995E+01 4 4 2.705698E+05 3.313728E+01 - 4.099995E+01 5 1 -1.038530E+04 3.067612E+01 - 4.099995E+01 5 5 8.269471E+05 3.307766E+02 - 4.099995E+01 6 6 9.077286E+05 3.497452E+00 - 4.109995E+01 1 1 2.010892E+03 2.835345E+00 - 4.109995E+01 1 5 -1.036773E+04 3.059193E+01 - 4.109995E+01 2 2 2.280834E+03 3.191469E+00 - 4.109995E+01 2 4 1.456115E+04 1.023820E+01 - 4.109995E+01 3 3 2.319937E+03 2.106193E+02 - 4.109995E+01 4 2 1.457750E+04 1.027547E+01 - 4.109995E+01 4 4 2.705685E+05 3.296493E+01 - 4.109995E+01 5 1 -1.038534E+04 3.052301E+01 - 4.109995E+01 5 5 8.269469E+05 3.293317E+02 - 4.109995E+01 6 6 9.077132E+05 3.431105E+00 - 4.119994E+01 1 1 2.010840E+03 2.820436E+00 - 4.119994E+01 1 5 -1.036777E+04 3.043818E+01 - 4.119994E+01 2 2 2.280764E+03 3.174535E+00 - 4.119994E+01 2 4 1.456088E+04 1.018240E+01 - 4.119994E+01 3 3 2.320303E+03 2.106497E+02 - 4.119994E+01 4 2 1.457721E+04 1.022033E+01 - 4.119994E+01 4 4 2.705678E+05 3.277423E+01 - 4.119994E+01 5 1 -1.038538E+04 3.036722E+01 - 4.119994E+01 5 5 8.269467E+05 3.276874E+02 - 4.119994E+01 6 6 9.076984E+05 3.423158E+00 - 4.129994E+01 1 1 2.010787E+03 2.805636E+00 - 4.129994E+01 1 5 -1.036778E+04 3.028543E+01 - 4.129994E+01 2 2 2.280697E+03 3.157800E+00 - 4.129994E+01 2 4 1.456059E+04 1.012721E+01 - 4.129994E+01 3 3 2.320671E+03 2.106786E+02 - 4.129994E+01 4 2 1.457696E+04 1.016713E+01 - 4.129994E+01 4 4 2.705668E+05 3.258274E+01 - 4.129994E+01 5 1 -1.038539E+04 3.021600E+01 - 4.129994E+01 5 5 8.269446E+05 3.261401E+02 - 4.129994E+01 6 6 9.076834E+05 3.391908E+00 - 4.139994E+01 1 1 2.010738E+03 2.790935E+00 - 4.139994E+01 1 5 -1.036780E+04 3.013216E+01 - 4.139994E+01 2 2 2.280635E+03 3.140967E+00 - 4.139994E+01 2 4 1.456034E+04 1.007382E+01 - 4.139994E+01 3 3 2.321048E+03 2.107092E+02 - 4.139994E+01 4 2 1.457667E+04 1.010970E+01 - 4.139994E+01 4 4 2.705659E+05 3.242693E+01 - 4.139994E+01 5 1 -1.038540E+04 3.006433E+01 - 4.139994E+01 5 5 8.269430E+05 3.246499E+02 - 4.139994E+01 6 6 9.076686E+05 3.320487E+00 - 4.149994E+01 1 1 2.010685E+03 2.776349E+00 - 4.149994E+01 1 5 -1.036781E+04 2.998286E+01 - 4.149994E+01 2 2 2.280570E+03 3.124676E+00 - 4.149994E+01 2 4 1.456005E+04 1.001935E+01 - 4.149994E+01 3 3 2.321431E+03 2.107393E+02 - 4.149994E+01 4 2 1.457639E+04 1.005757E+01 - 4.149994E+01 4 4 2.705651E+05 3.223020E+01 - 4.149994E+01 5 1 -1.038540E+04 2.991556E+01 - 4.149994E+01 5 5 8.269421E+05 3.229818E+02 - 4.149994E+01 6 6 9.076525E+05 3.292625E+00 - 4.159994E+01 1 1 2.010633E+03 2.761979E+00 - 4.159994E+01 1 5 -1.036784E+04 2.983413E+01 - 4.159994E+01 2 2 2.280502E+03 3.108115E+00 - 4.159994E+01 2 4 1.455977E+04 9.966230E+00 - 4.159994E+01 3 3 2.321802E+03 2.107699E+02 - 4.159994E+01 4 2 1.457613E+04 1.000151E+01 - 4.159994E+01 4 4 2.705635E+05 3.205392E+01 - 4.159994E+01 5 1 -1.038544E+04 2.976593E+01 - 4.159994E+01 5 5 8.269400E+05 3.214334E+02 - 4.159994E+01 6 6 9.076379E+05 3.296375E+00 - 4.169994E+01 1 1 2.010583E+03 2.747638E+00 - 4.169994E+01 1 5 -1.036785E+04 2.968378E+01 - 4.169994E+01 2 2 2.280436E+03 3.091906E+00 - 4.169994E+01 2 4 1.455952E+04 9.914182E+00 - 4.169994E+01 3 3 2.322174E+03 2.108015E+02 - 4.169994E+01 4 2 1.457589E+04 9.948250E+00 - 4.169994E+01 4 4 2.705623E+05 3.190782E+01 - 4.169994E+01 5 1 -1.038545E+04 2.961996E+01 - 4.169994E+01 5 5 8.269397E+05 3.200453E+02 - 4.169994E+01 6 6 9.076232E+05 3.239015E+00 - 4.179993E+01 1 1 2.010532E+03 2.733359E+00 - 4.179993E+01 1 5 -1.036787E+04 2.953878E+01 - 4.179993E+01 2 2 2.280375E+03 3.075854E+00 - 4.179993E+01 2 4 1.455924E+04 9.861310E+00 - 4.179993E+01 3 3 2.322546E+03 2.108277E+02 - 4.179993E+01 4 2 1.457561E+04 9.894742E+00 - 4.179993E+01 4 4 2.705612E+05 3.172332E+01 - 4.179993E+01 5 1 -1.038547E+04 2.947310E+01 - 4.179993E+01 5 5 8.269386E+05 3.183591E+02 - 4.179993E+01 6 6 9.076082E+05 3.194246E+00 - 4.189993E+01 1 1 2.010479E+03 2.719279E+00 - 4.189993E+01 1 5 -1.036789E+04 2.939155E+01 - 4.189993E+01 2 2 2.280311E+03 3.059813E+00 - 4.189993E+01 2 4 1.455897E+04 9.809370E+00 - 4.189993E+01 3 3 2.322901E+03 2.108558E+02 - 4.189993E+01 4 2 1.457534E+04 9.842846E+00 - 4.189993E+01 4 4 2.705602E+05 3.155300E+01 - 4.189993E+01 5 1 -1.038547E+04 2.932571E+01 - 4.189993E+01 5 5 8.269378E+05 3.168844E+02 - 4.189993E+01 6 6 9.075934E+05 3.168942E+00 - 4.199993E+01 1 1 2.010434E+03 2.705281E+00 - 4.199993E+01 1 5 -1.036793E+04 2.924620E+01 - 4.199993E+01 2 2 2.280251E+03 3.044036E+00 - 4.199993E+01 2 4 1.455869E+04 9.758191E+00 - 4.199993E+01 3 3 2.323268E+03 2.108832E+02 - 4.199993E+01 4 2 1.457507E+04 9.791515E+00 - 4.199993E+01 4 4 2.705584E+05 3.139161E+01 - 4.199993E+01 5 1 -1.038549E+04 2.918254E+01 - 4.199993E+01 5 5 8.269366E+05 3.153878E+02 - 4.199993E+01 6 6 9.075792E+05 3.160925E+00 \ No newline at end of file diff --git a/Test_Cases/MHK_RM1/MHK_RM1_Floating.3 b/Test_Cases/MHK_RM1/MHK_RM1_Floating.3 deleted file mode 100644 index 2bfe7b48..00000000 --- a/Test_Cases/MHK_RM1/MHK_RM1_Floating.3 +++ /dev/null @@ -1,10080 +0,0 @@ - 1.000000E-01 0.000000E+00 1 3.928387E-05 9.000026E+01 -1.752301E-10 3.928387E-05 - 1.000000E-01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.000000E-01 0.000000E+00 3 5.096992E-06 2.330833E-04 5.096992E-06 2.073492E-11 - 1.000000E-01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.000000E-01 0.000000E+00 5 2.129045E-05 -8.999974E+01 9.931642E-11 -2.129045E-05 - 1.000000E-01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.000000E-01 3.000000E+01 1 2.479953E-05 9.000016E+01 -6.785025E-11 2.479953E-05 - 1.000000E-01 3.000000E+01 2 1.030077E-05 9.000000E+01 -3.776052E-13 1.030077E-05 - 1.000000E-01 3.000000E+01 3 6.027945E-06 2.529555E-05 6.027945E-06 2.661282E-12 - 1.000000E-01 3.000000E+01 4 4.842914E-05 -8.999998E+01 1.348501E-11 -4.842914E-05 - 1.000000E-01 3.000000E+01 5 1.310311E-05 -8.999985E+01 3.597847E-11 -1.310311E-05 - 1.000000E-01 3.000000E+01 6 1.316677E-04 -1.799997E+02 -1.316677E-04 -7.396868E-10 - 1.000000E-01 6.000000E+01 1 2.777314E-05 9.000978E+01 -4.741620E-09 2.777314E-05 - 1.000000E-01 6.000000E+01 2 3.752036E-06 9.000040E+01 -2.665548E-11 3.752036E-06 - 1.000000E-01 6.000000E+01 3 4.212014E-06 1.799998E+02 -4.212014E-06 1.676656E-11 - 1.000000E-01 6.000000E+01 4 1.801150E-05 -8.999966E+01 1.074628E-10 -1.801150E-05 - 1.000000E-01 6.000000E+01 5 1.438257E-05 -8.998517E+01 3.722973E-09 -1.438257E-05 - 1.000000E-01 6.000000E+01 6 2.408331E-04 2.416988E-04 2.408331E-04 1.015940E-09 - 1.000000E-01 9.000000E+01 1 3.569052E-10 9.000000E+01 -3.883185E-16 3.569052E-10 - 1.000000E-01 9.000000E+01 2 6.679657E-06 -8.999947E+01 6.145705E-11 -6.679657E-06 - 1.000000E-01 9.000000E+01 3 8.607126E-07 1.438843E-03 8.607126E-07 2.161469E-11 - 1.000000E-01 9.000000E+01 4 3.630382E-05 9.000039E+01 -2.475569E-10 3.630382E-05 - 1.000000E-01 9.000000E+01 5 1.129626E-10 9.000000E+01 -7.992531E-17 1.129626E-10 - 1.000000E-01 9.000000E+01 6 2.390679E-10 1.799993E+02 -2.390679E-10 2.915754E-15 - 2.000000E-01 0.000000E+00 1 4.794502E-03 -7.108732E+01 1.554026E-03 -4.535664E-03 - 2.000000E-01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.000000E-01 0.000000E+00 3 5.115628E-03 1.557186E+01 4.927857E-03 1.373273E-03 - 2.000000E-01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.000000E-01 0.000000E+00 5 3.931623E-04 -1.080528E+02 -1.218386E-04 -3.738074E-04 - 2.000000E-01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.000000E-01 3.000000E+01 1 7.095869E-03 -7.712666E+01 1.580935E-03 -6.917514E-03 - 2.000000E-01 3.000000E+01 2 4.226396E-03 1.086416E+02 -1.350958E-03 4.004665E-03 - 2.000000E-01 3.000000E+01 3 3.649259E-03 1.847425E+01 3.461199E-03 1.156371E-03 - 2.000000E-01 3.000000E+01 4 2.471381E-02 -7.209129E+01 7.599527E-03 -2.351637E-02 - 2.000000E-01 3.000000E+01 5 4.199853E-04 8.719241E+01 2.057174E-05 4.194811E-04 - 2.000000E-01 3.000000E+01 6 2.909344E-02 -1.673242E+02 -2.838435E-02 -6.384108E-03 - 2.000000E-01 6.000000E+01 1 2.047991E-03 -7.983326E+01 3.614978E-04 -2.015834E-03 - 2.000000E-01 6.000000E+01 2 1.384893E-03 -1.384165E+01 1.344677E-03 -3.313209E-04 - 2.000000E-01 6.000000E+01 3 3.288509E-03 -1.597656E+02 -3.085559E-03 -1.137370E-03 - 2.000000E-01 6.000000E+01 4 7.811303E-03 1.663535E+02 -7.590788E-03 1.842930E-03 - 2.000000E-01 6.000000E+01 5 7.411336E-04 -8.593498E+01 5.253779E-05 -7.392691E-04 - 2.000000E-01 6.000000E+01 6 3.474759E-02 6.111718E+00 3.455009E-02 3.699487E-03 - 2.000000E-01 9.000000E+01 1 1.420143E-08 -8.680801E+01 7.907613E-10 -1.417940E-08 - 2.000000E-01 9.000000E+01 2 1.406377E-02 1.025577E+02 -3.057782E-03 1.372733E-02 - 2.000000E-01 9.000000E+01 3 7.963536E-04 -1.482715E+02 -6.773379E-04 -4.187988E-04 - 2.000000E-01 9.000000E+01 4 7.866052E-02 -7.677493E+01 1.799571E-02 -7.657436E-02 - 2.000000E-01 9.000000E+01 5 2.518591E-09 9.854890E+01 -3.743971E-10 2.490607E-09 - 2.000000E-01 9.000000E+01 6 5.488987E-08 5.854488E+01 2.864320E-08 4.682376E-08 - 3.000000E-01 0.000000E+00 1 3.888490E-02 -9.719932E+01 -4.873109E-03 -3.857834E-02 - 3.000000E-01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.000000E-01 0.000000E+00 3 1.602358E-02 1.495198E+02 -1.380919E-02 8.127803E-03 - 3.000000E-01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.000000E-01 0.000000E+00 5 4.695172E-04 -3.361153E+01 3.910186E-04 -2.599056E-04 - 3.000000E-01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.000000E-01 3.000000E+01 1 4.646594E-03 5.454666E+01 2.695209E-03 3.785060E-03 - 3.000000E-01 3.000000E+01 2 7.563305E-03 1.047204E+01 7.437328E-03 1.374674E-03 - 3.000000E-01 3.000000E+01 3 1.330938E-02 -8.915330E+01 1.966758E-04 -1.330793E-02 - 3.000000E-01 3.000000E+01 4 4.322376E-02 -1.644875E+02 -4.164920E-02 -1.156016E-02 - 3.000000E-01 3.000000E+01 5 2.016536E-03 -1.208179E+02 -1.033095E-03 -1.731801E-03 - 3.000000E-01 3.000000E+01 6 8.285185E-02 7.853923E+01 1.646241E-02 8.119986E-02 - 3.000000E-01 6.000000E+01 1 2.509840E-02 -1.168346E+02 -1.132984E-02 -2.239563E-02 - 3.000000E-01 6.000000E+01 2 7.971748E-03 -4.328616E+01 5.802942E-03 -5.465769E-03 - 3.000000E-01 6.000000E+01 3 1.678508E-02 3.530571E+01 1.369797E-02 9.700751E-03 - 3.000000E-01 6.000000E+01 4 3.282496E-02 1.413052E+02 -2.561945E-02 2.052126E-02 - 3.000000E-01 6.000000E+01 5 5.603014E-04 1.154969E+02 -2.411888E-04 5.057327E-04 - 3.000000E-01 6.000000E+01 6 1.670086E-01 -1.458209E+02 -1.381638E-01 -9.382232E-02 - 3.000000E-01 9.000000E+01 1 2.949139E-07 -9.067712E+01 -3.485205E-09 -2.948933E-07 - 3.000000E-01 9.000000E+01 2 4.167762E-02 1.074692E+02 -1.251132E-02 3.975539E-02 - 3.000000E-01 9.000000E+01 3 2.107524E-02 1.002967E+02 -3.767119E-03 2.073582E-02 - 3.000000E-01 9.000000E+01 4 2.493339E-01 -7.362067E+01 7.031103E-02 -2.392149E-01 - 3.000000E-01 9.000000E+01 5 5.106316E-08 -9.276367E+01 -2.462081E-09 -5.100377E-08 - 3.000000E-01 9.000000E+01 6 3.944706E-07 3.112561E+01 3.376811E-07 2.039081E-07 - 4.000000E-01 0.000000E+00 1 1.307384E-01 -5.282935E+01 7.899095E-02 -1.041775E-01 - 4.000000E-01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 4.000000E-01 0.000000E+00 3 2.012498E-02 5.517360E+01 1.149321E-02 1.652032E-02 - 4.000000E-01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 4.000000E-01 0.000000E+00 5 6.834955E-03 1.047795E+02 -1.743601E-03 6.608818E-03 - 4.000000E-01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 4.000000E-01 3.000000E+01 1 5.314526E-02 -1.338230E+02 -3.679949E-02 -3.834339E-02 - 4.000000E-01 3.000000E+01 2 4.128766E-02 -9.884937E+01 -6.351586E-03 -4.079618E-02 - 4.000000E-01 3.000000E+01 3 2.686598E-02 -1.495038E+02 -2.314942E-02 -1.363397E-02 - 4.000000E-01 3.000000E+01 4 1.264045E-01 1.048542E+02 -3.240515E-02 1.221802E-01 - 4.000000E-01 3.000000E+01 5 4.001336E-03 7.631565E+01 9.466071E-04 3.887753E-03 - 4.000000E-01 3.000000E+01 6 5.532191E-01 -1.786506E+02 -5.530657E-01 -1.302844E-02 - 4.000000E-01 6.000000E+01 1 3.044731E-02 1.381135E+02 -2.266707E-02 2.032837E-02 - 4.000000E-01 6.000000E+01 2 7.044896E-02 8.796443E+01 2.502343E-03 7.040451E-02 - 4.000000E-01 6.000000E+01 3 6.615130E-02 -1.709194E+02 -6.532224E-02 -1.044024E-02 - 4.000000E-01 6.000000E+01 4 3.611451E-01 -8.312469E+01 4.323230E-02 -3.585481E-01 - 4.000000E-01 6.000000E+01 5 6.043765E-03 5.819611E+01 3.185145E-03 5.136336E-03 - 4.000000E-01 6.000000E+01 6 3.507415E-01 -1.755146E+02 -3.496673E-01 -2.742958E-02 - 4.000000E-01 9.000000E+01 1 5.332167E-07 -9.304235E+01 -2.829999E-08 -5.324652E-07 - 4.000000E-01 9.000000E+01 2 3.888678E-02 1.746534E+02 -3.871759E-02 3.623477E-03 - 4.000000E-01 9.000000E+01 3 5.207599E-02 1.688102E+02 -5.108601E-02 1.010584E-02 - 4.000000E-01 9.000000E+01 4 1.950537E-01 1.483926E+01 1.885483E-01 4.995484E-02 - 4.000000E-01 9.000000E+01 5 2.097070E-07 8.940276E+01 2.185888E-09 2.096956E-07 - 4.000000E-01 9.000000E+01 6 5.884815E-07 -8.653599E+00 5.817823E-07 -8.854307E-08 - 5.000000E-01 0.000000E+00 1 3.081082E-01 8.983705E+01 8.762858E-04 3.081069E-01 - 5.000000E-01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 5.000000E-01 0.000000E+00 3 2.407918E-02 2.501227E+01 2.182096E-02 1.018097E-02 - 5.000000E-01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 5.000000E-01 0.000000E+00 5 4.103291E-02 -9.531126E+01 -3.798261E-03 -4.085674E-02 - 5.000000E-01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 5.000000E-01 3.000000E+01 1 9.193930E-02 1.028800E+02 -2.049419E-02 8.962601E-02 - 5.000000E-01 3.000000E+01 2 1.244288E-02 1.155199E+02 -5.360694E-03 1.122890E-02 - 5.000000E-01 3.000000E+01 3 5.293012E-02 9.640726E+01 -5.906723E-03 5.259950E-02 - 5.000000E-01 3.000000E+01 4 3.355523E-01 -5.319021E+01 2.010497E-01 -2.686529E-01 - 5.000000E-01 3.000000E+01 5 3.948701E-03 6.551472E+01 1.636576E-03 3.593585E-03 - 5.000000E-01 3.000000E+01 6 1.075385E+00 2.140287E+01 1.001224E+00 3.924331E-01 - 5.000000E-01 6.000000E+01 1 1.267945E-01 1.144335E+02 -5.244690E-02 1.154391E-01 - 5.000000E-01 6.000000E+01 2 8.339784E-02 1.031805E+02 -1.901636E-02 8.120085E-02 - 5.000000E-01 6.000000E+01 3 6.141623E-02 -1.751663E+02 -6.119780E-02 -5.175158E-03 - 5.000000E-01 6.000000E+01 4 4.040240E-01 -6.234457E+01 1.875290E-01 -3.578662E-01 - 5.000000E-01 6.000000E+01 5 1.285017E-02 4.696736E+01 8.769150E-03 9.393029E-03 - 5.000000E-01 6.000000E+01 6 1.832786E+00 1.790019E+02 -1.832507E+00 3.192545E-02 - 5.000000E-01 9.000000E+01 1 1.766503E-06 8.096854E+01 2.773000E-07 1.744602E-06 - 5.000000E-01 9.000000E+01 2 2.347312E-01 6.647649E+01 9.368712E-02 2.152242E-01 - 5.000000E-01 9.000000E+01 3 3.180214E-02 1.300939E+02 -2.048190E-02 2.432833E-02 - 5.000000E-01 9.000000E+01 4 4.249727E-01 -8.168529E+01 6.145542E-02 -4.205057E-01 - 5.000000E-01 9.000000E+01 5 1.556368E-07 9.600702E+01 -1.628744E-08 1.547822E-07 - 5.000000E-01 9.000000E+01 6 7.300903E-05 1.775445E+02 -7.294200E-05 3.127902E-06 - 6.000000E-01 0.000000E+00 1 1.872266E-01 -1.771957E+02 -1.870024E-01 -9.159982E-03 - 6.000000E-01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 6.000000E-01 0.000000E+00 3 2.174157E-02 1.385365E+02 -1.629265E-02 1.439602E-02 - 6.000000E-01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 6.000000E-01 0.000000E+00 5 7.292495E-03 -1.096383E+02 -2.450872E-03 -6.868312E-03 - 6.000000E-01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 6.000000E-01 3.000000E+01 1 2.012022E-01 1.017873E+02 -4.110143E-02 1.969594E-01 - 6.000000E-01 3.000000E+01 2 9.185858E-02 1.075576E+02 -2.771054E-02 8.757925E-02 - 6.000000E-01 3.000000E+01 3 5.708990E-02 -1.741342E+02 -5.679097E-02 -5.834544E-03 - 6.000000E-01 3.000000E+01 4 3.475970E-01 -7.517700E+01 8.892706E-02 -3.360293E-01 - 6.000000E-01 3.000000E+01 5 3.762222E-02 -8.768892E+01 1.517118E-03 -3.759162E-02 - 6.000000E-01 3.000000E+01 6 5.433523E-01 -8.032565E+01 9.130932E-02 -5.356252E-01 - 6.000000E-01 6.000000E+01 1 6.134738E-02 -6.685158E+01 2.411654E-02 -5.640827E-02 - 6.000000E-01 6.000000E+01 2 2.838711E-01 -5.865669E+01 1.476598E-01 -2.424446E-01 - 6.000000E-01 6.000000E+01 3 7.000349E-02 3.677592E+01 5.607161E-02 4.191018E-02 - 6.000000E-01 6.000000E+01 4 8.238294E-01 1.504999E+02 -7.170240E-01 4.056741E-01 - 6.000000E-01 6.000000E+01 5 1.140813E-02 -4.424509E+01 8.172348E-03 -7.959786E-03 - 6.000000E-01 6.000000E+01 6 9.150789E-01 3.374132E+01 7.609373E-01 5.082753E-01 - 6.000000E-01 9.000000E+01 1 7.724071E-07 6.753969E+01 2.950931E-07 7.138157E-07 - 6.000000E-01 9.000000E+01 2 2.032647E-01 9.344522E+01 -1.221503E-02 2.028973E-01 - 6.000000E-01 9.000000E+01 3 5.020192E-02 6.025718E+01 2.490556E-02 4.358836E-02 - 6.000000E-01 9.000000E+01 4 9.899581E-01 -8.339436E+01 1.138798E-01 -9.833862E-01 - 6.000000E-01 9.000000E+01 5 4.465225E-07 -1.031010E+02 -1.012124E-07 -4.349005E-07 - 6.000000E-01 9.000000E+01 6 9.935205E-06 -1.697474E+02 -9.776565E-06 -1.768350E-06 - 7.000000E-01 0.000000E+00 1 8.027183E-01 6.060232E+01 3.940291E-01 6.993552E-01 - 7.000000E-01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 7.000000E-01 0.000000E+00 3 1.692642E-01 3.964836E+01 1.303292E-01 1.080031E-01 - 7.000000E-01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 7.000000E-01 0.000000E+00 5 1.808603E-01 -1.052378E+02 -4.753476E-02 -1.745018E-01 - 7.000000E-01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 7.000000E-01 3.000000E+01 1 1.148481E-01 -1.690576E+02 -1.127600E-01 -2.180065E-02 - 7.000000E-01 3.000000E+01 2 1.608283E-01 4.394753E+00 1.603555E-01 1.232391E-02 - 7.000000E-01 3.000000E+01 3 7.954486E-03 -1.564072E+02 -7.289595E-03 -3.183652E-03 - 7.000000E-01 3.000000E+01 4 8.603882E-01 8.365328E+01 9.511141E-02 8.551151E-01 - 7.000000E-01 3.000000E+01 5 7.463598E-02 -6.266520E+01 3.427203E-02 -6.630202E-02 - 7.000000E-01 3.000000E+01 6 9.527321E+00 1.384091E+02 -7.125519E+00 6.324304E+00 - 7.000000E-01 6.000000E+01 1 4.940590E-01 -1.497921E+02 -4.269682E-01 -2.485807E-01 - 7.000000E-01 6.000000E+01 2 4.148615E-01 -1.045590E+02 -1.042866E-01 -4.015400E-01 - 7.000000E-01 6.000000E+01 3 1.437976E-01 2.332423E+01 1.320463E-01 5.693434E-02 - 7.000000E-01 6.000000E+01 4 1.464140E+00 -7.177795E+01 4.578373E-01 -1.390716E+00 - 7.000000E-01 6.000000E+01 5 6.378181E-02 7.214042E+01 1.956094E-02 6.070822E-02 - 7.000000E-01 6.000000E+01 6 1.511462E+01 -1.530150E+01 1.457881E+01 -3.988723E+00 - 7.000000E-01 9.000000E+01 1 1.589562E-06 -5.732171E+01 8.582388E-07 -1.337959E-06 - 7.000000E-01 9.000000E+01 2 6.702136E-01 5.452286E+01 3.889773E-01 5.457866E-01 - 7.000000E-01 9.000000E+01 3 1.072043E-01 8.414521E+01 1.093565E-02 1.066451E-01 - 7.000000E-01 9.000000E+01 4 1.161876E+00 -5.514134E+01 6.640748E-01 -9.533941E-01 - 7.000000E-01 9.000000E+01 5 3.845822E-07 -1.378897E+02 -2.853046E-07 -2.578852E-07 - 7.000000E-01 9.000000E+01 6 2.159800E-04 1.604690E+02 -2.035527E-04 7.220576E-05 - 8.000001E-01 0.000000E+00 1 4.028370E+00 -5.588440E+01 2.259370E+00 -3.335119E+00 - 8.000001E-01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 8.000001E-01 0.000000E+00 3 2.095643E-01 -3.923662E+00 2.090731E-01 -1.433992E-02 - 8.000001E-01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 8.000001E-01 0.000000E+00 5 7.912704E-01 1.254263E+02 -4.586639E-01 6.447762E-01 - 8.000001E-01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 8.000001E-01 3.000000E+01 1 5.347347E-01 -7.389597E+01 1.483259E-01 -5.137515E-01 - 8.000001E-01 3.000000E+01 2 3.749571E-01 4.094019E+01 2.832404E-01 2.456985E-01 - 8.000001E-01 3.000000E+01 3 2.190640E-01 -1.435698E+02 -1.762548E-01 -1.300895E-01 - 8.000001E-01 3.000000E+01 4 1.997968E+00 -5.941833E+01 1.016498E+00 -1.720060E+00 - 8.000001E-01 3.000000E+01 5 1.540143E-01 1.044117E+02 -3.833220E-02 1.491678E-01 - 8.000001E-01 3.000000E+01 6 1.853185E+01 -1.581446E+02 -1.719990E+01 -6.898758E+00 - 8.000001E-01 6.000000E+01 1 2.647785E-01 -9.986835E+00 2.607664E-01 -4.591838E-02 - 8.000001E-01 6.000000E+01 2 3.127118E-02 -1.723142E+02 -3.099025E-02 -4.182242E-03 - 8.000001E-01 6.000000E+01 3 2.191740E-01 -1.447901E+02 -1.790750E-01 -1.263701E-01 - 8.000001E-01 6.000000E+01 4 1.036278E+00 -4.005235E+01 7.932259E-01 -6.668315E-01 - 8.000001E-01 6.000000E+01 5 1.151183E-01 -1.673150E+02 -1.123085E-01 -2.527882E-02 - 8.000001E-01 6.000000E+01 6 2.461483E+00 -1.095917E+01 2.416592E+00 -4.679509E-01 - 8.000001E-01 9.000000E+01 1 1.617859E-06 1.135123E+02 -6.454394E-07 1.483535E-06 - 8.000001E-01 9.000000E+01 2 1.755162E+00 -7.329680E+01 5.044584E-01 -1.681106E+00 - 8.000001E-01 9.000000E+01 3 8.098494E-02 6.427621E+01 3.515016E-02 7.295907E-02 - 8.000001E-01 9.000000E+01 4 1.641137E+00 -6.077317E+01 8.013152E-01 -1.432210E+00 - 8.000001E-01 9.000000E+01 5 5.084881E-07 -8.231286E+01 6.801734E-08 -5.039184E-07 - 8.000001E-01 9.000000E+01 6 2.693365E-04 2.322025E+01 2.475192E-04 1.061904E-04 - 9.000001E-01 0.000000E+00 1 1.068581E+00 6.843844E+01 3.927042E-01 9.938048E-01 - 9.000001E-01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 9.000001E-01 0.000000E+00 3 5.909093E-02 -1.017197E+02 -1.200281E-02 -5.785906E-02 - 9.000001E-01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 9.000001E-01 0.000000E+00 5 2.806859E-01 -1.200122E+02 -1.403947E-01 -2.430512E-01 - 9.000001E-01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 9.000001E-01 3.000000E+01 1 6.341945E-01 -6.897472E+01 2.275362E-01 -5.919712E-01 - 9.000001E-01 3.000000E+01 2 2.360800E-01 1.247190E+02 -1.344599E-01 1.940472E-01 - 9.000001E-01 3.000000E+01 3 3.962129E-02 -6.630566E+00 3.935628E-02 -4.574955E-03 - 9.000001E-01 3.000000E+01 4 1.353328E+00 2.196399E+01 1.255102E+00 5.061766E-01 - 9.000001E-01 3.000000E+01 5 1.222350E-01 1.242814E+02 -6.884973E-02 1.010005E-01 - 9.000001E-01 3.000000E+01 6 3.158235E+01 -3.682267E+01 2.528149E+01 -1.892858E+01 - 9.000001E-01 6.000000E+01 1 1.149328E+00 7.111678E+01 3.719688E-01 1.087471E+00 - 9.000001E-01 6.000000E+01 2 1.495766E+00 5.134853E+01 9.342274E-01 1.168133E+00 - 9.000001E-01 6.000000E+01 3 1.335133E-01 1.577747E+02 -1.235937E-01 5.050145E-02 - 9.000001E-01 6.000000E+01 4 6.085460E-01 -1.030611E+02 -1.375258E-01 -5.928026E-01 - 9.000001E-01 6.000000E+01 5 1.975831E-01 -1.385824E+02 -1.481691E-01 -1.307095E-01 - 9.000001E-01 6.000000E+01 6 3.867049E+00 -6.315012E+01 1.746570E+00 -3.450154E+00 - 9.000001E-01 9.000000E+01 1 2.148013E-06 -3.934335E+01 1.661189E-06 -1.361768E-06 - 9.000001E-01 9.000000E+01 2 5.254689E-01 6.716647E+01 2.039109E-01 4.842912E-01 - 9.000001E-01 9.000000E+01 3 2.646114E-01 -2.418865E+01 2.413789E-01 -1.084225E-01 - 9.000001E-01 9.000000E+01 4 1.538332E+00 9.886794E+01 -2.371452E-01 1.519943E+00 - 9.000001E-01 9.000000E+01 5 5.961102E-07 -1.758145E+02 -5.945204E-07 -4.350777E-08 - 9.000001E-01 9.000000E+01 6 2.369981E-04 1.465884E+02 -1.978308E-04 1.305030E-04 - 1.000000E+00 0.000000E+00 1 4.498790E+00 1.417020E+02 -3.530643E+00 2.788131E+00 - 1.000000E+00 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.000000E+00 0.000000E+00 3 4.891869E-01 1.280575E+02 -3.015603E-01 3.851821E-01 - 1.000000E+00 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.000000E+00 0.000000E+00 5 1.111608E+00 -4.117408E+01 8.367217E-01 -7.318260E-01 - 1.000000E+00 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.000000E+00 3.000000E+01 1 9.384710E-01 6.006435E+01 4.683224E-01 8.132662E-01 - 1.000000E+00 3.000000E+01 2 5.688173E-01 6.984396E+01 1.960020E-01 5.339816E-01 - 1.000000E+00 3.000000E+01 3 3.170465E-01 1.560125E+02 -2.896644E-01 1.288915E-01 - 1.000000E+00 3.000000E+01 4 2.548091E+00 -1.309901E+02 -1.671366E+00 -1.923358E+00 - 1.000000E+00 3.000000E+01 5 2.532068E-01 -1.020614E+02 -5.291017E-02 -2.476170E-01 - 1.000000E+00 3.000000E+01 6 1.370568E+01 8.000809E+01 2.378060E+00 1.349780E+01 - 1.000000E+00 6.000000E+01 1 1.063347E+00 1.199143E+02 -5.302954E-01 9.216798E-01 - 1.000000E+00 6.000000E+01 2 9.221056E-01 -1.749147E+02 -9.184759E-01 -8.173476E-02 - 1.000000E+00 6.000000E+01 3 5.232720E-01 -1.733326E+02 -5.197331E-01 -6.075449E-02 - 1.000000E+00 6.000000E+01 4 5.569331E-01 -2.655671E+01 4.981723E-01 -2.489956E-01 - 1.000000E+00 6.000000E+01 5 4.033430E-01 -6.104259E+01 1.952823E-01 -3.529170E-01 - 1.000000E+00 6.000000E+01 6 9.770492E+00 4.874333E+01 6.442988E+00 7.345094E+00 - 1.000000E+00 9.000000E+01 1 3.758858E-06 3.555691E+01 3.057976E-06 2.185818E-06 - 1.000000E+00 9.000000E+01 2 2.487580E+00 1.172793E+02 -1.140129E+00 2.210919E+00 - 1.000000E+00 9.000000E+01 3 9.679143E-02 8.315680E+00 9.577379E-02 1.399865E-02 - 1.000000E+00 9.000000E+01 4 2.912810E+00 -1.650378E+02 -2.814055E+00 -7.520341E-01 - 1.000000E+00 9.000000E+01 5 6.350767E-07 -1.537991E+02 -5.698235E-07 -2.803990E-07 - 1.000000E+00 9.000000E+01 6 3.296134E-04 -1.187178E+02 -1.583778E-04 -2.890700E-04 - 1.100000E+00 0.000000E+00 1 2.409579E+00 1.689714E+02 -2.365078E+00 4.609488E-01 - 1.100000E+00 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.100000E+00 0.000000E+00 3 7.349316E-01 -1.583984E+02 -6.833147E-01 -2.705651E-01 - 1.100000E+00 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.100000E+00 0.000000E+00 5 6.515889E-01 2.371388E+00 6.510308E-01 2.696060E-02 - 1.100000E+00 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.100000E+00 3.000000E+01 1 1.383384E+00 -2.329154E+01 1.270645E+00 -5.470040E-01 - 1.100000E+00 3.000000E+01 2 7.300221E-01 -7.040385E+01 2.448408E-01 -6.877392E-01 - 1.100000E+00 3.000000E+01 3 2.772623E-01 -6.642005E+01 1.109128E-01 -2.541117E-01 - 1.100000E+00 3.000000E+01 4 2.365005E+00 1.220531E+02 -1.255120E+00 2.004475E+00 - 1.100000E+00 3.000000E+01 5 1.840076E-01 1.413332E+02 -1.436718E-01 1.149662E-01 - 1.100000E+00 3.000000E+01 6 1.300902E+01 -7.074613E+00 1.290998E+01 -1.602214E+00 - 1.100000E+00 6.000000E+01 1 6.888239E-01 1.965264E+01 6.486992E-01 2.316631E-01 - 1.100000E+00 6.000000E+01 2 1.274021E+00 7.086687E+01 4.175786E-01 1.203644E+00 - 1.100000E+00 6.000000E+01 3 3.023910E-01 -1.388350E+02 -2.276452E-01 -1.990427E-01 - 1.100000E+00 6.000000E+01 4 4.212014E+00 1.605077E+02 -3.970607E+00 1.405468E+00 - 1.100000E+00 6.000000E+01 5 6.740979E-02 1.239330E+02 -3.762972E-02 5.592928E-02 - 1.100000E+00 6.000000E+01 6 6.277072E+00 -1.779185E+02 -6.272930E+00 -2.279956E-01 - 1.100000E+00 9.000000E+01 1 9.634122E-07 1.621139E+02 -9.168493E-07 2.958890E-07 - 1.100000E+00 9.000000E+01 2 3.993272E-01 -1.672850E+02 -3.895345E-01 -8.789238E-02 - 1.100000E+00 9.000000E+01 3 3.142914E-01 1.432106E+02 -2.516979E-01 1.882212E-01 - 1.100000E+00 9.000000E+01 4 3.689179E+00 -3.181832E+01 3.134784E+00 -1.945037E+00 - 1.100000E+00 9.000000E+01 5 4.653694E-07 -5.811555E+01 2.458118E-07 -3.951522E-07 - 1.100000E+00 9.000000E+01 6 6.607713E-05 2.584140E-01 6.607646E-05 2.980184E-07 - 1.200000E+00 0.000000E+00 1 1.443482E+00 -1.671270E+02 -1.407202E+00 -3.215949E-01 - 1.200000E+00 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.200000E+00 0.000000E+00 3 4.628122E-01 -1.645647E+02 -4.461193E-01 -1.231774E-01 - 1.200000E+00 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.200000E+00 0.000000E+00 5 5.352653E-01 4.020810E+01 4.087847E-01 3.455489E-01 - 1.200000E+00 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.200000E+00 3.000000E+01 1 2.075541E+00 1.748229E+02 -2.067074E+00 1.872850E-01 - 1.200000E+00 3.000000E+01 2 1.362046E+00 1.108371E+02 -4.844972E-01 1.272962E+00 - 1.200000E+00 3.000000E+01 3 8.534918E-01 -1.128969E+02 -3.320719E-01 -7.862421E-01 - 1.200000E+00 3.000000E+01 4 2.205437E+00 1.177562E+01 2.159022E+00 4.500845E-01 - 1.200000E+00 3.000000E+01 5 6.961068E-01 -5.783009E+00 6.925641E-01 -7.014059E-02 - 1.200000E+00 3.000000E+01 6 1.774967E+01 -7.653576E+01 4.132805E+00 -1.726183E+01 - 1.200000E+00 6.000000E+01 1 2.512922E+00 1.082590E+02 -7.873306E-01 2.386397E+00 - 1.200000E+00 6.000000E+01 2 4.185233E+00 8.515934E+01 3.531708E-01 4.170305E+00 - 1.200000E+00 6.000000E+01 3 3.349589E-01 5.579454E+01 1.883012E-01 2.770200E-01 - 1.200000E+00 6.000000E+01 4 1.705958E+00 2.558417E+01 1.538692E+00 7.366951E-01 - 1.200000E+00 6.000000E+01 5 9.582613E-01 -7.502637E+01 2.475901E-01 -9.257234E-01 - 1.200000E+00 6.000000E+01 6 1.168844E+02 1.558077E+02 -1.066191E+02 4.789923E+01 - 1.200000E+00 9.000000E+01 1 3.344430E-06 -1.190675E+02 -1.624855E-06 -2.923193E-06 - 1.200000E+00 9.000000E+01 2 3.579329E+00 -7.162445E+01 1.128362E+00 -3.396821E+00 - 1.200000E+00 9.000000E+01 3 5.534689E-01 1.540251E+02 -4.975608E-01 2.424069E-01 - 1.200000E+00 9.000000E+01 4 1.741812E+00 1.029711E+02 -3.909655E-01 1.697367E+00 - 1.200000E+00 9.000000E+01 5 1.616718E-06 8.714442E+01 8.054281E-08 1.614711E-06 - 1.200000E+00 9.000000E+01 6 4.290794E-04 -2.489748E+01 3.892018E-04 -1.806407E-04 - 1.300000E+00 0.000000E+00 1 7.003986E+00 1.314920E+02 -4.640247E+00 5.246325E+00 - 1.300000E+00 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.300000E+00 0.000000E+00 3 6.571900E-01 -1.645828E+02 -6.335413E-01 -1.747112E-01 - 1.300000E+00 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.300000E+00 0.000000E+00 5 2.849876E+00 -4.921009E+01 1.861788E+00 -2.157670E+00 - 1.300000E+00 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.300000E+00 3.000000E+01 1 2.263089E+00 1.555407E+02 -2.059990E+00 9.370242E-01 - 1.300000E+00 3.000000E+01 2 2.027119E+00 1.166973E+02 -9.107381E-01 1.811013E+00 - 1.300000E+00 3.000000E+01 3 5.080034E-01 6.292294E+01 2.312373E-01 4.523238E-01 - 1.300000E+00 3.000000E+01 4 4.724977E+00 -4.095230E+01 3.568564E+00 -3.096894E+00 - 1.300000E+00 3.000000E+01 5 6.495391E-01 -1.060814E+01 6.384380E-01 -1.195743E-01 - 1.300000E+00 3.000000E+01 6 3.506529E+01 7.157618E+01 1.108216E+01 3.326801E+01 - 1.300000E+00 6.000000E+01 1 9.093643E-01 8.503635E+01 7.868150E-02 9.059540E-01 - 1.300000E+00 6.000000E+01 2 2.073938E+00 1.441509E+02 -1.681056E+00 1.214607E+00 - 1.300000E+00 6.000000E+01 3 1.249524E+00 2.353761E+00 1.248470E+00 5.131713E-02 - 1.300000E+00 6.000000E+01 4 1.618520E+00 -1.168375E+02 -7.307007E-01 -1.444189E+00 - 1.300000E+00 6.000000E+01 5 5.895178E-01 -1.037552E+02 -1.401722E-01 -5.726107E-01 - 1.300000E+00 6.000000E+01 6 1.155252E+02 4.325387E+01 8.413983E+01 7.916157E+01 - 1.300000E+00 9.000000E+01 1 7.389086E-06 3.724580E+01 5.882055E-06 4.472139E-06 - 1.300000E+00 9.000000E+01 2 2.336719E+00 -1.787105E+02 -2.336127E+00 -5.258447E-02 - 1.300000E+00 9.000000E+01 3 4.543476E-01 -1.128423E+02 -1.763758E-01 -4.187163E-01 - 1.300000E+00 9.000000E+01 4 2.450729E+00 1.110250E+02 -8.792601E-01 2.287569E+00 - 1.300000E+00 9.000000E+01 5 3.034535E-06 -1.440656E+02 -2.457031E-06 -1.780843E-06 - 1.300000E+00 9.000000E+01 6 4.249371E-04 -1.246016E+02 -2.413078E-04 -3.497743E-04 - 1.400000E+00 0.000000E+00 1 1.171565E+01 7.347941E+01 3.331463E+00 1.123200E+01 - 1.400000E+00 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.400000E+00 0.000000E+00 3 2.655761E-01 -3.997689E+01 2.035120E-01 -1.706269E-01 - 1.400000E+00 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.400000E+00 0.000000E+00 5 5.973072E+00 -1.114528E+02 -2.184563E+00 -5.559251E+00 - 1.400000E+00 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.400000E+00 3.000000E+01 1 1.173266E+01 7.165550E+01 3.692616E+00 1.113642E+01 - 1.400000E+00 3.000000E+01 2 4.782632E+00 5.907642E+01 2.457768E+00 4.102797E+00 - 1.400000E+00 3.000000E+01 3 1.455644E+00 6.325904E+01 6.549782E-01 1.299963E+00 - 1.400000E+00 3.000000E+01 4 5.447604E+00 1.608448E+02 -5.145986E+00 1.787515E+00 - 1.400000E+00 3.000000E+01 5 5.153780E+00 -1.096298E+02 -1.731364E+00 -4.854259E+00 - 1.400000E+00 3.000000E+01 6 2.281675E+01 9.611151E+01 -2.429159E+00 2.268707E+01 - 1.400000E+00 6.000000E+01 1 1.157303E+01 -1.016479E+02 -2.336565E+00 -1.133470E+01 - 1.400000E+00 6.000000E+01 2 1.292264E+01 -9.645769E+01 -1.453401E+00 -1.284064E+01 - 1.400000E+00 6.000000E+01 3 6.924345E-01 1.279500E+02 -4.258292E-01 5.460174E-01 - 1.400000E+00 6.000000E+01 4 5.056304E+00 1.624172E+02 -4.820082E+00 1.527424E+00 - 1.400000E+00 6.000000E+01 5 5.463288E+00 7.882168E+01 1.059131E+00 5.359642E+00 - 1.400000E+00 6.000000E+01 6 1.273826E+02 1.634732E+02 -1.221200E+02 3.623571E+01 - 1.400000E+00 9.000000E+01 1 7.535232E-06 1.578394E+02 -6.978606E-06 2.842320E-06 - 1.400000E+00 9.000000E+01 2 1.086191E+01 6.206549E+01 5.088391E+00 9.596318E+00 - 1.400000E+00 9.000000E+01 3 9.402484E-02 -1.133706E+02 -3.729743E-02 -8.631090E-02 - 1.400000E+00 9.000000E+01 4 3.135868E+00 1.319860E+01 3.053032E+00 7.160037E-01 - 1.400000E+00 9.000000E+01 5 4.244722E-06 -2.349240E+01 3.892890E-06 -1.692062E-06 - 1.400000E+00 9.000000E+01 6 4.178208E-04 1.586816E+02 -3.892313E-04 1.518986E-04 - 1.500000E+00 0.000000E+00 1 2.253690E+01 2.170131E+01 2.093958E+01 8.333425E+00 - 1.500000E+00 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.500000E+00 0.000000E+00 3 8.662427E-01 1.083845E+02 -2.732056E-01 8.220311E-01 - 1.500000E+00 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.500000E+00 0.000000E+00 5 1.326415E+01 -1.582939E+02 -1.232364E+01 -4.905677E+00 - 1.500000E+00 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.500000E+00 3.000000E+01 1 3.378882E+00 9.253078E+00 3.334915E+00 5.433093E-01 - 1.500000E+00 3.000000E+01 2 7.914361E+00 2.474301E+01 7.187777E+00 3.312547E+00 - 1.500000E+00 3.000000E+01 3 5.950861E-01 -3.377501E+01 4.946517E-01 -3.308280E-01 - 1.500000E+00 3.000000E+01 4 8.162408E+00 -1.378921E+02 -6.055557E+00 -5.473128E+00 - 1.500000E+00 3.000000E+01 5 1.556425E+00 1.701120E+02 -1.533305E+00 2.672737E-01 - 1.500000E+00 3.000000E+01 6 3.121408E+01 -1.125936E+02 -1.199218E+01 -2.881851E+01 - 1.500000E+00 6.000000E+01 1 8.058857E+00 1.511977E+01 7.779881E+00 2.102053E+00 - 1.500000E+00 6.000000E+01 2 1.575511E+01 2.624129E+01 1.413138E+01 6.966158E+00 - 1.500000E+00 6.000000E+01 3 1.023166E+00 1.520826E+02 -9.040931E-01 4.790444E-01 - 1.500000E+00 6.000000E+01 4 3.840172E+00 5.642629E+01 2.123651E+00 3.199536E+00 - 1.500000E+00 6.000000E+01 5 5.091404E+00 -1.611259E+02 -4.817647E+00 -1.647017E+00 - 1.500000E+00 6.000000E+01 6 1.822460E+01 1.319307E+02 -1.217826E+01 1.355825E+01 - 1.500000E+00 9.000000E+01 1 7.987765E-06 1.628710E+02 -7.633459E-06 2.352590E-06 - 1.500000E+00 9.000000E+01 2 5.198710E+00 1.088665E+02 -1.681076E+00 4.919408E+00 - 1.500000E+00 9.000000E+01 3 6.865063E-01 4.361718E+01 4.970066E-01 4.735772E-01 - 1.500000E+00 9.000000E+01 4 7.910254E+00 1.620439E+01 7.595998E+00 2.207472E+00 - 1.500000E+00 9.000000E+01 5 4.914498E-06 -2.147218E+01 4.573409E-06 -1.798949E-06 - 1.500000E+00 9.000000E+01 6 5.152921E-04 1.271103E+02 -3.109023E-04 4.109327E-04 - 1.600000E+00 0.000000E+00 1 2.117395E+01 -6.286393E+01 9.657549E+00 -1.884324E+01 - 1.600000E+00 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.600000E+00 0.000000E+00 3 6.416135E-02 1.035933E+02 -1.507976E-02 6.236409E-02 - 1.600000E+00 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.600000E+00 0.000000E+00 5 1.372208E+01 1.168204E+02 -6.191330E+00 1.224594E+01 - 1.600000E+00 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.600000E+00 3.000000E+01 1 1.415636E+00 3.696273E+01 1.131131E+00 8.512152E-01 - 1.600000E+00 3.000000E+01 2 2.140322E+00 3.397316E+01 1.774968E+00 1.196021E+00 - 1.600000E+00 3.000000E+01 3 2.697981E+00 -4.465592E+01 1.919183E+00 -1.896270E+00 - 1.600000E+00 3.000000E+01 4 3.825750E+00 1.541572E+02 -3.443149E+00 1.667660E+00 - 1.600000E+00 3.000000E+01 5 3.813242E-01 -1.302608E+02 -2.464376E-01 -2.909925E-01 - 1.600000E+00 3.000000E+01 6 5.789972E+01 -1.640426E+02 -5.566863E+01 -1.591795E+01 - 1.600000E+00 6.000000E+01 1 6.619334E+00 1.283833E+02 -4.110074E+00 5.188725E+00 - 1.600000E+00 6.000000E+01 2 1.838614E+01 1.424945E+02 -1.458563E+01 1.119418E+01 - 1.600000E+00 6.000000E+01 3 2.027168E+00 -1.594750E+02 -1.898481E+00 -7.107591E-01 - 1.600000E+00 6.000000E+01 4 9.656239E+00 1.708991E+02 -9.534679E+00 1.527363E+00 - 1.600000E+00 6.000000E+01 5 4.125096E+00 -4.624290E+01 2.852927E+00 -2.979468E+00 - 1.600000E+00 6.000000E+01 6 2.767762E+01 -1.623947E+02 -2.638127E+01 -8.371320E+00 - 1.600000E+00 9.000000E+01 1 1.362756E-06 -1.219808E+02 -7.217633E-07 -1.155925E-06 - 1.600000E+00 9.000000E+01 2 1.583243E+01 -3.573277E+01 1.285197E+01 -9.246226E+00 - 1.600000E+00 9.000000E+01 3 6.111758E-01 6.304171E+01 2.770716E-01 5.447634E-01 - 1.600000E+00 9.000000E+01 4 4.628506E+00 -3.940343E+01 3.576426E+00 -2.938068E+00 - 1.600000E+00 9.000000E+01 5 9.186458E-07 1.975923E+01 8.645574E-07 3.105651E-07 - 1.600000E+00 9.000000E+01 6 4.913512E-04 5.417681E+01 2.875809E-04 3.984009E-04 - 1.700000E+00 0.000000E+00 1 1.530682E+01 -5.350866E+01 9.102983E+00 -1.230587E+01 - 1.700000E+00 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.700000E+00 0.000000E+00 3 5.826858E-01 4.770614E+01 3.921086E-01 4.310145E-01 - 1.700000E+00 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.700000E+00 0.000000E+00 5 1.124916E+01 1.277608E+02 -6.888609E+00 8.893294E+00 - 1.700000E+00 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.700000E+00 3.000000E+01 1 5.635712E+00 8.176098E+01 8.076141E-01 5.577545E+00 - 1.700000E+00 3.000000E+01 2 7.947534E+00 8.021186E+01 1.351125E+00 7.831843E+00 - 1.700000E+00 3.000000E+01 3 1.510188E+00 -3.053736E+01 1.300722E+00 -7.673268E-01 - 1.700000E+00 3.000000E+01 4 1.109124E+01 6.744710E+01 4.253893E+00 1.024305E+01 - 1.700000E+00 3.000000E+01 5 4.486289E+00 -9.376264E+01 -2.944054E-01 -4.476618E+00 - 1.700000E+00 3.000000E+01 6 3.115220E+01 1.183897E+02 -1.481183E+01 2.740564E+01 - 1.700000E+00 6.000000E+01 1 3.911623E+00 -7.028982E+00 3.882225E+00 -4.786707E-01 - 1.700000E+00 6.000000E+01 2 4.845512E+00 -4.624642E+01 3.350954E+00 -3.500014E+00 - 1.700000E+00 6.000000E+01 3 1.029428E+00 -5.107076E+00 1.025342E+00 -9.163695E-02 - 1.700000E+00 6.000000E+01 4 1.075074E+01 -9.466867E+01 -8.750406E-01 -1.071507E+01 - 1.700000E+00 6.000000E+01 5 3.100899E+00 1.428822E+02 -2.472644E+00 1.871257E+00 - 1.700000E+00 6.000000E+01 6 9.706261E+01 1.629150E+02 -9.277924E+01 2.851603E+01 - 1.700000E+00 9.000000E+01 1 7.440038E-06 -3.070845E+01 6.396773E-06 -3.799403E-06 - 1.700000E+00 9.000000E+01 2 1.270294E+01 -8.442886E+01 1.233221E+00 -1.264294E+01 - 1.700000E+00 9.000000E+01 3 4.901777E-01 -1.579370E+02 -4.542825E-01 -1.841238E-01 - 1.700000E+00 9.000000E+01 4 8.660085E+00 -1.339957E+02 -6.015331E+00 -6.229998E+00 - 1.700000E+00 9.000000E+01 5 6.433670E-06 1.572520E+02 -5.933221E-06 2.487768E-06 - 1.700000E+00 9.000000E+01 6 6.261227E-04 1.977188E+01 5.892108E-04 2.118024E-04 - 1.800000E+00 0.000000E+00 1 1.563779E+01 -2.521997E+01 1.414717E+01 -6.663180E+00 - 1.800000E+00 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.800000E+00 0.000000E+00 3 8.863202E-01 8.969315E+00 8.754823E-01 1.381822E-01 - 1.800000E+00 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.800000E+00 0.000000E+00 5 1.281577E+01 1.564779E+02 -1.175086E+01 5.114805E+00 - 1.800000E+00 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.800000E+00 3.000000E+01 1 2.043249E+01 -1.258618E+02 -1.197001E+01 -1.655915E+01 - 1.800000E+00 3.000000E+01 2 1.070184E+01 -1.181437E+02 -5.047898E+00 -9.436531E+00 - 1.800000E+00 3.000000E+01 3 1.688774E+00 -5.875546E+01 8.759534E-01 -1.443837E+00 - 1.800000E+00 3.000000E+01 4 9.695031E+00 7.104430E+01 3.149306E+00 9.169270E+00 - 1.800000E+00 3.000000E+01 5 1.565632E+01 5.198190E+01 9.642890E+00 1.233430E+01 - 1.800000E+00 3.000000E+01 6 2.845789E+02 -2.323301E+01 2.615019E+02 -1.122582E+02 - 1.800000E+00 6.000000E+01 1 1.510823E+01 -1.385775E+02 -1.132893E+01 -9.995703E+00 - 1.800000E+00 6.000000E+01 2 1.004253E+01 -8.650637E+01 6.119674E-01 -1.002386E+01 - 1.800000E+00 6.000000E+01 3 1.388990E+00 6.042284E+00 1.381273E+00 1.462084E-01 - 1.800000E+00 6.000000E+01 4 1.351580E+01 -1.059756E+02 -3.719937E+00 -1.299381E+01 - 1.800000E+00 6.000000E+01 5 1.413674E+01 4.748552E+01 9.553273E+00 1.042028E+01 - 1.800000E+00 6.000000E+01 6 3.829813E+02 -1.331674E+01 3.726835E+02 -8.821362E+01 - 1.800000E+00 9.000000E+01 1 5.628297E-06 1.162374E+02 -2.488218E-06 5.048415E-06 - 1.800000E+00 9.000000E+01 2 6.767492E+00 -4.651331E+01 4.657294E+00 -4.910047E+00 - 1.800000E+00 9.000000E+01 3 1.506869E+00 -6.931219E+01 5.323405E-01 -1.409705E+00 - 1.800000E+00 9.000000E+01 4 1.066799E+01 -9.853442E+01 -1.583167E+00 -1.054986E+01 - 1.800000E+00 9.000000E+01 5 4.086576E-06 -6.425894E+01 1.774819E-06 -3.681049E-06 - 1.800000E+00 9.000000E+01 6 6.607128E-04 -2.933037E+01 5.760159E-04 -3.236466E-04 - 1.900000E+00 0.000000E+00 1 2.451026E+01 -1.332121E+02 -1.678221E+01 -1.786365E+01 - 1.900000E+00 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.900000E+00 0.000000E+00 3 1.532402E+00 2.599337E+01 1.377392E+00 6.716014E-01 - 1.900000E+00 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.900000E+00 0.000000E+00 5 2.241921E+01 4.611429E+01 1.554149E+01 1.615807E+01 - 1.900000E+00 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.900000E+00 3.000000E+01 1 1.175581E+01 -9.466068E+01 -9.552123E-01 -1.171694E+01 - 1.900000E+00 3.000000E+01 2 9.560308E+00 -9.428857E+01 -7.149178E-01 -9.533540E+00 - 1.900000E+00 3.000000E+01 3 1.041836E+00 -5.468043E+01 6.023233E-01 -8.500760E-01 - 1.900000E+00 3.000000E+01 4 8.651684E+00 7.486741E+01 2.258555E+00 8.351681E+00 - 1.900000E+00 3.000000E+01 5 8.733264E+00 8.609362E+01 5.949658E-01 8.712974E+00 - 1.900000E+00 3.000000E+01 6 1.218528E+02 1.527181E+02 -1.082982E+02 5.585350E+01 - 1.900000E+00 6.000000E+01 1 4.766725E+00 1.457030E+02 -3.937923E+00 2.685968E+00 - 1.900000E+00 6.000000E+01 2 7.627123E+00 6.175206E+01 3.609826E+00 6.718791E+00 - 1.900000E+00 6.000000E+01 3 1.806216E+00 -1.179529E+00 1.805833E+00 -3.718132E-02 - 1.900000E+00 6.000000E+01 4 2.338598E+00 5.864749E+01 1.216777E+00 1.997122E+00 - 1.900000E+00 6.000000E+01 5 4.262382E+00 -1.407905E+01 4.134345E+00 -1.036868E+00 - 1.900000E+00 6.000000E+01 6 1.326395E+02 -1.746618E+02 -1.320642E+02 -1.234013E+01 - 1.900000E+00 9.000000E+01 1 5.604497E-06 6.239099E+00 5.571302E-06 6.090841E-07 - 1.900000E+00 9.000000E+01 2 1.889650E+01 -1.268181E+02 -1.132423E+01 -1.512744E+01 - 1.900000E+00 9.000000E+01 3 1.551565E+00 -1.180688E+02 -7.300589E-01 -1.369075E+00 - 1.900000E+00 9.000000E+01 4 2.209306E+01 -1.472831E+02 -1.858802E+01 -1.194106E+01 - 1.900000E+00 9.000000E+01 5 6.493098E-06 -1.682033E+02 -6.355958E-06 -1.327448E-06 - 1.900000E+00 9.000000E+01 6 5.750424E-04 -4.119217E+01 4.327223E-04 -3.787153E-04 - 2.000000E+00 0.000000E+00 1 5.821302E+00 -6.600632E+01 2.367150E+00 -5.318286E+00 - 2.000000E+00 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.000000E+00 0.000000E+00 3 8.212474E-01 -5.246426E+00 8.178069E-01 -7.509445E-02 - 2.000000E+00 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.000000E+00 0.000000E+00 5 5.942253E+00 1.149928E+02 -2.510632E+00 5.385824E+00 - 2.000000E+00 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.000000E+00 3.000000E+01 1 2.971290E+01 1.648385E+02 -2.867867E+01 7.771135E+00 - 2.000000E+00 3.000000E+01 2 2.109365E+01 -1.544192E+02 -1.902600E+01 -9.107873E+00 - 2.000000E+00 3.000000E+01 3 1.116087E+00 1.449782E+02 -9.140012E-01 6.405092E-01 - 2.000000E+00 3.000000E+01 4 1.737694E+01 1.613567E+02 -1.646511E+01 5.554991E+00 - 2.000000E+00 3.000000E+01 5 3.115120E+01 -2.130091E+01 2.902312E+01 -1.131617E+01 - 2.000000E+00 3.000000E+01 6 1.132266E+02 -9.659354E+01 -1.300126E+01 -1.124777E+02 - 2.000000E+00 6.000000E+01 1 1.129384E+01 -7.250443E+01 3.395290E+00 -1.077139E+01 - 2.000000E+00 6.000000E+01 2 8.313642E+00 1.825148E+01 7.895391E+00 2.603735E+00 - 2.000000E+00 6.000000E+01 3 3.279949E+00 -2.767537E+01 2.904701E+00 -1.523410E+00 - 2.000000E+00 6.000000E+01 4 1.487036E+01 1.412784E+01 1.442059E+01 3.629652E+00 - 2.000000E+00 6.000000E+01 5 1.104694E+01 1.092108E+02 -3.634940E+00 1.043178E+01 - 2.000000E+00 6.000000E+01 6 5.640735E+02 1.091309E+02 -1.848626E+02 5.329210E+02 - 2.000000E+00 9.000000E+01 1 1.187785E-05 8.651313E+01 7.224082E-07 1.185586E-05 - 2.000000E+00 9.000000E+01 2 3.749706E+01 -1.751489E+02 -3.736274E+01 -3.170978E+00 - 2.000000E+00 9.000000E+01 3 1.734941E+00 -6.733071E+01 6.686662E-01 -1.600908E+00 - 2.000000E+00 9.000000E+01 4 3.541190E+01 -1.760981E+02 -3.532981E+01 -2.409709E+00 - 2.000000E+00 9.000000E+01 5 1.130888E-05 -8.963467E+01 7.210677E-08 -1.130865E-05 - 2.000000E+00 9.000000E+01 6 7.684740E-04 -6.270164E+01 3.524407E-04 -6.828893E-04 - 2.100000E+00 0.000000E+00 1 3.469384E+01 -1.632826E+02 -3.322751E+01 -9.979723E+00 - 2.100000E+00 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.100000E+00 0.000000E+00 3 3.800893E-01 1.574097E+02 -3.509271E-01 1.460069E-01 - 2.100000E+00 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.100000E+00 0.000000E+00 5 3.752528E+01 1.653084E+01 3.597424E+01 1.067712E+01 - 2.100000E+00 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.100000E+00 3.000000E+01 1 3.390757E+00 4.897110E+01 2.225828E+00 2.557914E+00 - 2.100000E+00 3.000000E+01 2 8.254489E+00 -9.804829E+01 -1.155693E+00 -8.173185E+00 - 2.100000E+00 3.000000E+01 3 2.355528E+00 1.350706E+02 -1.667662E+00 1.663556E+00 - 2.100000E+00 3.000000E+01 4 4.972169E+00 2.617470E+01 4.462290E+00 2.193272E+00 - 2.100000E+00 3.000000E+01 5 8.047062E+00 -1.089703E+02 -2.615923E+00 -7.610003E+00 - 2.100000E+00 3.000000E+01 6 1.375585E+02 1.384727E+02 -1.029817E+02 9.119812E+01 - 2.100000E+00 6.000000E+01 1 9.750317E+00 -1.259258E+02 -5.720868E+00 -7.895591E+00 - 2.100000E+00 6.000000E+01 2 3.188938E+00 4.149963E+01 2.388387E+00 2.113039E+00 - 2.100000E+00 6.000000E+01 3 2.481020E+00 -4.064047E+01 1.882626E+00 -1.615914E+00 - 2.100000E+00 6.000000E+01 4 1.363382E+01 6.727907E+01 5.265969E+00 1.257579E+01 - 2.100000E+00 6.000000E+01 5 1.113503E+01 5.728171E+01 6.018582E+00 9.368325E+00 - 2.100000E+00 6.000000E+01 6 1.587328E+02 1.919057E+01 1.499120E+02 5.217724E+01 - 2.100000E+00 9.000000E+01 1 7.526227E-06 -6.560124E+01 3.108969E-06 -6.854080E-06 - 2.100000E+00 9.000000E+01 2 2.984016E+01 1.745603E+02 -2.970577E+01 2.828802E+00 - 2.100000E+00 9.000000E+01 3 2.147939E+00 -1.599565E+02 -2.017844E+00 -7.361711E-01 - 2.100000E+00 9.000000E+01 4 2.823634E+01 1.683424E+02 -2.765389E+01 5.705529E+00 - 2.100000E+00 9.000000E+01 5 8.384823E-06 1.164150E+02 -3.730158E-06 7.509405E-06 - 2.100000E+00 9.000000E+01 6 6.949179E-04 -1.031911E+02 -1.585795E-04 -6.765822E-04 - 2.200000E+00 0.000000E+00 1 1.840914E+01 1.246068E+02 -1.045532E+01 1.515199E+01 - 2.200000E+00 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.200000E+00 0.000000E+00 3 3.016562E+00 7.359667E+01 8.518687E-01 2.893780E+00 - 2.200000E+00 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.200000E+00 0.000000E+00 5 2.189817E+01 -5.459550E+01 1.268660E+01 -1.784881E+01 - 2.200000E+00 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.200000E+00 3.000000E+01 1 1.003793E+01 1.687380E+02 -9.844638E+00 1.960372E+00 - 2.200000E+00 3.000000E+01 2 7.348200E+00 -1.333114E+02 -5.040593E+00 -5.346819E+00 - 2.200000E+00 3.000000E+01 3 3.990573E+00 1.612579E+02 -3.778970E+00 1.282207E+00 - 2.200000E+00 3.000000E+01 4 2.769185E+00 1.150331E+02 -1.171758E+00 2.509058E+00 - 2.200000E+00 3.000000E+01 5 1.299058E+01 -2.709982E+01 1.156440E+01 -5.917757E+00 - 2.200000E+00 3.000000E+01 6 4.706312E+02 6.546182E+01 1.954529E+02 4.281260E+02 - 2.200000E+00 6.000000E+01 1 9.554170E+00 -5.325864E+01 5.715340E+00 -7.656177E+00 - 2.200000E+00 6.000000E+01 2 5.871254E+00 -1.696238E+02 -5.775238E+00 -1.057474E+00 - 2.200000E+00 6.000000E+01 3 4.580588E+00 -6.968203E+00 4.546754E+00 -5.557101E-01 - 2.200000E+00 6.000000E+01 4 9.044420E+00 9.761833E+01 -1.199051E+00 8.964586E+00 - 2.200000E+00 6.000000E+01 5 1.148960E+01 1.325676E+02 -7.772250E+00 8.461858E+00 - 2.200000E+00 6.000000E+01 6 4.873628E+02 -1.109005E+02 -1.738651E+02 -4.552949E+02 - 2.200000E+00 9.000000E+01 1 6.787387E-06 2.305665E+01 6.245197E-06 2.658220E-06 - 2.200000E+00 9.000000E+01 2 1.074581E+01 1.732706E+02 -1.067178E+01 1.259205E+00 - 2.200000E+00 9.000000E+01 3 4.149904E+00 -1.095534E+02 -1.388911E+00 -3.910579E+00 - 2.200000E+00 9.000000E+01 4 6.907977E+00 1.615725E+02 -6.553764E+00 2.183648E+00 - 2.200000E+00 9.000000E+01 5 8.732525E-06 -1.405445E+02 -6.742548E-06 -5.549329E-06 - 2.200000E+00 9.000000E+01 6 7.234850E-04 -1.137432E+02 -2.913027E-04 -6.622486E-04 - 2.300000E+00 0.000000E+00 1 6.652022E+00 1.714180E+02 -6.577542E+00 9.926440E-01 - 2.300000E+00 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.300000E+00 0.000000E+00 3 3.341569E+00 9.958330E+01 -5.563088E-01 3.294936E+00 - 2.300000E+00 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.300000E+00 0.000000E+00 5 8.600190E+00 -1.346889E+01 8.363655E+00 -2.003134E+00 - 2.300000E+00 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.300000E+00 3.000000E+01 1 2.813330E+01 1.017791E+02 -5.743085E+00 2.754087E+01 - 2.300000E+00 3.000000E+01 2 1.331318E+01 1.719806E+02 -1.318299E+01 1.857306E+00 - 2.300000E+00 3.000000E+01 3 5.697778E+00 1.764393E+02 -5.686778E+00 3.538708E-01 - 2.300000E+00 3.000000E+01 4 1.458461E+01 1.343526E+02 -1.019570E+01 1.042874E+01 - 2.300000E+00 3.000000E+01 5 4.251502E+01 -7.939967E+01 7.820933E+00 -4.178947E+01 - 2.300000E+00 3.000000E+01 6 2.409720E+02 1.194129E+01 2.357574E+02 4.985936E+01 - 2.300000E+00 6.000000E+01 1 8.122261E+00 -2.673362E+00 8.113421E+00 -3.788389E-01 - 2.300000E+00 6.000000E+01 2 1.754300E+01 -7.681292E+01 4.002109E+00 -1.708040E+01 - 2.300000E+00 6.000000E+01 3 3.457100E+00 6.086721E+01 1.683038E+00 3.019755E+00 - 2.300000E+00 6.000000E+01 4 1.385956E+01 -4.006794E+01 1.060647E+01 -8.921338E+00 - 2.300000E+00 6.000000E+01 5 1.238480E+01 -1.746265E+02 -1.233038E+01 -1.159803E+00 - 2.300000E+00 6.000000E+01 6 8.567575E+02 -1.341973E+02 -5.972726E+02 -6.142466E+02 - 2.300000E+00 9.000000E+01 1 8.110849E-06 5.452580E+01 4.707020E-06 6.605288E-06 - 2.300000E+00 9.000000E+01 2 1.484728E+01 -1.770321E+02 -1.482736E+01 -7.687485E-01 - 2.300000E+00 9.000000E+01 3 3.613738E+00 -4.756544E+01 2.438361E+00 -2.667114E+00 - 2.300000E+00 9.000000E+01 4 1.042713E+01 -1.320228E+02 -6.980190E+00 -7.746091E+00 - 2.300000E+00 9.000000E+01 5 1.129052E-05 -1.152556E+02 -4.817187E-06 -1.021129E-05 - 2.300000E+00 9.000000E+01 6 6.935667E-04 -1.311100E+02 -4.560248E-04 -5.225670E-04 - 2.400000E+00 0.000000E+00 1 6.691988E+01 1.437616E+02 -5.397520E+01 3.955941E+01 - 2.400000E+00 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.400000E+00 0.000000E+00 3 2.040703E+00 1.177941E+02 -9.515707E-01 1.805265E+00 - 2.400000E+00 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.400000E+00 0.000000E+00 5 9.895098E+01 -3.651546E+01 7.952654E+01 -5.887976E+01 - 2.400000E+00 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.400000E+00 3.000000E+01 1 2.056048E+01 -7.887166E+01 3.968325E+00 -2.017389E+01 - 2.400000E+00 3.000000E+01 2 1.794580E+01 -6.599496E+01 7.300655E+00 -1.639366E+01 - 2.400000E+00 3.000000E+01 3 4.279415E+00 -1.772949E+02 -4.274646E+00 -2.019664E-01 - 2.400000E+00 3.000000E+01 4 2.314850E+01 -5.315101E+01 1.388234E+01 -1.852386E+01 - 2.400000E+00 3.000000E+01 5 2.366356E+01 1.133196E+02 -9.367453E+00 2.173051E+01 - 2.400000E+00 3.000000E+01 6 2.629239E+01 1.162468E+02 -1.162751E+01 2.358158E+01 - 2.400000E+00 6.000000E+01 1 1.101585E+01 -7.089606E+01 3.605299E+00 -1.040917E+01 - 2.400000E+00 6.000000E+01 2 2.194420E+01 -7.073899E+01 7.238779E+00 -2.071589E+01 - 2.400000E+00 6.000000E+01 3 2.151742E+00 1.444439E+02 -1.750542E+00 1.251238E+00 - 2.400000E+00 6.000000E+01 4 2.502406E+01 -4.151780E+01 1.873676E+01 -1.658726E+01 - 2.400000E+00 6.000000E+01 5 1.221794E+01 1.362352E+02 -8.823617E+00 8.451142E+00 - 2.400000E+00 6.000000E+01 6 5.474531E+02 -1.368706E+02 -3.995377E+02 -3.742652E+02 - 2.400000E+00 9.000000E+01 1 1.443677E-05 1.781123E+02 -1.442893E-05 4.755645E-07 - 2.400000E+00 9.000000E+01 2 2.785631E+01 -1.771170E+02 -2.782105E+01 -1.401092E+00 - 2.400000E+00 9.000000E+01 3 1.413268E+00 2.660327E+01 1.263643E+00 6.328756E-01 - 2.400000E+00 9.000000E+01 4 1.771157E+01 -1.481608E+02 -1.504654E+01 -9.343523E+00 - 2.400000E+00 9.000000E+01 5 2.027583E-05 -8.507624E+00 2.005272E-05 -2.999627E-06 - 2.400000E+00 9.000000E+01 6 9.715804E-04 -1.369534E+02 -7.100300E-04 -6.631936E-04 - 2.500000E+00 0.000000E+00 1 5.129078E+01 1.138478E+02 -2.073730E+01 4.691171E+01 - 2.500000E+00 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.500000E+00 0.000000E+00 3 1.529491E+00 1.225288E+02 -8.224432E-01 1.289546E+00 - 2.500000E+00 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.500000E+00 0.000000E+00 5 8.451809E+01 -6.702504E+01 3.298985E+01 -7.781374E+01 - 2.500000E+00 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.500000E+00 3.000000E+01 1 4.145443E+01 -4.538499E+01 2.911509E+01 -2.950900E+01 - 2.500000E+00 3.000000E+01 2 3.950846E+01 -6.894279E+01 1.419539E+01 -3.687017E+01 - 2.500000E+00 3.000000E+01 3 3.751704E+00 1.699554E+02 -3.694198E+00 6.543530E-01 - 2.500000E+00 3.000000E+01 4 6.341410E+01 -6.394818E+01 2.785045E+01 -5.697105E+01 - 2.500000E+00 3.000000E+01 5 6.103278E+01 1.379704E+02 -4.533508E+01 4.086234E+01 - 2.500000E+00 3.000000E+01 6 2.903393E+02 5.470456E+01 1.677559E+02 2.369702E+02 - 2.500000E+00 6.000000E+01 1 4.370257E+00 1.419348E+02 -3.440747E+00 2.694514E+00 - 2.500000E+00 6.000000E+01 2 1.341662E+01 -6.668523E+01 5.310061E+00 -1.232108E+01 - 2.500000E+00 6.000000E+01 3 1.843527E+00 1.454165E+02 -1.517775E+00 1.046398E+00 - 2.500000E+00 6.000000E+01 4 2.508925E+01 1.343679E+01 2.440248E+01 5.830053E+00 - 2.500000E+00 6.000000E+01 5 1.784713E+01 -8.089987E+01 2.822708E+00 -1.762249E+01 - 2.500000E+00 6.000000E+01 6 2.772294E+02 3.482975E+01 2.275645E+02 1.583367E+02 - 2.500000E+00 9.000000E+01 1 4.373749E-06 -8.041764E+01 7.280764E-07 -4.312723E-06 - 2.500000E+00 9.000000E+01 2 3.571795E+01 1.595034E+02 -3.345677E+01 1.250667E+01 - 2.500000E+00 9.000000E+01 3 1.586350E+00 9.202799E+01 -5.613745E-02 1.585356E+00 - 2.500000E+00 9.000000E+01 4 3.055895E+01 1.481671E+02 -2.596258E+01 1.611813E+01 - 2.500000E+00 9.000000E+01 5 2.473950E-06 1.016150E+02 -4.980903E-07 2.423290E-06 - 2.500000E+00 9.000000E+01 6 8.151199E-04 -1.394990E+02 -6.198129E-04 -5.293887E-04 - 2.600000E+00 0.000000E+00 1 2.374993E+01 8.941797E+01 2.412556E-01 2.374870E+01 - 2.600000E+00 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.600000E+00 0.000000E+00 3 1.379885E+00 1.207559E+02 -7.056479E-01 1.185809E+00 - 2.600000E+00 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.600000E+00 0.000000E+00 5 3.882188E+01 -9.195899E+01 -1.327094E+00 -3.879919E+01 - 2.600000E+00 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.600000E+00 3.000000E+01 1 2.512787E+01 -7.338380E+01 7.185550E+00 -2.407857E+01 - 2.600000E+00 3.000000E+01 2 3.913450E+01 -7.277780E+01 1.158687E+01 -3.737986E+01 - 2.600000E+00 3.000000E+01 3 4.915434E+00 1.651986E+02 -4.752327E+00 1.255740E+00 - 2.600000E+00 3.000000E+01 4 7.238557E+01 -6.670432E+01 2.862678E+01 -6.648442E+01 - 2.600000E+00 3.000000E+01 5 3.821024E+01 9.774843E+01 -5.151649E+00 3.786136E+01 - 2.600000E+00 3.000000E+01 6 7.005328E+02 1.571709E+01 6.743406E+02 1.897657E+02 - 2.600000E+00 6.000000E+01 1 1.314660E+01 1.011741E+02 -2.547699E+00 1.289738E+01 - 2.600000E+00 6.000000E+01 2 1.136843E+01 9.581977E+01 -1.152753E+00 1.130984E+01 - 2.600000E+00 6.000000E+01 3 2.856414E+00 1.617910E+02 -2.713374E+00 8.925833E-01 - 2.600000E+00 6.000000E+01 4 6.483476E+01 8.739442E+01 2.947407E+00 6.476773E+01 - 2.600000E+00 6.000000E+01 5 4.451958E+01 -7.846105E+01 8.905430E+00 -4.361979E+01 - 2.600000E+00 6.000000E+01 6 9.317444E+02 2.763584E+01 8.254451E+02 4.321898E+02 - 2.600000E+00 9.000000E+01 1 4.715702E-06 -1.099771E+02 -1.611092E-06 -4.431955E-06 - 2.600000E+00 9.000000E+01 2 4.229353E+01 1.186479E+02 -2.027663E+01 3.711604E+01 - 2.600000E+00 9.000000E+01 3 1.893995E+00 1.071196E+02 -5.575296E-01 1.810077E+00 - 2.600000E+00 9.000000E+01 4 5.444688E+01 9.005308E+01 -5.043561E-02 5.444685E+01 - 2.600000E+00 9.000000E+01 5 4.799822E-06 -1.704821E+00 4.797698E-06 -1.427964E-07 - 2.600000E+00 9.000000E+01 6 8.340525E-04 -1.562957E+02 -7.636857E-04 -3.353025E-04 - 2.700000E+00 0.000000E+00 1 1.285704E+01 1.376649E+02 -9.504169E+00 8.658763E+00 - 2.700000E+00 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.700000E+00 0.000000E+00 3 1.071230E+00 1.054962E+02 -2.862057E-01 1.032289E+00 - 2.700000E+00 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.700000E+00 0.000000E+00 5 2.219130E+01 -2.058312E+01 2.077468E+01 -7.801703E+00 - 2.700000E+00 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.700000E+00 3.000000E+01 1 1.246238E+01 -1.406525E+02 -9.637338E+00 -7.901432E+00 - 2.700000E+00 3.000000E+01 2 1.873427E+01 -5.288271E+01 1.130517E+01 -1.493874E+01 - 2.700000E+00 3.000000E+01 3 5.321106E+00 1.741083E+02 -5.292998E+00 5.462034E-01 - 2.700000E+00 3.000000E+01 4 4.667109E+01 -3.742222E+01 3.706520E+01 -2.836127E+01 - 2.700000E+00 3.000000E+01 5 2.527288E+01 2.607484E+01 2.270062E+01 1.110856E+01 - 2.700000E+00 3.000000E+01 6 7.275867E+02 4.028961E+00 7.257886E+02 5.112075E+01 - 2.700000E+00 6.000000E+01 1 3.480887E+01 1.156737E+02 -1.508077E+01 3.137241E+01 - 2.700000E+00 6.000000E+01 2 3.563494E+01 1.025745E+02 -7.758019E+00 3.478020E+01 - 2.700000E+00 6.000000E+01 3 3.903898E+00 1.766144E+02 -3.897084E+00 2.305482E-01 - 2.700000E+00 6.000000E+01 4 1.007721E+02 1.107006E+02 -3.562133E+01 9.426632E+01 - 2.700000E+00 6.000000E+01 5 7.932731E+01 -6.428683E+01 3.441743E+01 -7.147211E+01 - 2.700000E+00 6.000000E+01 6 1.200961E+03 1.413786E+01 1.164585E+03 2.933418E+02 - 2.700000E+00 9.000000E+01 1 1.373922E-05 -5.906470E+01 7.062917E-06 -1.178479E-05 - 2.700000E+00 9.000000E+01 2 8.003942E+01 8.975844E+01 3.374447E-01 8.003871E+01 - 2.700000E+00 9.000000E+01 3 1.309628E+00 1.092766E+02 -4.323460E-01 1.236205E+00 - 2.700000E+00 9.000000E+01 4 1.853950E+02 7.520155E+01 4.735352E+01 1.792455E+02 - 2.700000E+00 9.000000E+01 5 1.659808E-05 1.194172E+02 -8.152405E-06 1.445803E-05 - 2.700000E+00 9.000000E+01 6 8.618580E-04 -1.684376E+02 -8.443682E-04 -1.727471E-04 - 2.799999E+00 0.000000E+00 1 3.084495E+01 1.363763E+02 -2.232826E+01 2.128050E+01 - 2.799999E+00 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.799999E+00 0.000000E+00 3 1.018026E+00 4.981052E+01 6.569498E-01 7.776847E-01 - 2.799999E+00 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.799999E+00 0.000000E+00 5 6.890652E+01 -3.809226E+01 5.423070E+01 -4.251048E+01 - 2.799999E+00 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.799999E+00 3.000000E+01 1 7.436464E+00 6.883179E+01 2.685361E+00 6.934684E+00 - 2.799999E+00 3.000000E+01 2 4.692299E+00 1.573202E+01 4.516528E+00 1.272262E+00 - 2.799999E+00 3.000000E+01 3 5.127012E+00 1.705119E+02 -5.056873E+00 8.451540E-01 - 2.799999E+00 3.000000E+01 4 1.385750E+01 2.200511E+01 1.284799E+01 5.192256E+00 - 2.799999E+00 3.000000E+01 5 2.142159E+01 -1.054122E+02 -5.693040E+00 -2.065124E+01 - 2.799999E+00 3.000000E+01 6 1.663048E+02 3.039669E+01 1.434450E+02 8.414754E+01 - 2.799999E+00 6.000000E+01 1 4.148475E+01 1.089419E+02 -1.346630E+01 3.923829E+01 - 2.799999E+00 6.000000E+01 2 4.794329E+01 9.155702E+01 -1.302705E+00 4.792559E+01 - 2.799999E+00 6.000000E+01 3 4.497569E+00 1.653757E+02 -4.351856E+00 1.135548E+00 - 2.799999E+00 6.000000E+01 4 1.051302E+02 9.357171E+01 -6.549361E+00 1.049260E+02 - 2.799999E+00 6.000000E+01 5 9.666524E+01 -7.074407E+01 3.187907E+01 -9.125729E+01 - 2.799999E+00 6.000000E+01 6 1.340882E+03 3.476051E+00 1.338415E+03 8.129942E+01 - 2.799999E+00 9.000000E+01 1 1.634091E-05 -2.739770E+01 1.450801E-05 -7.519499E-06 - 2.799999E+00 9.000000E+01 2 1.083563E+02 9.151974E+01 -2.873775E+00 1.083182E+02 - 2.799999E+00 9.000000E+01 3 3.234695E+00 7.527977E+01 8.219343E-01 3.128526E+00 - 2.799999E+00 9.000000E+01 4 2.391108E+02 9.031908E+01 -1.331573E+00 2.391071E+02 - 2.799999E+00 9.000000E+01 5 2.194817E-05 1.451231E+02 -1.800589E-05 1.255030E-05 - 2.799999E+00 9.000000E+01 6 1.012854E-03 -1.762982E+02 -1.010741E-03 -6.539427E-05 - 2.899999E+00 0.000000E+00 1 5.913933E+01 7.511961E+01 1.518710E+01 5.715604E+01 - 2.899999E+00 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.899999E+00 0.000000E+00 3 1.474937E+00 3.119394E+01 1.261689E+00 7.639238E-01 - 2.899999E+00 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.899999E+00 0.000000E+00 5 1.361311E+02 -9.472819E+01 -1.122113E+01 -1.356678E+02 - 2.899999E+00 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.899999E+00 3.000000E+01 1 1.404502E+01 7.505493E+01 3.622111E+00 1.356993E+01 - 2.899999E+00 3.000000E+01 2 1.182106E+01 -9.669734E+01 -1.378627E+00 -1.174040E+01 - 2.899999E+00 3.000000E+01 3 6.231650E+00 1.707256E+02 -6.150188E+00 1.004316E+00 - 2.899999E+00 3.000000E+01 4 2.915959E+01 -1.004853E+02 -5.306571E+00 -2.867267E+01 - 2.899999E+00 3.000000E+01 5 3.683768E+01 -1.315670E+02 -2.444164E+01 -2.756121E+01 - 2.899999E+00 3.000000E+01 6 8.204958E+02 1.632954E+02 -7.858704E+02 2.358412E+02 - 2.899999E+00 6.000000E+01 1 5.087309E+01 1.082702E+02 -1.594861E+01 4.830852E+01 - 2.899999E+00 6.000000E+01 2 5.881094E+01 8.293089E+01 7.237651E+00 5.836389E+01 - 2.899999E+00 6.000000E+01 3 6.112622E+00 1.666014E+02 -5.946246E+00 1.416439E+00 - 2.899999E+00 6.000000E+01 4 1.303272E+02 8.085902E+01 2.070435E+01 1.286721E+02 - 2.899999E+00 6.000000E+01 5 1.126831E+02 -7.312285E+01 3.271422E+01 -1.078298E+02 - 2.899999E+00 6.000000E+01 6 1.045594E+03 7.533033E+00 1.036570E+03 1.370750E+02 - 2.899999E+00 9.000000E+01 1 2.153102E-05 2.575455E+01 1.939221E-05 9.355592E-06 - 2.899999E+00 9.000000E+01 2 1.126526E+02 8.799042E+01 3.950352E+00 1.125833E+02 - 2.899999E+00 9.000000E+01 3 4.730039E+00 9.452670E+01 -3.733119E-01 4.715284E+00 - 2.899999E+00 9.000000E+01 4 2.431560E+02 8.754437E+01 1.041817E+01 2.429327E+02 - 2.899999E+00 9.000000E+01 5 3.590472E-05 -1.538434E+02 -3.222781E-05 -1.582773E-05 - 2.899999E+00 9.000000E+01 6 1.082301E-03 -1.765180E+02 -1.080303E-03 -6.573328E-05 - 2.999999E+00 0.000000E+00 1 1.535824E+02 7.256065E+01 4.602804E+01 1.465229E+02 - 2.999999E+00 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.999999E+00 0.000000E+00 3 1.969451E+00 5.637770E+01 1.090516E+00 1.639974E+00 - 2.999999E+00 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.999999E+00 0.000000E+00 5 3.425206E+02 -1.060463E+02 -9.467750E+01 -3.291755E+02 - 2.999999E+00 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.999999E+00 3.000000E+01 1 5.881850E+01 -1.358674E+02 -4.221578E+01 -4.095662E+01 - 2.999999E+00 3.000000E+01 2 3.964449E+01 -9.267473E+01 -1.850040E+00 -3.960130E+01 - 2.999999E+00 3.000000E+01 3 6.848557E+00 1.763287E+02 -6.834503E+00 4.385305E-01 - 2.999999E+00 3.000000E+01 4 9.575523E+01 -9.607970E+01 -1.014161E+01 -9.521666E+01 - 2.999999E+00 3.000000E+01 5 1.050537E+02 5.814314E+01 5.544724E+01 8.922939E+01 - 2.999999E+00 3.000000E+01 6 1.311709E+03 1.717300E+02 -1.298069E+03 1.886731E+02 - 2.999999E+00 6.000000E+01 1 4.004496E+01 1.390207E+02 -3.023180E+01 2.626094E+01 - 2.999999E+00 6.000000E+01 2 5.293253E+01 8.055581E+01 8.685534E+00 5.221508E+01 - 2.999999E+00 6.000000E+01 3 7.548622E+00 1.712188E+02 -7.460140E+00 1.152391E+00 - 2.999999E+00 6.000000E+01 4 1.187431E+02 7.564075E+01 2.944842E+01 1.150335E+02 - 2.999999E+00 6.000000E+01 5 8.239848E+01 -4.672632E+01 5.648284E+01 -5.999332E+01 - 2.999999E+00 6.000000E+01 6 2.921517E+02 2.838828E+01 2.570193E+02 1.389019E+02 - 2.999999E+00 9.000000E+01 1 2.870632E-05 1.225683E+02 -1.545275E-05 2.419226E-05 - 2.999999E+00 9.000000E+01 2 1.085063E+02 8.412341E+01 1.110955E+01 1.079361E+02 - 2.999999E+00 9.000000E+01 3 6.175937E+00 1.148498E+02 -2.595377E+00 5.604125E+00 - 2.999999E+00 9.000000E+01 4 2.412059E+02 8.263962E+01 3.090086E+01 2.392184E+02 - 2.999999E+00 9.000000E+01 5 7.033809E-05 -5.379518E+01 4.154685E-05 -5.675655E-05 - 2.999999E+00 9.000000E+01 6 1.061258E-03 -1.797259E+02 -1.061246E-03 -5.077388E-06 - 3.099999E+00 0.000000E+00 1 1.352772E+02 7.965231E+01 2.429864E+01 1.330770E+02 - 3.099999E+00 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.099999E+00 0.000000E+00 3 4.043180E+00 9.310086E+01 -2.187111E-01 4.037260E+00 - 3.099999E+00 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.099999E+00 0.000000E+00 5 3.204205E+02 -1.041802E+02 -7.849390E+01 -3.106574E+02 - 3.099999E+00 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.099999E+00 3.000000E+01 1 1.023205E+02 -1.063303E+02 -2.876989E+01 -9.819260E+01 - 3.099999E+00 3.000000E+01 2 5.650270E+01 -9.243196E+01 -2.397580E+00 -5.645181E+01 - 3.099999E+00 3.000000E+01 3 5.845279E+00 -1.780309E+02 -5.841827E+00 -2.008460E-01 - 3.099999E+00 3.000000E+01 4 1.438770E+02 -9.665790E+01 -1.668124E+01 -1.429067E+02 - 3.099999E+00 3.000000E+01 5 2.320557E+02 8.034755E+01 3.890910E+01 2.287705E+02 - 3.099999E+00 3.000000E+01 6 1.158180E+03 1.715860E+02 -1.145714E+03 1.694695E+02 - 3.099999E+00 6.000000E+01 1 1.398031E+01 1.693249E+02 -1.373836E+01 2.589702E+00 - 3.099999E+00 6.000000E+01 2 3.398200E+01 6.586255E+01 1.389616E+01 3.101085E+01 - 3.099999E+00 6.000000E+01 3 7.300803E+00 -1.706796E+02 -7.204419E+00 -1.182402E+00 - 3.099999E+00 6.000000E+01 4 7.537634E+01 5.599914E+01 4.215086E+01 6.248919E+01 - 3.099999E+00 6.000000E+01 5 2.412563E+01 2.367664E+01 2.209489E+01 9.688235E+00 - 3.099999E+00 6.000000E+01 6 5.216992E+02 1.745547E+02 -5.193450E+02 4.950640E+01 - 3.099999E+00 9.000000E+01 1 2.174027E-05 -1.530094E+02 -1.937235E-05 -9.866681E-06 - 3.099999E+00 9.000000E+01 2 9.793117E+01 7.983202E+01 1.728826E+01 9.639310E+01 - 3.099999E+00 9.000000E+01 3 6.437273E+00 1.435798E+02 -5.179974E+00 3.821827E+00 - 3.099999E+00 9.000000E+01 4 2.273067E+02 7.777940E+01 4.811544E+01 2.221559E+02 - 3.099999E+00 9.000000E+01 5 6.417438E-05 1.557107E+01 6.181907E-05 1.722655E-05 - 3.099999E+00 9.000000E+01 6 1.061670E-03 1.746794E+02 -1.057096E-03 9.844666E-05 - 3.199999E+00 0.000000E+00 1 9.313126E+01 7.703487E+01 2.089476E+01 9.075704E+01 - 3.199999E+00 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.199999E+00 0.000000E+00 3 6.376946E+00 1.272288E+02 -3.858049E+00 5.077490E+00 - 3.199999E+00 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.199999E+00 0.000000E+00 5 2.207682E+02 -1.136822E+02 -8.867440E+01 -2.021768E+02 - 3.199999E+00 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.199999E+00 3.000000E+01 1 1.148556E+02 -1.046191E+02 -2.898855E+01 -1.111372E+02 - 3.199999E+00 3.000000E+01 2 6.264732E+01 -1.008677E+02 -1.181164E+01 -6.152375E+01 - 3.199999E+00 3.000000E+01 3 4.421484E+00 -1.709751E+02 -4.366747E+00 -6.935720E-01 - 3.199999E+00 3.000000E+01 4 1.708979E+02 -1.044649E+02 -4.268807E+01 -1.654806E+02 - 3.199999E+00 3.000000E+01 5 2.763033E+02 7.809556E+01 5.699586E+01 2.703609E+02 - 3.199999E+00 3.000000E+01 6 7.071581E+02 1.658765E+02 -6.857822E+02 1.725552E+02 - 3.199999E+00 6.000000E+01 1 1.593430E+01 -1.136228E+02 -6.385092E+00 -1.459906E+01 - 3.199999E+00 6.000000E+01 2 1.738074E+01 2.798335E+01 1.534865E+01 8.155304E+00 - 3.199999E+00 6.000000E+01 3 4.390622E+00 1.773398E+02 -4.385890E+00 2.037780E-01 - 3.199999E+00 6.000000E+01 4 4.314693E+01 -5.031633E+00 4.298066E+01 -3.784233E+00 - 3.199999E+00 6.000000E+01 5 8.151366E+01 8.811880E+01 2.675864E+00 8.146973E+01 - 3.199999E+00 6.000000E+01 6 1.115759E+03 1.776656E+02 -1.114833E+03 4.544571E+01 - 3.199999E+00 9.000000E+01 1 1.641946E-05 -1.242221E+02 -9.234337E-06 -1.357666E-05 - 3.199999E+00 9.000000E+01 2 8.466059E+01 7.749667E+01 1.832870E+01 8.265273E+01 - 3.199999E+00 9.000000E+01 3 5.032353E+00 1.462475E+02 -4.184126E+00 2.796008E+00 - 3.199999E+00 9.000000E+01 4 2.031117E+02 7.519678E+01 5.189503E+01 1.963702E+02 - 3.199999E+00 9.000000E+01 5 4.495156E-05 3.121729E+01 3.844293E-05 2.329773E-05 - 3.199999E+00 9.000000E+01 6 1.099406E-03 1.695473E+02 -1.081162E-03 1.994592E-04 - 3.299999E+00 0.000000E+00 1 4.678250E+01 8.237811E+01 6.204999E+00 4.636917E+01 - 3.299999E+00 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.299999E+00 0.000000E+00 3 7.054717E+00 1.426483E+02 -5.607983E+00 4.280135E+00 - 3.299999E+00 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.299999E+00 0.000000E+00 5 1.004503E+02 -1.286896E+02 -6.279161E+01 -7.840590E+01 - 3.299999E+00 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.299999E+00 3.000000E+01 1 1.055210E+02 -1.072739E+02 -3.133335E+01 -1.007616E+02 - 3.299999E+00 3.000000E+01 2 6.150303E+01 -1.091924E+02 -2.021861E+01 -5.808468E+01 - 3.299999E+00 3.000000E+01 3 2.173652E+00 -1.587816E+02 -2.026295E+00 -7.866974E-01 - 3.299999E+00 3.000000E+01 4 1.770257E+02 -1.119721E+02 -6.623500E+01 -1.641676E+02 - 3.299999E+00 3.000000E+01 5 2.544291E+02 7.011642E+01 8.653385E+01 2.392614E+02 - 3.299999E+00 3.000000E+01 6 2.318566E+02 1.571164E+02 -2.136087E+02 9.015990E+01 - 3.299999E+00 6.000000E+01 1 3.435871E+01 -9.594345E+01 -3.557737E+00 -3.417402E+01 - 3.299999E+00 6.000000E+01 2 2.065511E+01 -6.633234E+01 8.291598E+00 -1.891780E+01 - 3.299999E+00 6.000000E+01 3 3.711243E+00 1.619598E+02 -3.528796E+00 1.149315E+00 - 3.299999E+00 6.000000E+01 4 9.041335E+01 -7.612052E+01 2.168839E+01 -8.777351E+01 - 3.299999E+00 6.000000E+01 5 1.689747E+02 9.353695E+01 -1.042441E+01 1.686529E+02 - 3.299999E+00 6.000000E+01 6 1.552885E+03 1.734821E+02 -1.542848E+03 1.762744E+02 - 3.299999E+00 9.000000E+01 1 1.429221E-05 -1.106028E+02 -5.029259E-06 -1.337811E-05 - 3.299999E+00 9.000000E+01 2 6.621753E+01 7.656819E+01 1.538153E+01 6.440629E+01 - 3.299999E+00 9.000000E+01 3 5.661932E+00 1.466332E+02 -4.728658E+00 3.114044E+00 - 3.299999E+00 9.000000E+01 4 1.632255E+02 7.372087E+01 4.575491E+01 1.566814E+02 - 3.299999E+00 9.000000E+01 5 3.369616E-05 3.174554E+01 2.865498E-05 1.772915E-05 - 3.299999E+00 9.000000E+01 6 1.156401E-03 1.667464E+02 -1.125600E-03 2.651193E-04 - 3.399999E+00 0.000000E+00 1 1.361654E+01 1.252903E+02 -7.866537E+00 1.111431E+01 - 3.399999E+00 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.399999E+00 0.000000E+00 3 6.630826E+00 1.534148E+02 -5.929750E+00 2.967477E+00 - 3.399999E+00 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.399999E+00 0.000000E+00 5 3.057225E+01 1.626662E+02 -2.918381E+01 9.108666E+00 - 3.399999E+00 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.399999E+00 3.000000E+01 1 7.400742E+01 -1.119290E+02 -2.763857E+01 -6.865280E+01 - 3.399999E+00 3.000000E+01 2 5.104679E+01 -1.168010E+02 -2.301664E+01 -4.556325E+01 - 3.399999E+00 3.000000E+01 3 1.701708E-01 1.513890E+02 -1.493914E-01 8.148818E-02 - 3.399999E+00 3.000000E+01 4 1.543932E+02 -1.191935E+02 -7.530685E+01 -1.347819E+02 - 3.399999E+00 3.000000E+01 5 1.754636E+02 5.171851E+01 1.087042E+02 1.377348E+02 - 3.399999E+00 3.000000E+01 6 1.745534E+02 -3.068357E+01 1.501157E+02 -8.907393E+01 - 3.399999E+00 6.000000E+01 1 5.649395E+01 -9.294634E+01 -2.903829E+00 -5.641927E+01 - 3.399999E+00 6.000000E+01 2 4.890638E+01 -9.335667E+01 -2.863540E+00 -4.882248E+01 - 3.399999E+00 6.000000E+01 3 1.974456E+00 1.499715E+02 -1.709438E+00 9.880779E-01 - 3.399999E+00 6.000000E+01 4 1.835228E+02 -9.412207E+01 -1.319192E+01 -1.830480E+02 - 3.399999E+00 6.000000E+01 5 2.654980E+02 9.541576E+01 -2.505829E+01 2.643128E+02 - 3.399999E+00 6.000000E+01 6 1.884565E+03 1.682920E+02 -1.845355E+03 3.824237E+02 - 3.399999E+00 9.000000E+01 1 1.524115E-05 -9.668856E+01 -1.775174E-06 -1.513742E-05 - 3.399999E+00 9.000000E+01 2 4.834594E+01 7.256494E+01 1.448564E+01 4.612479E+01 - 3.399999E+00 9.000000E+01 3 6.366030E+00 1.568401E+02 -5.852995E+00 2.503754E+00 - 3.399999E+00 9.000000E+01 4 1.239776E+02 6.965963E+01 4.309418E+01 1.162469E+02 - 3.399999E+00 9.000000E+01 5 2.766623E-05 2.271446E+01 2.552046E-05 1.068301E-05 - 3.399999E+00 9.000000E+01 6 1.139374E-03 1.668813E+02 -1.109638E-03 2.586038E-04 - 3.499999E+00 0.000000E+00 1 8.050917E+00 1.672397E+02 -7.852081E+00 1.778225E+00 - 3.499999E+00 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.499999E+00 0.000000E+00 3 5.365941E+00 1.646354E+02 -5.174159E+00 1.421762E+00 - 3.499999E+00 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.499999E+00 0.000000E+00 5 2.002238E+01 1.748561E+02 -1.994174E+01 1.795141E+00 - 3.499999E+00 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.499999E+00 3.000000E+01 1 3.266153E+01 -1.400336E+02 -2.503250E+01 -2.097973E+01 - 3.499999E+00 3.000000E+01 2 3.473077E+01 -1.264799E+02 -2.064885E+01 -2.792581E+01 - 3.499999E+00 3.000000E+01 3 1.774829E+00 8.915792E+01 2.608388E-02 1.774637E+00 - 3.499999E+00 3.000000E+01 4 1.095299E+02 -1.286510E+02 -6.840970E+01 -8.553900E+01 - 3.499999E+00 3.000000E+01 5 1.383809E+02 -1.414545E+00 1.383387E+02 -3.416065E+00 - 3.499999E+00 3.000000E+01 6 4.447607E+02 -3.494680E+01 3.645633E+02 -2.547658E+02 - 3.499999E+00 6.000000E+01 1 7.875937E+01 -8.723781E+01 3.795474E+00 -7.866786E+01 - 3.499999E+00 6.000000E+01 2 7.877679E+01 -1.023097E+02 -1.679493E+01 -7.696567E+01 - 3.499999E+00 6.000000E+01 3 2.027775E+00 3.002265E+01 1.755703E+00 1.014581E+00 - 3.499999E+00 6.000000E+01 4 2.833362E+02 -1.022665E+02 -6.019749E+01 -2.768676E+02 - 3.499999E+00 6.000000E+01 5 3.520478E+02 9.965697E+01 -5.905570E+01 3.470592E+02 - 3.499999E+00 6.000000E+01 6 2.114968E+03 1.639057E+02 -2.032075E+03 5.863102E+02 - 3.499999E+00 9.000000E+01 1 1.697149E-05 -7.374596E+01 4.750265E-06 -1.629314E-05 - 3.499999E+00 9.000000E+01 2 3.708871E+01 6.821251E+01 1.376604E+01 3.443935E+01 - 3.499999E+00 9.000000E+01 3 6.407467E+00 1.718145E+02 -6.342189E+00 9.122886E-01 - 3.499999E+00 9.000000E+01 4 9.978592E+01 6.746081E+01 3.824947E+01 9.216402E+01 - 3.499999E+00 9.000000E+01 5 2.805061E-05 1.040976E+01 2.758892E-05 5.068373E-06 - 3.499999E+00 9.000000E+01 6 1.127239E-03 1.654328E+02 -1.091002E-03 2.835178E-04 - 3.599999E+00 0.000000E+00 1 2.577330E+01 9.237114E+01 -1.066301E+00 2.575124E+01 - 3.599999E+00 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.599999E+00 0.000000E+00 3 4.057404E+00 1.715391E+02 -4.013245E+00 5.969842E-01 - 3.599999E+00 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.599999E+00 0.000000E+00 5 1.168028E+02 -9.787395E+01 -1.600130E+01 -1.157016E+02 - 3.599999E+00 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.599999E+00 3.000000E+01 1 3.466184E+01 1.459034E+02 -2.870325E+01 1.943107E+01 - 3.599999E+00 3.000000E+01 2 1.695292E+01 -1.442497E+02 -1.375849E+01 -9.904814E+00 - 3.599999E+00 3.000000E+01 3 3.636840E+00 1.338848E+02 -2.521097E+00 2.621197E+00 - 3.599999E+00 3.000000E+01 4 5.423851E+01 -1.489744E+02 -4.647898E+01 -2.795567E+01 - 3.599999E+00 3.000000E+01 5 2.045745E+02 -3.209956E+01 1.733004E+02 -1.087093E+02 - 3.599999E+00 3.000000E+01 6 4.912776E+02 -3.812108E+01 3.864920E+02 -3.032781E+02 - 3.599999E+00 6.000000E+01 1 8.862406E+01 -8.002473E+01 1.535174E+01 -8.728429E+01 - 3.599999E+00 6.000000E+01 2 1.076934E+02 -1.082558E+02 -3.373612E+01 -1.022729E+02 - 3.599999E+00 6.000000E+01 3 6.449351E+00 2.759315E+01 5.715795E+00 2.987276E+00 - 3.599999E+00 6.000000E+01 4 3.844471E+02 -1.080811E+02 -1.193178E+02 -3.654625E+02 - 3.599999E+00 6.000000E+01 5 3.885133E+02 1.044001E+02 -9.662006E+01 3.763072E+02 - 3.599999E+00 6.000000E+01 6 2.230641E+03 1.606511E+02 -2.104650E+03 7.390564E+02 - 3.599999E+00 9.000000E+01 1 1.746707E-05 -4.613996E+01 1.210292E-05 -1.259436E-05 - 3.599999E+00 9.000000E+01 2 3.031299E+01 7.251962E+01 9.105392E+00 2.891313E+01 - 3.599999E+00 9.000000E+01 3 5.550235E+00 -1.756765E+02 -5.534440E+00 -4.184227E-01 - 3.599999E+00 9.000000E+01 4 8.694468E+01 7.543147E+01 2.186988E+01 8.414919E+01 - 3.599999E+00 9.000000E+01 5 2.958998E-05 1.050274E+01 2.909423E-05 5.393735E-06 - 3.599999E+00 9.000000E+01 6 1.111655E-03 1.640854E+02 -1.069047E-03 3.048207E-04 - 3.699999E+00 0.000000E+00 1 6.448834E+01 8.812731E+01 2.107403E+00 6.445390E+01 - 3.699999E+00 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.699999E+00 0.000000E+00 3 4.135828E+00 1.736109E+02 -4.110141E+00 4.602304E-01 - 3.699999E+00 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.699999E+00 0.000000E+00 5 2.780600E+02 -8.937009E+01 3.056895E+00 -2.780432E+02 - 3.699999E+00 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.699999E+00 3.000000E+01 1 4.616284E+01 1.214222E+02 -2.406658E+01 3.939299E+01 - 3.699999E+00 3.000000E+01 2 6.240627E+00 1.255741E+02 -3.630517E+00 5.075901E+00 - 3.699999E+00 3.000000E+01 3 5.365453E+00 1.765769E+02 -5.355880E+00 3.203621E-01 - 3.699999E+00 3.000000E+01 4 3.015887E+01 1.169264E+02 -1.365729E+01 2.688932E+01 - 3.699999E+00 3.000000E+01 5 2.150159E+02 -4.157241E+01 1.608572E+02 -1.426772E+02 - 3.699999E+00 3.000000E+01 6 2.990040E+02 -4.463598E+01 2.127668E+02 -2.100802E+02 - 3.699999E+00 6.000000E+01 1 8.421621E+01 -7.756512E+01 1.813427E+01 -8.224061E+01 - 3.699999E+00 6.000000E+01 2 1.357168E+02 -1.126557E+02 -5.227703E+01 -1.252444E+02 - 3.699999E+00 6.000000E+01 3 9.447015E+00 4.043707E+01 7.190301E+00 6.127451E+00 - 3.699999E+00 6.000000E+01 4 4.851443E+02 -1.124662E+02 -1.853927E+02 -4.483242E+02 - 3.699999E+00 6.000000E+01 5 3.718708E+02 1.051254E+02 -9.703284E+01 3.589882E+02 - 3.699999E+00 6.000000E+01 6 2.221244E+03 1.585461E+02 -2.067339E+03 8.124263E+02 - 3.699999E+00 9.000000E+01 1 1.675151E-05 -1.914058E+01 1.582543E-05 -5.492601E-06 - 3.699999E+00 9.000000E+01 2 2.606002E+01 9.104572E+01 -4.755977E-01 2.605568E+01 - 3.699999E+00 9.000000E+01 3 4.797679E+00 -1.754465E+02 -4.782536E+00 -3.808895E-01 - 3.699999E+00 9.000000E+01 4 8.483791E+01 9.507306E+01 -7.501873E+00 8.450558E+01 - 3.699999E+00 9.000000E+01 5 2.136629E-05 2.694220E+01 1.904728E-05 9.680883E-06 - 3.699999E+00 9.000000E+01 6 1.095377E-03 1.630527E+02 -1.047808E-03 3.192936E-04 - 3.799999E+00 0.000000E+00 1 9.680605E+01 8.504037E+01 8.369260E+00 9.644360E+01 - 3.799999E+00 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.799999E+00 0.000000E+00 3 5.284828E+00 -1.749997E+02 -5.264716E+00 -4.606299E-01 - 3.799999E+00 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.799999E+00 0.000000E+00 5 4.108856E+02 -8.898692E+01 7.264781E+00 -4.108213E+02 - 3.799999E+00 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.799999E+00 3.000000E+01 1 4.886696E+01 9.373832E+01 -3.186108E+00 4.876299E+01 - 3.799999E+00 3.000000E+01 2 1.746278E+01 5.889301E+01 9.021933E+00 1.495170E+01 - 3.799999E+00 3.000000E+01 3 6.057806E+00 -1.521841E+02 -5.357835E+00 -2.826767E+00 - 3.799999E+00 3.000000E+01 4 7.572858E+01 6.843237E+01 2.783778E+01 7.042639E+01 - 3.799999E+00 3.000000E+01 5 1.618238E+02 -6.106374E+01 7.829624E+01 -1.416215E+02 - 3.799999E+00 3.000000E+01 6 1.136665E+02 1.716626E+02 -1.124651E+02 1.648192E+01 - 3.799999E+00 6.000000E+01 1 7.506390E+01 -8.244417E+01 9.870318E+00 -7.441214E+01 - 3.799999E+00 6.000000E+01 2 1.623081E+02 -1.157113E+02 -7.041512E+01 -1.462383E+02 - 3.799999E+00 6.000000E+01 3 9.810149E+00 4.842605E+01 6.509879E+00 7.338972E+00 - 3.799999E+00 6.000000E+01 4 5.820505E+02 -1.156258E+02 -2.517319E+02 -5.247988E+02 - 3.799999E+00 6.000000E+01 5 3.351341E+02 1.002252E+02 -5.949224E+01 3.298113E+02 - 3.799999E+00 6.000000E+01 6 2.078295E+03 1.573983E+02 -1.918680E+03 7.987352E+02 - 3.799999E+00 9.000000E+01 1 1.561437E-05 5.050616E+00 1.555374E-05 1.374623E-06 - 3.799999E+00 9.000000E+01 2 2.564585E+01 1.215206E+02 -1.340777E+01 2.186187E+01 - 3.799999E+00 9.000000E+01 3 5.158154E+00 -1.783746E+02 -5.156078E+00 -1.463055E-01 - 3.799999E+00 9.000000E+01 4 9.451308E+01 1.181360E+02 -4.456914E+01 8.334455E+01 - 3.799999E+00 9.000000E+01 5 5.694140E-06 -1.429422E+02 -4.544086E-06 -3.431402E-06 - 3.799999E+00 9.000000E+01 6 1.075892E-03 1.624064E+02 -1.025566E-03 3.252031E-04 - 3.899998E+00 0.000000E+00 1 1.199427E+02 7.651603E+01 2.796745E+01 1.166365E+02 - 3.899998E+00 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.899998E+00 0.000000E+00 3 6.305821E+00 -1.622106E+02 -6.004313E+00 -1.926551E+00 - 3.899998E+00 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.899998E+00 0.000000E+00 5 4.949913E+02 -9.490263E+01 -4.230329E+01 -4.931804E+02 - 3.899998E+00 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.899998E+00 3.000000E+01 1 6.339765E+01 6.585059E+01 2.593709E+01 5.784919E+01 - 3.899998E+00 3.000000E+01 2 3.166013E+01 3.966199E+01 2.437271E+01 2.020731E+01 - 3.899998E+00 3.000000E+01 3 5.663646E+00 -1.308824E+02 -3.706906E+00 -4.282024E+00 - 3.899998E+00 3.000000E+01 4 1.285910E+02 5.258181E+01 7.813549E+01 1.021298E+02 - 3.899998E+00 3.000000E+01 5 1.490516E+02 -1.063731E+02 -4.201637E+01 -1.430070E+02 - 3.899998E+00 3.000000E+01 6 6.498409E+02 1.471119E+02 -5.456924E+02 3.528640E+02 - 3.899998E+00 6.000000E+01 1 6.852900E+01 -9.329747E+01 -3.941782E+00 -6.841554E+01 - 3.899998E+00 6.000000E+01 2 1.866383E+02 -1.175325E+02 -8.627378E+01 -1.655013E+02 - 3.899998E+00 6.000000E+01 3 8.832902E+00 4.766920E+01 5.948164E+00 6.529892E+00 - 3.899998E+00 6.000000E+01 4 6.714777E+02 -1.176640E+02 -3.117577E+02 -5.947179E+02 - 3.899998E+00 6.000000E+01 5 3.008390E+02 9.106235E+01 -5.577679E+00 3.007873E+02 - 3.899998E+00 6.000000E+01 6 1.807456E+03 1.565780E+02 -1.658525E+03 7.184641E+02 - 3.899998E+00 9.000000E+01 1 1.434072E-05 2.640816E+01 1.284425E-05 6.378219E-06 - 3.899998E+00 9.000000E+01 2 2.865577E+01 1.522909E+02 -2.536953E+01 1.332442E+01 - 3.899998E+00 9.000000E+01 3 5.945359E+00 -1.762351E+02 -5.932528E+00 -3.903839E-01 - 3.899998E+00 9.000000E+01 4 1.056488E+02 1.360561E+02 -7.606926E+01 7.331535E+01 - 3.899998E+00 9.000000E+01 5 3.824207E-05 -1.125429E+02 -1.466106E-05 -3.532010E-05 - 3.899998E+00 9.000000E+01 6 1.051411E-03 1.620507E+02 -1.000238E-03 3.240192E-04 - 3.999998E+00 0.000000E+00 1 1.436809E+02 6.415221E+01 6.264229E+01 1.293064E+02 - 3.999998E+00 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.999998E+00 0.000000E+00 3 6.736756E+00 -1.539550E+02 -6.052634E+00 -2.957956E+00 - 3.999998E+00 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.999998E+00 0.000000E+00 5 5.601800E+02 -1.058728E+02 -1.532105E+02 -5.388211E+02 - 3.999998E+00 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.999998E+00 3.000000E+01 1 8.682338E+01 5.205758E+01 5.338503E+01 6.847144E+01 - 3.999998E+00 3.000000E+01 2 4.819812E+01 2.988014E+01 4.179112E+01 2.401169E+01 - 3.999998E+00 3.000000E+01 3 4.733355E+00 -1.156061E+02 -2.045673E+00 -4.268475E+00 - 3.999998E+00 3.000000E+01 4 1.867685E+02 4.412656E+01 1.340631E+02 1.300368E+02 - 3.999998E+00 3.000000E+01 5 2.228042E+02 -1.358351E+02 -1.598257E+02 -1.552336E+02 - 3.999998E+00 3.000000E+01 6 1.290208E+03 1.445139E+02 -1.050561E+03 7.489717E+02 - 3.999998E+00 6.000000E+01 1 6.732007E+01 -1.073700E+02 -2.009781E+01 -6.425006E+01 - 3.999998E+00 6.000000E+01 2 2.078974E+02 -1.181541E+02 -9.809530E+01 -1.832993E+02 - 3.999998E+00 6.000000E+01 3 7.912072E+00 3.934391E+01 6.118838E+00 5.016046E+00 - 3.999998E+00 6.000000E+01 4 7.497960E+02 -1.185743E+02 -3.586257E+02 -6.584692E+02 - 3.999998E+00 6.000000E+01 5 2.748507E+02 7.875133E+01 5.361447E+01 2.695708E+02 - 3.999998E+00 6.000000E+01 6 1.442472E+03 1.549349E+02 -1.306630E+03 6.110990E+02 - 3.999998E+00 9.000000E+01 1 1.314687E-05 4.594492E+01 9.141666E-06 9.448280E-06 - 3.999998E+00 9.000000E+01 2 3.048443E+01 1.780125E+02 -3.046609E+01 1.057267E+00 - 3.999998E+00 9.000000E+01 3 6.787580E+00 -1.731823E+02 -6.739584E+00 -8.057644E-01 - 3.999998E+00 9.000000E+01 4 1.024031E+02 1.458316E+02 -8.472736E+01 5.751231E+01 - 3.999998E+00 9.000000E+01 5 6.856214E-05 -9.788301E+01 -9.403356E-06 -6.791424E-05 - 3.999998E+00 9.000000E+01 6 1.022519E-03 1.618751E+02 -9.717822E-04 3.180952E-04 - 4.099998E+00 0.000000E+00 1 1.769769E+02 5.216186E+01 1.085635E+02 1.397670E+02 - 4.099998E+00 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 4.099998E+00 0.000000E+00 3 6.656598E+00 -1.504145E+02 -5.788711E+00 -3.286505E+00 - 4.099998E+00 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 4.099998E+00 0.000000E+00 5 6.470839E+02 -1.186960E+02 -3.107056E+02 -5.676087E+02 - 4.099998E+00 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 4.099998E+00 3.000000E+01 1 1.083780E+02 4.710453E+01 7.376889E+01 7.939737E+01 - 4.099998E+00 3.000000E+01 2 6.552439E+01 2.731570E+01 5.821786E+01 3.006869E+01 - 4.099998E+00 3.000000E+01 3 3.793626E+00 -1.018131E+02 -7.766338E-01 -3.713279E+00 - 4.099998E+00 3.000000E+01 4 2.468741E+02 4.157050E+01 1.846964E+02 1.638111E+02 - 4.099998E+00 3.000000E+01 5 3.059917E+02 -1.451601E+02 -2.511432E+02 -1.748085E+02 - 4.099998E+00 3.000000E+01 6 1.953405E+03 1.440962E+02 -1.582263E+03 1.145528E+03 - 4.099998E+00 6.000000E+01 1 7.278704E+01 -1.211571E+02 -3.765905E+01 -6.228763E+01 - 4.099998E+00 6.000000E+01 2 2.250607E+02 -1.174773E+02 -1.038424E+02 -1.996724E+02 - 4.099998E+00 6.000000E+01 3 7.562171E+00 2.844657E+01 6.649127E+00 3.602157E+00 - 4.099998E+00 6.000000E+01 4 8.121299E+02 -1.182283E+02 -3.841263E+02 -7.155431E+02 - 4.099998E+00 6.000000E+01 5 2.641593E+02 6.395090E+01 1.160033E+02 2.373255E+02 - 4.099998E+00 6.000000E+01 6 1.038762E+03 1.507644E+02 -9.064431E+02 5.073342E+02 - 4.099998E+00 9.000000E+01 1 1.218451E-05 6.544556E+01 5.063365E-06 1.108262E-05 - 4.099998E+00 9.000000E+01 2 2.692613E+01 -1.580917E+02 -2.498158E+01 -1.004675E+01 - 4.099998E+00 9.000000E+01 3 7.728706E+00 -1.708995E+02 -7.631421E+00 -1.222420E+00 - 4.099998E+00 9.000000E+01 4 7.902838E+01 1.398593E+02 -6.041432E+01 5.094698E+01 - 4.099998E+00 9.000000E+01 5 9.701904E-05 -8.663662E+01 5.691952E-06 -9.685192E-05 - 4.099998E+00 9.000000E+01 6 9.907717E-04 1.618420E+02 -9.414321E-04 3.087624E-04 - 4.199998E+00 0.000000E+00 1 2.222129E+02 4.372376E+01 1.605889E+02 1.535896E+02 - 4.199998E+00 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 4.199998E+00 0.000000E+00 3 6.272953E+00 -1.497196E+02 -5.417120E+00 -3.163029E+00 - 4.199998E+00 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 4.199998E+00 0.000000E+00 5 7.777079E+02 -1.293957E+02 -4.935896E+02 -6.009982E+02 - 4.199998E+00 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 4.199998E+00 3.000000E+01 1 1.235069E+02 4.672363E+01 8.466619E+01 8.991985E+01 - 4.199998E+00 3.000000E+01 2 7.948988E+01 2.993484E+01 6.888541E+01 3.966662E+01 - 4.199998E+00 3.000000E+01 3 3.152623E+00 -8.481982E+01 2.846442E-01 -3.139747E+00 - 4.199998E+00 3.000000E+01 4 2.969751E+02 4.384402E+01 2.141868E+02 2.057139E+02 - 4.199998E+00 3.000000E+01 5 3.638582E+02 -1.468557E+02 -3.046570E+02 -1.989394E+02 - 4.199998E+00 3.000000E+01 6 2.577388E+03 1.443839E+02 -2.095253E+03 1.500947E+03 - 4.199998E+00 6.000000E+01 1 8.496262E+01 -1.310437E+02 -5.578941E+01 -6.407954E+01 - 4.199998E+00 6.000000E+01 2 2.361464E+02 -1.153644E+02 -1.011588E+02 -2.133824E+02 - 4.199998E+00 6.000000E+01 3 7.540276E+00 1.941462E+01 7.111519E+00 2.506401E+00 - 4.199998E+00 6.000000E+01 4 8.499861E+02 -1.165007E+02 -3.792712E+02 -7.606771E+02 - 4.199998E+00 6.000000E+01 5 2.771346E+02 4.957950E+01 1.796919E+02 2.109843E+02 - 4.199998E+00 6.000000E+01 6 6.496003E+02 1.407102E+02 -5.027601E+02 4.113549E+02 - 4.199998E+00 9.000000E+01 1 1.162693E-05 8.708602E+01 5.910740E-07 1.161190E-05 - 4.199998E+00 9.000000E+01 2 1.717420E+01 -1.257395E+02 -1.003147E+01 -1.393998E+01 - 4.199998E+00 9.000000E+01 3 8.776693E+00 -1.691979E+02 -8.621174E+00 -1.644905E+00 - 4.199998E+00 9.000000E+01 4 7.172317E+01 9.604378E+01 -7.551608E+00 7.132451E+01 - 4.199998E+00 9.000000E+01 5 1.239009E-04 -7.636890E+01 2.919967E-05 -1.204110E-04 - 4.199998E+00 9.000000E+01 6 9.571696E-04 1.619692E+02 -9.101634E-04 2.962704E-04 - 4.299998E+00 0.000000E+00 1 2.769825E+02 4.001219E+01 2.121430E+02 1.780860E+02 - 4.299998E+00 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 4.299998E+00 0.000000E+00 3 5.694993E+00 -1.497345E+02 -4.918758E+00 -2.870323E+00 - 4.299998E+00 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 4.299998E+00 0.000000E+00 5 9.487909E+02 -1.354382E+02 -6.760075E+02 -6.657462E+02 - 4.299998E+00 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 4.299998E+00 3.000000E+01 1 1.304576E+02 4.986138E+01 8.409808E+01 9.973315E+01 - 4.299998E+00 3.000000E+01 2 8.628721E+01 3.583747E+01 6.995141E+01 5.052013E+01 - 4.299998E+00 3.000000E+01 3 2.998477E+00 -6.388546E+01 1.319831E+00 -2.692380E+00 - 4.299998E+00 3.000000E+01 4 3.243755E+02 4.959517E+01 2.102551E+02 2.470067E+02 - 4.299998E+00 3.000000E+01 5 3.863448E+02 -1.441945E+02 -3.133285E+02 -2.260256E+02 - 4.299998E+00 3.000000E+01 6 3.126312E+03 1.450128E+02 -2.561323E+03 1.792609E+03 - 4.299998E+00 6.000000E+01 1 1.021343E+02 -1.351964E+02 -7.246703E+01 -7.197182E+01 - 4.299998E+00 6.000000E+01 2 2.381832E+02 -1.119180E+02 -8.890878E+01 -2.209671E+02 - 4.299998E+00 6.000000E+01 3 7.493745E+00 1.328287E+01 7.293269E+00 1.721753E+00 - 4.299998E+00 6.000000E+01 4 8.518859E+02 -1.135350E+02 -3.401663E+02 -7.810228E+02 - 4.299998E+00 6.000000E+01 5 3.114526E+02 4.011540E+01 2.381828E+02 2.006780E+02 - 4.299998E+00 6.000000E+01 6 3.336525E+02 1.111197E+02 -1.202209E+02 3.112410E+02 - 4.299998E+00 9.000000E+01 1 1.169914E-05 1.126883E+02 -4.512574E-06 1.079382E-05 - 4.299998E+00 9.000000E+01 2 1.171045E+01 -3.668459E+01 9.391036E+00 -6.995934E+00 - 4.299998E+00 9.000000E+01 3 9.869135E+00 -1.678559E+02 -9.648279E+00 -2.076180E+00 - 4.299998E+00 9.000000E+01 4 1.410076E+02 6.587157E+01 5.764157E+01 1.286880E+02 - 4.299998E+00 9.000000E+01 5 1.475130E-04 -6.556328E+01 6.102437E-05 -1.342986E-04 - 4.299998E+00 9.000000E+01 6 9.218401E-04 1.622708E+02 -8.780588E-04 2.807167E-04 - 4.399998E+00 0.000000E+00 1 3.343017E+02 4.143633E+01 2.506232E+02 2.212366E+02 - 4.399998E+00 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 4.399998E+00 0.000000E+00 3 4.950696E+00 -1.486069E+02 -4.225980E+00 -2.578854E+00 - 4.399998E+00 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 4.399998E+00 0.000000E+00 5 1.134238E+03 -1.358509E+02 -8.138492E+02 -7.900288E+02 - 4.399998E+00 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 4.399998E+00 3.000000E+01 1 1.271773E+02 5.689435E+01 6.946230E+01 1.065320E+02 - 4.399998E+00 3.000000E+01 2 8.429147E+01 4.361216E+01 6.102916E+01 5.814200E+01 - 4.399998E+00 3.000000E+01 3 3.361035E+00 -4.464866E+01 2.391139E+00 -2.361993E+00 - 4.399998E+00 3.000000E+01 4 3.224410E+02 5.764745E+01 1.725470E+02 2.723889E+02 - 4.399998E+00 3.000000E+01 5 3.667534E+02 -1.374053E+02 -2.699893E+02 -2.482214E+02 - 4.399998E+00 3.000000E+01 6 3.582413E+03 1.460116E+02 -2.970361E+03 2.002658E+03 - 4.399998E+00 6.000000E+01 1 1.208290E+02 -1.332758E+02 -8.282953E+01 -8.797112E+01 - 4.399998E+00 6.000000E+01 2 2.289413E+02 -1.076797E+02 -6.952862E+01 -2.181281E+02 - 4.399998E+00 6.000000E+01 3 7.232306E+00 9.682171E+00 7.129288E+00 1.216348E+00 - 4.399998E+00 6.000000E+01 4 8.101049E+02 -1.099217E+02 -2.760321E+02 -7.616274E+02 - 4.399998E+00 6.000000E+01 5 3.493807E+02 3.800619E+01 2.752925E+02 2.151300E+02 - 4.399998E+00 6.000000E+01 6 3.082111E+02 3.977768E+01 2.368704E+02 1.971967E+02 - 4.399998E+00 9.000000E+01 1 9.736978E-06 -1.223660E+02 -5.212446E-06 -8.224301E-06 - 4.399998E+00 9.000000E+01 2 2.901769E+01 2.097297E+01 2.709525E+01 1.038623E+01 - 4.399998E+00 9.000000E+01 3 1.092908E+01 -1.668187E+02 -1.064114E+01 -2.492191E+00 - 4.399998E+00 9.000000E+01 4 2.484756E+02 6.239579E+01 1.151340E+02 2.201915E+02 - 4.399998E+00 9.000000E+01 5 1.173416E-04 -7.779848E+01 2.480024E-05 -1.146909E-04 - 4.399998E+00 9.000000E+01 6 8.845504E-04 1.627181E+02 -8.446172E-04 2.627760E-04 - 4.499998E+00 0.000000E+00 1 3.779098E+02 4.799015E+01 2.529193E+02 2.807982E+02 - 4.499998E+00 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 4.499998E+00 0.000000E+00 3 4.052723E+00 -1.444656E+02 -3.297972E+00 -2.355407E+00 - 4.499998E+00 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 4.499998E+00 0.000000E+00 5 1.275649E+03 -1.306416E+02 -8.308618E+02 -9.679617E+02 - 4.499998E+00 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 4.499998E+00 3.000000E+01 1 1.105494E+02 6.842512E+01 4.065087E+01 1.028040E+02 - 4.499998E+00 3.000000E+01 2 7.465453E+01 5.225248E+01 4.570224E+01 5.903053E+01 - 4.499998E+00 3.000000E+01 3 4.060913E+00 -3.087147E+01 3.485565E+00 -2.083710E+00 - 4.499998E+00 3.000000E+01 4 2.938735E+02 6.712950E+01 1.142138E+02 2.707708E+02 - 4.499998E+00 3.000000E+01 5 2.988004E+02 -1.262189E+02 -1.765529E+02 -2.410618E+02 - 4.499998E+00 3.000000E+01 6 3.932096E+03 1.475261E+02 -3.317257E+03 2.111204E+03 - 4.499998E+00 6.000000E+01 1 1.344396E+02 -1.256581E+02 -7.837117E+01 -1.092335E+02 - 4.499998E+00 6.000000E+01 2 2.091497E+02 -1.035040E+02 -4.883919E+01 -2.033674E+02 - 4.499998E+00 6.000000E+01 3 6.686349E+00 8.363100E+00 6.615248E+00 9.725019E-01 - 4.499998E+00 6.000000E+01 4 7.285418E+02 -1.065712E+02 -2.077849E+02 -6.982826E+02 - 4.499998E+00 6.000000E+01 5 3.606620E+02 4.315837E+01 2.630906E+02 2.466990E+02 - 4.499998E+00 6.000000E+01 6 5.779142E+02 6.874489E+00 5.737595E+02 6.917333E+01 - 4.499998E+00 9.000000E+01 1 1.015033E-05 -1.126452E+02 -3.908118E-06 -9.367806E-06 - 4.499998E+00 9.000000E+01 2 5.162467E+01 4.145635E+01 3.869064E+01 3.417807E+01 - 4.499998E+00 9.000000E+01 3 1.188245E+01 -1.660739E+02 -1.153318E+01 -2.859762E+00 - 4.499998E+00 9.000000E+01 4 3.639225E+02 6.548040E+01 1.510294E+02 3.311037E+02 - 4.499998E+00 9.000000E+01 5 1.262468E-04 -7.941154E+01 2.319828E-05 -1.240971E-04 - 4.499998E+00 9.000000E+01 6 8.453398E-04 1.632377E+02 -8.094208E-04 2.437979E-04 - 4.599998E+00 0.000000E+00 1 3.841077E+02 5.818426E+01 2.024975E+02 3.263947E+02 - 4.599998E+00 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 4.599998E+00 0.000000E+00 3 3.049386E+00 -1.344309E+02 -2.134718E+00 -2.177552E+00 - 4.599998E+00 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 4.599998E+00 0.000000E+00 5 1.292093E+03 -1.214620E+02 -6.743853E+02 -1.102138E+03 - 4.599998E+00 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 4.599998E+00 3.000000E+01 1 8.041452E+01 8.405013E+01 8.335629E+00 7.998132E+01 - 4.599998E+00 3.000000E+01 2 6.048987E+01 6.132509E+01 2.902542E+01 5.307118E+01 - 4.599998E+00 3.000000E+01 3 4.875956E+00 -2.113382E+01 4.548004E+00 -1.758014E+00 - 4.599998E+00 3.000000E+01 4 2.488913E+02 7.771290E+01 5.296669E+01 2.431901E+02 - 4.599998E+00 3.000000E+01 5 1.903443E+02 -1.115959E+02 -7.005787E+01 -1.769826E+02 - 4.599998E+00 3.000000E+01 6 4.159670E+03 1.496618E+02 -3.590040E+03 2.101063E+03 - 4.599998E+00 6.000000E+01 1 1.341561E+02 -1.141581E+02 -5.490426E+01 -1.224067E+02 - 4.599998E+00 6.000000E+01 2 1.825358E+02 -1.001821E+02 -3.226822E+01 -1.796610E+02 - 4.599998E+00 6.000000E+01 3 5.846311E+00 9.632482E+00 5.763885E+00 9.782497E-01 - 4.599998E+00 6.000000E+01 4 6.221777E+02 -1.043536E+02 -1.542407E+02 -6.027560E+02 - 4.599998E+00 6.000000E+01 5 3.155230E+02 5.339978E+01 1.881236E+02 2.533066E+02 - 4.599998E+00 6.000000E+01 6 8.984623E+02 -4.113700E+00 8.961475E+02 -6.445203E+01 - 4.599998E+00 9.000000E+01 1 1.011548E-05 -1.062156E+02 -2.824781E-06 -9.713065E-06 - 4.599998E+00 9.000000E+01 2 7.347574E+01 5.378092E+01 4.341493E+01 5.927755E+01 - 4.599998E+00 9.000000E+01 3 1.265103E+01 -1.656356E+02 -1.225552E+01 -3.138562E+00 - 4.599998E+00 9.000000E+01 4 4.728514E+02 6.973167E+01 1.638038E+02 4.435728E+02 - 4.599998E+00 9.000000E+01 5 1.366691E-04 -8.105184E+01 2.125763E-05 -1.350058E-04 - 4.599998E+00 9.000000E+01 6 8.048025E-04 1.637364E+02 -7.725970E-04 2.253906E-04 - 4.699998E+00 0.000000E+00 1 3.460417E+02 6.870765E+01 1.256570E+02 3.224208E+02 - 4.699998E+00 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 4.699998E+00 0.000000E+00 3 2.093747E+00 -1.122938E+02 -7.942743E-01 -1.937241E+00 - 4.699998E+00 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 4.699998E+00 0.000000E+00 5 1.162250E+03 -1.118040E+02 -4.316968E+02 -1.079103E+03 - 4.699998E+00 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 4.699998E+00 3.000000E+01 1 4.541433E+01 1.033159E+02 -1.045981E+01 4.419337E+01 - 4.699998E+00 3.000000E+01 2 4.515564E+01 7.131896E+01 1.446332E+01 4.277667E+01 - 4.699998E+00 3.000000E+01 3 5.617669E+00 -1.294745E+01 5.474845E+00 -1.258679E+00 - 4.699998E+00 3.000000E+01 4 1.996091E+02 8.985918E+01 4.906016E-01 1.996085E+02 - 4.699998E+00 3.000000E+01 5 7.648222E+01 -9.556819E+01 -7.421094E+00 -7.612133E+01 - 4.699998E+00 3.000000E+01 6 4.250005E+03 1.524145E+02 -3.766867E+03 1.968059E+03 - 4.699998E+00 6.000000E+01 1 1.177873E+02 -1.023044E+02 -2.510108E+01 -1.150816E+02 - 4.699998E+00 6.000000E+01 2 1.535583E+02 -9.816393E+01 -2.180615E+01 -1.520021E+02 - 4.699998E+00 6.000000E+01 3 4.744053E+00 1.478502E+01 4.586978E+00 1.210649E+00 - 4.699998E+00 6.000000E+01 4 5.082306E+02 -1.038524E+02 -1.216815E+02 -4.934490E+02 - 4.699998E+00 6.000000E+01 5 2.164927E+02 6.491900E+01 9.177108E+01 1.960795E+02 - 4.699998E+00 6.000000E+01 6 1.220451E+03 -9.020590E+00 1.205357E+03 -1.913538E+02 - 4.699998E+00 9.000000E+01 1 9.939735E-06 -1.026334E+02 -2.173937E-06 -9.699089E-06 - 4.699998E+00 9.000000E+01 2 9.290768E+01 6.229543E+01 4.319396E+01 8.225642E+01 - 4.699998E+00 9.000000E+01 3 1.314444E+01 -1.656420E+02 -1.273388E+01 -3.259555E+00 - 4.699998E+00 9.000000E+01 4 5.692185E+02 7.359039E+01 1.608055E+02 5.460323E+02 - 4.699998E+00 9.000000E+01 5 1.475656E-04 -8.213509E+01 2.019256E-05 -1.461775E-04 - 4.699998E+00 9.000000E+01 6 7.639885E-04 1.641319E+02 -7.348755E-04 2.088932E-04 - 4.799998E+00 0.000000E+00 1 2.851581E+02 7.683483E+01 6.494731E+01 2.776635E+02 - 4.799998E+00 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 4.799998E+00 0.000000E+00 3 1.573121E+00 -6.936901E+01 5.542859E-01 -1.472236E+00 - 4.799998E+00 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 4.799998E+00 0.000000E+00 5 9.603394E+02 -1.045776E+02 -2.417084E+02 -9.294238E+02 - 4.799998E+00 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 4.799998E+00 3.000000E+01 1 1.800440E+01 1.379652E+02 -1.337255E+01 1.205543E+01 - 4.799998E+00 3.000000E+01 2 3.116061E+01 8.419940E+01 3.149298E+00 3.100105E+01 - 4.799998E+00 3.000000E+01 3 6.096856E+00 -4.478701E+00 6.078238E+00 -4.760943E-01 - 4.799998E+00 3.000000E+01 4 1.558646E+02 1.047826E+02 -3.976906E+01 1.507056E+02 - 4.799998E+00 3.000000E+01 5 8.520231E+00 7.131519E+01 2.729558E+00 8.071175E+00 - 4.799998E+00 3.000000E+01 6 4.196128E+03 1.556629E+02 -3.823245E+03 1.729244E+03 - 4.799998E+00 6.000000E+01 1 9.337648E+01 -9.295598E+01 -4.815296E+00 -9.325224E+01 - 4.799998E+00 6.000000E+01 2 1.254169E+02 -9.756944E+01 -1.652089E+01 -1.243240E+02 - 4.799998E+00 6.000000E+01 3 3.493744E+00 2.757178E+01 3.096965E+00 1.617113E+00 - 4.799998E+00 6.000000E+01 4 3.988786E+02 -1.054398E+02 -1.061915E+02 -3.844834E+02 - 4.799998E+00 6.000000E+01 5 9.889384E+01 7.518446E+01 2.528795E+01 9.560602E+01 - 4.799998E+00 6.000000E+01 6 1.526965E+03 -1.134167E+01 1.497147E+03 -3.002918E+02 - 4.799998E+00 9.000000E+01 1 9.805247E-06 -1.010645E+02 -1.881760E-06 -9.622985E-06 - 4.799998E+00 9.000000E+01 2 1.096895E+02 6.836515E+01 4.044143E+01 1.019621E+02 - 4.799998E+00 9.000000E+01 3 1.328537E+01 -1.665575E+02 -1.292139E+01 -3.088449E+00 - 4.799998E+00 9.000000E+01 4 6.525575E+02 7.666199E+01 1.505419E+02 6.349554E+02 - 4.799998E+00 9.000000E+01 5 1.578573E-04 -8.271859E+01 2.000726E-05 -1.565842E-04 - 4.799998E+00 9.000000E+01 6 7.240947E-04 1.643738E+02 -6.973319E-04 1.950419E-04 - 4.899998E+00 0.000000E+00 1 2.242526E+02 8.205466E+01 3.099806E+01 2.220998E+02 - 4.899998E+00 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 4.899998E+00 0.000000E+00 3 1.730230E+00 -2.364791E+01 1.584938E+00 -6.940214E-01 - 4.899998E+00 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 4.899998E+00 0.000000E+00 5 7.637006E+02 -1.005024E+02 -1.392053E+02 -7.509065E+02 - 4.899998E+00 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 4.899998E+00 3.000000E+01 1 1.331560E+01 -1.353097E+02 -9.466311E+00 -9.364521E+00 - 4.899998E+00 3.000000E+01 2 2.033665E+01 1.046555E+02 -5.145310E+00 1.967499E+01 - 4.899998E+00 3.000000E+01 3 6.114715E+00 5.298188E+00 6.088590E+00 5.646272E-01 - 4.899998E+00 3.000000E+01 4 1.244294E+02 1.236556E+02 -6.895877E+01 1.035730E+02 - 4.899998E+00 3.000000E+01 5 5.477603E+01 1.016458E+02 -1.105713E+01 5.364843E+01 - 4.899998E+00 3.000000E+01 6 4.006181E+03 1.592074E+02 -3.745264E+03 1.422142E+03 - 4.899998E+00 6.000000E+01 1 6.913773E+01 -8.669994E+01 3.979922E+00 -6.902308E+01 - 4.899998E+00 6.000000E+01 2 9.966670E+01 -9.837323E+01 -1.451354E+01 -9.860430E+01 - 4.899998E+00 6.000000E+01 3 2.494493E+00 5.765803E+01 1.334482E+00 2.107523E+00 - 4.899998E+00 6.000000E+01 4 3.002386E+02 -1.096119E+02 -1.007742E+02 -2.828211E+02 - 4.899998E+00 6.000000E+01 5 9.884706E+00 -1.214070E+02 -5.151062E+00 -8.436466E+00 - 4.899998E+00 6.000000E+01 6 1.805199E+03 -1.231811E+01 1.763640E+03 -3.851199E+02 - 4.899998E+00 9.000000E+01 1 9.782155E-06 -1.006720E+02 -1.811526E-06 -9.612956E-06 - 4.899998E+00 9.000000E+01 2 1.241622E+02 7.274443E+01 3.683076E+01 1.185738E+02 - 4.899998E+00 9.000000E+01 3 1.312218E+01 -1.693184E+02 -1.289481E+01 -2.432216E+00 - 4.899998E+00 9.000000E+01 4 7.247023E+02 7.897560E+01 1.385827E+02 7.113286E+02 - 4.899998E+00 9.000000E+01 5 1.670554E-04 -8.305560E+01 2.019804E-05 -1.658299E-04 - 4.899998E+00 9.000000E+01 6 6.861564E-04 1.644506E+02 -6.610429E-04 1.839371E-04 - 4.999998E+00 0.000000E+00 1 1.726201E+02 8.508228E+01 1.479787E+01 1.719847E+02 - 4.999998E+00 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 4.999998E+00 0.000000E+00 3 1.957078E+00 6.319008E+00 1.945188E+00 2.154040E-01 - 4.999998E+00 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 4.999998E+00 0.000000E+00 5 6.035105E+02 -9.911384E+01 -9.559399E+01 -5.958915E+02 - 4.999998E+00 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 4.999998E+00 3.000000E+01 1 2.238787E+01 -1.032164E+02 -5.118547E+00 -2.179489E+01 - 4.999998E+00 3.000000E+01 2 1.473204E+01 1.385222E+02 -1.103742E+01 9.757474E+00 - 4.999998E+00 3.000000E+01 3 5.556369E+00 1.667700E+01 5.322656E+00 1.594544E+00 - 4.999998E+00 3.000000E+01 4 1.086218E+02 1.453653E+02 -8.937321E+01 6.173428E+01 - 4.999998E+00 3.000000E+01 5 7.309184E+01 1.132108E+02 -2.880659E+01 6.717587E+01 - 4.999998E+00 3.000000E+01 6 3.704331E+03 1.628360E+02 -3.539354E+03 1.093178E+03 - 4.999998E+00 6.000000E+01 1 4.828257E+01 -8.284464E+01 6.014091E+00 -4.790655E+01 - 4.999998E+00 6.000000E+01 2 7.673846E+01 -1.006174E+02 -1.413899E+01 -7.542466E+01 - 4.999998E+00 6.000000E+01 3 2.660417E+00 1.029868E+02 -5.978680E-01 2.592368E+00 - 4.999998E+00 6.000000E+01 4 2.149162E+02 -1.176101E+02 -9.960352E+01 -1.904419E+02 - 4.999998E+00 6.000000E+01 5 9.926028E+01 -9.857103E+01 -1.479330E+01 -9.815173E+01 - 4.999998E+00 6.000000E+01 6 2.046443E+03 -1.259009E+01 1.997236E+03 -4.460722E+02 - 4.999998E+00 9.000000E+01 1 9.873493E-06 -1.008077E+02 -1.851404E-06 -9.698359E-06 - 4.999998E+00 9.000000E+01 2 1.367568E+02 7.594843E+01 3.320388E+01 1.326647E+02 - 4.999998E+00 9.000000E+01 3 1.298596E+01 -1.747427E+02 -1.293134E+01 -1.189889E+00 - 4.999998E+00 9.000000E+01 4 7.877038E+02 8.068748E+01 1.274659E+02 7.773221E+02 - 4.999998E+00 9.000000E+01 5 1.751611E-04 -8.334624E+01 2.029577E-05 -1.739813E-04 - 4.999998E+00 9.000000E+01 6 6.508722E-04 1.643833E+02 -6.268446E-04 1.752157E-04 - 5.099998E+00 0.000000E+00 1 1.312804E+02 8.677015E+01 7.396552E+00 1.310719E+02 - 5.099998E+00 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 5.099998E+00 0.000000E+00 3 1.801020E+00 2.839039E+01 1.584408E+00 8.563427E-01 - 5.099998E+00 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 5.099998E+00 0.000000E+00 5 4.830936E+02 -9.984545E+01 -8.260476E+01 -4.759789E+02 - 5.099998E+00 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 5.099998E+00 3.000000E+01 1 2.846573E+01 -9.460564E+01 -2.285713E+00 -2.837381E+01 - 5.099998E+00 3.000000E+01 2 1.517342E+01 1.739700E+02 -1.508947E+01 1.593953E+00 - 5.099998E+00 3.000000E+01 3 4.530262E+00 2.998076E+01 3.924082E+00 2.263813E+00 - 5.099998E+00 3.000000E+01 4 1.063378E+02 1.655567E+02 -1.029770E+02 2.652286E+01 - 5.099998E+00 3.000000E+01 5 7.443301E+01 1.267481E+02 -4.453309E+01 5.964124E+01 - 5.099998E+00 3.000000E+01 6 3.324823E+03 1.663876E+02 -3.231429E+03 7.825051E+02 - 5.099998E+00 6.000000E+01 1 3.106172E+01 -8.046489E+01 5.145436E+00 -3.063258E+01 - 5.099998E+00 6.000000E+01 2 5.653857E+01 -1.046741E+02 -1.432239E+01 -5.469442E+01 - 5.099998E+00 6.000000E+01 3 3.987724E+00 1.300531E+02 -2.566091E+00 3.052396E+00 - 5.099998E+00 6.000000E+01 4 1.457803E+02 -1.327872E+02 -9.902529E+01 -1.069855E+02 - 5.099998E+00 6.000000E+01 5 1.720107E+02 -9.528493E+01 -1.584369E+01 -1.712795E+02 - 5.099998E+00 6.000000E+01 6 2.247497E+03 -1.253841E+01 2.193896E+03 -4.879184E+02 - 5.099998E+00 9.000000E+01 1 1.005404E-05 -1.010651E+02 -1.929613E-06 -9.867133E-06 - 5.099998E+00 9.000000E+01 2 1.478123E+02 7.833849E+01 2.987723E+01 1.447613E+02 - 5.099998E+00 9.000000E+01 3 1.335400E+01 1.780605E+02 -1.334635E+01 4.519591E-01 - 5.099998E+00 9.000000E+01 4 8.430808E+02 8.196151E+01 1.178951E+02 8.347970E+02 - 5.099998E+00 9.000000E+01 5 1.824164E-04 -8.369120E+01 2.004519E-05 -1.813117E-04 - 5.099998E+00 9.000000E+01 6 6.185627E-04 1.642137E+02 -5.952326E-04 1.682797E-04 - 5.199997E+00 0.000000E+00 1 9.872353E+01 8.776910E+01 3.842977E+00 9.864870E+01 - 5.199997E+00 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 5.199997E+00 0.000000E+00 3 1.284143E+00 5.091521E+01 8.096135E-01 9.967697E-01 - 5.199997E+00 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 5.199997E+00 0.000000E+00 5 3.974545E+02 -1.023061E+02 -8.471117E+01 -3.883222E+02 - 5.199997E+00 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 5.199997E+00 3.000000E+01 1 3.130427E+01 -9.179281E+01 -9.793614E-01 -3.128895E+01 - 5.199997E+00 3.000000E+01 2 1.834637E+01 -1.649215E+02 -1.771471E+01 -4.772676E+00 - 5.199997E+00 3.000000E+01 3 3.355320E+00 4.752442E+01 2.265767E+00 2.474767E+00 - 5.199997E+00 3.000000E+01 4 1.111701E+02 -1.790739E+02 -1.111556E+02 -1.796929E+00 - 5.199997E+00 3.000000E+01 5 6.993764E+01 1.462886E+02 -5.817718E+01 3.881610E+01 - 5.199997E+00 3.000000E+01 6 2.903145E+03 1.697889E+02 -2.857164E+03 5.146542E+02 - 5.199997E+00 6.000000E+01 1 1.686113E+01 -7.846501E+01 3.371660E+00 -1.652059E+01 - 5.199997E+00 6.000000E+01 2 3.889046E+01 -1.118502E+02 -1.447432E+01 -3.609656E+01 - 5.199997E+00 6.000000E+01 3 5.714093E+00 1.418495E+02 -4.493509E+00 3.529765E+00 - 5.199997E+00 6.000000E+01 4 1.021020E+02 -1.621298E+02 -9.717603E+01 -3.133125E+01 - 5.199997E+00 6.000000E+01 5 2.306090E+02 -9.358036E+01 -1.440116E+01 -2.301589E+02 - 5.199997E+00 6.000000E+01 6 2.410101E+03 -1.237994E+01 2.354060E+03 -5.167098E+02 - 5.199997E+00 9.000000E+01 1 1.029325E-05 -1.012334E+02 -2.005185E-06 -1.009605E-05 - 5.199997E+00 9.000000E+01 2 1.575495E+02 8.016237E+01 2.691839E+01 1.552329E+02 - 5.199997E+00 9.000000E+01 3 1.436696E+01 1.714826E+02 -1.420850E+01 2.127890E+00 - 5.199997E+00 9.000000E+01 4 8.917733E+02 8.292913E+01 1.097745E+02 8.849910E+02 - 5.199997E+00 9.000000E+01 5 1.891061E-04 -8.411414E+01 1.939230E-05 -1.881092E-04 - 5.199997E+00 9.000000E+01 6 5.892388E-04 1.639931E+02 -5.663932E-04 1.624843E-04 - 5.299997E+00 0.000000E+00 1 7.318203E+01 8.851676E+01 1.894282E+00 7.315751E+01 - 5.299997E+00 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 5.299997E+00 0.000000E+00 3 7.291105E-01 9.409160E+01 -5.202293E-02 7.272522E-01 - 5.299997E+00 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 5.299997E+00 0.000000E+00 5 3.408557E+02 -1.061450E+02 -9.478160E+01 -3.274127E+02 - 5.299997E+00 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 5.299997E+00 3.000000E+01 1 3.183023E+01 -9.126304E+01 -7.016137E-01 -3.182250E+01 - 5.299997E+00 3.000000E+01 2 2.139673E+01 -1.538552E+02 -1.920749E+01 -9.428274E+00 - 5.299997E+00 3.000000E+01 3 2.469082E+00 7.542561E+01 6.213123E-01 2.389631E+00 - 5.299997E+00 3.000000E+01 4 1.172394E+02 -1.684819E+02 -1.148783E+02 -2.341015E+01 - 5.299997E+00 3.000000E+01 5 7.161636E+01 1.724431E+02 -7.099435E+01 9.418367E+00 - 5.299997E+00 3.000000E+01 6 2.469182E+03 1.730642E+02 -2.451113E+03 2.981705E+02 - 5.299997E+00 6.000000E+01 1 5.029590E+00 -7.181719E+01 1.569483E+00 -4.778441E+00 - 5.299997E+00 6.000000E+01 2 2.403101E+01 -1.265989E+02 -1.432751E+01 -1.929280E+01 - 5.299997E+00 6.000000E+01 3 7.550153E+00 1.475927E+02 -6.374292E+00 4.046382E+00 - 5.299997E+00 6.000000E+01 4 1.006784E+02 1.580147E+02 -9.335703E+01 3.769087E+01 - 5.299997E+00 6.000000E+01 5 2.778275E+02 -9.266583E+01 -1.292196E+01 -2.775269E+02 - 5.299997E+00 6.000000E+01 6 2.538895E+03 -1.221761E+01 2.481391E+03 -5.372943E+02 - 5.299997E+00 9.000000E+01 1 1.056448E-05 -1.012218E+02 -2.055921E-06 -1.036250E-05 - 5.299997E+00 9.000000E+01 2 1.661043E+02 8.158524E+01 2.430735E+01 1.643162E+02 - 5.299997E+00 9.000000E+01 3 1.576545E+01 1.668751E+02 -1.535362E+01 3.579932E+00 - 5.299997E+00 9.000000E+01 4 9.343185E+02 8.368379E+01 1.027895E+02 9.286471E+02 - 5.299997E+00 9.000000E+01 5 1.954692E-04 -8.459381E+01 1.841629E-05 -1.945997E-04 - 5.299997E+00 9.000000E+01 6 5.626847E-04 1.637713E+02 -5.402638E-04 1.572549E-04 - 5.399997E+00 0.000000E+00 1 5.320681E+01 8.927164E+01 6.763632E-01 5.320251E+01 - 5.399997E+00 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 5.399997E+00 0.000000E+00 3 8.946602E-01 1.628443E+02 -8.548536E-01 2.638978E-01 - 5.399997E+00 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 5.399997E+00 0.000000E+00 5 3.084848E+02 -1.108280E+02 -1.096860E+02 -2.883259E+02 - 5.399997E+00 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 5.399997E+00 3.000000E+01 1 3.072328E+01 -9.174631E+01 -9.362619E-01 -3.070901E+01 - 5.399997E+00 3.000000E+01 2 2.341204E+01 -1.477095E+02 -1.979138E+01 -1.250700E+01 - 5.399997E+00 3.000000E+01 3 2.390580E+00 1.128374E+02 -9.278246E-01 2.203183E+00 - 5.399997E+00 3.000000E+01 4 1.212354E+02 -1.613960E+02 -1.149004E+02 -3.867727E+01 - 5.399997E+00 3.000000E+01 5 8.786434E+01 -1.629816E+02 -8.401685E+01 -2.571596E+01 - 5.399997E+00 3.000000E+01 6 2.044515E+03 1.763336E+02 -2.040331E+03 1.307424E+02 - 5.399997E+00 6.000000E+01 1 5.211673E+00 8.915567E+01 7.679845E-02 5.211107E+00 - 5.399997E+00 6.000000E+01 2 1.436965E+01 -1.638569E+02 -1.380306E+01 -3.995303E+00 - 5.399997E+00 6.000000E+01 3 9.404319E+00 1.508960E+02 -8.216909E+00 4.574233E+00 - 5.399997E+00 6.000000E+01 4 1.336929E+02 1.309017E+02 -8.753727E+01 1.010495E+02 - 5.399997E+00 6.000000E+01 5 3.157938E+02 -9.220214E+01 -1.213439E+01 -3.155605E+02 - 5.399997E+00 6.000000E+01 6 2.639307E+03 -1.208229E+01 2.580841E+03 -5.524499E+02 - 5.399997E+00 9.000000E+01 1 1.084641E-05 -1.010023E+02 -2.070025E-06 -1.064705E-05 - 5.399997E+00 9.000000E+01 2 1.735647E+02 8.271427E+01 2.201106E+01 1.721633E+02 - 5.399997E+00 9.000000E+01 3 1.724582E+01 1.640994E+02 -1.658596E+01 4.724835E+00 - 5.399997E+00 9.000000E+01 4 9.710290E+02 8.428634E+01 9.667275E+01 9.662048E+02 - 5.399997E+00 9.000000E+01 5 2.016459E-04 -8.508926E+01 1.726162E-05 -2.009057E-04 - 5.399997E+00 9.000000E+01 6 5.385648E-04 1.635914E+02 -5.166297E-04 1.521372E-04 - 5.499997E+00 0.000000E+00 1 3.771612E+01 9.009675E+01 -6.368235E-02 3.771607E+01 - 5.499997E+00 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 5.499997E+00 0.000000E+00 3 1.600938E+00 -1.721058E+02 -1.585767E+00 -2.198788E-01 - 5.499997E+00 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 5.499997E+00 0.000000E+00 5 2.962563E+02 -1.155710E+02 -1.278731E+02 -2.672382E+02 - 5.499997E+00 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 5.499997E+00 3.000000E+01 1 2.840397E+01 -9.256886E+01 -1.273066E+00 -2.837543E+01 - 5.499997E+00 3.000000E+01 2 2.422392E+01 -1.442243E+02 -1.965315E+01 -1.416163E+01 - 5.499997E+00 3.000000E+01 3 3.138138E+00 1.397190E+02 -2.394031E+00 2.028922E+00 - 5.499997E+00 3.000000E+01 4 1.217762E+02 -1.567622E+02 -1.118971E+02 -4.804665E+01 - 5.499997E+00 3.000000E+01 5 1.172373E+02 -1.464309E+02 -9.768437E+01 -6.482551E+01 - 5.499997E+00 3.000000E+01 6 1.642951E+03 1.798269E+02 -1.642944E+03 4.963988E+00 - 5.499997E+00 6.000000E+01 1 1.392469E+01 9.416711E+01 -1.011847E+00 1.388788E+01 - 5.499997E+00 6.000000E+01 2 1.634966E+01 1.422125E+02 -1.292094E+01 1.001801E+01 - 5.499997E+00 6.000000E+01 3 1.121547E+01 1.531807E+02 -1.000906E+01 5.060182E+00 - 5.499997E+00 6.000000E+01 4 1.784242E+02 1.166464E+02 -8.002017E+01 1.594741E+02 - 5.499997E+00 6.000000E+01 5 3.460588E+02 -9.198971E+01 -1.201513E+01 -3.458501E+02 - 5.499997E+00 6.000000E+01 6 2.716236E+03 -1.196644E+01 2.657210E+03 -5.631809E+02 - 5.499997E+00 9.000000E+01 1 1.112227E-05 -1.005776E+02 -2.041689E-06 -1.093327E-05 - 5.499997E+00 9.000000E+01 2 1.800022E+02 8.361764E+01 2.000959E+01 1.788865E+02 - 5.499997E+00 9.000000E+01 3 1.862189E+01 1.626125E+02 -1.777097E+01 5.564838E+00 - 5.499997E+00 9.000000E+01 4 1.002173E+03 8.477409E+01 9.128094E+01 9.980078E+02 - 5.499997E+00 9.000000E+01 5 2.076841E-04 -8.555885E+01 1.608203E-05 -2.070605E-04 - 5.499997E+00 9.000000E+01 6 5.164861E-04 1.634863E+02 -4.951819E-04 1.468086E-04 - 5.599997E+00 0.000000E+00 1 2.592664E+01 9.071744E+01 -3.246363E-01 2.592461E+01 - 5.599997E+00 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 5.599997E+00 0.000000E+00 3 2.360951E+00 -1.646193E+02 -2.276394E+00 -6.261969E-01 - 5.599997E+00 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 5.599997E+00 0.000000E+00 5 3.003529E+02 -1.195644E+02 -1.481948E+02 -2.612473E+02 - 5.599997E+00 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 5.599997E+00 3.000000E+01 1 2.511107E+01 -9.324791E+01 -1.422701E+00 -2.507073E+01 - 5.599997E+00 3.000000E+01 2 2.390110E+01 -1.424890E+02 -1.895922E+01 -1.455372E+01 - 5.599997E+00 3.000000E+01 3 4.252658E+00 1.533592E+02 -3.801176E+00 1.906873E+00 - 5.599997E+00 3.000000E+01 4 1.185494E+02 -1.539626E+02 -1.065176E+02 -5.203813E+01 - 5.599997E+00 3.000000E+01 5 1.546024E+02 -1.363390E+02 -1.118452E+02 -1.067360E+02 - 5.599997E+00 3.000000E+01 6 1.272583E+03 -1.760506E+02 -1.269561E+03 -8.764964E+01 - 5.599997E+00 6.000000E+01 1 2.162773E+01 9.453346E+01 -1.709483E+00 2.156006E+01 - 5.599997E+00 6.000000E+01 2 2.574589E+01 1.171429E+02 -1.174558E+01 2.291052E+01 - 5.599997E+00 6.000000E+01 3 1.292267E+01 1.550454E+02 -1.171624E+01 5.452082E+00 - 5.599997E+00 6.000000E+01 4 2.250487E+02 1.084547E+02 -7.124017E+01 2.134754E+02 - 5.599997E+00 6.000000E+01 5 3.697420E+02 -9.189798E+01 -1.224580E+01 -3.695392E+02 - 5.599997E+00 6.000000E+01 6 2.773529E+03 -1.184790E+01 2.714442E+03 -5.694453E+02 - 5.599997E+00 9.000000E+01 1 1.137850E-05 -9.996614E+01 -1.969235E-06 -1.120680E-05 - 5.599997E+00 9.000000E+01 2 1.854883E+02 8.433888E+01 1.829739E+01 1.845836E+02 - 5.599997E+00 9.000000E+01 3 1.979555E+01 1.619875E+02 -1.882535E+01 6.121271E+00 - 5.599997E+00 9.000000E+01 4 1.028038E+03 8.516866E+01 8.658434E+01 1.024386E+03 - 5.599997E+00 9.000000E+01 5 2.135555E-04 -8.597174E+01 1.500195E-05 -2.130279E-04 - 5.599997E+00 9.000000E+01 6 5.334870E-04 1.735302E+02 -5.300895E-04 6.011270E-05 - 5.699997E+00 0.000000E+00 1 1.728198E+01 9.010542E+01 -3.179745E-02 1.728195E+01 - 5.699997E+00 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 5.699997E+00 0.000000E+00 3 3.096178E+00 -1.628466E+02 -2.958456E+00 -9.131567E-01 - 5.699997E+00 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 5.699997E+00 0.000000E+00 5 3.170832E+02 -1.222886E+02 -1.693808E+02 -2.680520E+02 - 5.699997E+00 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 5.699997E+00 3.000000E+01 1 2.096853E+01 -9.330057E+01 -1.207242E+00 -2.093375E+01 - 5.699997E+00 3.000000E+01 2 2.260131E+01 -1.422039E+02 -1.785948E+01 -1.385128E+01 - 5.699997E+00 3.000000E+01 3 5.475793E+00 1.603896E+02 -5.158177E+00 1.837805E+00 - 5.699997E+00 3.000000E+01 4 1.118138E+02 -1.527302E+02 -9.938672E+01 -5.123090E+01 - 5.699997E+00 3.000000E+01 5 1.962200E+02 -1.298908E+02 -1.258410E+02 -1.505534E+02 - 5.699997E+00 3.000000E+01 6 9.383300E+02 -1.705120E+02 -9.254937E+02 -1.546758E+02 - 5.699997E+00 6.000000E+01 1 2.851969E+01 9.417486E+01 -2.076246E+00 2.844401E+01 - 5.699997E+00 6.000000E+01 2 3.630803E+01 1.065696E+02 -1.035434E+01 3.480030E+01 - 5.699997E+00 6.000000E+01 3 1.446616E+01 1.567466E+02 -1.329104E+01 5.711210E+00 - 5.699997E+00 6.000000E+01 4 2.705252E+02 1.031721E+02 -6.164660E+01 2.634077E+02 - 5.699997E+00 6.000000E+01 5 3.876318E+02 -9.183718E+01 -1.242720E+01 -3.874325E+02 - 5.699997E+00 6.000000E+01 6 2.813971E+03 -1.170341E+01 2.755471E+03 -5.708015E+02 - 5.699997E+00 9.000000E+01 1 1.160414E-05 -9.919559E+01 -1.854404E-06 -1.145501E-05 - 5.699997E+00 9.000000E+01 2 1.901039E+02 8.490704E+01 1.687589E+01 1.893534E+02 - 5.699997E+00 9.000000E+01 3 2.071064E+01 1.619549E+02 -1.969195E+01 6.415437E+00 - 5.699997E+00 9.000000E+01 4 1.048984E+03 8.548279E+01 8.261642E+01 1.045725E+03 - 5.699997E+00 9.000000E+01 5 2.191727E-04 -8.631281E+01 1.409480E-05 -2.187190E-04 - 5.699997E+00 9.000000E+01 6 5.074404E-04 1.735952E+02 -5.042733E-04 5.660590E-05 - 5.799997E+00 0.000000E+00 1 1.144484E+01 8.563708E+01 8.706529E-01 1.141168E+01 - 5.799997E+00 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 5.799997E+00 0.000000E+00 3 3.805194E+00 -1.636273E+02 -3.650888E+00 -1.072621E+00 - 5.799997E+00 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 5.799997E+00 0.000000E+00 5 3.429525E+02 -1.236140E+02 -1.898565E+02 -2.856062E+02 - 5.799997E+00 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 5.799997E+00 3.000000E+01 1 1.604464E+01 -9.196248E+01 -5.494484E-01 -1.603523E+01 - 5.799997E+00 3.000000E+01 2 2.052374E+01 -1.434422E+02 -1.648582E+01 -1.222463E+01 - 5.799997E+00 3.000000E+01 3 6.704503E+00 1.643690E+02 -6.456552E+00 1.806462E+00 - 5.799997E+00 3.000000E+01 4 1.021577E+02 -1.530744E+02 -9.108334E+01 -4.626033E+01 - 5.799997E+00 3.000000E+01 5 2.396104E+02 -1.253522E+02 -1.386386E+02 -1.954289E+02 - 5.799997E+00 3.000000E+01 6 6.452072E+02 -1.617413E+02 -6.127220E+02 -2.021487E+02 - 5.799997E+00 6.000000E+01 1 3.476017E+01 9.361497E+01 -2.191678E+00 3.469101E+01 - 5.799997E+00 6.000000E+01 2 4.661618E+01 1.009082E+02 -8.821434E+00 4.577390E+01 - 5.799997E+00 6.000000E+01 3 1.579199E+01 1.583885E+02 -1.468185E+01 5.816370E+00 - 5.799997E+00 6.000000E+01 4 3.137964E+02 9.947241E+01 -5.164229E+01 3.095178E+02 - 5.799997E+00 6.000000E+01 5 4.002642E+02 -9.174596E+01 -1.219529E+01 -4.000784E+02 - 5.799997E+00 6.000000E+01 6 2.839525E+03 -1.151507E+01 2.782372E+03 -5.668420E+02 - 5.799997E+00 9.000000E+01 1 1.179089E-05 -9.829910E+01 -1.701904E-06 -1.166742E-05 - 5.799997E+00 9.000000E+01 2 1.939394E+02 8.534341E+01 1.574466E+01 1.932993E+02 - 5.799997E+00 9.000000E+01 3 2.133052E+01 1.623423E+02 -2.032555E+01 6.470180E+00 - 5.799997E+00 9.000000E+01 4 1.065437E+03 8.572481E+01 7.942514E+01 1.062473E+03 - 5.799997E+00 9.000000E+01 5 2.244461E-04 -8.658265E+01 1.337895E-05 -2.240470E-04 - 5.799997E+00 9.000000E+01 6 4.829921E-04 1.736989E+02 -4.800743E-04 5.300975E-05 - 5.899997E+00 0.000000E+00 1 8.392694E+00 7.358714E+01 2.371412E+00 8.050696E+00 - 5.899997E+00 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 5.899997E+00 0.000000E+00 3 4.499769E+00 -1.656466E+02 -4.359310E+00 -1.115499E+00 - 5.899997E+00 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 5.899997E+00 0.000000E+00 5 3.747024E+02 -1.236756E+02 -2.077689E+02 -3.118236E+02 - 5.899997E+00 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 5.899997E+00 3.000000E+01 1 1.042408E+01 -8.704988E+01 5.364913E-01 -1.041026E+01 - 5.899997E+00 3.000000E+01 2 1.789810E+01 -1.466397E+02 -1.494902E+01 -9.842196E+00 - 5.899997E+00 3.000000E+01 3 7.883803E+00 1.668464E+02 -7.676961E+00 1.794051E+00 - 5.899997E+00 3.000000E+01 4 9.039412E+01 -1.552851E+02 -8.211400E+01 -3.779402E+01 - 5.899997E+00 3.000000E+01 5 2.828014E+02 -1.217937E+02 -1.489974E+02 -2.403673E+02 - 5.899997E+00 3.000000E+01 6 4.059503E+02 -1.446949E+02 -3.312903E+02 -2.346111E+02 - 5.899997E+00 6.000000E+01 1 4.046095E+01 9.303251E+01 -2.140489E+00 4.040429E+01 - 5.899997E+00 6.000000E+01 2 5.636086E+01 9.735036E+01 -7.210611E+00 5.589771E+01 - 5.899997E+00 6.000000E+01 3 1.685619E+01 1.600059E+02 -1.584023E+01 5.763529E+00 - 5.899997E+00 6.000000E+01 4 3.544296E+02 9.673380E+01 -4.155926E+01 3.519846E+02 - 5.899997E+00 6.000000E+01 5 4.080023E+02 -9.158569E+01 -1.129021E+01 -4.078460E+02 - 5.899997E+00 6.000000E+01 6 2.851611E+03 -1.127238E+01 2.796601E+03 -5.574141E+02 - 5.899997E+00 9.000000E+01 1 1.193312E-05 -9.731239E+01 -1.518836E-06 -1.183606E-05 - 5.899997E+00 9.000000E+01 2 1.970907E+02 8.566570E+01 1.489529E+01 1.965271E+02 - 5.899997E+00 9.000000E+01 3 2.163098E+01 1.630303E+02 -2.068915E+01 6.313335E+00 - 5.899997E+00 9.000000E+01 4 1.077874E+03 8.590173E+01 7.703280E+01 1.075118E+03 - 5.899997E+00 9.000000E+01 5 2.292903E-04 -8.679324E+01 1.282634E-05 -2.289313E-04 - 5.899997E+00 9.000000E+01 6 4.599442E-04 1.738406E+02 -4.572890E-04 4.934994E-05 - 5.999997E+00 0.000000E+00 1 8.249591E+00 5.801945E+01 4.369242E+00 6.997534E+00 - 5.999997E+00 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 5.999997E+00 0.000000E+00 3 5.187577E+00 -1.681797E+02 -5.077574E+00 -1.062639E+00 - 5.999997E+00 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 5.999997E+00 0.000000E+00 5 4.092494E+02 -1.227191E+02 -2.212080E+02 -3.443139E+02 - 5.999997E+00 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 5.999997E+00 3.000000E+01 1 4.531404E+00 -6.442155E+01 1.956418E+00 -4.087304E+00 - 5.999997E+00 3.000000E+01 2 1.500057E+01 -1.527637E+02 -1.333741E+01 -6.865170E+00 - 5.999997E+00 3.000000E+01 3 8.973127E+00 1.685330E+02 -8.794018E+00 1.783891E+00 - 5.999997E+00 3.000000E+01 4 7.756216E+01 -1.600227E+02 -7.289507E+01 -2.649899E+01 - 5.999997E+00 3.000000E+01 5 3.239916E+02 -1.187229E+02 -1.557018E+02 -2.841259E+02 - 5.999997E+00 3.000000E+01 6 2.677123E+02 -1.074318E+02 -8.019846E+01 -2.554175E+02 - 5.999997E+00 6.000000E+01 1 4.569069E+01 9.251271E+01 -2.003130E+00 4.564676E+01 - 5.999997E+00 6.000000E+01 2 6.546344E+01 9.488390E+01 -5.573354E+00 6.522576E+01 - 5.999997E+00 6.000000E+01 3 1.762659E+01 1.616013E+02 -1.672557E+01 5.563430E+00 - 5.999997E+00 6.000000E+01 4 3.922416E+02 9.462893E+01 -3.165479E+01 3.909622E+02 - 5.999997E+00 6.000000E+01 5 4.110932E+02 -9.133858E+01 -9.603373E+00 -4.109810E+02 - 5.999997E+00 6.000000E+01 6 2.851342E+03 -1.097183E+01 2.799222E+03 -5.426855E+02 - 5.999997E+00 9.000000E+01 1 1.202753E-05 -9.627190E+01 -1.313971E-06 -1.195555E-05 - 5.999997E+00 9.000000E+01 2 1.996523E+02 8.589021E+01 1.430868E+01 1.991389E+02 - 5.999997E+00 9.000000E+01 3 2.159931E+01 1.639290E+02 -2.075520E+01 5.979290E+00 - 5.999997E+00 9.000000E+01 4 1.086781E+03 8.602073E+01 7.541784E+01 1.084161E+03 - 5.999997E+00 9.000000E+01 5 2.336553E-04 -8.696281E+01 1.238002E-05 -2.333271E-04 - 5.999997E+00 9.000000E+01 6 4.381380E-04 1.740168E+02 -4.357513E-04 4.567037E-05 - 6.099997E+00 0.000000E+00 1 1.046364E+01 5.035596E+01 6.675972E+00 8.057245E+00 - 6.099997E+00 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 6.099997E+00 0.000000E+00 3 5.866732E+00 -1.707883E+02 -5.791072E+00 -9.391614E-01 - 6.099997E+00 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 6.099997E+00 0.000000E+00 5 4.436782E+02 -1.210020E+02 -2.285244E+02 -3.802985E+02 - 6.099997E+00 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 6.099997E+00 3.000000E+01 1 4.574429E+00 3.900104E+01 3.554947E+00 2.878845E+00 - 6.099997E+00 3.000000E+01 2 1.221256E+01 -1.636316E+02 -1.171758E+01 -3.441653E+00 - 6.099997E+00 3.000000E+01 3 9.939134E+00 1.697807E+02 -9.781460E+00 1.763356E+00 - 6.099997E+00 3.000000E+01 4 6.506376E+01 -1.684614E+02 -6.374884E+01 -1.301454E+01 - 6.099997E+00 3.000000E+01 5 3.614323E+02 -1.158878E+02 -1.578053E+02 -3.251627E+02 - 6.099997E+00 3.000000E+01 6 3.025023E+02 -6.198606E+01 1.420812E+02 -2.670591E+02 - 6.099997E+00 6.000000E+01 1 5.048534E+01 9.209763E+01 -1.847879E+00 5.045151E+01 - 6.099997E+00 6.000000E+01 2 7.391103E+01 9.306325E+01 -3.949679E+00 7.380543E+01 - 6.099997E+00 6.000000E+01 3 1.808422E+01 1.631641E+02 -1.730909E+01 5.237776E+00 - 6.099997E+00 6.000000E+01 4 4.271609E+02 9.296829E+01 -2.211983E+01 4.265879E+02 - 6.099997E+00 6.000000E+01 5 4.097423E+02 -9.100600E+01 -7.193880E+00 -4.096792E+02 - 6.099997E+00 6.000000E+01 6 2.839707E+03 -1.061555E+01 2.791107E+03 -5.231253E+02 - 6.099997E+00 9.000000E+01 1 1.207376E-05 -9.521217E+01 -1.096832E-06 -1.202384E-05 - 6.099997E+00 9.000000E+01 2 2.017121E+02 8.603269E+01 1.395591E+01 2.012287E+02 - 6.099997E+00 9.000000E+01 3 2.123364E+01 1.649668E+02 -2.050693E+01 5.507566E+00 - 6.099997E+00 9.000000E+01 4 1.092631E+03 8.608970E+01 7.451158E+01 1.090088E+03 - 6.099997E+00 9.000000E+01 5 2.375192E-04 -8.711062E+01 1.197284E-05 -2.372173E-04 - 6.099997E+00 9.000000E+01 6 4.174509E-04 1.742228E+02 -4.153306E-04 4.202110E-05 - 6.199996E+00 0.000000E+00 1 1.423732E+01 5.055992E+01 9.044558E+00 1.099533E+01 - 6.199996E+00 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 6.199996E+00 0.000000E+00 3 6.524652E+00 -1.732178E+02 -6.478994E+00 -7.705297E-01 - 6.199996E+00 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 6.199996E+00 0.000000E+00 5 4.753039E+02 -1.187623E+02 -2.287052E+02 -4.166626E+02 - 6.199996E+00 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 6.199996E+00 3.000000E+01 1 1.159182E+01 6.364566E+01 5.145857E+00 1.038704E+01 - 6.199996E+00 3.000000E+01 2 1.014111E+01 1.783265E+02 -1.013678E+01 2.961683E-01 - 6.199996E+00 3.000000E+01 3 1.075400E+01 1.707731E+02 -1.061486E+01 1.724348E+00 - 6.199996E+00 3.000000E+01 4 5.494801E+01 1.778411E+02 -5.490900E+01 2.069896E+00 - 6.199996E+00 3.000000E+01 5 3.935418E+02 -1.131767E+02 -1.548857E+02 -3.617812E+02 - 6.199996E+00 3.000000E+01 6 4.329815E+02 -3.882263E+01 3.373317E+02 -2.714411E+02 - 6.199996E+00 6.000000E+01 1 5.485495E+01 9.180088E+01 -1.723876E+00 5.482785E+01 - 6.199996E+00 6.000000E+01 2 8.171471E+01 9.166198E+01 -2.369965E+00 8.168033E+01 - 6.199996E+00 6.000000E+01 3 1.822185E+01 1.646790E+02 -1.757425E+01 4.814692E+00 - 6.199996E+00 6.000000E+01 4 4.591909E+02 9.163345E+01 -1.308932E+01 4.590043E+02 - 6.199996E+00 6.000000E+01 5 4.041983E+02 -9.060629E+01 -4.277046E+00 -4.041757E+02 - 6.199996E+00 6.000000E+01 6 2.817646E+03 -1.020965E+01 2.773031E+03 -4.994294E+02 - 6.199996E+00 9.000000E+01 1 1.207343E-05 -9.416452E+01 -8.767791E-07 -1.204155E-05 - 6.199996E+00 9.000000E+01 2 2.033479E+02 8.610851E+01 1.380067E+01 2.028790E+02 - 6.199996E+00 9.000000E+01 3 2.054312E+01 1.660861E+02 -1.994034E+01 4.939880E+00 - 6.199996E+00 9.000000E+01 4 1.095863E+03 8.611726E+01 7.420622E+01 1.093347E+03 - 6.199996E+00 9.000000E+01 5 2.409031E-04 -8.725345E+01 1.154361E-05 -2.406263E-04 - 6.199996E+00 9.000000E+01 6 3.977880E-04 1.744530E+02 -3.959252E-04 3.845130E-05 - 6.299996E+00 0.000000E+00 1 1.914362E+01 5.413163E+01 1.121673E+01 1.551332E+01 - 6.299996E+00 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 6.299996E+00 0.000000E+00 3 7.141086E+00 -1.753409E+02 -7.117488E+00 -5.800562E-01 - 6.299996E+00 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 6.299996E+00 0.000000E+00 5 5.019013E+02 -1.162051E+02 -2.216324E+02 -4.503155E+02 - 6.299996E+00 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 6.299996E+00 3.000000E+01 1 1.941873E+01 7.028712E+01 6.550072E+00 1.828069E+01 - 6.299996E+00 3.000000E+01 2 9.609566E+00 1.538569E+02 -8.626476E+00 4.234107E+00 - 6.299996E+00 3.000000E+01 3 1.139540E+01 1.716096E+02 -1.127343E+01 1.662793E+00 - 6.299996E+00 3.000000E+01 4 4.997646E+01 1.586054E+02 -4.653260E+01 1.823085E+01 - 6.299996E+00 3.000000E+01 5 4.190488E+02 -1.105592E+02 -1.471591E+02 -3.923597E+02 - 6.299996E+00 3.000000E+01 6 5.748251E+02 -2.802354E+01 5.074295E+02 -2.700725E+02 - 6.299996E+00 6.000000E+01 1 5.879642E+01 9.161513E+01 -1.657208E+00 5.877306E+01 - 6.299996E+00 6.000000E+01 2 8.889552E+01 9.055240E+01 -8.570521E-01 8.889138E+01 - 6.299996E+00 6.000000E+01 3 1.804291E+01 1.661316E+02 -1.751694E+01 4.324758E+00 - 6.299996E+00 6.000000E+01 4 4.883799E+02 9.054623E+01 -4.655920E+00 4.883577E+02 - 6.299996E+00 6.000000E+01 5 3.947912E+02 -9.016973E+01 -1.169526E+00 -3.947895E+02 - 6.299996E+00 6.000000E+01 6 2.786145E+03 -9.762721E+00 2.745798E+03 -4.724420E+02 - 6.299996E+00 9.000000E+01 1 1.203010E-05 -9.315540E+01 -6.621877E-07 -1.201186E-05 - 6.299996E+00 9.000000E+01 2 2.046265E+02 8.613224E+01 1.380285E+01 2.041604E+02 - 6.299996E+00 9.000000E+01 3 1.954493E+01 1.672406E+02 -1.906229E+01 4.316647E+00 - 6.299996E+00 9.000000E+01 4 1.096852E+03 8.611218E+01 7.436994E+01 1.094328E+03 - 6.299996E+00 9.000000E+01 5 2.438480E-04 -8.740331E+01 1.104761E-05 -2.435977E-04 - 6.299996E+00 9.000000E+01 6 3.790760E-04 1.747016E+02 -3.774563E-04 3.500461E-05 - 6.399996E+00 0.000000E+00 1 2.490040E+01 5.859365E+01 1.297570E+01 2.125232E+01 - 6.399996E+00 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 6.399996E+00 0.000000E+00 3 7.690893E+00 -1.771123E+02 -7.681128E+00 -3.874537E-01 - 6.399996E+00 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 6.399996E+00 0.000000E+00 5 5.218397E+02 -1.135057E+02 -2.081304E+02 -4.785378E+02 - 6.399996E+00 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 6.399996E+00 3.000000E+01 1 2.744187E+01 7.385473E+01 7.630864E+00 2.635955E+01 - 6.399996E+00 3.000000E+01 2 1.097380E+01 1.310448E+02 -7.205935E+00 8.276397E+00 - 6.399996E+00 3.000000E+01 3 1.184639E+01 1.723465E+02 -1.174086E+01 1.577718E+00 - 6.399996E+00 3.000000E+01 4 5.220620E+01 1.378680E+02 -3.871618E+01 3.502207E+01 - 6.399996E+00 3.000000E+01 5 4.371505E+02 -1.080518E+02 -1.354627E+02 -4.156325E+02 - 6.399996E+00 3.000000E+01 6 7.056147E+02 -2.198862E+01 6.542870E+02 -2.641980E+02 - 6.399996E+00 6.000000E+01 1 6.230491E+01 9.151879E+01 -1.651382E+00 6.228302E+01 - 6.399996E+00 6.000000E+01 2 9.548029E+01 8.965668E+01 5.721323E-01 9.547857E+01 - 6.399996E+00 6.000000E+01 3 1.755966E+01 1.675099E+02 -1.714409E+01 3.797630E+00 - 6.399996E+00 6.000000E+01 4 5.148070E+02 8.965267E+01 3.120712E+00 5.147975E+02 - 6.399996E+00 6.000000E+01 5 3.819733E+02 -8.973202E+01 1.786511E+00 -3.819691E+02 - 6.399996E+00 6.000000E+01 6 2.746226E+03 -9.284508E+00 2.710248E+03 -4.430677E+02 - 6.399996E+00 9.000000E+01 1 1.194856E-05 -9.220567E+01 -4.598603E-07 -1.193971E-05 - 6.399996E+00 9.000000E+01 2 2.056012E+02 8.611742E+01 1.392169E+01 2.051293E+02 - 6.399996E+00 9.000000E+01 3 1.826296E+01 1.683928E+02 -1.788948E+01 3.674524E+00 - 6.399996E+00 9.000000E+01 4 1.095928E+03 8.608315E+01 7.486142E+01 1.093369E+03 - 6.399996E+00 9.000000E+01 5 2.464013E-04 -8.756695E+01 1.046024E-05 -2.461792E-04 - 6.399996E+00 9.000000E+01 6 3.612580E-04 1.749633E+02 -3.598631E-04 3.171640E-05 - 6.499996E+00 0.000000E+00 1 3.122998E+01 6.298394E+01 1.418592E+01 2.782214E+01 - 6.499996E+00 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 6.499996E+00 0.000000E+00 3 8.148113E+00 -1.785369E+02 -8.145456E+00 -2.080519E-01 - 6.499996E+00 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 6.499996E+00 0.000000E+00 5 5.342173E+02 -1.108041E+02 -1.897402E+02 -4.993865E+02 - 6.499996E+00 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 6.499996E+00 3.000000E+01 1 3.539780E+01 7.641184E+01 8.316403E+00 3.440700E+01 - 6.499996E+00 3.000000E+01 2 1.367614E+01 1.154904E+02 -5.885651E+00 1.234487E+01 - 6.499996E+00 3.000000E+01 3 1.209567E+01 1.730168E+02 -1.200595E+01 1.470577E+00 - 6.499996E+00 3.000000E+01 4 6.085913E+01 1.211826E+02 -3.151083E+01 5.206631E+01 - 6.499996E+00 3.000000E+01 5 4.475864E+02 -1.056898E+02 -1.210405E+02 -4.309092E+02 - 6.499996E+00 3.000000E+01 6 8.204029E+02 -1.809916E+01 7.798096E+02 -2.548684E+02 - 6.499996E+00 6.000000E+01 1 6.538300E+01 9.148339E+01 -1.692576E+00 6.536109E+01 - 6.499996E+00 6.000000E+01 2 1.014976E+02 8.892442E+01 1.905245E+00 1.014797E+02 - 6.499996E+00 6.000000E+01 3 1.678957E+01 1.688050E+02 -1.647010E+01 3.259687E+00 - 6.499996E+00 6.000000E+01 4 5.385770E+02 8.891418E+01 1.020595E+01 5.384803E+02 - 6.499996E+00 6.000000E+01 5 3.662848E+02 -8.932704E+01 4.302074E+00 -3.662596E+02 - 6.499996E+00 6.000000E+01 6 2.698946E+03 -8.785026E+00 2.667282E+03 -4.122033E+02 - 6.499996E+00 9.000000E+01 1 1.183456E-05 -9.133024E+01 -2.747390E-07 -1.183137E-05 - 6.499996E+00 9.000000E+01 2 2.063142E+02 8.607605E+01 1.411855E+01 2.058306E+02 - 6.499996E+00 9.000000E+01 3 1.672458E+01 1.695131E+02 -1.644522E+01 3.044042E+00 - 6.499996E+00 9.000000E+01 4 1.093365E+03 8.603822E+01 7.554176E+01 1.090752E+03 - 6.499996E+00 9.000000E+01 5 2.486224E-04 -8.774632E+01 9.776836E-06 -2.484300E-04 - 6.499996E+00 9.000000E+01 6 3.442881E-04 1.752327E+02 -3.430970E-04 2.861344E-05 - 6.599996E+00 0.000000E+00 1 3.786176E+01 6.697951E+01 1.480623E+01 3.484664E+01 - 6.599996E+00 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 6.599996E+00 0.000000E+00 3 8.487835E+00 -1.796442E+02 -8.487671E+00 -5.270457E-02 - 6.599996E+00 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 6.599996E+00 0.000000E+00 5 5.388351E+02 -1.082077E+02 -1.683661E+02 -5.118555E+02 - 6.599996E+00 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 6.599996E+00 3.000000E+01 1 4.308966E+01 7.848481E+01 8.601892E+00 4.222235E+01 - 6.599996E+00 3.000000E+01 2 1.702968E+01 1.059161E+02 -4.670047E+00 1.637683E+01 - 6.599996E+00 3.000000E+01 3 1.213597E+01 1.736402E+02 -1.206129E+01 1.344316E+00 - 6.599996E+00 3.000000E+01 4 7.342095E+01 1.098535E+02 -2.493490E+01 6.905713E+01 - 6.599996E+00 3.000000E+01 5 4.506039E+02 -1.035107E+02 -1.052731E+02 -4.381340E+02 - 6.599996E+00 3.000000E+01 6 9.185867E+02 -1.533850E+01 8.858665E+02 -2.429855E+02 - 6.599996E+00 6.000000E+01 1 6.804441E+01 9.148019E+01 -1.757680E+00 6.802171E+01 - 6.599996E+00 6.000000E+01 2 1.069763E+02 8.832145E+01 3.133549E+00 1.069304E+02 - 6.599996E+00 6.000000E+01 3 1.575467E+01 1.700105E+02 -1.551582E+01 2.732924E+00 - 6.599996E+00 6.000000E+01 4 5.598049E+02 8.830235E+01 1.658437E+01 5.595591E+02 - 6.599996E+00 6.000000E+01 5 3.483130E+02 -8.898127E+01 6.192752E+00 -3.482580E+02 - 6.599996E+00 6.000000E+01 6 2.645371E+03 -8.273825E+00 2.617837E+03 -3.806798E+02 - 6.599996E+00 9.000000E+01 1 1.169387E-05 -9.053847E+01 -1.098983E-07 -1.169335E-05 - 6.599996E+00 9.000000E+01 2 2.067984E+02 8.601857E+01 1.435866E+01 2.062993E+02 - 6.599996E+00 9.000000E+01 3 1.495983E+01 1.705767E+02 -1.475796E+01 2.449327E+00 - 6.599996E+00 9.000000E+01 4 1.089383E+03 8.598453E+01 7.628492E+01 1.086709E+03 - 6.599996E+00 9.000000E+01 5 2.505603E-04 -8.793982E+01 9.007451E-06 -2.503984E-04 - 6.599996E+00 9.000000E+01 6 3.281282E-04 1.755054E+02 -3.271191E-04 2.571375E-05 - 6.699996E+00 0.000000E+00 1 4.455798E+01 7.049490E+01 1.487750E+01 4.200088E+01 - 6.699996E+00 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 6.699996E+00 0.000000E+00 3 8.688542E+00 1.795257E+02 -8.688245E+00 7.192025E-02 - 6.699996E+00 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 6.699996E+00 0.000000E+00 5 5.360759E+02 -1.057896E+02 -1.458690E+02 -5.158484E+02 - 6.699996E+00 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 6.699996E+00 3.000000E+01 1 5.037367E+01 8.024486E+01 8.535211E+00 4.964531E+01 - 6.699996E+00 3.000000E+01 2 2.063268E+01 9.993425E+01 -3.559507E+00 2.032333E+01 - 6.699996E+00 3.000000E+01 3 1.196493E+01 1.742294E+02 -1.190430E+01 1.203019E+00 - 6.699996E+00 3.000000E+01 4 8.782640E+01 1.024838E+02 -1.898485E+01 8.574994E+01 - 6.699996E+00 3.000000E+01 5 4.468409E+02 -1.015424E+02 -8.940945E+01 -4.378044E+02 - 6.699996E+00 3.000000E+01 6 1.000911E+03 -1.324486E+01 9.742869E+02 -2.293219E+02 - 6.699996E+00 6.000000E+01 1 7.031628E+01 9.148508E+01 -1.822360E+00 7.029266E+01 - 6.699996E+00 6.000000E+01 2 1.119460E+02 8.782357E+01 4.251348E+00 1.118652E+02 - 6.699996E+00 6.000000E+01 3 1.447888E+01 1.711226E+02 -1.430544E+01 2.234383E+00 - 6.699996E+00 6.000000E+01 4 5.786184E+02 8.779576E+01 2.225468E+01 5.781902E+02 - 6.699996E+00 6.000000E+01 5 3.286430E+02 -8.871101E+01 7.392869E+00 -3.285598E+02 - 6.699996E+00 6.000000E+01 6 2.586569E+03 -7.759521E+00 2.562885E+03 -3.492271E+02 - 6.699996E+00 9.000000E+01 1 1.153209E-05 -8.983506E+01 3.319838E-08 -1.153204E-05 - 6.699996E+00 9.000000E+01 2 2.070776E+02 8.595363E+01 1.461220E+01 2.065614E+02 - 6.699996E+00 9.000000E+01 3 1.299832E+01 1.715605E+02 -1.285757E+01 1.907696E+00 - 6.699996E+00 9.000000E+01 4 1.084159E+03 8.592821E+01 7.698219E+01 1.081422E+03 - 6.699996E+00 9.000000E+01 5 2.522556E-04 -8.814351E+01 8.172125E-06 -2.521232E-04 - 6.699996E+00 9.000000E+01 6 3.127473E-04 1.757775E+02 -3.118984E-04 2.302751E-05 - 6.799996E+00 0.000000E+00 1 5.113235E+01 7.353231E+01 1.449473E+01 4.903489E+01 - 6.799996E+00 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 6.799996E+00 0.000000E+00 3 8.732897E+00 1.789313E+02 -8.731378E+00 1.628813E-01 - 6.799996E+00 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 6.799996E+00 0.000000E+00 5 5.266843E+02 -1.035937E+02 -1.237892E+02 -5.119302E+02 - 6.799996E+00 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 6.799996E+00 3.000000E+01 1 5.715731E+01 8.175683E+01 8.194915E+00 5.656678E+01 - 6.799996E+00 3.000000E+01 2 2.428172E+01 9.603278E+01 -2.551944E+00 2.414725E+01 - 6.799996E+00 3.000000E+01 3 1.158336E+01 1.747928E+02 -1.153555E+01 1.051281E+00 - 6.799996E+00 3.000000E+01 4 1.028631E+02 9.762134E+01 -1.364228E+01 1.019544E+02 - 6.799996E+00 3.000000E+01 5 4.371751E+02 -9.979926E+01 -7.440577E+01 -4.307968E+02 - 6.799996E+00 3.000000E+01 6 1.068589E+03 -1.158160E+01 1.046832E+03 -2.145334E+02 - 6.799996E+00 6.000000E+01 1 7.223330E+01 9.148089E+01 -1.866762E+00 7.220918E+01 - 6.799996E+00 6.000000E+01 2 1.164352E+02 8.741300E+01 5.255457E+00 1.163165E+02 - 6.799996E+00 6.000000E+01 3 1.298696E+01 1.721374E+02 -1.286487E+01 1.776593E+00 - 6.799996E+00 6.000000E+01 4 5.951456E+02 8.737786E+01 2.722735E+01 5.945225E+02 - 6.799996E+00 6.000000E+01 5 3.077865E+02 -8.852185E+01 7.939594E+00 -3.076841E+02 - 6.799996E+00 6.000000E+01 6 2.523560E+03 -7.249585E+00 2.503386E+03 -3.184525E+02 - 6.799996E+00 9.000000E+01 1 1.135437E-05 -8.922071E+01 1.544279E-07 -1.135332E-05 - 6.799996E+00 9.000000E+01 2 2.071705E+02 8.588818E+01 1.485480E+01 2.066373E+02 - 6.799996E+00 9.000000E+01 3 1.086942E+01 1.724371E+02 -1.077487E+01 1.430578E+00 - 6.799996E+00 9.000000E+01 4 1.077842E+03 8.587426E+01 7.754592E+01 1.075049E+03 - 6.799996E+00 9.000000E+01 5 2.537453E-04 -8.835240E+01 7.295710E-06 -2.536403E-04 - 6.799996E+00 9.000000E+01 6 2.981145E-04 1.760457E+02 -2.974048E-04 2.055814E-05 - 6.899996E+00 0.000000E+00 1 5.745194E+01 7.612595E+01 1.377632E+01 5.577579E+01 - 6.899996E+00 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 6.899996E+00 0.000000E+00 3 8.607684E+00 1.785334E+02 -8.604864E+00 2.203111E-01 - 6.899996E+00 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 6.899996E+00 0.000000E+00 5 5.116173E+02 -1.016391E+02 -1.032173E+02 -5.010972E+02 - 6.899996E+00 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 6.899996E+00 3.000000E+01 1 6.339461E+01 8.305264E+01 7.668045E+00 6.292915E+01 - 6.899996E+00 3.000000E+01 2 2.786877E+01 9.338131E+01 -1.643719E+00 2.782025E+01 - 6.899996E+00 3.000000E+01 3 1.099518E+01 1.753356E+02 -1.095876E+01 8.941151E-01 - 6.899996E+00 3.000000E+01 4 1.178615E+02 9.432112E+01 -8.880433E+00 1.175264E+02 - 6.899996E+00 3.000000E+01 5 4.225779E+02 -9.828252E+01 -6.087412E+01 -4.181703E+02 - 6.899996E+00 3.000000E+01 6 1.122989E+03 -1.021568E+01 1.105186E+03 -1.991666E+02 - 6.899996E+00 6.000000E+01 1 7.383486E+01 9.145753E+01 -1.878057E+00 7.381097E+01 - 6.899996E+00 6.000000E+01 2 1.204713E+02 8.707623E+01 6.144914E+00 1.203145E+02 - 6.899996E+00 6.000000E+01 3 1.130301E+01 1.730492E+02 -1.121993E+01 1.367863E+00 - 6.899996E+00 6.000000E+01 4 6.095179E+02 8.703556E+01 3.152198E+01 6.087022E+02 - 6.899996E+00 6.000000E+01 5 2.861794E+02 -8.841126E+01 7.934399E+00 -2.860694E+02 - 6.899996E+00 6.000000E+01 6 2.457310E+03 -6.750232E+00 2.440276E+03 -2.888357E+02 - 6.899996E+00 9.000000E+01 1 1.116526E-05 -8.869334E+01 2.546057E-07 -1.116236E-05 - 6.899996E+00 9.000000E+01 2 2.070912E+02 8.582763E+01 1.506740E+01 2.065423E+02 - 6.899996E+00 9.000000E+01 3 8.599986E+00 1.731607E+02 -8.538789E+00 1.024133E+00 - 6.899996E+00 9.000000E+01 4 1.070553E+03 8.582662E+01 7.790929E+01 1.067714E+03 - 6.899996E+00 9.000000E+01 5 2.550481E-04 -8.856126E+01 6.403743E-06 -2.549677E-04 - 6.899996E+00 9.000000E+01 6 2.842032E-04 1.763074E+02 -2.836132E-04 1.830359E-05 - 6.999996E+00 0.000000E+00 1 6.343251E+01 7.832144E+01 1.284006E+01 6.211937E+01 - 6.999996E+00 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 6.999996E+00 0.000000E+00 3 8.304324E+00 1.782966E+02 -8.300654E+00 2.468486E-01 - 6.999996E+00 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 6.999996E+00 0.000000E+00 5 4.918595E+02 -9.992722E+01 -8.479517E+01 -4.844952E+02 - 6.999996E+00 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 6.999996E+00 3.000000E+01 1 6.907496E+01 8.415459E+01 7.034931E+00 6.871579E+01 - 6.999996E+00 3.000000E+01 2 3.133360E+01 9.151859E+01 -8.303803E-01 3.132260E+01 - 6.999996E+00 3.000000E+01 3 1.020716E+01 1.758622E+02 -1.018056E+01 7.364960E-01 - 6.999996E+00 3.000000E+01 4 1.324410E+02 9.201951E+01 -4.667178E+00 1.323587E+02 - 6.999996E+00 3.000000E+01 5 4.039922E+02 -9.698272E+01 -4.911329E+01 -4.009958E+02 - 6.999996E+00 3.000000E+01 6 1.165503E+03 -9.066772E+00 1.150941E+03 -1.836663E+02 - 6.999996E+00 6.000000E+01 1 7.516010E+01 9.141090E+01 -1.850616E+00 7.513731E+01 - 6.999996E+00 6.000000E+01 2 1.240806E+02 8.680267E+01 6.920580E+00 1.238875E+02 - 6.999996E+00 6.000000E+01 3 9.450929E+00 1.738460E+02 -9.396466E+00 1.013153E+00 - 6.999996E+00 6.000000E+01 4 6.218619E+02 8.675819E+01 3.516629E+01 6.208668E+02 - 6.999996E+00 6.000000E+01 5 2.641574E+02 -8.837112E+01 7.508770E+00 -2.640507E+02 - 6.999996E+00 6.000000E+01 6 2.388713E+03 -6.266428E+00 2.374440E+03 -2.607325E+02 - 6.999996E+00 9.000000E+01 1 1.096863E-05 -8.824891E+01 3.351755E-07 -1.096351E-05 - 6.999996E+00 9.000000E+01 2 2.068489E+02 8.577593E+01 1.523589E+01 2.062870E+02 - 6.999996E+00 9.000000E+01 3 6.214508E+00 1.736199E+02 -6.176019E+00 6.905746E-01 - 6.999996E+00 9.000000E+01 4 1.062390E+03 8.578819E+01 7.802592E+01 1.059521E+03 - 6.999996E+00 9.000000E+01 5 2.561845E-04 -8.876540E+01 5.519805E-06 -2.561250E-04 - 6.999996E+00 9.000000E+01 6 2.709863E-04 1.765605E+02 -2.704981E-04 1.625756E-05 - 7.099996E+00 0.000000E+00 1 6.902799E+01 8.016754E+01 1.178775E+01 6.801406E+01 - 7.099996E+00 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 7.099996E+00 0.000000E+00 3 7.818867E+00 1.781913E+02 -7.814971E+00 2.467834E-01 - 7.099996E+00 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 7.099996E+00 0.000000E+00 5 4.683553E+02 -9.844705E+01 -6.879926E+01 -4.632746E+02 - 7.099996E+00 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 7.099996E+00 3.000000E+01 1 7.421140E+01 8.508284E+01 6.361053E+00 7.393828E+01 - 7.099996E+00 3.000000E+01 2 3.464056E+01 9.017688E+01 -1.069370E-01 3.464040E+01 - 7.099996E+00 3.000000E+01 3 9.228217E+00 1.763761E+02 -9.209764E+00 5.832899E-01 - 7.099996E+00 3.000000E+01 4 1.463782E+02 9.037870E+01 -9.674802E-01 1.463750E+02 - 7.099996E+00 3.000000E+01 5 3.822705E+02 -9.588326E+01 -3.918346E+01 -3.802570E+02 - 7.099996E+00 3.000000E+01 6 1.197489E+03 -8.083371E+00 1.185591E+03 -1.683836E+02 - 7.099996E+00 6.000000E+01 1 7.624609E+01 9.134110E+01 -1.784504E+00 7.622520E+01 - 7.099996E+00 6.000000E+01 2 1.272887E+02 8.658373E+01 7.585104E+00 1.270625E+02 - 7.099996E+00 6.000000E+01 3 7.452615E+00 1.744976E+02 -7.418275E+00 7.146100E-01 - 7.099996E+00 6.000000E+01 4 6.323093E+02 8.653707E+01 3.819326E+01 6.311547E+02 - 7.099996E+00 6.000000E+01 5 2.420005E+02 -8.839009E+01 6.798873E+00 -2.419050E+02 - 7.099996E+00 6.000000E+01 6 2.318564E+03 -5.801970E+00 2.306687E+03 -2.343848E+02 - 7.099996E+00 9.000000E+01 1 1.076766E-05 -8.788194E+01 3.979592E-07 -1.076031E-05 - 7.099996E+00 9.000000E+01 2 2.064532E+02 8.573586E+01 1.535073E+01 2.058817E+02 - 7.099996E+00 9.000000E+01 3 3.737227E+00 1.734104E+02 -3.712537E+00 4.288726E-01 - 7.099996E+00 9.000000E+01 4 1.053439E+03 8.576096E+01 7.786783E+01 1.050557E+03 - 7.099996E+00 9.000000E+01 5 2.571575E-04 -8.896078E+01 4.663993E-06 -2.571152E-04 - 7.099996E+00 9.000000E+01 6 2.584371E-04 1.768035E+02 -2.580350E-04 1.441059E-05 - 7.199996E+00 0.000000E+00 1 7.421930E+01 8.171126E+01 1.069959E+01 7.344402E+01 - 7.199996E+00 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 7.199996E+00 0.000000E+00 3 7.150705E+00 1.781928E+02 -7.147148E+00 2.255081E-01 - 7.199996E+00 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 7.199996E+00 0.000000E+00 5 4.419293E+02 -9.717999E+01 -5.523533E+01 -4.384639E+02 - 7.199996E+00 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 7.199996E+00 3.000000E+01 1 7.883245E+01 8.585766E+01 5.694427E+00 7.862652E+01 - 7.199996E+00 3.000000E+01 2 3.776899E+01 8.919318E+01 5.318334E-01 3.776524E+01 - 7.199996E+00 3.000000E+01 3 8.068378E+00 1.768814E+02 -8.056430E+00 4.389446E-01 - 7.199996E+00 3.000000E+01 4 1.595447E+02 8.919025E+01 2.254713E+00 1.595288E+02 - 7.199996E+00 3.000000E+01 5 3.581570E+02 -9.496335E+01 -3.098722E+01 -3.568139E+02 - 7.199996E+00 3.000000E+01 6 1.220220E+03 -7.230842E+00 1.210516E+03 -1.535857E+02 - 7.199996E+00 6.000000E+01 1 7.712525E+01 9.125092E+01 -1.683711E+00 7.710687E+01 - 7.199996E+00 6.000000E+01 2 1.301200E+02 8.641229E+01 8.142446E+00 1.298650E+02 - 7.199996E+00 6.000000E+01 3 5.329028E+00 1.749167E+02 -5.308068E+00 4.721779E-01 - 7.199996E+00 6.000000E+01 4 6.409879E+02 8.636476E+01 4.064141E+01 6.396981E+02 - 7.199996E+00 6.000000E+01 5 2.198767E+02 -8.845608E+01 5.924181E+00 -2.197969E+02 - 7.199996E+00 6.000000E+01 6 2.247585E+03 -5.359552E+00 2.237759E+03 -2.099368E+02 - 7.199996E+00 9.000000E+01 1 1.056503E-05 -8.758630E+01 4.449422E-07 -1.055565E-05 - 7.199996E+00 9.000000E+01 2 2.059109E+02 8.570915E+01 1.540616E+01 2.053338E+02 - 7.199996E+00 9.000000E+01 3 1.192611E+00 1.686046E+02 -1.169101E+00 2.356335E-01 - 7.199996E+00 9.000000E+01 4 1.043784E+03 8.574621E+01 7.742220E+01 1.040909E+03 - 7.199996E+00 9.000000E+01 5 2.579798E-04 -8.914448E+01 3.851947E-06 -2.579511E-04 - 7.199996E+00 9.000000E+01 6 2.465296E-04 1.770352E+02 -2.461996E-04 1.275104E-05 - 7.299995E+00 0.000000E+00 1 7.900702E+01 8.299664E+01 9.633142E+00 7.841755E+01 - 7.299995E+00 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 7.299995E+00 0.000000E+00 3 6.303385E+00 1.782814E+02 -6.300550E+00 1.890387E-01 - 7.299995E+00 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 7.299995E+00 0.000000E+00 5 4.132928E+02 -9.610378E+01 -4.394532E+01 -4.109499E+02 - 7.299995E+00 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 7.299995E+00 3.000000E+01 1 8.297503E+01 8.649887E+01 5.067137E+00 8.282017E+01 - 7.299995E+00 3.000000E+01 2 4.070684E+01 8.846386E+01 1.091247E+00 4.069221E+01 - 7.299995E+00 3.000000E+01 3 6.739426E+00 1.773851E+02 -6.732409E+00 3.074704E-01 - 7.299995E+00 3.000000E+01 4 1.718642E+02 8.832094E+01 5.035780E+00 1.717904E+02 - 7.299995E+00 3.000000E+01 5 3.322572E+02 -9.420104E+01 -2.433993E+01 -3.313644E+02 - 7.299995E+00 3.000000E+01 6 1.234887E+03 -6.484753E+00 1.226986E+03 -1.394666E+02 - 7.299995E+00 6.000000E+01 1 7.782559E+01 9.114442E+01 -1.554368E+00 7.781007E+01 - 7.299995E+00 6.000000E+01 2 1.325970E+02 8.628230E+01 8.597677E+00 1.323180E+02 - 7.299995E+00 6.000000E+01 3 3.099323E+00 1.747380E+02 -3.086262E+00 2.842379E-01 - 7.299995E+00 6.000000E+01 4 6.480093E+02 8.623495E+01 4.255168E+01 6.466107E+02 - 7.299995E+00 6.000000E+01 5 1.979331E+02 -8.855743E+01 4.982943E+00 -1.978704E+02 - 7.299995E+00 6.000000E+01 6 2.176386E+03 -4.941000E+00 2.168298E+03 -1.874518E+02 - 7.299995E+00 9.000000E+01 1 1.036275E-05 -8.735548E+01 4.781286E-07 -1.035171E-05 - 7.299995E+00 9.000000E+01 2 2.052295E+02 8.569668E+01 1.539971E+01 2.046509E+02 - 7.299995E+00 9.000000E+01 3 1.438498E+00 4.225457E+00 1.434588E+00 1.059904E-01 - 7.299995E+00 9.000000E+01 4 1.033485E+03 8.574448E+01 7.668940E+01 1.030635E+03 - 7.299995E+00 9.000000E+01 5 2.586495E-04 -8.931433E+01 3.095230E-06 -2.586310E-04 - 7.299995E+00 9.000000E+01 6 2.352377E-04 1.772550E+02 -2.349678E-04 1.126597E-05 - 7.399995E+00 0.000000E+00 1 8.340108E+01 8.406290E+01 8.626729E+00 8.295373E+01 - 7.399995E+00 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 7.399995E+00 0.000000E+00 3 5.281970E+00 1.784444E+02 -5.280023E+00 1.433921E-01 - 7.399995E+00 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 7.399995E+00 0.000000E+00 5 3.830153E+02 -9.519530E+01 -3.468234E+01 -3.814418E+02 - 7.399995E+00 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 7.399995E+00 3.000000E+01 1 8.667696E+01 8.702539E+01 4.497969E+00 8.656017E+01 - 7.399995E+00 3.000000E+01 2 4.344891E+01 8.792039E+01 1.576675E+00 4.342029E+01 - 7.399995E+00 3.000000E+01 3 5.253987E+00 1.779033E+02 -5.250469E+00 1.922214E-01 - 7.399995E+00 3.000000E+01 4 1.832959E+02 8.768266E+01 7.411419E+00 1.831460E+02 - 7.399995E+00 3.000000E+01 5 3.050693E+02 -9.357434E+01 -1.901909E+01 -3.044759E+02 - 7.399995E+00 3.000000E+01 6 1.242579E+03 -5.827247E+00 1.236158E+03 -1.261583E+02 - 7.399995E+00 6.000000E+01 1 7.837060E+01 9.102612E+01 -1.403471E+00 7.835803E+01 - 7.399995E+00 6.000000E+01 2 1.347433E+02 8.618854E+01 8.956859E+00 1.344453E+02 - 7.399995E+00 6.000000E+01 3 7.860215E-01 1.691552E+02 -7.719834E-01 1.478894E-01 - 7.399995E+00 6.000000E+01 4 6.535016E+02 8.614218E+01 4.396807E+01 6.520209E+02 - 7.399995E+00 6.000000E+01 5 1.762595E+02 -8.868392E+01 4.048314E+00 -1.762130E+02 - 7.399995E+00 6.000000E+01 6 2.105494E+03 -4.547356E+00 2.098867E+03 -1.669300E+02 - 7.399995E+00 9.000000E+01 1 1.016247E-05 -8.718291E+01 4.994621E-07 -1.015019E-05 - 7.399995E+00 9.000000E+01 2 2.044150E+02 8.569868E+01 1.533145E+01 2.038392E+02 - 7.399995E+00 9.000000E+01 3 4.082258E+00 4.759538E-01 4.082117E+00 3.391077E-02 - 7.399995E+00 9.000000E+01 4 1.022605E+03 8.575587E+01 7.567914E+01 1.019801E+03 - 7.399995E+00 9.000000E+01 5 2.591698E-04 -8.946914E+01 2.401235E-06 -2.591586E-04 - 7.399995E+00 9.000000E+01 6 2.245352E-04 1.774623E+02 -2.243150E-04 9.941742E-06 - 7.499995E+00 0.000000E+00 1 8.742158E+01 8.494504E+01 7.702832E+00 8.708157E+01 - 7.499995E+00 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 7.499995E+00 0.000000E+00 3 4.095227E+00 1.786794E+02 -4.094140E+00 9.438183E-02 - 7.499995E+00 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 7.499995E+00 0.000000E+00 5 3.515769E+02 -9.443193E+01 -2.716799E+01 -3.505256E+02 - 7.499995E+00 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 7.499995E+00 3.000000E+01 1 8.997755E+01 8.745473E+01 3.995785E+00 8.988879E+01 - 7.499995E+00 3.000000E+01 2 4.599360E+01 8.751589E+01 1.993469E+00 4.595038E+01 - 7.499995E+00 3.000000E+01 3 3.625280E+00 1.784841E+02 -3.624011E+00 9.590188E-02 - 7.499995E+00 3.000000E+01 4 1.938288E+02 8.721533E+01 9.416683E+00 1.935999E+02 - 7.499995E+00 3.000000E+01 5 2.769919E+02 -9.306342E+01 -1.480279E+01 -2.765961E+02 - 7.499995E+00 3.000000E+01 6 1.244277E+03 -5.244829E+00 1.239067E+03 -1.137415E+02 - 7.499995E+00 6.000000E+01 1 7.877998E+01 9.090032E+01 -1.237872E+00 7.877025E+01 - 7.499995E+00 6.000000E+01 2 1.365795E+02 8.612640E+01 9.226720E+00 1.362675E+02 - 7.499995E+00 6.000000E+01 3 1.619560E+00 2.104268E+00 1.618468E+00 5.946723E-02 - 7.499995E+00 6.000000E+01 4 6.575726E+02 8.608166E+01 4.493509E+01 6.560355E+02 - 7.499995E+00 6.000000E+01 5 1.549301E+02 -8.882681E+01 3.172145E+00 -1.548976E+02 - 7.499995E+00 6.000000E+01 6 2.035356E+03 -4.178991E+00 2.029945E+03 -1.483215E+02 - 7.499995E+00 9.000000E+01 1 9.965480E-06 -8.706212E+01 5.107633E-07 -9.952382E-06 - 7.499995E+00 9.000000E+01 2 2.034739E+02 8.571490E+01 1.520344E+01 2.029051E+02 - 7.499995E+00 9.000000E+01 3 6.759169E+00 1.113236E-01 6.759156E+00 1.313281E-02 - 7.499995E+00 9.000000E+01 4 1.011207E+03 8.578003E+01 7.441042E+01 1.008466E+03 - 7.499995E+00 9.000000E+01 5 2.595411E-04 -8.960838E+01 1.773960E-06 -2.595350E-04 - 7.499995E+00 9.000000E+01 6 2.143955E-04 1.776571E+02 -2.142163E-04 8.764559E-06 - 7.599995E+00 0.000000E+00 1 9.108731E+01 8.567310E+01 6.872245E+00 9.082770E+01 - 7.599995E+00 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 7.599995E+00 0.000000E+00 3 2.753061E+00 1.790195E+02 -2.752658E+00 4.711146E-02 - 7.599995E+00 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 7.599995E+00 0.000000E+00 5 3.193669E+02 -9.379190E+01 -2.112063E+01 -3.186677E+02 - 7.599995E+00 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 7.599995E+00 3.000000E+01 1 9.291185E+01 8.780254E+01 3.562552E+00 9.284352E+01 - 7.599995E+00 3.000000E+01 2 4.834269E+01 8.721734E+01 2.346922E+00 4.828569E+01 - 7.599995E+00 3.000000E+01 3 1.866945E+00 1.793741E+02 -1.866833E+00 2.039605E-02 - 7.599995E+00 3.000000E+01 4 2.034649E+02 8.687680E+01 1.108542E+01 2.031627E+02 - 7.599995E+00 3.000000E+01 5 2.483542E+02 -9.264957E+01 -1.148071E+01 -2.480887E+02 - 7.599995E+00 3.000000E+01 6 1.240875E+03 -4.726879E+00 1.236654E+03 -1.022556E+02 - 7.599995E+00 6.000000E+01 1 7.907039E+01 9.077093E+01 -1.063876E+00 7.906323E+01 - 7.599995E+00 6.000000E+01 2 1.381267E+02 8.609180E+01 9.414437E+00 1.378055E+02 - 7.599995E+00 6.000000E+01 3 4.069374E+00 2.072948E-01 4.069347E+00 1.472287E-02 - 7.599995E+00 6.000000E+01 4 6.603373E+02 8.604908E+01 4.549854E+01 6.587679E+02 - 7.599995E+00 6.000000E+01 5 1.340043E+02 -8.897920E+01 2.387324E+00 -1.339831E+02 - 7.599995E+00 6.000000E+01 6 1.966332E+03 -3.835799E+00 1.961927E+03 -1.315424E+02 - 7.599995E+00 9.000000E+01 1 9.772629E-06 -8.698692E+01 5.136886E-07 -9.759118E-06 - 7.599995E+00 9.000000E+01 2 2.024144E+02 8.574466E+01 1.501944E+01 2.018564E+02 - 7.599995E+00 9.000000E+01 3 9.453634E+00 2.233773E-01 9.453563E+00 3.685650E-02 - 7.599995E+00 9.000000E+01 4 9.993538E+02 8.581632E+01 7.290702E+01 9.966908E+02 - 7.599995E+00 9.000000E+01 5 2.597687E-04 -8.973209E+01 1.214688E-06 -2.597658E-04 - 7.599995E+00 9.000000E+01 6 2.047929E-04 1.778394E+02 -2.046473E-04 7.720900E-06 - 7.699995E+00 0.000000E+00 1 9.442255E+01 8.627306E+01 6.137610E+00 9.422286E+01 - 7.699995E+00 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 7.699995E+00 0.000000E+00 3 1.266463E+00 1.797298E+02 -1.266448E+00 5.973011E-03 - 7.699995E+00 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 7.699995E+00 0.000000E+00 5 2.866823E+02 -9.325626E+01 -1.628411E+01 -2.862195E+02 - 7.699995E+00 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 7.699995E+00 3.000000E+01 1 9.551472E+01 8.808272E+01 3.195601E+00 9.546125E+01 - 7.699995E+00 3.000000E+01 2 5.050034E+01 8.700081E+01 2.642276E+00 5.043117E+01 - 7.699995E+00 3.000000E+01 3 3.403573E-02 -7.708894E+01 7.604886E-03 -3.317524E-02 - 7.699995E+00 3.000000E+01 4 2.122245E+02 8.663680E+01 1.245017E+01 2.118590E+02 - 7.699995E+00 3.000000E+01 5 2.194090E+02 -9.231698E+01 -8.870259E+00 -2.192297E+02 - 7.699995E+00 3.000000E+01 6 1.233160E+03 -4.264926E+00 1.229745E+03 -9.170797E+01 - 7.699995E+00 6.000000E+01 1 7.925520E+01 9.064118E+01 -8.868990E-01 7.925024E+01 - 7.699995E+00 6.000000E+01 2 1.394051E+02 8.608114E+01 9.527458E+00 1.390791E+02 - 7.699995E+00 6.000000E+01 3 6.567874E+00 7.875823E-02 6.567868E+00 9.028135E-03 - 7.699995E+00 6.000000E+01 4 6.618986E+02 8.604070E+01 4.570275E+01 6.603188E+02 - 7.699995E+00 6.000000E+01 5 1.135088E+02 -8.913577E+01 1.712074E+00 -1.134959E+02 - 7.699995E+00 6.000000E+01 6 1.898716E+03 -3.517265E+00 1.895140E+03 -1.164849E+02 - 7.699995E+00 9.000000E+01 1 9.584668E-06 -8.695145E+01 5.097324E-07 -9.571104E-06 - 7.699995E+00 9.000000E+01 2 2.012424E+02 8.578704E+01 1.478404E+01 2.006986E+02 - 7.699995E+00 9.000000E+01 3 1.215646E+01 4.643328E-01 1.215606E+01 9.851649E-02 - 7.699995E+00 9.000000E+01 4 9.870933E+02 8.586389E+01 7.119507E+01 9.845224E+02 - 7.699995E+00 9.000000E+01 5 2.598501E-04 -8.984074E+01 7.222630E-07 -2.598492E-04 - 7.699995E+00 9.000000E+01 6 1.957017E-04 1.780094E+02 -1.955836E-04 6.797717E-06 - 7.799995E+00 0.000000E+00 1 9.744762E+01 8.676672E+01 5.496192E+00 9.729250E+01 - 7.799995E+00 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 7.799995E+00 0.000000E+00 3 3.533028E-01 -4.133177E+00 3.523839E-01 -2.546430E-02 - 7.799995E+00 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 7.799995E+00 0.000000E+00 5 2.537789E+02 -9.280707E+01 -1.242832E+01 -2.534744E+02 - 7.799995E+00 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 7.799995E+00 3.000000E+01 1 9.781522E+01 8.830712E+01 2.889658E+00 9.777252E+01 - 7.799995E+00 3.000000E+01 2 5.247171E+01 8.684859E+01 2.884618E+00 5.239236E+01 - 7.799995E+00 3.000000E+01 3 1.986412E+00 -1.854771E+00 1.985371E+00 -6.429262E-02 - 7.799995E+00 3.000000E+01 4 2.201274E+02 8.647298E+01 1.354209E+01 2.197104E+02 - 7.799995E+00 3.000000E+01 5 1.903563E+02 -9.205275E+01 -6.818476E+00 -1.902341E+02 - 7.799995E+00 3.000000E+01 6 1.221833E+03 -3.851990E+00 1.219072E+03 -8.208183E+01 - 7.799995E+00 6.000000E+01 1 7.934649E+01 9.051372E+01 -7.114094E-01 7.934330E+01 - 7.799995E+00 6.000000E+01 2 1.404336E+02 8.609111E+01 9.573378E+00 1.401069E+02 - 7.799995E+00 6.000000E+01 3 9.102118E+00 2.380052E-01 9.102040E+00 3.780986E-02 - 7.799995E+00 6.000000E+01 4 6.623581E+02 8.605309E+01 4.559156E+01 6.607872E+02 - 7.799995E+00 6.000000E+01 5 9.347800E+01 -8.929327E+01 1.153013E+00 -9.347089E+01 - 7.799995E+00 6.000000E+01 6 1.832736E+03 -3.222579E+00 1.829838E+03 -1.030272E+02 - 7.799995E+00 9.000000E+01 1 9.401953E-06 -8.695017E+01 5.002249E-07 -9.388636E-06 - 7.799995E+00 9.000000E+01 2 1.999665E+02 8.584091E+01 1.450279E+01 1.994399E+02 - 7.799995E+00 9.000000E+01 3 1.485886E+01 7.400206E-01 1.485762E+01 1.919087E-01 - 7.799995E+00 9.000000E+01 4 9.744837E+02 8.592172E+01 6.930460E+01 9.720161E+02 - 7.799995E+00 9.000000E+01 5 2.597919E-04 -8.993514E+01 2.940749E-07 -2.597917E-04 - 7.799995E+00 9.000000E+01 6 1.870968E-04 1.781676E+02 -1.870011E-04 5.982688E-06 - 7.899995E+00 0.000000E+00 1 1.001835E+02 8.717259E+01 4.941816E+00 1.000616E+02 - 7.899995E+00 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 7.899995E+00 0.000000E+00 3 2.091449E+00 -1.222346E+00 2.090973E+00 -4.461550E-02 - 7.899995E+00 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 7.899995E+00 0.000000E+00 5 2.208600E+02 -9.242885E+01 -9.359738E+00 -2.206615E+02 - 7.899995E+00 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 7.899995E+00 3.000000E+01 1 9.984132E+01 8.848597E+01 2.637978E+00 9.980646E+01 - 7.899995E+00 3.000000E+01 2 5.426383E+01 8.674731E+01 3.078921E+00 5.417641E+01 - 7.899995E+00 3.000000E+01 3 4.054196E+00 -1.035074E+00 4.053535E+00 -7.323688E-02 - 7.899995E+00 3.000000E+01 4 2.272098E+02 8.636868E+01 1.439062E+01 2.267536E+02 - 7.899995E+00 3.000000E+01 5 1.613735E+02 -9.184579E+01 -5.197766E+00 -1.612898E+02 - 7.899995E+00 3.000000E+01 6 1.207513E+03 -3.482229E+00 1.205284E+03 -7.334307E+01 - 7.899995E+00 6.000000E+01 1 7.935417E+01 9.039056E+01 -5.409049E-01 7.935233E+01 - 7.899995E+00 6.000000E+01 2 1.412311E+02 8.611877E+01 9.559717E+00 1.409072E+02 - 7.899995E+00 6.000000E+01 3 1.166198E+01 4.730663E-01 1.166158E+01 9.628679E-02 - 7.899995E+00 6.000000E+01 4 6.618198E+02 8.608330E+01 4.520630E+01 6.602740E+02 - 7.899995E+00 6.000000E+01 5 7.393465E+01 -8.944995E+01 7.097710E-01 -7.393124E+01 - 7.899995E+00 6.000000E+01 6 1.768568E+03 -2.950732E+00 1.766223E+03 -9.104096E+01 - 7.899995E+00 9.000000E+01 1 9.224881E-06 -8.697808E+01 4.863176E-07 -9.212054E-06 - 7.899995E+00 9.000000E+01 2 1.985938E+02 8.590507E+01 1.418145E+01 1.980869E+02 - 7.899995E+00 9.000000E+01 3 1.755438E+01 1.015346E+00 1.755162E+01 3.110671E-01 - 7.899995E+00 9.000000E+01 4 9.615761E+02 8.598869E+01 6.726544E+01 9.592205E+02 - 7.899995E+00 9.000000E+01 5 2.595977E-04 -9.001629E+01 -7.377717E-08 -2.595977E-04 - 7.899995E+00 9.000000E+01 6 1.789530E-04 1.783143E+02 -1.788755E-04 5.264333E-06 - 7.999995E+00 0.000000E+00 1 1.026511E+02 8.750613E+01 4.466602E+00 1.025539E+02 - 7.999995E+00 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 7.999995E+00 0.000000E+00 3 3.937476E+00 -7.238156E-01 3.937161E+00 -4.974067E-02 - 7.999995E+00 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 7.999995E+00 0.000000E+00 5 1.880801E+02 -9.210726E+01 -6.915757E+00 -1.879529E+02 - 7.999995E+00 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 7.999995E+00 3.000000E+01 1 1.016173E+02 8.862783E+01 2.433381E+00 1.015881E+02 - 7.999995E+00 3.000000E+01 2 5.588414E+01 8.668661E+01 3.229963E+00 5.579073E+01 - 7.999995E+00 3.000000E+01 3 6.199816E+00 -5.616584E-01 6.199518E+00 -6.077451E-02 - 7.999995E+00 3.000000E+01 4 2.335099E+02 8.631115E+01 1.502359E+01 2.330261E+02 - 7.999995E+00 3.000000E+01 5 1.325916E+02 -9.168777E+01 -3.905201E+00 -1.325341E+02 - 7.999995E+00 3.000000E+01 6 1.190741E+03 -3.150677E+00 1.188941E+03 -6.544550E+01 - 7.999995E+00 6.000000E+01 1 7.928681E+01 9.027322E+01 -3.780780E-01 7.928591E+01 - 7.999995E+00 6.000000E+01 2 1.418152E+02 8.616150E+01 9.493734E+00 1.414971E+02 - 7.999995E+00 6.000000E+01 3 1.423871E+01 7.244696E-01 1.423757E+01 1.800348E-01 - 7.999995E+00 6.000000E+01 4 6.603688E+02 8.612856E+01 4.458681E+01 6.588619E+02 - 7.999995E+00 6.000000E+01 5 5.490401E+01 -8.960667E+01 3.769139E-01 -5.490271E+01 - 7.999995E+00 6.000000E+01 6 1.706345E+03 -2.700556E+00 1.704450E+03 -8.039639E+01 - 7.999995E+00 9.000000E+01 1 9.053556E-06 -8.703043E+01 4.690244E-07 -9.041399E-06 - 7.999995E+00 9.000000E+01 2 1.971333E+02 8.597823E+01 1.382605E+01 1.966479E+02 - 7.999995E+00 9.000000E+01 3 2.023759E+01 1.275899E+00 2.023257E+01 4.506261E-01 - 7.999995E+00 9.000000E+01 4 9.484269E+02 8.606368E+01 6.510731E+01 9.461896E+02 - 7.999995E+00 9.000000E+01 5 2.592711E-04 -9.008528E+01 -3.859052E-07 -2.592708E-04 - 7.999995E+00 9.000000E+01 6 1.712471E-04 1.784500E+02 -1.711845E-04 4.632054E-06 - 8.099995E+00 0.000000E+00 1 1.048676E+02 8.778030E+01 4.061672E+00 1.047889E+02 - 8.099995E+00 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 8.099995E+00 0.000000E+00 3 5.878958E+00 -3.878740E-01 5.878823E+00 -3.979835E-02 - 8.099995E+00 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 8.099995E+00 0.000000E+00 5 1.555692E+02 -9.182758E+01 -4.961399E+00 -1.554901E+02 - 8.099995E+00 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 8.099995E+00 3.000000E+01 1 1.031647E+02 8.873989E+01 2.268725E+00 1.031398E+02 - 8.099995E+00 3.000000E+01 2 5.734096E+01 8.665842E+01 3.342315E+00 5.724347E+01 - 8.099995E+00 3.000000E+01 3 8.412326E+00 -1.913998E-01 8.412279E+00 -2.810179E-02 - 8.099995E+00 3.000000E+01 4 2.390619E+02 8.629047E+01 1.546689E+01 2.385610E+02 - 8.099995E+00 3.000000E+01 5 1.041119E+02 -9.157516E+01 -2.861869E+00 -1.040726E+02 - 8.099995E+00 3.000000E+01 6 1.171987E+03 -2.853062E+00 1.170535E+03 -5.833537E+01 - 8.099995E+00 6.000000E+01 1 7.915191E+01 9.016277E+01 -2.248562E-01 7.915159E+01 - 8.099995E+00 6.000000E+01 2 1.422033E+02 8.621691E+01 9.382489E+00 1.418934E+02 - 8.099995E+00 6.000000E+01 3 1.682552E+01 9.696588E-01 1.682311E+01 2.847371E-01 - 8.099995E+00 6.000000E+01 4 6.580927E+02 8.618642E+01 4.376996E+01 6.566354E+02 - 8.099995E+00 6.000000E+01 5 3.638227E+01 -8.977335E+01 1.439245E-01 -3.638198E+01 - 8.099995E+00 6.000000E+01 6 1.646148E+03 -2.470806E+00 1.644618E+03 -7.096602E+01 - 8.099995E+00 9.000000E+01 1 8.888026E-06 -8.710305E+01 4.491992E-07 -8.876667E-06 - 8.099995E+00 9.000000E+01 2 1.955928E+02 8.605914E+01 1.344249E+01 1.951303E+02 - 8.099995E+00 9.000000E+01 3 2.290479E+01 1.515339E+00 2.289677E+01 6.057073E-01 - 8.099995E+00 9.000000E+01 4 9.350745E+02 8.614549E+01 6.285859E+01 9.329593E+02 - 8.099995E+00 9.000000E+01 5 2.588207E-04 -9.014330E+01 -6.473321E-07 -2.588199E-04 - 8.099995E+00 9.000000E+01 6 1.639552E-04 1.785754E+02 -1.639046E-04 4.076145E-06 - 8.199995E+00 0.000000E+00 1 1.068520E+02 8.800578E+01 3.718322E+00 1.067873E+02 - 8.199995E+00 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 8.199995E+00 0.000000E+00 3 7.902928E+00 -1.063022E-01 7.902915E+00 -1.466247E-02 - 8.199995E+00 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 8.199995E+00 0.000000E+00 5 1.234563E+02 -9.157329E+01 -3.389571E+00 -1.234097E+02 - 8.199995E+00 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 8.199995E+00 3.000000E+01 1 1.045033E+02 8.882807E+01 2.137357E+00 1.044814E+02 - 8.199995E+00 3.000000E+01 2 5.864267E+01 8.665630E+01 3.420366E+00 5.854284E+01 - 8.199995E+00 3.000000E+01 3 1.068015E+01 1.240289E-01 1.068013E+01 2.311945E-02 - 8.199995E+00 3.000000E+01 4 2.439129E+02 8.629896E+01 1.574469E+01 2.434042E+02 - 8.199995E+00 3.000000E+01 5 7.604199E+01 -9.151055E+01 -2.004550E+00 -7.601556E+01 - 8.199995E+00 3.000000E+01 6 1.151663E+03 -2.585664E+00 1.150490E+03 -5.195500E+01 - 8.199995E+00 6.000000E+01 1 7.895687E+01 9.005986E+01 -8.249161E-02 7.895683E+01 - 8.199995E+00 6.000000E+01 2 1.424118E+02 8.628288E+01 9.232624E+00 1.421122E+02 - 8.199995E+00 6.000000E+01 3 1.941458E+01 1.199059E+00 1.941032E+01 4.062694E-01 - 8.199995E+00 6.000000E+01 4 6.550826E+02 8.625477E+01 4.279003E+01 6.536836E+02 - 8.199995E+00 6.000000E+01 5 1.840337E+01 -8.999612E+01 1.248352E-03 -1.840337E+01 - 8.199995E+00 6.000000E+01 6 1.588037E+03 -2.260185E+00 1.586802E+03 -6.262812E+01 - 8.199995E+00 9.000000E+01 1 8.728281E-06 -8.719205E+01 4.275842E-07 -8.717801E-06 - 8.199995E+00 9.000000E+01 2 1.939802E+02 8.614654E+01 1.303642E+01 1.935417E+02 - 8.199995E+00 9.000000E+01 3 2.555106E+01 1.731206E+00 2.553940E+01 7.719142E-01 - 8.199995E+00 9.000000E+01 4 9.215750E+02 8.623306E+01 6.054570E+01 9.195839E+02 - 8.199995E+00 9.000000E+01 5 2.582526E-04 -9.019151E+01 -8.632314E-07 -2.582512E-04 - 8.199995E+00 9.000000E+01 6 1.570556E-04 1.786910E+02 -1.570146E-04 3.587820E-06 - 8.299995E+00 0.000000E+00 1 1.086188E+02 8.819144E+01 3.428026E+00 1.085647E+02 - 8.299995E+00 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 8.299995E+00 0.000000E+00 3 9.999021E+00 1.456736E-01 9.998988E+00 2.542233E-02 - 8.299995E+00 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 8.299995E+00 0.000000E+00 5 9.182286E+01 -9.132073E+01 -2.116430E+00 -9.179847E+01 - 8.299995E+00 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 8.299995E+00 3.000000E+01 1 1.056509E+02 8.889730E+01 2.033197E+00 1.056313E+02 - 8.299995E+00 3.000000E+01 2 5.979816E+01 8.667507E+01 3.468193E+00 5.969751E+01 - 8.299995E+00 3.000000E+01 3 1.299342E+01 4.014685E-01 1.299310E+01 9.104348E-02 - 8.299995E+00 3.000000E+01 4 2.481039E+02 8.633039E+01 1.587941E+01 2.475952E+02 - 8.299995E+00 3.000000E+01 5 4.845108E+01 -9.152054E+01 -1.285665E+00 -4.843402E+01 - 8.299995E+00 3.000000E+01 6 1.130121E+03 -2.345234E+00 1.129175E+03 -4.624528E+01 - 8.299995E+00 6.000000E+01 1 7.870705E+01 8.996489E+01 4.823263E-02 7.870704E+01 - 8.299995E+00 6.000000E+01 2 1.424557E+02 8.635747E+01 9.050406E+00 1.421679E+02 - 8.299995E+00 6.000000E+01 3 2.200033E+01 1.409368E+00 2.199367E+01 5.411121E-01 - 8.299995E+00 6.000000E+01 4 6.514143E+02 8.633164E+01 4.167820E+01 6.500797E+02 - 8.299995E+00 6.000000E+01 5 9.643353E-01 -9.382101E+01 -6.426318E-02 -9.621917E-01 - 8.299995E+00 6.000000E+01 6 1.532040E+03 -2.067390E+00 1.531042E+03 -5.526822E+01 - 8.299995E+00 9.000000E+01 1 8.574210E-06 -8.729401E+01 4.047953E-07 -8.564650E-06 - 8.299995E+00 9.000000E+01 2 1.923042E+02 8.623924E+01 1.261333E+01 1.918901E+02 - 8.299995E+00 9.000000E+01 3 2.817375E+01 1.923349E+00 2.815788E+01 9.455803E-01 - 8.299995E+00 9.000000E+01 4 9.079691E+02 8.632528E+01 5.819356E+01 9.061024E+02 - 8.299995E+00 9.000000E+01 5 2.575735E-04 -9.023106E+01 -1.038740E-06 -2.575714E-04 - 8.299995E+00 9.000000E+01 6 1.505263E-04 1.787974E+02 -1.504932E-04 3.159157E-06 - 8.399996E+00 0.000000E+00 1 1.101842E+02 8.834463E+01 3.182974E+00 1.101382E+02 - 8.399996E+00 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 8.399996E+00 0.000000E+00 3 1.215627E+01 3.754811E-01 1.215601E+01 7.966411E-02 - 8.399996E+00 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 8.399996E+00 0.000000E+00 5 6.073744E+01 -9.101222E+01 -1.072971E+00 -6.072796E+01 - 8.399996E+00 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 8.399996E+00 3.000000E+01 1 1.066237E+02 8.895159E+01 1.950916E+00 1.066059E+02 - 8.399996E+00 3.000000E+01 2 6.081600E+01 8.671054E+01 3.489645E+00 6.071580E+01 - 8.399996E+00 3.000000E+01 3 1.534336E+01 6.485831E-01 1.534238E+01 1.736817E-01 - 8.399996E+00 3.000000E+01 4 2.516782E+02 8.637983E+01 1.589144E+01 2.511760E+02 - 8.399996E+00 3.000000E+01 5 2.139992E+01 -9.179913E+01 -6.718618E-01 -2.138937E+01 - 8.399996E+00 3.000000E+01 6 1.107667E+03 -2.128899E+00 1.106903E+03 -4.114735E+01 - 8.399996E+00 6.000000E+01 1 7.840784E+01 8.987799E+01 1.669732E-01 7.840767E+01 - 8.399996E+00 6.000000E+01 2 1.423499E+02 8.643902E+01 8.841481E+00 1.420750E+02 - 8.399996E+00 6.000000E+01 3 2.457878E+01 1.598849E+00 2.456922E+01 6.857862E-01 - 8.399996E+00 6.000000E+01 4 6.471569E+02 8.641531E+01 4.046268E+01 6.458907E+02 - 8.399996E+00 6.000000E+01 5 1.593196E+01 9.023058E+01 -6.411661E-02 1.593184E+01 - 8.399996E+00 6.000000E+01 6 1.478153E+03 -1.891146E+00 1.477348E+03 -4.878013E+01 - 8.399996E+00 9.000000E+01 1 8.425674E-06 -8.740590E+01 3.813477E-07 -8.417040E-06 - 8.399996E+00 9.000000E+01 2 1.905720E+02 8.633611E+01 1.217818E+01 1.901825E+02 - 8.399996E+00 9.000000E+01 3 3.077169E+01 2.092187E+00 3.075118E+01 1.123396E+00 - 8.399996E+00 9.000000E+01 4 8.942975E+02 8.642114E+01 5.582407E+01 8.925535E+02 - 8.399996E+00 9.000000E+01 5 2.567888E-04 -9.026302E+01 -1.178763E-06 -2.567861E-04 - 8.399996E+00 9.000000E+01 6 1.443470E-04 1.788952E+02 -1.443201E-04 2.783047E-06 - 8.499996E+00 0.000000E+00 1 1.115610E+02 8.847137E+01 2.976067E+00 1.115213E+02 - 8.499996E+00 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 8.499996E+00 0.000000E+00 3 1.436424E+01 5.859408E-01 1.436349E+01 1.468947E-01 - 8.499996E+00 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 8.499996E+00 0.000000E+00 5 3.026838E+01 -9.039252E+01 -2.073547E-01 -3.026767E+01 - 8.499996E+00 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 8.499996E+00 3.000000E+01 1 1.074365E+02 8.899419E+01 1.885903E+00 1.074199E+02 - 8.499996E+00 3.000000E+01 2 6.170529E+01 8.675925E+01 3.488291E+00 6.160661E+01 - 8.499996E+00 3.000000E+01 3 1.772121E+01 8.693196E-01 1.771917E+01 2.688645E-01 - 8.499996E+00 3.000000E+01 4 2.546799E+02 8.644330E+01 1.579940E+01 2.541894E+02 - 8.499996E+00 3.000000E+01 5 5.062679E+00 9.151420E+01 -1.337793E-01 5.060912E+00 - 8.499996E+00 3.000000E+01 6 1.084562E+03 -1.934128E+00 1.083944E+03 -3.660450E+01 - 8.499996E+00 6.000000E+01 1 7.806481E+01 8.979910E+01 2.737343E-01 7.806433E+01 - 8.499996E+00 6.000000E+01 2 1.421089E+02 8.652599E+01 8.611196E+00 1.418477E+02 - 8.499996E+00 6.000000E+01 3 2.714522E+01 1.767649E+00 2.713231E+01 8.373327E-01 - 8.499996E+00 6.000000E+01 4 6.423845E+02 8.650430E+01 3.916857E+01 6.411893E+02 - 8.499996E+00 6.000000E+01 5 3.227318E+01 9.001779E+01 -1.001967E-02 3.227318E+01 - 8.499996E+00 6.000000E+01 6 1.426372E+03 -1.730191E+00 1.425722E+03 -4.306636E+01 - 8.499996E+00 9.000000E+01 1 1.042746E-05 -8.652386E+01 6.322487E-07 -1.040828E-05 - 8.499996E+00 9.000000E+01 2 1.887924E+02 8.643615E+01 1.173549E+01 1.884273E+02 - 8.499996E+00 9.000000E+01 3 3.334180E+01 2.238865E+00 3.331635E+01 1.302519E+00 - 8.499996E+00 9.000000E+01 4 8.806016E+02 8.651970E+01 5.345721E+01 8.789775E+02 - 8.499996E+00 9.000000E+01 5 3.221859E-04 -8.928722E+01 4.007965E-06 -3.221609E-04 - 8.499996E+00 9.000000E+01 6 1.384979E-04 1.789851E+02 -1.384762E-04 2.453158E-06 - 8.599997E+00 0.000000E+00 1 1.127633E+02 8.857661E+01 2.801085E+00 1.127285E+02 - 8.599997E+00 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 8.599997E+00 0.000000E+00 3 1.661392E+01 7.786490E-01 1.661238E+01 2.257760E-01 - 8.599997E+00 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 8.599997E+00 0.000000E+00 5 7.083997E-01 -4.257503E+01 5.216599E-01 -4.792714E-01 - 8.599997E+00 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 8.599997E+00 3.000000E+01 1 1.081019E+02 8.902776E+01 1.834273E+00 1.080864E+02 - 8.599997E+00 3.000000E+01 2 6.247464E+01 8.681840E+01 3.467401E+00 6.237835E+01 - 8.599997E+00 3.000000E+01 3 2.011938E+01 1.066583E+00 2.011590E+01 3.745086E-01 - 8.599997E+00 3.000000E+01 4 2.571511E+02 8.651755E+01 1.562009E+01 2.566763E+02 - 8.599997E+00 3.000000E+01 5 3.088075E+01 8.935660E+01 3.467661E-01 3.087881E+01 - 8.599997E+00 3.000000E+01 6 1.061029E+03 -1.758672E+00 1.060529E+03 -3.256275E+01 - 8.599997E+00 6.000000E+01 1 7.768225E+01 8.972802E+01 3.687541E-01 7.768137E+01 - 8.599997E+00 6.000000E+01 2 1.417454E+02 8.661707E+01 8.364246E+00 1.414984E+02 - 8.599997E+00 6.000000E+01 3 2.969547E+01 1.916534E+00 2.967886E+01 9.931231E-01 - 8.599997E+00 6.000000E+01 4 6.371637E+02 8.659726E+01 3.781829E+01 6.360403E+02 - 8.599997E+00 6.000000E+01 5 4.805872E+01 8.989476E+01 8.827934E-02 4.805864E+01 - 8.599997E+00 6.000000E+01 6 1.376663E+03 -1.583330E+00 1.376137E+03 -3.803830E+01 - 8.599997E+00 9.000000E+01 1 1.023129E-05 -8.663912E+01 5.998070E-07 -1.021369E-05 - 8.599997E+00 9.000000E+01 2 1.869718E+02 8.653838E+01 1.128936E+01 1.866306E+02 - 8.599997E+00 9.000000E+01 3 3.588227E+01 2.364943E+00 3.585170E+01 1.480657E+00 - 8.599997E+00 9.000000E+01 4 8.669142E+02 8.662012E+01 5.110961E+01 8.654063E+02 - 8.599997E+00 9.000000E+01 5 3.202662E-04 -8.929819E+01 3.922801E-06 -3.202422E-04 - 8.599997E+00 9.000000E+01 6 1.329601E-04 1.790675E+02 -1.329425E-04 2.163852E-06 - 8.699997E+00 0.000000E+00 1 1.138037E+02 8.866444E+01 2.652522E+00 1.137728E+02 - 8.699997E+00 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 8.699997E+00 0.000000E+00 3 1.889723E+01 9.544963E-01 1.889460E+01 3.147963E-01 - 8.699997E+00 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 8.699997E+00 0.000000E+00 5 2.862950E+01 8.771075E+01 1.143582E+00 2.860665E+01 - 8.699997E+00 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 8.699997E+00 3.000000E+01 1 1.086335E+02 8.905442E+01 1.792759E+00 1.086187E+02 - 8.699997E+00 3.000000E+01 2 6.313221E+01 8.688560E+01 3.429956E+00 6.303897E+01 - 8.699997E+00 3.000000E+01 3 2.253175E+01 1.242531E+00 2.252645E+01 4.885909E-01 - 8.699997E+00 3.000000E+01 4 2.591305E+02 8.659990E+01 1.536855E+01 2.586743E+02 - 8.699997E+00 3.000000E+01 5 5.604251E+01 8.920014E+01 7.823366E-01 5.603704E+01 - 8.699997E+00 3.000000E+01 6 1.037252E+03 -1.600515E+00 1.036847E+03 -2.897108E+01 - 8.699997E+00 6.000000E+01 1 7.726470E+01 8.966447E+01 4.524664E-01 7.726337E+01 - 8.699997E+00 6.000000E+01 2 1.412723E+02 8.671111E+01 8.104875E+00 1.410396E+02 - 8.699997E+00 6.000000E+01 3 3.222758E+01 2.046584E+00 3.220703E+01 1.150913E+00 - 8.699997E+00 6.000000E+01 4 6.315511E+02 8.669302E+01 3.643149E+01 6.304995E+02 - 8.699997E+00 6.000000E+01 5 6.329416E+01 8.980098E+01 2.198613E-01 6.329378E+01 - 8.699997E+00 6.000000E+01 6 1.328988E+03 -1.449415E+00 1.328563E+03 -3.361591E+01 - 8.699997E+00 9.000000E+01 1 1.004328E-05 -8.676299E+01 5.671095E-07 -1.002725E-05 - 8.699997E+00 9.000000E+01 2 1.851176E+02 8.664194E+01 1.084338E+01 1.847998E+02 - 8.699997E+00 9.000000E+01 3 3.839290E+01 2.472024E+00 3.835717E+01 1.655946E+00 - 8.699997E+00 9.000000E+01 4 8.532695E+02 8.672157E+01 4.879702E+01 8.518731E+02 - 8.699997E+00 9.000000E+01 5 3.182887E-04 -8.931004E+01 3.832783E-06 -3.182656E-04 - 8.699997E+00 9.000000E+01 6 1.277159E-04 1.791430E+02 -1.277016E-04 1.910145E-06 - 8.799997E+00 0.000000E+00 1 1.146925E+02 8.873815E+01 2.525715E+00 1.146646E+02 - 8.799997E+00 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 8.799997E+00 0.000000E+00 3 2.120618E+01 1.114105E+00 2.120217E+01 4.123240E-01 - 8.799997E+00 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 8.799997E+00 0.000000E+00 5 5.696907E+01 8.830740E+01 1.682705E+00 5.694421E+01 - 8.799997E+00 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 8.799997E+00 3.000000E+01 1 1.090416E+02 8.907587E+01 1.758680E+00 1.090274E+02 - 8.799997E+00 3.000000E+01 2 6.368653E+01 8.695892E+01 3.378690E+00 6.359685E+01 - 8.799997E+00 3.000000E+01 3 2.495154E+01 1.398870E+00 2.494411E+01 6.091287E-01 - 8.799997E+00 3.000000E+01 4 2.606603E+02 8.668817E+01 1.505839E+01 2.602250E+02 - 8.799997E+00 3.000000E+01 5 8.050187E+01 8.915780E+01 1.183269E+00 8.049317E+01 - 8.799997E+00 3.000000E+01 6 1.013393E+03 -1.457878E+00 1.013065E+03 -2.578277E+01 - 8.799997E+00 6.000000E+01 1 7.681592E+01 8.960807E+01 5.254475E-01 7.681412E+01 - 8.799997E+00 6.000000E+01 2 1.407009E+02 8.680706E+01 7.836827E+00 1.404825E+02 - 8.799997E+00 6.000000E+01 3 3.473800E+01 2.159020E+00 3.471334E+01 1.308688E+00 - 8.799997E+00 6.000000E+01 4 6.256008E+02 8.679055E+01 3.502496E+01 6.246196E+02 - 8.799997E+00 6.000000E+01 5 7.797361E+01 8.972295E+01 3.770394E-01 7.797270E+01 - 8.799997E+00 6.000000E+01 6 1.283291E+03 -1.327380E+00 1.282947E+03 -2.972753E+01 - 8.799997E+00 9.000000E+01 1 9.863033E-06 -8.689292E+01 5.345981E-07 -9.848533E-06 - 8.799997E+00 9.000000E+01 2 1.832373E+02 8.674611E+01 1.040067E+01 1.829419E+02 - 8.799997E+00 9.000000E+01 3 4.087251E+01 2.561725E+00 4.083166E+01 1.826823E+00 - 8.799997E+00 9.000000E+01 4 8.397040E+02 8.682341E+01 4.653093E+01 8.384138E+02 - 8.799997E+00 9.000000E+01 5 3.162640E-04 -8.932271E+01 3.738477E-06 -3.162420E-04 - 8.799997E+00 9.000000E+01 6 1.227483E-04 1.792122E+02 -1.227367E-04 1.687626E-06 - 8.899998E+00 0.000000E+00 1 1.154415E+02 8.880047E+01 2.416671E+00 1.154162E+02 - 8.899998E+00 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 8.899998E+00 0.000000E+00 3 2.353365E+01 1.258228E+00 2.352797E+01 5.167626E-01 - 8.899998E+00 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 8.899998E+00 0.000000E+00 5 8.453156E+01 8.853838E+01 2.156168E+00 8.450405E+01 - 8.899998E+00 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 8.899998E+00 3.000000E+01 1 1.093369E+02 8.909344E+01 1.729911E+00 1.093232E+02 - 8.899998E+00 3.000000E+01 2 6.414483E+01 8.703671E+01 3.316039E+00 6.405906E+01 - 8.899998E+00 3.000000E+01 3 2.737386E+01 1.537138E+00 2.736401E+01 7.343010E-01 - 8.899998E+00 3.000000E+01 4 2.617768E+02 8.678060E+01 1.470127E+01 2.613637E+02 - 8.899998E+00 3.000000E+01 5 1.042432E+02 8.914483E+01 1.555832E+00 1.042316E+02 - 8.899998E+00 3.000000E+01 6 9.895847E+02 -1.329165E+00 9.893184E+02 -2.295463E+01 - 8.899998E+00 6.000000E+01 1 7.633929E+01 8.955841E+01 5.883585E-01 7.633702E+01 - 8.899998E+00 6.000000E+01 2 1.400420E+02 8.690406E+01 7.563385E+00 1.398376E+02 - 8.899998E+00 6.000000E+01 3 3.722475E+01 2.255234E+00 3.719592E+01 1.464835E+00 - 8.899998E+00 6.000000E+01 4 6.193709E+02 8.688903E+01 3.361327E+01 6.184581E+02 - 8.899998E+00 6.000000E+01 5 9.210502E+01 8.965668E+01 5.518961E-01 9.210336E+01 - 8.899998E+00 6.000000E+01 6 1.239524E+03 -1.216205E+00 1.239245E+03 -2.630914E+01 - 8.899998E+00 9.000000E+01 1 9.690153E-06 -8.702674E+01 5.026269E-07 -9.677109E-06 - 8.899998E+00 9.000000E+01 2 1.813369E+02 8.685020E+01 9.963889E+00 1.810629E+02 - 8.899998E+00 9.000000E+01 3 4.331962E+01 2.635539E+00 4.327380E+01 1.991950E+00 - 8.899998E+00 9.000000E+01 4 8.262416E+02 8.692502E+01 4.432195E+01 8.250520E+02 - 8.899998E+00 9.000000E+01 5 3.141985E-04 -8.933611E+01 3.640586E-06 -3.141774E-04 - 8.899998E+00 9.000000E+01 6 1.180415E-04 1.792756E+02 -1.180320E-04 1.492417E-06 - 8.999998E+00 0.000000E+00 1 1.160606E+02 8.885361E+01 2.322023E+00 1.160374E+02 - 8.999998E+00 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 8.999998E+00 0.000000E+00 3 2.587355E+01 1.387605E+00 2.586596E+01 6.265516E-01 - 8.999998E+00 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 8.999998E+00 0.000000E+00 5 1.113087E+02 8.867339E+01 2.576969E+00 1.112789E+02 - 8.999998E+00 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 8.999998E+00 3.000000E+01 1 1.095290E+02 8.910822E+01 1.704707E+00 1.095157E+02 - 8.999998E+00 3.000000E+01 2 6.451524E+01 8.711766E+01 3.244162E+00 6.443362E+01 - 8.999998E+00 3.000000E+01 3 2.979382E+01 1.658782E+00 2.978134E+01 8.624467E-01 - 8.999998E+00 3.000000E+01 4 2.625165E+02 8.687570E+01 1.430773E+01 2.621263E+02 - 8.999998E+00 3.000000E+01 5 1.272618E+02 8.914267E+01 1.904178E+00 1.272476E+02 - 8.999998E+00 3.000000E+01 6 9.659369E+02 -1.212944E+00 9.657205E+02 -2.044723E+01 - 8.999998E+00 6.000000E+01 1 7.583825E+01 8.951503E+01 6.419079E-01 7.583553E+01 - 8.999998E+00 6.000000E+01 2 1.393056E+02 8.700136E+01 7.287399E+00 1.391148E+02 - 8.999998E+00 6.000000E+01 3 3.968670E+01 2.336427E+00 3.965370E+01 1.617909E+00 - 8.999998E+00 6.000000E+01 4 6.129016E+02 8.698767E+01 3.220852E+01 6.120547E+02 - 8.999998E+00 6.000000E+01 5 1.056942E+02 8.959994E+01 7.379875E-01 1.056916E+02 - 8.999998E+00 6.000000E+01 6 1.197618E+03 -1.114954E+00 1.197392E+03 -2.330372E+01 - 8.999998E+00 9.000000E+01 1 9.524249E-06 -8.716258E+01 4.714704E-07 -9.512573E-06 - 8.999998E+00 9.000000E+01 2 1.794218E+02 8.695363E+01 9.535217E+00 1.791683E+02 - 8.999998E+00 9.000000E+01 3 4.573512E+01 2.695062E+00 4.568454E+01 2.150482E+00 - 8.999998E+00 9.000000E+01 4 8.129009E+02 8.702586E+01 4.217762E+01 8.118060E+02 - 8.999998E+00 9.000000E+01 5 3.121020E-04 -8.935016E+01 3.539742E-06 -3.120819E-04 - 8.999998E+00 9.000000E+01 6 1.135800E-04 1.793336E+02 -1.135724E-04 1.321103E-06 - 9.099998E+00 0.000000E+00 1 1.165594E+02 8.889934E+01 2.238990E+00 1.165379E+02 - 9.099998E+00 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 9.099998E+00 0.000000E+00 3 2.822002E+01 1.503054E+00 2.821031E+01 7.402175E-01 - 9.099998E+00 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 9.099998E+00 0.000000E+00 5 1.372598E+02 8.876658E+01 2.954594E+00 1.372280E+02 - 9.099998E+00 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 9.099998E+00 3.000000E+01 1 1.096270E+02 8.912101E+01 1.681753E+00 1.096141E+02 - 9.099998E+00 3.000000E+01 2 6.480476E+01 8.720060E+01 3.165014E+00 6.472742E+01 - 9.099998E+00 3.000000E+01 3 3.220694E+01 1.765186E+00 3.219166E+01 9.920846E-01 - 9.099998E+00 3.000000E+01 4 2.629136E+02 8.697227E+01 1.388687E+01 2.625466E+02 - 9.099998E+00 3.000000E+01 5 1.495354E+02 8.914532E+01 2.230549E+00 1.495188E+02 - 9.099998E+00 3.000000E+01 6 9.425421E+02 -1.107938E+00 9.423659E+02 -1.822496E+01 - 9.099998E+00 6.000000E+01 1 7.531596E+01 8.947748E+01 6.868495E-01 7.531282E+01 - 9.099998E+00 6.000000E+01 2 1.385013E+02 8.709830E+01 7.011276E+00 1.383237E+02 - 9.099998E+00 6.000000E+01 3 4.212157E+01 2.404099E+00 4.208450E+01 1.766879E+00 - 9.099998E+00 6.000000E+01 4 6.062382E+02 8.708585E+01 3.082088E+01 6.054542E+02 - 9.099998E+00 6.000000E+01 5 1.187472E+02 8.955143E+01 9.296626E-01 1.187436E+02 - 9.099998E+00 6.000000E+01 6 1.157509E+03 -1.022758E+00 1.157325E+03 -2.066101E+01 - 9.099998E+00 9.000000E+01 1 9.364927E-06 -8.729887E+01 4.413322E-07 -9.354522E-06 - 9.099998E+00 9.000000E+01 2 1.774974E+02 8.705589E+01 9.116605E+00 1.772631E+02 - 9.099998E+00 9.000000E+01 3 4.811776E+01 2.741782E+00 4.806268E+01 2.301706E+00 - 9.099998E+00 9.000000E+01 4 7.997100E+02 8.712547E+01 4.010474E+01 7.987038E+02 - 9.099998E+00 9.000000E+01 5 3.099794E-04 -8.936478E+01 3.436606E-06 -3.099604E-04 - 9.099998E+00 9.000000E+01 6 1.093497E-04 1.793866E+02 -1.093434E-04 1.170687E-06 - 9.199999E+00 0.000000E+00 1 1.169471E+02 8.893913E+01 2.165245E+00 1.169271E+02 - 9.199999E+00 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 9.199999E+00 0.000000E+00 3 3.056842E+01 1.605399E+00 3.055642E+01 8.563998E-01 - 9.199999E+00 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 9.199999E+00 0.000000E+00 5 1.623999E+02 8.883729E+01 3.295392E+00 1.623665E+02 - 9.199999E+00 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 9.199999E+00 3.000000E+01 1 1.096390E+02 8.913246E+01 1.660030E+00 1.096264E+02 - 9.199999E+00 3.000000E+01 2 6.502007E+01 8.728464E+01 3.080281E+00 6.494707E+01 - 9.199999E+00 3.000000E+01 3 3.460962E+01 1.857570E+00 3.459143E+01 1.121872E+00 - 9.199999E+00 3.000000E+01 4 2.629997E+02 8.706934E+01 1.344649E+01 2.626557E+02 - 9.199999E+00 3.000000E+01 5 1.710542E+02 8.915020E+01 2.536954E+00 1.710354E+02 - 9.199999E+00 3.000000E+01 6 9.194749E+02 -1.013012E+00 9.193312E+02 -1.625583E+01 - 9.199999E+00 6.000000E+01 1 7.477536E+01 8.944529E+01 7.239272E-01 7.477186E+01 - 9.199999E+00 6.000000E+01 2 1.376372E+02 8.719436E+01 6.737082E+00 1.374722E+02 - 9.199999E+00 6.000000E+01 3 4.452791E+01 2.459471E+00 4.448689E+01 1.910812E+00 - 9.199999E+00 6.000000E+01 4 5.994178E+02 8.718303E+01 2.945880E+01 5.986935E+02 - 9.199999E+00 6.000000E+01 5 1.312729E+02 8.951003E+01 1.122579E+00 1.312681E+02 - 9.199999E+00 6.000000E+01 6 1.119135E+03 -9.388041E-01 1.118985E+03 -1.833646E+01 - 9.199999E+00 9.000000E+01 1 9.211790E-06 -8.743430E+01 4.123651E-07 -9.202556E-06 - 9.199999E+00 9.000000E+01 2 1.755691E+02 8.715659E+01 8.709388E+00 1.753530E+02 - 9.199999E+00 9.000000E+01 3 5.046645E+01 2.777081E+00 5.040718E+01 2.445111E+00 - 9.199999E+00 9.000000E+01 4 7.866900E+02 8.722346E+01 3.810787E+01 7.857665E+02 - 9.199999E+00 9.000000E+01 5 3.078333E-04 -8.937985E+01 3.331829E-06 -3.078153E-04 - 9.199999E+00 9.000000E+01 6 1.053368E-04 1.794351E+02 -1.053317E-04 1.038555E-06 - 9.299999E+00 0.000000E+00 1 1.172321E+02 8.897412E+01 2.098919E+00 1.172133E+02 - 9.299999E+00 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 9.299999E+00 0.000000E+00 3 3.291422E+01 1.695353E+00 3.289981E+01 9.737731E-01 - 9.299999E+00 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 9.299999E+00 0.000000E+00 5 1.867091E+02 8.889349E+01 3.605545E+00 1.866742E+02 - 9.299999E+00 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 9.299999E+00 3.000000E+01 1 1.095727E+02 8.914307E+01 1.638749E+00 1.095604E+02 - 9.299999E+00 3.000000E+01 2 6.516769E+01 8.736900E+01 2.991433E+00 6.509899E+01 - 9.299999E+00 3.000000E+01 3 3.699881E+01 1.936981E+00 3.697767E+01 1.250569E+00 - 9.299999E+00 3.000000E+01 4 2.628047E+02 8.716611E+01 1.299326E+01 2.624833E+02 - 9.299999E+00 3.000000E+01 5 1.918302E+02 8.915633E+01 2.824592E+00 1.918094E+02 - 9.299999E+00 3.000000E+01 6 8.967960E+02 -9.271351E-01 8.966786E+02 -1.451092E+01 - 9.299999E+00 6.000000E+01 1 7.421921E+01 8.941801E+01 7.538694E-01 7.421538E+01 - 9.299999E+00 6.000000E+01 2 1.367218E+02 8.728908E+01 6.466522E+00 1.365688E+02 - 9.299999E+00 6.000000E+01 3 4.690530E+01 2.503586E+00 4.686052E+01 2.048913E+00 - 9.299999E+00 6.000000E+01 4 5.924759E+02 8.727876E+01 2.812886E+01 5.918078E+02 - 9.299999E+00 6.000000E+01 5 1.432829E+02 8.947479E+01 1.313416E+00 1.432769E+02 - 9.299999E+00 6.000000E+01 6 1.082423E+03 -8.623536E-01 1.082300E+03 -1.629083E+01 - 9.299999E+00 9.000000E+01 1 9.064471E-06 -8.756777E+01 3.846747E-07 -9.056304E-06 - 9.299999E+00 9.000000E+01 2 1.736416E+02 8.725536E+01 8.314786E+00 1.734424E+02 - 9.299999E+00 9.000000E+01 3 5.278285E+01 2.802060E+00 5.271974E+01 2.580326E+00 - 9.299999E+00 9.000000E+01 4 7.738512E+02 8.731953E+01 3.618996E+01 7.730045E+02 - 9.299999E+00 9.000000E+01 5 3.056753E-04 -8.939530E+01 3.226063E-06 -3.056583E-04 - 9.299999E+00 9.000000E+01 6 1.015288E-04 1.794794E+02 -1.015247E-04 9.224037E-07 - 9.400000E+00 0.000000E+00 1 1.174227E+02 8.900529E+01 2.038470E+00 1.174050E+02 - 9.400000E+00 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 9.400000E+00 0.000000E+00 3 3.525301E+01 1.773938E+00 3.523611E+01 1.091296E+00 - 9.400000E+00 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 9.400000E+00 0.000000E+00 5 2.101871E+02 8.893999E+01 3.888407E+00 2.101512E+02 - 9.400000E+00 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 9.400000E+00 3.000000E+01 1 1.094354E+02 8.915318E+01 1.617389E+00 1.094234E+02 - 9.400000E+00 3.000000E+01 2 6.525328E+01 8.745300E+01 2.899776E+00 6.518882E+01 - 9.400000E+00 3.000000E+01 3 3.937164E+01 2.004708E+00 3.934754E+01 1.377283E+00 - 9.400000E+00 3.000000E+01 4 2.623578E+02 8.726190E+01 1.253300E+01 2.620582E+02 - 9.400000E+00 3.000000E+01 5 2.118597E+02 8.916341E+01 3.093292E+00 2.118371E+02 - 9.400000E+00 3.000000E+01 6 8.745499E+02 -8.493958E-01 8.744538E+02 -1.296451E+01 - 9.400000E+00 6.000000E+01 1 7.364943E+01 8.939521E+01 7.774000E-01 7.364532E+01 - 9.400000E+00 6.000000E+01 2 1.357621E+02 8.738207E+01 6.201006E+00 1.356204E+02 - 9.400000E+00 6.000000E+01 3 4.925246E+01 2.537764E+00 4.920415E+01 2.180793E+00 - 9.400000E+00 6.000000E+01 4 5.854478E+02 8.737270E+01 2.683640E+01 5.848324E+02 - 9.400000E+00 6.000000E+01 5 1.547827E+02 8.944517E+01 1.498852E+00 1.547754E+02 - 9.400000E+00 6.000000E+01 6 1.047306E+03 -7.927245E-01 1.047206E+03 -1.448970E+01 - 9.400000E+00 9.000000E+01 1 8.922653E-06 -8.769844E+01 3.583247E-07 -8.915456E-06 - 9.400000E+00 9.000000E+01 2 1.717189E+02 8.735191E+01 7.933661E+00 1.715355E+02 - 9.400000E+00 9.000000E+01 3 5.506533E+01 2.818021E+00 5.499874E+01 2.707227E+00 - 9.400000E+00 9.000000E+01 4 7.612180E+02 8.741341E+01 3.435312E+01 7.604424E+02 - 9.400000E+00 9.000000E+01 5 3.035088E-04 -8.941103E+01 3.119849E-06 -3.034928E-04 - 9.400000E+00 9.000000E+01 6 9.791365E-05 1.795200E+02 -9.791021E-05 8.202282E-07 - 9.500000E+00 0.000000E+00 1 1.175263E+02 8.903337E+01 1.982663E+00 1.175095E+02 - 9.500000E+00 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 9.500000E+00 0.000000E+00 3 3.758219E+01 1.841845E+00 3.756277E+01 1.207919E+00 - 9.500000E+00 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 9.500000E+00 0.000000E+00 5 2.328416E+02 8.897963E+01 4.146432E+00 2.328046E+02 - 9.500000E+00 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 9.500000E+00 3.000000E+01 1 1.092334E+02 8.916306E+01 1.595552E+00 1.092217E+02 - 9.500000E+00 3.000000E+01 2 6.528275E+01 8.753620E+01 2.806384E+00 6.522240E+01 - 9.500000E+00 3.000000E+01 3 4.172578E+01 2.061700E+00 4.169877E+01 1.501114E+00 - 9.500000E+00 3.000000E+01 4 2.616840E+02 8.735624E+01 1.207042E+01 2.614055E+02 - 9.500000E+00 3.000000E+01 5 2.311435E+02 8.917111E+01 3.343805E+00 2.311194E+02 - 9.500000E+00 3.000000E+01 6 8.527784E+02 -7.789711E-01 8.526996E+02 -1.159369E+01 - 9.500000E+00 6.000000E+01 1 7.306854E+01 8.937646E+01 7.951841E-01 7.306422E+01 - 9.500000E+00 6.000000E+01 2 1.347647E+02 8.747308E+01 5.941638E+00 1.346337E+02 - 9.500000E+00 6.000000E+01 3 5.156913E+01 2.562895E+00 5.151755E+01 2.305967E+00 - 9.500000E+00 6.000000E+01 4 5.783568E+02 8.746452E+01 2.558543E+01 5.777906E+02 - 9.500000E+00 6.000000E+01 5 1.657898E+02 8.942056E+01 1.676633E+00 1.657813E+02 - 9.500000E+00 6.000000E+01 6 1.013714E+03 -7.292941E-01 1.013632E+03 -1.290279E+01 - 9.500000E+00 9.000000E+01 1 8.785993E-06 -8.782562E+01 3.333497E-07 -8.779667E-06 - 9.500000E+00 9.000000E+01 2 1.698040E+02 8.744601E+01 7.566580E+00 1.696353E+02 - 9.500000E+00 9.000000E+01 3 5.731452E+01 2.825916E+00 5.724482E+01 2.825694E+00 - 9.500000E+00 9.000000E+01 4 7.487892E+02 8.750488E+01 3.259814E+01 7.480793E+02 - 9.500000E+00 9.000000E+01 5 3.013330E-04 -8.942694E+01 3.013811E-06 -3.013179E-04 - 9.500000E+00 9.000000E+01 6 9.447982E-05 1.795571E+02 -9.447700E-05 7.302739E-07 - 9.600000E+00 0.000000E+00 1 1.175499E+02 8.905898E+01 1.930542E+00 1.175340E+02 - 9.600000E+00 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 9.600000E+00 0.000000E+00 3 3.989761E+01 1.899998E+00 3.987568E+01 1.322811E+00 - 9.600000E+00 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 9.600000E+00 0.000000E+00 5 2.546638E+02 8.901414E+01 4.381640E+00 2.546261E+02 - 9.600000E+00 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 9.600000E+00 3.000000E+01 1 1.089727E+02 8.917290E+01 1.573015E+00 1.089613E+02 - 9.600000E+00 3.000000E+01 2 6.526106E+01 8.761814E+01 2.712210E+00 6.520468E+01 - 9.600000E+00 3.000000E+01 3 4.405827E+01 2.109046E+00 4.402843E+01 1.621410E+00 - 9.600000E+00 3.000000E+01 4 2.608084E+02 8.744871E+01 1.160957E+01 2.605499E+02 - 9.600000E+00 3.000000E+01 5 2.496811E+02 8.917929E+01 3.576336E+00 2.496555E+02 - 9.600000E+00 3.000000E+01 6 8.315068E+02 -7.151269E-01 8.314421E+02 -1.037803E+01 - 9.600000E+00 6.000000E+01 1 7.247884E+01 8.936135E+01 8.078730E-01 7.247433E+01 - 9.600000E+00 6.000000E+01 2 1.337359E+02 8.756182E+01 5.689329E+00 1.336148E+02 - 9.600000E+00 6.000000E+01 3 5.385368E+01 2.580039E+00 5.379909E+01 2.424221E+00 - 9.600000E+00 6.000000E+01 4 5.712331E+02 8.755403E+01 2.437869E+01 5.707126E+02 - 9.600000E+00 6.000000E+01 5 1.763068E+02 8.940032E+01 1.845266E+00 1.762971E+02 - 9.600000E+00 6.000000E+01 6 9.815810E+02 -6.714934E-01 9.815136E+02 -1.150364E+01 - 9.600000E+00 9.000000E+01 1 8.654189E-06 -8.794876E+01 3.097618E-07 -8.648643E-06 - 9.600000E+00 9.000000E+01 2 1.679009E+02 8.753750E+01 7.213941E+00 1.677458E+02 - 9.600000E+00 9.000000E+01 3 5.952987E+01 2.826792E+00 5.945744E+01 2.935823E+00 - 9.600000E+00 9.000000E+01 4 7.365856E+02 8.759377E+01 3.092498E+01 7.359361E+02 - 9.600000E+00 9.000000E+01 5 2.991584E-04 -8.944297E+01 2.908380E-06 -2.991442E-04 - 9.600000E+00 9.000000E+01 6 9.121706E-05 1.795911E+02 -9.121474E-05 6.510139E-07 - 9.700001E+00 0.000000E+00 1 1.175001E+02 8.908259E+01 1.881315E+00 1.174850E+02 - 9.700001E+00 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 9.700001E+00 0.000000E+00 3 4.219749E+01 1.949078E+00 4.217308E+01 1.435190E+00 - 9.700001E+00 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 9.700001E+00 0.000000E+00 5 2.756729E+02 8.904470E+01 4.596128E+00 2.756346E+02 - 9.700001E+00 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 9.700001E+00 3.000000E+01 1 1.086600E+02 8.918287E+01 1.549620E+00 1.086490E+02 - 9.700001E+00 3.000000E+01 2 6.519335E+01 8.769851E+01 2.618025E+00 6.514076E+01 - 9.700001E+00 3.000000E+01 3 4.636815E+01 2.147478E+00 4.633559E+01 1.737497E+00 - 9.700001E+00 3.000000E+01 4 2.597520E+02 8.753899E+01 1.115364E+01 2.595125E+02 - 9.700001E+00 3.000000E+01 5 2.675006E+02 8.918803E+01 3.790771E+00 2.674738E+02 - 9.700001E+00 3.000000E+01 6 8.107560E+02 -6.572052E-01 8.107027E+02 -9.299488E+00 - 9.700001E+00 6.000000E+01 1 7.188165E+01 8.934953E+01 8.160516E-01 7.187702E+01 - 9.700001E+00 6.000000E+01 2 1.326802E+02 8.764812E+01 5.444745E+00 1.325684E+02 - 9.700001E+00 6.000000E+01 3 5.610655E+01 2.589999E+00 5.604924E+01 2.535378E+00 - 9.700001E+00 6.000000E+01 4 5.640962E+02 8.764104E+01 2.321823E+01 5.636182E+02 - 9.700001E+00 6.000000E+01 5 1.863526E+02 8.938400E+01 2.003495E+00 1.863418E+02 - 9.700001E+00 6.000000E+01 6 9.508435E+02 -6.188014E-01 9.507880E+02 -1.026903E+01 - 9.700001E+00 9.000000E+01 1 8.526941E-06 -8.806748E+01 2.875491E-07 -8.522092E-06 - 9.700001E+00 9.000000E+01 2 1.660127E+02 8.762624E+01 6.875925E+00 1.658703E+02 - 9.700001E+00 9.000000E+01 3 6.171202E+01 2.821412E+00 6.163721E+01 3.037653E+00 - 9.700001E+00 9.000000E+01 4 7.246121E+02 8.767999E+01 2.933279E+01 7.240182E+02 - 9.700001E+00 9.000000E+01 5 2.969830E-04 -8.945903E+01 2.803997E-06 -2.969697E-04 - 9.700001E+00 9.000000E+01 6 8.811515E-05 1.796221E+02 -8.811324E-05 5.811088E-07 - 9.800001E+00 0.000000E+00 1 1.173830E+02 8.910458E+01 1.834391E+00 1.173687E+02 - 9.800001E+00 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 9.800001E+00 0.000000E+00 3 4.447944E+01 1.989984E+00 4.445261E+01 1.544539E+00 - 9.800001E+00 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 9.800001E+00 0.000000E+00 5 2.958734E+02 8.907237E+01 4.790026E+00 2.958347E+02 - 9.800001E+00 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 9.800001E+00 3.000000E+01 1 1.082990E+02 8.919299E+01 1.525331E+00 1.082883E+02 - 9.800001E+00 3.000000E+01 2 6.508414E+01 8.777704E+01 2.524505E+00 6.503516E+01 - 9.800001E+00 3.000000E+01 3 4.865367E+01 2.177999E+00 4.861852E+01 1.849039E+00 - 9.800001E+00 3.000000E+01 4 2.585378E+02 8.762685E+01 1.070539E+01 2.583160E+02 - 9.800001E+00 3.000000E+01 5 2.846022E+02 8.919722E+01 3.987484E+00 2.845743E+02 - 9.800001E+00 3.000000E+01 6 7.905407E+02 -6.046118E-01 7.904967E+02 -8.342000E+00 - 9.800001E+00 6.000000E+01 1 7.127917E+01 8.934064E+01 8.202709E-01 7.127444E+01 - 9.800001E+00 6.000000E+01 2 1.316037E+02 8.773186E+01 5.208350E+00 1.315005E+02 - 9.800001E+00 6.000000E+01 3 5.832739E+01 2.593717E+00 5.826764E+01 2.639515E+00 - 9.800001E+00 6.000000E+01 4 5.569635E+02 8.772540E+01 2.210526E+01 5.565247E+02 - 9.800001E+00 6.000000E+01 5 1.959448E+02 8.937125E+01 2.150185E+00 1.959330E+02 - 9.800001E+00 6.000000E+01 6 9.214333E+02 -5.707465E-01 9.213876E+02 -9.178619E+00 - 9.800001E+00 9.000000E+01 1 8.404029E-06 -8.818153E+01 2.666843E-07 -8.399797E-06 - 9.800001E+00 9.000000E+01 2 1.641413E+02 8.771213E+01 6.552562E+00 1.640104E+02 - 9.800001E+00 9.000000E+01 3 6.386058E+01 2.810702E+00 6.378376E+01 3.131488E+00 - 9.800001E+00 9.000000E+01 4 7.128737E+02 8.776344E+01 2.782015E+01 7.123307E+02 - 9.800001E+00 9.000000E+01 5 2.948142E-04 -8.947506E+01 2.701058E-06 -2.948018E-04 - 9.800001E+00 9.000000E+01 6 8.516476E-05 1.796506E+02 -8.516318E-05 5.193963E-07 - 9.900002E+00 0.000000E+00 1 1.172050E+02 8.912526E+01 1.789311E+00 1.171914E+02 - 9.900002E+00 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 9.900002E+00 0.000000E+00 3 4.674041E+01 2.023381E+00 4.671127E+01 1.650278E+00 - 9.900002E+00 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 9.900002E+00 0.000000E+00 5 3.152844E+02 8.909766E+01 4.965184E+00 3.152453E+02 - 9.900002E+00 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 9.900002E+00 3.000000E+01 1 1.078954E+02 8.920335E+01 1.500136E+00 1.078849E+02 - 9.900002E+00 3.000000E+01 2 6.493745E+01 8.785353E+01 2.432174E+00 6.489188E+01 - 9.900002E+00 3.000000E+01 3 5.091317E+01 2.201357E+00 5.087559E+01 1.955649E+00 - 9.900002E+00 3.000000E+01 4 2.571832E+02 8.771211E+01 1.026689E+01 2.569782E+02 - 9.900002E+00 3.000000E+01 5 3.009960E+02 8.920689E+01 4.166389E+00 3.009671E+02 - 9.900002E+00 3.000000E+01 6 7.708690E+02 -5.568187E-01 7.708326E+02 -7.491434E+00 - 9.900002E+00 6.000000E+01 1 7.067269E+01 8.933435E+01 8.210385E-01 7.066792E+01 - 9.900002E+00 6.000000E+01 2 1.305102E+02 8.781295E+01 4.980528E+00 1.304152E+02 - 9.900002E+00 6.000000E+01 3 6.051537E+01 2.591830E+00 6.045346E+01 2.736538E+00 - 9.900002E+00 6.000000E+01 4 5.498582E+02 8.780705E+01 2.104022E+01 5.494555E+02 - 9.900002E+00 6.000000E+01 5 2.050883E+02 8.936155E+01 2.285264E+00 2.050755E+02 - 9.900002E+00 6.000000E+01 6 8.932906E+02 -5.268963E-01 8.932528E+02 -8.214651E+00 - 9.900002E+00 9.000000E+01 1 8.285133E-06 -8.829071E+01 2.471319E-07 -8.281447E-06 - 9.900002E+00 9.000000E+01 2 1.622894E+02 8.779511E+01 6.243764E+00 1.621692E+02 - 9.900002E+00 9.000000E+01 3 6.597607E+01 2.795250E+00 6.589757E+01 3.217452E+00 - 9.900002E+00 9.000000E+01 4 7.013761E+02 8.784407E+01 2.638522E+01 7.008796E+02 - 9.900002E+00 9.000000E+01 5 2.926507E-04 -8.949097E+01 2.599930E-06 -2.926391E-04 - 9.900002E+00 9.000000E+01 6 8.235678E-05 1.796766E+02 -8.235547E-05 4.648591E-07 - 1.000000E+01 0.000000E+00 1 1.169712E+02 8.914487E+01 1.745720E+00 1.169581E+02 - 1.000000E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.000000E+01 0.000000E+00 3 4.897959E+01 2.049965E+00 4.894825E+01 1.752050E+00 - 1.000000E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.000000E+01 0.000000E+00 5 3.339042E+02 8.912106E+01 5.122027E+00 3.338649E+02 - 1.000000E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.000000E+01 3.000000E+01 1 1.074541E+02 8.921397E+01 1.474098E+00 1.074440E+02 - 1.000000E+01 3.000000E+01 2 6.475717E+01 8.792786E+01 2.341482E+00 6.471483E+01 - 1.000000E+01 3.000000E+01 3 5.314511E+01 2.218310E+00 5.310529E+01 2.057096E+00 - 1.000000E+01 3.000000E+01 4 2.557055E+02 8.779467E+01 9.839749E+00 2.555161E+02 - 1.000000E+01 3.000000E+01 5 3.167002E+02 8.921693E+01 4.328268E+00 3.166707E+02 - 1.000000E+01 3.000000E+01 6 7.517448E+02 -5.133530E-01 7.517147E+02 -6.735319E+00 - 1.000000E+01 6.000000E+01 1 7.006360E+01 8.933038E+01 8.188215E-01 7.005882E+01 - 1.000000E+01 6.000000E+01 2 1.294039E+02 8.789131E+01 4.761447E+00 1.293162E+02 - 1.000000E+01 6.000000E+01 3 6.267030E+01 2.585020E+00 6.260653E+01 2.826543E+00 - 1.000000E+01 6.000000E+01 4 5.427922E+02 8.788593E+01 2.002315E+01 5.424228E+02 - 1.000000E+01 6.000000E+01 5 2.138007E+02 8.935457E+01 2.408391E+00 2.137871E+02 - 1.000000E+01 6.000000E+01 6 8.663563E+02 -4.868632E-01 8.663251E+02 -7.361658E+00 - 1.000000E+01 9.000000E+01 1 8.170079E-06 -8.839492E+01 2.288456E-07 -8.166873E-06 - 1.000000E+01 9.000000E+01 2 1.604586E+02 8.787517E+01 5.949301E+00 1.603483E+02 - 1.000000E+01 9.000000E+01 3 6.805760E+01 2.775809E+00 6.797775E+01 3.295897E+00 - 1.000000E+01 9.000000E+01 4 6.901216E+02 8.792185E+01 2.502566E+01 6.896677E+02 - 1.000000E+01 9.000000E+01 5 2.904943E-04 -8.950674E+01 2.500847E-06 -2.904835E-04 - 1.000000E+01 9.000000E+01 6 7.968334E-05 1.797004E+02 -7.968225E-05 4.166122E-07 - 1.010000E+01 0.000000E+00 1 1.166864E+02 8.916358E+01 1.703356E+00 1.166740E+02 - 1.010000E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.010000E+01 0.000000E+00 3 5.119496E+01 2.070443E+00 5.116154E+01 1.849581E+00 - 1.010000E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.010000E+01 0.000000E+00 5 3.517633E+02 8.914294E+01 5.261702E+00 3.517239E+02 - 1.010000E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.010000E+01 3.000000E+01 1 1.069780E+02 8.922484E+01 1.447280E+00 1.069682E+02 - 1.010000E+01 3.000000E+01 2 6.454665E+01 8.799989E+01 2.252775E+00 6.450732E+01 - 1.010000E+01 3.000000E+01 3 5.534990E+01 2.229496E+00 5.530801E+01 2.153234E+00 - 1.010000E+01 3.000000E+01 4 2.541205E+02 8.787442E+01 9.425289E+00 2.539457E+02 - 1.010000E+01 3.000000E+01 5 3.317360E+02 8.922735E+01 4.473430E+00 3.317058E+02 - 1.010000E+01 3.000000E+01 6 7.331686E+02 -4.737875E-01 7.331436E+02 -6.062614E+00 - 1.010000E+01 6.000000E+01 1 6.945335E+01 8.932846E+01 8.140199E-01 6.944859E+01 - 1.010000E+01 6.000000E+01 2 1.282881E+02 8.796692E+01 4.551222E+00 1.282073E+02 - 1.010000E+01 6.000000E+01 3 6.479252E+01 2.573969E+00 6.472715E+01 2.909775E+00 - 1.010000E+01 6.000000E+01 4 5.357795E+02 8.796202E+01 1.905341E+01 5.354407E+02 - 1.010000E+01 6.000000E+01 5 2.220971E+02 8.935001E+01 2.519507E+00 2.220828E+02 - 1.010000E+01 6.000000E+01 6 8.405726E+02 -4.502915E-01 8.405467E+02 -6.606051E+00 - 1.010000E+01 9.000000E+01 1 8.058648E-06 -8.849416E+01 2.117711E-07 -8.055865E-06 - 1.010000E+01 9.000000E+01 2 1.586507E+02 8.795229E+01 5.668875E+00 1.585494E+02 - 1.010000E+01 9.000000E+01 3 7.010595E+01 2.752871E+00 7.002505E+01 3.367061E+00 - 1.010000E+01 9.000000E+01 4 6.791106E+02 8.799677E+01 2.373888E+01 6.786956E+02 - 1.010000E+01 9.000000E+01 5 2.883523E-04 -8.952231E+01 2.404073E-06 -2.883423E-04 - 1.010000E+01 9.000000E+01 6 7.713650E-05 1.797223E+02 -7.713559E-05 3.738827E-07 - 1.020000E+01 0.000000E+00 1 1.163559E+02 8.918156E+01 1.662029E+00 1.163440E+02 - 1.020000E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.020000E+01 0.000000E+00 3 5.338578E+01 2.085252E+00 5.335043E+01 1.942520E+00 - 1.020000E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.020000E+01 0.000000E+00 5 3.688779E+02 8.916357E+01 5.384873E+00 3.688386E+02 - 1.020000E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.020000E+01 3.000000E+01 1 1.064719E+02 8.923595E+01 1.419788E+00 1.064624E+02 - 1.020000E+01 3.000000E+01 2 6.430946E+01 8.806957E+01 2.166323E+00 6.427296E+01 - 1.020000E+01 3.000000E+01 3 5.752578E+01 2.235494E+00 5.748199E+01 2.243899E+00 - 1.020000E+01 3.000000E+01 4 2.524415E+02 8.795133E+01 9.024391E+00 2.522802E+02 - 1.020000E+01 3.000000E+01 5 3.461152E+02 8.923814E+01 4.602109E+00 3.460846E+02 - 1.020000E+01 3.000000E+01 6 7.151368E+02 -4.377417E-01 7.151159E+02 -5.463615E+00 - 1.020000E+01 6.000000E+01 1 6.884287E+01 8.932832E+01 8.070253E-01 6.883814E+01 - 1.020000E+01 6.000000E+01 2 1.271661E+02 8.803976E+01 4.349825E+00 1.270917E+02 - 1.020000E+01 6.000000E+01 3 6.688241E+01 2.559122E+00 6.681570E+01 2.986316E+00 - 1.020000E+01 6.000000E+01 4 5.288314E+02 8.803529E+01 1.813049E+01 5.285204E+02 - 1.020000E+01 6.000000E+01 5 2.299881E+02 8.934759E+01 2.618761E+00 2.299732E+02 - 1.020000E+01 6.000000E+01 6 8.158806E+02 -4.168615E-01 8.158589E+02 -5.935972E+00 - 1.020000E+01 9.000000E+01 1 7.950614E-06 -8.858845E+01 1.958533E-07 -7.948202E-06 - 1.020000E+01 9.000000E+01 2 1.568666E+02 8.802647E+01 5.402133E+00 1.567735E+02 - 1.020000E+01 9.000000E+01 3 7.212234E+01 2.726942E+00 7.204066E+01 3.431303E+00 - 1.020000E+01 9.000000E+01 4 6.683471E+02 8.806887E+01 2.252207E+01 6.679675E+02 - 1.020000E+01 9.000000E+01 5 2.862214E-04 -8.953762E+01 2.309812E-06 -2.862121E-04 - 1.020000E+01 9.000000E+01 6 7.470902E-05 1.797423E+02 -7.470826E-05 3.359954E-07 - 1.030000E+01 0.000000E+00 1 1.159833E+02 8.919891E+01 1.621601E+00 1.159719E+02 - 1.030000E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.030000E+01 0.000000E+00 3 5.555044E+01 2.095102E+00 5.551330E+01 2.030828E+00 - 1.030000E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.030000E+01 0.000000E+00 5 3.852576E+02 8.918316E+01 5.492260E+00 3.852184E+02 - 1.030000E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.030000E+01 3.000000E+01 1 1.059390E+02 8.924728E+01 1.391723E+00 1.059299E+02 - 1.030000E+01 3.000000E+01 2 6.404846E+01 8.813687E+01 2.082344E+00 6.401460E+01 - 1.030000E+01 3.000000E+01 3 5.967226E+01 2.236973E+00 5.962678E+01 2.329164E+00 - 1.030000E+01 3.000000E+01 4 2.506837E+02 8.802541E+01 8.637652E+00 2.505348E+02 - 1.030000E+01 3.000000E+01 5 3.598548E+02 8.924917E+01 4.715608E+00 3.598239E+02 - 1.030000E+01 3.000000E+01 6 6.976420E+02 -4.048707E-01 6.976246E+02 -4.929726E+00 - 1.030000E+01 6.000000E+01 1 6.823340E+01 8.932977E+01 7.981609E-01 6.822873E+01 - 1.030000E+01 6.000000E+01 2 1.260409E+02 8.810987E+01 4.157207E+00 1.259723E+02 - 1.030000E+01 6.000000E+01 3 6.893880E+01 2.541027E+00 6.887101E+01 3.056384E+00 - 1.030000E+01 6.000000E+01 4 5.219585E+02 8.810577E+01 1.725308E+01 5.216733E+02 - 1.030000E+01 6.000000E+01 5 2.374935E+02 8.934695E+01 2.706846E+00 2.374780E+02 - 1.030000E+01 6.000000E+01 6 7.922292E+02 -3.862822E-01 7.922112E+02 -5.341087E+00 - 1.030000E+01 9.000000E+01 1 7.845823E-06 -8.867785E+01 1.810329E-07 -7.843734E-06 - 1.030000E+01 9.000000E+01 2 1.551079E+02 8.809779E+01 5.148639E+00 1.550224E+02 - 1.030000E+01 9.000000E+01 3 7.410574E+01 2.698485E+00 7.402357E+01 3.488901E+00 - 1.030000E+01 9.000000E+01 4 6.578296E+02 8.813818E+01 2.137241E+01 6.574823E+02 - 1.030000E+01 9.000000E+01 5 2.841064E-04 -8.955265E+01 2.218179E-06 -2.840977E-04 - 1.030000E+01 9.000000E+01 6 7.239411E-05 1.797607E+02 -7.239348E-05 3.023628E-07 - 1.040000E+01 0.000000E+00 1 1.155735E+02 8.921570E+01 1.581993E+00 1.155627E+02 - 1.040000E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.040000E+01 0.000000E+00 3 5.768827E+01 2.100430E+00 5.764951E+01 2.114344E+00 - 1.040000E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.040000E+01 0.000000E+00 5 4.009281E+02 8.920187E+01 5.584766E+00 4.008892E+02 - 1.040000E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.040000E+01 3.000000E+01 1 1.053823E+02 8.925881E+01 1.363213E+00 1.053735E+02 - 1.040000E+01 3.000000E+01 2 6.376615E+01 8.820177E+01 2.000984E+00 6.373475E+01 - 1.040000E+01 3.000000E+01 3 6.178837E+01 2.234376E+00 6.174139E+01 2.408964E+00 - 1.040000E+01 3.000000E+01 4 2.488582E+02 8.809665E+01 8.265490E+00 2.487209E+02 - 1.040000E+01 3.000000E+01 5 3.729734E+02 8.926048E+01 4.813849E+00 3.729423E+02 - 1.040000E+01 3.000000E+01 6 6.806799E+02 -3.748697E-01 6.806653E+02 -4.453459E+00 - 1.040000E+01 6.000000E+01 1 6.762556E+01 8.933258E+01 7.877367E-01 6.762097E+01 - 1.040000E+01 6.000000E+01 2 1.249154E+02 8.817728E+01 3.973207E+00 1.248521E+02 - 1.040000E+01 6.000000E+01 3 7.096295E+01 2.520146E+00 7.089432E+01 3.120288E+00 - 1.040000E+01 6.000000E+01 4 5.151669E+02 8.817352E+01 1.641975E+01 5.149052E+02 - 1.040000E+01 6.000000E+01 5 2.446202E+02 8.934795E+01 2.783833E+00 2.446044E+02 - 1.040000E+01 6.000000E+01 6 7.695685E+02 -3.582901E-01 7.695535E+02 -4.812344E+00 - 1.040000E+01 9.000000E+01 1 7.744115E-06 -8.876249E+01 1.672494E-07 -7.742309E-06 - 1.040000E+01 9.000000E+01 2 1.533754E+02 8.816624E+01 4.907936E+00 1.532968E+02 - 1.040000E+01 9.000000E+01 3 7.605679E+01 2.667913E+00 7.597435E+01 3.540219E+00 - 1.040000E+01 9.000000E+01 4 6.475590E+02 8.820473E+01 2.028681E+01 6.472411E+02 - 1.040000E+01 9.000000E+01 5 2.820044E-04 -8.956738E+01 2.129336E-06 -2.819964E-04 - 1.040000E+01 9.000000E+01 6 7.018534E-05 1.797776E+02 -7.018481E-05 2.724718E-07 - 1.050000E+01 0.000000E+00 1 1.151296E+02 8.923202E+01 1.543128E+00 1.151192E+02 - 1.050000E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.050000E+01 0.000000E+00 3 5.979835E+01 2.101754E+00 5.975812E+01 2.193062E+00 - 1.050000E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.050000E+01 0.000000E+00 5 4.159096E+02 8.921983E+01 5.663044E+00 4.158711E+02 - 1.050000E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.050000E+01 3.000000E+01 1 1.048050E+02 8.927050E+01 1.334369E+00 1.047966E+02 - 1.050000E+01 3.000000E+01 2 6.346526E+01 8.826427E+01 1.922339E+00 6.343614E+01 - 1.050000E+01 3.000000E+01 3 6.387455E+01 2.228186E+00 6.382626E+01 2.483403E+00 - 1.050000E+01 3.000000E+01 4 2.469748E+02 8.816509E+01 7.908054E+00 2.468482E+02 - 1.050000E+01 3.000000E+01 5 3.854914E+02 8.927195E+01 4.898271E+00 3.854603E+02 - 1.050000E+01 3.000000E+01 6 6.642385E+02 -3.474618E-01 6.642263E+02 -4.028152E+00 - 1.050000E+01 6.000000E+01 1 6.702032E+01 8.933657E+01 7.760142E-01 6.701583E+01 - 1.050000E+01 6.000000E+01 2 1.237905E+02 8.824201E+01 3.797640E+00 1.237323E+02 - 1.050000E+01 6.000000E+01 3 7.295372E+01 2.496862E+00 7.288446E+01 3.178205E+00 - 1.050000E+01 6.000000E+01 4 5.084659E+02 8.823856E+01 1.562921E+01 5.082257E+02 - 1.050000E+01 6.000000E+01 5 2.513903E+02 8.935038E+01 2.850223E+00 2.513742E+02 - 1.050000E+01 6.000000E+01 6 7.478476E+02 -3.326485E-01 7.478350E+02 -4.341838E+00 - 1.050000E+01 9.000000E+01 1 7.645333E-06 -8.884250E+01 1.544425E-07 -7.643774E-06 - 1.050000E+01 9.000000E+01 2 1.516699E+02 8.823196E+01 4.679524E+00 1.515977E+02 - 1.050000E+01 9.000000E+01 3 7.797541E+01 2.635607E+00 7.789293E+01 3.585605E+00 - 1.050000E+01 9.000000E+01 4 6.375266E+02 8.826861E+01 1.926221E+01 6.372355E+02 - 1.050000E+01 9.000000E+01 5 2.799223E-04 -8.958176E+01 2.043348E-06 -2.799149E-04 - 1.050000E+01 9.000000E+01 6 6.807659E-05 1.797931E+02 -6.807614E-05 2.458727E-07 - 1.060000E+01 0.000000E+00 1 1.146553E+02 8.924791E+01 1.504978E+00 1.146454E+02 - 1.060000E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.060000E+01 0.000000E+00 3 6.187998E+01 2.099505E+00 6.183844E+01 2.266978E+00 - 1.060000E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.060000E+01 0.000000E+00 5 4.302150E+02 8.923714E+01 5.727894E+00 4.301769E+02 - 1.060000E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.060000E+01 3.000000E+01 1 1.042095E+02 8.928232E+01 1.305299E+00 1.042013E+02 - 1.060000E+01 3.000000E+01 2 6.314794E+01 8.832440E+01 1.846480E+00 6.312094E+01 - 1.060000E+01 3.000000E+01 3 6.592982E+01 2.218868E+00 6.588039E+01 2.552597E+00 - 1.060000E+01 3.000000E+01 4 2.450438E+02 8.823080E+01 7.565379E+00 2.449270E+02 - 1.060000E+01 3.000000E+01 5 3.974218E+02 8.928361E+01 4.969038E+00 3.973907E+02 - 1.060000E+01 3.000000E+01 6 6.483076E+02 -3.223989E-01 6.482973E+02 -3.647957E+00 - 1.060000E+01 6.000000E+01 1 6.641848E+01 8.934158E+01 7.632339E-01 6.641409E+01 - 1.060000E+01 6.000000E+01 2 1.226696E+02 8.830415E+01 3.630279E+00 1.226159E+02 - 1.060000E+01 6.000000E+01 3 7.491222E+01 2.471537E+00 7.484253E+01 3.230445E+00 - 1.060000E+01 6.000000E+01 4 5.018592E+02 8.830099E+01 1.487966E+01 5.016385E+02 - 1.060000E+01 6.000000E+01 5 2.578091E+02 8.935396E+01 2.906878E+00 2.577927E+02 - 1.060000E+01 6.000000E+01 6 7.270218E+02 -3.091397E-01 7.270112E+02 -3.922631E+00 - 1.060000E+01 9.000000E+01 1 7.549281E-06 -8.891802E+01 1.425530E-07 -7.547935E-06 - 1.060000E+01 9.000000E+01 2 1.499921E+02 8.829495E+01 4.462903E+00 1.499257E+02 - 1.060000E+01 9.000000E+01 3 7.986166E+01 2.601855E+00 7.977934E+01 3.625347E+00 - 1.060000E+01 9.000000E+01 4 6.277375E+02 8.832988E+01 1.829544E+01 6.274709E+02 - 1.060000E+01 9.000000E+01 5 2.778549E-04 -8.959577E+01 1.960276E-06 -2.778480E-04 - 1.060000E+01 9.000000E+01 6 6.606242E-05 1.798073E+02 -6.606205E-05 2.221744E-07 - 1.070000E+01 0.000000E+00 1 1.141537E+02 8.926340E+01 1.467511E+00 1.141442E+02 - 1.070000E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.070000E+01 0.000000E+00 3 6.393304E+01 2.094086E+00 6.389034E+01 2.336149E+00 - 1.070000E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.070000E+01 0.000000E+00 5 4.438734E+02 8.925386E+01 5.780247E+00 4.438358E+02 - 1.070000E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.070000E+01 3.000000E+01 1 1.035983E+02 8.929422E+01 1.276119E+00 1.035905E+02 - 1.070000E+01 3.000000E+01 2 6.281622E+01 8.838221E+01 1.773431E+00 6.279118E+01 - 1.070000E+01 3.000000E+01 3 6.795429E+01 2.206761E+00 6.790389E+01 2.616629E+00 - 1.070000E+01 3.000000E+01 4 2.430734E+02 8.829381E+01 7.237322E+00 2.429656E+02 - 1.070000E+01 3.000000E+01 5 4.087933E+02 8.929536E+01 5.027290E+00 4.087624E+02 - 1.070000E+01 3.000000E+01 6 6.328757E+02 -2.994595E-01 6.328670E+02 -3.307744E+00 - 1.070000E+01 6.000000E+01 1 6.582057E+01 8.934747E+01 7.495978E-01 6.581631E+01 - 1.070000E+01 6.000000E+01 2 1.215535E+02 8.836374E+01 3.470883E+00 1.215040E+02 - 1.070000E+01 6.000000E+01 3 7.683866E+01 2.444463E+00 7.676874E+01 3.277245E+00 - 1.070000E+01 6.000000E+01 4 4.953550E+02 8.836084E+01 1.416955E+01 4.951523E+02 - 1.070000E+01 6.000000E+01 5 2.638965E+02 8.935859E+01 2.954202E+00 2.638800E+02 - 1.070000E+01 6.000000E+01 6 7.070473E+02 -2.875706E-01 7.070384E+02 -3.548694E+00 - 1.070000E+01 9.000000E+01 1 7.455899E-06 -8.898923E+01 1.315240E-07 -7.454739E-06 - 1.070000E+01 9.000000E+01 2 1.483416E+02 8.835533E+01 4.257556E+00 1.482805E+02 - 1.070000E+01 9.000000E+01 3 8.171694E+01 2.566934E+00 8.163495E+01 3.659813E+00 - 1.070000E+01 9.000000E+01 4 6.181830E+02 8.838859E+01 1.738377E+01 6.179386E+02 - 1.070000E+01 9.000000E+01 5 2.758073E-04 -8.960943E+01 1.880126E-06 -2.758008E-04 - 1.070000E+01 9.000000E+01 6 6.413752E-05 1.798204E+02 -6.413721E-05 2.010338E-07 - 1.080000E+01 0.000000E+00 1 1.136280E+02 8.927855E+01 1.430734E+00 1.136190E+02 - 1.080000E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.080000E+01 0.000000E+00 3 6.595620E+01 2.085848E+00 6.591250E+01 2.400599E+00 - 1.080000E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.080000E+01 0.000000E+00 5 4.568948E+02 8.927005E+01 5.820706E+00 4.568578E+02 - 1.080000E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.080000E+01 3.000000E+01 1 1.029741E+02 8.930618E+01 1.246922E+00 1.029666E+02 - 1.080000E+01 3.000000E+01 2 6.247221E+01 8.843774E+01 1.703198E+00 6.244899E+01 - 1.080000E+01 3.000000E+01 3 6.994787E+01 2.192204E+00 6.989668E+01 2.675635E+00 - 1.080000E+01 3.000000E+01 4 2.410707E+02 8.835420E+01 6.923707E+00 2.409713E+02 - 1.080000E+01 3.000000E+01 5 4.196074E+02 8.930720E+01 5.073658E+00 4.195768E+02 - 1.080000E+01 3.000000E+01 6 6.179302E+02 -2.784428E-01 6.179229E+02 -3.002970E+00 - 1.080000E+01 6.000000E+01 1 6.522710E+01 8.935410E+01 7.352954E-01 6.522296E+01 - 1.080000E+01 6.000000E+01 2 1.204439E+02 8.842086E+01 3.319156E+00 1.203982E+02 - 1.080000E+01 6.000000E+01 3 7.873296E+01 2.415946E+00 7.866298E+01 3.318888E+00 - 1.080000E+01 6.000000E+01 4 4.889547E+02 8.841821E+01 1.349714E+01 4.887684E+02 - 1.080000E+01 6.000000E+01 5 2.696635E+02 8.936408E+01 2.992888E+00 2.696469E+02 - 1.080000E+01 6.000000E+01 6 6.878823E+02 -2.677642E-01 6.878748E+02 -3.214714E+00 - 1.080000E+01 9.000000E+01 1 7.365016E-06 -8.905633E+01 1.212971E-07 -7.364017E-06 - 1.080000E+01 9.000000E+01 2 1.467195E+02 8.841316E+01 4.062960E+00 1.466632E+02 - 1.080000E+01 9.000000E+01 3 8.354046E+01 2.531108E+00 8.345895E+01 3.689297E+00 - 1.080000E+01 9.000000E+01 4 6.088626E+02 8.844485E+01 1.652410E+01 6.086384E+02 - 1.080000E+01 9.000000E+01 5 2.737784E-04 -8.962268E+01 1.802924E-06 -2.737724E-04 - 1.080000E+01 9.000000E+01 6 6.229666E-05 1.798325E+02 -6.229639E-05 1.821510E-07 - 1.090001E+01 0.000000E+00 1 1.130809E+02 8.929334E+01 1.394639E+00 1.130723E+02 - 1.090001E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.090001E+01 0.000000E+00 3 6.795072E+01 2.075143E+00 6.790616E+01 2.460506E+00 - 1.090001E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.090001E+01 0.000000E+00 5 4.693108E+02 8.928577E+01 5.850070E+00 4.692743E+02 - 1.090001E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.090001E+01 3.000000E+01 1 1.023384E+02 8.931818E+01 1.217809E+00 1.023312E+02 - 1.090001E+01 3.000000E+01 2 6.211732E+01 8.849104E+01 1.635760E+00 6.209578E+01 - 1.090001E+01 3.000000E+01 3 7.191013E+01 2.175603E+00 7.185829E+01 2.729875E+00 - 1.090001E+01 3.000000E+01 4 2.390453E+02 8.841207E+01 6.624189E+00 2.389535E+02 - 1.090001E+01 3.000000E+01 5 4.299111E+02 8.931908E+01 5.109051E+00 4.298808E+02 - 1.090001E+01 3.000000E+01 6 6.034572E+02 -2.591694E-01 6.034510E+02 -2.729645E+00 - 1.090001E+01 6.000000E+01 1 6.463866E+01 8.936135E+01 7.204774E-01 6.463465E+01 - 1.090001E+01 6.000000E+01 2 1.193423E+02 8.847560E+01 3.174819E+00 1.193001E+02 - 1.090001E+01 6.000000E+01 3 8.059480E+01 2.386306E+00 8.052491E+01 3.355714E+00 - 1.090001E+01 6.000000E+01 4 4.826599E+02 8.847315E+01 1.286060E+01 4.824885E+02 - 1.090001E+01 6.000000E+01 5 2.751201E+02 8.937035E+01 3.023324E+00 2.751035E+02 - 1.090001E+01 6.000000E+01 6 6.694854E+02 -2.495624E-01 6.694791E+02 -2.916059E+00 - 1.090001E+01 9.000000E+01 1 7.276533E-06 -8.911949E+01 1.118204E-07 -7.275674E-06 - 1.090001E+01 9.000000E+01 2 1.451256E+02 8.846854E+01 3.878605E+00 1.450737E+02 - 1.090001E+01 9.000000E+01 3 8.533361E+01 2.494587E+00 8.525275E+01 3.714146E+00 - 1.090001E+01 9.000000E+01 4 5.997737E+02 8.849873E+01 1.571356E+01 5.995679E+02 - 1.090001E+01 9.000000E+01 5 2.717693E-04 -8.963556E+01 1.728637E-06 -2.717638E-04 - 1.090001E+01 9.000000E+01 6 6.053559E-05 1.798436E+02 -6.053536E-05 1.652639E-07 - 1.100001E+01 0.000000E+00 1 1.125144E+02 8.930782E+01 1.359243E+00 1.125062E+02 - 1.100001E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.100001E+01 0.000000E+00 3 6.991489E+01 2.062274E+00 6.986961E+01 2.515937E+00 - 1.100001E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.100001E+01 0.000000E+00 5 4.811365E+02 8.930108E+01 5.869034E+00 4.811007E+02 - 1.100001E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.100001E+01 3.000000E+01 1 1.016928E+02 8.933015E+01 1.188864E+00 1.016858E+02 - 1.100001E+01 3.000000E+01 2 6.175324E+01 8.854217E+01 1.571076E+00 6.173325E+01 - 1.100001E+01 3.000000E+01 3 7.384133E+01 2.157180E+00 7.378900E+01 2.779461E+00 - 1.100001E+01 3.000000E+01 4 2.370016E+02 8.846749E+01 6.338412E+00 2.369169E+02 - 1.100001E+01 3.000000E+01 5 4.396971E+02 8.933101E+01 5.133879E+00 4.396672E+02 - 1.100001E+01 3.000000E+01 6 5.894427E+02 -2.414777E-01 5.894375E+02 -2.484246E+00 - 1.100001E+01 6.000000E+01 1 6.405579E+01 8.936913E+01 7.052865E-01 6.405190E+01 - 1.100001E+01 6.000000E+01 2 1.182499E+02 8.852805E+01 3.037569E+00 1.182109E+02 - 1.100001E+01 6.000000E+01 3 8.242564E+01 2.355674E+00 8.235598E+01 3.387915E+00 - 1.100001E+01 6.000000E+01 4 4.764743E+02 8.852579E+01 1.225823E+01 4.763166E+02 - 1.100001E+01 6.000000E+01 5 2.802826E+02 8.937723E+01 3.046450E+00 2.802660E+02 - 1.100001E+01 6.000000E+01 6 6.518202E+02 -2.328204E-01 6.518148E+02 -2.648653E+00 - 1.100001E+01 9.000000E+01 1 7.190376E-06 -8.917889E+01 1.030418E-07 -7.189638E-06 - 1.100001E+01 9.000000E+01 2 1.435599E+02 8.852155E+01 3.703973E+00 1.435121E+02 - 1.100001E+01 9.000000E+01 3 8.709569E+01 2.457584E+00 8.701558E+01 3.734643E+00 - 1.100001E+01 9.000000E+01 4 5.909086E+02 8.855032E+01 1.494944E+01 5.907194E+02 - 1.100001E+01 9.000000E+01 5 2.697787E-04 -8.964803E+01 1.657267E-06 -2.697736E-04 - 1.100001E+01 9.000000E+01 6 5.884979E-05 1.798538E+02 -5.884960E-05 1.501424E-07 - 1.110001E+01 0.000000E+00 1 1.119316E+02 8.932198E+01 1.324538E+00 1.119238E+02 - 1.110001E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.110001E+01 0.000000E+00 3 7.184986E+01 2.047471E+00 7.180399E+01 2.567016E+00 - 1.110001E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.110001E+01 0.000000E+00 5 4.924015E+02 8.931596E+01 5.878577E+00 4.923664E+02 - 1.110001E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.110001E+01 3.000000E+01 1 1.010397E+02 8.934211E+01 1.160147E+00 1.010330E+02 - 1.110001E+01 3.000000E+01 2 6.138131E+01 8.859121E+01 1.509093E+00 6.136276E+01 - 1.110001E+01 3.000000E+01 3 7.574242E+01 2.137134E+00 7.568974E+01 2.824539E+00 - 1.110001E+01 3.000000E+01 4 2.349445E+02 8.852053E+01 6.065991E+00 2.348662E+02 - 1.110001E+01 3.000000E+01 5 4.489980E+02 8.934286E+01 5.149603E+00 4.489685E+02 - 1.110001E+01 3.000000E+01 6 5.758735E+02 -2.252217E-01 5.758691E+02 -2.263673E+00 - 1.110001E+01 6.000000E+01 1 6.347852E+01 8.937733E+01 6.898419E-01 6.347477E+01 - 1.110001E+01 6.000000E+01 2 1.171672E+02 8.857825E+01 2.907109E+00 1.171311E+02 - 1.110001E+01 6.000000E+01 3 8.422581E+01 2.324244E+00 8.415652E+01 3.415742E+00 - 1.110001E+01 6.000000E+01 4 4.703987E+02 8.857618E+01 1.168838E+01 4.702535E+02 - 1.110001E+01 6.000000E+01 5 2.851645E+02 8.938467E+01 3.062518E+00 2.851480E+02 - 1.110001E+01 6.000000E+01 6 6.348505E+02 -2.174072E-01 6.348459E+02 -2.408916E+00 - 1.110001E+01 9.000000E+01 1 7.106396E-06 -8.923474E+01 9.491247E-08 -7.105763E-06 - 1.110001E+01 9.000000E+01 2 1.420220E+02 8.857228E+01 3.538598E+00 1.419779E+02 - 1.110001E+01 9.000000E+01 3 8.882748E+01 2.420229E+00 8.874824E+01 3.751043E+00 - 1.110001E+01 9.000000E+01 4 5.822624E+02 8.859971E+01 1.422893E+01 5.820885E+02 - 1.110001E+01 9.000000E+01 5 2.678100E-04 -8.966010E+01 1.588743E-06 -2.678053E-04 - 1.110001E+01 9.000000E+01 6 5.723511E-05 1.798633E+02 -5.723494E-05 1.365836E-07 - 1.120001E+01 0.000000E+00 1 1.113342E+02 8.933583E+01 1.290555E+00 1.113267E+02 - 1.120001E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.120001E+01 0.000000E+00 3 7.375426E+01 2.031043E+00 7.370792E+01 2.613922E+00 - 1.120001E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.120001E+01 0.000000E+00 5 5.031029E+02 8.933041E+01 5.879393E+00 5.030686E+02 - 1.120001E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.120001E+01 3.000000E+01 1 1.003808E+02 8.935400E+01 1.131748E+00 1.003744E+02 - 1.120001E+01 3.000000E+01 2 6.100290E+01 8.863823E+01 1.449747E+00 6.098566E+01 - 1.120001E+01 3.000000E+01 3 7.761174E+01 2.115768E+00 7.755883E+01 2.865326E+00 - 1.120001E+01 3.000000E+01 4 2.328806E+02 8.857130E+01 5.806410E+00 2.328082E+02 - 1.120001E+01 3.000000E+01 5 4.578250E+02 8.935469E+01 5.156323E+00 4.577959E+02 - 1.120001E+01 3.000000E+01 6 5.627352E+02 -2.102707E-01 5.627314E+02 -2.065186E+00 - 1.120001E+01 6.000000E+01 1 6.290738E+01 8.938589E+01 6.742471E-01 6.290377E+01 - 1.120001E+01 6.000000E+01 2 1.160951E+02 8.862632E+01 2.783134E+00 1.160617E+02 - 1.120001E+01 6.000000E+01 3 8.599400E+01 2.292254E+00 8.592519E+01 3.439478E+00 - 1.120001E+01 6.000000E+01 4 4.644374E+02 8.862442E+01 1.114933E+01 4.643036E+02 - 1.120001E+01 6.000000E+01 5 2.897723E+02 8.939249E+01 3.072418E+00 2.897560E+02 - 1.120001E+01 6.000000E+01 6 6.185414E+02 -2.032062E-01 6.185375E+02 -2.193725E+00 - 1.120001E+01 9.000000E+01 1 7.024513E-06 -8.928721E+01 8.738753E-08 -7.023969E-06 - 1.120001E+01 9.000000E+01 2 1.405123E+02 8.862083E+01 3.381952E+00 1.404716E+02 - 1.120001E+01 9.000000E+01 3 9.052944E+01 2.382656E+00 9.045117E+01 3.763600E+00 - 1.120001E+01 9.000000E+01 4 5.738329E+02 8.864698E+01 1.354965E+01 5.736729E+02 - 1.120001E+01 9.000000E+01 5 2.658614E-04 -8.967177E+01 1.523023E-06 -2.658571E-04 - 1.120001E+01 9.000000E+01 6 5.568777E-05 1.798720E+02 -5.568763E-05 1.244114E-07 - 1.130001E+01 0.000000E+00 1 1.107238E+02 8.934938E+01 1.257293E+00 1.107167E+02 - 1.130001E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.130001E+01 0.000000E+00 3 7.562865E+01 2.013171E+00 7.558198E+01 2.656777E+00 - 1.130001E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.130001E+01 0.000000E+00 5 5.132776E+02 8.934452E+01 5.871973E+00 5.132441E+02 - 1.130001E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.130001E+01 3.000000E+01 1 9.971642E+01 8.936581E+01 1.103706E+00 9.971030E+01 - 1.130001E+01 3.000000E+01 2 6.061891E+01 8.868329E+01 1.392957E+00 6.060290E+01 - 1.130001E+01 3.000000E+01 3 7.945041E+01 2.093302E+00 7.939739E+01 2.902076E+00 - 1.130001E+01 3.000000E+01 4 2.308129E+02 8.861987E+01 5.559219E+00 2.307459E+02 - 1.130001E+01 3.000000E+01 5 4.662014E+02 8.936644E+01 5.154998E+00 4.661729E+02 - 1.130001E+01 3.000000E+01 6 5.500144E+02 -1.965068E-01 5.500112E+02 -1.886376E+00 - 1.130001E+01 6.000000E+01 1 6.234248E+01 8.939471E+01 6.585937E-01 6.233900E+01 - 1.130001E+01 6.000000E+01 2 1.150346E+02 8.867235E+01 2.665341E+00 1.150037E+02 - 1.130001E+01 6.000000E+01 3 8.773208E+01 2.259831E+00 8.766385E+01 3.459388E+00 - 1.130001E+01 6.000000E+01 4 4.585868E+02 8.867059E+01 1.063947E+01 4.584634E+02 - 1.130001E+01 6.000000E+01 5 2.941199E+02 8.940067E+01 3.076541E+00 2.941038E+02 - 1.130001E+01 6.000000E+01 6 6.028621E+02 -1.901099E-01 6.028588E+02 -2.000319E+00 - 1.130001E+01 9.000000E+01 1 6.944631E-06 -8.933647E+01 8.042228E-08 -6.944166E-06 - 1.130001E+01 9.000000E+01 2 1.390304E+02 8.866728E+01 3.233606E+00 1.389928E+02 - 1.130001E+01 9.000000E+01 3 9.220133E+01 2.345079E+00 9.212411E+01 3.772687E+00 - 1.130001E+01 9.000000E+01 4 5.656148E+02 8.869221E+01 1.290913E+01 5.654675E+02 - 1.130001E+01 9.000000E+01 5 2.639317E-04 -8.968305E+01 1.460027E-06 -2.639277E-04 - 1.130001E+01 9.000000E+01 6 5.420435E-05 1.798801E+02 -5.420423E-05 1.134699E-07 - 1.140001E+01 0.000000E+00 1 1.101025E+02 8.936264E+01 1.224765E+00 1.100957E+02 - 1.140001E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.140001E+01 0.000000E+00 3 7.747333E+01 1.994088E+00 7.742641E+01 2.695791E+00 - 1.140001E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.140001E+01 0.000000E+00 5 5.229449E+02 8.935825E+01 5.857249E+00 5.229121E+02 - 1.140001E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.140001E+01 3.000000E+01 1 9.904882E+01 8.937751E+01 1.076087E+00 9.904298E+01 - 1.140001E+01 3.000000E+01 2 6.023065E+01 8.872647E+01 1.338648E+00 6.021577E+01 - 1.140001E+01 3.000000E+01 3 8.125858E+01 2.069893E+00 8.120556E+01 2.934945E+00 - 1.140001E+01 3.000000E+01 4 2.287463E+02 8.866636E+01 5.323910E+00 2.286843E+02 - 1.140001E+01 3.000000E+01 5 4.741358E+02 8.937807E+01 5.146564E+00 4.741078E+02 - 1.140001E+01 3.000000E+01 6 5.376979E+02 -1.838224E-01 5.376951E+02 -1.725097E+00 - 1.140001E+01 6.000000E+01 1 6.178437E+01 8.940375E+01 6.429548E-01 6.178102E+01 - 1.140001E+01 6.000000E+01 2 1.139862E+02 8.871640E+01 2.553433E+00 1.139576E+02 - 1.140001E+01 6.000000E+01 3 8.943973E+01 2.227108E+00 8.937217E+01 3.475679E+00 - 1.140001E+01 6.000000E+01 4 4.528462E+02 8.871477E+01 1.015718E+01 4.527323E+02 - 1.140001E+01 6.000000E+01 5 2.982212E+02 8.940913E+01 3.075377E+00 2.982053E+02 - 1.140001E+01 6.000000E+01 6 5.877830E+02 -1.780215E-01 5.877802E+02 -1.826275E+00 - 1.140001E+01 9.000000E+01 1 6.866730E-06 -8.938273E+01 7.397684E-08 -6.866332E-06 - 1.140001E+01 9.000000E+01 2 1.375760E+02 8.871172E+01 3.093096E+00 1.375413E+02 - 1.140001E+01 9.000000E+01 3 9.384401E+01 2.307541E+00 9.376791E+01 3.778470E+00 - 1.140001E+01 9.000000E+01 4 5.576008E+02 8.873551E+01 1.230498E+01 5.574650E+02 - 1.140001E+01 9.000000E+01 5 2.620240E-04 -8.969394E+01 1.399698E-06 -2.620202E-04 - 1.140001E+01 9.000000E+01 6 5.278120E-05 1.798875E+02 -5.278110E-05 1.036221E-07 - 1.150001E+01 0.000000E+00 1 1.094725E+02 8.937561E+01 1.192975E+00 1.094660E+02 - 1.150001E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.150001E+01 0.000000E+00 3 7.928864E+01 1.973968E+00 7.924158E+01 2.731131E+00 - 1.150001E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.150001E+01 0.000000E+00 5 5.321284E+02 8.937166E+01 5.835532E+00 5.320964E+02 - 1.150001E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.150001E+01 3.000000E+01 1 9.837859E+01 8.938910E+01 1.048917E+00 9.837300E+01 - 1.150001E+01 3.000000E+01 2 5.983892E+01 8.876785E+01 1.286740E+00 5.982508E+01 - 1.150001E+01 3.000000E+01 3 8.303709E+01 2.045689E+00 8.298417E+01 2.964127E+00 - 1.150001E+01 3.000000E+01 4 2.266836E+02 8.871083E+01 5.100006E+00 2.266263E+02 - 1.150001E+01 3.000000E+01 5 4.816543E+02 8.938961E+01 5.131142E+00 4.816269E+02 - 1.150001E+01 3.000000E+01 6 5.257704E+02 -1.721227E-01 5.257680E+02 -1.579469E+00 - 1.150001E+01 6.000000E+01 1 6.123268E+01 8.941293E+01 6.273907E-01 6.122946E+01 - 1.150001E+01 6.000000E+01 2 1.129500E+02 8.875856E+01 2.447115E+00 1.129235E+02 - 1.150001E+01 6.000000E+01 3 9.111797E+01 2.194224E+00 9.105116E+01 3.488640E+00 - 1.150001E+01 6.000000E+01 4 4.472183E+02 8.875706E+01 9.700960E+00 4.471131E+02 - 1.150001E+01 6.000000E+01 5 3.020876E+02 8.941781E+01 3.069503E+00 3.020721E+02 - 1.150001E+01 6.000000E+01 6 5.732735E+02 -1.668540E-01 5.732711E+02 -1.669457E+00 - 1.150001E+01 9.000000E+01 1 6.790643E-06 -8.942614E+01 6.801285E-08 -6.790302E-06 - 1.150001E+01 9.000000E+01 2 1.361487E+02 8.875424E+01 2.959986E+00 1.361165E+02 - 1.150001E+01 9.000000E+01 3 9.545879E+01 2.270139E+00 9.538387E+01 3.781222E+00 - 1.150001E+01 9.000000E+01 4 5.497868E+02 8.877695E+01 1.173502E+01 5.496616E+02 - 1.150001E+01 9.000000E+01 5 2.601389E-04 -8.970444E+01 1.341961E-06 -2.601354E-04 - 1.150001E+01 9.000000E+01 6 5.141528E-05 1.798944E+02 -5.141519E-05 9.474749E-08 - 1.160001E+01 0.000000E+00 1 1.088344E+02 8.938829E+01 1.161933E+00 1.088281E+02 - 1.160001E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.160001E+01 0.000000E+00 3 8.107460E+01 1.952964E+00 8.102750E+01 2.762945E+00 - 1.160001E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.160001E+01 0.000000E+00 5 5.408304E+02 8.938472E+01 5.807692E+00 5.407993E+02 - 1.160001E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.160001E+01 3.000000E+01 1 9.770663E+01 8.940054E+01 1.022247E+00 9.770128E+01 - 1.160001E+01 3.000000E+01 2 5.944448E+01 8.880750E+01 1.237135E+00 5.943161E+01 - 1.160001E+01 3.000000E+01 3 8.478502E+01 2.020885E+00 8.473228E+01 2.989840E+00 - 1.160001E+01 3.000000E+01 4 2.246288E+02 8.875339E+01 4.886991E+00 2.245756E+02 - 1.160001E+01 3.000000E+01 5 4.887805E+02 8.940102E+01 5.109688E+00 4.887538E+02 - 1.160001E+01 3.000000E+01 6 5.142203E+02 -1.613197E-01 5.142183E+02 -1.447816E+00 - 1.160001E+01 6.000000E+01 1 6.068818E+01 8.942224E+01 6.119623E-01 6.068510E+01 - 1.160001E+01 6.000000E+01 2 1.119269E+02 8.879893E+01 2.346122E+00 1.119023E+02 - 1.160001E+01 6.000000E+01 3 9.276630E+01 2.161283E+00 9.270030E+01 3.498454E+00 - 1.160001E+01 6.000000E+01 4 4.417021E+02 8.879754E+01 9.269327E+00 4.416049E+02 - 1.160001E+01 6.000000E+01 5 3.057259E+02 8.942667E+01 3.059182E+00 3.057105E+02 - 1.160001E+01 6.000000E+01 6 5.593065E+02 -1.565280E-01 5.593044E+02 -1.527984E+00 - 1.160001E+01 9.000000E+01 1 6.716354E-06 -8.946687E+01 6.249444E-08 -6.716063E-06 - 1.160001E+01 9.000000E+01 2 1.347481E+02 8.879493E+01 2.833873E+00 1.347183E+02 - 1.160001E+01 9.000000E+01 3 9.704471E+01 2.232968E+00 9.697102E+01 3.781131E+00 - 1.160001E+01 9.000000E+01 4 5.421680E+02 8.881660E+01 1.119728E+01 5.420523E+02 - 1.160001E+01 9.000000E+01 5 2.582736E-04 -8.971455E+01 1.286725E-06 -2.582704E-04 - 1.160001E+01 9.000000E+01 6 5.010374E-05 1.799008E+02 -5.010366E-05 8.673994E-08 - 1.170001E+01 0.000000E+00 1 1.081895E+02 8.940069E+01 1.131644E+00 1.081836E+02 - 1.170001E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.170001E+01 0.000000E+00 3 8.283031E+01 1.931236E+00 8.278326E+01 2.791385E+00 - 1.170001E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.170001E+01 0.000000E+00 5 5.490875E+02 8.939746E+01 5.774291E+00 5.490571E+02 - 1.170001E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.170001E+01 3.000000E+01 1 9.703459E+01 8.941183E+01 9.961008E-01 9.702948E+01 - 1.170001E+01 3.000000E+01 2 5.904829E+01 8.884548E+01 1.189748E+00 5.903631E+01 - 1.170001E+01 3.000000E+01 3 8.650333E+01 1.995570E+00 8.645087E+01 3.012239E+00 - 1.170001E+01 3.000000E+01 4 2.225845E+02 8.879410E+01 4.684371E+00 2.225352E+02 - 1.170001E+01 3.000000E+01 5 4.955051E+02 8.941225E+01 5.082895E+00 4.954790E+02 - 1.170001E+01 3.000000E+01 6 5.030318E+02 -1.513360E-01 5.030301E+02 -1.328662E+00 - 1.170001E+01 6.000000E+01 1 6.015052E+01 8.943160E+01 5.967079E-01 6.014756E+01 - 1.170001E+01 6.000000E+01 2 1.109169E+02 8.883756E+01 2.250171E+00 1.108940E+02 - 1.170001E+01 6.000000E+01 3 9.438599E+01 2.128350E+00 9.432087E+01 3.505323E+00 - 1.170001E+01 6.000000E+01 4 4.362974E+02 8.883627E+01 8.860934E+00 4.362074E+02 - 1.170001E+01 6.000000E+01 5 3.091421E+02 8.943562E+01 3.045091E+00 3.091271E+02 - 1.170001E+01 6.000000E+01 6 5.458569E+02 -1.469714E-01 5.458551E+02 -1.400195E+00 - 1.170001E+01 9.000000E+01 1 6.643791E-06 -8.950507E+01 5.738891E-08 -6.643544E-06 - 1.170001E+01 9.000000E+01 2 1.333739E+02 8.883386E+01 2.714365E+00 1.333463E+02 - 1.170001E+01 9.000000E+01 3 9.860223E+01 2.196118E+00 9.852982E+01 3.778448E+00 - 1.170001E+01 9.000000E+01 4 5.347398E+02 8.885456E+01 1.068966E+01 5.346329E+02 - 1.170001E+01 9.000000E+01 5 2.564288E-04 -8.972430E+01 1.233911E-06 -2.564258E-04 - 1.170001E+01 9.000000E+01 6 4.884357E-05 1.799067E+02 -4.884350E-05 7.950538E-08 - 1.180001E+01 0.000000E+00 1 1.075397E+02 8.941280E+01 1.102103E+00 1.075341E+02 - 1.180001E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.180001E+01 0.000000E+00 3 8.455796E+01 1.908912E+00 8.451103E+01 2.816679E+00 - 1.180001E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.180001E+01 0.000000E+00 5 5.569067E+02 8.940990E+01 5.735585E+00 5.568771E+02 - 1.180001E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.180001E+01 3.000000E+01 1 9.636280E+01 8.942295E+01 9.705013E-01 9.635791E+01 - 1.180001E+01 3.000000E+01 2 5.865092E+01 8.888188E+01 1.144490E+00 5.863975E+01 - 1.180001E+01 3.000000E+01 3 8.819274E+01 1.969882E+00 8.814062E+01 3.031551E+00 - 1.180001E+01 3.000000E+01 4 2.205512E+02 8.883305E+01 4.491670E+00 2.205054E+02 - 1.180001E+01 3.000000E+01 5 5.018663E+02 8.942335E+01 5.050970E+00 5.018409E+02 - 1.180001E+01 3.000000E+01 6 4.921938E+02 -1.421004E-01 4.921923E+02 -1.220698E+00 - 1.180001E+01 6.000000E+01 1 5.961980E+01 8.944099E+01 5.816728E-01 5.961696E+01 - 1.180001E+01 6.000000E+01 2 1.099202E+02 8.887455E+01 2.159002E+00 1.098990E+02 - 1.180001E+01 6.000000E+01 3 9.597688E+01 2.095549E+00 9.591269E+01 3.509498E+00 - 1.180001E+01 6.000000E+01 4 4.309995E+02 8.887337E+01 8.474439E+00 4.309162E+02 - 1.180001E+01 6.000000E+01 5 3.123563E+02 8.944466E+01 3.027450E+00 3.123416E+02 - 1.180001E+01 6.000000E+01 6 5.328994E+02 -1.381192E-01 5.328979E+02 -1.284625E+00 - 1.180001E+01 9.000000E+01 1 6.572867E-06 -8.954091E+01 5.266531E-08 -6.572656E-06 - 1.180001E+01 9.000000E+01 2 1.320260E+02 8.887112E+01 2.601086E+00 1.320003E+02 - 1.180001E+01 9.000000E+01 3 1.001325E+02 2.159629E+00 1.000614E+02 3.773364E+00 - 1.180001E+01 9.000000E+01 4 5.274958E+02 8.889090E+01 1.021038E+01 5.273970E+02 - 1.180001E+01 9.000000E+01 5 2.546061E-04 -8.973369E+01 1.183421E-06 -2.546033E-04 - 1.180001E+01 9.000000E+01 6 4.763217E-05 1.799122E+02 -4.763211E-05 7.296139E-08 - 1.190001E+01 0.000000E+00 1 1.068864E+02 8.942465E+01 1.073315E+00 1.068810E+02 - 1.190001E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.190001E+01 0.000000E+00 3 8.625607E+01 1.886070E+00 8.620934E+01 2.838876E+00 - 1.190001E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.190001E+01 0.000000E+00 5 5.643052E+02 8.942200E+01 5.692641E+00 5.642765E+02 - 1.190001E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.190001E+01 3.000000E+01 1 9.569206E+01 8.943389E+01 9.454651E-01 9.568739E+01 - 1.190001E+01 3.000000E+01 2 5.825286E+01 8.891676E+01 1.101272E+00 5.824245E+01 - 1.190001E+01 3.000000E+01 3 8.985291E+01 1.943876E+00 8.980120E+01 3.047858E+00 - 1.190001E+01 3.000000E+01 4 2.185332E+02 8.887034E+01 4.308407E+00 2.184907E+02 - 1.190001E+01 3.000000E+01 5 5.078765E+02 8.943426E+01 5.014700E+00 5.078517E+02 - 1.190001E+01 3.000000E+01 6 4.816945E+02 -1.335487E-01 4.816932E+02 -1.122764E+00 - 1.190001E+01 6.000000E+01 1 5.909634E+01 8.945039E+01 5.668811E-01 5.909362E+01 - 1.190001E+01 6.000000E+01 2 1.089371E+02 8.890997E+01 2.072361E+00 1.089174E+02 - 1.190001E+01 6.000000E+01 3 9.754016E+01 2.062865E+00 9.747695E+01 3.511057E+00 - 1.190001E+01 6.000000E+01 4 4.258096E+02 8.890886E+01 8.108605E+00 4.257324E+02 - 1.190001E+01 6.000000E+01 5 3.153695E+02 8.945371E+01 3.006876E+00 3.153551E+02 - 1.190001E+01 6.000000E+01 6 5.204125E+02 -1.299123E-01 5.204112E+02 -1.179981E+00 - 1.190001E+01 9.000000E+01 1 6.503536E-06 -8.957452E+01 4.829484E-08 -6.503357E-06 - 1.190001E+01 9.000000E+01 2 1.307033E+02 8.890679E+01 2.493684E+00 1.306795E+02 - 1.190001E+01 9.000000E+01 3 1.016361E+02 2.123506E+00 1.015663E+02 3.765992E+00 - 1.190001E+01 9.000000E+01 4 5.204306E+02 8.892568E+01 9.757710E+00 5.203391E+02 - 1.190001E+01 9.000000E+01 5 2.528031E-04 -8.974271E+01 1.135188E-06 -2.528005E-04 - 1.190001E+01 9.000000E+01 6 4.646727E-05 1.799173E+02 -4.646722E-05 6.703487E-08 - 1.200001E+01 0.000000E+00 1 1.062292E+02 8.943621E+01 1.045279E+00 1.062241E+02 - 1.200001E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.200001E+01 0.000000E+00 3 8.792551E+01 1.862878E+00 8.787904E+01 2.858249E+00 - 1.200001E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.200001E+01 0.000000E+00 5 5.713010E+02 8.943381E+01 5.645458E+00 5.712731E+02 - 1.200001E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.200001E+01 3.000000E+01 1 9.502312E+01 8.944466E+01 9.210083E-01 9.501866E+01 - 1.200001E+01 3.000000E+01 2 5.785476E+01 8.895018E+01 1.059999E+00 5.784505E+01 - 1.200001E+01 3.000000E+01 3 9.148434E+01 1.917713E+00 9.143310E+01 3.061446E+00 - 1.200001E+01 3.000000E+01 4 2.165313E+02 8.890603E+01 4.134084E+00 2.164918E+02 - 1.200001E+01 3.000000E+01 5 5.135402E+02 8.944498E+01 4.974524E+00 5.135161E+02 - 1.200001E+01 3.000000E+01 6 4.715199E+02 -1.256225E-01 4.715188E+02 -1.033819E+00 - 1.200001E+01 6.000000E+01 1 5.857990E+01 8.945974E+01 5.523602E-01 5.857729E+01 - 1.200001E+01 6.000000E+01 2 1.079678E+02 8.894389E+01 1.990017E+00 1.079494E+02 - 1.200001E+01 6.000000E+01 3 9.907504E+01 2.030438E+00 9.901284E+01 3.510269E+00 - 1.200001E+01 6.000000E+01 4 4.207267E+02 8.894286E+01 7.762195E+00 4.206550E+02 - 1.200001E+01 6.000000E+01 5 3.181928E+02 8.946277E+01 2.983491E+00 3.181788E+02 - 1.200001E+01 6.000000E+01 6 5.083714E+02 -1.222968E-01 5.083702E+02 -1.085109E+00 - 1.200001E+01 9.000000E+01 1 6.435780E-06 -8.960605E+01 4.425109E-08 -6.435627E-06 - 1.200001E+01 9.000000E+01 2 1.294058E+02 8.894093E+01 2.391825E+00 1.293837E+02 - 1.200001E+01 9.000000E+01 3 1.031123E+02 2.087878E+00 1.030439E+02 3.756617E+00 - 1.200001E+01 9.000000E+01 4 5.135405E+02 8.895899E+01 9.330029E+00 5.134557E+02 - 1.200001E+01 9.000000E+01 5 2.510214E-04 -8.975141E+01 1.089106E-06 -2.510191E-04 - 1.200001E+01 9.000000E+01 6 4.534634E-05 1.799221E+02 -4.534630E-05 6.166076E-08 - 1.210001E+01 0.000000E+00 1 1.055706E+02 8.944751E+01 1.017983E+00 1.055657E+02 - 1.210001E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.210001E+01 0.000000E+00 3 8.956721E+01 1.839370E+00 8.952106E+01 2.874888E+00 - 1.210001E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.210001E+01 0.000000E+00 5 5.779141E+02 8.944532E+01 5.594736E+00 5.778870E+02 - 1.210001E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.210001E+01 3.000000E+01 1 9.435610E+01 8.945523E+01 8.971375E-01 9.435184E+01 - 1.210001E+01 3.000000E+01 2 5.745713E+01 8.898222E+01 1.020595E+00 5.744807E+01 - 1.210001E+01 3.000000E+01 3 9.308748E+01 1.891421E+00 9.303676E+01 3.072401E+00 - 1.210001E+01 3.000000E+01 4 2.145465E+02 8.894019E+01 3.968291E+00 2.145098E+02 - 1.210001E+01 3.000000E+01 5 5.188732E+02 8.945552E+01 4.930748E+00 5.188497E+02 - 1.210001E+01 3.000000E+01 6 4.616594E+02 -1.182696E-01 4.616584E+02 -9.529539E-01 - 1.210001E+01 6.000000E+01 1 5.807073E+01 8.946905E+01 5.381309E-01 5.806824E+01 - 1.210001E+01 6.000000E+01 2 1.070119E+02 8.897638E+01 1.911727E+00 1.069948E+02 - 1.210001E+01 6.000000E+01 3 1.005827E+02 1.998309E+00 1.005216E+02 3.507320E+00 - 1.210001E+01 6.000000E+01 4 4.157474E+02 8.897543E+01 7.434075E+00 4.156809E+02 - 1.210001E+01 6.000000E+01 5 3.208337E+02 8.947179E+01 2.957735E+00 3.208201E+02 - 1.210001E+01 6.000000E+01 6 4.967585E+02 -1.152239E-01 4.967575E+02 -9.989983E-01 - 1.210001E+01 9.000000E+01 1 6.369472E-06 -8.963560E+01 4.050915E-08 -6.369344E-06 - 1.210001E+01 9.000000E+01 2 1.281328E+02 8.897363E+01 2.295185E+00 1.281122E+02 - 1.210001E+01 9.000000E+01 3 1.045628E+02 2.052713E+00 1.044957E+02 3.745329E+00 - 1.210001E+01 9.000000E+01 4 5.068209E+02 8.899091E+01 8.925686E+00 5.067423E+02 - 1.210001E+01 9.000000E+01 5 2.492595E-04 -8.975977E+01 1.045091E-06 -2.492573E-04 - 1.210001E+01 9.000000E+01 6 4.426733E-05 1.799265E+02 -4.426729E-05 5.678195E-08 - 1.220001E+01 0.000000E+00 1 1.049102E+02 8.945853E+01 9.914271E-01 1.049055E+02 - 1.220001E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.220001E+01 0.000000E+00 3 9.118073E+01 1.815689E+00 9.113495E+01 2.889012E+00 - 1.220001E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.220001E+01 0.000000E+00 5 5.841580E+02 8.945654E+01 5.540733E+00 5.841317E+02 - 1.220001E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.220001E+01 3.000000E+01 1 9.369230E+01 8.946560E+01 8.738610E-01 9.368822E+01 - 1.220001E+01 3.000000E+01 2 5.706032E+01 8.901293E+01 9.829652E-01 5.705185E+01 - 1.220001E+01 3.000000E+01 3 9.466312E+01 1.865110E+00 9.461298E+01 3.080958E+00 - 1.220001E+01 3.000000E+01 4 2.125812E+02 8.897290E+01 3.810581E+00 2.125471E+02 - 1.220001E+01 3.000000E+01 5 5.239091E+02 8.946588E+01 4.883858E+00 5.238863E+02 - 1.220001E+01 3.000000E+01 6 4.521007E+02 -1.114424E-01 4.520999E+02 -8.793516E-01 - 1.220001E+01 6.000000E+01 1 5.756867E+01 8.947827E+01 5.242051E-01 5.756628E+01 - 1.220001E+01 6.000000E+01 2 1.060700E+02 8.900750E+01 1.837288E+00 1.060541E+02 - 1.220001E+01 6.000000E+01 3 1.020632E+02 1.966529E+00 1.020031E+02 3.502366E+00 - 1.220001E+01 6.000000E+01 4 4.108702E+02 8.900661E+01 7.123251E+00 4.108085E+02 - 1.220001E+01 6.000000E+01 5 3.233058E+02 8.948078E+01 2.929794E+00 3.232925E+02 - 1.220001E+01 6.000000E+01 6 4.855527E+02 -1.086493E-01 4.855518E+02 -9.207476E-01 - 1.220001E+01 9.000000E+01 1 6.304601E-06 -8.966332E+01 3.704645E-08 -6.304493E-06 - 1.220001E+01 9.000000E+01 2 1.268837E+02 8.900494E+01 2.203476E+00 1.268646E+02 - 1.220001E+01 9.000000E+01 3 1.059868E+02 2.018099E+00 1.059210E+02 3.732344E+00 - 1.220001E+01 9.000000E+01 4 5.002638E+02 8.902147E+01 8.543369E+00 5.001908E+02 - 1.220001E+01 9.000000E+01 5 2.475191E-04 -8.976781E+01 1.003075E-06 -2.475171E-04 - 1.220001E+01 9.000000E+01 6 4.322813E-05 1.799306E+02 -4.322810E-05 5.234746E-08 - 1.230001E+01 0.000000E+00 1 1.042497E+02 8.946930E+01 9.655973E-01 1.042452E+02 - 1.230001E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.230001E+01 0.000000E+00 3 9.276642E+01 1.791852E+00 9.272105E+01 2.900677E+00 - 1.230001E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.230001E+01 0.000000E+00 5 5.900499E+02 8.946748E+01 5.483995E+00 5.900244E+02 - 1.230001E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.230001E+01 3.000000E+01 1 9.303152E+01 8.947578E+01 8.511832E-01 9.302763E+01 - 1.230001E+01 3.000000E+01 2 5.666471E+01 8.904237E+01 9.470353E-01 5.665679E+01 - 1.230001E+01 3.000000E+01 3 9.621081E+01 1.838820E+00 9.616126E+01 3.087209E+00 - 1.230001E+01 3.000000E+01 4 2.106349E+02 8.900423E+01 3.660543E+00 2.106031E+02 - 1.230001E+01 3.000000E+01 5 5.286344E+02 8.947604E+01 4.834286E+00 5.286123E+02 - 1.230001E+01 3.000000E+01 6 4.428337E+02 -1.050971E-01 4.428329E+02 -8.122854E-01 - 1.230001E+01 6.000000E+01 1 5.707371E+01 8.948741E+01 5.105975E-01 5.707143E+01 - 1.230001E+01 6.000000E+01 2 1.051417E+02 8.903733E+01 1.766484E+00 1.051268E+02 - 1.230001E+01 6.000000E+01 3 1.035178E+02 1.935063E+00 1.034588E+02 3.495465E+00 - 1.230001E+01 6.000000E+01 4 4.060948E+02 8.903651E+01 6.828631E+00 4.060374E+02 - 1.230001E+01 6.000000E+01 5 3.256099E+02 8.948969E+01 2.900049E+00 3.255970E+02 - 1.230001E+01 6.000000E+01 6 4.747352E+02 -1.025328E-01 4.747344E+02 -8.495545E-01 - 1.230001E+01 9.000000E+01 1 6.241133E-06 -8.968932E+01 3.384201E-08 -6.241041E-06 - 1.230001E+01 9.000000E+01 2 1.256580E+02 8.903494E+01 2.116406E+00 1.256402E+02 - 1.230001E+01 9.000000E+01 3 1.073860E+02 1.983983E+00 1.073217E+02 3.717717E+00 - 1.230001E+01 9.000000E+01 4 4.938672E+02 8.905077E+01 8.181700E+00 4.937994E+02 - 1.230001E+01 9.000000E+01 5 2.457996E-04 -8.977554E+01 9.629482E-07 -2.457977E-04 - 1.230001E+01 9.000000E+01 6 4.222679E-05 1.799344E+02 -4.222676E-05 4.831198E-08 - 1.240001E+01 0.000000E+00 1 1.035895E+02 8.947980E+01 9.404937E-01 1.035852E+02 - 1.240001E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.240001E+01 0.000000E+00 3 9.432555E+01 1.767963E+00 9.428065E+01 2.910121E+00 - 1.240001E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.240001E+01 0.000000E+00 5 5.956002E+02 8.947814E+01 5.424707E+00 5.955754E+02 - 1.240001E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.240001E+01 3.000000E+01 1 9.237492E+01 8.948574E+01 8.291031E-01 9.237119E+01 - 1.240001E+01 3.000000E+01 2 5.627071E+01 8.907061E+01 9.127184E-01 5.626330E+01 - 1.240001E+01 3.000000E+01 3 9.773093E+01 1.812637E+00 9.768202E+01 3.091347E+00 - 1.240001E+01 3.000000E+01 4 2.087110E+02 8.903425E+01 3.517780E+00 2.086814E+02 - 1.240001E+01 3.000000E+01 5 5.330732E+02 8.948598E+01 4.782290E+00 5.330518E+02 - 1.240001E+01 3.000000E+01 6 4.338464E+02 -9.919482E-02 4.338457E+02 -7.511076E-01 - 1.240001E+01 6.000000E+01 1 5.658599E+01 8.949644E+01 4.973158E-01 5.658380E+01 - 1.240001E+01 6.000000E+01 2 1.042272E+02 8.906592E+01 1.699119E+00 1.042134E+02 - 1.240001E+01 6.000000E+01 3 1.049463E+02 1.904029E+00 1.048884E+02 3.486890E+00 - 1.240001E+01 6.000000E+01 4 4.014172E+02 8.906515E+01 6.549312E+00 4.013638E+02 - 1.240001E+01 6.000000E+01 5 3.277592E+02 8.949853E+01 2.868647E+00 3.277467E+02 - 1.240001E+01 6.000000E+01 6 4.642887E+02 -9.683754E-02 4.642880E+02 -7.847096E-01 - 1.240001E+01 9.000000E+01 1 6.179006E-06 -8.971370E+01 3.087587E-08 -6.178929E-06 - 1.240001E+01 9.000000E+01 2 1.244558E+02 8.906370E+01 2.033714E+00 1.244392E+02 - 1.240001E+01 9.000000E+01 3 1.087600E+02 1.950470E+00 1.086970E+02 3.701705E+00 - 1.240001E+01 9.000000E+01 4 4.876261E+02 8.907884E+01 7.839365E+00 4.875630E+02 - 1.240001E+01 9.000000E+01 5 2.440982E-04 -8.978297E+01 9.246425E-07 -2.440964E-04 - 1.240001E+01 9.000000E+01 6 4.126145E-05 1.799380E+02 -4.126142E-05 4.463558E-08 - 1.250001E+01 0.000000E+00 1 1.029296E+02 8.949005E+01 9.160917E-01 1.029255E+02 - 1.250001E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.250001E+01 0.000000E+00 3 9.585702E+01 1.744084E+00 9.581261E+01 2.917438E+00 - 1.250001E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.250001E+01 0.000000E+00 5 6.008287E+02 8.948854E+01 5.363334E+00 6.008048E+02 - 1.250001E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.250001E+01 3.000000E+01 1 9.172245E+01 8.949551E+01 8.076090E-01 9.171889E+01 - 1.250001E+01 3.000000E+01 2 5.587859E+01 8.909771E+01 8.799407E-01 5.587166E+01 - 1.250001E+01 3.000000E+01 3 9.922520E+01 1.786535E+00 9.917697E+01 3.093431E+00 - 1.250001E+01 3.000000E+01 4 2.068085E+02 8.906302E+01 3.381885E+00 2.067808E+02 - 1.250001E+01 3.000000E+01 5 5.372525E+02 8.949575E+01 4.728209E+00 5.372317E+02 - 1.250001E+01 3.000000E+01 6 4.251291E+02 -9.369939E-02 4.251285E+02 -6.952400E-01 - 1.250001E+01 6.000000E+01 1 5.610529E+01 8.950536E+01 4.843614E-01 5.610320E+01 - 1.250001E+01 6.000000E+01 2 1.033262E+02 8.909333E+01 1.635004E+00 1.033132E+02 - 1.250001E+01 6.000000E+01 3 1.063493E+02 1.873419E+00 1.062925E+02 3.476720E+00 - 1.250001E+01 6.000000E+01 4 3.968362E+02 8.909261E+01 6.284411E+00 3.967865E+02 - 1.250001E+01 6.000000E+01 5 3.297563E+02 8.950726E+01 2.835852E+00 3.297441E+02 - 1.250001E+01 6.000000E+01 6 4.541964E+02 -9.152967E-02 4.541958E+02 -7.255757E-01 - 1.250001E+01 9.000000E+01 1 6.118162E-06 -8.973656E+01 2.813067E-08 -6.118098E-06 - 1.250001E+01 9.000000E+01 2 1.232759E+02 8.909126E+01 1.955142E+00 1.232604E+02 - 1.250001E+01 9.000000E+01 3 1.101094E+02 1.917527E+00 1.100478E+02 3.684362E+00 - 1.250001E+01 9.000000E+01 4 4.815327E+02 8.910576E+01 7.515173E+00 4.814741E+02 - 1.250001E+01 9.000000E+01 5 2.424188E-04 -8.979011E+01 8.880730E-07 -2.424172E-04 - 1.250001E+01 9.000000E+01 6 4.033050E-05 1.799413E+02 -4.033048E-05 4.128229E-08 - 1.260001E+01 0.000000E+00 1 1.022716E+02 8.950005E+01 8.923918E-01 1.022678E+02 - 1.260001E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.260001E+01 0.000000E+00 3 9.736290E+01 1.720210E+00 9.731902E+01 2.922719E+00 - 1.260001E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.260001E+01 0.000000E+00 5 6.057446E+02 8.949866E+01 5.300231E+00 6.057214E+02 - 1.260001E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.260001E+01 3.000000E+01 1 9.107421E+01 8.950507E+01 7.867076E-01 9.107082E+01 - 1.260001E+01 3.000000E+01 2 5.548875E+01 8.912370E+01 8.486320E-01 5.548226E+01 - 1.260001E+01 3.000000E+01 3 1.006928E+02 1.760619E+00 1.006452E+02 3.093660E+00 - 1.260001E+01 3.000000E+01 4 2.049292E+02 8.909059E+01 3.252542E+00 2.049034E+02 - 1.260001E+01 3.000000E+01 5 5.411503E+02 8.950527E+01 4.672566E+00 5.411301E+02 - 1.260001E+01 3.000000E+01 6 4.166722E+02 -8.857828E-02 4.166717E+02 -6.441677E-01 - 1.260001E+01 6.000000E+01 1 5.563151E+01 8.951414E+01 4.717415E-01 5.562951E+01 - 1.260001E+01 6.000000E+01 2 1.024386E+02 8.911962E+01 1.573968E+00 1.024265E+02 - 1.260001E+01 6.000000E+01 3 1.077271E+02 1.843222E+00 1.076713E+02 3.465012E+00 - 1.260001E+01 6.000000E+01 4 3.923490E+02 8.911895E+01 6.033013E+00 3.923026E+02 - 1.260001E+01 6.000000E+01 5 3.316088E+02 8.951587E+01 2.801925E+00 3.315970E+02 - 1.260001E+01 6.000000E+01 6 4.444436E+02 -8.657908E-02 4.444431E+02 -6.715940E-01 - 1.260001E+01 9.000000E+01 1 6.058593E-06 -8.975800E+01 2.558908E-08 -6.058538E-06 - 1.260001E+01 9.000000E+01 2 1.221181E+02 8.911768E+01 1.880469E+00 1.221036E+02 - 1.260001E+01 9.000000E+01 3 1.114346E+02 1.885134E+00 1.113743E+02 3.665738E+00 - 1.260001E+01 9.000000E+01 4 4.755874E+02 8.913158E+01 7.208121E+00 4.755328E+02 - 1.260001E+01 9.000000E+01 5 2.407573E-04 -8.979696E+01 8.531620E-07 -2.407558E-04 - 1.260001E+01 9.000000E+01 6 3.943224E-05 1.799445E+02 -3.943222E-05 3.822041E-08 - 1.270001E+01 0.000000E+00 1 1.016153E+02 8.950980E+01 8.693728E-01 1.016116E+02 - 1.270001E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.270001E+01 0.000000E+00 3 9.884223E+01 1.696432E+00 9.879891E+01 2.926125E+00 - 1.270001E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.270001E+01 0.000000E+00 5 6.103551E+02 8.950853E+01 5.235420E+00 6.103326E+02 - 1.270001E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.270001E+01 3.000000E+01 1 9.043067E+01 8.951442E+01 7.663884E-01 9.042742E+01 - 1.270001E+01 3.000000E+01 2 5.510102E+01 8.914865E+01 8.187144E-01 5.509494E+01 - 1.270001E+01 3.000000E+01 3 1.021355E+02 1.734906E+00 1.020887E+02 3.092173E+00 - 1.270001E+01 3.000000E+01 4 2.030723E+02 8.911703E+01 3.129369E+00 2.030482E+02 - 1.270001E+01 3.000000E+01 5 5.448085E+02 8.951463E+01 4.615272E+00 5.447889E+02 - 1.270001E+01 3.000000E+01 6 4.084662E+02 -8.380222E-02 4.084658E+02 -5.974325E-01 - 1.270001E+01 6.000000E+01 1 5.516476E+01 8.952279E+01 4.594568E-01 5.516285E+01 - 1.270001E+01 6.000000E+01 2 1.015644E+02 8.914484E+01 1.515838E+00 1.015531E+02 - 1.270001E+01 6.000000E+01 3 1.090804E+02 1.813513E+00 1.090258E+02 3.452014E+00 - 1.270001E+01 6.000000E+01 4 3.879556E+02 8.914421E+01 5.794427E+00 3.879123E+02 - 1.270001E+01 6.000000E+01 5 3.333284E+02 8.952438E+01 2.766979E+00 3.333169E+02 - 1.270001E+01 6.000000E+01 6 4.350145E+02 -8.195766E-02 4.350140E+02 -6.222580E-01 - 1.270001E+01 9.000000E+01 1 6.000205E-06 -8.977811E+01 2.323623E-08 -6.000160E-06 - 1.270001E+01 9.000000E+01 2 1.209816E+02 8.914303E+01 1.809454E+00 1.209680E+02 - 1.270001E+01 9.000000E+01 3 1.127366E+02 1.853378E+00 1.126776E+02 3.646115E+00 - 1.270001E+01 9.000000E+01 4 4.697818E+02 8.915635E+01 6.917041E+00 4.697309E+02 - 1.270001E+01 9.000000E+01 5 2.391163E-04 -8.980356E+01 8.198295E-07 -2.391149E-04 - 1.270001E+01 9.000000E+01 6 3.856514E-05 1.799474E+02 -3.856512E-05 3.542146E-08 - 1.280001E+01 0.000000E+00 1 1.009614E+02 8.951931E+01 8.470231E-01 1.009578E+02 - 1.280001E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.280001E+01 0.000000E+00 3 1.002962E+02 1.672778E+00 1.002535E+02 2.927781E+00 - 1.280001E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.280001E+01 0.000000E+00 5 6.146942E+02 8.951814E+01 5.169532E+00 6.146724E+02 - 1.280001E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.280001E+01 3.000000E+01 1 8.979245E+01 8.952357E+01 7.466415E-01 8.978934E+01 - 1.280001E+01 3.000000E+01 2 5.471620E+01 8.917259E+01 7.901255E-01 5.471049E+01 - 1.280001E+01 3.000000E+01 3 1.035522E+02 1.709448E+00 1.035061E+02 3.089072E+00 - 1.280001E+01 3.000000E+01 4 2.012382E+02 8.914239E+01 3.012062E+00 2.012156E+02 - 1.280001E+01 3.000000E+01 5 5.482299E+02 8.952376E+01 4.556846E+00 5.482110E+02 - 1.280001E+01 3.000000E+01 6 4.005014E+02 -7.934381E-02 4.005010E+02 -5.546184E-01 - 1.280001E+01 6.000000E+01 1 5.470491E+01 8.953130E+01 4.475023E-01 5.470308E+01 - 1.280001E+01 6.000000E+01 2 1.007037E+02 8.916904E+01 1.460459E+00 1.006931E+02 - 1.280001E+01 6.000000E+01 3 1.104098E+02 1.784248E+00 1.103563E+02 3.437717E+00 - 1.280001E+01 6.000000E+01 4 3.836539E+02 8.916846E+01 5.567841E+00 3.836135E+02 - 1.280001E+01 6.000000E+01 5 3.349163E+02 8.953274E+01 2.731304E+00 3.349051E+02 - 1.280001E+01 6.000000E+01 6 4.258942E+02 -7.764024E-02 4.258938E+02 -5.771196E-01 - 1.280001E+01 9.000000E+01 1 5.943022E-06 -8.979699E+01 2.105765E-08 -5.942984E-06 - 1.280001E+01 9.000000E+01 2 1.198662E+02 8.916734E+01 1.741907E+00 1.198535E+02 - 1.280001E+01 9.000000E+01 3 1.140152E+02 1.822179E+00 1.139576E+02 3.625418E+00 - 1.280001E+01 9.000000E+01 4 4.641135E+02 8.918012E+01 6.641050E+00 4.640660E+02 - 1.280001E+01 9.000000E+01 5 2.374954E-04 -8.980989E+01 7.880111E-07 -2.374941E-04 - 1.280001E+01 9.000000E+01 6 3.772786E-05 1.799501E+02 -3.772785E-05 3.286006E-08 - 1.290001E+01 0.000000E+00 1 1.003103E+02 8.952858E+01 8.253285E-01 1.003070E+02 - 1.290001E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.290001E+01 0.000000E+00 3 1.017248E+02 1.649289E+00 1.016827E+02 2.927798E+00 - 1.290001E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.290001E+01 0.000000E+00 5 6.187474E+02 8.952752E+01 5.102357E+00 6.187264E+02 - 1.290001E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.290001E+01 3.000000E+01 1 8.915935E+01 8.953251E+01 7.274616E-01 8.915638E+01 - 1.290001E+01 3.000000E+01 2 5.433393E+01 8.919559E+01 7.627972E-01 5.432858E+01 - 1.290001E+01 3.000000E+01 3 1.049436E+02 1.684247E+00 1.048983E+02 3.084443E+00 - 1.290001E+01 3.000000E+01 4 1.994283E+02 8.916672E+01 2.900286E+00 1.994072E+02 - 1.290001E+01 3.000000E+01 5 5.514082E+02 8.953268E+01 4.497407E+00 5.513898E+02 - 1.290001E+01 3.000000E+01 6 3.927689E+02 -7.517843E-02 3.927686E+02 -5.153563E-01 - 1.290001E+01 6.000000E+01 1 5.425166E+01 8.953966E+01 4.358831E-01 5.424991E+01 - 1.290001E+01 6.000000E+01 2 9.985564E+01 8.919227E+01 1.407678E+00 9.984572E+01 - 1.290001E+01 6.000000E+01 3 1.117153E+02 1.755491E+00 1.116628E+02 3.422320E+00 - 1.290001E+01 6.000000E+01 4 3.794368E+02 8.919173E+01 5.352582E+00 3.793991E+02 - 1.290001E+01 6.000000E+01 5 3.363806E+02 8.954098E+01 2.694847E+00 3.363698E+02 - 1.290001E+01 6.000000E+01 6 4.170709E+02 -7.360327E-02 4.170705E+02 -5.357772E-01 - 1.290001E+01 9.000000E+01 1 5.886964E-06 -8.981469E+01 1.904019E-08 -5.886933E-06 - 1.290001E+01 9.000000E+01 2 1.187717E+02 8.919069E+01 1.677620E+00 1.187598E+02 - 1.290001E+01 9.000000E+01 3 1.152706E+02 1.791620E+00 1.152143E+02 3.603888E+00 - 1.290001E+01 9.000000E+01 4 4.585769E+02 8.920294E+01 6.379220E+00 4.585326E+02 - 1.290001E+01 9.000000E+01 5 2.358923E-04 -8.981598E+01 7.576314E-07 -2.358911E-04 - 1.290001E+01 9.000000E+01 6 3.691895E-05 1.799527E+02 -3.691894E-05 3.051355E-08 - 1.300001E+01 0.000000E+00 1 9.966228E+01 8.953762E+01 8.042725E-01 9.965904E+01 - 1.300001E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.300001E+01 0.000000E+00 3 1.031288E+02 1.625988E+00 1.030872E+02 2.926281E+00 - 1.300001E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.300001E+01 0.000000E+00 5 6.225383E+02 8.953664E+01 5.034557E+00 6.225179E+02 - 1.300001E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.300001E+01 3.000000E+01 1 8.853170E+01 8.954125E+01 7.088355E-01 8.852886E+01 - 1.300001E+01 3.000000E+01 2 5.395467E+01 8.921769E+01 7.366695E-01 5.394965E+01 - 1.300001E+01 3.000000E+01 3 1.063111E+02 1.659326E+00 1.062665E+02 3.078414E+00 - 1.300001E+01 3.000000E+01 4 1.976420E+02 8.919007E+01 2.793766E+00 1.976223E+02 - 1.300001E+01 3.000000E+01 5 5.543762E+02 8.954140E+01 4.437195E+00 5.543584E+02 - 1.300001E+01 3.000000E+01 6 3.852600E+02 -7.128378E-02 3.852597E+02 -4.793159E-01 - 1.300001E+01 6.000000E+01 1 5.380541E+01 8.954787E+01 4.245897E-01 5.380374E+01 - 1.300001E+01 6.000000E+01 2 9.902090E+01 8.921458E+01 1.357359E+00 9.901160E+01 - 1.300001E+01 6.000000E+01 3 1.129971E+02 1.727234E+00 1.129457E+02 3.405884E+00 - 1.300001E+01 6.000000E+01 4 3.753094E+02 8.921407E+01 5.148009E+00 3.752740E+02 - 1.300001E+01 6.000000E+01 5 3.377252E+02 8.954906E+01 2.657947E+00 3.377147E+02 - 1.300001E+01 6.000000E+01 6 4.085299E+02 -6.982595E-02 4.085296E+02 -4.978722E-01 - 1.300001E+01 9.000000E+01 1 5.832023E-06 -8.983130E+01 1.717203E-08 -5.831997E-06 - 1.300001E+01 9.000000E+01 2 1.176967E+02 8.921309E+01 1.616412E+00 1.176856E+02 - 1.300001E+01 9.000000E+01 3 1.165038E+02 1.761626E+00 1.164487E+02 3.581482E+00 - 1.300001E+01 9.000000E+01 4 4.531705E+02 8.922485E+01 6.130694E+00 4.531290E+02 - 1.300001E+01 9.000000E+01 5 2.343102E-04 -8.982183E+01 7.286212E-07 -2.343090E-04 - 1.300001E+01 9.000000E+01 6 3.613716E-05 1.799550E+02 -3.613715E-05 2.836163E-08 - 1.310001E+01 0.000000E+00 1 9.901750E+01 8.954643E+01 7.838416E-01 9.901440E+01 - 1.310001E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.310001E+01 0.000000E+00 3 1.045077E+02 1.602922E+00 1.044668E+02 2.923352E+00 - 1.310001E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.310001E+01 0.000000E+00 5 6.260788E+02 8.954553E+01 4.966015E+00 6.260591E+02 - 1.310001E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.310001E+01 3.000000E+01 1 8.790895E+01 8.954979E+01 6.907496E-01 8.790623E+01 - 1.310001E+01 3.000000E+01 2 5.357861E+01 8.923892E+01 7.116803E-01 5.357389E+01 - 1.310001E+01 3.000000E+01 3 1.076543E+02 1.634723E+00 1.076105E+02 3.071101E+00 - 1.310001E+01 3.000000E+01 4 1.958805E+02 8.921249E+01 2.692211E+00 1.958620E+02 - 1.310001E+01 3.000000E+01 5 5.571302E+02 8.954993E+01 4.376284E+00 5.571130E+02 - 1.310001E+01 3.000000E+01 6 3.779671E+02 -6.763905E-02 3.779669E+02 -4.461991E-01 - 1.310001E+01 6.000000E+01 1 5.336574E+01 8.955592E+01 4.136202E-01 5.336414E+01 - 1.310001E+01 6.000000E+01 2 9.819876E+01 8.923601E+01 1.309368E+00 9.819003E+01 - 1.310001E+01 6.000000E+01 3 1.142560E+02 1.699478E+00 1.142057E+02 3.388506E+00 - 1.310001E+01 6.000000E+01 4 3.712650E+02 8.923553E+01 4.953495E+00 3.712319E+02 - 1.310001E+01 6.000000E+01 5 3.389550E+02 8.955701E+01 2.620605E+00 3.389448E+02 - 1.310001E+01 6.000000E+01 6 4.002613E+02 -6.628826E-02 4.002610E+02 -4.630815E-01 - 1.310001E+01 9.000000E+01 1 5.778136E-06 -8.984689E+01 1.544170E-08 -5.778116E-06 - 1.310001E+01 9.000000E+01 2 1.166413E+02 8.923461E+01 1.558110E+00 1.166309E+02 - 1.310001E+01 9.000000E+01 3 1.177151E+02 1.732256E+00 1.176613E+02 3.558406E+00 - 1.310001E+01 9.000000E+01 4 4.478879E+02 8.924590E+01 5.894688E+00 4.478491E+02 - 1.310001E+01 9.000000E+01 5 2.327449E-04 -8.982745E+01 7.009148E-07 -2.327438E-04 - 1.310001E+01 9.000000E+01 6 3.538123E-05 1.799573E+02 -3.538122E-05 2.638610E-08 - 1.320001E+01 0.000000E+00 1 9.837684E+01 8.955502E+01 7.640185E-01 9.837387E+01 - 1.320001E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.320001E+01 0.000000E+00 3 1.058633E+02 1.580071E+00 1.058230E+02 2.919067E+00 - 1.320001E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.320001E+01 0.000000E+00 5 6.293903E+02 8.955421E+01 4.897017E+00 6.293712E+02 - 1.320001E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.320001E+01 3.000000E+01 1 8.729283E+01 8.955813E+01 6.731992E-01 8.729024E+01 - 1.320001E+01 3.000000E+01 2 5.320554E+01 8.925933E+01 6.877763E-01 5.320110E+01 - 1.320001E+01 3.000000E+01 3 1.089736E+02 1.610426E+00 1.089306E+02 3.062545E+00 - 1.320001E+01 3.000000E+01 4 1.941425E+02 8.923402E+01 2.595366E+00 1.941252E+02 - 1.320001E+01 3.000000E+01 5 5.596900E+02 8.955827E+01 4.314929E+00 5.596733E+02 - 1.320001E+01 3.000000E+01 6 3.708825E+02 -6.422561E-02 3.708823E+02 -4.157401E-01 - 1.320001E+01 6.000000E+01 1 5.293261E+01 8.956381E+01 4.029681E-01 5.293108E+01 - 1.320001E+01 6.000000E+01 2 9.738930E+01 8.925660E+01 1.263577E+00 9.738110E+01 - 1.320001E+01 6.000000E+01 3 1.154934E+02 1.672202E+00 1.154442E+02 3.370245E+00 - 1.320001E+01 6.000000E+01 4 3.673029E+02 8.925615E+01 4.768451E+00 3.672720E+02 - 1.320001E+01 6.000000E+01 5 3.400790E+02 8.956483E+01 2.582965E+00 3.400692E+02 - 1.320001E+01 6.000000E+01 6 3.922525E+02 -6.297272E-02 3.922523E+02 -4.311173E-01 - 1.320001E+01 9.000000E+01 1 5.725295E-06 -8.986151E+01 1.383912E-08 -5.725278E-06 - 1.320001E+01 9.000000E+01 2 1.156054E+02 8.925529E+01 1.502553E+00 1.155956E+02 - 1.320001E+01 9.000000E+01 3 1.189044E+02 1.703483E+00 1.188518E+02 3.534670E+00 - 1.320001E+01 9.000000E+01 4 4.427265E+02 8.926614E+01 5.670448E+00 4.426902E+02 - 1.320001E+01 9.000000E+01 5 2.311977E-04 -8.983286E+01 6.744531E-07 -2.311967E-04 - 1.320001E+01 9.000000E+01 6 3.465001E-05 1.799594E+02 -3.465001E-05 2.457063E-08 - 1.330001E+01 0.000000E+00 1 9.774033E+01 8.956340E+01 7.447913E-01 9.773750E+01 - 1.330001E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.330001E+01 0.000000E+00 3 1.071949E+02 1.557480E+00 1.071553E+02 2.913537E+00 - 1.330001E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.330001E+01 0.000000E+00 5 6.324617E+02 8.956264E+01 4.827824E+00 6.324432E+02 - 1.330001E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.330001E+01 3.000000E+01 1 8.668199E+01 8.956628E+01 6.561638E-01 8.667950E+01 - 1.330001E+01 3.000000E+01 2 5.283584E+01 8.927895E+01 6.649019E-01 5.283165E+01 - 1.330001E+01 3.000000E+01 3 1.102699E+02 1.586484E+00 1.102276E+02 3.052914E+00 - 1.330001E+01 3.000000E+01 4 1.924293E+02 8.925472E+01 2.502980E+00 1.924130E+02 - 1.330001E+01 3.000000E+01 5 5.620496E+02 8.956641E+01 4.253352E+00 5.620335E+02 - 1.330001E+01 3.000000E+01 6 3.639974E+02 -6.102650E-02 3.639972E+02 -3.876984E-01 - 1.330001E+01 6.000000E+01 1 5.250566E+01 8.957155E+01 3.926283E-01 5.250420E+01 - 1.330001E+01 6.000000E+01 2 9.659223E+01 8.927639E+01 1.219870E+00 9.658453E+01 - 1.330001E+01 6.000000E+01 3 1.167076E+02 1.645454E+00 1.166595E+02 3.351216E+00 - 1.330001E+01 6.000000E+01 4 3.634221E+02 8.927597E+01 4.592340E+00 3.633930E+02 - 1.330001E+01 6.000000E+01 5 3.411006E+02 8.957249E+01 2.545118E+00 3.410912E+02 - 1.330001E+01 6.000000E+01 6 3.844919E+02 -5.986314E-02 3.844917E+02 -4.017205E-01 - 1.330001E+01 9.000000E+01 1 5.673464E-06 -8.987523E+01 1.235477E-08 -5.673451E-06 - 1.330001E+01 9.000000E+01 2 1.145877E+02 8.927516E+01 1.449587E+00 1.145785E+02 - 1.330001E+01 9.000000E+01 3 1.200731E+02 1.675291E+00 1.200218E+02 3.510358E+00 - 1.330001E+01 9.000000E+01 4 4.376828E+02 8.928558E+01 5.457304E+00 4.376488E+02 - 1.330001E+01 9.000000E+01 5 2.296706E-04 -8.983805E+01 6.491774E-07 -2.296697E-04 - 1.330001E+01 9.000000E+01 6 3.394248E-05 1.799613E+02 -3.394248E-05 2.290062E-08 - 1.340001E+01 0.000000E+00 1 9.710779E+01 8.957156E+01 7.261354E-01 9.710507E+01 - 1.340001E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.340001E+01 0.000000E+00 3 1.085035E+02 1.535164E+00 1.084645E+02 2.906857E+00 - 1.340001E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.340001E+01 0.000000E+00 5 6.353191E+02 8.957086E+01 4.758424E+00 6.353013E+02 - 1.340001E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.340001E+01 3.000000E+01 1 8.607747E+01 8.957423E+01 6.396378E-01 8.607509E+01 - 1.340001E+01 3.000000E+01 2 5.246952E+01 8.929783E+01 6.430091E-01 5.246558E+01 - 1.340001E+01 3.000000E+01 3 1.115434E+02 1.562870E+00 1.115019E+02 3.042217E+00 - 1.340001E+01 3.000000E+01 4 1.907394E+02 8.927460E+01 2.414806E+00 1.907242E+02 - 1.340001E+01 3.000000E+01 5 5.642354E+02 8.957436E+01 4.191593E+00 5.642198E+02 - 1.340001E+01 3.000000E+01 6 3.573062E+02 -5.802537E-02 3.573061E+02 -3.618560E-01 - 1.340001E+01 6.000000E+01 1 5.208547E+01 8.957913E+01 3.825932E-01 5.208406E+01 - 1.340001E+01 6.000000E+01 2 9.580726E+01 8.929543E+01 1.178136E+00 9.580002E+01 - 1.340001E+01 6.000000E+01 3 1.179009E+02 1.619188E+00 1.178538E+02 3.331455E+00 - 1.340001E+01 6.000000E+01 4 3.596194E+02 8.929503E+01 4.424686E+00 3.595922E+02 - 1.340001E+01 6.000000E+01 5 3.420238E+02 8.957999E+01 2.507203E+00 3.420146E+02 - 1.340001E+01 6.000000E+01 6 3.769714E+02 -5.694431E-02 3.769712E+02 -3.746589E-01 - 1.340001E+01 9.000000E+01 1 5.622613E-06 -8.988811E+01 1.097981E-08 -5.622602E-06 - 1.340001E+01 9.000000E+01 2 1.135885E+02 8.929427E+01 1.399070E+00 1.135799E+02 - 1.340001E+01 9.000000E+01 3 1.212212E+02 1.647668E+00 1.211711E+02 3.485506E+00 - 1.340001E+01 9.000000E+01 4 4.327518E+02 8.930429E+01 5.254560E+00 4.327199E+02 - 1.340001E+01 9.000000E+01 5 2.281604E-04 -8.984305E+01 6.250299E-07 -2.281596E-04 - 1.340001E+01 9.000000E+01 6 3.325758E-05 1.799632E+02 -3.325758E-05 2.136287E-08 - 1.350002E+01 0.000000E+00 1 9.647980E+01 8.957951E+01 7.080393E-01 9.647720E+01 - 1.350002E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.350002E+01 0.000000E+00 3 1.097896E+02 1.513120E+00 1.097513E+02 2.899089E+00 - 1.350002E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.350002E+01 0.000000E+00 5 6.379564E+02 8.957887E+01 4.689035E+00 6.379391E+02 - 1.350002E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.350002E+01 3.000000E+01 1 8.547876E+01 8.958200E+01 6.236005E-01 8.547649E+01 - 1.350002E+01 3.000000E+01 2 5.210656E+01 8.931599E+01 6.220471E-01 5.210284E+01 - 1.350002E+01 3.000000E+01 3 1.127945E+02 1.539611E+00 1.127538E+02 3.030568E+00 - 1.350002E+01 3.000000E+01 4 1.890742E+02 8.929372E+01 2.330631E+00 1.890598E+02 - 1.350002E+01 3.000000E+01 5 5.662357E+02 8.958212E+01 4.129840E+00 5.662206E+02 - 1.350002E+01 3.000000E+01 6 3.508008E+02 -5.520827E-02 3.508006E+02 -3.380197E-01 - 1.350002E+01 6.000000E+01 1 5.167117E+01 8.958656E+01 3.728577E-01 5.166982E+01 - 1.350002E+01 6.000000E+01 2 9.503458E+01 8.931373E+01 1.138269E+00 9.502776E+01 - 1.350002E+01 6.000000E+01 3 1.190729E+02 1.593426E+00 1.190269E+02 3.311053E+00 - 1.350002E+01 6.000000E+01 4 3.558934E+02 8.931335E+01 4.264977E+00 3.558679E+02 - 1.350002E+01 6.000000E+01 5 3.428521E+02 8.958733E+01 2.469314E+00 3.428432E+02 - 1.350002E+01 6.000000E+01 6 3.696781E+02 -5.420265E-02 3.696780E+02 -3.497209E-01 - 1.350002E+01 9.000000E+01 1 5.572710E-06 -8.990021E+01 9.706190E-09 -5.572701E-06 - 1.350002E+01 9.000000E+01 2 1.126070E+02 8.931264E+01 1.350871E+00 1.125989E+02 - 1.350002E+01 9.000000E+01 3 1.223481E+02 1.620644E+00 1.222992E+02 3.460225E+00 - 1.350002E+01 9.000000E+01 4 4.279327E+02 8.932228E+01 5.061672E+00 4.279028E+02 - 1.350002E+01 9.000000E+01 5 2.266682E-04 -8.984784E+01 6.019519E-07 -2.266674E-04 - 1.350002E+01 9.000000E+01 6 3.259435E-05 1.799649E+02 -3.259435E-05 1.994554E-08 - 1.360002E+01 0.000000E+00 1 9.585638E+01 8.958727E+01 6.904913E-01 9.585390E+01 - 1.360002E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.360002E+01 0.000000E+00 3 1.110531E+02 1.491375E+00 1.110155E+02 2.890318E+00 - 1.360002E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.360002E+01 0.000000E+00 5 6.404005E+02 8.958669E+01 4.619687E+00 6.403839E+02 - 1.360002E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.360002E+01 3.000000E+01 1 8.488598E+01 8.958958E+01 6.080474E-01 8.488380E+01 - 1.360002E+01 3.000000E+01 2 5.174720E+01 8.933347E+01 6.019685E-01 5.174369E+01 - 1.360002E+01 3.000000E+01 3 1.140237E+02 1.516720E+00 1.139837E+02 3.018055E+00 - 1.360002E+01 3.000000E+01 4 1.874324E+02 8.931211E+01 2.250251E+00 1.874189E+02 - 1.360002E+01 3.000000E+01 5 5.680785E+02 8.958969E+01 4.068121E+00 5.680639E+02 - 1.360002E+01 3.000000E+01 6 3.444746E+02 -5.256160E-02 3.444745E+02 -3.160116E-01 - 1.360002E+01 6.000000E+01 1 5.126316E+01 8.959382E+01 3.634132E-01 5.126187E+01 - 1.360002E+01 6.000000E+01 2 9.427340E+01 8.933135E+01 1.100167E+00 9.426698E+01 - 1.360002E+01 6.000000E+01 3 1.202243E+02 1.568163E+00 1.201793E+02 3.290081E+00 - 1.360002E+01 6.000000E+01 4 3.522416E+02 8.933100E+01 4.112770E+00 3.522176E+02 - 1.360002E+01 6.000000E+01 5 3.435918E+02 8.959454E+01 2.431463E+00 3.435832E+02 - 1.360002E+01 6.000000E+01 6 3.626053E+02 -5.162517E-02 3.626052E+02 -3.267179E-01 - 1.360002E+01 9.000000E+01 1 5.523750E-06 -8.991156E+01 8.526428E-09 -5.523743E-06 - 1.360002E+01 9.000000E+01 2 1.116428E+02 8.933032E+01 1.304857E+00 1.116352E+02 - 1.360002E+01 9.000000E+01 3 1.234563E+02 1.594159E+00 1.234086E+02 3.434522E+00 - 1.360002E+01 9.000000E+01 4 4.232200E+02 8.933959E+01 4.878055E+00 4.231919E+02 - 1.360002E+01 9.000000E+01 5 2.251913E-04 -8.985246E+01 5.798990E-07 -2.251906E-04 - 1.360002E+01 9.000000E+01 6 3.195180E-05 1.799666E+02 -3.195180E-05 1.863791E-08 - 1.370002E+01 0.000000E+00 1 9.523803E+01 8.959483E+01 6.734699E-01 9.523565E+01 - 1.370002E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.370002E+01 0.000000E+00 3 1.122953E+02 1.469924E+00 1.122583E+02 2.880620E+00 - 1.370002E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.370002E+01 0.000000E+00 5 6.426550E+02 8.959429E+01 4.550618E+00 6.426389E+02 - 1.370002E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.370002E+01 3.000000E+01 1 8.429946E+01 8.959698E+01 5.929583E-01 8.429738E+01 - 1.370002E+01 3.000000E+01 2 5.139131E+01 8.935030E+01 5.827336E-01 5.138801E+01 - 1.370002E+01 3.000000E+01 3 1.152318E+02 1.494177E+00 1.151926E+02 3.004710E+00 - 1.370002E+01 3.000000E+01 4 1.858150E+02 8.932980E+01 2.173457E+00 1.858023E+02 - 1.370002E+01 3.000000E+01 5 5.697527E+02 8.959708E+01 4.006640E+00 5.697386E+02 - 1.370002E+01 3.000000E+01 6 3.383217E+02 -5.007343E-02 3.383216E+02 -2.956749E-01 - 1.370002E+01 6.000000E+01 1 5.086125E+01 8.960093E+01 3.542526E-01 5.086002E+01 - 1.370002E+01 6.000000E+01 2 9.352402E+01 8.934830E+01 1.063745E+00 9.351797E+01 - 1.370002E+01 6.000000E+01 3 1.213550E+02 1.543401E+00 1.213110E+02 3.268597E+00 - 1.370002E+01 6.000000E+01 4 3.486605E+02 8.934798E+01 3.967686E+00 3.486379E+02 - 1.370002E+01 6.000000E+01 5 3.442470E+02 8.960159E+01 2.393731E+00 3.442386E+02 - 1.370002E+01 6.000000E+01 6 3.557429E+02 -4.920064E-02 3.557427E+02 -3.054811E-01 - 1.370002E+01 9.000000E+01 1 5.475670E-06 -8.992222E+01 7.433633E-09 -5.475665E-06 - 1.370002E+01 9.000000E+01 2 1.106953E+02 8.934734E+01 1.260907E+00 1.106881E+02 - 1.370002E+01 9.000000E+01 3 1.245441E+02 1.568268E+00 1.244974E+02 3.408525E+00 - 1.370002E+01 9.000000E+01 4 4.186085E+02 8.935625E+01 4.703158E+00 4.185821E+02 - 1.370002E+01 9.000000E+01 5 2.237349E-04 -8.985690E+01 5.588086E-07 -2.237342E-04 - 1.370002E+01 9.000000E+01 6 3.132915E-05 1.799681E+02 -3.132915E-05 1.743039E-08 - 1.380002E+01 0.000000E+00 1 9.462417E+01 8.960220E+01 6.569591E-01 9.462189E+01 - 1.380002E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.380002E+01 0.000000E+00 3 1.135152E+02 1.448807E+00 1.134789E+02 2.870092E+00 - 1.380002E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.380002E+01 0.000000E+00 5 6.447154E+02 8.960169E+01 4.481882E+00 6.446998E+02 - 1.380002E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.380002E+01 3.000000E+01 1 8.371916E+01 8.960421E+01 5.783236E-01 8.371716E+01 - 1.380002E+01 3.000000E+01 2 5.103907E+01 8.936652E+01 5.642987E-01 5.103595E+01 - 1.380002E+01 3.000000E+01 3 1.164179E+02 1.472036E+00 1.163795E+02 2.990666E+00 - 1.380002E+01 3.000000E+01 4 1.842216E+02 8.934684E+01 2.100059E+00 1.842097E+02 - 1.380002E+01 3.000000E+01 5 5.712762E+02 8.960429E+01 3.945374E+00 5.712626E+02 - 1.380002E+01 3.000000E+01 6 3.323361E+02 -4.773237E-02 3.323359E+02 -2.768648E-01 - 1.380002E+01 6.000000E+01 1 5.046520E+01 8.960788E+01 3.453674E-01 5.046402E+01 - 1.380002E+01 6.000000E+01 2 9.278586E+01 8.936463E+01 1.028909E+00 9.278015E+01 - 1.380002E+01 6.000000E+01 3 1.224657E+02 1.519127E+00 1.224227E+02 3.246646E+00 - 1.380002E+01 6.000000E+01 4 3.451521E+02 8.936433E+01 3.829268E+00 3.451308E+02 - 1.380002E+01 6.000000E+01 5 3.448199E+02 8.960848E+01 2.356209E+00 3.448118E+02 - 1.380002E+01 6.000000E+01 6 3.490835E+02 -4.691823E-02 3.490834E+02 -2.858566E-01 - 1.380002E+01 9.000000E+01 1 5.428473E-06 -8.993223E+01 6.421432E-09 -5.428470E-06 - 1.380002E+01 9.000000E+01 2 1.097644E+02 8.936373E+01 1.218917E+00 1.097577E+02 - 1.380002E+01 9.000000E+01 3 1.256127E+02 1.542922E+00 1.255671E+02 3.382223E+00 - 1.380002E+01 9.000000E+01 4 4.140994E+02 8.937231E+01 4.536509E+00 4.140746E+02 - 1.380002E+01 9.000000E+01 5 2.222941E-04 -8.986117E+01 5.386522E-07 -2.222934E-04 - 1.380002E+01 9.000000E+01 6 3.072555E-05 1.799696E+02 -3.072555E-05 1.631426E-08 - 1.390002E+01 0.000000E+00 1 9.401585E+01 8.960938E+01 6.409466E-01 9.401367E+01 - 1.390002E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.390002E+01 0.000000E+00 3 1.147139E+02 1.428002E+00 1.146783E+02 2.858756E+00 - 1.390002E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.390002E+01 0.000000E+00 5 6.466078E+02 8.960892E+01 4.413477E+00 6.465928E+02 - 1.390002E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.390002E+01 3.000000E+01 1 8.314499E+01 8.961125E+01 5.641295E-01 8.314307E+01 - 1.390002E+01 3.000000E+01 2 5.069037E+01 8.938213E+01 5.466266E-01 5.068742E+01 - 1.390002E+01 3.000000E+01 3 1.175835E+02 1.450251E+00 1.175459E+02 2.975916E+00 - 1.390002E+01 3.000000E+01 4 1.826507E+02 8.936324E+01 2.029879E+00 1.826394E+02 - 1.390002E+01 3.000000E+01 5 5.726527E+02 8.961134E+01 3.884524E+00 5.726395E+02 - 1.390002E+01 3.000000E+01 6 3.265115E+02 -4.552826E-02 3.265114E+02 -2.594519E-01 - 1.390002E+01 6.000000E+01 1 5.007525E+01 8.961469E+01 3.367526E-01 5.007412E+01 - 1.390002E+01 6.000000E+01 2 9.205920E+01 8.938036E+01 9.955786E-01 9.205381E+01 - 1.390002E+01 6.000000E+01 3 1.235569E+02 1.495332E+00 1.235148E+02 3.224281E+00 - 1.390002E+01 6.000000E+01 4 3.417121E+02 8.938007E+01 3.697199E+00 3.416921E+02 - 1.390002E+01 6.000000E+01 5 3.453161E+02 8.961524E+01 2.318897E+00 3.453083E+02 - 1.390002E+01 6.000000E+01 6 3.426181E+02 -4.476813E-02 3.426180E+02 -2.677051E-01 - 1.390002E+01 9.000000E+01 1 5.382105E-06 -8.994162E+01 5.483923E-09 -5.382103E-06 - 1.390002E+01 9.000000E+01 2 1.088496E+02 8.937951E+01 1.178782E+00 1.088432E+02 - 1.390002E+01 9.000000E+01 3 1.266628E+02 1.518117E+00 1.266184E+02 3.355685E+00 - 1.390002E+01 9.000000E+01 4 4.096870E+02 8.938776E+01 4.377617E+00 4.096636E+02 - 1.390002E+01 9.000000E+01 5 2.208703E-04 -8.986527E+01 5.193689E-07 -2.208697E-04 - 1.390002E+01 9.000000E+01 6 3.014010E-05 1.799709E+02 -3.014010E-05 1.528172E-08 - 1.400002E+01 0.000000E+00 1 9.341292E+01 8.961639E+01 6.254156E-01 9.341083E+01 - 1.400002E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.400002E+01 0.000000E+00 3 1.158918E+02 1.407507E+00 1.158568E+02 2.846669E+00 - 1.400002E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.400002E+01 0.000000E+00 5 6.483340E+02 8.961596E+01 4.345604E+00 6.483194E+02 - 1.400002E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.400002E+01 3.000000E+01 1 8.257697E+01 8.961813E+01 5.503611E-01 8.257514E+01 - 1.400002E+01 3.000000E+01 2 5.034540E+01 8.939719E+01 5.296783E-01 5.034261E+01 - 1.400002E+01 3.000000E+01 3 1.187293E+02 1.428819E+00 1.186924E+02 2.960516E+00 - 1.400002E+01 3.000000E+01 4 1.811027E+02 8.937902E+01 1.962768E+00 1.810921E+02 - 1.400002E+01 3.000000E+01 5 5.738928E+02 8.961822E+01 3.824070E+00 5.738800E+02 - 1.400002E+01 3.000000E+01 6 3.208421E+02 -4.345161E-02 3.208420E+02 -2.433182E-01 - 1.400002E+01 6.000000E+01 1 4.969078E+01 8.962134E+01 3.283996E-01 4.968969E+01 - 1.400002E+01 6.000000E+01 2 9.134313E+01 8.939552E+01 9.636754E-01 9.133805E+01 - 1.400002E+01 6.000000E+01 3 1.246293E+02 1.472011E+00 1.245882E+02 3.201554E+00 - 1.400002E+01 6.000000E+01 4 3.383389E+02 8.939524E+01 3.571121E+00 3.383200E+02 - 1.400002E+01 6.000000E+01 5 3.457374E+02 8.962184E+01 2.281882E+00 3.457299E+02 - 1.400002E+01 6.000000E+01 6 3.363388E+02 -4.274136E-02 3.363387E+02 -2.509011E-01 - 1.400002E+01 9.000000E+01 1 5.336591E-06 -8.995045E+01 4.615730E-09 -5.336589E-06 - 1.400002E+01 9.000000E+01 2 1.079504E+02 8.939471E+01 1.140400E+00 1.079444E+02 - 1.400002E+01 9.000000E+01 3 1.276943E+02 1.493816E+00 1.276509E+02 3.328869E+00 - 1.400002E+01 9.000000E+01 4 4.053708E+02 8.940267E+01 4.226071E+00 4.053488E+02 - 1.400002E+01 9.000000E+01 5 2.194629E-04 -8.986922E+01 5.009261E-07 -2.194623E-04 - 1.400002E+01 9.000000E+01 6 2.957223E-05 1.799722E+02 -2.957222E-05 1.432562E-08 - 1.410002E+01 0.000000E+00 1 9.281465E+01 8.962321E+01 6.103522E-01 9.281264E+01 - 1.410002E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.410002E+01 0.000000E+00 3 1.170500E+02 1.387336E+00 1.170157E+02 2.833923E+00 - 1.410002E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.410002E+01 0.000000E+00 5 6.498899E+02 8.962283E+01 4.278166E+00 6.498758E+02 - 1.410002E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.410002E+01 3.000000E+01 1 8.201529E+01 8.962485E+01 5.370075E-01 8.201353E+01 - 1.410002E+01 3.000000E+01 2 5.000404E+01 8.941170E+01 5.134202E-01 5.000141E+01 - 1.410002E+01 3.000000E+01 3 1.198546E+02 1.407775E+00 1.198184E+02 2.944569E+00 - 1.410002E+01 3.000000E+01 4 1.795791E+02 8.939424E+01 1.898557E+00 1.795691E+02 - 1.410002E+01 3.000000E+01 5 5.749977E+02 8.962492E+01 3.764142E+00 5.749854E+02 - 1.410002E+01 3.000000E+01 6 3.153224E+02 -4.149376E-02 3.153224E+02 -2.283574E-01 - 1.410002E+01 6.000000E+01 1 4.931218E+01 8.962784E+01 3.202994E-01 4.931113E+01 - 1.410002E+01 6.000000E+01 2 9.063799E+01 8.941013E+01 9.331260E-01 9.063319E+01 - 1.410002E+01 6.000000E+01 3 1.256827E+02 1.449176E+00 1.256425E+02 3.178539E+00 - 1.410002E+01 6.000000E+01 4 3.350314E+02 8.940987E+01 3.450684E+00 3.350136E+02 - 1.410002E+01 6.000000E+01 5 3.460934E+02 8.962830E+01 2.245189E+00 3.460861E+02 - 1.410002E+01 6.000000E+01 6 3.302390E+02 -4.082947E-02 3.302389E+02 -2.353311E-01 - 1.410002E+01 9.000000E+01 1 5.291866E-06 -8.995872E+01 3.811751E-09 -5.291865E-06 - 1.410002E+01 9.000000E+01 2 1.070666E+02 8.940937E+01 1.103676E+00 1.070609E+02 - 1.410002E+01 9.000000E+01 3 1.287075E+02 1.470075E+00 1.286651E+02 3.301970E+00 - 1.410002E+01 9.000000E+01 4 4.011458E+02 8.941704E+01 4.081447E+00 4.011251E+02 - 1.410002E+01 9.000000E+01 5 2.180719E-04 -8.987302E+01 4.832769E-07 -2.180714E-04 - 1.410002E+01 9.000000E+01 6 2.902108E-05 1.799735E+02 -2.902108E-05 1.343956E-08 - 1.420002E+01 0.000000E+00 1 9.222209E+01 8.962988E+01 5.957394E-01 9.222017E+01 - 1.420002E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.420002E+01 0.000000E+00 3 1.181887E+02 1.367490E+00 1.181551E+02 2.820566E+00 - 1.420002E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.420002E+01 0.000000E+00 5 6.512989E+02 8.962952E+01 4.211454E+00 6.512853E+02 - 1.420002E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.420002E+01 3.000000E+01 1 8.145914E+01 8.963139E+01 5.240567E-01 8.145745E+01 - 1.420002E+01 3.000000E+01 2 4.966637E+01 8.942570E+01 4.978178E-01 4.966388E+01 - 1.420002E+01 3.000000E+01 3 1.209608E+02 1.387103E+00 1.209254E+02 2.928117E+00 - 1.420002E+01 3.000000E+01 4 1.780764E+02 8.940891E+01 1.837086E+00 1.780669E+02 - 1.420002E+01 3.000000E+01 5 5.759803E+02 8.963148E+01 3.704710E+00 5.759684E+02 - 1.420002E+01 3.000000E+01 6 3.099483E+02 -3.964655E-02 3.099482E+02 -2.144727E-01 - 1.420002E+01 6.000000E+01 1 4.893873E+01 8.963420E+01 3.124456E-01 4.893773E+01 - 1.420002E+01 6.000000E+01 2 8.994339E+01 8.942421E+01 9.038602E-01 8.993885E+01 - 1.420002E+01 6.000000E+01 3 1.267177E+02 1.426796E+00 1.266785E+02 3.155236E+00 - 1.420002E+01 6.000000E+01 4 3.317870E+02 8.942397E+01 3.335597E+00 3.317702E+02 - 1.420002E+01 6.000000E+01 5 3.463760E+02 8.963463E+01 2.208806E+00 3.463690E+02 - 1.420002E+01 6.000000E+01 6 3.243127E+02 -3.902475E-02 3.243127E+02 -2.208927E-01 - 1.420002E+01 9.000000E+01 1 5.247934E-06 -8.996651E+01 3.067469E-09 -5.247933E-06 - 1.420002E+01 9.000000E+01 2 1.061972E+02 8.942349E+01 1.068530E+00 1.061918E+02 - 1.420002E+01 9.000000E+01 3 1.297040E+02 1.446820E+00 1.296626E+02 3.274906E+00 - 1.420002E+01 9.000000E+01 4 3.970090E+02 8.943089E+01 3.943370E+00 3.969894E+02 - 1.420002E+01 9.000000E+01 5 2.166960E-04 -8.987669E+01 4.663885E-07 -2.166955E-04 - 1.420002E+01 9.000000E+01 6 2.848610E-05 1.799746E+02 -2.848610E-05 1.261768E-08 - 1.430002E+01 0.000000E+00 1 9.163473E+01 8.963637E+01 5.815630E-01 9.163288E+01 - 1.430002E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.430002E+01 0.000000E+00 3 1.193063E+02 1.347985E+00 1.192732E+02 2.806632E+00 - 1.430002E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.430002E+01 0.000000E+00 5 6.525556E+02 8.963602E+01 4.145412E+00 6.525424E+02 - 1.430002E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.430002E+01 3.000000E+01 1 8.090956E+01 8.963779E+01 5.114934E-01 8.090794E+01 - 1.430002E+01 3.000000E+01 2 4.933223E+01 8.943921E+01 4.828393E-01 4.932987E+01 - 1.430002E+01 3.000000E+01 3 1.220479E+02 1.366797E+00 1.220132E+02 2.911189E+00 - 1.430002E+01 3.000000E+01 4 1.765970E+02 8.942306E+01 1.778233E+00 1.765881E+02 - 1.430002E+01 3.000000E+01 5 5.768289E+02 8.963786E+01 3.645904E+00 5.768173E+02 - 1.430002E+01 3.000000E+01 6 3.047135E+02 -3.790264E-02 3.047134E+02 -2.015758E-01 - 1.430002E+01 6.000000E+01 1 4.857093E+01 8.964041E+01 3.048303E-01 4.856997E+01 - 1.430002E+01 6.000000E+01 2 8.925934E+01 8.943781E+01 8.758137E-01 8.925504E+01 - 1.430002E+01 6.000000E+01 3 1.277345E+02 1.404871E+00 1.276961E+02 3.131686E+00 - 1.430002E+01 6.000000E+01 4 3.286065E+02 8.943757E+01 3.225616E+00 3.285907E+02 - 1.430002E+01 6.000000E+01 5 3.465981E+02 8.964080E+01 2.172868E+00 3.465913E+02 - 1.430002E+01 6.000000E+01 6 3.185517E+02 -3.732009E-02 3.185517E+02 -2.074914E-01 - 1.430002E+01 9.000000E+01 1 5.204746E-06 -8.997382E+01 2.378467E-09 -5.204746E-06 - 1.430002E+01 9.000000E+01 2 1.053429E+02 8.943713E+01 1.034876E+00 1.053378E+02 - 1.430002E+01 9.000000E+01 3 1.306822E+02 1.424090E+00 1.306419E+02 3.247781E+00 - 1.430002E+01 9.000000E+01 4 3.929597E+02 8.944426E+01 3.811475E+00 3.929412E+02 - 1.430002E+01 9.000000E+01 5 2.153368E-04 -8.988021E+01 4.502167E-07 -2.153363E-04 - 1.430002E+01 9.000000E+01 6 2.796662E-05 1.799757E+02 -2.796661E-05 1.185471E-08 - 1.440002E+01 0.000000E+00 1 9.105280E+01 8.964269E+01 5.678107E-01 9.105103E+01 - 1.440002E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.440002E+01 0.000000E+00 3 1.204055E+02 1.328791E+00 1.203731E+02 2.792167E+00 - 1.440002E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.440002E+01 0.000000E+00 5 6.536740E+02 8.964238E+01 4.079990E+00 6.536613E+02 - 1.440002E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.440002E+01 3.000000E+01 1 8.036610E+01 8.964403E+01 4.993050E-01 8.036456E+01 - 1.440002E+01 3.000000E+01 2 4.900182E+01 8.945224E+01 4.684564E-01 4.899958E+01 - 1.440002E+01 3.000000E+01 3 1.231159E+02 1.346855E+00 1.230819E+02 2.893824E+00 - 1.440002E+01 3.000000E+01 4 1.751390E+02 8.943670E+01 1.721862E+00 1.751306E+02 - 1.440002E+01 3.000000E+01 5 5.775671E+02 8.964409E+01 3.587728E+00 5.775560E+02 - 1.440002E+01 3.000000E+01 6 2.996143E+02 -3.625504E-02 2.996142E+02 -1.895868E-01 - 1.440002E+01 6.000000E+01 1 4.820866E+01 8.964648E+01 2.974450E-01 4.820774E+01 - 1.440002E+01 6.000000E+01 2 8.858540E+01 8.945092E+01 8.489271E-01 8.858134E+01 - 1.440002E+01 6.000000E+01 3 1.287342E+02 1.383388E+00 1.286967E+02 3.107944E+00 - 1.440002E+01 6.000000E+01 4 3.254849E+02 8.945070E+01 3.120404E+00 3.254700E+02 - 1.440002E+01 6.000000E+01 5 3.467580E+02 8.964685E+01 2.137307E+00 3.467514E+02 - 1.440002E+01 6.000000E+01 6 3.129503E+02 -3.570894E-02 3.129503E+02 -1.950427E-01 - 1.440002E+01 9.000000E+01 1 5.162310E-06 -8.998068E+01 1.740849E-09 -5.162309E-06 - 1.440002E+01 9.000000E+01 2 1.045026E+02 8.945028E+01 1.002634E+00 1.044978E+02 - 1.440002E+01 9.000000E+01 3 1.316441E+02 1.401820E+00 1.316047E+02 3.220534E+00 - 1.440002E+01 9.000000E+01 4 3.889918E+02 8.945715E+01 3.685435E+00 3.889743E+02 - 1.440002E+01 9.000000E+01 5 2.139940E-04 -8.988361E+01 4.347340E-07 -2.139936E-04 - 1.440002E+01 9.000000E+01 6 2.746197E-05 1.799767E+02 -2.746197E-05 1.114580E-08 - 1.450002E+01 0.000000E+00 1 9.047619E+01 8.964887E+01 5.544686E-01 9.047449E+01 - 1.450002E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.450002E+01 0.000000E+00 3 1.214867E+02 1.309920E+00 1.214549E+02 2.777238E+00 - 1.450002E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.450002E+01 0.000000E+00 5 6.546560E+02 8.964857E+01 4.015304E+00 6.546437E+02 - 1.450002E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.450002E+01 3.000000E+01 1 7.982861E+01 8.965012E+01 4.874841E-01 7.982712E+01 - 1.450002E+01 3.000000E+01 2 4.867495E+01 8.946483E+01 4.546393E-01 4.867282E+01 - 1.450002E+01 3.000000E+01 3 1.241655E+02 1.327266E+00 1.241322E+02 2.876056E+00 - 1.450002E+01 3.000000E+01 4 1.737033E+02 8.944986E+01 1.667834E+00 1.736953E+02 - 1.450002E+01 3.000000E+01 5 5.781986E+02 8.965018E+01 3.530241E+00 5.781878E+02 - 1.450002E+01 3.000000E+01 6 2.946451E+02 -3.469753E-02 2.946450E+02 -1.784330E-01 - 1.450002E+01 6.000000E+01 1 4.785126E+01 8.965242E+01 2.902845E-01 4.785038E+01 - 1.450002E+01 6.000000E+01 2 8.792124E+01 8.946358E+01 8.231394E-01 8.791739E+01 - 1.450002E+01 6.000000E+01 3 1.297157E+02 1.362360E+00 1.296790E+02 3.084047E+00 - 1.450002E+01 6.000000E+01 4 3.224222E+02 8.946337E+01 3.019745E+00 3.224081E+02 - 1.450002E+01 6.000000E+01 5 3.468647E+02 8.965275E+01 2.102222E+00 3.468583E+02 - 1.450002E+01 6.000000E+01 6 3.075024E+02 -3.418531E-02 3.075024E+02 -1.834701E-01 - 1.450002E+01 9.000000E+01 1 5.120589E-06 -8.998712E+01 1.150930E-09 -5.120589E-06 - 1.450002E+01 9.000000E+01 2 1.036764E+02 8.946297E+01 9.717385E-01 1.036719E+02 - 1.450002E+01 9.000000E+01 3 1.325885E+02 1.380049E+00 1.325500E+02 3.193270E+00 - 1.450002E+01 9.000000E+01 4 3.851090E+02 8.946960E+01 3.564947E+00 3.850925E+02 - 1.450002E+01 9.000000E+01 5 2.126657E-04 -8.988687E+01 4.199055E-07 -2.126653E-04 - 1.450002E+01 9.000000E+01 6 2.697163E-05 1.799777E+02 -2.697163E-05 1.048662E-08 - 1.460002E+01 0.000000E+00 1 8.990534E+01 8.965489E+01 5.415218E-01 8.990371E+01 - 1.460002E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.460002E+01 0.000000E+00 3 1.225487E+02 1.291372E+00 1.225176E+02 2.761854E+00 - 1.460002E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.460002E+01 0.000000E+00 5 6.555183E+02 8.965462E+01 3.951430E+00 6.555064E+02 - 1.460002E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.460002E+01 3.000000E+01 1 7.929740E+01 8.965606E+01 4.760134E-01 7.929597E+01 - 1.460002E+01 3.000000E+01 2 4.835192E+01 8.947699E+01 4.413630E-01 4.834990E+01 - 1.460002E+01 3.000000E+01 3 1.251974E+02 1.308041E+00 1.251648E+02 2.857962E+00 - 1.460002E+01 3.000000E+01 4 1.722886E+02 8.946256E+01 1.616053E+00 1.722810E+02 - 1.460002E+01 3.000000E+01 5 5.787271E+02 8.965612E+01 3.473412E+00 5.787167E+02 - 1.460002E+01 3.000000E+01 6 2.898024E+02 -3.322428E-02 2.898023E+02 -1.680486E-01 - 1.460002E+01 6.000000E+01 1 4.749929E+01 8.965822E+01 2.833395E-01 4.749844E+01 - 1.460002E+01 6.000000E+01 2 8.726714E+01 8.947580E+01 7.983971E-01 8.726349E+01 - 1.460002E+01 6.000000E+01 3 1.306810E+02 1.341744E+00 1.306452E+02 3.059990E+00 - 1.460002E+01 6.000000E+01 4 3.194173E+02 8.947560E+01 2.923404E+00 3.194039E+02 - 1.460002E+01 6.000000E+01 5 3.469147E+02 8.965853E+01 2.067532E+00 3.469086E+02 - 1.460002E+01 6.000000E+01 6 3.022028E+02 -3.274328E-02 3.022027E+02 -1.727022E-01 - 1.460002E+01 9.000000E+01 1 5.079569E-06 -8.999317E+01 6.052689E-10 -5.079569E-06 - 1.460002E+01 9.000000E+01 2 1.028633E+02 8.947523E+01 9.421161E-01 1.028589E+02 - 1.460002E+01 9.000000E+01 3 1.335172E+02 1.358744E+00 1.334797E+02 3.166005E+00 - 1.460002E+01 9.000000E+01 4 3.813017E+02 8.948164E+01 3.449689E+00 3.812861E+02 - 1.460002E+01 9.000000E+01 5 2.113527E-04 -8.989001E+01 4.056980E-07 -2.113523E-04 - 1.460002E+01 9.000000E+01 6 2.649499E-05 1.799787E+02 -2.649499E-05 9.873189E-09 - 1.470002E+01 0.000000E+00 1 8.934002E+01 8.966077E+01 5.289591E-01 8.933846E+01 - 1.470002E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.470002E+01 0.000000E+00 3 1.235926E+02 1.273147E+00 1.235621E+02 2.746077E+00 - 1.470002E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.470002E+01 0.000000E+00 5 6.562511E+02 8.966051E+01 3.888381E+00 6.562396E+02 - 1.470002E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.470002E+01 3.000000E+01 1 7.877178E+01 8.966186E+01 4.648857E-01 7.877041E+01 - 1.470002E+01 3.000000E+01 2 4.803225E+01 8.948874E+01 4.285992E-01 4.803034E+01 - 1.470002E+01 3.000000E+01 3 1.262114E+02 1.289177E+00 1.261794E+02 2.839566E+00 - 1.470002E+01 3.000000E+01 4 1.708953E+02 8.947484E+01 1.566375E+00 1.708882E+02 - 1.470002E+01 3.000000E+01 5 5.791414E+02 8.966192E+01 3.417307E+00 5.791313E+02 - 1.470002E+01 3.000000E+01 6 2.850809E+02 -3.182985E-02 2.850809E+02 -1.583726E-01 - 1.470002E+01 6.000000E+01 1 4.715218E+01 8.966389E+01 2.766046E-01 4.715137E+01 - 1.470002E+01 6.000000E+01 2 8.662259E+01 8.948761E+01 7.746499E-01 8.661913E+01 - 1.470002E+01 6.000000E+01 3 1.316294E+02 1.321567E+00 1.315944E+02 3.035854E+00 - 1.470002E+01 6.000000E+01 4 3.164691E+02 8.948743E+01 2.831140E+00 3.164564E+02 - 1.470002E+01 6.000000E+01 5 3.469092E+02 8.966417E+01 2.033355E+00 3.469033E+02 - 1.470002E+01 6.000000E+01 6 2.970460E+02 -3.137781E-02 2.970460E+02 -1.626761E-01 - 1.470002E+01 9.000000E+01 1 5.039243E-06 -8.999886E+01 1.007715E-10 -5.039243E-06 - 1.470002E+01 9.000000E+01 2 1.020634E+02 8.948706E+01 9.137036E-01 1.020593E+02 - 1.470002E+01 9.000000E+01 3 1.344297E+02 1.337892E+00 1.343931E+02 3.138733E+00 - 1.470002E+01 9.000000E+01 4 3.775727E+02 8.949325E+01 3.339386E+00 3.775579E+02 - 1.470002E+01 9.000000E+01 5 2.100547E-04 -8.989306E+01 3.920825E-07 -2.100543E-04 - 1.470002E+01 9.000000E+01 6 2.603161E-05 1.799795E+02 -2.603161E-05 9.301885E-09 - 1.480002E+01 0.000000E+00 1 8.877970E+01 8.966649E+01 5.167668E-01 8.877820E+01 - 1.480002E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.480002E+01 0.000000E+00 3 1.246186E+02 1.255260E+00 1.245887E+02 2.729977E+00 - 1.480002E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.480002E+01 0.000000E+00 5 6.568660E+02 8.966626E+01 3.826134E+00 6.568548E+02 - 1.480002E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.480002E+01 3.000000E+01 1 7.825255E+01 8.966753E+01 4.540872E-01 7.825123E+01 - 1.480002E+01 3.000000E+01 2 4.771630E+01 8.950009E+01 4.163271E-01 4.771449E+01 - 1.480002E+01 3.000000E+01 3 1.272083E+02 1.270658E+00 1.271770E+02 2.820889E+00 - 1.480002E+01 3.000000E+01 4 1.695220E+02 8.948669E+01 1.518737E+00 1.695152E+02 - 1.480002E+01 3.000000E+01 5 5.794677E+02 8.966758E+01 3.361999E+00 5.794579E+02 - 1.480002E+01 3.000000E+01 6 2.804776E+02 -3.050905E-02 2.804776E+02 -1.493496E-01 - 1.480002E+01 6.000000E+01 1 4.681024E+01 8.966943E+01 2.700717E-01 4.680946E+01 - 1.480002E+01 6.000000E+01 2 8.598749E+01 8.949902E+01 7.518459E-01 8.598420E+01 - 1.480002E+01 6.000000E+01 3 1.325615E+02 1.301795E+00 1.325273E+02 3.011619E+00 - 1.480002E+01 6.000000E+01 4 3.135744E+02 8.949885E+01 2.742731E+00 3.135624E+02 - 1.480002E+01 6.000000E+01 5 3.468528E+02 8.966969E+01 1.999662E+00 3.468470E+02 - 1.480002E+01 6.000000E+01 6 2.920262E+02 -3.008408E-02 2.920262E+02 -1.533331E-01 - 1.480002E+01 9.000000E+01 1 4.999580E-06 -9.000419E+01 -3.654768E-10 -4.999580E-06 - 1.480002E+01 9.000000E+01 2 1.012766E+02 8.949850E+01 8.864421E-01 1.012727E+02 - 1.480002E+01 9.000000E+01 3 1.353274E+02 1.317483E+00 1.352916E+02 3.111501E+00 - 1.480002E+01 9.000000E+01 4 3.739180E+02 8.950448E+01 3.233794E+00 3.739040E+02 - 1.480002E+01 9.000000E+01 5 2.087706E-04 -8.989598E+01 3.790296E-07 -2.087702E-04 - 1.480002E+01 9.000000E+01 6 2.558093E-05 1.799804E+02 -2.558093E-05 8.769400E-09 - 1.490002E+01 0.000000E+00 1 8.822519E+01 8.967208E+01 5.049328E-01 8.822375E+01 - 1.490002E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.490002E+01 0.000000E+00 3 1.256275E+02 1.237665E+00 1.255981E+02 2.713509E+00 - 1.490002E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.490002E+01 0.000000E+00 5 6.573676E+02 8.967187E+01 3.764722E+00 6.573568E+02 - 1.490002E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.490002E+01 3.000000E+01 1 7.773914E+01 8.967305E+01 4.436097E-01 7.773788E+01 - 1.490002E+01 3.000000E+01 2 4.740380E+01 8.951105E+01 4.045225E-01 4.740208E+01 - 1.490002E+01 3.000000E+01 3 1.281878E+02 1.252486E+00 1.281572E+02 2.801964E+00 - 1.490002E+01 3.000000E+01 4 1.681700E+02 8.949814E+01 1.473014E+00 1.681635E+02 - 1.490002E+01 3.000000E+01 5 5.797009E+02 8.967310E+01 3.307492E+00 5.796915E+02 - 1.490002E+01 3.000000E+01 6 2.759885E+02 -2.925755E-02 2.759884E+02 -1.409309E-01 - 1.490002E+01 6.000000E+01 1 4.647306E+01 8.967484E+01 2.637374E-01 4.647231E+01 - 1.490002E+01 6.000000E+01 2 8.536143E+01 8.951005E+01 7.299417E-01 8.535831E+01 - 1.490002E+01 6.000000E+01 3 1.334781E+02 1.282427E+00 1.334447E+02 2.987334E+00 - 1.490002E+01 6.000000E+01 4 3.107328E+02 8.950988E+01 2.658035E+00 3.107214E+02 - 1.490002E+01 6.000000E+01 5 3.467537E+02 8.967508E+01 1.966433E+00 3.467481E+02 - 1.490002E+01 6.000000E+01 6 2.871392E+02 -2.885762E-02 2.871392E+02 -1.446207E-01 - 1.490002E+01 9.000000E+01 1 4.960578E-06 -9.000919E+01 -7.961881E-10 -4.960578E-06 - 1.490002E+01 9.000000E+01 2 1.005024E+02 8.950956E+01 8.602720E-01 1.004988E+02 - 1.490002E+01 9.000000E+01 3 1.362085E+02 1.297531E+00 1.361736E+02 3.084341E+00 - 1.490002E+01 9.000000E+01 4 3.703365E+02 8.951534E+01 3.132666E+00 3.703233E+02 - 1.490002E+01 9.000000E+01 5 2.075021E-04 -8.989880E+01 3.665159E-07 -2.075017E-04 - 1.490002E+01 9.000000E+01 6 2.514250E-05 1.799812E+02 -2.514250E-05 8.272731E-09 - 1.500002E+01 0.000000E+00 1 8.767646E+01 8.967754E+01 4.934455E-01 8.767507E+01 - 1.500002E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.500002E+01 0.000000E+00 3 1.266190E+02 1.220399E+00 1.265903E+02 2.696779E+00 - 1.500002E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.500002E+01 0.000000E+00 5 6.577644E+02 8.967734E+01 3.704196E+00 6.577540E+02 - 1.500002E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.500002E+01 3.000000E+01 1 7.723136E+01 8.967844E+01 4.334382E-01 7.723015E+01 - 1.500002E+01 3.000000E+01 2 4.709496E+01 8.952168E+01 3.931641E-01 4.709332E+01 - 1.500002E+01 3.000000E+01 3 1.291510E+02 1.234663E+00 1.291210E+02 2.782850E+00 - 1.500002E+01 3.000000E+01 4 1.668384E+02 8.950921E+01 1.429110E+00 1.668323E+02 - 1.500002E+01 3.000000E+01 5 5.798446E+02 8.967849E+01 3.253777E+00 5.798354E+02 - 1.500002E+01 3.000000E+01 6 2.716092E+02 -2.807072E-02 2.716092E+02 -1.330685E-01 - 1.500002E+01 6.000000E+01 1 4.614055E+01 8.968013E+01 2.575900E-01 4.613984E+01 - 1.500002E+01 6.000000E+01 2 8.474454E+01 8.952071E+01 7.088934E-01 8.474157E+01 - 1.500002E+01 6.000000E+01 3 1.343785E+02 1.263469E+00 1.343458E+02 2.963034E+00 - 1.500002E+01 6.000000E+01 4 3.079449E+02 8.952056E+01 2.576803E+00 3.079342E+02 - 1.500002E+01 6.000000E+01 5 3.466065E+02 8.968035E+01 1.933706E+00 3.466011E+02 - 1.500002E+01 6.000000E+01 6 2.823795E+02 -2.769420E-02 2.823794E+02 -1.364895E-01 - 1.500002E+01 9.000000E+01 1 4.922194E-06 -9.001389E+01 -1.193877E-09 -4.922194E-06 - 1.500002E+01 9.000000E+01 2 9.974036E+01 8.952024E+01 8.351440E-01 9.973687E+01 - 1.500002E+01 9.000000E+01 3 1.370753E+02 1.277996E+00 1.370412E+02 3.057245E+00 - 1.500002E+01 9.000000E+01 4 3.668237E+02 8.952583E+01 3.035752E+00 3.668111E+02 - 1.500002E+01 9.000000E+01 5 2.062474E-04 -8.990152E+01 3.545141E-07 -2.062470E-04 - 1.500002E+01 9.000000E+01 6 2.471590E-05 1.799819E+02 -2.471590E-05 7.809119E-09 - 1.510002E+01 0.000000E+00 1 8.713300E+01 8.968285E+01 4.822934E-01 8.713167E+01 - 1.510002E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.510002E+01 0.000000E+00 3 1.275944E+02 1.203435E+00 1.275662E+02 2.679784E+00 - 1.510002E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.510002E+01 0.000000E+00 5 6.580576E+02 8.968267E+01 3.644553E+00 6.580475E+02 - 1.510002E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.510002E+01 3.000000E+01 1 7.672961E+01 8.968371E+01 4.235687E-01 7.672844E+01 - 1.510002E+01 3.000000E+01 2 4.678942E+01 8.953194E+01 3.822304E-01 4.678786E+01 - 1.510002E+01 3.000000E+01 3 1.300972E+02 1.217184E+00 1.300678E+02 2.763560E+00 - 1.510002E+01 3.000000E+01 4 1.655255E+02 8.951991E+01 1.386959E+00 1.655197E+02 - 1.510002E+01 3.000000E+01 5 5.799040E+02 8.968375E+01 3.200826E+00 5.798951E+02 - 1.510002E+01 3.000000E+01 6 2.673363E+02 -2.694475E-02 2.673362E+02 -1.257215E-01 - 1.510002E+01 6.000000E+01 1 4.581274E+01 8.968530E+01 2.516267E-01 4.581205E+01 - 1.510002E+01 6.000000E+01 2 8.413657E+01 8.953103E+01 6.886593E-01 8.413375E+01 - 1.510002E+01 6.000000E+01 3 1.352637E+02 1.244908E+00 1.352318E+02 2.938744E+00 - 1.510002E+01 6.000000E+01 4 3.052050E+02 8.953088E+01 2.498896E+00 3.051948E+02 - 1.510002E+01 6.000000E+01 5 3.464147E+02 8.968550E+01 1.901496E+00 3.464095E+02 - 1.510002E+01 6.000000E+01 6 2.777427E+02 -2.658994E-02 2.777427E+02 -1.288954E-01 - 1.510002E+01 9.000000E+01 1 4.884440E-06 -9.001831E+01 -1.560826E-09 -4.884439E-06 - 1.510002E+01 9.000000E+01 2 9.899045E+01 8.953059E+01 8.110016E-01 9.898713E+01 - 1.510002E+01 9.000000E+01 3 1.379266E+02 1.258885E+00 1.378933E+02 3.030236E+00 - 1.510002E+01 9.000000E+01 4 3.633807E+02 8.953598E+01 2.942872E+00 3.633688E+02 - 1.510002E+01 9.000000E+01 5 2.050074E-04 -8.990414E+01 3.429994E-07 -2.050071E-04 - 1.510002E+01 9.000000E+01 6 2.430062E-05 1.799826E+02 -2.430062E-05 7.376046E-09 - 1.520002E+01 0.000000E+00 1 8.659521E+01 8.968806E+01 4.714664E-01 8.659393E+01 - 1.520002E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.520002E+01 0.000000E+00 3 1.285534E+02 1.186760E+00 1.285259E+02 2.662521E+00 - 1.520002E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.520002E+01 0.000000E+00 5 6.582505E+02 8.968787E+01 3.585832E+00 6.582408E+02 - 1.520002E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.520002E+01 3.000000E+01 1 7.623369E+01 8.968886E+01 4.139851E-01 7.623257E+01 - 1.520002E+01 3.000000E+01 2 4.648751E+01 8.954188E+01 3.717035E-01 4.648602E+01 - 1.520002E+01 3.000000E+01 3 1.310284E+02 1.199995E+00 1.309997E+02 2.744039E+00 - 1.520002E+01 3.000000E+01 4 1.642324E+02 8.953027E+01 1.346447E+00 1.642269E+02 - 1.520002E+01 3.000000E+01 5 5.798818E+02 8.968889E+01 3.148697E+00 5.798732E+02 - 1.520002E+01 3.000000E+01 6 2.631668E+02 -2.587582E-02 2.631667E+02 -1.188509E-01 - 1.520002E+01 6.000000E+01 1 4.548966E+01 8.969035E+01 2.458408E-01 4.548900E+01 - 1.520002E+01 6.000000E+01 2 8.353723E+01 8.954101E+01 6.692020E-01 8.353455E+01 - 1.520002E+01 6.000000E+01 3 1.361334E+02 1.226707E+00 1.361022E+02 2.914402E+00 - 1.520002E+01 6.000000E+01 4 3.025162E+02 8.954087E+01 2.424147E+00 3.025065E+02 - 1.520002E+01 6.000000E+01 5 3.461852E+02 8.969054E+01 1.869825E+00 3.461802E+02 - 1.520002E+01 6.000000E+01 6 2.732248E+02 -2.554131E-02 2.732248E+02 -1.217982E-01 - 1.520002E+01 9.000000E+01 1 4.847285E-06 -9.002245E+01 -1.899215E-09 -4.847284E-06 - 1.520002E+01 9.000000E+01 2 9.825237E+01 8.954059E+01 7.878018E-01 9.824921E+01 - 1.520002E+01 9.000000E+01 3 1.387645E+02 1.240151E+00 1.387320E+02 3.003283E+00 - 1.520002E+01 9.000000E+01 4 3.600040E+02 8.954581E+01 2.853787E+00 3.599927E+02 - 1.520002E+01 9.000000E+01 5 2.037803E-04 -8.990667E+01 3.319499E-07 -2.037801E-04 - 1.520002E+01 9.000000E+01 6 2.389628E-05 1.799833E+02 -2.389628E-05 6.971225E-09 - 1.530002E+01 0.000000E+00 1 8.606243E+01 8.969312E+01 4.609525E-01 8.606120E+01 - 1.530002E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.530002E+01 0.000000E+00 3 1.294955E+02 1.170427E+00 1.294685E+02 2.645124E+00 - 1.530002E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.530002E+01 0.000000E+00 5 6.583472E+02 8.969296E+01 3.527977E+00 6.583377E+02 - 1.530002E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.530002E+01 3.000000E+01 1 7.574323E+01 8.969388E+01 4.046807E-01 7.574215E+01 - 1.530002E+01 3.000000E+01 2 4.618900E+01 8.955148E+01 3.615649E-01 4.618759E+01 - 1.530002E+01 3.000000E+01 3 1.319434E+02 1.183168E+00 1.319152E+02 2.724460E+00 - 1.530002E+01 3.000000E+01 4 1.629589E+02 8.954028E+01 1.307519E+00 1.629536E+02 - 1.530002E+01 3.000000E+01 5 5.797832E+02 8.969391E+01 3.097349E+00 5.797749E+02 - 1.530002E+01 3.000000E+01 6 2.590969E+02 -2.486056E-02 2.590969E+02 -1.124218E-01 - 1.530002E+01 6.000000E+01 1 4.517104E+01 8.969530E+01 2.402260E-01 4.517040E+01 - 1.530002E+01 6.000000E+01 2 8.294641E+01 8.955067E+01 6.504865E-01 8.294386E+01 - 1.530002E+01 6.000000E+01 3 1.369893E+02 1.208894E+00 1.369588E+02 2.890149E+00 - 1.530002E+01 6.000000E+01 4 2.998741E+02 8.955054E+01 2.352382E+00 2.998648E+02 - 1.530002E+01 6.000000E+01 5 3.459137E+02 8.969545E+01 1.838653E+00 3.459088E+02 - 1.530002E+01 6.000000E+01 6 2.688218E+02 -2.454494E-02 2.688217E+02 -1.151606E-01 - 1.530002E+01 9.000000E+01 1 4.810727E-06 -9.002634E+01 -2.211027E-09 -4.810727E-06 - 1.530002E+01 9.000000E+01 2 9.752534E+01 8.955027E+01 7.654933E-01 9.752234E+01 - 1.530002E+01 9.000000E+01 3 1.395885E+02 1.221842E+00 1.395568E+02 2.976523E+00 - 1.530002E+01 9.000000E+01 4 3.566913E+02 8.955532E+01 2.768331E+00 3.566806E+02 - 1.530002E+01 9.000000E+01 5 2.025673E-04 -8.990911E+01 3.213458E-07 -2.025671E-04 - 1.530002E+01 9.000000E+01 6 2.350250E-05 1.799839E+02 -2.350250E-05 6.592542E-09 - 1.540002E+01 0.000000E+00 1 8.553530E+01 8.969807E+01 4.507416E-01 8.553411E+01 - 1.540002E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.540002E+01 0.000000E+00 3 1.304226E+02 1.154364E+00 1.303961E+02 2.627505E+00 - 1.540002E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.540002E+01 0.000000E+00 5 6.583620E+02 8.969792E+01 3.470994E+00 6.583528E+02 - 1.540002E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.540002E+01 3.000000E+01 1 7.525835E+01 8.969878E+01 3.956480E-01 7.525731E+01 - 1.540002E+01 3.000000E+01 2 4.589386E+01 8.956080E+01 3.517953E-01 4.589251E+01 - 1.540002E+01 3.000000E+01 3 1.328431E+02 1.166649E+00 1.328155E+02 2.704745E+00 - 1.540002E+01 3.000000E+01 4 1.617028E+02 8.954997E+01 1.270088E+00 1.616978E+02 - 1.540002E+01 3.000000E+01 5 5.796142E+02 8.969881E+01 3.046833E+00 5.796062E+02 - 1.540002E+01 3.000000E+01 6 2.551239E+02 -2.389564E-02 2.551238E+02 -1.064014E-01 - 1.540002E+01 6.000000E+01 1 4.485680E+01 8.970012E+01 2.347775E-01 4.485618E+01 - 1.540002E+01 6.000000E+01 2 8.236400E+01 8.956002E+01 6.324736E-01 8.236157E+01 - 1.540002E+01 6.000000E+01 3 1.378305E+02 1.191440E+00 1.378007E+02 2.865917E+00 - 1.540002E+01 6.000000E+01 4 2.972792E+02 8.955989E+01 2.283461E+00 2.972704E+02 - 1.540002E+01 6.000000E+01 5 3.456057E+02 8.970026E+01 1.807986E+00 3.456010E+02 - 1.540002E+01 6.000000E+01 6 2.645298E+02 -2.359766E-02 2.645297E+02 -1.089484E-01 - 1.540002E+01 9.000000E+01 1 4.774732E-06 -9.002998E+01 -2.498079E-09 -4.774731E-06 - 1.540002E+01 9.000000E+01 2 9.680955E+01 8.955964E+01 7.440415E-01 9.680669E+01 - 1.540002E+01 9.000000E+01 3 1.403971E+02 1.203922E+00 1.403661E+02 2.949863E+00 - 1.540002E+01 9.000000E+01 4 3.534423E+02 8.956452E+01 2.686297E+00 3.534321E+02 - 1.540002E+01 9.000000E+01 5 2.013682E-04 -8.991146E+01 3.111631E-07 -2.013679E-04 - 1.540002E+01 9.000000E+01 6 2.311891E-05 1.799845E+02 -2.311891E-05 6.238065E-09 - 1.550002E+01 0.000000E+00 1 8.501358E+01 8.970290E+01 4.408222E-01 8.501244E+01 - 1.550002E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.550002E+01 0.000000E+00 3 1.313343E+02 1.138597E+00 1.313084E+02 2.609739E+00 - 1.550002E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.550002E+01 0.000000E+00 5 6.582881E+02 8.970277E+01 3.414966E+00 6.582793E+02 - 1.550002E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.550002E+01 3.000000E+01 1 7.477923E+01 8.970358E+01 3.868747E-01 7.477823E+01 - 1.550002E+01 3.000000E+01 2 4.560212E+01 8.956982E+01 3.423804E-01 4.560084E+01 - 1.550002E+01 3.000000E+01 3 1.337283E+02 1.150445E+00 1.337013E+02 2.684956E+00 - 1.550002E+01 3.000000E+01 4 1.604662E+02 8.955936E+01 1.234099E+00 1.604614E+02 - 1.550002E+01 3.000000E+01 5 5.793742E+02 8.970361E+01 2.997118E+00 5.793665E+02 - 1.550002E+01 3.000000E+01 6 2.512444E+02 -2.297812E-02 2.512443E+02 -1.007600E-01 - 1.550002E+01 6.000000E+01 1 4.454686E+01 8.970483E+01 2.294877E-01 4.454627E+01 - 1.550002E+01 6.000000E+01 2 8.178957E+01 8.956908E+01 6.151325E-01 8.178726E+01 - 1.550002E+01 6.000000E+01 3 1.386578E+02 1.174335E+00 1.386287E+02 2.841734E+00 - 1.550002E+01 6.000000E+01 4 2.947299E+02 8.956896E+01 2.217250E+00 2.947216E+02 - 1.550002E+01 6.000000E+01 5 3.452635E+02 8.970497E+01 1.777822E+00 3.452590E+02 - 1.550002E+01 6.000000E+01 6 2.603443E+02 -2.269665E-02 2.603442E+02 -1.031305E-01 - 1.550002E+01 9.000000E+01 1 4.739297E-06 -9.003339E+01 -2.762163E-09 -4.739296E-06 - 1.550002E+01 9.000000E+01 2 9.610486E+01 8.956872E+01 7.234001E-01 9.610213E+01 - 1.550002E+01 9.000000E+01 3 1.411937E+02 1.186374E+00 1.411634E+02 2.923365E+00 - 1.550002E+01 9.000000E+01 4 3.502533E+02 8.957345E+01 2.607532E+00 3.502436E+02 - 1.550002E+01 9.000000E+01 5 2.001821E-04 -8.991374E+01 3.013827E-07 -2.001819E-04 - 1.550002E+01 9.000000E+01 6 2.274516E-05 1.799851E+02 -2.274516E-05 5.906017E-09 - 1.560002E+01 0.000000E+00 1 8.449736E+01 8.970763E+01 4.311863E-01 8.449626E+01 - 1.560002E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.560002E+01 0.000000E+00 3 1.322307E+02 1.123103E+00 1.322053E+02 2.591802E+00 - 1.560002E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.560002E+01 0.000000E+00 5 6.581295E+02 8.970750E+01 3.359847E+00 6.581208E+02 - 1.560002E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.560002E+01 3.000000E+01 1 7.430541E+01 8.970826E+01 3.783545E-01 7.430445E+01 - 1.560002E+01 3.000000E+01 2 4.531374E+01 8.957856E+01 3.333023E-01 4.531251E+01 - 1.560002E+01 3.000000E+01 3 1.345982E+02 1.134543E+00 1.345718E+02 2.665074E+00 - 1.560002E+01 3.000000E+01 4 1.592472E+02 8.956844E+01 1.199459E+00 1.592427E+02 - 1.560002E+01 3.000000E+01 5 5.790646E+02 8.970828E+01 2.948259E+00 5.790571E+02 - 1.560002E+01 3.000000E+01 6 2.474553E+02 -2.210524E-02 2.474553E+02 -9.547052E-02 - 1.560002E+01 6.000000E+01 1 4.424113E+01 8.970945E+01 2.243525E-01 4.424057E+01 - 1.560002E+01 6.000000E+01 2 8.122330E+01 8.957786E+01 5.984322E-01 8.122110E+01 - 1.560002E+01 6.000000E+01 3 1.394710E+02 1.157583E+00 1.394425E+02 2.817630E+00 - 1.560002E+01 6.000000E+01 4 2.922254E+02 8.957774E+01 2.153616E+00 2.922175E+02 - 1.560002E+01 6.000000E+01 5 3.448848E+02 8.970957E+01 1.748207E+00 3.448803E+02 - 1.560002E+01 6.000000E+01 6 2.562623E+02 -2.183915E-02 2.562622E+02 -9.767821E-02 - 1.560002E+01 9.000000E+01 1 4.704414E-06 -9.003660E+01 -3.004812E-09 -4.704413E-06 - 1.560002E+01 9.000000E+01 2 9.541071E+01 8.957751E+01 7.035336E-01 9.540811E+01 - 1.560002E+01 9.000000E+01 3 1.419765E+02 1.169180E+00 1.419470E+02 2.896977E+00 - 1.560002E+01 9.000000E+01 4 3.471267E+02 8.958209E+01 2.531875E+00 3.471174E+02 - 1.560002E+01 9.000000E+01 5 1.990087E-04 -8.991594E+01 2.919870E-07 -1.990085E-04 - 1.560002E+01 9.000000E+01 6 2.238082E-05 1.799857E+02 -2.238082E-05 5.594784E-09 - 1.570002E+01 0.000000E+00 1 8.398630E+01 8.971223E+01 4.218252E-01 8.398524E+01 - 1.570002E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.570002E+01 0.000000E+00 3 1.331126E+02 1.107914E+00 1.330877E+02 2.573803E+00 - 1.570002E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.570002E+01 0.000000E+00 5 6.578960E+02 8.971211E+01 3.305639E+00 6.578877E+02 - 1.570002E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.570002E+01 3.000000E+01 1 7.383731E+01 8.971283E+01 3.700774E-01 7.383638E+01 - 1.570002E+01 3.000000E+01 2 4.502851E+01 8.958703E+01 3.245486E-01 4.502734E+01 - 1.570002E+01 3.000000E+01 3 1.354543E+02 1.118935E+00 1.354284E+02 2.645133E+00 - 1.570002E+01 3.000000E+01 4 1.580459E+02 8.957725E+01 1.166122E+00 1.580416E+02 - 1.570002E+01 3.000000E+01 5 5.786974E+02 8.971285E+01 2.900206E+00 5.786901E+02 - 1.570002E+01 3.000000E+01 6 2.437544E+02 -2.127433E-02 2.437544E+02 -9.050775E-02 - 1.570002E+01 6.000000E+01 1 4.393958E+01 8.971396E+01 2.193666E-01 4.393903E+01 - 1.570002E+01 6.000000E+01 2 8.066491E+01 8.958636E+01 5.823464E-01 8.066280E+01 - 1.570002E+01 6.000000E+01 3 1.402710E+02 1.141168E+00 1.402432E+02 2.793614E+00 - 1.570002E+01 6.000000E+01 4 2.897626E+02 8.958625E+01 2.092440E+00 2.897550E+02 - 1.570002E+01 6.000000E+01 5 3.444773E+02 8.971407E+01 1.719118E+00 3.444730E+02 - 1.570002E+01 6.000000E+01 6 2.522802E+02 -2.102265E-02 2.522801E+02 -9.256525E-02 - 1.570002E+01 9.000000E+01 1 4.670068E-06 -9.003960E+01 -3.227515E-09 -4.670067E-06 - 1.570002E+01 9.000000E+01 2 9.472731E+01 8.958603E+01 6.844041E-01 9.472484E+01 - 1.570002E+01 9.000000E+01 3 1.427458E+02 1.152369E+00 1.427170E+02 2.870800E+00 - 1.570002E+01 9.000000E+01 4 3.440529E+02 8.959046E+01 2.459167E+00 3.440441E+02 - 1.570002E+01 9.000000E+01 5 1.978478E-04 -8.991805E+01 2.829585E-07 -1.978476E-04 - 1.570002E+01 9.000000E+01 6 2.202568E-05 1.799862E+02 -2.202568E-05 5.302874E-09 - 1.580002E+01 0.000000E+00 1 8.348027E+01 8.971673E+01 4.127260E-01 8.347925E+01 - 1.580002E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.580002E+01 0.000000E+00 3 1.339804E+02 1.092994E+00 1.339560E+02 2.555701E+00 - 1.580002E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.580002E+01 0.000000E+00 5 6.575893E+02 8.971663E+01 3.252314E+00 6.575812E+02 - 1.580002E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.580002E+01 3.000000E+01 1 7.337444E+01 8.971729E+01 3.620350E-01 7.337354E+01 - 1.580002E+01 3.000000E+01 2 4.474663E+01 8.959525E+01 3.161027E-01 4.474551E+01 - 1.580002E+01 3.000000E+01 3 1.362958E+02 1.103642E+00 1.362705E+02 2.625192E+00 - 1.580002E+01 3.000000E+01 4 1.568627E+02 8.958578E+01 1.134036E+00 1.568586E+02 - 1.580002E+01 3.000000E+01 5 5.782645E+02 8.971732E+01 2.852954E+00 5.782575E+02 - 1.580002E+01 3.000000E+01 6 2.401385E+02 -2.048301E-02 2.401385E+02 -8.584853E-02 - 1.580002E+01 6.000000E+01 1 4.364219E+01 8.971836E+01 2.145253E-01 4.364167E+01 - 1.580002E+01 6.000000E+01 2 8.011423E+01 8.959460E+01 5.668424E-01 8.011222E+01 - 1.580002E+01 6.000000E+01 3 1.410566E+02 1.125105E+00 1.410294E+02 2.769721E+00 - 1.580002E+01 6.000000E+01 4 2.873427E+02 8.959451E+01 2.033598E+00 2.873354E+02 - 1.580002E+01 6.000000E+01 5 3.440365E+02 8.971846E+01 1.690512E+00 3.440323E+02 - 1.580002E+01 6.000000E+01 6 2.483942E+02 -2.024484E-02 2.483942E+02 -8.776741E-02 - 1.580002E+01 9.000000E+01 1 4.636241E-06 -9.004241E+01 -3.431655E-09 -4.636240E-06 - 1.580002E+01 9.000000E+01 2 9.405357E+01 8.959430E+01 6.659787E-01 9.405122E+01 - 1.580002E+01 9.000000E+01 3 1.435032E+02 1.135892E+00 1.434750E+02 2.844773E+00 - 1.580002E+01 9.000000E+01 4 3.410387E+02 8.959859E+01 2.389280E+00 3.410303E+02 - 1.580002E+01 9.000000E+01 5 1.967006E-04 -8.992011E+01 2.742790E-07 -1.967004E-04 - 1.580002E+01 9.000000E+01 6 2.167934E-05 1.799867E+02 -2.167934E-05 5.028896E-09 - 1.590002E+01 0.000000E+00 1 8.298023E+01 8.972113E+01 4.038826E-01 8.297925E+01 - 1.590002E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.590002E+01 0.000000E+00 3 1.348329E+02 1.078353E+00 1.348090E+02 2.537514E+00 - 1.590002E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.590002E+01 0.000000E+00 5 6.572054E+02 8.972102E+01 3.199937E+00 6.571976E+02 - 1.590002E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.590002E+01 3.000000E+01 1 7.291677E+01 8.972166E+01 3.542206E-01 7.291591E+01 - 1.590002E+01 3.000000E+01 2 4.446796E+01 8.960321E+01 3.079539E-01 4.446689E+01 - 1.590002E+01 3.000000E+01 3 1.371233E+02 1.088633E+00 1.370986E+02 2.605219E+00 - 1.590002E+01 3.000000E+01 4 1.556960E+02 8.959405E+01 1.103129E+00 1.556920E+02 - 1.590002E+01 3.000000E+01 5 5.777761E+02 8.972169E+01 2.806556E+00 5.777693E+02 - 1.590002E+01 3.000000E+01 6 2.366047E+02 -1.972905E-02 2.366047E+02 -8.147172E-02 - 1.590002E+01 6.000000E+01 1 4.334882E+01 8.972267E+01 2.098231E-01 4.334831E+01 - 1.590002E+01 6.000000E+01 2 7.957107E+01 8.960260E+01 5.518972E-01 7.956915E+01 - 1.590002E+01 6.000000E+01 3 1.418307E+02 1.109341E+00 1.418042E+02 2.745907E+00 - 1.590002E+01 6.000000E+01 4 2.849661E+02 8.960250E+01 1.976981E+00 2.849593E+02 - 1.590002E+01 6.000000E+01 5 3.435679E+02 8.972276E+01 1.662444E+00 3.435639E+02 - 1.590002E+01 6.000000E+01 6 2.446023E+02 -1.950350E-02 2.446022E+02 -8.326268E-02 - 1.590002E+01 9.000000E+01 1 4.602926E-06 -9.004504E+01 -3.618515E-09 -4.602924E-06 - 1.590002E+01 9.000000E+01 2 9.338999E+01 8.960230E+01 6.482276E-01 9.338774E+01 - 1.590002E+01 9.000000E+01 3 1.442480E+02 1.119761E+00 1.442204E+02 2.818933E+00 - 1.590002E+01 9.000000E+01 4 3.380776E+02 8.960646E+01 2.322075E+00 3.380696E+02 - 1.590002E+01 9.000000E+01 5 1.955658E-04 -8.992209E+01 2.659353E-07 -1.955656E-04 - 1.590002E+01 9.000000E+01 6 2.134156E-05 1.799872E+02 -2.134156E-05 4.771601E-09 - 1.600002E+01 0.000000E+00 1 8.248469E+01 8.972543E+01 3.952885E-01 8.248374E+01 - 1.600002E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.600002E+01 0.000000E+00 3 1.356718E+02 1.063973E+00 1.356484E+02 2.519257E+00 - 1.600002E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.600002E+01 0.000000E+00 5 6.567580E+02 8.972533E+01 3.148412E+00 6.567504E+02 - 1.600002E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.600002E+01 3.000000E+01 1 7.246449E+01 8.972593E+01 3.466277E-01 7.246365E+01 - 1.600002E+01 3.000000E+01 2 4.419244E+01 8.961094E+01 3.000866E-01 4.419143E+01 - 1.600002E+01 3.000000E+01 3 1.379379E+02 1.073897E+00 1.379137E+02 2.585224E+00 - 1.600002E+01 3.000000E+01 4 1.545462E+02 8.960207E+01 1.073349E+00 1.545425E+02 - 1.600002E+01 3.000000E+01 5 5.772315E+02 8.972595E+01 2.760939E+00 5.772249E+02 - 1.600002E+01 3.000000E+01 6 2.331511E+02 -1.901023E-02 2.331510E+02 -7.735745E-02 - 1.600002E+01 6.000000E+01 1 4.305938E+01 8.972688E+01 2.052545E-01 4.305889E+01 - 1.600002E+01 6.000000E+01 2 7.903542E+01 8.961035E+01 5.374856E-01 7.903358E+01 - 1.600002E+01 6.000000E+01 3 1.425912E+02 1.093902E+00 1.425652E+02 2.722215E+00 - 1.600002E+01 6.000000E+01 4 2.826280E+02 8.961026E+01 1.922494E+00 2.826215E+02 - 1.600002E+01 6.000000E+01 5 3.430718E+02 8.972696E+01 1.634872E+00 3.430679E+02 - 1.600002E+01 6.000000E+01 6 2.409003E+02 -1.879655E-02 2.409003E+02 -7.903018E-02 - 1.600002E+01 9.000000E+01 1 4.570110E-06 -9.004751E+01 -3.789268E-09 -4.570109E-06 - 1.600002E+01 9.000000E+01 2 9.273631E+01 8.961008E+01 6.311160E-01 9.273416E+01 - 1.600002E+01 9.000000E+01 3 1.449802E+02 1.103963E+00 1.449532E+02 2.793275E+00 - 1.600002E+01 9.000000E+01 4 3.351709E+02 8.961411E+01 2.257408E+00 3.351633E+02 - 1.600002E+01 9.000000E+01 5 1.944421E-04 -8.992400E+01 2.579107E-07 -1.944419E-04 - 1.600002E+01 9.000000E+01 6 2.101203E-05 1.799876E+02 -2.101203E-05 4.529813E-09 - 1.610003E+01 0.000000E+00 1 8.199458E+01 8.972961E+01 3.869341E-01 8.199367E+01 - 1.610003E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.610003E+01 0.000000E+00 3 1.364973E+02 1.049858E+00 1.364744E+02 2.500965E+00 - 1.610003E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.610003E+01 0.000000E+00 5 6.562446E+02 8.972954E+01 3.097819E+00 6.562373E+02 - 1.610003E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.610003E+01 3.000000E+01 1 7.201734E+01 8.973010E+01 3.392474E-01 7.201654E+01 - 1.610003E+01 3.000000E+01 2 4.392006E+01 8.961843E+01 2.924908E-01 4.391909E+01 - 1.610003E+01 3.000000E+01 3 1.387381E+02 1.059451E+00 1.387144E+02 2.565246E+00 - 1.610003E+01 3.000000E+01 4 1.534126E+02 8.960985E+01 1.044645E+00 1.534091E+02 - 1.610003E+01 3.000000E+01 5 5.766322E+02 8.973013E+01 2.716109E+00 5.766258E+02 - 1.610003E+01 3.000000E+01 6 2.297751E+02 -1.832469E-02 2.297751E+02 -7.348808E-02 - 1.610003E+01 6.000000E+01 1 4.277364E+01 8.973100E+01 2.008175E-01 4.277316E+01 - 1.610003E+01 6.000000E+01 2 7.850677E+01 8.961787E+01 5.235832E-01 7.850502E+01 - 1.610003E+01 6.000000E+01 3 1.433391E+02 1.078775E+00 1.433137E+02 2.698655E+00 - 1.610003E+01 6.000000E+01 4 2.803295E+02 8.961778E+01 1.870026E+00 2.803232E+02 - 1.610003E+01 6.000000E+01 5 3.425508E+02 8.973108E+01 1.607805E+00 3.425470E+02 - 1.610003E+01 6.000000E+01 6 2.372856E+02 -1.812215E-02 2.372856E+02 -7.505134E-02 - 1.610003E+01 9.000000E+01 1 4.537772E-06 -9.004981E+01 -3.945039E-09 -4.537770E-06 - 1.610003E+01 9.000000E+01 2 9.209183E+01 8.961761E+01 6.146173E-01 9.208978E+01 - 1.610003E+01 9.000000E+01 3 1.457000E+02 1.088498E+00 1.456738E+02 2.767825E+00 - 1.610003E+01 9.000000E+01 4 3.323153E+02 8.962151E+01 2.195188E+00 3.323080E+02 - 1.610003E+01 9.000000E+01 5 1.933317E-04 -8.992586E+01 2.501906E-07 -1.933316E-04 - 1.610003E+01 9.000000E+01 6 2.069044E-05 1.799881E+02 -2.069044E-05 4.302473E-09 - 1.620003E+01 0.000000E+00 1 8.150962E+01 8.973372E+01 3.788093E-01 8.150874E+01 - 1.620003E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.620003E+01 0.000000E+00 3 1.373093E+02 1.036007E+00 1.372869E+02 2.482654E+00 - 1.620003E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.620003E+01 0.000000E+00 5 6.556716E+02 8.973365E+01 3.048084E+00 6.556645E+02 - 1.620003E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.620003E+01 3.000000E+01 1 7.157527E+01 8.973418E+01 3.320727E-01 7.157450E+01 - 1.620003E+01 3.000000E+01 2 4.365086E+01 8.962571E+01 2.851542E-01 4.364993E+01 - 1.620003E+01 3.000000E+01 3 1.395263E+02 1.045278E+00 1.395030E+02 2.545311E+00 - 1.620003E+01 3.000000E+01 4 1.522952E+02 8.961739E+01 1.016979E+00 1.522918E+02 - 1.620003E+01 3.000000E+01 5 5.759805E+02 8.973420E+01 2.672055E+00 5.759743E+02 - 1.620003E+01 3.000000E+01 6 2.264742E+02 -1.767052E-02 2.264742E+02 -6.984662E-02 - 1.620003E+01 6.000000E+01 1 4.249178E+01 8.973503E+01 1.965063E-01 4.249132E+01 - 1.620003E+01 6.000000E+01 2 7.798560E+01 8.962518E+01 5.101681E-01 7.798392E+01 - 1.620003E+01 6.000000E+01 3 1.440754E+02 1.063956E+00 1.440506E+02 2.675261E+00 - 1.620003E+01 6.000000E+01 4 2.780690E+02 8.962509E+01 1.819491E+00 2.780630E+02 - 1.620003E+01 6.000000E+01 5 3.420031E+02 8.973509E+01 1.581232E+00 3.419995E+02 - 1.620003E+01 6.000000E+01 6 2.337555E+02 -1.747839E-02 2.337555E+02 -7.130837E-02 - 1.620003E+01 9.000000E+01 1 4.505927E-06 -9.005197E+01 -4.086868E-09 -4.505926E-06 - 1.620003E+01 9.000000E+01 2 9.145695E+01 8.962492E+01 5.987044E-01 9.145499E+01 - 1.620003E+01 9.000000E+01 3 1.464088E+02 1.073344E+00 1.463831E+02 2.742572E+00 - 1.620003E+01 9.000000E+01 4 3.295114E+02 8.962872E+01 2.135277E+00 3.295044E+02 - 1.620003E+01 9.000000E+01 5 1.922324E-04 -8.992764E+01 2.427637E-07 -1.922322E-04 - 1.620003E+01 9.000000E+01 6 2.037656E-05 1.799885E+02 -2.037656E-05 4.088583E-09 - 1.630003E+01 0.000000E+00 1 8.102962E+01 8.973773E+01 3.709082E-01 8.102878E+01 - 1.630003E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.630003E+01 0.000000E+00 3 1.381084E+02 1.022408E+00 1.380864E+02 2.464328E+00 - 1.630003E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.630003E+01 0.000000E+00 5 6.550367E+02 8.973766E+01 2.999223E+00 6.550299E+02 - 1.630003E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.630003E+01 3.000000E+01 1 7.113800E+01 8.973816E+01 3.250960E-01 7.113726E+01 - 1.630003E+01 3.000000E+01 2 4.338460E+01 8.963277E+01 2.780656E-01 4.338371E+01 - 1.630003E+01 3.000000E+01 3 1.403013E+02 1.031371E+00 1.402785E+02 2.525403E+00 - 1.630003E+01 3.000000E+01 4 1.511939E+02 8.962472E+01 9.902994E-01 1.511906E+02 - 1.630003E+01 3.000000E+01 5 5.752880E+02 8.973818E+01 2.628852E+00 5.752820E+02 - 1.630003E+01 3.000000E+01 6 2.232461E+02 -1.704601E-02 2.232461E+02 -6.641772E-02 - 1.630003E+01 6.000000E+01 1 4.221375E+01 8.973898E+01 1.923163E-01 4.221331E+01 - 1.630003E+01 6.000000E+01 2 7.747129E+01 8.963226E+01 4.972187E-01 7.746970E+01 - 1.630003E+01 6.000000E+01 3 1.448003E+02 1.049418E+00 1.447760E+02 2.651986E+00 - 1.630003E+01 6.000000E+01 4 2.758463E+02 8.963219E+01 1.770804E+00 2.758407E+02 - 1.630003E+01 6.000000E+01 5 3.414315E+02 8.973903E+01 1.555139E+00 3.414279E+02 - 1.630003E+01 6.000000E+01 6 2.303071E+02 -1.686371E-02 2.303071E+02 -6.778567E-02 - 1.630003E+01 9.000000E+01 1 4.474533E-06 -9.005399E+01 -4.215642E-09 -4.474531E-06 - 1.630003E+01 9.000000E+01 2 9.083119E+01 8.963202E+01 5.833520E-01 9.082932E+01 - 1.630003E+01 9.000000E+01 3 1.471063E+02 1.058501E+00 1.470812E+02 2.717536E+00 - 1.630003E+01 9.000000E+01 4 3.267547E+02 8.963570E+01 2.077567E+00 3.267481E+02 - 1.630003E+01 9.000000E+01 5 1.911456E-04 -8.992938E+01 2.356130E-07 -1.911455E-04 - 1.630003E+01 9.000000E+01 6 2.007018E-05 1.799889E+02 -2.007018E-05 3.887227E-09 - 1.640003E+01 0.000000E+00 1 8.055461E+01 8.974165E+01 3.632233E-01 8.055379E+01 - 1.640003E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.640003E+01 0.000000E+00 3 1.388940E+02 1.009062E+00 1.388724E+02 2.445999E+00 - 1.640003E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.640003E+01 0.000000E+00 5 6.543459E+02 8.974158E+01 2.951299E+00 6.543393E+02 - 1.640003E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.640003E+01 3.000000E+01 1 7.070606E+01 8.974206E+01 3.183130E-01 7.070535E+01 - 1.640003E+01 3.000000E+01 2 4.312134E+01 8.963963E+01 2.712153E-01 4.312048E+01 - 1.640003E+01 3.000000E+01 3 1.410633E+02 1.017727E+00 1.410411E+02 2.505533E+00 - 1.640003E+01 3.000000E+01 4 1.501079E+02 8.963183E+01 9.645554E-01 1.501048E+02 - 1.640003E+01 3.000000E+01 5 5.745479E+02 8.974207E+01 2.586395E+00 5.745421E+02 - 1.640003E+01 3.000000E+01 6 2.200888E+02 -1.644952E-02 2.200888E+02 -6.318712E-02 - 1.640003E+01 6.000000E+01 1 4.193920E+01 8.974283E+01 1.882436E-01 4.193877E+01 - 1.640003E+01 6.000000E+01 2 7.696369E+01 8.963915E+01 4.847154E-01 7.696217E+01 - 1.640003E+01 6.000000E+01 3 1.455114E+02 1.035188E+00 1.454877E+02 2.628876E+00 - 1.640003E+01 6.000000E+01 4 2.736604E+02 8.963908E+01 1.723872E+00 2.736549E+02 - 1.640003E+01 6.000000E+01 5 3.408386E+02 8.974288E+01 1.529532E+00 3.408352E+02 - 1.640003E+01 6.000000E+01 6 2.269384E+02 -1.627640E-02 2.269384E+02 -6.446794E-02 - 1.640003E+01 9.000000E+01 1 4.443601E-06 -9.005586E+01 -4.332325E-09 -4.443599E-06 - 1.640003E+01 9.000000E+01 2 9.021398E+01 8.963892E+01 5.685329E-01 9.021219E+01 - 1.640003E+01 9.000000E+01 3 1.477919E+02 1.043959E+00 1.477673E+02 2.692695E+00 - 1.640003E+01 9.000000E+01 4 3.240478E+02 8.964249E+01 2.021979E+00 3.240415E+02 - 1.640003E+01 9.000000E+01 5 1.900700E-04 -8.993105E+01 2.287292E-07 -1.900699E-04 - 1.640003E+01 9.000000E+01 6 1.977098E-05 1.799893E+02 -1.977098E-05 3.697572E-09 - 1.650003E+01 0.000000E+00 1 8.008446E+01 8.974548E+01 3.557478E-01 8.008366E+01 - 1.650003E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.650003E+01 0.000000E+00 3 1.396676E+02 9.959418E-01 1.396465E+02 2.427645E+00 - 1.650003E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.650003E+01 0.000000E+00 5 6.536002E+02 8.974541E+01 2.904176E+00 6.535938E+02 - 1.650003E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.650003E+01 3.000000E+01 1 7.027889E+01 8.974587E+01 3.117142E-01 7.027820E+01 - 1.650003E+01 3.000000E+01 2 4.286112E+01 8.964629E+01 2.645930E-01 4.286031E+01 - 1.650003E+01 3.000000E+01 3 1.418136E+02 1.004334E+00 1.417918E+02 2.485714E+00 - 1.650003E+01 3.000000E+01 4 1.490375E+02 8.963873E+01 9.397214E-01 1.490346E+02 - 1.650003E+01 3.000000E+01 5 5.737659E+02 8.974589E+01 2.544692E+00 5.737603E+02 - 1.650003E+01 3.000000E+01 6 2.170004E+02 -1.587954E-02 2.170004E+02 -6.014171E-02 - 1.650003E+01 6.000000E+01 1 4.166819E+01 8.974660E+01 1.842842E-01 4.166778E+01 - 1.650003E+01 6.000000E+01 2 7.646296E+01 8.964584E+01 4.726377E-01 7.646150E+01 - 1.650003E+01 6.000000E+01 3 1.462129E+02 1.021221E+00 1.461897E+02 2.605911E+00 - 1.650003E+01 6.000000E+01 4 2.715097E+02 8.964576E+01 1.678620E+00 2.715045E+02 - 1.650003E+01 6.000000E+01 5 3.402256E+02 8.974664E+01 1.504421E+00 3.402223E+02 - 1.650003E+01 6.000000E+01 6 2.236460E+02 -1.571510E-02 2.236460E+02 -6.134169E-02 - 1.650003E+01 9.000000E+01 1 4.413116E-06 -9.005762E+01 -4.437728E-09 -4.413114E-06 - 1.650003E+01 9.000000E+01 2 8.960568E+01 8.964561E+01 5.542263E-01 8.960397E+01 - 1.650003E+01 9.000000E+01 3 1.484664E+02 1.029708E+00 1.484424E+02 2.668064E+00 - 1.650003E+01 9.000000E+01 4 3.213871E+02 8.964908E+01 1.968395E+00 3.213810E+02 - 1.650003E+01 9.000000E+01 5 1.890061E-04 -8.993267E+01 2.220995E-07 -1.890059E-04 - 1.650003E+01 9.000000E+01 6 1.947877E-05 1.799897E+02 -1.947877E-05 3.518819E-09 - 1.660003E+01 0.000000E+00 1 7.961937E+01 8.974923E+01 3.484754E-01 7.961861E+01 - 1.660003E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.660003E+01 0.000000E+00 3 1.404284E+02 9.830716E-01 1.404077E+02 2.409329E+00 - 1.660003E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.660003E+01 0.000000E+00 5 6.528055E+02 8.974917E+01 2.857936E+00 6.527993E+02 - 1.660003E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.660003E+01 3.000000E+01 1 6.985648E+01 8.974960E+01 3.052970E-01 6.985582E+01 - 1.660003E+01 3.000000E+01 2 4.260384E+01 8.965277E+01 2.581891E-01 4.260305E+01 - 1.660003E+01 3.000000E+01 3 1.425518E+02 9.911868E-01 1.425305E+02 2.465948E+00 - 1.660003E+01 3.000000E+01 4 1.479819E+02 8.964544E+01 9.157410E-01 1.479791E+02 - 1.660003E+01 3.000000E+01 5 5.729396E+02 8.974961E+01 2.503804E+00 5.729341E+02 - 1.660003E+01 3.000000E+01 6 2.139779E+02 -1.533474E-02 2.139779E+02 -5.726939E-02 - 1.660003E+01 6.000000E+01 1 4.140081E+01 8.975029E+01 1.804350E-01 4.140041E+01 - 1.660003E+01 6.000000E+01 2 7.596867E+01 8.965234E+01 4.609694E-01 7.596728E+01 - 1.660003E+01 6.000000E+01 3 1.469029E+02 1.007521E+00 1.468802E+02 2.583089E+00 - 1.660003E+01 6.000000E+01 4 2.693941E+02 8.965227E+01 1.634977E+00 2.693891E+02 - 1.660003E+01 6.000000E+01 5 3.395906E+02 8.975034E+01 1.479773E+00 3.395873E+02 - 1.660003E+01 6.000000E+01 6 2.204283E+02 -1.517843E-02 2.204282E+02 -5.839444E-02 - 1.660003E+01 9.000000E+01 1 4.383061E-06 -9.005925E+01 -4.532602E-09 -4.383058E-06 - 1.660003E+01 9.000000E+01 2 8.900592E+01 8.965212E+01 5.404093E-01 8.900428E+01 - 1.660003E+01 9.000000E+01 3 1.491305E+02 1.015738E+00 1.491071E+02 2.643642E+00 - 1.660003E+01 9.000000E+01 4 3.187715E+02 8.965548E+01 1.916744E+00 3.187658E+02 - 1.660003E+01 9.000000E+01 5 1.879531E-04 -8.993424E+01 2.157135E-07 -1.879529E-04 - 1.660003E+01 9.000000E+01 6 1.919333E-05 1.799900E+02 -1.919333E-05 3.350276E-09 - 1.670003E+01 0.000000E+00 1 7.915928E+01 8.975289E+01 3.413980E-01 7.915855E+01 - 1.670003E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.670003E+01 0.000000E+00 3 1.411773E+02 9.704314E-01 1.411570E+02 2.391037E+00 - 1.670003E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.670003E+01 0.000000E+00 5 6.519617E+02 8.975283E+01 2.812466E+00 6.519557E+02 - 1.670003E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.670003E+01 3.000000E+01 1 6.943875E+01 8.975324E+01 2.990534E-01 6.943811E+01 - 1.670003E+01 3.000000E+01 2 4.234944E+01 8.965907E+01 2.519954E-01 4.234869E+01 - 1.670003E+01 3.000000E+01 3 1.432779E+02 9.782935E-01 1.432570E+02 2.446272E+00 - 1.670003E+01 3.000000E+01 4 1.469415E+02 8.965195E+01 8.925918E-01 1.469388E+02 - 1.670003E+01 3.000000E+01 5 5.720788E+02 8.975326E+01 2.463653E+00 5.720735E+02 - 1.670003E+01 3.000000E+01 6 2.110209E+02 -1.481364E-02 2.110209E+02 -5.455877E-02 - 1.670003E+01 6.000000E+01 1 4.113696E+01 8.975391E+01 1.766920E-01 4.113658E+01 - 1.670003E+01 6.000000E+01 2 7.548108E+01 8.965865E+01 4.496918E-01 7.547974E+01 - 1.670003E+01 6.000000E+01 3 1.475816E+02 9.941030E-01 1.475593E+02 2.560466E+00 - 1.670003E+01 6.000000E+01 4 2.673114E+02 8.965858E+01 1.592865E+00 2.673066E+02 - 1.670003E+01 6.000000E+01 5 3.389381E+02 8.975394E+01 1.455589E+00 3.389350E+02 - 1.670003E+01 6.000000E+01 6 2.172823E+02 -1.466502E-02 2.172823E+02 -5.561403E-02 - 1.670003E+01 9.000000E+01 1 4.353434E-06 -9.006077E+01 -4.617680E-09 -4.353431E-06 - 1.670003E+01 9.000000E+01 2 8.841442E+01 8.965845E+01 5.270610E-01 8.841285E+01 - 1.670003E+01 9.000000E+01 3 1.497841E+02 1.002045E+00 1.497612E+02 2.619438E+00 - 1.670003E+01 9.000000E+01 4 3.162005E+02 8.966171E+01 1.866930E+00 3.161950E+02 - 1.670003E+01 9.000000E+01 5 1.869116E-04 -8.993577E+01 2.095604E-07 -1.869115E-04 - 1.670003E+01 9.000000E+01 6 1.891439E-05 1.799903E+02 -1.891439E-05 3.191249E-09 - 1.680003E+01 0.000000E+00 1 7.870379E+01 8.975648E+01 3.345112E-01 7.870308E+01 - 1.680003E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.680003E+01 0.000000E+00 3 1.419147E+02 9.580268E-01 1.418949E+02 2.372806E+00 - 1.680003E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.680003E+01 0.000000E+00 5 6.510717E+02 8.975642E+01 2.767807E+00 6.510659E+02 - 1.680003E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.680003E+01 3.000000E+01 1 6.902589E+01 8.975681E+01 2.929785E-01 6.902527E+01 - 1.680003E+01 3.000000E+01 2 4.209784E+01 8.966518E+01 2.460019E-01 4.209712E+01 - 1.680003E+01 3.000000E+01 3 1.439933E+02 9.656351E-01 1.439729E+02 2.426679E+00 - 1.680003E+01 3.000000E+01 4 1.459150E+02 8.965829E+01 8.702304E-01 1.459124E+02 - 1.680003E+01 3.000000E+01 5 5.711770E+02 8.975683E+01 2.424177E+00 5.711719E+02 - 1.680003E+01 3.000000E+01 6 2.081268E+02 -1.431505E-02 2.081268E+02 -5.199940E-02 - 1.680003E+01 6.000000E+01 1 4.087637E+01 8.975744E+01 1.730514E-01 4.087600E+01 - 1.680003E+01 6.000000E+01 2 7.499953E+01 8.966479E+01 4.387893E-01 7.499825E+01 - 1.680003E+01 6.000000E+01 3 1.482493E+02 9.809484E-01 1.482275E+02 2.538019E+00 - 1.680003E+01 6.000000E+01 4 2.652624E+02 8.966473E+01 1.552231E+00 2.652578E+02 - 1.680003E+01 6.000000E+01 5 3.382650E+02 8.975747E+01 1.431869E+00 3.382619E+02 - 1.680003E+01 6.000000E+01 6 2.142068E+02 -1.417367E-02 2.142068E+02 -5.298986E-02 - 1.680003E+01 9.000000E+01 1 4.324208E-06 -9.006219E+01 -4.693642E-09 -4.324205E-06 - 1.680003E+01 9.000000E+01 2 8.783129E+01 8.966460E+01 5.141620E-01 8.782979E+01 - 1.680003E+01 9.000000E+01 3 1.504268E+02 9.886392E-01 1.504044E+02 2.595487E+00 - 1.680003E+01 9.000000E+01 4 3.136725E+02 8.966776E+01 1.818861E+00 3.136672E+02 - 1.680003E+01 9.000000E+01 5 1.858807E-04 -8.993723E+01 2.036307E-07 -1.858806E-04 - 1.680003E+01 9.000000E+01 6 1.864179E-05 1.799906E+02 -1.864179E-05 3.041129E-09 - 1.690003E+01 0.000000E+00 1 7.825299E+01 8.975999E+01 3.278065E-01 7.825230E+01 - 1.690003E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.690003E+01 0.000000E+00 3 1.426401E+02 9.458489E-01 1.426206E+02 2.354621E+00 - 1.690003E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.690003E+01 0.000000E+00 5 6.501360E+02 8.975993E+01 2.724063E+00 6.501302E+02 - 1.690003E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.690003E+01 3.000000E+01 1 6.861776E+01 8.976030E+01 2.870665E-01 6.861716E+01 - 1.690003E+01 3.000000E+01 2 4.184914E+01 8.967113E+01 2.402019E-01 4.184845E+01 - 1.690003E+01 3.000000E+01 3 1.446970E+02 9.532170E-01 1.446770E+02 2.407180E+00 - 1.690003E+01 3.000000E+01 4 1.449025E+02 8.966444E+01 8.486223E-01 1.449000E+02 - 1.690003E+01 3.000000E+01 5 5.702377E+02 8.976031E+01 2.385506E+00 5.702327E+02 - 1.690003E+01 3.000000E+01 6 2.052938E+02 -1.383781E-02 2.052938E+02 -4.958160E-02 - 1.690003E+01 6.000000E+01 1 4.061907E+01 8.976090E+01 1.695097E-01 4.061872E+01 - 1.690003E+01 6.000000E+01 2 7.452441E+01 8.967075E+01 4.282461E-01 7.452318E+01 - 1.690003E+01 6.000000E+01 3 1.489065E+02 9.680391E-01 1.488852E+02 2.515725E+00 - 1.690003E+01 6.000000E+01 4 2.632462E+02 8.967069E+01 1.512990E+00 2.632419E+02 - 1.690003E+01 6.000000E+01 5 3.375758E+02 8.976092E+01 1.408611E+00 3.375729E+02 - 1.690003E+01 6.000000E+01 6 2.111987E+02 -1.370325E-02 2.111987E+02 -5.051173E-02 - 1.690003E+01 9.000000E+01 1 4.295412E-06 -9.006351E+01 -4.761101E-09 -4.295409E-06 - 1.690003E+01 9.000000E+01 2 8.725597E+01 8.967057E+01 5.016919E-01 8.725453E+01 - 1.690003E+01 9.000000E+01 3 1.510592E+02 9.754964E-01 1.510374E+02 2.571754E+00 - 1.690003E+01 9.000000E+01 4 3.111864E+02 8.967365E+01 1.772481E+00 3.111813E+02 - 1.690003E+01 9.000000E+01 5 1.848607E-04 -8.993866E+01 1.979136E-07 -1.848606E-04 - 1.690003E+01 9.000000E+01 6 1.837537E-05 1.799910E+02 -1.837537E-05 2.899343E-09 - 1.700003E+01 0.000000E+00 1 7.780700E+01 8.976341E+01 3.212808E-01 7.780634E+01 - 1.700003E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.700003E+01 0.000000E+00 3 1.433537E+02 9.338885E-01 1.433346E+02 2.336479E+00 - 1.700003E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.700003E+01 0.000000E+00 5 6.491511E+02 8.976337E+01 2.681012E+00 6.491456E+02 - 1.700003E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.700003E+01 3.000000E+01 1 6.821416E+01 8.976371E+01 2.813120E-01 6.821358E+01 - 1.700003E+01 3.000000E+01 2 4.160308E+01 8.967693E+01 2.345867E-01 4.160242E+01 - 1.700003E+01 3.000000E+01 3 1.453886E+02 9.410301E-01 1.453690E+02 2.387765E+00 - 1.700003E+01 3.000000E+01 4 1.439045E+02 8.967043E+01 8.277432E-01 1.439021E+02 - 1.700003E+01 3.000000E+01 5 5.692606E+02 8.976373E+01 2.347507E+00 5.692558E+02 - 1.700003E+01 3.000000E+01 6 2.025197E+02 -1.338084E-02 2.025197E+02 -4.729638E-02 - 1.700003E+01 6.000000E+01 1 4.036497E+01 8.976428E+01 1.660650E-01 4.036462E+01 - 1.700003E+01 6.000000E+01 2 7.405534E+01 8.967656E+01 4.180475E-01 7.405415E+01 - 1.700003E+01 6.000000E+01 3 1.495526E+02 9.553865E-01 1.495318E+02 2.493621E+00 - 1.700003E+01 6.000000E+01 4 2.612618E+02 8.967651E+01 1.475102E+00 2.612577E+02 - 1.700003E+01 6.000000E+01 5 3.368707E+02 8.976430E+01 1.385798E+00 3.368678E+02 - 1.700003E+01 6.000000E+01 6 2.082564E+02 -1.325271E-02 2.082564E+02 -4.817042E-02 - 1.700003E+01 9.000000E+01 1 4.267002E-06 -9.006474E+01 -4.820654E-09 -4.266999E-06 - 1.700003E+01 9.000000E+01 2 8.668875E+01 8.967638E+01 4.896342E-01 8.668737E+01 - 1.700003E+01 9.000000E+01 3 1.516819E+02 9.626111E-01 1.516604E+02 2.548246E+00 - 1.700003E+01 9.000000E+01 4 3.087421E+02 8.967937E+01 1.727703E+00 3.087373E+02 - 1.700003E+01 9.000000E+01 5 1.838514E-04 -8.994004E+01 1.924002E-07 -1.838513E-04 - 1.700003E+01 9.000000E+01 6 1.811487E-05 1.799913E+02 -1.811487E-05 2.765362E-09 - 1.710003E+01 0.000000E+00 1 7.736562E+01 8.976677E+01 3.149246E-01 7.736497E+01 - 1.710003E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.710003E+01 0.000000E+00 3 1.440564E+02 9.221410E-01 1.440378E+02 2.318401E+00 - 1.710003E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.710003E+01 0.000000E+00 5 6.481404E+02 8.976672E+01 2.638818E+00 6.481351E+02 - 1.710003E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.710003E+01 3.000000E+01 1 6.781467E+01 8.976705E+01 2.757103E-01 6.781411E+01 - 1.710003E+01 3.000000E+01 2 4.135986E+01 8.968256E+01 2.291498E-01 4.135922E+01 - 1.710003E+01 3.000000E+01 3 1.460704E+02 9.290562E-01 1.460512E+02 2.368441E+00 - 1.710003E+01 3.000000E+01 4 1.429198E+02 8.967625E+01 8.075590E-01 1.429175E+02 - 1.710003E+01 3.000000E+01 5 5.682650E+02 8.976707E+01 2.310235E+00 5.682603E+02 - 1.710003E+01 3.000000E+01 6 1.998033E+02 -1.294307E-02 1.998033E+02 -4.513539E-02 - 1.710003E+01 6.000000E+01 1 4.011433E+01 8.976760E+01 1.627119E-01 4.011400E+01 - 1.710003E+01 6.000000E+01 2 7.359230E+01 8.968221E+01 4.081792E-01 7.359117E+01 - 1.710003E+01 6.000000E+01 3 1.501896E+02 9.429771E-01 1.501692E+02 2.471717E+00 - 1.710003E+01 6.000000E+01 4 2.593072E+02 8.968215E+01 1.438494E+00 2.593032E+02 - 1.710003E+01 6.000000E+01 5 3.361512E+02 8.976762E+01 1.363393E+00 3.361484E+02 - 1.710003E+01 6.000000E+01 6 2.053779E+02 -1.282100E-02 2.053779E+02 -4.595713E-02 - 1.710003E+01 9.000000E+01 1 4.238977E-06 -9.006586E+01 -4.872835E-09 -4.238974E-06 - 1.710003E+01 9.000000E+01 2 8.612893E+01 8.968204E+01 4.779708E-01 8.612760E+01 - 1.710003E+01 9.000000E+01 3 1.522950E+02 9.499663E-01 1.522740E+02 2.524941E+00 - 1.710003E+01 9.000000E+01 4 3.063377E+02 8.968494E+01 1.684460E+00 3.063331E+02 - 1.710003E+01 9.000000E+01 5 1.828522E-04 -8.994138E+01 1.870827E-07 -1.828521E-04 - 1.710003E+01 9.000000E+01 6 1.786016E-05 1.799915E+02 -1.786016E-05 2.638687E-09 - 1.720003E+01 0.000000E+00 1 7.692882E+01 8.977006E+01 3.087362E-01 7.692820E+01 - 1.720003E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.720003E+01 0.000000E+00 3 1.447481E+02 9.106072E-01 1.447298E+02 2.300398E+00 - 1.720003E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.720003E+01 0.000000E+00 5 6.470827E+02 8.977002E+01 2.597396E+00 6.470775E+02 - 1.720003E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.720003E+01 3.000000E+01 1 6.742007E+01 8.977033E+01 2.702556E-01 6.741953E+01 - 1.720003E+01 3.000000E+01 2 4.111934E+01 8.968804E+01 2.238836E-01 4.111873E+01 - 1.720003E+01 3.000000E+01 3 1.467415E+02 9.173130E-01 1.467227E+02 2.349250E+00 - 1.720003E+01 3.000000E+01 4 1.419483E+02 8.968192E+01 7.880372E-01 1.419461E+02 - 1.720003E+01 3.000000E+01 5 5.672308E+02 8.977034E+01 2.273669E+00 5.672262E+02 - 1.720003E+01 3.000000E+01 6 1.971432E+02 -1.252353E-02 1.971432E+02 -4.309093E-02 - 1.720003E+01 6.000000E+01 1 3.986652E+01 8.977084E+01 1.594489E-01 3.986620E+01 - 1.720003E+01 6.000000E+01 2 7.313503E+01 8.968771E+01 3.986283E-01 7.313394E+01 - 1.720003E+01 6.000000E+01 3 1.508159E+02 9.308029E-01 1.507961E+02 2.449984E+00 - 1.720003E+01 6.000000E+01 4 2.573831E+02 8.968765E+01 1.403127E+00 2.573793E+02 - 1.720003E+01 6.000000E+01 5 3.354142E+02 8.977086E+01 1.341441E+00 3.354116E+02 - 1.720003E+01 6.000000E+01 6 2.025613E+02 -1.240717E-02 2.025613E+02 -4.386384E-02 - 1.720003E+01 9.000000E+01 1 4.211352E-06 -9.006691E+01 -4.918130E-09 -4.211350E-06 - 1.720003E+01 9.000000E+01 2 8.557645E+01 8.968754E+01 4.666883E-01 8.557518E+01 - 1.720003E+01 9.000000E+01 3 1.528981E+02 9.375727E-01 1.528776E+02 2.501872E+00 - 1.720003E+01 9.000000E+01 4 3.039721E+02 8.969037E+01 1.642692E+00 3.039677E+02 - 1.720003E+01 9.000000E+01 5 1.818636E-04 -8.994268E+01 1.819528E-07 -1.818635E-04 - 1.720003E+01 9.000000E+01 6 1.761103E-05 1.799918E+02 -1.761103E-05 2.518862E-09 - 1.730003E+01 0.000000E+00 1 7.649648E+01 8.977328E+01 3.027084E-01 7.649587E+01 - 1.730003E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.730003E+01 0.000000E+00 3 1.454297E+02 8.992753E-01 1.454118E+02 2.282471E+00 - 1.730003E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.730003E+01 0.000000E+00 5 6.459941E+02 8.977323E+01 2.556705E+00 6.459890E+02 - 1.730003E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.730003E+01 3.000000E+01 1 6.702960E+01 8.977353E+01 2.649444E-01 6.702908E+01 - 1.730003E+01 3.000000E+01 2 4.088143E+01 8.969337E+01 2.187814E-01 4.088085E+01 - 1.730003E+01 3.000000E+01 3 1.474021E+02 9.057806E-01 1.473837E+02 2.330162E+00 - 1.730003E+01 3.000000E+01 4 1.409897E+02 8.968742E+01 7.691571E-01 1.409876E+02 - 1.730003E+01 3.000000E+01 5 5.661701E+02 8.977354E+01 2.237766E+00 5.661657E+02 - 1.730003E+01 3.000000E+01 6 1.945372E+02 -1.212130E-02 1.945372E+02 -4.115565E-02 - 1.730003E+01 6.000000E+01 1 3.962185E+01 8.977402E+01 1.562728E-01 3.962154E+01 - 1.730003E+01 6.000000E+01 2 7.268350E+01 8.969305E+01 3.893808E-01 7.268246E+01 - 1.730003E+01 6.000000E+01 3 1.514333E+02 9.188576E-01 1.514138E+02 2.428445E+00 - 1.730003E+01 6.000000E+01 4 2.554887E+02 8.969300E+01 1.368935E+00 2.554850E+02 - 1.730003E+01 6.000000E+01 5 3.346673E+02 8.977402E+01 1.319904E+00 3.346647E+02 - 1.730003E+01 6.000000E+01 6 1.998048E+02 -1.201034E-02 1.998048E+02 -4.188307E-02 - 1.730003E+01 9.000000E+01 1 4.184083E-06 -9.006788E+01 -4.957047E-09 -4.184080E-06 - 1.730003E+01 9.000000E+01 2 8.503168E+01 8.969289E+01 4.557677E-01 8.503046E+01 - 1.730003E+01 9.000000E+01 3 1.534927E+02 9.254283E-01 1.534726E+02 2.479070E+00 - 1.730003E+01 9.000000E+01 4 3.016447E+02 8.969564E+01 1.602325E+00 3.016405E+02 - 1.730003E+01 9.000000E+01 5 1.808851E-04 -8.994393E+01 1.770024E-07 -1.808850E-04 - 1.730003E+01 9.000000E+01 6 1.736735E-05 1.799921E+02 -1.736735E-05 2.405464E-09 - 1.740003E+01 0.000000E+00 1 7.606857E+01 8.977642E+01 2.968370E-01 7.606799E+01 - 1.740003E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.740003E+01 0.000000E+00 3 1.461000E+02 8.881522E-01 1.460824E+02 2.264631E+00 - 1.740003E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.740003E+01 0.000000E+00 5 6.448622E+02 8.977638E+01 2.516809E+00 6.448573E+02 - 1.740003E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.740003E+01 3.000000E+01 1 6.664342E+01 8.977666E+01 2.597717E-01 6.664291E+01 - 1.740003E+01 3.000000E+01 2 4.064622E+01 8.969857E+01 2.138377E-01 4.064566E+01 - 1.740003E+01 3.000000E+01 3 1.480520E+02 8.944587E-01 1.480340E+02 2.311183E+00 - 1.740003E+01 3.000000E+01 4 1.400447E+02 8.969279E+01 7.508884E-01 1.400427E+02 - 1.740003E+01 3.000000E+01 5 5.650781E+02 8.977668E+01 2.202544E+00 5.650739E+02 - 1.740003E+01 3.000000E+01 6 1.919844E+02 -1.173553E-02 1.919844E+02 -3.932295E-02 - 1.740003E+01 6.000000E+01 1 3.938031E+01 8.977714E+01 1.531806E-01 3.938001E+01 - 1.740003E+01 6.000000E+01 2 7.223764E+01 8.969826E+01 3.804266E-01 7.223664E+01 - 1.740003E+01 6.000000E+01 3 1.520408E+02 9.071378E-01 1.520217E+02 2.407091E+00 - 1.740003E+01 6.000000E+01 4 2.536234E+02 8.969821E+01 1.335878E+00 2.536199E+02 - 1.740003E+01 6.000000E+01 5 3.339070E+02 8.977714E+01 1.298781E+00 3.339045E+02 - 1.740003E+01 6.000000E+01 6 1.971064E+02 -1.162970E-02 1.971064E+02 -4.000797E-02 - 1.740003E+01 9.000000E+01 1 4.157188E-06 -9.006878E+01 -4.990004E-09 -4.157185E-06 - 1.740003E+01 9.000000E+01 2 8.449390E+01 8.969811E+01 4.451937E-01 8.449272E+01 - 1.740003E+01 9.000000E+01 3 1.540770E+02 9.135116E-01 1.540574E+02 2.456466E+00 - 1.740003E+01 9.000000E+01 4 2.993548E+02 8.970079E+01 1.563310E+00 2.993507E+02 - 1.740003E+01 9.000000E+01 5 1.799171E-04 -8.994516E+01 1.722229E-07 -1.799170E-04 - 1.740003E+01 9.000000E+01 6 1.712890E-05 1.799923E+02 -1.712890E-05 2.298087E-09 - 1.750003E+01 0.000000E+00 1 7.564523E+01 8.977950E+01 2.911168E-01 7.564468E+01 - 1.750003E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.750003E+01 0.000000E+00 3 1.467605E+02 8.772206E-01 1.467433E+02 2.246873E+00 - 1.750003E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.750003E+01 0.000000E+00 5 6.437031E+02 8.977946E+01 2.477639E+00 6.436983E+02 - 1.750003E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.750003E+01 3.000000E+01 1 6.626160E+01 8.977974E+01 2.547330E-01 6.626112E+01 - 1.750003E+01 3.000000E+01 2 4.041354E+01 8.970363E+01 2.090445E-01 4.041300E+01 - 1.750003E+01 3.000000E+01 3 1.486924E+02 8.833405E-01 1.486747E+02 2.292330E+00 - 1.750003E+01 3.000000E+01 4 1.391121E+02 8.969801E+01 7.332051E-01 1.391102E+02 - 1.750003E+01 3.000000E+01 5 5.639617E+02 8.977975E+01 2.167981E+00 5.639575E+02 - 1.750003E+01 3.000000E+01 6 1.894836E+02 -1.136537E-02 1.894836E+02 -3.758655E-02 - 1.750003E+01 6.000000E+01 1 3.914173E+01 8.978018E+01 1.501700E-01 3.914144E+01 - 1.750003E+01 6.000000E+01 2 7.179738E+01 8.970333E+01 3.717521E-01 7.179642E+01 - 1.750003E+01 6.000000E+01 3 1.526384E+02 8.956429E-01 1.526198E+02 2.385934E+00 - 1.750003E+01 6.000000E+01 4 2.517860E+02 8.970329E+01 1.303899E+00 2.517826E+02 - 1.750003E+01 6.000000E+01 5 3.331340E+02 8.978019E+01 1.278064E+00 3.331315E+02 - 1.750003E+01 6.000000E+01 6 1.944650E+02 -1.126439E-02 1.944650E+02 -3.823193E-02 - 1.750003E+01 9.000000E+01 1 4.130654E-06 -9.006960E+01 -5.017452E-09 -4.130651E-06 - 1.750003E+01 9.000000E+01 2 8.396326E+01 8.970319E+01 4.349561E-01 8.396214E+01 - 1.750003E+01 9.000000E+01 3 1.546528E+02 9.018231E-01 1.546337E+02 2.434101E+00 - 1.750003E+01 9.000000E+01 4 2.971018E+02 8.970580E+01 1.525586E+00 2.970979E+02 - 1.750003E+01 9.000000E+01 5 1.789581E-04 -8.994634E+01 1.676095E-07 -1.789580E-04 - 1.750003E+01 9.000000E+01 6 1.689559E-05 1.799926E+02 -1.689559E-05 2.196375E-09 - 1.760003E+01 0.000000E+00 1 7.522603E+01 8.978252E+01 2.855424E-01 7.522549E+01 - 1.760003E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.760003E+01 0.000000E+00 3 1.474105E+02 8.664895E-01 1.473936E+02 2.229218E+00 - 1.760003E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.760003E+01 0.000000E+00 5 6.425116E+02 8.978249E+01 2.439182E+00 6.425070E+02 - 1.760003E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.760003E+01 3.000000E+01 1 6.588400E+01 8.978275E+01 2.498240E-01 6.588353E+01 - 1.760003E+01 3.000000E+01 2 4.018336E+01 8.970856E+01 2.043981E-01 4.018284E+01 - 1.760003E+01 3.000000E+01 3 1.493228E+02 8.724263E-01 1.493055E+02 2.273607E+00 - 1.760003E+01 3.000000E+01 4 1.381915E+02 8.970310E+01 7.160906E-01 1.381896E+02 - 1.760003E+01 3.000000E+01 5 5.628223E+02 8.978275E+01 2.134067E+00 5.628182E+02 - 1.760003E+01 3.000000E+01 6 1.870322E+02 -1.101012E-02 1.870322E+02 -3.594062E-02 - 1.760003E+01 6.000000E+01 1 3.890599E+01 8.978316E+01 1.472380E-01 3.890571E+01 - 1.760003E+01 6.000000E+01 2 7.136261E+01 8.970827E+01 3.633476E-01 7.136169E+01 - 1.760003E+01 6.000000E+01 3 1.532270E+02 8.843609E-01 1.532087E+02 2.364966E+00 - 1.760003E+01 6.000000E+01 4 2.499757E+02 8.970823E+01 1.272962E+00 2.499725E+02 - 1.760003E+01 6.000000E+01 5 3.323467E+02 8.978316E+01 1.257752E+00 3.323443E+02 - 1.760003E+01 6.000000E+01 6 1.918781E+02 -1.091368E-02 1.918781E+02 -3.654889E-02 - 1.760003E+01 9.000000E+01 1 4.104470E-06 -9.007036E+01 -5.039729E-09 -4.104467E-06 - 1.760003E+01 9.000000E+01 2 8.343951E+01 8.970814E+01 4.250399E-01 8.343843E+01 - 1.760003E+01 9.000000E+01 3 1.552197E+02 8.903571E-01 1.552009E+02 2.411964E+00 - 1.760003E+01 9.000000E+01 4 2.948824E+02 8.971067E+01 1.489102E+00 2.948787E+02 - 1.760003E+01 9.000000E+01 5 1.780100E-04 -8.994749E+01 1.631530E-07 -1.780099E-04 - 1.760003E+01 9.000000E+01 6 1.666724E-05 1.799928E+02 -1.666724E-05 2.099976E-09 - 1.770003E+01 0.000000E+00 1 7.481139E+01 8.978548E+01 2.801100E-01 7.481087E+01 - 1.770003E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.770003E+01 0.000000E+00 3 1.480506E+02 8.559459E-01 1.480341E+02 2.211657E+00 - 1.770003E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.770003E+01 0.000000E+00 5 6.412889E+02 8.978545E+01 2.401450E+00 6.412844E+02 - 1.770003E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.770003E+01 3.000000E+01 1 6.551038E+01 8.978568E+01 2.450408E-01 6.550993E+01 - 1.770003E+01 3.000000E+01 2 3.995592E+01 8.971336E+01 1.998918E-01 3.995542E+01 - 1.770003E+01 3.000000E+01 3 1.499435E+02 8.617072E-01 1.499266E+02 2.255009E+00 - 1.770003E+01 3.000000E+01 4 1.372833E+02 8.970805E+01 6.995165E-01 1.372816E+02 - 1.770003E+01 3.000000E+01 5 5.616598E+02 8.978569E+01 2.100796E+00 5.616559E+02 - 1.770003E+01 3.000000E+01 6 1.846298E+02 -1.066901E-02 1.846298E+02 -3.437980E-02 - 1.770003E+01 6.000000E+01 1 3.867310E+01 8.978609E+01 1.443823E-01 3.867283E+01 - 1.770003E+01 6.000000E+01 2 7.093285E+01 8.971309E+01 3.552011E-01 7.093196E+01 - 1.770003E+01 6.000000E+01 3 1.538070E+02 8.732904E-01 1.537892E+02 2.344204E+00 - 1.770003E+01 6.000000E+01 4 2.481922E+02 8.971304E+01 1.243022E+00 2.481891E+02 - 1.770003E+01 6.000000E+01 5 3.315513E+02 8.978609E+01 1.237825E+00 3.315490E+02 - 1.770003E+01 6.000000E+01 6 1.893453E+02 -1.057689E-02 1.893453E+02 -3.495344E-02 - 1.770003E+01 9.000000E+01 1 4.078627E-06 -9.007104E+01 -5.057224E-09 -4.078624E-06 - 1.770003E+01 9.000000E+01 2 8.292255E+01 8.971296E+01 4.154316E-01 8.292151E+01 - 1.770003E+01 9.000000E+01 3 1.557786E+02 8.791062E-01 1.557602E+02 2.390063E+00 - 1.770003E+01 9.000000E+01 4 2.926987E+02 8.971542E+01 1.453803E+00 2.926951E+02 - 1.770003E+01 9.000000E+01 5 1.770701E-04 -8.994860E+01 1.588489E-07 -1.770701E-04 - 1.770003E+01 9.000000E+01 6 1.644369E-05 1.799930E+02 -1.644369E-05 2.008577E-09 - 1.780003E+01 0.000000E+00 1 7.440078E+01 8.978837E+01 2.748142E-01 7.440027E+01 - 1.780003E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.780003E+01 0.000000E+00 3 1.486817E+02 8.455824E-01 1.486656E+02 2.194195E+00 - 1.780003E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.780003E+01 0.000000E+00 5 6.400364E+02 8.978835E+01 2.364407E+00 6.400320E+02 - 1.780003E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.780003E+01 3.000000E+01 1 6.514104E+01 8.978857E+01 2.403791E-01 6.514060E+01 - 1.780003E+01 3.000000E+01 2 3.973069E+01 8.971804E+01 1.955202E-01 3.973021E+01 - 1.780003E+01 3.000000E+01 3 1.505547E+02 8.511811E-01 1.505381E+02 2.236545E+00 - 1.780003E+01 3.000000E+01 4 1.363872E+02 8.971288E+01 6.834597E-01 1.363855E+02 - 1.780003E+01 3.000000E+01 5 5.604759E+02 8.978858E+01 2.068119E+00 5.604720E+02 - 1.780003E+01 3.000000E+01 6 1.822750E+02 -1.034134E-02 1.822750E+02 -3.289888E-02 - 1.780003E+01 6.000000E+01 1 3.844302E+01 8.978896E+01 1.416005E-01 3.844276E+01 - 1.780003E+01 6.000000E+01 2 7.050869E+01 8.971778E+01 3.473049E-01 7.050784E+01 - 1.780003E+01 6.000000E+01 3 1.543772E+02 8.624300E-01 1.543597E+02 2.323635E+00 - 1.780003E+01 6.000000E+01 4 2.464359E+02 8.971774E+01 1.214041E+00 2.464330E+02 - 1.780003E+01 6.000000E+01 5 3.307463E+02 8.978896E+01 1.218282E+00 3.307440E+02 - 1.780003E+01 6.000000E+01 6 1.868641E+02 -1.025334E-02 1.868641E+02 -3.344018E-02 - 1.780003E+01 9.000000E+01 1 4.053125E-06 -9.007167E+01 -5.070256E-09 -4.053122E-06 - 1.780003E+01 9.000000E+01 2 8.241228E+01 8.971765E+01 4.061211E-01 8.241128E+01 - 1.780003E+01 9.000000E+01 3 1.563274E+02 8.680727E-01 1.563095E+02 2.368384E+00 - 1.780003E+01 9.000000E+01 4 2.905500E+02 8.972005E+01 1.419651E+00 2.905465E+02 - 1.780003E+01 9.000000E+01 5 1.761400E-04 -8.994968E+01 1.546902E-07 -1.761399E-04 - 1.780003E+01 9.000000E+01 6 1.622480E-05 1.799932E+02 -1.622480E-05 1.921874E-09 - 1.790003E+01 0.000000E+00 1 7.399467E+01 8.979121E+01 2.696534E-01 7.399419E+01 - 1.790003E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.790003E+01 0.000000E+00 3 1.493023E+02 8.354082E-01 1.492865E+02 2.176844E+00 - 1.790003E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.790003E+01 0.000000E+00 5 6.387642E+02 8.979118E+01 2.328068E+00 6.387599E+02 - 1.790003E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.790003E+01 3.000000E+01 1 6.477534E+01 8.979140E+01 2.358356E-01 6.477492E+01 - 1.790003E+01 3.000000E+01 2 3.950798E+01 8.972260E+01 1.912789E-01 3.950752E+01 - 1.790003E+01 3.000000E+01 3 1.511558E+02 8.408459E-01 1.511395E+02 2.218212E+00 - 1.790003E+01 3.000000E+01 4 1.355029E+02 8.971758E+01 6.679081E-01 1.355012E+02 - 1.790003E+01 3.000000E+01 5 5.592638E+02 8.979140E+01 2.036119E+00 5.592601E+02 - 1.790003E+01 3.000000E+01 6 1.799663E+02 -1.002654E-02 1.799663E+02 -3.149339E-02 - 1.790003E+01 6.000000E+01 1 3.821576E+01 8.979176E+01 1.388902E-01 3.821550E+01 - 1.790003E+01 6.000000E+01 2 7.008968E+01 8.972235E+01 3.396469E-01 7.008885E+01 - 1.790003E+01 6.000000E+01 3 1.549396E+02 8.517636E-01 1.549225E+02 2.303259E+00 - 1.790003E+01 6.000000E+01 4 2.447059E+02 8.972231E+01 1.185986E+00 2.447030E+02 - 1.790003E+01 6.000000E+01 5 3.299292E+02 8.979176E+01 1.199113E+00 3.299270E+02 - 1.790003E+01 6.000000E+01 6 1.844336E+02 -9.942386E-03 1.844336E+02 -3.200428E-02 - 1.790003E+01 9.000000E+01 1 4.027956E-06 -9.007224E+01 -5.079143E-09 -4.027953E-06 - 1.790003E+01 9.000000E+01 2 8.190853E+01 8.972223E+01 3.970944E-01 8.190757E+01 - 1.790003E+01 9.000000E+01 3 1.568689E+02 8.572463E-01 1.568513E+02 2.346948E+00 - 1.790003E+01 9.000000E+01 4 2.884336E+02 8.972456E+01 1.386583E+00 2.884302E+02 - 1.790003E+01 9.000000E+01 5 1.752189E-04 -8.995073E+01 1.506712E-07 -1.752189E-04 - 1.790003E+01 9.000000E+01 6 1.601048E-05 1.799934E+02 -1.601048E-05 1.839592E-09 - 1.800003E+01 0.000000E+00 1 7.359242E+01 8.979398E+01 2.646198E-01 7.359195E+01 - 1.800003E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.800003E+01 0.000000E+00 3 1.499134E+02 8.254050E-01 1.498979E+02 2.159583E+00 - 1.800003E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.800003E+01 0.000000E+00 5 6.374623E+02 8.979396E+01 2.292387E+00 6.374581E+02 - 1.800003E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.800003E+01 3.000000E+01 1 6.441399E+01 8.979417E+01 2.314064E-01 6.441357E+01 - 1.800003E+01 3.000000E+01 2 3.928770E+01 8.972705E+01 1.871628E-01 3.928726E+01 - 1.800003E+01 3.000000E+01 3 1.517487E+02 8.306831E-01 1.517327E+02 2.199999E+00 - 1.800003E+01 3.000000E+01 4 1.346301E+02 8.972217E+01 6.528330E-01 1.346285E+02 - 1.800003E+01 3.000000E+01 5 5.580375E+02 8.979417E+01 2.004682E+00 5.580339E+02 - 1.800003E+01 3.000000E+01 6 1.777027E+02 -9.723916E-03 1.777027E+02 -3.015869E-02 - 1.800003E+01 6.000000E+01 1 3.799120E+01 8.979452E+01 1.362488E-01 3.799096E+01 - 1.800003E+01 6.000000E+01 2 6.967571E+01 8.972681E+01 3.322195E-01 6.967492E+01 - 1.800003E+01 6.000000E+01 3 1.554927E+02 8.412932E-01 1.554759E+02 2.283069E+00 - 1.800003E+01 6.000000E+01 4 2.430007E+02 8.972678E+01 1.158802E+00 2.429979E+02 - 1.800003E+01 6.000000E+01 5 3.291052E+02 8.979451E+01 1.180315E+00 3.291031E+02 - 1.800003E+01 6.000000E+01 6 1.820520E+02 -9.643480E-03 1.820520E+02 -3.064126E-02 - 1.800003E+01 9.000000E+01 1 4.003104E-06 -9.007277E+01 -5.084192E-09 -4.003100E-06 - 1.800003E+01 9.000000E+01 2 8.141106E+01 8.972669E+01 3.883424E-01 8.141014E+01 - 1.800003E+01 9.000000E+01 3 1.574014E+02 8.466154E-01 1.573842E+02 2.325713E+00 - 1.800003E+01 9.000000E+01 4 2.863488E+02 8.972896E+01 1.354571E+00 2.863456E+02 - 1.800003E+01 9.000000E+01 5 1.743079E-04 -8.995175E+01 1.467860E-07 -1.743078E-04 - 1.800003E+01 9.000000E+01 6 1.580057E-05 1.799936E+02 -1.580057E-05 1.761472E-09 - 1.810003E+01 0.000000E+00 1 7.319434E+01 8.979670E+01 2.597115E-01 7.319389E+01 - 1.810003E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.810003E+01 0.000000E+00 3 1.505152E+02 8.155890E-01 1.505000E+02 2.142469E+00 - 1.810003E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.810003E+01 0.000000E+00 5 6.361327E+02 8.979668E+01 2.257386E+00 6.361287E+02 - 1.810003E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.810003E+01 3.000000E+01 1 6.405619E+01 8.979688E+01 2.270879E-01 6.405579E+01 - 1.810003E+01 3.000000E+01 2 3.906975E+01 8.973138E+01 1.831671E-01 3.906932E+01 - 1.810003E+01 3.000000E+01 3 1.523327E+02 8.207114E-01 1.523171E+02 2.181957E+00 - 1.810003E+01 3.000000E+01 4 1.337683E+02 8.972664E+01 6.382182E-01 1.337668E+02 - 1.810003E+01 3.000000E+01 5 5.567880E+02 8.979689E+01 1.973825E+00 5.567845E+02 - 1.810003E+01 3.000000E+01 6 1.754824E+02 -9.432958E-03 1.754824E+02 -2.889074E-02 - 1.810003E+01 6.000000E+01 1 3.776931E+01 8.979722E+01 1.336748E-01 3.776907E+01 - 1.810003E+01 6.000000E+01 2 6.926653E+01 8.973116E+01 3.250135E-01 6.926576E+01 - 1.810003E+01 6.000000E+01 3 1.560380E+02 8.310156E-01 1.560216E+02 2.263090E+00 - 1.810003E+01 6.000000E+01 4 2.413194E+02 8.973112E+01 1.132469E+00 2.413167E+02 - 1.810003E+01 6.000000E+01 5 3.282740E+02 8.979721E+01 1.161875E+00 3.282720E+02 - 1.810003E+01 6.000000E+01 6 1.797184E+02 -9.355979E-03 1.797184E+02 -2.934668E-02 - 1.810003E+01 9.000000E+01 1 3.978574E-06 -9.007323E+01 -5.085662E-09 -3.978570E-06 - 1.810003E+01 9.000000E+01 2 8.091991E+01 8.973104E+01 3.798544E-01 8.091902E+01 - 1.810003E+01 9.000000E+01 3 1.579263E+02 8.361931E-01 1.579095E+02 2.304746E+00 - 1.810003E+01 9.000000E+01 4 2.842980E+02 8.973326E+01 1.323563E+00 2.842949E+02 - 1.810003E+01 9.000000E+01 5 1.734056E-04 -8.995274E+01 1.430287E-07 -1.734055E-04 - 1.810003E+01 9.000000E+01 6 1.559493E-05 1.799938E+02 -1.559493E-05 1.687267E-09 - 1.820003E+01 0.000000E+00 1 7.280035E+01 8.979937E+01 2.549250E-01 7.279990E+01 - 1.820003E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.820003E+01 0.000000E+00 3 1.511089E+02 8.059275E-01 1.510940E+02 2.125441E+00 - 1.820003E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.820003E+01 0.000000E+00 5 6.347894E+02 8.979935E+01 2.223038E+00 6.347855E+02 - 1.820003E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.820003E+01 3.000000E+01 1 6.370239E+01 8.979954E+01 2.228774E-01 6.370200E+01 - 1.820003E+01 3.000000E+01 2 3.885412E+01 8.973561E+01 1.792869E-01 3.885371E+01 - 1.820003E+01 3.000000E+01 3 1.529076E+02 8.109112E-01 1.528923E+02 2.164040E+00 - 1.820003E+01 3.000000E+01 4 1.329179E+02 8.973100E+01 6.240516E-01 1.329165E+02 - 1.820003E+01 3.000000E+01 5 5.555248E+02 8.979955E+01 1.943584E+00 5.555214E+02 - 1.820003E+01 3.000000E+01 6 1.733053E+02 -9.153094E-03 1.733053E+02 -2.768579E-02 - 1.820003E+01 6.000000E+01 1 3.754996E+01 8.979986E+01 1.311652E-01 3.754973E+01 - 1.820003E+01 6.000000E+01 2 6.886234E+01 8.973540E+01 3.180218E-01 6.886160E+01 - 1.820003E+01 6.000000E+01 3 1.565751E+02 8.209197E-01 1.565590E+02 2.243292E+00 - 1.820003E+01 6.000000E+01 4 2.396626E+02 8.973536E+01 1.106960E+00 2.396601E+02 - 1.820003E+01 6.000000E+01 5 3.274324E+02 8.979985E+01 1.143814E+00 3.274304E+02 - 1.820003E+01 6.000000E+01 6 1.774308E+02 -9.079442E-03 1.774308E+02 -2.811678E-02 - 1.820003E+01 9.000000E+01 1 3.954354E-06 -9.007366E+01 -5.083816E-09 -3.954351E-06 - 1.820003E+01 9.000000E+01 2 8.043484E+01 8.973528E+01 3.716185E-01 8.043398E+01 - 1.820003E+01 9.000000E+01 3 1.584439E+02 8.259460E-01 1.584274E+02 2.283965E+00 - 1.820003E+01 9.000000E+01 4 2.822743E+02 8.973744E+01 1.293522E+00 2.822714E+02 - 1.820003E+01 9.000000E+01 5 1.725127E-04 -8.995370E+01 1.393963E-07 -1.725126E-04 - 1.820003E+01 9.000000E+01 6 1.539349E-05 1.799940E+02 -1.539349E-05 1.616758E-09 - 1.830003E+01 0.000000E+00 1 7.241020E+01 8.980198E+01 2.502557E-01 7.240977E+01 - 1.830003E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.830003E+01 0.000000E+00 3 1.516930E+02 7.964388E-01 1.516783E+02 2.108537E+00 - 1.830003E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.830003E+01 0.000000E+00 5 6.334097E+02 8.980196E+01 2.189332E+00 6.334059E+02 - 1.830003E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.830003E+01 3.000000E+01 1 6.335241E+01 8.980215E+01 2.187716E-01 6.335203E+01 - 1.830003E+01 3.000000E+01 2 3.864079E+01 8.973975E+01 1.755189E-01 3.864039E+01 - 1.830003E+01 3.000000E+01 3 1.534740E+02 8.012852E-01 1.534589E+02 2.146273E+00 - 1.830003E+01 3.000000E+01 4 1.320782E+02 8.973524E+01 6.103086E-01 1.320768E+02 - 1.830003E+01 3.000000E+01 5 5.542449E+02 8.980215E+01 1.913880E+00 5.542416E+02 - 1.830003E+01 3.000000E+01 6 1.711694E+02 -8.883815E-03 1.711694E+02 -2.654013E-02 - 1.830003E+01 6.000000E+01 1 3.733328E+01 8.980245E+01 1.287194E-01 3.733306E+01 - 1.830003E+01 6.000000E+01 2 6.846301E+01 8.973953E+01 3.112344E-01 6.846230E+01 - 1.830003E+01 6.000000E+01 3 1.571040E+02 8.110126E-01 1.570883E+02 2.223709E+00 - 1.830003E+01 6.000000E+01 4 2.380298E+02 8.973950E+01 1.082225E+00 2.380274E+02 - 1.830003E+01 6.000000E+01 5 3.265837E+02 8.980244E+01 1.126073E+00 3.265818E+02 - 1.830003E+01 6.000000E+01 6 1.751885E+02 -8.813322E-03 1.751885E+02 -2.694776E-02 - 1.830003E+01 9.000000E+01 1 3.930443E-06 -9.007404E+01 -5.078886E-09 -3.930440E-06 - 1.830003E+01 9.000000E+01 2 7.995577E+01 8.973943E+01 3.636277E-01 7.995495E+01 - 1.830003E+01 9.000000E+01 3 1.589527E+02 8.159044E-01 1.589366E+02 2.263445E+00 - 1.830003E+01 9.000000E+01 4 2.802824E+02 8.974153E+01 1.264404E+00 2.802796E+02 - 1.830003E+01 9.000000E+01 5 1.716281E-04 -8.995464E+01 1.358817E-07 -1.716281E-04 - 1.830003E+01 9.000000E+01 6 1.519608E-05 1.799942E+02 -1.519608E-05 1.549729E-09 - 1.840003E+01 0.000000E+00 1 7.202413E+01 8.980454E+01 2.457006E-01 7.202371E+01 - 1.840003E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.840003E+01 0.000000E+00 3 1.522688E+02 7.871171E-01 1.522544E+02 2.091770E+00 - 1.840003E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.840003E+01 0.000000E+00 5 6.320253E+02 8.980453E+01 2.156214E+00 6.320217E+02 - 1.840003E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.840003E+01 3.000000E+01 1 6.300617E+01 8.980470E+01 2.147653E-01 6.300580E+01 - 1.840003E+01 3.000000E+01 2 3.842981E+01 8.974377E+01 1.718586E-01 3.842942E+01 - 1.840003E+01 3.000000E+01 3 1.540321E+02 7.918285E-01 1.540174E+02 2.128659E+00 - 1.840003E+01 3.000000E+01 4 1.312489E+02 8.973939E+01 5.969814E-01 1.312476E+02 - 1.840003E+01 3.000000E+01 5 5.529463E+02 8.980471E+01 1.884742E+00 5.529431E+02 - 1.840003E+01 3.000000E+01 6 1.690739E+02 -8.624646E-03 1.690739E+02 -2.545044E-02 - 1.840003E+01 6.000000E+01 1 3.711906E+01 8.980499E+01 1.263339E-01 3.711884E+01 - 1.840003E+01 6.000000E+01 2 6.806809E+01 8.974357E+01 3.046451E-01 6.806741E+01 - 1.840003E+01 6.000000E+01 3 1.576254E+02 8.012876E-01 1.576100E+02 2.204337E+00 - 1.840003E+01 6.000000E+01 4 2.364193E+02 8.974354E+01 1.058241E+00 2.364169E+02 - 1.840003E+01 6.000000E+01 5 3.257329E+02 8.980498E+01 1.108688E+00 3.257310E+02 - 1.840003E+01 6.000000E+01 6 1.729902E+02 -8.557120E-03 1.729902E+02 -2.583607E-02 - 1.840003E+01 9.000000E+01 1 3.906815E-06 -9.007437E+01 -5.071096E-09 -3.906812E-06 - 1.840003E+01 9.000000E+01 2 7.948264E+01 8.974347E+01 3.558712E-01 7.948185E+01 - 1.840003E+01 9.000000E+01 3 1.594551E+02 8.060344E-01 1.594393E+02 2.243133E+00 - 1.840003E+01 9.000000E+01 4 2.783203E+02 8.974551E+01 1.236186E+00 2.783175E+02 - 1.840003E+01 9.000000E+01 5 1.707521E-04 -8.995554E+01 1.324810E-07 -1.707521E-04 - 1.840003E+01 9.000000E+01 6 1.500261E-05 1.799943E+02 -1.500261E-05 1.485979E-09 - 1.850003E+01 0.000000E+00 1 7.164205E+01 8.980706E+01 2.412556E-01 7.164165E+01 - 1.850003E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.850003E+01 0.000000E+00 3 1.528361E+02 7.779517E-01 1.528220E+02 2.075117E+00 - 1.850003E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.850003E+01 0.000000E+00 5 6.306125E+02 8.980704E+01 2.123773E+00 6.306089E+02 - 1.850003E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.850003E+01 3.000000E+01 1 6.266346E+01 8.980721E+01 2.108573E-01 6.266311E+01 - 1.850003E+01 3.000000E+01 2 3.822110E+01 8.974770E+01 1.683022E-01 3.822073E+01 - 1.850003E+01 3.000000E+01 3 1.545818E+02 7.825297E-01 1.545674E+02 2.111169E+00 - 1.850003E+01 3.000000E+01 4 1.304306E+02 8.974344E+01 5.840477E-01 1.304293E+02 - 1.850003E+01 3.000000E+01 5 5.516334E+02 8.980721E+01 1.856169E+00 5.516302E+02 - 1.850003E+01 3.000000E+01 6 1.670181E+02 -8.375099E-03 1.670181E+02 -2.441354E-02 - 1.850003E+01 6.000000E+01 1 3.690732E+01 8.980749E+01 1.240075E-01 3.690711E+01 - 1.850003E+01 6.000000E+01 2 6.767809E+01 8.974751E+01 2.982456E-01 6.767743E+01 - 1.850003E+01 6.000000E+01 3 1.581387E+02 7.917254E-01 1.581236E+02 2.185125E+00 - 1.850003E+01 6.000000E+01 4 2.348323E+02 8.974747E+01 1.034985E+00 2.348300E+02 - 1.850003E+01 6.000000E+01 5 3.248682E+02 8.980747E+01 1.091634E+00 3.248664E+02 - 1.850003E+01 6.000000E+01 6 1.708347E+02 -8.310426E-03 1.708347E+02 -2.477859E-02 - 1.850003E+01 9.000000E+01 1 3.883495E-06 -9.007466E+01 -5.060660E-09 -3.883492E-06 - 1.850003E+01 9.000000E+01 2 7.901544E+01 8.974741E+01 3.483408E-01 7.901467E+01 - 1.850003E+01 9.000000E+01 3 1.599494E+02 7.963436E-01 1.599340E+02 2.223036E+00 - 1.850003E+01 9.000000E+01 4 2.763865E+02 8.974940E+01 1.208826E+00 2.763838E+02 - 1.850003E+01 9.000000E+01 5 1.698839E-04 -8.995643E+01 1.291906E-07 -1.698839E-04 - 1.850003E+01 9.000000E+01 6 1.481295E-05 1.799945E+02 -1.481295E-05 1.425329E-09 - 1.860003E+01 0.000000E+00 1 7.126378E+01 8.980952E+01 2.369186E-01 7.126338E+01 - 1.860003E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.860003E+01 0.000000E+00 3 1.533943E+02 7.689454E-01 1.533805E+02 2.058587E+00 - 1.860003E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.860003E+01 0.000000E+00 5 6.291846E+02 8.980950E+01 2.091887E+00 6.291811E+02 - 1.860003E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.860003E+01 3.000000E+01 1 6.232437E+01 8.980966E+01 2.070444E-01 6.232403E+01 - 1.860003E+01 3.000000E+01 2 3.801441E+01 8.975154E+01 1.648460E-01 3.801405E+01 - 1.860003E+01 3.000000E+01 3 1.551238E+02 7.734011E-01 1.551096E+02 2.093859E+00 - 1.860003E+01 3.000000E+01 4 1.296225E+02 8.974739E+01 5.714963E-01 1.296213E+02 - 1.860003E+01 3.000000E+01 5 5.503102E+02 8.980967E+01 1.828118E+00 5.503071E+02 - 1.860003E+01 3.000000E+01 6 1.650007E+02 -8.134776E-03 1.650007E+02 -2.342656E-02 - 1.860003E+01 6.000000E+01 1 3.669810E+01 8.980994E+01 1.217389E-01 3.669790E+01 - 1.860003E+01 6.000000E+01 2 6.729265E+01 8.975135E+01 2.920308E-01 6.729202E+01 - 1.860003E+01 6.000000E+01 3 1.586445E+02 7.823420E-01 1.586297E+02 2.166135E+00 - 1.860003E+01 6.000000E+01 4 2.332667E+02 8.975132E+01 1.012429E+00 2.332645E+02 - 1.860003E+01 6.000000E+01 5 3.240025E+02 8.980992E+01 1.074895E+00 3.240008E+02 - 1.860003E+01 6.000000E+01 6 1.687207E+02 -8.072804E-03 1.687207E+02 -2.377225E-02 - 1.860003E+01 9.000000E+01 1 3.860472E-06 -9.007492E+01 -5.047793E-09 -3.860469E-06 - 1.860003E+01 9.000000E+01 2 7.855367E+01 8.975126E+01 3.410285E-01 7.855293E+01 - 1.860003E+01 9.000000E+01 3 1.604366E+02 7.868304E-01 1.604214E+02 2.203171E+00 - 1.860003E+01 9.000000E+01 4 2.744805E+02 8.975320E+01 1.182297E+00 2.744779E+02 - 1.860003E+01 9.000000E+01 5 1.690257E-04 -8.995729E+01 1.260047E-07 -1.690256E-04 - 1.860003E+01 9.000000E+01 6 1.462706E-05 1.799946E+02 -1.462706E-05 1.367605E-09 - 1.870004E+01 0.000000E+00 1 7.088927E+01 8.981194E+01 2.326851E-01 7.088889E+01 - 1.870004E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.870004E+01 0.000000E+00 3 1.539454E+02 7.600883E-01 1.539318E+02 2.042186E+00 - 1.870004E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.870004E+01 0.000000E+00 5 6.277385E+02 8.981192E+01 2.060601E+00 6.277351E+02 - 1.870004E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.870004E+01 3.000000E+01 1 6.198892E+01 8.981207E+01 2.033236E-01 6.198859E+01 - 1.870004E+01 3.000000E+01 2 3.780996E+01 8.975529E+01 1.614865E-01 3.780961E+01 - 1.870004E+01 3.000000E+01 3 1.556573E+02 7.644194E-01 1.556434E+02 2.076661E+00 - 1.870004E+01 3.000000E+01 4 1.288244E+02 8.975124E+01 5.593082E-01 1.288232E+02 - 1.870004E+01 3.000000E+01 5 5.489734E+02 8.981208E+01 1.800582E+00 5.489705E+02 - 1.870004E+01 3.000000E+01 6 1.630204E+02 -7.903268E-03 1.630204E+02 -2.248672E-02 - 1.870004E+01 6.000000E+01 1 3.649121E+01 8.981233E+01 1.195254E-01 3.649101E+01 - 1.870004E+01 6.000000E+01 2 6.691158E+01 8.975510E+01 2.859918E-01 6.691096E+01 - 1.870004E+01 6.000000E+01 3 1.591425E+02 7.731164E-01 1.591281E+02 2.147313E+00 - 1.870004E+01 6.000000E+01 4 2.317234E+02 8.975508E+01 9.905398E-01 2.317213E+02 - 1.870004E+01 6.000000E+01 5 3.231285E+02 8.981232E+01 1.058487E+00 3.231268E+02 - 1.870004E+01 6.000000E+01 6 1.666478E+02 -7.843827E-03 1.666478E+02 -2.281418E-02 - 1.870004E+01 9.000000E+01 1 3.837726E-06 -9.007513E+01 -5.032650E-09 -3.837723E-06 - 1.870004E+01 9.000000E+01 2 7.809767E+01 8.975502E+01 3.339256E-01 7.809695E+01 - 1.870004E+01 9.000000E+01 3 1.609160E+02 7.774919E-01 1.609012E+02 2.183530E+00 - 1.870004E+01 9.000000E+01 4 2.726035E+02 8.975692E+01 1.156559E+00 2.726011E+02 - 1.870004E+01 9.000000E+01 5 1.681753E-04 -8.995812E+01 1.229208E-07 -1.681752E-04 - 1.870004E+01 9.000000E+01 6 1.444477E-05 1.799948E+02 -1.444477E-05 1.312643E-09 - 1.880004E+01 0.000000E+00 1 7.051838E+01 8.981431E+01 2.285529E-01 7.051801E+01 - 1.880004E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.880004E+01 0.000000E+00 3 1.544878E+02 7.513816E-01 1.544745E+02 2.025908E+00 - 1.880004E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.880004E+01 0.000000E+00 5 6.262758E+02 8.981429E+01 2.029913E+00 6.262725E+02 - 1.880004E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.880004E+01 3.000000E+01 1 6.165702E+01 8.981444E+01 1.996926E-01 6.165670E+01 - 1.880004E+01 3.000000E+01 2 3.760765E+01 8.975895E+01 1.582202E-01 3.760732E+01 - 1.880004E+01 3.000000E+01 3 1.561836E+02 7.555948E-01 1.561700E+02 2.059630E+00 - 1.880004E+01 3.000000E+01 4 1.280360E+02 8.975500E+01 5.474756E-01 1.280349E+02 - 1.880004E+01 3.000000E+01 5 5.476246E+02 8.981444E+01 1.773582E+00 5.476217E+02 - 1.880004E+01 3.000000E+01 6 1.610770E+02 -7.680135E-03 1.610770E+02 -2.159135E-02 - 1.880004E+01 6.000000E+01 1 3.628674E+01 8.981468E+01 1.173662E-01 3.628654E+01 - 1.880004E+01 6.000000E+01 2 6.653476E+01 8.975877E+01 2.801238E-01 6.653417E+01 - 1.880004E+01 6.000000E+01 3 1.596335E+02 7.640691E-01 1.596193E+02 2.128733E+00 - 1.880004E+01 6.000000E+01 4 2.301998E+02 8.975875E+01 9.692938E-01 2.301978E+02 - 1.880004E+01 6.000000E+01 5 3.222533E+02 8.981467E+01 1.042398E+00 3.222516E+02 - 1.880004E+01 6.000000E+01 6 1.646141E+02 -7.623150E-03 1.646141E+02 -2.190175E-02 - 1.880004E+01 9.000000E+01 1 3.815251E-06 -9.007532E+01 -5.015422E-09 -3.815248E-06 - 1.880004E+01 9.000000E+01 2 7.764704E+01 8.975869E+01 3.270249E-01 7.764635E+01 - 1.880004E+01 9.000000E+01 3 1.613897E+02 7.683160E-01 1.613752E+02 2.164113E+00 - 1.880004E+01 9.000000E+01 4 2.707519E+02 8.976054E+01 1.131587E+00 2.707496E+02 - 1.880004E+01 9.000000E+01 5 1.673326E-04 -8.995893E+01 1.199335E-07 -1.673326E-04 - 1.880004E+01 9.000000E+01 6 1.426603E-05 1.799949E+02 -1.426603E-05 1.260288E-09 - 1.890004E+01 0.000000E+00 1 7.015113E+01 8.981663E+01 2.245188E-01 7.015077E+01 - 1.890004E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.890004E+01 0.000000E+00 3 1.550225E+02 7.428225E-01 1.550094E+02 2.009763E+00 - 1.890004E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.890004E+01 0.000000E+00 5 6.247957E+02 8.981661E+01 1.999770E+00 6.247925E+02 - 1.890004E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.890004E+01 3.000000E+01 1 6.132856E+01 8.981675E+01 1.961475E-01 6.132825E+01 - 1.890004E+01 3.000000E+01 2 3.740742E+01 8.976253E+01 1.550437E-01 3.740710E+01 - 1.890004E+01 3.000000E+01 3 1.567010E+02 7.469233E-01 1.566877E+02 2.042739E+00 - 1.890004E+01 3.000000E+01 4 1.272576E+02 8.975868E+01 5.359846E-01 1.272565E+02 - 1.890004E+01 3.000000E+01 5 5.462592E+02 8.981675E+01 1.747093E+00 5.462563E+02 - 1.890004E+01 3.000000E+01 6 1.591689E+02 -7.465058E-03 1.591689E+02 -2.073810E-02 - 1.890004E+01 6.000000E+01 1 3.608452E+01 8.981699E+01 1.152586E-01 3.608434E+01 - 1.890004E+01 6.000000E+01 2 6.616258E+01 8.976235E+01 2.744199E-01 6.616201E+01 - 1.890004E+01 6.000000E+01 3 1.601171E+02 7.551630E-01 1.601032E+02 2.110296E+00 - 1.890004E+01 6.000000E+01 4 2.286984E+02 8.976233E+01 9.486709E-01 2.286964E+02 - 1.890004E+01 6.000000E+01 5 3.213707E+02 8.981698E+01 1.026604E+00 3.213691E+02 - 1.890004E+01 6.000000E+01 6 1.626183E+02 -7.410386E-03 1.626183E+02 -2.103234E-02 - 1.890004E+01 9.000000E+01 1 3.793045E-06 -9.007547E+01 -4.996249E-09 -3.793042E-06 - 1.890004E+01 9.000000E+01 2 7.720198E+01 8.976228E+01 3.203201E-01 7.720132E+01 - 1.890004E+01 9.000000E+01 3 1.618545E+02 7.593017E-01 1.618403E+02 2.144884E+00 - 1.890004E+01 9.000000E+01 4 2.689290E+02 8.976408E+01 1.107348E+00 2.689268E+02 - 1.890004E+01 9.000000E+01 5 1.664985E-04 -8.995972E+01 1.170405E-07 -1.664984E-04 - 1.890004E+01 9.000000E+01 6 1.409072E-05 1.799951E+02 -1.409072E-05 1.210402E-09 - 1.900004E+01 0.000000E+00 1 6.978777E+01 8.981891E+01 2.205790E-01 6.978741E+01 - 1.900004E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.900004E+01 0.000000E+00 3 1.555495E+02 7.344062E-01 1.555367E+02 1.993748E+00 - 1.900004E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.900004E+01 0.000000E+00 5 6.233063E+02 8.981889E+01 1.970198E+00 6.233032E+02 - 1.900004E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.900004E+01 3.000000E+01 1 6.100338E+01 8.981902E+01 1.926873E-01 6.100307E+01 - 1.900004E+01 3.000000E+01 2 3.720937E+01 8.976602E+01 1.519540E-01 3.720906E+01 - 1.900004E+01 3.000000E+01 3 1.572115E+02 7.384052E-01 1.571984E+02 2.026023E+00 - 1.900004E+01 3.000000E+01 4 1.264887E+02 8.976228E+01 5.248197E-01 1.264876E+02 - 1.900004E+01 3.000000E+01 5 5.448878E+02 8.981903E+01 1.721063E+00 5.448850E+02 - 1.900004E+01 3.000000E+01 6 1.572953E+02 -7.257670E-03 1.572953E+02 -1.992464E-02 - 1.900004E+01 6.000000E+01 1 3.588451E+01 8.981926E+01 1.132025E-01 3.588433E+01 - 1.900004E+01 6.000000E+01 2 6.579439E+01 8.976586E+01 2.688755E-01 6.579384E+01 - 1.900004E+01 6.000000E+01 3 1.605941E+02 7.464270E-01 1.605805E+02 2.092098E+00 - 1.900004E+01 6.000000E+01 4 2.272180E+02 8.976583E+01 9.286466E-01 2.272161E+02 - 1.900004E+01 6.000000E+01 5 3.204846E+02 8.981924E+01 1.011113E+00 3.204830E+02 - 1.900004E+01 6.000000E+01 6 1.606605E+02 -7.205190E-03 1.606605E+02 -2.020374E-02 - 1.900004E+01 9.000000E+01 1 3.771110E-06 -9.007559E+01 -4.975303E-09 -3.771107E-06 - 1.900004E+01 9.000000E+01 2 7.676212E+01 8.976578E+01 3.138021E-01 7.676148E+01 - 1.900004E+01 9.000000E+01 3 1.623144E+02 7.504477E-01 1.623005E+02 2.125898E+00 - 1.900004E+01 9.000000E+01 4 2.671296E+02 8.976754E+01 1.083821E+00 2.671274E+02 - 1.900004E+01 9.000000E+01 5 1.656728E-04 -8.996049E+01 1.142378E-07 -1.656728E-04 - 1.900004E+01 9.000000E+01 6 1.391878E-05 1.799952E+02 -1.391878E-05 1.162848E-09 - 1.910004E+01 0.000000E+00 1 6.942786E+01 8.982114E+01 2.167330E-01 6.942752E+01 - 1.910004E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.910004E+01 0.000000E+00 3 1.560689E+02 7.261311E-01 1.560564E+02 1.977868E+00 - 1.910004E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.910004E+01 0.000000E+00 5 6.218000E+02 8.982114E+01 1.941159E+00 6.217969E+02 - 1.910004E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.910004E+01 3.000000E+01 1 6.068158E+01 8.982126E+01 1.893084E-01 6.068128E+01 - 1.910004E+01 3.000000E+01 2 3.701323E+01 8.976943E+01 1.489489E-01 3.701293E+01 - 1.910004E+01 3.000000E+01 3 1.577154E+02 7.300221E-01 1.577026E+02 2.009443E+00 - 1.910004E+01 3.000000E+01 4 1.257294E+02 8.976578E+01 5.139754E-01 1.257283E+02 - 1.910004E+01 3.000000E+01 5 5.435054E+02 8.982126E+01 1.695528E+00 5.435027E+02 - 1.910004E+01 3.000000E+01 6 1.554560E+02 -7.057612E-03 1.554560E+02 -1.914885E-02 - 1.910004E+01 6.000000E+01 1 3.568686E+01 8.982148E+01 1.111949E-01 3.568669E+01 - 1.910004E+01 6.000000E+01 2 6.543037E+01 8.976927E+01 2.634829E-01 6.542984E+01 - 1.910004E+01 6.000000E+01 3 1.610642E+02 7.378352E-01 1.610508E+02 2.074071E+00 - 1.910004E+01 6.000000E+01 4 2.257564E+02 8.976925E+01 9.091973E-01 2.257546E+02 - 1.910004E+01 6.000000E+01 5 3.195949E+02 8.982146E+01 9.959189E-01 3.195933E+02 - 1.910004E+01 6.000000E+01 6 1.587390E+02 -7.007251E-03 1.587390E+02 -1.941372E-02 - 1.910004E+01 9.000000E+01 1 3.749427E-06 -9.007568E+01 -4.952720E-09 -3.749424E-06 - 1.910004E+01 9.000000E+01 2 7.632726E+01 8.976920E+01 3.074666E-01 7.632664E+01 - 1.910004E+01 9.000000E+01 3 1.627665E+02 7.417550E-01 1.627528E+02 2.107127E+00 - 1.910004E+01 9.000000E+01 4 2.653554E+02 8.977091E+01 1.060974E+00 2.653533E+02 - 1.910004E+01 9.000000E+01 5 1.648544E-04 -8.996124E+01 1.115214E-07 -1.648543E-04 - 1.910004E+01 9.000000E+01 6 1.375006E-05 1.799953E+02 -1.375006E-05 1.117500E-09 - 1.920004E+01 0.000000E+00 1 6.907115E+01 8.982333E+01 2.129757E-01 6.907082E+01 - 1.920004E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.920004E+01 0.000000E+00 3 1.565803E+02 7.179950E-01 1.565680E+02 1.962116E+00 - 1.920004E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.920004E+01 0.000000E+00 5 6.202828E+02 8.982333E+01 1.912669E+00 6.202799E+02 - 1.920004E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.920004E+01 3.000000E+01 1 6.036312E+01 8.982344E+01 1.860089E-01 6.036284E+01 - 1.920004E+01 3.000000E+01 2 3.681923E+01 8.977277E+01 1.460243E-01 3.681894E+01 - 1.920004E+01 3.000000E+01 3 1.582106E+02 7.217817E-01 1.581981E+02 1.993000E+00 - 1.920004E+01 3.000000E+01 4 1.249795E+02 8.976920E+01 5.034329E-01 1.249784E+02 - 1.920004E+01 3.000000E+01 5 5.421082E+02 8.982345E+01 1.670478E+00 5.421056E+02 - 1.920004E+01 3.000000E+01 6 1.536496E+02 -6.864610E-03 1.536496E+02 -1.840876E-02 - 1.920004E+01 6.000000E+01 1 3.549138E+01 8.982365E+01 1.092358E-01 3.549121E+01 - 1.920004E+01 6.000000E+01 2 6.507050E+01 8.977261E+01 2.582391E-01 6.506998E+01 - 1.920004E+01 6.000000E+01 3 1.615269E+02 7.293875E-01 1.615138E+02 2.056216E+00 - 1.920004E+01 6.000000E+01 4 2.243149E+02 8.977259E+01 8.903069E-01 2.243131E+02 - 1.920004E+01 6.000000E+01 5 3.186985E+02 8.982363E+01 9.810125E-01 3.186970E+02 - 1.920004E+01 6.000000E+01 6 1.568531E+02 -6.816230E-03 1.568531E+02 -1.866014E-02 - 1.920004E+01 9.000000E+01 1 3.728017E-06 -9.007575E+01 -4.928615E-09 -3.728014E-06 - 1.920004E+01 9.000000E+01 2 7.589767E+01 8.977254E+01 3.013060E-01 7.589707E+01 - 1.920004E+01 9.000000E+01 3 1.632128E+02 7.332022E-01 1.631994E+02 2.088543E+00 - 1.920004E+01 9.000000E+01 4 2.636079E+02 8.977422E+01 1.038785E+00 2.636059E+02 - 1.920004E+01 9.000000E+01 5 1.640436E-04 -8.996197E+01 1.088889E-07 -1.640436E-04 - 1.920004E+01 9.000000E+01 6 1.358456E-05 1.799955E+02 -1.358456E-05 1.074242E-09 - 1.930004E+01 0.000000E+00 1 6.871840E+01 8.982549E+01 2.093058E-01 6.871808E+01 - 1.930004E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.930004E+01 0.000000E+00 3 1.570845E+02 7.099943E-01 1.570725E+02 1.946501E+00 - 1.930004E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.930004E+01 0.000000E+00 5 6.187471E+02 8.982548E+01 1.884677E+00 6.187443E+02 - 1.930004E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.930004E+01 3.000000E+01 1 6.004795E+01 8.982559E+01 1.827856E-01 6.004767E+01 - 1.930004E+01 3.000000E+01 2 3.662716E+01 8.977603E+01 1.431779E-01 3.662688E+01 - 1.930004E+01 3.000000E+01 3 1.586995E+02 7.136821E-01 1.586872E+02 1.976727E+00 - 1.930004E+01 3.000000E+01 4 1.242382E+02 8.977256E+01 4.931839E-01 1.242372E+02 - 1.930004E+01 3.000000E+01 5 5.407071E+02 8.982559E+01 1.645885E+00 5.407046E+02 - 1.930004E+01 3.000000E+01 6 1.518755E+02 -6.678335E-03 1.518755E+02 -1.770245E-02 - 1.930004E+01 6.000000E+01 1 3.529807E+01 8.982579E+01 1.073225E-01 3.529791E+01 - 1.930004E+01 6.000000E+01 2 6.471467E+01 8.977589E+01 2.531377E-01 6.471417E+01 - 1.930004E+01 6.000000E+01 3 1.619833E+02 7.210882E-01 1.619704E+02 2.038564E+00 - 1.930004E+01 6.000000E+01 4 2.228919E+02 8.977586E+01 8.719522E-01 2.228902E+02 - 1.930004E+01 6.000000E+01 5 3.178018E+02 8.982578E+01 9.663804E-01 3.178004E+02 - 1.930004E+01 6.000000E+01 6 1.550019E+02 -6.631880E-03 1.550019E+02 -1.794118E-02 - 1.930004E+01 9.000000E+01 1 3.706853E-06 -9.007578E+01 -4.903121E-09 -3.706850E-06 - 1.930004E+01 9.000000E+01 2 7.547302E+01 8.977581E+01 2.953140E-01 7.547244E+01 - 1.930004E+01 9.000000E+01 3 1.636519E+02 7.248065E-01 1.636389E+02 2.070184E+00 - 1.930004E+01 9.000000E+01 4 2.618840E+02 8.977745E+01 1.017237E+00 2.618820E+02 - 1.930004E+01 9.000000E+01 5 1.632413E-04 -8.996268E+01 1.063370E-07 -1.632413E-04 - 1.930004E+01 9.000000E+01 6 1.342214E-05 1.799956E+02 -1.342214E-05 1.032962E-09 - 1.940004E+01 0.000000E+00 1 6.836884E+01 8.982761E+01 2.057198E-01 6.836853E+01 - 1.940004E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.940004E+01 0.000000E+00 3 1.575827E+02 7.021175E-01 1.575708E+02 1.931011E+00 - 1.940004E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.940004E+01 0.000000E+00 5 6.172117E+02 8.982760E+01 1.857207E+00 6.172089E+02 - 1.940004E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.940004E+01 3.000000E+01 1 5.973589E+01 8.982770E+01 1.796385E-01 5.973562E+01 - 1.940004E+01 3.000000E+01 2 3.643702E+01 8.977922E+01 1.404070E-01 3.643675E+01 - 1.940004E+01 3.000000E+01 3 1.591822E+02 7.057143E-01 1.591701E+02 1.960603E+00 - 1.940004E+01 3.000000E+01 4 1.235057E+02 8.977583E+01 4.832211E-01 1.235048E+02 - 1.940004E+01 3.000000E+01 5 5.392993E+02 8.982771E+01 1.621748E+00 5.392968E+02 - 1.940004E+01 3.000000E+01 6 1.501328E+02 -6.498507E-03 1.501328E+02 -1.702811E-02 - 1.940004E+01 6.000000E+01 1 3.510679E+01 8.982790E+01 1.054539E-01 3.510663E+01 - 1.940004E+01 6.000000E+01 2 6.436284E+01 8.977908E+01 2.481732E-01 6.436236E+01 - 1.940004E+01 6.000000E+01 3 1.624339E+02 7.129310E-01 1.624213E+02 2.021111E+00 - 1.940004E+01 6.000000E+01 4 2.214881E+02 8.977905E+01 8.541104E-01 2.214865E+02 - 1.940004E+01 6.000000E+01 5 3.169031E+02 8.982787E+01 9.520346E-01 3.169017E+02 - 1.940004E+01 6.000000E+01 6 1.531846E+02 -6.453868E-03 1.531846E+02 -1.725490E-02 - 1.940004E+01 9.000000E+01 1 3.685946E-06 -9.007580E+01 -4.876348E-09 -3.685942E-06 - 1.940004E+01 9.000000E+01 2 7.505329E+01 8.977901E+01 2.894852E-01 7.505273E+01 - 1.940004E+01 9.000000E+01 3 1.640857E+02 7.165560E-01 1.640729E+02 2.052046E+00 - 1.940004E+01 9.000000E+01 4 2.601810E+02 8.978060E+01 9.962885E-01 2.601790E+02 - 1.940004E+01 9.000000E+01 5 1.624452E-04 -8.996336E+01 1.038618E-07 -1.624452E-04 - 1.940004E+01 9.000000E+01 6 1.326271E-05 1.799957E+02 -1.326271E-05 9.935558E-10 - 1.950004E+01 0.000000E+00 1 6.802279E+01 8.982967E+01 2.022174E-01 6.802249E+01 - 1.950004E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.950004E+01 0.000000E+00 3 1.580724E+02 6.943756E-01 1.580608E+02 1.915655E+00 - 1.950004E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.950004E+01 0.000000E+00 5 6.156529E+02 8.982967E+01 1.830267E+00 6.156501E+02 - 1.950004E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.950004E+01 3.000000E+01 1 5.942714E+01 8.982977E+01 1.765630E-01 5.942687E+01 - 1.950004E+01 3.000000E+01 2 3.624876E+01 8.978233E+01 1.377095E-01 3.624850E+01 - 1.950004E+01 3.000000E+01 3 1.596567E+02 6.978816E-01 1.596449E+02 1.944623E+00 - 1.950004E+01 3.000000E+01 4 1.227823E+02 8.977903E+01 4.735329E-01 1.227813E+02 - 1.950004E+01 3.000000E+01 5 5.378788E+02 8.982977E+01 1.598069E+00 5.378764E+02 - 1.950004E+01 3.000000E+01 6 1.484208E+02 -6.324852E-03 1.484208E+02 -1.638410E-02 - 1.950004E+01 6.000000E+01 1 3.491772E+01 8.982996E+01 1.036295E-01 3.491757E+01 - 1.950004E+01 6.000000E+01 2 6.401466E+01 8.978220E+01 2.433422E-01 6.401420E+01 - 1.950004E+01 6.000000E+01 3 1.628769E+02 7.049140E-01 1.628646E+02 2.003836E+00 - 1.950004E+01 6.000000E+01 4 2.201030E+02 8.978217E+01 8.367677E-01 2.201014E+02 - 1.950004E+01 6.000000E+01 5 3.159998E+02 8.982993E+01 9.379523E-01 3.159984E+02 - 1.950004E+01 6.000000E+01 6 1.514002E+02 -6.281951E-03 1.514002E+02 -1.659963E-02 - 1.950004E+01 9.000000E+01 1 3.665270E-06 -9.007579E+01 -4.848439E-09 -3.665266E-06 - 1.950004E+01 9.000000E+01 2 7.463833E+01 8.978214E+01 2.838138E-01 7.463779E+01 - 1.950004E+01 9.000000E+01 3 1.645125E+02 7.084419E-01 1.644999E+02 2.034086E+00 - 1.950004E+01 9.000000E+01 4 2.585056E+02 8.978369E+01 9.759369E-01 2.585038E+02 - 1.950004E+01 9.000000E+01 5 1.616570E-04 -8.996404E+01 1.014617E-07 -1.616569E-04 - 1.950004E+01 9.000000E+01 6 1.310622E-05 1.799958E+02 -1.310622E-05 9.559269E-10 - 1.960004E+01 0.000000E+00 1 6.768022E+01 8.983171E+01 1.987937E-01 6.767993E+01 - 1.960004E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.960004E+01 0.000000E+00 3 1.585559E+02 6.867648E-01 1.585445E+02 1.900454E+00 - 1.960004E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.960004E+01 0.000000E+00 5 6.140935E+02 8.983170E+01 1.803811E+00 6.140909E+02 - 1.960004E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.960004E+01 3.000000E+01 1 5.912159E+01 8.983180E+01 1.735587E-01 5.912133E+01 - 1.960004E+01 3.000000E+01 2 3.606258E+01 8.978539E+01 1.350825E-01 3.606233E+01 - 1.960004E+01 3.000000E+01 3 1.601251E+02 6.901776E-01 1.601135E+02 1.928800E+00 - 1.960004E+01 3.000000E+01 4 1.220670E+02 8.978216E+01 4.641080E-01 1.220661E+02 - 1.960004E+01 3.000000E+01 5 5.364617E+02 8.983181E+01 1.574792E+00 5.364594E+02 - 1.960004E+01 3.000000E+01 6 1.467386E+02 -6.157144E-03 1.467386E+02 -1.576889E-02 - 1.960004E+01 6.000000E+01 1 3.473074E+01 8.983198E+01 1.018475E-01 3.473059E+01 - 1.960004E+01 6.000000E+01 2 6.367042E+01 8.978526E+01 2.386403E-01 6.366998E+01 - 1.960004E+01 6.000000E+01 3 1.633143E+02 6.970323E-01 1.633022E+02 1.986753E+00 - 1.960004E+01 6.000000E+01 4 2.187356E+02 8.978523E+01 8.199068E-01 2.187341E+02 - 1.960004E+01 6.000000E+01 5 3.150946E+02 8.983196E+01 9.241250E-01 3.150932E+02 - 1.960004E+01 6.000000E+01 6 1.496480E+02 -6.115883E-03 1.496480E+02 -1.597377E-02 - 1.960004E+01 9.000000E+01 1 3.644839E-06 -9.007577E+01 -4.819454E-09 -3.644836E-06 - 1.960004E+01 9.000000E+01 2 7.422815E+01 8.978519E+01 2.782941E-01 7.422763E+01 - 1.960004E+01 9.000000E+01 3 1.649340E+02 7.004694E-01 1.649216E+02 2.016349E+00 - 1.960004E+01 9.000000E+01 4 2.568502E+02 8.978671E+01 9.561508E-01 2.568484E+02 - 1.960004E+01 9.000000E+01 5 1.608771E-04 -8.996470E+01 9.913363E-08 -1.608770E-04 - 1.960004E+01 9.000000E+01 6 1.295262E-05 1.799959E+02 -1.295262E-05 9.199813E-10 - 1.970004E+01 0.000000E+00 1 6.734092E+01 8.983371E+01 1.954481E-01 6.734064E+01 - 1.970004E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.970004E+01 0.000000E+00 3 1.590327E+02 6.792712E-01 1.590215E+02 1.885371E+00 - 1.970004E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.970004E+01 0.000000E+00 5 6.125246E+02 8.983370E+01 1.777803E+00 6.125220E+02 - 1.970004E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.970004E+01 3.000000E+01 1 5.881894E+01 8.983380E+01 1.706220E-01 5.881870E+01 - 1.970004E+01 3.000000E+01 2 3.587813E+01 8.978836E+01 1.325237E-01 3.587788E+01 - 1.970004E+01 3.000000E+01 3 1.605865E+02 6.826011E-01 1.605751E+02 1.913124E+00 - 1.970004E+01 3.000000E+01 4 1.213605E+02 8.978522E+01 4.549405E-01 1.213596E+02 - 1.970004E+01 3.000000E+01 5 5.350274E+02 8.983380E+01 1.551983E+00 5.350251E+02 - 1.970004E+01 3.000000E+01 6 1.450856E+02 -5.995097E-03 1.450856E+02 -1.518091E-02 - 1.970004E+01 6.000000E+01 1 3.454567E+01 8.983397E+01 1.001060E-01 3.454552E+01 - 1.970004E+01 6.000000E+01 2 6.332985E+01 8.978824E+01 2.340613E-01 6.332942E+01 - 1.970004E+01 6.000000E+01 3 1.637459E+02 6.892782E-01 1.637341E+02 1.969845E+00 - 1.970004E+01 6.000000E+01 4 2.173860E+02 8.978822E+01 8.035110E-01 2.173845E+02 - 1.970004E+01 6.000000E+01 5 3.141878E+02 8.983395E+01 9.105613E-01 3.141865E+02 - 1.970004E+01 6.000000E+01 6 1.479271E+02 -5.955416E-03 1.479271E+02 -1.537578E-02 - 1.970004E+01 9.000000E+01 1 3.624643E-06 -9.007571E+01 -4.789501E-09 -3.624640E-06 - 1.970004E+01 9.000000E+01 2 7.382257E+01 8.978818E+01 2.729210E-01 7.382207E+01 - 1.970004E+01 9.000000E+01 3 1.653496E+02 6.926309E-01 1.653375E+02 1.998811E+00 - 1.970004E+01 9.000000E+01 4 2.552161E+02 8.978967E+01 9.369106E-01 2.552144E+02 - 1.970004E+01 9.000000E+01 5 1.601036E-04 -8.996533E+01 9.687469E-08 -1.601036E-04 - 1.970004E+01 9.000000E+01 6 1.280180E-05 1.799960E+02 -1.280180E-05 8.856320E-10 - 1.980004E+01 0.000000E+00 1 6.700471E+01 8.983567E+01 1.921776E-01 6.700443E+01 - 1.980004E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.980004E+01 0.000000E+00 3 1.595020E+02 6.718988E-01 1.594910E+02 1.870412E+00 - 1.980004E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.980004E+01 0.000000E+00 5 6.109462E+02 8.983567E+01 1.752289E+00 6.109437E+02 - 1.980004E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.980004E+01 3.000000E+01 1 5.851933E+01 8.983575E+01 1.677530E-01 5.851908E+01 - 1.980004E+01 3.000000E+01 2 3.569559E+01 8.979129E+01 1.300312E-01 3.569535E+01 - 1.980004E+01 3.000000E+01 3 1.610419E+02 6.751460E-01 1.610307E+02 1.897596E+00 - 1.980004E+01 3.000000E+01 4 1.206626E+02 8.978822E+01 4.460172E-01 1.206618E+02 - 1.980004E+01 3.000000E+01 5 5.335878E+02 8.983575E+01 1.529572E+00 5.335856E+02 - 1.980004E+01 3.000000E+01 6 1.434617E+02 -5.838491E-03 1.434617E+02 -1.461887E-02 - 1.980004E+01 6.000000E+01 1 3.436272E+01 8.983592E+01 9.840482E-02 3.436258E+01 - 1.980004E+01 6.000000E+01 2 6.299330E+01 8.979116E+01 2.296038E-01 6.299288E+01 - 1.980004E+01 6.000000E+01 3 1.641703E+02 6.816542E-01 1.641586E+02 1.953106E+00 - 1.980004E+01 6.000000E+01 4 2.160534E+02 8.979115E+01 7.875615E-01 2.160520E+02 - 1.980004E+01 6.000000E+01 5 3.132790E+02 8.983590E+01 8.972627E-01 3.132777E+02 - 1.980004E+01 6.000000E+01 6 1.462366E+02 -5.800338E-03 1.462366E+02 -1.480426E-02 - 1.980004E+01 9.000000E+01 1 3.604679E-06 -9.007564E+01 -4.758652E-09 -3.604676E-06 - 1.980004E+01 9.000000E+01 2 7.342159E+01 8.979110E+01 2.676905E-01 7.342110E+01 - 1.980004E+01 9.000000E+01 3 1.657582E+02 6.849240E-01 1.657464E+02 1.981456E+00 - 1.980004E+01 9.000000E+01 4 2.536058E+02 8.979256E+01 9.182081E-01 2.536041E+02 - 1.980004E+01 9.000000E+01 5 1.593371E-04 -8.996596E+01 9.468278E-08 -1.593371E-04 - 1.980004E+01 9.000000E+01 6 1.265372E-05 1.799961E+02 -1.265372E-05 8.527974E-10 - 1.990004E+01 0.000000E+00 1 6.667184E+01 8.983759E+01 1.889807E-01 6.667157E+01 - 1.990004E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.990004E+01 0.000000E+00 3 1.599651E+02 6.646500E-01 1.599543E+02 1.855606E+00 - 1.990004E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.990004E+01 0.000000E+00 5 6.093580E+02 8.983759E+01 1.727242E+00 6.093556E+02 - 1.990004E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 1.990004E+01 3.000000E+01 1 5.822293E+01 8.983768E+01 1.649476E-01 5.822269E+01 - 1.990004E+01 3.000000E+01 2 3.551482E+01 8.979414E+01 1.276025E-01 3.551460E+01 - 1.990004E+01 3.000000E+01 3 1.614907E+02 6.678128E-01 1.614797E+02 1.882217E+00 - 1.990004E+01 3.000000E+01 4 1.199726E+02 8.979115E+01 4.373339E-01 1.199718E+02 - 1.990004E+01 3.000000E+01 5 5.321520E+02 8.983768E+01 1.507587E+00 5.321498E+02 - 1.990004E+01 3.000000E+01 6 1.418652E+02 -5.687098E-03 1.418652E+02 -1.408134E-02 - 1.990004E+01 6.000000E+01 1 3.418168E+01 8.983784E+01 9.674253E-02 3.418155E+01 - 1.990004E+01 6.000000E+01 2 6.266013E+01 8.979403E+01 2.252613E-01 6.265973E+01 - 1.990004E+01 6.000000E+01 3 1.645891E+02 6.741656E-01 1.645777E+02 1.936578E+00 - 1.990004E+01 6.000000E+01 4 2.147379E+02 8.979401E+01 7.720474E-01 2.147365E+02 - 1.990004E+01 6.000000E+01 5 3.123662E+02 8.983781E+01 8.842103E-01 3.123649E+02 - 1.990004E+01 6.000000E+01 6 1.445764E+02 -5.650376E-03 1.445764E+02 -1.425779E-02 - 1.990004E+01 9.000000E+01 1 3.584934E-06 -9.007555E+01 -4.727026E-09 -3.584930E-06 - 1.990004E+01 9.000000E+01 2 7.302515E+01 8.979396E+01 2.625970E-01 7.302467E+01 - 1.990004E+01 9.000000E+01 3 1.661619E+02 6.773497E-01 1.661503E+02 1.964318E+00 - 1.990004E+01 9.000000E+01 4 2.520165E+02 8.979539E+01 9.000081E-01 2.520149E+02 - 1.990004E+01 9.000000E+01 5 1.585784E-04 -8.996656E+01 9.255515E-08 -1.585784E-04 - 1.990004E+01 9.000000E+01 6 1.250827E-05 1.799962E+02 -1.250827E-05 8.214012E-10 - 2.000004E+01 0.000000E+00 1 6.634226E+01 8.983949E+01 1.858546E-01 6.634200E+01 - 2.000004E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.000004E+01 0.000000E+00 3 1.604220E+02 6.575137E-01 1.604115E+02 1.840927E+00 - 2.000004E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.000004E+01 0.000000E+00 5 6.077615E+02 8.983949E+01 1.702645E+00 6.077592E+02 - 2.000004E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.000004E+01 3.000000E+01 1 5.792927E+01 8.983957E+01 1.622059E-01 5.792904E+01 - 2.000004E+01 3.000000E+01 2 3.533589E+01 8.979694E+01 1.252355E-01 3.533567E+01 - 2.000004E+01 3.000000E+01 3 1.619333E+02 6.605989E-01 1.619226E+02 1.866989E+00 - 2.000004E+01 3.000000E+01 4 1.192906E+02 8.979401E+01 4.288814E-01 1.192898E+02 - 2.000004E+01 3.000000E+01 5 5.307010E+02 8.983957E+01 1.485988E+00 5.306990E+02 - 2.000004E+01 3.000000E+01 6 1.402961E+02 -5.540731E-03 1.402961E+02 -1.356720E-02 - 2.000004E+01 6.000000E+01 1 3.400243E+01 8.983972E+01 9.511802E-02 3.400230E+01 - 2.000004E+01 6.000000E+01 2 6.233058E+01 8.979683E+01 2.210312E-01 6.233019E+01 - 2.000004E+01 6.000000E+01 3 1.650017E+02 6.667956E-01 1.649906E+02 1.920210E+00 - 2.000004E+01 6.000000E+01 4 2.134400E+02 8.979681E+01 7.569461E-01 2.134387E+02 - 2.000004E+01 6.000000E+01 5 3.114556E+02 8.983970E+01 8.713866E-01 3.114543E+02 - 2.000004E+01 6.000000E+01 6 1.429450E+02 -5.505381E-03 1.429450E+02 -1.373516E-02 - 2.000004E+01 9.000000E+01 1 3.565423E-06 -9.007544E+01 -4.694682E-09 -3.565420E-06 - 2.000004E+01 9.000000E+01 2 7.263313E+01 8.979677E+01 2.576355E-01 7.263268E+01 - 2.000004E+01 9.000000E+01 3 1.665602E+02 6.698995E-01 1.665488E+02 1.947369E+00 - 2.000004E+01 9.000000E+01 4 2.504476E+02 8.979815E+01 8.823016E-01 2.504461E+02 - 2.000004E+01 9.000000E+01 5 1.578268E-04 -8.996715E+01 9.048949E-08 -1.578268E-04 - 2.000004E+01 9.000000E+01 6 1.236541E-05 1.799963E+02 -1.236541E-05 7.913703E-10 - 2.010004E+01 0.000000E+00 1 6.601561E+01 8.984135E+01 1.827983E-01 6.601536E+01 - 2.010004E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.010004E+01 0.000000E+00 3 1.608723E+02 6.504965E-01 1.608620E+02 1.826393E+00 - 2.010004E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.010004E+01 0.000000E+00 5 6.061603E+02 8.984135E+01 1.678491E+00 6.061580E+02 - 2.010004E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.010004E+01 3.000000E+01 1 5.763844E+01 8.984143E+01 1.595245E-01 5.763822E+01 - 2.010004E+01 3.000000E+01 2 3.515861E+01 8.979967E+01 1.229283E-01 3.515839E+01 - 2.010004E+01 3.000000E+01 3 1.623705E+02 6.535022E-01 1.623599E+02 1.851919E+00 - 2.010004E+01 3.000000E+01 4 1.186168E+02 8.979681E+01 4.206497E-01 1.186160E+02 - 2.010004E+01 3.000000E+01 5 5.292515E+02 8.984143E+01 1.464780E+00 5.292495E+02 - 2.010004E+01 3.000000E+01 6 1.387538E+02 -5.399149E-03 1.387538E+02 -1.307518E-02 - 2.010004E+01 6.000000E+01 1 3.382521E+01 8.984157E+01 9.352974E-02 3.382508E+01 - 2.010004E+01 6.000000E+01 2 6.200449E+01 8.979957E+01 2.169100E-01 6.200412E+01 - 2.010004E+01 6.000000E+01 3 1.654107E+02 6.595407E-01 1.653997E+02 1.904026E+00 - 2.010004E+01 6.000000E+01 4 2.121576E+02 8.979955E+01 7.422479E-01 2.121563E+02 - 2.010004E+01 6.000000E+01 5 3.105449E+02 8.984155E+01 8.588048E-01 3.105437E+02 - 2.010004E+01 6.000000E+01 6 1.413419E+02 -5.365128E-03 1.413419E+02 -1.323513E-02 - 2.010004E+01 9.000000E+01 1 3.546126E-06 -9.007532E+01 -4.661665E-09 -3.546123E-06 - 2.010004E+01 9.000000E+01 2 7.224520E+01 8.979951E+01 2.528028E-01 7.224476E+01 - 2.010004E+01 9.000000E+01 3 1.669528E+02 6.625724E-01 1.669416E+02 1.930611E+00 - 2.010004E+01 9.000000E+01 4 2.488997E+02 8.980087E+01 8.650754E-01 2.488982E+02 - 2.010004E+01 9.000000E+01 5 1.570815E-04 -8.996773E+01 8.848377E-08 -1.570815E-04 - 2.010004E+01 9.000000E+01 6 1.222509E-05 1.799964E+02 -1.222509E-05 7.626365E-10 - 2.020004E+01 0.000000E+00 1 6.569223E+01 8.984318E+01 1.798095E-01 6.569199E+01 - 2.020004E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.020004E+01 0.000000E+00 3 1.613166E+02 6.435845E-01 1.613064E+02 1.811978E+00 - 2.020004E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.020004E+01 0.000000E+00 5 6.045582E+02 8.984318E+01 1.654773E+00 6.045560E+02 - 2.020004E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.020004E+01 3.000000E+01 1 5.735064E+01 8.984325E+01 1.569035E-01 5.735043E+01 - 2.020004E+01 3.000000E+01 2 3.498322E+01 8.980235E+01 1.206792E-01 3.498301E+01 - 2.020004E+01 3.000000E+01 3 1.628003E+02 6.465209E-01 1.627899E+02 1.836986E+00 - 2.020004E+01 3.000000E+01 4 1.179500E+02 8.979956E+01 4.126361E-01 1.179493E+02 - 2.020004E+01 3.000000E+01 5 5.278019E+02 8.984325E+01 1.443964E+00 5.278000E+02 - 2.020004E+01 3.000000E+01 6 1.372371E+02 -5.262219E-03 1.372371E+02 -1.260427E-02 - 2.020004E+01 6.000000E+01 1 3.364986E+01 8.984338E+01 9.197762E-02 3.364973E+01 - 2.020004E+01 6.000000E+01 2 6.168205E+01 8.980224E+01 2.128942E-01 6.168168E+01 - 2.020004E+01 6.000000E+01 3 1.658120E+02 6.524107E-01 1.658013E+02 1.888013E+00 - 2.020004E+01 6.000000E+01 4 2.108919E+02 8.980223E+01 7.279456E-01 2.108907E+02 - 2.020004E+01 6.000000E+01 5 3.096325E+02 8.984337E+01 8.464613E-01 3.096313E+02 - 2.020004E+01 6.000000E+01 6 1.397670E+02 -5.229436E-03 1.397670E+02 -1.275665E-02 - 2.020004E+01 9.000000E+01 1 3.527041E-06 -9.007518E+01 -4.628080E-09 -3.527038E-06 - 2.020004E+01 9.000000E+01 2 7.186182E+01 8.980219E+01 2.480940E-01 7.186139E+01 - 2.020004E+01 9.000000E+01 3 1.673397E+02 6.553698E-01 1.673287E+02 1.914050E+00 - 2.020004E+01 9.000000E+01 4 2.473715E+02 8.980352E+01 8.483040E-01 2.473701E+02 - 2.020004E+01 9.000000E+01 5 1.563432E-04 -8.996829E+01 8.653625E-08 -1.563432E-04 - 2.020004E+01 9.000000E+01 6 1.208725E-05 1.799965E+02 -1.208725E-05 7.351357E-10 - 2.030004E+01 0.000000E+00 1 6.537163E+01 8.984496E+01 1.768856E-01 6.537139E+01 - 2.030004E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.030004E+01 0.000000E+00 3 1.617542E+02 6.367794E-01 1.617442E+02 1.797682E+00 - 2.030004E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.030004E+01 0.000000E+00 5 6.029449E+02 8.984496E+01 1.631472E+00 6.029427E+02 - 2.030004E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.030004E+01 3.000000E+01 1 5.706572E+01 8.984504E+01 1.543395E-01 5.706551E+01 - 2.030004E+01 3.000000E+01 2 3.480951E+01 8.980498E+01 1.184862E-01 3.480930E+01 - 2.030004E+01 3.000000E+01 3 1.632244E+02 6.396463E-01 1.632142E+02 1.822188E+00 - 2.030004E+01 3.000000E+01 4 1.172912E+02 8.980224E+01 4.048288E-01 1.172905E+02 - 2.030004E+01 3.000000E+01 5 5.263376E+02 8.984504E+01 1.423520E+00 5.263356E+02 - 2.030004E+01 3.000000E+01 6 1.357458E+02 -5.129692E-03 1.357458E+02 -1.215333E-02 - 2.030004E+01 6.000000E+01 1 3.347633E+01 8.984518E+01 9.046014E-02 3.347621E+01 - 2.030004E+01 6.000000E+01 2 6.136294E+01 8.980487E+01 2.089788E-01 6.136259E+01 - 2.030004E+01 6.000000E+01 3 1.662077E+02 6.453947E-01 1.661971E+02 1.872167E+00 - 2.030004E+01 6.000000E+01 4 2.096410E+02 8.980486E+01 7.140174E-01 2.096398E+02 - 2.030004E+01 6.000000E+01 5 3.087147E+02 8.984515E+01 8.343419E-01 3.087136E+02 - 2.030004E+01 6.000000E+01 6 1.382186E+02 -5.098135E-03 1.382186E+02 -1.229859E-02 - 2.030004E+01 9.000000E+01 1 3.508177E-06 -9.007504E+01 -4.593992E-09 -3.508174E-06 - 2.030004E+01 9.000000E+01 2 7.148273E+01 8.980482E+01 2.435053E-01 7.148232E+01 - 2.030004E+01 9.000000E+01 3 1.677212E+02 6.482777E-01 1.677105E+02 1.897655E+00 - 2.030004E+01 9.000000E+01 4 2.458635E+02 8.980611E+01 8.319848E-01 2.458621E+02 - 2.030004E+01 9.000000E+01 5 1.556109E-04 -8.996883E+01 8.464443E-08 -1.556108E-04 - 2.030004E+01 9.000000E+01 6 1.195181E-05 1.799966E+02 -1.195181E-05 7.088051E-10 - 2.040004E+01 0.000000E+00 1 6.505441E+01 8.984673E+01 1.740260E-01 6.505418E+01 - 2.040004E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.040004E+01 0.000000E+00 3 1.621866E+02 6.300892E-01 1.621768E+02 1.783551E+00 - 2.040004E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.040004E+01 0.000000E+00 5 6.013277E+02 8.984673E+01 1.608596E+00 6.013256E+02 - 2.040004E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.040004E+01 3.000000E+01 1 5.678340E+01 8.984679E+01 1.518325E-01 5.678320E+01 - 2.040004E+01 3.000000E+01 2 3.463754E+01 8.980754E+01 1.163479E-01 3.463734E+01 - 2.040004E+01 3.000000E+01 3 1.636433E+02 6.328843E-01 1.636333E+02 1.807553E+00 - 2.040004E+01 3.000000E+01 4 1.166399E+02 8.980488E+01 3.972221E-01 1.166392E+02 - 2.040004E+01 3.000000E+01 5 5.248781E+02 8.984680E+01 1.403457E+00 5.248762E+02 - 2.040004E+01 3.000000E+01 6 1.342797E+02 -5.001434E-03 1.342797E+02 -1.172147E-02 - 2.040004E+01 6.000000E+01 1 3.330465E+01 8.984693E+01 8.897616E-02 3.330453E+01 - 2.040004E+01 6.000000E+01 2 6.104716E+01 8.980745E+01 2.051624E-01 6.104681E+01 - 2.040004E+01 6.000000E+01 3 1.665987E+02 6.384989E-01 1.665884E+02 1.856522E+00 - 2.040004E+01 6.000000E+01 4 2.084066E+02 8.980743E+01 7.004500E-01 2.084054E+02 - 2.040004E+01 6.000000E+01 5 3.078017E+02 8.984691E+01 8.224401E-01 3.078006E+02 - 2.040004E+01 6.000000E+01 6 1.366971E+02 -4.971014E-03 1.366971E+02 -1.185991E-02 - 2.040004E+01 9.000000E+01 1 3.489508E-06 -9.007486E+01 -4.559416E-09 -3.489505E-06 - 2.040004E+01 9.000000E+01 2 7.110738E+01 8.980740E+01 2.390324E-01 7.110697E+01 - 2.040004E+01 9.000000E+01 3 1.680971E+02 6.413115E-01 1.680865E+02 1.881471E+00 - 2.040004E+01 9.000000E+01 4 2.443733E+02 8.980866E+01 8.160858E-01 2.443720E+02 - 2.040004E+01 9.000000E+01 5 1.548858E-04 -8.996937E+01 8.280615E-08 -1.548858E-04 - 2.040004E+01 9.000000E+01 6 1.181870E-05 1.799967E+02 -1.181870E-05 6.835885E-10 - 2.050004E+01 0.000000E+00 1 6.474009E+01 8.984846E+01 1.712274E-01 6.473986E+01 - 2.050004E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.050004E+01 0.000000E+00 3 1.626125E+02 6.234991E-01 1.626029E+02 1.769532E+00 - 2.050004E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.050004E+01 0.000000E+00 5 5.997079E+02 8.984846E+01 1.586125E+00 5.997059E+02 - 2.050004E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.050004E+01 3.000000E+01 1 5.650393E+01 8.984853E+01 1.493797E-01 5.650373E+01 - 2.050004E+01 3.000000E+01 2 3.446715E+01 8.981007E+01 1.142618E-01 3.446696E+01 - 2.050004E+01 3.000000E+01 3 1.640561E+02 6.262299E-01 1.640463E+02 1.793061E+00 - 2.050004E+01 3.000000E+01 4 1.159960E+02 8.980746E+01 3.898126E-01 1.159953E+02 - 2.050004E+01 3.000000E+01 5 5.234153E+02 8.984853E+01 1.383736E+00 5.234135E+02 - 2.050004E+01 3.000000E+01 6 1.328376E+02 -4.877278E-03 1.328376E+02 -1.130774E-02 - 2.050004E+01 6.000000E+01 1 3.313467E+01 8.984866E+01 8.752491E-02 3.313456E+01 - 2.050004E+01 6.000000E+01 2 6.073477E+01 8.980997E+01 2.014418E-01 6.073443E+01 - 2.050004E+01 6.000000E+01 3 1.669841E+02 6.317062E-01 1.669740E+02 1.841022E+00 - 2.050004E+01 6.000000E+01 4 2.071870E+02 8.980995E+01 6.872378E-01 2.071858E+02 - 2.050004E+01 6.000000E+01 5 3.068885E+02 8.984863E+01 8.107663E-01 3.068875E+02 - 2.050004E+01 6.000000E+01 6 1.352013E+02 -4.847961E-03 1.352013E+02 -1.143977E-02 - 2.050004E+01 9.000000E+01 1 3.471049E-06 -9.007468E+01 -4.524483E-09 -3.471046E-06 - 2.050004E+01 9.000000E+01 2 7.073632E+01 8.980992E+01 2.346719E-01 7.073593E+01 - 2.050004E+01 9.000000E+01 3 1.684690E+02 6.344550E-01 1.684587E+02 1.865475E+00 - 2.050004E+01 9.000000E+01 4 2.429040E+02 8.981116E+01 8.006036E-01 2.429027E+02 - 2.050004E+01 9.000000E+01 5 1.541678E-04 -8.996989E+01 8.102046E-08 -1.541678E-04 - 2.050004E+01 9.000000E+01 6 1.168791E-05 1.799968E+02 -1.168791E-05 6.594332E-10 - 2.060004E+01 0.000000E+00 1 6.442854E+01 8.985017E+01 1.684904E-01 6.442831E+01 - 2.060004E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.060004E+01 0.000000E+00 3 1.630331E+02 6.170130E-01 1.630237E+02 1.755655E+00 - 2.060004E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.060004E+01 0.000000E+00 5 5.980828E+02 8.985017E+01 1.564067E+00 5.980807E+02 - 2.060004E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.060004E+01 3.000000E+01 1 5.622699E+01 8.985023E+01 1.469798E-01 5.622680E+01 - 2.060004E+01 3.000000E+01 2 3.429849E+01 8.981253E+01 1.122268E-01 3.429831E+01 - 2.060004E+01 3.000000E+01 3 1.644636E+02 6.196801E-01 1.644540E+02 1.778714E+00 - 2.060004E+01 3.000000E+01 4 1.153591E+02 8.980998E+01 3.825918E-01 1.153585E+02 - 2.060004E+01 3.000000E+01 5 5.219458E+02 8.985023E+01 1.364384E+00 5.219440E+02 - 2.060004E+01 3.000000E+01 6 1.314194E+02 -4.757043E-03 1.314194E+02 -1.091124E-02 - 2.060004E+01 6.000000E+01 1 3.296656E+01 8.985035E+01 8.610546E-02 3.296645E+01 - 2.060004E+01 6.000000E+01 2 6.042552E+01 8.981243E+01 1.978129E-01 6.042519E+01 - 2.060004E+01 6.000000E+01 3 1.673642E+02 6.250291E-01 1.673542E+02 1.825709E+00 - 2.060004E+01 6.000000E+01 4 2.059819E+02 8.981242E+01 6.743651E-01 2.059808E+02 - 2.060004E+01 6.000000E+01 5 3.059727E+02 8.985033E+01 7.992912E-01 3.059717E+02 - 2.060004E+01 6.000000E+01 6 1.337309E+02 -4.728779E-03 1.337309E+02 -1.103718E-02 - 2.060004E+01 9.000000E+01 1 3.452798E-06 -9.007449E+01 -4.489176E-09 -3.452795E-06 - 2.060004E+01 9.000000E+01 2 7.036932E+01 8.981239E+01 2.304207E-01 7.036894E+01 - 2.060004E+01 9.000000E+01 3 1.688353E+02 6.277081E-01 1.688251E+02 1.849650E+00 - 2.060004E+01 9.000000E+01 4 2.414518E+02 8.981360E+01 7.855271E-01 2.414505E+02 - 2.060004E+01 9.000000E+01 5 1.534564E-04 -8.997040E+01 7.928448E-08 -1.534564E-04 - 2.060004E+01 9.000000E+01 6 1.155933E-05 1.799969E+02 -1.155933E-05 6.362832E-10 - 2.070004E+01 0.000000E+00 1 6.412022E+01 8.985184E+01 1.658124E-01 6.412000E+01 - 2.070004E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.070004E+01 0.000000E+00 3 1.634482E+02 6.106256E-01 1.634389E+02 1.741905E+00 - 2.070004E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.070004E+01 0.000000E+00 5 5.964514E+02 8.985184E+01 1.542398E+00 5.964493E+02 - 2.070004E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.070004E+01 3.000000E+01 1 5.595306E+01 8.985190E+01 1.446317E-01 5.595288E+01 - 2.070004E+01 3.000000E+01 2 3.413142E+01 8.981494E+01 1.102414E-01 3.413124E+01 - 2.070004E+01 3.000000E+01 3 1.648655E+02 6.132323E-01 1.648561E+02 1.764509E+00 - 2.070004E+01 3.000000E+01 4 1.147300E+02 8.981245E+01 3.755530E-01 1.147294E+02 - 2.070004E+01 3.000000E+01 5 5.204780E+02 8.985190E+01 1.345384E+00 5.204763E+02 - 2.070004E+01 3.000000E+01 6 1.300244E+02 -4.640601E-03 1.300244E+02 -1.053116E-02 - 2.070004E+01 6.000000E+01 1 3.280011E+01 8.985201E+01 8.471688E-02 3.280000E+01 - 2.070004E+01 6.000000E+01 2 6.011945E+01 8.981485E+01 1.942734E-01 6.011913E+01 - 2.070004E+01 6.000000E+01 3 1.677389E+02 6.184556E-01 1.677292E+02 1.810553E+00 - 2.070004E+01 6.000000E+01 4 2.047917E+02 8.981483E+01 6.618194E-01 2.047907E+02 - 2.070004E+01 6.000000E+01 5 3.050566E+02 8.985199E+01 7.880349E-01 3.050556E+02 - 2.070004E+01 6.000000E+01 6 1.322850E+02 -4.613339E-03 1.322850E+02 -1.065131E-02 - 2.070004E+01 9.000000E+01 1 3.434739E-06 -9.007429E+01 -4.453538E-09 -3.434736E-06 - 2.070004E+01 9.000000E+01 2 7.000589E+01 8.981481E+01 2.262746E-01 7.000552E+01 - 2.070004E+01 9.000000E+01 3 1.691965E+02 6.210708E-01 1.691866E+02 1.834009E+00 - 2.070004E+01 9.000000E+01 4 2.400188E+02 8.981599E+01 7.708381E-01 2.400176E+02 - 2.070004E+01 9.000000E+01 5 1.527502E-04 -8.997089E+01 7.759730E-08 -1.527502E-04 - 2.070004E+01 9.000000E+01 6 1.143296E-05 1.799969E+02 -1.143296E-05 6.140952E-10 - 2.080004E+01 0.000000E+00 1 6.381456E+01 8.985349E+01 1.631899E-01 6.381435E+01 - 2.080004E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.080004E+01 0.000000E+00 3 1.638572E+02 6.043389E-01 1.638481E+02 1.728285E+00 - 2.080004E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.080004E+01 0.000000E+00 5 5.948220E+02 8.985349E+01 1.521102E+00 5.948200E+02 - 2.080004E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.080004E+01 3.000000E+01 1 5.568153E+01 8.985354E+01 1.423347E-01 5.568134E+01 - 2.080004E+01 3.000000E+01 2 3.396597E+01 8.981731E+01 1.083039E-01 3.396580E+01 - 2.080004E+01 3.000000E+01 3 1.652620E+02 6.068804E-01 1.652527E+02 1.750433E+00 - 2.080004E+01 3.000000E+01 4 1.141076E+02 8.981487E+01 3.686909E-01 1.141070E+02 - 2.080004E+01 3.000000E+01 5 5.190084E+02 8.985354E+01 1.326702E+00 5.190067E+02 - 2.080004E+01 3.000000E+01 6 1.286520E+02 -4.527792E-03 1.286520E+02 -1.016671E-02 - 2.080004E+01 6.000000E+01 1 3.263537E+01 8.985365E+01 8.335859E-02 3.263527E+01 - 2.080004E+01 6.000000E+01 2 5.981660E+01 8.981722E+01 1.908207E-01 5.981630E+01 - 2.080004E+01 6.000000E+01 3 1.681095E+02 6.119814E-01 1.680999E+02 1.795558E+00 - 2.080004E+01 6.000000E+01 4 2.036151E+02 8.981721E+01 6.495958E-01 2.036141E+02 - 2.080004E+01 6.000000E+01 5 3.041458E+02 8.985363E+01 7.769811E-01 3.041448E+02 - 2.080004E+01 6.000000E+01 6 1.308632E+02 -4.501495E-03 1.308632E+02 -1.028139E-02 - 2.080004E+01 9.000000E+01 1 3.416880E-06 -9.007407E+01 -4.417677E-09 -3.416877E-06 - 2.080004E+01 9.000000E+01 2 6.964664E+01 8.981718E+01 2.222306E-01 6.964629E+01 - 2.080004E+01 9.000000E+01 3 1.695526E+02 6.145399E-01 1.695428E+02 1.818543E+00 - 2.080004E+01 9.000000E+01 4 2.386036E+02 8.981834E+01 7.565217E-01 2.386024E+02 - 2.080004E+01 9.000000E+01 5 1.520502E-04 -8.997137E+01 7.595667E-08 -1.520501E-04 - 2.080004E+01 9.000000E+01 6 1.130872E-05 1.799970E+02 -1.130872E-05 5.928200E-10 - 2.090004E+01 0.000000E+00 1 6.351139E+01 8.985509E+01 1.606237E-01 6.351119E+01 - 2.090004E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.090004E+01 0.000000E+00 3 1.642611E+02 5.981480E-01 1.642521E+02 1.714797E+00 - 2.090004E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.090004E+01 0.000000E+00 5 5.931834E+02 8.985510E+01 1.500171E+00 5.931815E+02 - 2.090004E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.090004E+01 3.000000E+01 1 5.541267E+01 8.985516E+01 1.400858E-01 5.541249E+01 - 2.090004E+01 3.000000E+01 2 3.380206E+01 8.981963E+01 1.064127E-01 3.380189E+01 - 2.090004E+01 3.000000E+01 3 1.656524E+02 6.006361E-01 1.656433E+02 1.736515E+00 - 2.090004E+01 3.000000E+01 4 1.134919E+02 8.981725E+01 3.619986E-01 1.134913E+02 - 2.090004E+01 3.000000E+01 5 5.175372E+02 8.985516E+01 1.308356E+00 5.175355E+02 - 2.090004E+01 3.000000E+01 6 1.273019E+02 -4.418476E-03 1.273019E+02 -9.817134E-03 - 2.090004E+01 6.000000E+01 1 3.247225E+01 8.985526E+01 8.202945E-02 3.247215E+01 - 2.090004E+01 6.000000E+01 2 5.951677E+01 8.981954E+01 1.874512E-01 5.951647E+01 - 2.090004E+01 6.000000E+01 3 1.684745E+02 6.056167E-01 1.684651E+02 1.780743E+00 - 2.090004E+01 6.000000E+01 4 2.024531E+02 8.981953E+01 6.376822E-01 2.024521E+02 - 2.090004E+01 6.000000E+01 5 3.032299E+02 8.985524E+01 7.661338E-01 3.032289E+02 - 2.090004E+01 6.000000E+01 6 1.294651E+02 -4.393109E-03 1.294651E+02 -9.926637E-03 - 2.090004E+01 9.000000E+01 1 3.399201E-06 -9.007386E+01 -4.381584E-09 -3.399198E-06 - 2.090004E+01 9.000000E+01 2 6.929110E+01 8.981950E+01 2.182860E-01 6.929076E+01 - 2.090004E+01 9.000000E+01 3 1.699045E+02 6.081139E-01 1.698949E+02 1.803263E+00 - 2.090004E+01 9.000000E+01 4 2.372046E+02 8.982063E+01 7.425726E-01 2.372035E+02 - 2.090004E+01 9.000000E+01 5 1.513574E-04 -8.997185E+01 7.436127E-08 -1.513574E-04 - 2.090004E+01 9.000000E+01 6 1.118656E-05 1.799971E+02 -1.118656E-05 5.724159E-10 - 2.100004E+01 0.000000E+00 1 6.321159E+01 8.985669E+01 1.581123E-01 6.321140E+01 - 2.100004E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.100004E+01 0.000000E+00 3 1.646583E+02 5.920571E-01 1.646495E+02 1.701441E+00 - 2.100004E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.100004E+01 0.000000E+00 5 5.915450E+02 8.985669E+01 1.479630E+00 5.915432E+02 - 2.100004E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.100004E+01 3.000000E+01 1 5.514629E+01 8.985674E+01 1.378856E-01 5.514612E+01 - 2.100004E+01 3.000000E+01 2 3.363964E+01 8.982190E+01 1.045666E-01 3.363948E+01 - 2.100004E+01 3.000000E+01 3 1.660384E+02 5.944797E-01 1.660295E+02 1.722722E+00 - 2.100004E+01 3.000000E+01 4 1.128829E+02 8.981958E+01 3.554713E-01 1.128823E+02 - 2.100004E+01 3.000000E+01 5 5.160685E+02 8.985674E+01 1.290331E+00 5.160669E+02 - 2.100004E+01 3.000000E+01 6 1.259733E+02 -4.312538E-03 1.259733E+02 -9.481760E-03 - 2.100004E+01 6.000000E+01 1 3.231078E+01 8.985685E+01 8.072911E-02 3.231068E+01 - 2.100004E+01 6.000000E+01 2 5.922005E+01 8.982182E+01 1.841640E-01 5.921976E+01 - 2.100004E+01 6.000000E+01 3 1.688344E+02 5.993465E-01 1.688251E+02 1.766071E+00 - 2.100004E+01 6.000000E+01 4 2.013048E+02 8.982181E+01 6.260641E-01 2.013038E+02 - 2.100004E+01 6.000000E+01 5 3.023165E+02 8.985682E+01 7.554740E-01 3.023156E+02 - 2.100004E+01 6.000000E+01 6 1.280900E+02 -4.288050E-03 1.280900E+02 -9.586333E-03 - 2.100004E+01 9.000000E+01 1 3.381708E-06 -9.007362E+01 -4.345329E-09 -3.381705E-06 - 2.100004E+01 9.000000E+01 2 6.893932E+01 8.982178E+01 2.144361E-01 6.893898E+01 - 2.100004E+01 9.000000E+01 3 1.702522E+02 6.017843E-01 1.702428E+02 1.788146E+00 - 2.100004E+01 9.000000E+01 4 2.358240E+02 8.982289E+01 7.289737E-01 2.358228E+02 - 2.100004E+01 9.000000E+01 5 1.506705E-04 -8.997231E+01 7.281010E-08 -1.506704E-04 - 2.100004E+01 9.000000E+01 6 1.106645E-05 1.799971E+02 -1.106645E-05 5.528405E-10 - 2.110004E+01 0.000000E+00 1 6.291412E+01 8.985825E+01 1.556526E-01 6.291393E+01 - 2.110004E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.110004E+01 0.000000E+00 3 1.650519E+02 5.860521E-01 1.650433E+02 1.688211E+00 - 2.110004E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.110004E+01 0.000000E+00 5 5.899127E+02 8.985825E+01 1.459441E+00 5.899108E+02 - 2.110004E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.110004E+01 3.000000E+01 1 5.488240E+01 8.985831E+01 1.357310E-01 5.488223E+01 - 2.110004E+01 3.000000E+01 2 3.347894E+01 8.982413E+01 1.027637E-01 3.347878E+01 - 2.110004E+01 3.000000E+01 3 1.664191E+02 5.884231E-01 1.664103E+02 1.709080E+00 - 2.110004E+01 3.000000E+01 4 1.122806E+02 8.982185E+01 3.491066E-01 1.122801E+02 - 2.110004E+01 3.000000E+01 5 5.145932E+02 8.985831E+01 1.272644E+00 5.145916E+02 - 2.110004E+01 3.000000E+01 6 1.246663E+02 -4.209812E-03 1.246663E+02 -9.159866E-03 - 2.110004E+01 6.000000E+01 1 3.215103E+01 8.985840E+01 7.945626E-02 3.215093E+01 - 2.110004E+01 6.000000E+01 2 5.892637E+01 8.982405E+01 1.809549E-01 5.892609E+01 - 2.110004E+01 6.000000E+01 3 1.691900E+02 5.931741E-01 1.691809E+02 1.751566E+00 - 2.110004E+01 6.000000E+01 4 2.001701E+02 8.982404E+01 6.147355E-01 2.001692E+02 - 2.110004E+01 6.000000E+01 5 3.014066E+02 8.985838E+01 7.450023E-01 3.014057E+02 - 2.110004E+01 6.000000E+01 6 1.267374E+02 -4.186208E-03 1.267374E+02 -9.259829E-03 - 2.110004E+01 9.000000E+01 1 3.364417E-06 -9.007338E+01 -4.308923E-09 -3.364414E-06 - 2.110004E+01 9.000000E+01 2 6.859097E+01 8.982402E+01 2.106795E-01 6.859065E+01 - 2.110004E+01 9.000000E+01 3 1.705944E+02 5.955566E-01 1.705852E+02 1.773198E+00 - 2.110004E+01 9.000000E+01 4 2.344595E+02 8.982510E+01 7.157160E-01 2.344584E+02 - 2.110004E+01 9.000000E+01 5 1.499893E-04 -8.997276E+01 7.130098E-08 -1.499893E-04 - 2.110004E+01 9.000000E+01 6 1.094833E-05 1.799972E+02 -1.094833E-05 5.340559E-10 - 2.120004E+01 0.000000E+00 1 6.261952E+01 8.985979E+01 1.532447E-01 6.261933E+01 - 2.120004E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.120004E+01 0.000000E+00 3 1.654395E+02 5.801370E-01 1.654310E+02 1.675096E+00 - 2.120004E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.120004E+01 0.000000E+00 5 5.882706E+02 8.985979E+01 1.439604E+00 5.882689E+02 - 2.120004E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.120004E+01 3.000000E+01 1 5.462117E+01 8.985983E+01 1.336218E-01 5.462101E+01 - 2.120004E+01 3.000000E+01 2 3.331966E+01 8.982632E+01 1.010039E-01 3.331951E+01 - 2.120004E+01 3.000000E+01 3 1.667948E+02 5.824519E-01 1.667862E+02 1.695557E+00 - 2.120004E+01 3.000000E+01 4 1.116853E+02 8.982409E+01 3.428971E-01 1.116847E+02 - 2.120004E+01 3.000000E+01 5 5.131204E+02 8.985983E+01 1.255259E+00 5.131188E+02 - 2.120004E+01 3.000000E+01 6 1.233801E+02 -4.110220E-03 1.233801E+02 -8.850900E-03 - 2.120004E+01 6.000000E+01 1 3.199291E+01 8.985994E+01 7.821047E-02 3.199281E+01 - 2.120004E+01 6.000000E+01 2 5.863548E+01 8.982624E+01 1.778218E-01 5.863521E+01 - 2.120004E+01 6.000000E+01 3 1.695406E+02 5.871015E-01 1.695318E+02 1.737228E+00 - 2.120004E+01 6.000000E+01 4 1.990490E+02 8.982623E+01 6.036870E-01 1.990481E+02 - 2.120004E+01 6.000000E+01 5 3.004943E+02 8.985991E+01 7.347198E-01 3.004934E+02 - 2.120004E+01 6.000000E+01 6 1.254070E+02 -4.087419E-03 1.254070E+02 -8.946401E-03 - 2.120004E+01 9.000000E+01 1 3.347297E-06 -9.007314E+01 -4.272425E-09 -3.347295E-06 - 2.120004E+01 9.000000E+01 2 6.824651E+01 8.982620E+01 2.070131E-01 6.824620E+01 - 2.120004E+01 9.000000E+01 3 1.709321E+02 5.894273E-01 1.709230E+02 1.758423E+00 - 2.120004E+01 9.000000E+01 4 2.331120E+02 8.982727E+01 7.027883E-01 2.331109E+02 - 2.120004E+01 9.000000E+01 5 1.493142E-04 -8.997321E+01 6.983249E-08 -1.493142E-04 - 2.120004E+01 9.000000E+01 6 1.083215E-05 1.799973E+02 -1.083215E-05 5.160244E-10 - 2.130005E+01 0.000000E+00 1 6.232783E+01 8.986130E+01 1.508870E-01 6.232764E+01 - 2.130005E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.130005E+01 0.000000E+00 3 1.658223E+02 5.743163E-01 1.658140E+02 1.662127E+00 - 2.130005E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.130005E+01 0.000000E+00 5 5.866271E+02 8.986130E+01 1.420107E+00 5.866254E+02 - 2.130005E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.130005E+01 3.000000E+01 1 5.436221E+01 8.986134E+01 1.315567E-01 5.436205E+01 - 2.130005E+01 3.000000E+01 2 3.316186E+01 8.982846E+01 9.928485E-02 3.316171E+01 - 2.130005E+01 3.000000E+01 3 1.671654E+02 5.765816E-01 1.671569E+02 1.682198E+00 - 2.130005E+01 3.000000E+01 4 1.110960E+02 8.982629E+01 3.368384E-01 1.110955E+02 - 2.130005E+01 3.000000E+01 5 5.116482E+02 8.986134E+01 1.238179E+00 5.116467E+02 - 2.130005E+01 3.000000E+01 6 1.221137E+02 -4.013660E-03 1.221137E+02 -8.554257E-03 - 2.130005E+01 6.000000E+01 1 3.183622E+01 8.986144E+01 7.699062E-02 3.183612E+01 - 2.130005E+01 6.000000E+01 2 5.834761E+01 8.982839E+01 1.747638E-01 5.834734E+01 - 2.130005E+01 6.000000E+01 3 1.698870E+02 5.811199E-01 1.698782E+02 1.723041E+00 - 2.130005E+01 6.000000E+01 4 1.979413E+02 8.982838E+01 5.929118E-01 1.979405E+02 - 2.130005E+01 6.000000E+01 5 2.995831E+02 8.986142E+01 7.246204E-01 2.995822E+02 - 2.130005E+01 6.000000E+01 6 1.240979E+02 -3.991625E-03 1.240979E+02 -8.645531E-03 - 2.130005E+01 9.000000E+01 1 3.330355E-06 -9.007288E+01 -4.235849E-09 -3.330353E-06 - 2.130005E+01 9.000000E+01 2 6.790550E+01 8.982835E+01 2.034333E-01 6.790520E+01 - 2.130005E+01 9.000000E+01 3 1.712655E+02 5.833960E-01 1.712566E+02 1.743826E+00 - 2.130005E+01 9.000000E+01 4 2.317809E+02 8.982939E+01 6.901794E-01 2.317798E+02 - 2.130005E+01 9.000000E+01 5 1.486448E-04 -8.997363E+01 6.840413E-08 -1.486447E-04 - 2.130005E+01 9.000000E+01 6 1.071788E-05 1.799973E+02 -1.071788E-05 4.987119E-10 - 2.140005E+01 0.000000E+00 1 6.203843E+01 8.986279E+01 1.485775E-01 6.203825E+01 - 2.140005E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.140005E+01 0.000000E+00 3 1.662000E+02 5.685813E-01 1.661918E+02 1.649278E+00 - 2.140005E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.140005E+01 0.000000E+00 5 5.849853E+02 8.986279E+01 1.400969E+00 5.849836E+02 - 2.140005E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.140005E+01 3.000000E+01 1 5.410566E+01 8.986282E+01 1.295345E-01 5.410550E+01 - 2.140005E+01 3.000000E+01 2 3.300554E+01 8.983056E+01 9.760576E-02 3.300539E+01 - 2.140005E+01 3.000000E+01 3 1.675312E+02 5.707949E-01 1.675228E+02 1.668960E+00 - 2.140005E+01 3.000000E+01 4 1.105131E+02 8.982843E+01 3.309246E-01 1.105126E+02 - 2.140005E+01 3.000000E+01 5 5.101770E+02 8.986283E+01 1.221408E+00 5.101755E+02 - 2.140005E+01 3.000000E+01 6 1.208675E+02 -3.919979E-03 1.208675E+02 -8.269336E-03 - 2.140005E+01 6.000000E+01 1 3.168116E+01 8.986292E+01 7.579711E-02 3.168107E+01 - 2.140005E+01 6.000000E+01 2 5.806268E+01 8.983049E+01 1.717770E-01 5.806242E+01 - 2.140005E+01 6.000000E+01 3 1.702287E+02 5.752325E-01 1.702201E+02 1.709016E+00 - 2.140005E+01 6.000000E+01 4 1.968455E+02 8.983048E+01 5.823973E-01 1.968446E+02 - 2.140005E+01 6.000000E+01 5 2.986749E+02 8.986290E+01 7.146987E-01 2.986740E+02 - 2.140005E+01 6.000000E+01 6 1.228098E+02 -3.898692E-03 1.228098E+02 -8.356597E-03 - 2.140005E+01 9.000000E+01 1 3.313598E-06 -9.007261E+01 -4.199223E-09 -3.313595E-06 - 2.140005E+01 9.000000E+01 2 6.756801E+01 8.983046E+01 1.999397E-01 6.756771E+01 - 2.140005E+01 9.000000E+01 3 1.715948E+02 5.774541E-01 1.715860E+02 1.729384E+00 - 2.140005E+01 9.000000E+01 4 2.304656E+02 8.983147E+01 6.778837E-01 2.304646E+02 - 2.140005E+01 9.000000E+01 5 1.479810E-04 -8.997405E+01 6.701373E-08 -1.479809E-04 - 2.140005E+01 9.000000E+01 6 1.060548E-05 1.799974E+02 -1.060548E-05 4.820866E-10 - 2.150005E+01 0.000000E+00 1 6.175196E+01 8.986425E+01 1.463160E-01 6.175179E+01 - 2.150005E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.150005E+01 0.000000E+00 3 1.665725E+02 5.629305E-01 1.665645E+02 1.636547E+00 - 2.150005E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.150005E+01 0.000000E+00 5 5.833430E+02 8.986425E+01 1.382147E+00 5.833413E+02 - 2.150005E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.150005E+01 3.000000E+01 1 5.385172E+01 8.986429E+01 1.275541E-01 5.385157E+01 - 2.150005E+01 3.000000E+01 2 3.285075E+01 8.983263E+01 9.596533E-02 3.285061E+01 - 2.150005E+01 3.000000E+01 3 1.678927E+02 5.650940E-01 1.678846E+02 1.655857E+00 - 2.150005E+01 3.000000E+01 4 1.099366E+02 8.983054E+01 3.251544E-01 1.099361E+02 - 2.150005E+01 3.000000E+01 5 5.087033E+02 8.986429E+01 1.204916E+00 5.087019E+02 - 2.150005E+01 3.000000E+01 6 1.196407E+02 -3.829093E-03 1.196407E+02 -7.995619E-03 - 2.150005E+01 6.000000E+01 1 3.152754E+01 8.986438E+01 7.462784E-02 3.152746E+01 - 2.150005E+01 6.000000E+01 2 5.778044E+01 8.983256E+01 1.688604E-01 5.778019E+01 - 2.150005E+01 6.000000E+01 3 1.705653E+02 5.694318E-01 1.705569E+02 1.695129E+00 - 2.150005E+01 6.000000E+01 4 1.957619E+02 8.983255E+01 5.721402E-01 1.957611E+02 - 2.150005E+01 6.000000E+01 5 2.977689E+02 8.986436E+01 7.049621E-01 2.977680E+02 - 2.150005E+01 6.000000E+01 6 1.215423E+02 -3.808532E-03 1.215423E+02 -8.079089E-03 - 2.150005E+01 9.000000E+01 1 3.297014E-06 -9.007234E+01 -4.162584E-09 -3.297011E-06 - 2.150005E+01 9.000000E+01 2 6.723403E+01 8.983252E+01 1.965273E-01 6.723374E+01 - 2.150005E+01 9.000000E+01 3 1.719196E+02 5.716041E-01 1.719111E+02 1.715106E+00 - 2.150005E+01 9.000000E+01 4 2.291658E+02 8.983352E+01 6.658836E-01 2.291648E+02 - 2.150005E+01 9.000000E+01 5 1.473238E-04 -8.997446E+01 6.566022E-08 -1.473238E-04 - 2.150005E+01 9.000000E+01 6 1.049490E-05 1.799975E+02 -1.049490E-05 4.661145E-10 - 2.160005E+01 0.000000E+00 1 6.146769E+01 8.986568E+01 1.441004E-01 6.146752E+01 - 2.160005E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.160005E+01 0.000000E+00 3 1.669404E+02 5.573655E-01 1.669325E+02 1.623948E+00 - 2.160005E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.160005E+01 0.000000E+00 5 5.816965E+02 8.986568E+01 1.363655E+00 5.816949E+02 - 2.160005E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.160005E+01 3.000000E+01 1 5.359994E+01 8.986572E+01 1.256144E-01 5.359979E+01 - 2.160005E+01 3.000000E+01 2 3.269737E+01 8.983465E+01 9.436276E-02 3.269723E+01 - 2.160005E+01 3.000000E+01 3 1.682483E+02 5.594834E-01 1.682403E+02 1.642890E+00 - 2.160005E+01 3.000000E+01 4 1.093665E+02 8.983261E+01 3.195192E-01 1.093660E+02 - 2.160005E+01 3.000000E+01 5 5.072311E+02 8.986572E+01 1.188723E+00 5.072297E+02 - 2.160005E+01 3.000000E+01 6 1.184330E+02 -3.740890E-03 1.184330E+02 -7.732589E-03 - 2.160005E+01 6.000000E+01 1 3.137555E+01 8.986581E+01 7.348310E-02 3.137546E+01 - 2.160005E+01 6.000000E+01 2 5.750114E+01 8.983458E+01 1.660112E-01 5.750090E+01 - 2.160005E+01 6.000000E+01 3 1.708976E+02 5.637235E-01 1.708893E+02 1.681405E+00 - 2.160005E+01 6.000000E+01 4 1.946926E+02 8.983457E+01 5.621283E-01 1.946917E+02 - 2.160005E+01 6.000000E+01 5 2.968618E+02 8.986579E+01 6.953874E-01 2.968609E+02 - 2.160005E+01 6.000000E+01 6 1.202948E+02 -3.721021E-03 1.202948E+02 -7.812435E-03 - 2.160005E+01 9.000000E+01 1 3.280595E-06 -9.007206E+01 -4.125944E-09 -3.280593E-06 - 2.160005E+01 9.000000E+01 2 6.690331E+01 8.983455E+01 1.931945E-01 6.690302E+01 - 2.160005E+01 9.000000E+01 3 1.722387E+02 5.658488E-01 1.722303E+02 1.700989E+00 - 2.160005E+01 9.000000E+01 4 2.278819E+02 8.983553E+01 6.541724E-01 2.278809E+02 - 2.160005E+01 9.000000E+01 5 1.466718E-04 -8.997487E+01 6.434252E-08 -1.466718E-04 - 2.160005E+01 9.000000E+01 6 1.038609E-05 1.799975E+02 -1.038609E-05 4.507669E-10 - 2.170005E+01 0.000000E+00 1 6.118621E+01 8.986710E+01 1.419300E-01 6.118605E+01 - 2.170005E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.170005E+01 0.000000E+00 3 1.673034E+02 5.518878E-01 1.672957E+02 1.611485E+00 - 2.170005E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.170005E+01 0.000000E+00 5 5.800552E+02 8.986710E+01 1.345487E+00 5.800536E+02 - 2.170005E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.170005E+01 3.000000E+01 1 5.335066E+01 8.986713E+01 1.237141E-01 5.335051E+01 - 2.170005E+01 3.000000E+01 2 3.254532E+01 8.983663E+01 9.279647E-02 3.254519E+01 - 2.170005E+01 3.000000E+01 3 1.686000E+02 5.539546E-01 1.685921E+02 1.630056E+00 - 2.170005E+01 3.000000E+01 4 1.088019E+02 8.983464E+01 3.140184E-01 1.088015E+02 - 2.170005E+01 3.000000E+01 5 5.057626E+02 8.986714E+01 1.172791E+00 5.057612E+02 - 2.170005E+01 3.000000E+01 6 1.172439E+02 -3.655281E-03 1.172439E+02 -7.479773E-03 - 2.170005E+01 6.000000E+01 1 3.122495E+01 8.986722E+01 7.236214E-02 3.122487E+01 - 2.170005E+01 6.000000E+01 2 5.722442E+01 8.983657E+01 1.632275E-01 5.722419E+01 - 2.170005E+01 6.000000E+01 3 1.712260E+02 5.581045E-01 1.712178E+02 1.667845E+00 - 2.170005E+01 6.000000E+01 4 1.936340E+02 8.983656E+01 5.523558E-01 1.936332E+02 - 2.170005E+01 6.000000E+01 5 2.959577E+02 8.986720E+01 6.859781E-01 2.959569E+02 - 2.170005E+01 6.000000E+01 6 1.190674E+02 -3.636078E-03 1.190674E+02 -7.556202E-03 - 2.170005E+01 9.000000E+01 1 3.264335E-06 -9.007178E+01 -4.089379E-09 -3.264332E-06 - 2.170005E+01 9.000000E+01 2 6.657600E+01 8.983654E+01 1.899386E-01 6.657572E+01 - 2.170005E+01 9.000000E+01 3 1.725552E+02 5.601832E-01 1.725470E+02 1.687053E+00 - 2.170005E+01 9.000000E+01 4 2.266125E+02 8.983749E+01 6.427448E-01 2.266116E+02 - 2.170005E+01 9.000000E+01 5 1.460258E-04 -8.997526E+01 6.305931E-08 -1.460258E-04 - 2.170005E+01 9.000000E+01 6 1.027902E-05 1.799976E+02 -1.027902E-05 4.360170E-10 - 2.180005E+01 0.000000E+00 1 6.090726E+01 8.986848E+01 1.398032E-01 6.090710E+01 - 2.180005E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.180005E+01 0.000000E+00 3 1.676612E+02 5.464816E-01 1.676535E+02 1.599112E+00 - 2.180005E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.180005E+01 0.000000E+00 5 5.784138E+02 8.986848E+01 1.327620E+00 5.784122E+02 - 2.180005E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.180005E+01 3.000000E+01 1 5.310334E+01 8.986853E+01 1.218527E-01 5.310320E+01 - 2.180005E+01 3.000000E+01 2 3.239473E+01 8.983858E+01 9.126551E-02 3.239460E+01 - 2.180005E+01 3.000000E+01 3 1.689474E+02 5.485032E-01 1.689396E+02 1.617340E+00 - 2.180005E+01 3.000000E+01 4 1.082436E+02 8.983662E+01 3.086476E-01 1.082431E+02 - 2.180005E+01 3.000000E+01 5 5.042939E+02 8.986853E+01 1.157151E+00 5.042926E+02 - 2.180005E+01 3.000000E+01 6 1.160730E+02 -3.572175E-03 1.160730E+02 -7.236714E-03 - 2.180005E+01 6.000000E+01 1 3.107590E+01 8.986861E+01 7.126382E-02 3.107582E+01 - 2.180005E+01 6.000000E+01 2 5.695058E+01 8.983852E+01 1.605081E-01 5.695035E+01 - 2.180005E+01 6.000000E+01 3 1.715500E+02 5.525618E-01 1.715420E+02 1.654407E+00 - 2.180005E+01 6.000000E+01 4 1.925879E+02 8.983851E+01 5.428147E-01 1.925871E+02 - 2.180005E+01 6.000000E+01 5 2.950564E+02 8.986858E+01 6.767493E-01 2.950557E+02 - 2.180005E+01 6.000000E+01 6 1.178590E+02 -3.553607E-03 1.178590E+02 -7.309865E-03 - 2.180005E+01 9.000000E+01 1 3.248258E-06 -9.007149E+01 -4.052839E-09 -3.248256E-06 - 2.180005E+01 9.000000E+01 2 6.625190E+01 8.983849E+01 1.867585E-01 6.625163E+01 - 2.180005E+01 9.000000E+01 3 1.728678E+02 5.545917E-01 1.728596E+02 1.673239E+00 - 2.180005E+01 9.000000E+01 4 2.253576E+02 8.983942E+01 6.315912E-01 2.253568E+02 - 2.180005E+01 9.000000E+01 5 1.453838E-04 -8.997564E+01 6.181024E-08 -1.453838E-04 - 2.180005E+01 9.000000E+01 6 1.017367E-05 1.799976E+02 -1.017367E-05 4.218362E-10 - 2.190005E+01 0.000000E+00 1 6.063079E+01 8.986986E+01 1.377197E-01 6.063063E+01 - 2.190005E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.190005E+01 0.000000E+00 3 1.680152E+02 5.411572E-01 1.680077E+02 1.586875E+00 - 2.190005E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.190005E+01 0.000000E+00 5 5.767661E+02 8.986986E+01 1.310061E+00 5.767646E+02 - 2.190005E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.190005E+01 3.000000E+01 1 5.285872E+01 8.986990E+01 1.200289E-01 5.285858E+01 - 2.190005E+01 3.000000E+01 2 3.224557E+01 8.984049E+01 8.976915E-02 3.224544E+01 - 2.190005E+01 3.000000E+01 3 1.692900E+02 5.431344E-01 1.692824E+02 1.604757E+00 - 2.190005E+01 3.000000E+01 4 1.076909E+02 8.983858E+01 3.034011E-01 1.076905E+02 - 2.190005E+01 3.000000E+01 5 5.028245E+02 8.986990E+01 1.141775E+00 5.028232E+02 - 2.190005E+01 3.000000E+01 6 1.149203E+02 -3.491472E-03 1.149203E+02 -7.002978E-03 - 2.190005E+01 6.000000E+01 1 3.092817E+01 8.986998E+01 7.018826E-02 3.092809E+01 - 2.190005E+01 6.000000E+01 2 5.667926E+01 8.984044E+01 1.578502E-01 5.667904E+01 - 2.190005E+01 6.000000E+01 3 1.718700E+02 5.471047E-01 1.718622E+02 1.641123E+00 - 2.190005E+01 6.000000E+01 4 1.915538E+02 8.984042E+01 5.335016E-01 1.915531E+02 - 2.190005E+01 6.000000E+01 5 2.941549E+02 8.986995E+01 6.676727E-01 2.941541E+02 - 2.190005E+01 6.000000E+01 6 1.166695E+02 -3.473520E-03 1.166695E+02 -7.073014E-03 - 2.190005E+01 9.000000E+01 1 3.232331E-06 -9.007120E+01 -4.016376E-09 -3.232328E-06 - 2.190005E+01 9.000000E+01 2 6.593121E+01 8.984040E+01 1.836506E-01 6.593095E+01 - 2.190005E+01 9.000000E+01 3 1.731751E+02 5.490936E-01 1.731672E+02 1.659597E+00 - 2.190005E+01 9.000000E+01 4 2.241180E+02 8.984132E+01 6.207018E-01 2.241171E+02 - 2.190005E+01 9.000000E+01 5 1.447487E-04 -8.997601E+01 6.059328E-08 -1.447486E-04 - 2.190005E+01 9.000000E+01 6 1.006997E-05 1.799977E+02 -1.006997E-05 4.081997E-10 - 2.200005E+01 0.000000E+00 1 6.035680E+01 8.987121E+01 1.356777E-01 6.035665E+01 - 2.200005E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.200005E+01 0.000000E+00 3 1.683641E+02 5.359118E-01 1.683568E+02 1.574758E+00 - 2.200005E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.200005E+01 0.000000E+00 5 5.751278E+02 8.987121E+01 1.292816E+00 5.751263E+02 - 2.200005E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.200005E+01 3.000000E+01 1 5.261614E+01 8.987124E+01 1.182418E-01 5.261601E+01 - 2.200005E+01 3.000000E+01 2 3.209763E+01 8.984237E+01 8.830625E-02 3.209751E+01 - 2.200005E+01 3.000000E+01 3 1.696278E+02 5.378510E-01 1.696203E+02 1.592319E+00 - 2.200005E+01 3.000000E+01 4 1.071438E+02 8.984050E+01 2.982757E-01 1.071434E+02 - 2.200005E+01 3.000000E+01 5 5.013560E+02 8.987124E+01 1.126672E+00 5.013547E+02 - 2.200005E+01 3.000000E+01 6 1.137848E+02 -3.413100E-03 1.137848E+02 -6.778141E-03 - 2.200005E+01 6.000000E+01 1 3.078190E+01 8.987132E+01 6.913461E-02 3.078182E+01 - 2.200005E+01 6.000000E+01 2 5.641064E+01 8.984232E+01 1.552524E-01 5.641043E+01 - 2.200005E+01 6.000000E+01 3 1.721860E+02 5.417319E-01 1.721783E+02 1.627995E+00 - 2.200005E+01 6.000000E+01 4 1.905308E+02 8.984230E+01 5.244043E-01 1.905301E+02 - 2.200005E+01 6.000000E+01 5 2.932545E+02 8.987129E+01 6.587522E-01 2.932538E+02 - 2.200005E+01 6.000000E+01 6 1.154984E+02 -3.395742E-03 1.154984E+02 -6.845228E-03 - 2.200005E+01 9.000000E+01 1 3.216569E-06 -9.007089E+01 -3.980032E-09 -3.216566E-06 - 2.200005E+01 9.000000E+01 2 6.561368E+01 8.984228E+01 1.806138E-01 6.561343E+01 - 2.200005E+01 9.000000E+01 3 1.734805E+02 5.436727E-01 1.734727E+02 1.646111E+00 - 2.200005E+01 9.000000E+01 4 2.228934E+02 8.984319E+01 6.100681E-01 2.228926E+02 - 2.200005E+01 9.000000E+01 5 1.441191E-04 -8.997639E+01 5.940745E-08 -1.441191E-04 - 2.200005E+01 9.000000E+01 6 9.967895E-06 1.799977E+02 -9.967895E-06 3.950835E-10 - 2.210005E+01 0.000000E+00 1 6.008511E+01 8.987253E+01 1.336762E-01 6.008496E+01 - 2.210005E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.210005E+01 0.000000E+00 3 1.687092E+02 5.307443E-01 1.687020E+02 1.562771E+00 - 2.210005E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.210005E+01 0.000000E+00 5 5.734885E+02 8.987254E+01 1.275833E+00 5.734871E+02 - 2.210005E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.210005E+01 3.000000E+01 1 5.237580E+01 8.987257E+01 1.164903E-01 5.237568E+01 - 2.210005E+01 3.000000E+01 2 3.195111E+01 8.984422E+01 8.687587E-02 3.195099E+01 - 2.210005E+01 3.000000E+01 3 1.699618E+02 5.326432E-01 1.699544E+02 1.580006E+00 - 2.210005E+01 3.000000E+01 4 1.066027E+02 8.984238E+01 2.932694E-01 1.066023E+02 - 2.210005E+01 3.000000E+01 5 4.998937E+02 8.987257E+01 1.111814E+00 4.998925E+02 - 2.210005E+01 3.000000E+01 6 1.126665E+02 -3.336977E-03 1.126665E+02 -6.561836E-03 - 2.210005E+01 6.000000E+01 1 3.063708E+01 8.987264E+01 6.810214E-02 3.063701E+01 - 2.210005E+01 6.000000E+01 2 5.614452E+01 8.984416E+01 1.527131E-01 5.614431E+01 - 2.210005E+01 6.000000E+01 3 1.724972E+02 5.364386E-01 1.724897E+02 1.615003E+00 - 2.210005E+01 6.000000E+01 4 1.895200E+02 8.984415E+01 5.155184E-01 1.895193E+02 - 2.210005E+01 6.000000E+01 5 2.923587E+02 8.987262E+01 6.499888E-01 2.923580E+02 - 2.210005E+01 6.000000E+01 6 1.143454E+02 -3.320177E-03 1.143454E+02 -6.626091E-03 - 2.210005E+01 9.000000E+01 1 3.200958E-06 -9.007059E+01 -3.943783E-09 -3.200955E-06 - 2.210005E+01 9.000000E+01 2 6.529917E+01 8.984413E+01 1.776451E-01 6.529893E+01 - 2.210005E+01 9.000000E+01 3 1.737801E+02 5.383422E-01 1.737724E+02 1.632786E+00 - 2.210005E+01 9.000000E+01 4 2.216816E+02 8.984501E+01 5.996847E-01 2.216808E+02 - 2.210005E+01 9.000000E+01 5 1.434940E-04 -8.997674E+01 5.825240E-08 -1.434940E-04 - 2.210005E+01 9.000000E+01 6 9.867438E-06 1.799978E+02 -9.867438E-06 3.824653E-10 - 2.220005E+01 0.000000E+00 1 5.981580E+01 8.987383E+01 1.317142E-01 5.981566E+01 - 2.220005E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.220005E+01 0.000000E+00 3 1.690494E+02 5.256490E-01 1.690423E+02 1.550889E+00 - 2.220005E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.220005E+01 0.000000E+00 5 5.718513E+02 8.987384E+01 1.259161E+00 5.718499E+02 - 2.220005E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.220005E+01 3.000000E+01 1 5.213771E+01 8.987387E+01 1.147740E-01 5.213758E+01 - 2.220005E+01 3.000000E+01 2 3.180588E+01 8.984602E+01 8.547690E-02 3.180576E+01 - 2.220005E+01 3.000000E+01 3 1.702915E+02 5.275040E-01 1.702843E+02 1.567797E+00 - 2.220005E+01 3.000000E+01 4 1.060671E+02 8.984422E+01 2.883778E-01 1.060667E+02 - 2.220005E+01 3.000000E+01 5 4.984298E+02 8.987387E+01 1.097223E+00 4.984286E+02 - 2.220005E+01 3.000000E+01 6 1.115650E+02 -3.263013E-03 1.115650E+02 -6.353665E-03 - 2.220005E+01 6.000000E+01 1 3.049358E+01 8.987394E+01 6.709035E-02 3.049351E+01 - 2.220005E+01 6.000000E+01 2 5.588098E+01 8.984597E+01 1.502306E-01 5.588078E+01 - 2.220005E+01 6.000000E+01 3 1.728050E+02 5.312185E-01 1.727976E+02 1.602141E+00 - 2.220005E+01 6.000000E+01 4 1.885188E+02 8.984595E+01 5.068418E-01 1.885181E+02 - 2.220005E+01 6.000000E+01 5 2.914639E+02 8.987392E+01 6.413736E-01 2.914632E+02 - 2.220005E+01 6.000000E+01 6 1.132102E+02 -3.246761E-03 1.132102E+02 -6.415244E-03 - 2.220005E+01 9.000000E+01 1 3.185517E-06 -9.007029E+01 -3.907673E-09 -3.185514E-06 - 2.220005E+01 9.000000E+01 2 6.498784E+01 8.984594E+01 1.747441E-01 6.498760E+01 - 2.220005E+01 9.000000E+01 3 1.740767E+02 5.330843E-01 1.740692E+02 1.619599E+00 - 2.220005E+01 9.000000E+01 4 2.204834E+02 8.984680E+01 5.895447E-01 2.204826E+02 - 2.220005E+01 9.000000E+01 5 1.428752E-04 -8.997710E+01 5.712690E-08 -1.428752E-04 - 2.220005E+01 9.000000E+01 6 9.768516E-06 1.799978E+02 -9.768516E-06 3.703224E-10 - 2.230005E+01 0.000000E+00 1 5.954891E+01 8.987512E+01 1.297910E-01 5.954877E+01 - 2.230005E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.230005E+01 0.000000E+00 3 1.693851E+02 5.206265E-01 1.693782E+02 1.539122E+00 - 2.230005E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.230005E+01 0.000000E+00 5 5.702155E+02 8.987513E+01 1.242772E+00 5.702141E+02 - 2.230005E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.230005E+01 3.000000E+01 1 5.190144E+01 8.987515E+01 1.130914E-01 5.190132E+01 - 2.230005E+01 3.000000E+01 2 3.166203E+01 8.984780E+01 8.410879E-02 3.166191E+01 - 2.230005E+01 3.000000E+01 3 1.706168E+02 5.224418E-01 1.706097E+02 1.555719E+00 - 2.230005E+01 3.000000E+01 4 1.055370E+02 8.984604E+01 2.835975E-01 1.055366E+02 - 2.230005E+01 3.000000E+01 5 4.969723E+02 8.987515E+01 1.082875E+00 4.969711E+02 - 2.230005E+01 3.000000E+01 6 1.104799E+02 -3.191143E-03 1.104799E+02 -6.153282E-03 - 2.230005E+01 6.000000E+01 1 3.035161E+01 8.987522E+01 6.609912E-02 3.035154E+01 - 2.230005E+01 6.000000E+01 2 5.561997E+01 8.984775E+01 1.478033E-01 5.561978E+01 - 2.230005E+01 6.000000E+01 3 1.731088E+02 5.260794E-01 1.731015E+02 1.589431E+00 - 2.230005E+01 6.000000E+01 4 1.875295E+02 8.984774E+01 4.983612E-01 1.875289E+02 - 2.230005E+01 6.000000E+01 5 2.905703E+02 8.987521E+01 6.329147E-01 2.905696E+02 - 2.230005E+01 6.000000E+01 6 1.120922E+02 -3.175411E-03 1.120922E+02 -6.212304E-03 - 2.230005E+01 9.000000E+01 1 3.170218E-06 -9.006997E+01 -3.871713E-09 -3.170216E-06 - 2.230005E+01 9.000000E+01 2 6.467928E+01 8.984772E+01 1.719072E-01 6.467905E+01 - 2.230005E+01 9.000000E+01 3 1.743694E+02 5.279021E-01 1.743620E+02 1.606552E+00 - 2.230005E+01 9.000000E+01 4 2.193003E+02 8.984856E+01 5.796371E-01 2.192995E+02 - 2.230005E+01 9.000000E+01 5 1.422606E-04 -8.997744E+01 5.602987E-08 -1.422606E-04 - 2.230005E+01 9.000000E+01 6 9.671127E-06 1.799979E+02 -9.671127E-06 3.586343E-10 - 2.240005E+01 0.000000E+00 1 5.928447E+01 8.987638E+01 1.279064E-01 5.928434E+01 - 2.240005E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.240005E+01 0.000000E+00 3 1.697171E+02 5.156795E-01 1.697102E+02 1.527485E+00 - 2.240005E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.240005E+01 0.000000E+00 5 5.685760E+02 8.987639E+01 1.226670E+00 5.685746E+02 - 2.240005E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.240005E+01 3.000000E+01 1 5.166759E+01 8.987642E+01 1.114418E-01 5.166747E+01 - 2.240005E+01 3.000000E+01 2 3.151941E+01 8.984954E+01 8.277039E-02 3.151930E+01 - 2.240005E+01 3.000000E+01 3 1.709379E+02 5.174570E-01 1.709310E+02 1.543776E+00 - 2.240005E+01 3.000000E+01 4 1.050123E+02 8.984782E+01 2.789247E-01 1.050119E+02 - 2.240005E+01 3.000000E+01 5 4.955127E+02 8.987642E+01 1.068766E+00 4.955115E+02 - 2.240005E+01 3.000000E+01 6 1.094111E+02 -3.121288E-03 1.094111E+02 -5.960361E-03 - 2.240005E+01 6.000000E+01 1 3.021082E+01 8.987649E+01 6.512718E-02 3.021075E+01 - 2.240005E+01 6.000000E+01 2 5.536131E+01 8.984949E+01 1.454293E-01 5.536111E+01 - 2.240005E+01 6.000000E+01 3 1.734088E+02 5.210173E-01 1.734016E+02 1.576865E+00 - 2.240005E+01 6.000000E+01 4 1.865516E+02 8.984948E+01 4.900765E-01 1.865509E+02 - 2.240005E+01 6.000000E+01 5 2.896793E+02 8.987646E+01 6.245902E-01 2.896786E+02 - 2.240005E+01 6.000000E+01 6 1.109913E+02 -3.106060E-03 1.109913E+02 -6.016947E-03 - 2.240005E+01 9.000000E+01 1 3.155059E-06 -9.006966E+01 -3.835916E-09 -3.155057E-06 - 2.240005E+01 9.000000E+01 2 6.437397E+01 8.984946E+01 1.691330E-01 6.437375E+01 - 2.240005E+01 9.000000E+01 3 1.746581E+02 5.228024E-01 1.746509E+02 1.593668E+00 - 2.240005E+01 9.000000E+01 4 2.181295E+02 8.985030E+01 5.699567E-01 2.181288E+02 - 2.240005E+01 9.000000E+01 5 1.416516E-04 -8.997777E+01 5.496045E-08 -1.416516E-04 - 2.240005E+01 9.000000E+01 6 9.575243E-06 1.799979E+02 -9.575243E-06 3.473817E-10 - 2.250005E+01 0.000000E+00 1 5.902221E+01 8.987763E+01 1.260573E-01 5.902208E+01 - 2.250005E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.250005E+01 0.000000E+00 3 1.700447E+02 5.108026E-01 1.700380E+02 1.515961E+00 - 2.250005E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.250005E+01 0.000000E+00 5 5.669478E+02 8.987763E+01 1.210813E+00 5.669465E+02 - 2.250005E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.250005E+01 3.000000E+01 1 5.143571E+01 8.987766E+01 1.098251E-01 5.143559E+01 - 2.250005E+01 3.000000E+01 2 3.137811E+01 8.985126E+01 8.146127E-02 3.137801E+01 - 2.250005E+01 3.000000E+01 3 1.712562E+02 5.125394E-01 1.712494E+02 1.531952E+00 - 2.250005E+01 3.000000E+01 4 1.044927E+02 8.984956E+01 2.743582E-01 1.044923E+02 - 2.250005E+01 3.000000E+01 5 4.940579E+02 8.987766E+01 1.054901E+00 4.940568E+02 - 2.250005E+01 3.000000E+01 6 1.083581E+02 -3.053386E-03 1.083581E+02 -5.774582E-03 - 2.250005E+01 6.000000E+01 1 3.007125E+01 8.987773E+01 6.417476E-02 3.007118E+01 - 2.250005E+01 6.000000E+01 2 5.510530E+01 8.985121E+01 1.431075E-01 5.510511E+01 - 2.250005E+01 6.000000E+01 3 1.737053E+02 5.160235E-01 1.736983E+02 1.564422E+00 - 2.250005E+01 6.000000E+01 4 1.855834E+02 8.985120E+01 4.819798E-01 1.855828E+02 - 2.250005E+01 6.000000E+01 5 2.887914E+02 8.987770E+01 6.164166E-01 2.887907E+02 - 2.250005E+01 6.000000E+01 6 1.099068E+02 -3.038650E-03 1.099068E+02 -5.828848E-03 - 2.250005E+01 9.000000E+01 1 3.140078E-06 -9.006934E+01 -3.800280E-09 -3.140075E-06 - 2.250005E+01 9.000000E+01 2 6.407160E+01 8.985118E+01 1.664205E-01 6.407139E+01 - 2.250005E+01 9.000000E+01 3 1.749439E+02 5.177726E-01 1.749368E+02 1.580918E+00 - 2.250005E+01 9.000000E+01 4 2.169711E+02 8.985199E+01 5.605000E-01 2.169704E+02 - 2.250005E+01 9.000000E+01 5 1.410474E-04 -8.997810E+01 5.391795E-08 -1.410474E-04 - 2.250005E+01 9.000000E+01 6 9.480822E-06 1.799980E+02 -9.480822E-06 3.365462E-10 - 2.260005E+01 0.000000E+00 1 5.876220E+01 8.987885E+01 1.242446E-01 5.876207E+01 - 2.260005E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.260005E+01 0.000000E+00 3 1.703676E+02 5.059933E-01 1.703610E+02 1.504540E+00 - 2.260005E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.260005E+01 0.000000E+00 5 5.653150E+02 8.987886E+01 1.195239E+00 5.653137E+02 - 2.260005E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.260005E+01 3.000000E+01 1 5.120598E+01 8.987889E+01 1.082396E-01 5.120586E+01 - 2.260005E+01 3.000000E+01 2 3.123807E+01 8.985294E+01 8.018006E-02 3.123797E+01 - 2.260005E+01 3.000000E+01 3 1.715686E+02 5.076953E-01 1.715618E+02 1.520242E+00 - 2.260005E+01 3.000000E+01 4 1.039790E+02 8.985128E+01 2.698922E-01 1.039787E+02 - 2.260005E+01 3.000000E+01 5 4.926046E+02 8.987889E+01 1.041268E+00 4.926035E+02 - 2.260005E+01 3.000000E+01 6 1.073204E+02 -2.987368E-03 1.073204E+02 -5.595624E-03 - 2.260005E+01 6.000000E+01 1 2.993316E+01 8.987895E+01 6.324082E-02 2.993309E+01 - 2.260005E+01 6.000000E+01 2 5.485150E+01 8.985289E+01 1.408364E-01 5.485132E+01 - 2.260005E+01 6.000000E+01 3 1.739983E+02 5.111058E-01 1.739913E+02 1.552127E+00 - 2.260005E+01 6.000000E+01 4 1.846258E+02 8.985288E+01 4.740637E-01 1.846252E+02 - 2.260005E+01 6.000000E+01 5 2.879061E+02 8.987892E+01 6.083838E-01 2.879054E+02 - 2.260005E+01 6.000000E+01 6 1.088388E+02 -2.973096E-03 1.088388E+02 -5.647680E-03 - 2.260005E+01 9.000000E+01 1 3.125226E-06 -9.006902E+01 -3.764844E-09 -3.125224E-06 - 2.260005E+01 9.000000E+01 2 6.377199E+01 8.985287E+01 1.637671E-01 6.377178E+01 - 2.260005E+01 9.000000E+01 3 1.752252E+02 5.128179E-01 1.752182E+02 1.568308E+00 - 2.260005E+01 9.000000E+01 4 2.158263E+02 8.985366E+01 5.512557E-01 2.158256E+02 - 2.260005E+01 9.000000E+01 5 1.404487E-04 -8.997842E+01 5.290142E-08 -1.404487E-04 - 2.260005E+01 9.000000E+01 6 9.387832E-06 1.799980E+02 -9.387832E-06 3.261088E-10 - 2.270005E+01 0.000000E+00 1 5.850466E+01 8.988007E+01 1.224671E-01 5.850453E+01 - 2.270005E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.270005E+01 0.000000E+00 3 1.706876E+02 5.012506E-01 1.706811E+02 1.493237E+00 - 2.270005E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.270005E+01 0.000000E+00 5 5.636855E+02 8.988007E+01 1.179917E+00 5.636843E+02 - 2.270005E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.270005E+01 3.000000E+01 1 5.097813E+01 8.988010E+01 1.066849E-01 5.097802E+01 - 2.270005E+01 3.000000E+01 2 3.109923E+01 8.985459E+01 7.892652E-02 3.109913E+01 - 2.270005E+01 3.000000E+01 3 1.718788E+02 5.029147E-01 1.718722E+02 1.508650E+00 - 2.270005E+01 3.000000E+01 4 1.034701E+02 8.985297E+01 2.655265E-01 1.034698E+02 - 2.270005E+01 3.000000E+01 5 4.911523E+02 8.988010E+01 1.027858E+00 4.911512E+02 - 2.270005E+01 3.000000E+01 6 1.062980E+02 -2.923173E-03 1.062980E+02 -5.423216E-03 - 2.270005E+01 6.000000E+01 1 2.979630E+01 8.988016E+01 6.232551E-02 2.979623E+01 - 2.270005E+01 6.000000E+01 2 5.460021E+01 8.985454E+01 1.386141E-01 5.460003E+01 - 2.270005E+01 6.000000E+01 3 1.742867E+02 5.062580E-01 1.742799E+02 1.539954E+00 - 2.270005E+01 6.000000E+01 4 1.836797E+02 8.985454E+01 4.663287E-01 1.836791E+02 - 2.270005E+01 6.000000E+01 5 2.870220E+02 8.988013E+01 6.004782E-01 2.870213E+02 - 2.270005E+01 6.000000E+01 6 1.077867E+02 -2.909345E-03 1.077867E+02 -5.473155E-03 - 2.270005E+01 9.000000E+01 1 3.110519E-06 -9.006870E+01 -3.729598E-09 -3.110516E-06 - 2.270005E+01 9.000000E+01 2 6.347538E+01 8.985452E+01 1.611714E-01 6.347517E+01 - 2.270005E+01 9.000000E+01 3 1.755040E+02 5.079331E-01 1.754971E+02 1.555841E+00 - 2.270005E+01 9.000000E+01 4 2.146954E+02 8.985530E+01 5.422186E-01 2.146947E+02 - 2.270005E+01 9.000000E+01 5 1.398552E-04 -8.997874E+01 5.191003E-08 -1.398552E-04 - 2.270005E+01 9.000000E+01 6 9.296253E-06 1.799980E+02 -9.296253E-06 3.160540E-10 - 2.280005E+01 0.000000E+00 1 5.824918E+01 8.988126E+01 1.207237E-01 5.824906E+01 - 2.280005E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.280005E+01 0.000000E+00 3 1.710032E+02 4.965749E-01 1.709967E+02 1.482043E+00 - 2.280005E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.280005E+01 0.000000E+00 5 5.620590E+02 8.988126E+01 1.164852E+00 5.620577E+02 - 2.280005E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.280005E+01 3.000000E+01 1 5.075246E+01 8.988128E+01 1.051603E-01 5.075235E+01 - 2.280005E+01 3.000000E+01 2 3.096159E+01 8.985622E+01 7.769980E-02 3.096150E+01 - 2.280005E+01 3.000000E+01 3 1.721832E+02 4.982095E-01 1.721766E+02 1.497182E+00 - 2.280005E+01 3.000000E+01 4 1.029662E+02 8.985462E+01 2.612569E-01 1.029658E+02 - 2.280005E+01 3.000000E+01 5 4.897064E+02 8.988128E+01 1.014680E+00 4.897053E+02 - 2.280005E+01 3.000000E+01 6 1.052905E+02 -2.860733E-03 1.052905E+02 -5.257073E-03 - 2.280005E+01 6.000000E+01 1 2.966075E+01 8.988134E+01 6.142784E-02 2.966069E+01 - 2.280005E+01 6.000000E+01 2 5.435117E+01 8.985616E+01 1.364400E-01 5.435100E+01 - 2.280005E+01 6.000000E+01 3 1.745713E+02 5.014826E-01 1.745646E+02 1.527920E+00 - 2.280005E+01 6.000000E+01 4 1.827427E+02 8.985616E+01 4.587638E-01 1.827421E+02 - 2.280005E+01 6.000000E+01 5 2.861421E+02 8.988132E+01 5.927127E-01 2.861415E+02 - 2.280005E+01 6.000000E+01 6 1.067502E+02 -2.847337E-03 1.067502E+02 -5.304995E-03 - 2.280005E+01 9.000000E+01 1 3.095955E-06 -9.006837E+01 -3.694568E-09 -3.095952E-06 - 2.280005E+01 9.000000E+01 2 6.318153E+01 8.985615E+01 1.586325E-01 6.318133E+01 - 2.280005E+01 9.000000E+01 3 1.757789E+02 5.031202E-01 1.757721E+02 1.543513E+00 - 2.280005E+01 9.000000E+01 4 2.135760E+02 8.985691E+01 5.333858E-01 2.135753E+02 - 2.280005E+01 9.000000E+01 5 1.392646E-04 -8.997904E+01 5.094318E-08 -1.392646E-04 - 2.280005E+01 9.000000E+01 6 9.206043E-06 1.799981E+02 -9.206043E-06 3.063649E-10 - 2.290005E+01 0.000000E+00 1 5.799576E+01 8.988242E+01 1.190134E-01 5.799564E+01 - 2.290005E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.290005E+01 0.000000E+00 3 1.713144E+02 4.919704E-01 1.713081E+02 1.470973E+00 - 2.290005E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.290005E+01 0.000000E+00 5 5.604406E+02 8.988243E+01 1.150034E+00 5.604395E+02 - 2.290005E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.290005E+01 3.000000E+01 1 5.052847E+01 8.988245E+01 1.036647E-01 5.052836E+01 - 2.290005E+01 3.000000E+01 2 3.082521E+01 8.985781E+01 7.649886E-02 3.082512E+01 - 2.290005E+01 3.000000E+01 3 1.724854E+02 4.935687E-01 1.724790E+02 1.485840E+00 - 2.290005E+01 3.000000E+01 4 1.024670E+02 8.985625E+01 2.570813E-01 1.024667E+02 - 2.290005E+01 3.000000E+01 5 4.882610E+02 8.988245E+01 1.001710E+00 4.882599E+02 - 2.290005E+01 3.000000E+01 6 1.042977E+02 -2.799999E-03 1.042977E+02 -5.096943E-03 - 2.290005E+01 6.000000E+01 1 2.952635E+01 8.988251E+01 6.054788E-02 2.952629E+01 - 2.290005E+01 6.000000E+01 2 5.410443E+01 8.985777E+01 1.343129E-01 5.410426E+01 - 2.290005E+01 6.000000E+01 3 1.748531E+02 4.967713E-01 1.748465E+02 1.516009E+00 - 2.290005E+01 6.000000E+01 4 1.818155E+02 8.985776E+01 4.513689E-01 1.818149E+02 - 2.290005E+01 6.000000E+01 5 2.852617E+02 8.988248E+01 5.850755E-01 2.852611E+02 - 2.290005E+01 6.000000E+01 6 1.057289E+02 -2.787019E-03 1.057289E+02 -5.142936E-03 - 2.290005E+01 9.000000E+01 1 3.081531E-06 -9.006805E+01 -3.659745E-09 -3.081529E-06 - 2.290005E+01 9.000000E+01 2 6.289063E+01 8.985774E+01 1.561481E-01 6.289043E+01 - 2.290005E+01 9.000000E+01 3 1.760497E+02 4.983768E-01 1.760430E+02 1.531317E+00 - 2.290005E+01 9.000000E+01 4 2.124675E+02 8.985850E+01 5.247492E-01 2.124668E+02 - 2.290005E+01 9.000000E+01 5 1.386812E-04 -8.997934E+01 5.000005E-08 -1.386812E-04 - 2.290005E+01 9.000000E+01 6 9.117193E-06 1.799981E+02 -9.117193E-06 2.970265E-10 - 2.300005E+01 0.000000E+00 1 5.774446E+01 8.988358E+01 1.173359E-01 5.774434E+01 - 2.300005E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.300005E+01 0.000000E+00 3 1.716221E+02 4.874241E-01 1.716158E+02 1.459998E+00 - 2.300005E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.300005E+01 0.000000E+00 5 5.588184E+02 8.988358E+01 1.135463E+00 5.588173E+02 - 2.300005E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.300005E+01 3.000000E+01 1 5.030678E+01 8.988361E+01 1.021980E-01 5.030668E+01 - 2.300005E+01 3.000000E+01 2 3.069005E+01 8.985938E+01 7.532332E-02 3.068996E+01 - 2.300005E+01 3.000000E+01 3 1.727834E+02 4.889895E-01 1.727771E+02 1.474598E+00 - 2.300005E+01 3.000000E+01 4 1.019732E+02 8.985785E+01 2.529953E-01 1.019728E+02 - 2.300005E+01 3.000000E+01 5 4.868222E+02 8.988361E+01 9.889663E-01 4.868212E+02 - 2.300005E+01 3.000000E+01 6 1.033190E+02 -2.740901E-03 1.033190E+02 -4.942546E-03 - 2.300005E+01 6.000000E+01 1 2.939326E+01 8.988366E+01 5.968458E-02 2.939320E+01 - 2.300005E+01 6.000000E+01 2 5.385995E+01 8.985934E+01 1.322304E-01 5.385979E+01 - 2.300005E+01 6.000000E+01 3 1.751313E+02 4.921286E-01 1.751248E+02 1.504230E+00 - 2.300005E+01 6.000000E+01 4 1.808982E+02 8.985933E+01 4.441353E-01 1.808977E+02 - 2.300005E+01 6.000000E+01 5 2.843881E+02 8.988364E+01 5.775701E-01 2.843875E+02 - 2.300005E+01 6.000000E+01 6 1.047226E+02 -2.728326E-03 1.047226E+02 -4.986711E-03 - 2.300005E+01 9.000000E+01 1 3.067234E-06 -9.006772E+01 -3.625147E-09 -3.067232E-06 - 2.300005E+01 9.000000E+01 2 6.260244E+01 8.985931E+01 1.537165E-01 6.260226E+01 - 2.300005E+01 9.000000E+01 3 1.763179E+02 4.936996E-01 1.763113E+02 1.519257E+00 - 2.300005E+01 9.000000E+01 4 2.113725E+02 8.986005E+01 5.163049E-01 2.113719E+02 - 2.300005E+01 9.000000E+01 5 1.381013E-04 -8.997964E+01 4.907984E-08 -1.381013E-04 - 2.300005E+01 9.000000E+01 6 9.029641E-06 1.799982E+02 -9.029641E-06 2.880232E-10 - 2.310005E+01 0.000000E+00 1 5.749552E+01 8.988471E+01 1.156901E-01 5.749540E+01 - 2.310005E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.310005E+01 0.000000E+00 3 1.719264E+02 4.829415E-01 1.719203E+02 1.449137E+00 - 2.310005E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.310005E+01 0.000000E+00 5 5.572003E+02 8.988472E+01 1.121129E+00 5.571992E+02 - 2.310005E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.310005E+01 3.000000E+01 1 5.008691E+01 8.988474E+01 1.007595E-01 5.008681E+01 - 2.310005E+01 3.000000E+01 2 3.055601E+01 8.986092E+01 7.417223E-02 3.055592E+01 - 2.310005E+01 3.000000E+01 3 1.730778E+02 4.844745E-01 1.730717E+02 1.463472E+00 - 2.310005E+01 3.000000E+01 4 1.014840E+02 8.985942E+01 2.489998E-01 1.014837E+02 - 2.310005E+01 3.000000E+01 5 4.853862E+02 8.988474E+01 9.764374E-01 4.853852E+02 - 2.310005E+01 3.000000E+01 6 1.023544E+02 -2.683394E-03 1.023544E+02 -4.793673E-03 - 2.310005E+01 6.000000E+01 1 2.926138E+01 8.988479E+01 5.883796E-02 2.926132E+01 - 2.310005E+01 6.000000E+01 2 5.361773E+01 8.986088E+01 1.301921E-01 5.361758E+01 - 2.310005E+01 6.000000E+01 3 1.754065E+02 4.875498E-01 1.754002E+02 1.492577E+00 - 2.310005E+01 6.000000E+01 4 1.799904E+02 8.986087E+01 4.370606E-01 1.799899E+02 - 2.310005E+01 6.000000E+01 5 2.835160E+02 8.988477E+01 5.701879E-01 2.835154E+02 - 2.310005E+01 6.000000E+01 6 1.037312E+02 -2.671204E-03 1.037312E+02 -4.836084E-03 - 2.310005E+01 9.000000E+01 1 3.053080E-06 -9.006739E+01 -3.590793E-09 -3.053078E-06 - 2.310005E+01 9.000000E+01 2 6.231676E+01 8.986086E+01 1.513368E-01 6.231658E+01 - 2.310005E+01 9.000000E+01 3 1.765828E+02 4.890909E-01 1.765764E+02 1.507336E+00 - 2.310005E+01 9.000000E+01 4 2.102881E+02 8.986158E+01 5.080464E-01 2.102875E+02 - 2.310005E+01 9.000000E+01 5 1.375266E-04 -8.997993E+01 4.818189E-08 -1.375266E-04 - 2.310005E+01 9.000000E+01 6 8.943385E-06 1.799982E+02 -8.943385E-06 2.793419E-10 - 2.320005E+01 0.000000E+00 1 5.724863E+01 8.988583E+01 1.140751E-01 5.724851E+01 - 2.320005E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.320005E+01 0.000000E+00 3 1.722262E+02 4.785225E-01 1.722202E+02 1.438381E+00 - 2.320005E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.320005E+01 0.000000E+00 5 5.555858E+02 8.988583E+01 1.107037E+00 5.555847E+02 - 2.320005E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.320005E+01 3.000000E+01 1 4.986903E+01 8.988586E+01 9.934754E-02 4.986893E+01 - 2.320005E+01 3.000000E+01 2 3.042311E+01 8.986243E+01 7.304538E-02 3.042302E+01 - 2.320005E+01 3.000000E+01 3 1.733679E+02 4.800298E-01 1.733618E+02 1.452477E+00 - 2.320005E+01 3.000000E+01 4 1.010003E+02 8.986097E+01 2.450888E-01 1.010000E+02 - 2.320005E+01 3.000000E+01 5 4.839494E+02 8.988586E+01 9.641139E-01 4.839485E+02 - 2.320005E+01 3.000000E+01 6 1.014036E+02 -2.627429E-03 1.014036E+02 -4.650094E-03 - 2.320005E+01 6.000000E+01 1 2.913063E+01 8.988590E+01 5.800764E-02 2.913058E+01 - 2.320005E+01 6.000000E+01 2 5.337780E+01 8.986240E+01 1.281967E-01 5.337764E+01 - 2.320005E+01 6.000000E+01 3 1.756773E+02 4.830391E-01 1.756711E+02 1.481052E+00 - 2.320005E+01 6.000000E+01 4 1.790919E+02 8.986239E+01 4.301402E-01 1.790914E+02 - 2.320005E+01 6.000000E+01 5 2.826436E+02 8.988589E+01 5.629311E-01 2.826431E+02 - 2.320005E+01 6.000000E+01 6 1.027541E+02 -2.615610E-03 1.027541E+02 -4.690829E-03 - 2.320005E+01 9.000000E+01 1 3.039066E-06 -9.006705E+01 -3.556683E-09 -3.039064E-06 - 2.320005E+01 9.000000E+01 2 6.203386E+01 8.986237E+01 1.490075E-01 6.203368E+01 - 2.320005E+01 9.000000E+01 3 1.768442E+02 4.845468E-01 1.768379E+02 1.495543E+00 - 2.320005E+01 9.000000E+01 4 2.092164E+02 8.986308E+01 4.999671E-01 2.092158E+02 - 2.320005E+01 9.000000E+01 5 1.369564E-04 -8.998021E+01 4.730575E-08 -1.369564E-04 - 2.320005E+01 9.000000E+01 6 8.858414E-06 1.799982E+02 -8.858414E-06 2.709699E-10 - 2.330005E+01 0.000000E+00 1 5.700379E+01 8.988694E+01 1.124909E-01 5.700368E+01 - 2.330005E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.330005E+01 0.000000E+00 3 1.725218E+02 4.741654E-01 1.725159E+02 1.427730E+00 - 2.330005E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.330005E+01 0.000000E+00 5 5.539759E+02 8.988694E+01 1.093164E+00 5.539748E+02 - 2.330005E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.330005E+01 3.000000E+01 1 4.965289E+01 8.988696E+01 9.796271E-02 4.965280E+01 - 2.330005E+01 3.000000E+01 2 3.029145E+01 8.986392E+01 7.194176E-02 3.029136E+01 - 2.330005E+01 3.000000E+01 3 1.736550E+02 4.756360E-01 1.736491E+02 1.441566E+00 - 2.330005E+01 3.000000E+01 4 1.005208E+02 8.986249E+01 2.412628E-01 1.005205E+02 - 2.330005E+01 3.000000E+01 5 4.825190E+02 8.988696E+01 9.519819E-01 4.825180E+02 - 2.330005E+01 3.000000E+01 6 1.004662E+02 -2.572953E-03 1.004662E+02 -4.511584E-03 - 2.330005E+01 6.000000E+01 1 2.900108E+01 8.988701E+01 5.719278E-02 2.900102E+01 - 2.330005E+01 6.000000E+01 2 5.314001E+01 8.986388E+01 1.262435E-01 5.313987E+01 - 2.330005E+01 6.000000E+01 3 1.759453E+02 4.785885E-01 1.759391E+02 1.469644E+00 - 2.330005E+01 6.000000E+01 4 1.782030E+02 8.986388E+01 4.233695E-01 1.782025E+02 - 2.330005E+01 6.000000E+01 5 2.817781E+02 8.988699E+01 5.557917E-01 2.817776E+02 - 2.330005E+01 6.000000E+01 6 1.017911E+02 -2.561494E-03 1.017911E+02 -4.550726E-03 - 2.330005E+01 9.000000E+01 1 3.025175E-06 -9.006672E+01 -3.522809E-09 -3.025173E-06 - 2.330005E+01 9.000000E+01 2 6.175347E+01 8.986386E+01 1.467271E-01 6.175330E+01 - 2.330005E+01 9.000000E+01 3 1.771024E+02 4.800657E-01 1.770962E+02 1.483875E+00 - 2.330005E+01 9.000000E+01 4 2.081564E+02 8.986456E+01 4.920636E-01 2.081558E+02 - 2.330005E+01 9.000000E+01 5 1.363912E-04 -8.998049E+01 4.645045E-08 -1.363912E-04 - 2.330005E+01 9.000000E+01 6 8.774668E-06 1.799983E+02 -8.774668E-06 2.628938E-10 - 2.340005E+01 0.000000E+00 1 5.676098E+01 8.988802E+01 1.109356E-01 5.676088E+01 - 2.340005E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.340005E+01 0.000000E+00 3 1.728155E+02 4.698642E-01 1.728097E+02 1.417188E+00 - 2.340005E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.340005E+01 0.000000E+00 5 5.523732E+02 8.988802E+01 1.079528E+00 5.523721E+02 - 2.340005E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.340005E+01 3.000000E+01 1 4.943872E+01 8.988805E+01 9.660371E-02 4.943862E+01 - 2.340005E+01 3.000000E+01 2 3.016082E+01 8.986539E+01 7.086073E-02 3.016074E+01 - 2.340005E+01 3.000000E+01 3 1.739397E+02 4.713049E-01 1.739338E+02 1.430781E+00 - 2.340005E+01 3.000000E+01 4 1.000457E+02 8.986398E+01 2.375182E-01 1.000454E+02 - 2.340005E+01 3.000000E+01 5 4.810920E+02 8.988805E+01 9.400615E-01 4.810911E+02 - 2.340005E+01 3.000000E+01 6 9.954193E+01 -2.519920E-03 9.954193E+01 -4.377943E-03 - 2.340005E+01 6.000000E+01 1 2.887272E+01 8.988809E+01 5.639353E-02 2.887266E+01 - 2.340005E+01 6.000000E+01 2 5.290430E+01 8.986536E+01 1.243302E-01 5.290416E+01 - 2.340005E+01 6.000000E+01 3 1.762097E+02 4.742000E-01 1.762036E+02 1.458357E+00 - 2.340005E+01 6.000000E+01 4 1.773237E+02 8.986535E+01 4.167439E-01 1.773232E+02 - 2.340005E+01 6.000000E+01 5 2.809125E+02 8.988807E+01 5.487711E-01 2.809119E+02 - 2.340005E+01 6.000000E+01 6 1.008419E+02 -2.508803E-03 1.008419E+02 -4.415549E-03 - 2.340005E+01 9.000000E+01 1 3.011427E-06 -9.006638E+01 -3.489197E-09 -3.011425E-06 - 2.340005E+01 9.000000E+01 2 6.147582E+01 8.986533E+01 1.444942E-01 6.147565E+01 - 2.340005E+01 9.000000E+01 3 1.773578E+02 4.756498E-01 1.773517E+02 1.472347E+00 - 2.340005E+01 9.000000E+01 4 2.071072E+02 8.986601E+01 4.843317E-01 2.071067E+02 - 2.340005E+01 9.000000E+01 5 1.358298E-04 -8.998076E+01 4.561563E-08 -1.358298E-04 - 2.340005E+01 9.000000E+01 6 8.692145E-06 1.799983E+02 -8.692145E-06 2.551012E-10 - 2.350005E+01 0.000000E+00 1 5.652029E+01 8.988909E+01 1.094099E-01 5.652018E+01 - 2.350005E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.350005E+01 0.000000E+00 3 1.731049E+02 4.656200E-01 1.730992E+02 1.406739E+00 - 2.350005E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.350005E+01 0.000000E+00 5 5.507627E+02 8.988909E+01 1.066108E+00 5.507617E+02 - 2.350005E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.350005E+01 3.000000E+01 1 4.922615E+01 8.988911E+01 9.526986E-02 4.922606E+01 - 2.350005E+01 3.000000E+01 2 3.003135E+01 8.986683E+01 6.980192E-02 3.003127E+01 - 2.350005E+01 3.000000E+01 3 1.742183E+02 4.670392E-01 1.742125E+02 1.420103E+00 - 2.350005E+01 3.000000E+01 4 9.957614E+01 8.986544E+01 2.338523E-01 9.957587E+01 - 2.350005E+01 3.000000E+01 5 4.796705E+02 8.988911E+01 9.283333E-01 4.796696E+02 - 2.350005E+01 3.000000E+01 6 9.863074E+01 -2.468276E-03 9.863074E+01 -4.248967E-03 - 2.350005E+01 6.000000E+01 1 2.874556E+01 8.988916E+01 5.560928E-02 2.874551E+01 - 2.350005E+01 6.000000E+01 2 5.267070E+01 8.986679E+01 1.224572E-01 5.267056E+01 - 2.350005E+01 6.000000E+01 3 1.764716E+02 4.698740E-01 1.764656E+02 1.447200E+00 - 2.350005E+01 6.000000E+01 4 1.764534E+02 8.986679E+01 4.102605E-01 1.764529E+02 - 2.350005E+01 6.000000E+01 5 2.800497E+02 8.988914E+01 5.418662E-01 2.800492E+02 - 2.350005E+01 6.000000E+01 6 9.990620E+01 -2.457497E-03 9.990620E+01 -4.285118E-03 - 2.350005E+01 9.000000E+01 1 2.997795E-06 -9.006606E+01 -3.455841E-09 -2.997793E-06 - 2.350005E+01 9.000000E+01 2 6.120066E+01 8.986678E+01 1.423084E-01 6.120050E+01 - 2.350005E+01 9.000000E+01 3 1.776091E+02 4.712927E-01 1.776031E+02 1.460926E+00 - 2.350005E+01 9.000000E+01 4 2.060689E+02 8.986745E+01 4.767658E-01 2.060684E+02 - 2.350005E+01 9.000000E+01 5 1.352738E-04 -8.998103E+01 4.480063E-08 -1.352738E-04 - 2.350005E+01 9.000000E+01 6 8.610819E-06 1.799984E+02 -8.610819E-06 2.475814E-10 - 2.360005E+01 0.000000E+00 1 5.628149E+01 8.989014E+01 1.079119E-01 5.628139E+01 - 2.360005E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.360005E+01 0.000000E+00 3 1.733906E+02 4.614415E-01 1.733849E+02 1.396416E+00 - 2.360005E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.360005E+01 0.000000E+00 5 5.491675E+02 8.989014E+01 1.052917E+00 5.491665E+02 - 2.360005E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.360005E+01 3.000000E+01 1 4.901573E+01 8.989017E+01 9.396078E-02 4.901564E+01 - 2.360005E+01 3.000000E+01 2 2.990297E+01 8.986824E+01 6.876475E-02 2.990289E+01 - 2.360005E+01 3.000000E+01 3 1.744954E+02 4.628298E-01 1.744897E+02 1.409542E+00 - 2.360005E+01 3.000000E+01 4 9.911015E+01 8.986688E+01 2.302644E-01 9.910988E+01 - 2.360005E+01 3.000000E+01 5 4.782509E+02 8.989017E+01 9.167892E-01 4.782500E+02 - 2.360005E+01 3.000000E+01 6 9.773241E+01 -2.417973E-03 9.773241E+01 -4.124463E-03 - 2.360005E+01 6.000000E+01 1 2.861949E+01 8.989021E+01 5.483994E-02 2.861944E+01 - 2.360005E+01 6.000000E+01 2 5.243935E+01 8.986821E+01 1.206222E-01 5.243922E+01 - 2.360005E+01 6.000000E+01 3 1.767299E+02 4.656098E-01 1.767241E+02 1.436167E+00 - 2.360005E+01 6.000000E+01 4 1.755913E+02 8.986820E+01 4.039136E-01 1.755909E+02 - 2.360005E+01 6.000000E+01 5 2.791902E+02 8.989020E+01 5.350783E-01 2.791897E+02 - 2.360005E+01 6.000000E+01 6 9.898397E+01 -2.407515E-03 9.898397E+01 -4.159214E-03 - 2.360005E+01 9.000000E+01 1 2.984292E-06 -9.006572E+01 -3.422742E-09 -2.984290E-06 - 2.360005E+01 9.000000E+01 2 6.092810E+01 8.986819E+01 1.401669E-01 6.092794E+01 - 2.360005E+01 9.000000E+01 3 1.778585E+02 4.669997E-01 1.778526E+02 1.449652E+00 - 2.360005E+01 9.000000E+01 4 2.050410E+02 8.986884E+01 4.693612E-01 2.050404E+02 - 2.360005E+01 9.000000E+01 5 1.347215E-04 -8.998129E+01 4.400496E-08 -1.347215E-04 - 2.360005E+01 9.000000E+01 6 8.530661E-06 1.799984E+02 -8.530661E-06 2.403228E-10 - 2.370005E+01 0.000000E+00 1 5.604475E+01 8.989118E+01 1.064415E-01 5.604465E+01 - 2.370005E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.370005E+01 0.000000E+00 3 1.736726E+02 4.573165E-01 1.736671E+02 1.386184E+00 - 2.370005E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.370005E+01 0.000000E+00 5 5.475739E+02 8.989118E+01 1.039919E+00 5.475729E+02 - 2.370005E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.370005E+01 3.000000E+01 1 4.880688E+01 8.989120E+01 9.267645E-02 4.880679E+01 - 2.370005E+01 3.000000E+01 2 2.977571E+01 8.986964E+01 6.774839E-02 2.977563E+01 - 2.370005E+01 3.000000E+01 3 1.747689E+02 4.586752E-01 1.747633E+02 1.399079E+00 - 2.370005E+01 3.000000E+01 4 9.864913E+01 8.986830E+01 2.267505E-01 9.864887E+01 - 2.370005E+01 3.000000E+01 5 4.768365E+02 8.989120E+01 9.054314E-01 4.768357E+02 - 2.370005E+01 3.000000E+01 6 9.684645E+01 -2.368985E-03 9.684645E+01 -4.004271E-03 - 2.370005E+01 6.000000E+01 1 2.849452E+01 8.989124E+01 5.408464E-02 2.849447E+01 - 2.370005E+01 6.000000E+01 2 5.220984E+01 8.986960E+01 1.188247E-01 5.220970E+01 - 2.370005E+01 6.000000E+01 3 1.769851E+02 4.614007E-01 1.769794E+02 1.425239E+00 - 2.370005E+01 6.000000E+01 4 1.747380E+02 8.986960E+01 3.977008E-01 1.747376E+02 - 2.370005E+01 6.000000E+01 5 2.783364E+02 8.989124E+01 5.283985E-01 2.783359E+02 - 2.370005E+01 6.000000E+01 6 9.807465E+01 -2.358844E-03 9.807465E+01 -4.037693E-03 - 2.370005E+01 9.000000E+01 1 2.970911E-06 -9.006538E+01 -3.389921E-09 -2.970909E-06 - 2.370005E+01 9.000000E+01 2 6.065782E+01 8.986958E+01 1.380700E-01 6.065766E+01 - 2.370005E+01 9.000000E+01 3 1.781040E+02 4.627653E-01 1.780982E+02 1.438491E+00 - 2.370005E+01 9.000000E+01 4 2.040250E+02 8.987022E+01 4.621148E-01 2.040245E+02 - 2.370005E+01 9.000000E+01 5 1.341733E-04 -8.998154E+01 4.322765E-08 -1.341733E-04 - 2.370005E+01 9.000000E+01 6 8.451640E-06 1.799984E+02 -8.451640E-06 2.333156E-10 - 2.380005E+01 0.000000E+00 1 5.580989E+01 8.989221E+01 1.049980E-01 5.580980E+01 - 2.380005E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.380005E+01 0.000000E+00 3 1.739525E+02 4.532427E-01 1.739470E+02 1.376050E+00 - 2.380005E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.380005E+01 0.000000E+00 5 5.459833E+02 8.989221E+01 1.027143E+00 5.459824E+02 - 2.380005E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.380005E+01 3.000000E+01 1 4.859989E+01 8.989223E+01 9.141497E-02 4.859980E+01 - 2.380005E+01 3.000000E+01 2 2.964947E+01 8.987101E+01 6.675254E-02 2.964939E+01 - 2.380005E+01 3.000000E+01 3 1.750398E+02 4.545767E-01 1.750343E+02 1.388727E+00 - 2.380005E+01 3.000000E+01 4 9.819201E+01 8.986970E+01 2.233101E-01 9.819176E+01 - 2.380005E+01 3.000000E+01 5 4.754251E+02 8.989223E+01 8.942596E-01 4.754243E+02 - 2.380005E+01 3.000000E+01 6 9.597267E+01 -2.321265E-03 9.597267E+01 -3.888210E-03 - 2.380005E+01 6.000000E+01 1 2.837053E+01 8.989227E+01 5.334353E-02 2.837048E+01 - 2.380005E+01 6.000000E+01 2 5.198251E+01 8.987097E+01 1.170637E-01 5.198238E+01 - 2.380005E+01 6.000000E+01 3 1.772378E+02 4.572474E-01 1.772321E+02 1.414426E+00 - 2.380005E+01 6.000000E+01 4 1.738934E+02 8.987096E+01 3.916194E-01 1.738930E+02 - 2.380005E+01 6.000000E+01 5 2.774833E+02 8.989225E+01 5.218289E-01 2.774828E+02 - 2.380005E+01 6.000000E+01 6 9.717832E+01 -2.311415E-03 9.717832E+01 -3.920348E-03 - 2.380005E+01 9.000000E+01 1 2.957657E-06 -9.006504E+01 -3.357362E-09 -2.957655E-06 - 2.380005E+01 9.000000E+01 2 6.039014E+01 8.987096E+01 1.360155E-01 6.038999E+01 - 2.380005E+01 9.000000E+01 3 1.783479E+02 4.585855E-01 1.783422E+02 1.427451E+00 - 2.380005E+01 9.000000E+01 4 2.030182E+02 8.987159E+01 4.550181E-01 2.030177E+02 - 2.380005E+01 9.000000E+01 5 1.336310E-04 -8.998180E+01 4.246865E-08 -1.336310E-04 - 2.380005E+01 9.000000E+01 6 8.373747E-06 1.799984E+02 -8.373747E-06 2.265489E-10 - 2.390005E+01 0.000000E+00 1 5.557702E+01 8.989321E+01 1.035810E-01 5.557692E+01 - 2.390005E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.390005E+01 0.000000E+00 3 1.742278E+02 4.492277E-01 1.742224E+02 1.366019E+00 - 2.390005E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.390005E+01 0.000000E+00 5 5.443948E+02 8.989322E+01 1.014572E+00 5.443939E+02 - 2.390005E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.390005E+01 3.000000E+01 1 4.839457E+01 8.989324E+01 9.017714E-02 4.839449E+01 - 2.390005E+01 3.000000E+01 2 2.952438E+01 8.987235E+01 6.577675E-02 2.952431E+01 - 2.390005E+01 3.000000E+01 3 1.753066E+02 4.505365E-01 1.753012E+02 1.378483E+00 - 2.390005E+01 3.000000E+01 4 9.773938E+01 8.987107E+01 2.199414E-01 9.773914E+01 - 2.390005E+01 3.000000E+01 5 4.740217E+02 8.989324E+01 8.832666E-01 4.740209E+02 - 2.390005E+01 3.000000E+01 6 9.511114E+01 -2.274766E-03 9.511114E+01 -3.776117E-03 - 2.390005E+01 6.000000E+01 1 2.824776E+01 8.989327E+01 5.261603E-02 2.824771E+01 - 2.390005E+01 6.000000E+01 2 5.175714E+01 8.987232E+01 1.153386E-01 5.175701E+01 - 2.390005E+01 6.000000E+01 3 1.774868E+02 4.531532E-01 1.774813E+02 1.403731E+00 - 2.390005E+01 6.000000E+01 4 1.730580E+02 8.987231E+01 3.856652E-01 1.730576E+02 - 2.390005E+01 6.000000E+01 5 2.766343E+02 8.989326E+01 5.153677E-01 2.766338E+02 - 2.390005E+01 6.000000E+01 6 9.629453E+01 -2.265204E-03 9.629453E+01 -3.807030E-03 - 2.390005E+01 9.000000E+01 1 2.944529E-06 -9.006470E+01 -3.325086E-09 -2.944527E-06 - 2.390005E+01 9.000000E+01 2 6.012493E+01 8.987231E+01 1.340033E-01 6.012478E+01 - 2.390005E+01 9.000000E+01 3 1.785874E+02 4.544663E-01 1.785818E+02 1.416529E+00 - 2.390005E+01 9.000000E+01 4 2.020221E+02 8.987292E+01 4.480752E-01 2.020216E+02 - 2.390005E+01 9.000000E+01 5 1.330919E-04 -8.998204E+01 4.172722E-08 -1.330919E-04 - 2.390005E+01 9.000000E+01 6 8.296965E-06 1.799985E+02 -8.296965E-06 2.200141E-10 - 2.400006E+01 0.000000E+00 1 5.534610E+01 8.989421E+01 1.021894E-01 5.534601E+01 - 2.400006E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.400006E+01 0.000000E+00 3 1.744997E+02 4.452660E-01 1.744944E+02 1.356086E+00 - 2.400006E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.400006E+01 0.000000E+00 5 5.428163E+02 8.989422E+01 1.002187E+00 5.428154E+02 - 2.400006E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.400006E+01 3.000000E+01 1 4.819088E+01 8.989423E+01 8.896141E-02 4.819080E+01 - 2.400006E+01 3.000000E+01 2 2.940030E+01 8.987368E+01 6.482036E-02 2.940022E+01 - 2.400006E+01 3.000000E+01 3 1.755704E+02 4.465468E-01 1.755651E+02 1.368332E+00 - 2.400006E+01 3.000000E+01 4 9.729131E+01 8.987241E+01 2.166428E-01 9.729107E+01 - 2.400006E+01 3.000000E+01 5 4.726164E+02 8.989423E+01 8.724545E-01 4.726156E+02 - 2.400006E+01 3.000000E+01 6 9.426125E+01 -2.229446E-03 9.426125E+01 -3.667816E-03 - 2.400006E+01 6.000000E+01 1 2.812609E+01 8.989427E+01 5.190174E-02 2.812604E+01 - 2.400006E+01 6.000000E+01 2 5.153378E+01 8.987364E+01 1.136480E-01 5.153366E+01 - 2.400006E+01 6.000000E+01 3 1.777336E+02 4.491123E-01 1.777282E+02 1.393149E+00 - 2.400006E+01 6.000000E+01 4 1.722303E+02 8.987364E+01 3.798343E-01 1.722299E+02 - 2.400006E+01 6.000000E+01 5 2.757869E+02 8.989425E+01 5.090078E-01 2.757864E+02 - 2.400006E+01 6.000000E+01 6 9.542294E+01 -2.220166E-03 9.542294E+01 -3.697563E-03 - 2.400006E+01 9.000000E+01 1 2.931508E-06 -9.006436E+01 -3.293080E-09 -2.931506E-06 - 2.400006E+01 9.000000E+01 2 5.986201E+01 8.987363E+01 1.320310E-01 5.986186E+01 - 2.400006E+01 9.000000E+01 3 1.788251E+02 4.504021E-01 1.788195E+02 1.405729E+00 - 2.400006E+01 9.000000E+01 4 2.010370E+02 8.987424E+01 4.412749E-01 2.010365E+02 - 2.400006E+01 9.000000E+01 5 1.325567E-04 -8.998228E+01 4.100292E-08 -1.325567E-04 - 2.400006E+01 9.000000E+01 6 8.221267E-06 1.799985E+02 -8.221267E-06 2.137008E-10 - 2.410006E+01 0.000000E+00 1 5.511711E+01 8.989520E+01 1.008234E-01 5.511702E+01 - 2.410006E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.410006E+01 0.000000E+00 3 1.747693E+02 4.413574E-01 1.747641E+02 1.346259E+00 - 2.410006E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.410006E+01 0.000000E+00 5 5.412387E+02 8.989520E+01 9.900017E-01 5.412378E+02 - 2.410006E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.410006E+01 3.000000E+01 1 4.798917E+01 8.989522E+01 8.776800E-02 4.798909E+01 - 2.410006E+01 3.000000E+01 2 2.927723E+01 8.987498E+01 6.388288E-02 2.927716E+01 - 2.410006E+01 3.000000E+01 3 1.758313E+02 4.426152E-01 1.758261E+02 1.358300E+00 - 2.410006E+01 3.000000E+01 4 9.684742E+01 8.987375E+01 2.134103E-01 9.684718E+01 - 2.410006E+01 3.000000E+01 5 4.712179E+02 8.989522E+01 8.618144E-01 4.712171E+02 - 2.410006E+01 3.000000E+01 6 9.342292E+01 -2.185286E-03 9.342292E+01 -3.563191E-03 - 2.410006E+01 6.000000E+01 1 2.800544E+01 8.989525E+01 5.120069E-02 2.800540E+01 - 2.410006E+01 6.000000E+01 2 5.131229E+01 8.987495E+01 1.119914E-01 5.131217E+01 - 2.410006E+01 6.000000E+01 3 1.779765E+02 4.451326E-01 1.779711E+02 1.382691E+00 - 2.410006E+01 6.000000E+01 4 1.714108E+02 8.987495E+01 3.741245E-01 1.714104E+02 - 2.410006E+01 6.000000E+01 5 2.749439E+02 8.989523E+01 5.027539E-01 2.749435E+02 - 2.410006E+01 6.000000E+01 6 9.456345E+01 -2.176280E-03 9.456345E+01 -3.591827E-03 - 2.410006E+01 9.000000E+01 1 2.918614E-06 -9.006403E+01 -3.261367E-09 -2.918612E-06 - 2.410006E+01 9.000000E+01 2 5.960152E+01 8.987494E+01 1.300989E-01 5.960138E+01 - 2.410006E+01 9.000000E+01 3 1.790594E+02 4.463964E-01 1.790540E+02 1.395054E+00 - 2.410006E+01 9.000000E+01 4 2.000620E+02 8.987553E+01 4.346154E-01 2.000615E+02 - 2.410006E+01 9.000000E+01 5 1.320264E-04 -8.998251E+01 4.029528E-08 -1.320264E-04 - 2.410006E+01 9.000000E+01 6 8.146621E-06 1.799986E+02 -8.146621E-06 2.076021E-10 - 2.420006E+01 0.000000E+00 1 5.488992E+01 8.989616E+01 9.948167E-02 5.488983E+01 - 2.420006E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.420006E+01 0.000000E+00 3 1.750341E+02 4.374979E-01 1.750291E+02 1.336509E+00 - 2.420006E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.420006E+01 0.000000E+00 5 5.396603E+02 8.989616E+01 9.780313E-01 5.396594E+02 - 2.420006E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.420006E+01 3.000000E+01 1 4.778897E+01 8.989618E+01 8.659603E-02 4.778889E+01 - 2.420006E+01 3.000000E+01 2 2.915520E+01 8.987626E+01 6.296390E-02 2.915514E+01 - 2.420006E+01 3.000000E+01 3 1.760889E+02 4.387318E-01 1.760838E+02 1.348355E+00 - 2.420006E+01 3.000000E+01 4 9.640749E+01 8.987505E+01 2.102454E-01 9.640726E+01 - 2.420006E+01 3.000000E+01 5 4.698246E+02 8.989618E+01 8.513460E-01 4.698238E+02 - 2.420006E+01 3.000000E+01 6 9.259603E+01 -2.142239E-03 9.259603E+01 -3.462085E-03 - 2.420006E+01 6.000000E+01 1 2.788586E+01 8.989622E+01 5.051244E-02 2.788581E+01 - 2.420006E+01 6.000000E+01 2 5.109282E+01 8.987624E+01 1.103676E-01 5.109270E+01 - 2.420006E+01 6.000000E+01 3 1.782167E+02 4.412003E-01 1.782114E+02 1.372326E+00 - 2.420006E+01 6.000000E+01 4 1.705998E+02 8.987624E+01 3.685305E-01 1.705994E+02 - 2.420006E+01 6.000000E+01 5 2.741026E+02 8.989620E+01 4.965967E-01 2.741021E+02 - 2.420006E+01 6.000000E+01 6 9.371589E+01 -2.133490E-03 9.371589E+01 -3.489644E-03 - 2.420006E+01 9.000000E+01 1 2.905833E-06 -9.006369E+01 -3.229919E-09 -2.905831E-06 - 2.420006E+01 9.000000E+01 2 5.934311E+01 8.987622E+01 1.282050E-01 5.934298E+01 - 2.420006E+01 9.000000E+01 3 1.792914E+02 4.424344E-01 1.792861E+02 1.384463E+00 - 2.420006E+01 9.000000E+01 4 1.990962E+02 8.987681E+01 4.280929E-01 1.990957E+02 - 2.420006E+01 9.000000E+01 5 1.314999E-04 -8.998274E+01 3.960369E-08 -1.314999E-04 - 2.420006E+01 9.000000E+01 6 8.073012E-06 1.799986E+02 -8.073012E-06 2.017078E-10 - 2.430006E+01 0.000000E+00 1 5.466449E+01 8.989711E+01 9.816404E-02 5.466441E+01 - 2.430006E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.430006E+01 0.000000E+00 3 1.752979E+02 4.336909E-01 1.752929E+02 1.326876E+00 - 2.430006E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.430006E+01 0.000000E+00 5 5.380936E+02 8.989712E+01 9.662327E-01 5.380928E+02 - 2.430006E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.430006E+01 3.000000E+01 1 4.759039E+01 8.989713E+01 8.544528E-02 4.759032E+01 - 2.430006E+01 3.000000E+01 2 2.903419E+01 8.987753E+01 6.206277E-02 2.903412E+01 - 2.430006E+01 3.000000E+01 3 1.763440E+02 4.348980E-01 1.763389E+02 1.338509E+00 - 2.430006E+01 3.000000E+01 4 9.597160E+01 8.987634E+01 2.071419E-01 9.597138E+01 - 2.430006E+01 3.000000E+01 5 4.684349E+02 8.989713E+01 8.410389E-01 4.684341E+02 - 2.430006E+01 3.000000E+01 6 9.178020E+01 -2.100270E-03 9.178020E+01 -3.364352E-03 - 2.430006E+01 6.000000E+01 1 2.776723E+01 8.989717E+01 4.983657E-02 2.776718E+01 - 2.430006E+01 6.000000E+01 2 5.087517E+01 8.987749E+01 1.087756E-01 5.087505E+01 - 2.430006E+01 6.000000E+01 3 1.784546E+02 4.373234E-01 1.784494E+02 1.362083E+00 - 2.430006E+01 6.000000E+01 4 1.697960E+02 8.987749E+01 3.630520E-01 1.697956E+02 - 2.430006E+01 6.000000E+01 5 2.732666E+02 8.989715E+01 4.905472E-01 2.732661E+02 - 2.430006E+01 6.000000E+01 6 9.287992E+01 -2.091775E-03 9.287992E+01 -3.390893E-03 - 2.430006E+01 9.000000E+01 1 2.893164E-06 -9.006335E+01 -3.198767E-09 -2.893162E-06 - 2.430006E+01 9.000000E+01 2 5.908727E+01 8.987749E+01 1.263492E-01 5.908714E+01 - 2.430006E+01 9.000000E+01 3 1.795202E+02 4.385376E-01 1.795150E+02 1.374021E+00 - 2.430006E+01 9.000000E+01 4 1.981402E+02 8.987806E+01 4.217054E-01 1.981397E+02 - 2.430006E+01 9.000000E+01 5 1.309774E-04 -8.998297E+01 3.892789E-08 -1.309774E-04 - 2.430006E+01 9.000000E+01 6 8.000432E-06 1.799986E+02 -8.000432E-06 1.960112E-10 - 2.440006E+01 0.000000E+00 1 5.444105E+01 8.989805E+01 9.686979E-02 5.444096E+01 - 2.440006E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.440006E+01 0.000000E+00 3 1.755571E+02 4.299337E-01 1.755522E+02 1.317326E+00 - 2.440006E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.440006E+01 0.000000E+00 5 5.365279E+02 8.989806E+01 9.546290E-01 5.365270E+02 - 2.440006E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.440006E+01 3.000000E+01 1 4.739366E+01 8.989807E+01 8.431499E-02 4.739359E+01 - 2.440006E+01 3.000000E+01 2 2.891417E+01 8.987877E+01 6.117931E-02 2.891411E+01 - 2.440006E+01 3.000000E+01 3 1.765949E+02 4.311201E-01 1.765899E+02 1.328769E+00 - 2.440006E+01 3.000000E+01 4 9.553999E+01 8.987760E+01 2.041023E-01 9.553976E+01 - 2.440006E+01 3.000000E+01 5 4.670530E+02 8.989807E+01 8.308989E-01 4.670522E+02 - 2.440006E+01 3.000000E+01 6 9.097534E+01 -2.059355E-03 9.097534E+01 -3.269884E-03 - 2.440006E+01 6.000000E+01 1 2.764974E+01 8.989810E+01 4.917292E-02 2.764970E+01 - 2.440006E+01 6.000000E+01 2 5.065941E+01 8.987874E+01 1.072153E-01 5.065929E+01 - 2.440006E+01 6.000000E+01 3 1.786896E+02 4.334970E-01 1.786844E+02 1.351943E+00 - 2.440006E+01 6.000000E+01 4 1.690008E+02 8.987873E+01 3.576838E-01 1.690005E+02 - 2.440006E+01 6.000000E+01 5 2.724322E+02 8.989809E+01 4.845830E-01 2.724317E+02 - 2.440006E+01 6.000000E+01 6 9.205544E+01 -2.051094E-03 9.205544E+01 -3.295432E-03 - 2.440006E+01 9.000000E+01 1 2.880607E-06 -9.006301E+01 -3.167894E-09 -2.880605E-06 - 2.440006E+01 9.000000E+01 2 5.883351E+01 8.987872E+01 1.245295E-01 5.883337E+01 - 2.440006E+01 9.000000E+01 3 1.797462E+02 4.346892E-01 1.797410E+02 1.363678E+00 - 2.440006E+01 9.000000E+01 4 1.971942E+02 8.987930E+01 4.154466E-01 1.971937E+02 - 2.440006E+01 9.000000E+01 5 1.304596E-04 -8.998319E+01 3.826728E-08 -1.304596E-04 - 2.440006E+01 9.000000E+01 6 7.928846E-06 1.799986E+02 -7.928846E-06 1.905042E-10 - 2.450006E+01 0.000000E+00 1 5.421926E+01 8.989898E+01 9.559872E-02 5.421917E+01 - 2.450006E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.450006E+01 0.000000E+00 3 1.758142E+02 4.262261E-01 1.758094E+02 1.307878E+00 - 2.450006E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.450006E+01 0.000000E+00 5 5.349677E+02 8.989899E+01 9.431933E-01 5.349668E+02 - 2.450006E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.450006E+01 3.000000E+01 1 4.719819E+01 8.989900E+01 8.320457E-02 4.719812E+01 - 2.450006E+01 3.000000E+01 2 2.879515E+01 8.987999E+01 6.031291E-02 2.879509E+01 - 2.450006E+01 3.000000E+01 3 1.768436E+02 4.273906E-01 1.768386E+02 1.319130E+00 - 2.450006E+01 3.000000E+01 4 9.511223E+01 8.987885E+01 2.011238E-01 9.511201E+01 - 2.450006E+01 3.000000E+01 5 4.656710E+02 8.989900E+01 8.209152E-01 4.656702E+02 - 2.450006E+01 3.000000E+01 6 9.018147E+01 -2.019447E-03 9.018147E+01 -3.178535E-03 - 2.450006E+01 6.000000E+01 1 2.753310E+01 8.989903E+01 4.852091E-02 2.753306E+01 - 2.450006E+01 6.000000E+01 2 5.044561E+01 8.987997E+01 1.056854E-01 5.044550E+01 - 2.450006E+01 6.000000E+01 3 1.789222E+02 4.297256E-01 1.789172E+02 1.341926E+00 - 2.450006E+01 6.000000E+01 4 1.682136E+02 8.987997E+01 3.524255E-01 1.682132E+02 - 2.450006E+01 6.000000E+01 5 2.716010E+02 8.989901E+01 4.787209E-01 2.716006E+02 - 2.450006E+01 6.000000E+01 6 9.124196E+01 -2.011430E-03 9.124196E+01 -3.203146E-03 - 2.450006E+01 9.000000E+01 1 2.868165E-06 -9.006267E+01 -3.137320E-09 -2.868163E-06 - 2.450006E+01 9.000000E+01 2 5.858204E+01 8.987995E+01 1.227459E-01 5.858191E+01 - 2.450006E+01 9.000000E+01 3 1.799697E+02 4.308933E-01 1.799646E+02 1.353451E+00 - 2.450006E+01 9.000000E+01 4 1.962583E+02 8.988050E+01 4.093162E-01 1.962579E+02 - 2.450006E+01 9.000000E+01 5 1.299453E-04 -8.998341E+01 3.762150E-08 -1.299453E-04 - 2.450006E+01 9.000000E+01 6 7.858253E-06 1.799987E+02 -7.858253E-06 1.851799E-10 - 2.460006E+01 0.000000E+00 1 5.399934E+01 8.989989E+01 9.434960E-02 5.399926E+01 - 2.460006E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.460006E+01 0.000000E+00 3 1.760677E+02 4.225669E-01 1.760629E+02 1.298520E+00 - 2.460006E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.460006E+01 0.000000E+00 5 5.334150E+02 8.989990E+01 9.319467E-01 5.334142E+02 - 2.460006E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.460006E+01 3.000000E+01 1 4.700480E+01 8.989991E+01 8.211408E-02 4.700473E+01 - 2.460006E+01 3.000000E+01 2 2.867704E+01 8.988120E+01 5.946324E-02 2.867698E+01 - 2.460006E+01 3.000000E+01 3 1.770899E+02 4.237058E-01 1.770851E+02 1.309579E+00 - 2.460006E+01 3.000000E+01 4 9.468811E+01 8.988007E+01 1.982032E-01 9.468790E+01 - 2.460006E+01 3.000000E+01 5 4.642968E+02 8.989991E+01 8.110967E-01 4.642961E+02 - 2.460006E+01 3.000000E+01 6 8.939787E+01 -1.980525E-03 8.939787E+01 -3.090188E-03 - 2.460006E+01 6.000000E+01 1 2.741760E+01 8.989994E+01 4.788094E-02 2.741756E+01 - 2.460006E+01 6.000000E+01 2 5.023351E+01 8.988116E+01 1.041852E-01 5.023340E+01 - 2.460006E+01 6.000000E+01 3 1.791508E+02 4.259996E-01 1.791459E+02 1.331991E+00 - 2.460006E+01 6.000000E+01 4 1.674326E+02 8.988116E+01 3.472713E-01 1.674323E+02 - 2.460006E+01 6.000000E+01 5 2.707739E+02 8.989993E+01 4.729458E-01 2.707735E+02 - 2.460006E+01 6.000000E+01 6 9.043964E+01 -1.972735E-03 9.043964E+01 -3.113902E-03 - 2.460006E+01 9.000000E+01 1 2.855832E-06 -9.006233E+01 -3.107019E-09 -2.855830E-06 - 2.460006E+01 9.000000E+01 2 5.833270E+01 8.988116E+01 1.209969E-01 5.833257E+01 - 2.460006E+01 9.000000E+01 3 1.801916E+02 4.271433E-01 1.801866E+02 1.343326E+00 - 2.460006E+01 9.000000E+01 4 1.953301E+02 8.988170E+01 4.033084E-01 1.953297E+02 - 2.460006E+01 9.000000E+01 5 1.294351E-04 -8.998363E+01 3.699022E-08 -1.294351E-04 - 2.460006E+01 9.000000E+01 6 7.788616E-06 1.799987E+02 -7.788616E-06 1.800306E-10 - 2.470006E+01 0.000000E+00 1 5.378117E+01 8.990079E+01 9.312256E-02 5.378109E+01 - 2.470006E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.470006E+01 0.000000E+00 3 1.763189E+02 4.189522E-01 1.763141E+02 1.289249E+00 - 2.470006E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.470006E+01 0.000000E+00 5 5.318651E+02 8.990079E+01 9.208829E-01 5.318643E+02 - 2.470006E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.470006E+01 3.000000E+01 1 4.681253E+01 8.990081E+01 8.104297E-02 4.681247E+01 - 2.470006E+01 3.000000E+01 2 2.856001E+01 8.988238E+01 5.862991E-02 2.855994E+01 - 2.470006E+01 3.000000E+01 3 1.773324E+02 4.200728E-01 1.773277E+02 1.300128E+00 - 2.470006E+01 3.000000E+01 4 9.426814E+01 8.988127E+01 1.953418E-01 9.426794E+01 - 2.470006E+01 3.000000E+01 5 4.629255E+02 8.990081E+01 8.014228E-01 4.629248E+02 - 2.470006E+01 3.000000E+01 6 8.862480E+01 -1.942562E-03 8.862480E+01 -3.004744E-03 - 2.470006E+01 6.000000E+01 1 2.730299E+01 8.990084E+01 4.725219E-02 2.730295E+01 - 2.470006E+01 6.000000E+01 2 5.002332E+01 8.988235E+01 1.027142E-01 5.002321E+01 - 2.470006E+01 6.000000E+01 3 1.793775E+02 4.223199E-01 1.793727E+02 1.322157E+00 - 2.470006E+01 6.000000E+01 4 1.666603E+02 8.988235E+01 3.422202E-01 1.666600E+02 - 2.470006E+01 6.000000E+01 5 2.699490E+02 8.990083E+01 4.672738E-01 2.699486E+02 - 2.470006E+01 6.000000E+01 6 8.964802E+01 -1.934987E-03 8.964802E+01 -3.027584E-03 - 2.470006E+01 9.000000E+01 1 2.843609E-06 -9.006200E+01 -3.077015E-09 -2.843607E-06 - 2.470006E+01 9.000000E+01 2 5.808551E+01 8.988234E+01 1.192822E-01 5.808539E+01 - 2.470006E+01 9.000000E+01 3 1.804100E+02 4.234435E-01 1.804051E+02 1.333305E+00 - 2.470006E+01 9.000000E+01 4 1.944115E+02 8.988287E+01 3.974206E-01 1.944111E+02 - 2.470006E+01 9.000000E+01 5 1.289278E-04 -8.998383E+01 3.637289E-08 -1.289278E-04 - 2.470006E+01 9.000000E+01 6 7.719932E-06 1.799987E+02 -7.719932E-06 1.750500E-10 - 2.480006E+01 0.000000E+00 1 5.356469E+01 8.990168E+01 9.191687E-02 5.356461E+01 - 2.480006E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.480006E+01 0.000000E+00 3 1.765668E+02 4.153858E-01 1.765622E+02 1.280072E+00 - 2.480006E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.480006E+01 0.000000E+00 5 5.303159E+02 8.990168E+01 9.099780E-01 5.303151E+02 - 2.480006E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.480006E+01 3.000000E+01 1 4.662207E+01 8.990170E+01 7.999029E-02 4.662200E+01 - 2.480006E+01 3.000000E+01 2 2.844382E+01 8.988355E+01 5.781246E-02 2.844377E+01 - 2.480006E+01 3.000000E+01 3 1.775724E+02 4.164839E-01 1.775677E+02 1.290765E+00 - 2.480006E+01 3.000000E+01 4 9.385210E+01 8.988245E+01 1.925367E-01 9.385190E+01 - 2.480006E+01 3.000000E+01 5 4.615573E+02 8.990170E+01 7.919074E-01 4.615566E+02 - 2.480006E+01 3.000000E+01 6 8.786177E+01 -1.905528E-03 8.786177E+01 -2.922084E-03 - 2.480006E+01 6.000000E+01 1 2.718941E+01 8.990173E+01 4.663461E-02 2.718937E+01 - 2.480006E+01 6.000000E+01 2 4.981487E+01 8.988352E+01 1.012714E-01 4.981477E+01 - 2.480006E+01 6.000000E+01 3 1.796018E+02 4.186890E-01 1.795970E+02 1.312429E+00 - 2.480006E+01 6.000000E+01 4 1.658963E+02 8.988352E+01 3.372680E-01 1.658959E+02 - 2.480006E+01 6.000000E+01 5 2.691268E+02 8.990171E+01 4.616813E-01 2.691264E+02 - 2.480006E+01 6.000000E+01 6 8.886719E+01 -1.898159E-03 8.886719E+01 -2.944092E-03 - 2.480006E+01 9.000000E+01 1 2.831491E-06 -9.006167E+01 -3.047292E-09 -2.831489E-06 - 2.480006E+01 9.000000E+01 2 5.784065E+01 8.988351E+01 1.176006E-01 5.784053E+01 - 2.480006E+01 9.000000E+01 3 1.806254E+02 4.197936E-01 1.806206E+02 1.323391E+00 - 2.480006E+01 9.000000E+01 4 1.935027E+02 8.988403E+01 3.916526E-01 1.935023E+02 - 2.480006E+01 9.000000E+01 5 1.284257E-04 -8.998404E+01 3.576919E-08 -1.284257E-04 - 2.480006E+01 9.000000E+01 6 7.652169E-06 1.799987E+02 -7.652169E-06 1.702321E-10 - 2.490006E+01 0.000000E+00 1 5.335005E+01 8.990256E+01 9.073237E-02 5.334998E+01 - 2.490006E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.490006E+01 0.000000E+00 3 1.768118E+02 4.118660E-01 1.768072E+02 1.270986E+00 - 2.490006E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.490006E+01 0.000000E+00 5 5.287761E+02 8.990257E+01 8.992478E-01 5.287753E+02 - 2.490006E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.490006E+01 3.000000E+01 1 4.643299E+01 8.990257E+01 7.895582E-02 4.643292E+01 - 2.490006E+01 3.000000E+01 2 2.832863E+01 8.988470E+01 5.701044E-02 2.832857E+01 - 2.490006E+01 3.000000E+01 3 1.778103E+02 4.129422E-01 1.778057E+02 1.281503E+00 - 2.490006E+01 3.000000E+01 4 9.343965E+01 8.988363E+01 1.897852E-01 9.343946E+01 - 2.490006E+01 3.000000E+01 5 4.601959E+02 8.990257E+01 7.825330E-01 4.601952E+02 - 2.490006E+01 3.000000E+01 6 8.710892E+01 -1.869385E-03 8.710892E+01 -2.842095E-03 - 2.490006E+01 6.000000E+01 1 2.707679E+01 8.990260E+01 4.602775E-02 2.707675E+01 - 2.490006E+01 6.000000E+01 2 4.960810E+01 8.988467E+01 9.985618E-02 4.960800E+01 - 2.490006E+01 6.000000E+01 3 1.798236E+02 4.151099E-01 1.798188E+02 1.302817E+00 - 2.490006E+01 6.000000E+01 4 1.651373E+02 8.988467E+01 3.324157E-01 1.651370E+02 - 2.490006E+01 6.000000E+01 5 2.683115E+02 8.990259E+01 4.561692E-01 2.683111E+02 - 2.490006E+01 6.000000E+01 6 8.809652E+01 -1.862227E-03 8.809652E+01 -2.863312E-03 - 2.490006E+01 9.000000E+01 1 2.819473E-06 -9.006133E+01 -3.017858E-09 -2.819471E-06 - 2.490006E+01 9.000000E+01 2 5.759768E+01 8.988466E+01 1.159510E-01 5.759756E+01 - 2.490006E+01 9.000000E+01 3 1.808393E+02 4.161923E-01 1.808345E+02 1.313591E+00 - 2.490006E+01 9.000000E+01 4 1.926020E+02 8.988518E+01 3.859954E-01 1.926016E+02 - 2.490006E+01 9.000000E+01 5 1.279273E-04 -8.998425E+01 3.517875E-08 -1.279273E-04 - 2.490006E+01 9.000000E+01 6 7.585311E-06 1.799987E+02 -7.585311E-06 1.655704E-10 - 2.500006E+01 0.000000E+00 1 5.313704E+01 8.990343E+01 8.956819E-02 5.313696E+01 - 2.500006E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.500006E+01 0.000000E+00 3 1.770543E+02 4.083896E-01 1.770498E+02 1.261987E+00 - 2.500006E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.500006E+01 0.000000E+00 5 5.272414E+02 8.990343E+01 8.886803E-01 5.272407E+02 - 2.500006E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.500006E+01 3.000000E+01 1 4.624553E+01 8.990343E+01 7.794006E-02 4.624546E+01 - 2.500006E+01 3.000000E+01 2 2.821434E+01 8.988583E+01 5.622368E-02 2.821428E+01 - 2.500006E+01 3.000000E+01 3 1.780443E+02 4.094484E-01 1.780397E+02 1.272333E+00 - 2.500006E+01 3.000000E+01 4 9.303102E+01 8.988478E+01 1.870886E-01 9.303083E+01 - 2.500006E+01 3.000000E+01 5 4.588366E+02 8.990343E+01 7.733034E-01 4.588360E+02 - 2.500006E+01 3.000000E+01 6 8.636576E+01 -1.834118E-03 8.636576E+01 -2.764689E-03 - 2.500006E+01 6.000000E+01 1 2.696503E+01 8.990347E+01 4.543158E-02 2.696499E+01 - 2.500006E+01 6.000000E+01 2 4.940303E+01 8.988580E+01 9.846783E-02 4.940293E+01 - 2.500006E+01 6.000000E+01 3 1.800412E+02 4.115758E-01 1.800365E+02 1.293288E+00 - 2.500006E+01 6.000000E+01 4 1.643874E+02 8.988580E+01 3.276581E-01 1.643871E+02 - 2.500006E+01 6.000000E+01 5 2.674931E+02 8.990345E+01 4.507528E-01 2.674927E+02 - 2.500006E+01 6.000000E+01 6 8.733630E+01 -1.827158E-03 8.733630E+01 -2.785148E-03 - 2.500006E+01 9.000000E+01 1 2.807568E-06 -9.006100E+01 -2.988725E-09 -2.807566E-06 - 2.500006E+01 9.000000E+01 2 5.735681E+01 8.988579E+01 1.143331E-01 5.735670E+01 - 2.500006E+01 9.000000E+01 3 1.810499E+02 4.126362E-01 1.810452E+02 1.303885E+00 - 2.500006E+01 9.000000E+01 4 1.917110E+02 8.988629E+01 3.804510E-01 1.917106E+02 - 2.500006E+01 9.000000E+01 5 1.274322E-04 -8.998444E+01 3.460135E-08 -1.274322E-04 - 2.500006E+01 9.000000E+01 6 7.519363E-06 1.799988E+02 -7.519363E-06 1.610591E-10 - 2.510006E+01 0.000000E+00 1 5.292557E+01 8.990427E+01 8.842468E-02 5.292550E+01 - 2.510006E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.510006E+01 0.000000E+00 3 1.772938E+02 4.049586E-01 1.772893E+02 1.253077E+00 - 2.510006E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.510006E+01 0.000000E+00 5 5.257103E+02 8.990428E+01 8.782778E-01 5.257095E+02 - 2.510006E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.510006E+01 3.000000E+01 1 4.605963E+01 8.990429E+01 7.694146E-02 4.605957E+01 - 2.510006E+01 3.000000E+01 2 2.810098E+01 8.988694E+01 5.545168E-02 2.810092E+01 - 2.510006E+01 3.000000E+01 3 1.782761E+02 4.060007E-01 1.782716E+02 1.263263E+00 - 2.510006E+01 3.000000E+01 4 9.262593E+01 8.988591E+01 1.844436E-01 9.262575E+01 - 2.510006E+01 3.000000E+01 5 4.574836E+02 8.990428E+01 7.642243E-01 4.574829E+02 - 2.510006E+01 3.000000E+01 6 8.563242E+01 -1.799699E-03 8.563242E+01 -2.689772E-03 - 2.510006E+01 6.000000E+01 1 2.685440E+01 8.990432E+01 4.484583E-02 2.685436E+01 - 2.510006E+01 6.000000E+01 2 4.919981E+01 8.988692E+01 9.710602E-02 4.919972E+01 - 2.510006E+01 6.000000E+01 3 1.802585E+02 4.080828E-01 1.802540E+02 1.283860E+00 - 2.510006E+01 6.000000E+01 4 1.636436E+02 8.988691E+01 3.229948E-01 1.636433E+02 - 2.510006E+01 6.000000E+01 5 2.666844E+02 8.990430E+01 4.454191E-01 2.666840E+02 - 2.510006E+01 6.000000E+01 6 8.658608E+01 -1.792929E-03 8.658608E+01 -2.709497E-03 - 2.510006E+01 9.000000E+01 1 2.795762E-06 -9.006066E+01 -2.959867E-09 -2.795760E-06 - 2.510006E+01 9.000000E+01 2 5.711811E+01 8.988690E+01 1.127463E-01 5.711800E+01 - 2.510006E+01 9.000000E+01 3 1.812591E+02 4.091276E-01 1.812544E+02 1.294292E+00 - 2.510006E+01 9.000000E+01 4 1.908277E+02 8.988740E+01 3.750165E-01 1.908274E+02 - 2.510006E+01 9.000000E+01 5 1.269409E-04 -8.998463E+01 3.403653E-08 -1.269409E-04 - 2.510006E+01 9.000000E+01 6 7.454297E-06 1.799988E+02 -7.454297E-06 1.566928E-10 - 2.520006E+01 0.000000E+00 1 5.271600E+01 8.990512E+01 8.730014E-02 5.271592E+01 - 2.520006E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.520006E+01 0.000000E+00 3 1.775309E+02 4.015695E-01 1.775265E+02 1.244252E+00 - 2.520006E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.520006E+01 0.000000E+00 5 5.241855E+02 8.990512E+01 8.680288E-01 5.241848E+02 - 2.520006E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.520006E+01 3.000000E+01 1 4.587526E+01 8.990513E+01 7.595998E-02 4.587519E+01 - 2.520006E+01 3.000000E+01 2 2.798850E+01 8.988804E+01 5.469400E-02 2.798845E+01 - 2.520006E+01 3.000000E+01 3 1.785062E+02 4.025902E-01 1.785018E+02 1.254268E+00 - 2.520006E+01 3.000000E+01 4 9.222443E+01 8.988702E+01 1.818499E-01 9.222426E+01 - 2.520006E+01 3.000000E+01 5 4.561398E+02 8.990513E+01 7.552798E-01 4.561392E+02 - 2.520006E+01 3.000000E+01 6 8.490846E+01 -1.766103E-03 8.490846E+01 -2.617246E-03 - 2.520006E+01 6.000000E+01 1 2.674450E+01 8.990516E+01 4.427037E-02 2.674446E+01 - 2.520006E+01 6.000000E+01 2 4.899820E+01 8.988802E+01 9.576986E-02 4.899810E+01 - 2.520006E+01 6.000000E+01 3 1.804727E+02 4.046407E-01 1.804682E+02 1.274544E+00 - 2.520006E+01 6.000000E+01 4 1.629073E+02 8.988801E+01 3.184209E-01 1.629070E+02 - 2.520006E+01 6.000000E+01 5 2.658757E+02 8.990514E+01 4.401714E-01 2.658753E+02 - 2.520006E+01 6.000000E+01 6 8.584565E+01 -1.759518E-03 8.584565E+01 -2.636266E-03 - 2.520006E+01 9.000000E+01 1 2.784061E-06 -9.006033E+01 -2.931307E-09 -2.784060E-06 - 2.520006E+01 9.000000E+01 2 5.688136E+01 8.988800E+01 1.111894E-01 5.688126E+01 - 2.520006E+01 9.000000E+01 3 1.814655E+02 4.056632E-01 1.814610E+02 1.284794E+00 - 2.520006E+01 9.000000E+01 4 1.899537E+02 8.988850E+01 3.696886E-01 1.899533E+02 - 2.520006E+01 9.000000E+01 5 1.264529E-04 -8.998483E+01 3.348378E-08 -1.264529E-04 - 2.520006E+01 9.000000E+01 6 7.390084E-06 1.799988E+02 -7.390084E-06 1.524657E-10 - 2.530006E+01 0.000000E+00 1 5.250806E+01 8.990594E+01 8.619491E-02 5.250799E+01 - 2.530006E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.530006E+01 0.000000E+00 3 1.777646E+02 3.982247E-01 1.777604E+02 1.235514E+00 - 2.530006E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.530006E+01 0.000000E+00 5 5.226671E+02 8.990595E+01 8.579420E-01 5.226663E+02 - 2.530006E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.530006E+01 3.000000E+01 1 4.569215E+01 8.990596E+01 7.499533E-02 4.569209E+01 - 2.530006E+01 3.000000E+01 2 2.787701E+01 8.988911E+01 5.395045E-02 2.787696E+01 - 2.530006E+01 3.000000E+01 3 1.787324E+02 3.992268E-01 1.787280E+02 1.245365E+00 - 2.530006E+01 3.000000E+01 4 9.182629E+01 8.988811E+01 1.793063E-01 9.182612E+01 - 2.530006E+01 3.000000E+01 5 4.547971E+02 8.990596E+01 7.464731E-01 4.547965E+02 - 2.530006E+01 3.000000E+01 6 8.419390E+01 -1.733304E-03 8.419390E+01 -2.547023E-03 - 2.530006E+01 6.000000E+01 1 2.663543E+01 8.990598E+01 4.370455E-02 2.663539E+01 - 2.530006E+01 6.000000E+01 2 4.879833E+01 8.988909E+01 9.445865E-02 4.879824E+01 - 2.530006E+01 6.000000E+01 3 1.806845E+02 4.012356E-01 1.806801E+02 1.265302E+00 - 2.530006E+01 6.000000E+01 4 1.621776E+02 8.988909E+01 3.139356E-01 1.621773E+02 - 2.530006E+01 6.000000E+01 5 2.650708E+02 8.990598E+01 4.350087E-01 2.650704E+02 - 2.530006E+01 6.000000E+01 6 8.511478E+01 -1.726902E-03 8.511478E+01 -2.565370E-03 - 2.530006E+01 9.000000E+01 1 2.772455E-06 -9.005999E+01 -2.903029E-09 -2.772453E-06 - 2.530006E+01 9.000000E+01 2 5.664659E+01 8.988908E+01 1.096615E-01 5.664648E+01 - 2.530006E+01 9.000000E+01 3 1.816694E+02 4.022422E-01 1.816649E+02 1.275391E+00 - 2.530006E+01 9.000000E+01 4 1.890861E+02 8.988956E+01 3.644627E-01 1.890857E+02 - 2.530006E+01 9.000000E+01 5 1.259696E-04 -8.998502E+01 3.294310E-08 -1.259696E-04 - 2.530006E+01 9.000000E+01 6 7.326716E-06 1.799988E+02 -7.326716E-06 1.483733E-10 - 2.540006E+01 0.000000E+00 1 5.230154E+01 8.990676E+01 8.510897E-02 5.230147E+01 - 2.540006E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.540006E+01 0.000000E+00 3 1.779963E+02 3.949230E-01 1.779921E+02 1.226866E+00 - 2.540006E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.540006E+01 0.000000E+00 5 5.211514E+02 8.990677E+01 8.480092E-01 5.211507E+02 - 2.540006E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.540006E+01 3.000000E+01 1 4.551067E+01 8.990678E+01 7.404727E-02 4.551060E+01 - 2.540006E+01 3.000000E+01 2 2.776632E+01 8.989018E+01 5.322068E-02 2.776627E+01 - 2.540006E+01 3.000000E+01 3 1.789560E+02 3.959090E-01 1.789518E+02 1.236561E+00 - 2.540006E+01 3.000000E+01 4 9.143183E+01 8.988921E+01 1.768100E-01 9.143166E+01 - 2.540006E+01 3.000000E+01 5 4.534624E+02 8.990678E+01 7.377992E-01 4.534618E+02 - 2.540006E+01 3.000000E+01 6 8.348849E+01 -1.701282E-03 8.348849E+01 -2.479021E-03 - 2.540006E+01 6.000000E+01 1 2.652739E+01 8.990681E+01 4.314886E-02 2.652736E+01 - 2.540006E+01 6.000000E+01 2 4.860004E+01 8.989016E+01 9.317198E-02 4.859996E+01 - 2.540006E+01 6.000000E+01 3 1.808939E+02 3.978804E-01 1.808895E+02 1.256175E+00 - 2.540006E+01 6.000000E+01 4 1.614544E+02 8.989015E+01 3.095352E-01 1.614541E+02 - 2.540006E+01 6.000000E+01 5 2.642698E+02 8.990679E+01 4.299184E-01 2.642694E+02 - 2.540006E+01 6.000000E+01 6 8.439370E+01 -1.695051E-03 8.439370E+01 -2.496722E-03 - 2.540006E+01 9.000000E+01 1 2.760949E-06 -9.005966E+01 -2.875039E-09 -2.760948E-06 - 2.540006E+01 9.000000E+01 2 5.641391E+01 8.989014E+01 1.081625E-01 5.641381E+01 - 2.540006E+01 9.000000E+01 3 1.818706E+02 3.988698E-01 1.818662E+02 1.266098E+00 - 2.540006E+01 9.000000E+01 4 1.882291E+02 8.989062E+01 3.593362E-01 1.882288E+02 - 2.540006E+01 9.000000E+01 5 1.254894E-04 -8.998520E+01 3.241390E-08 -1.254894E-04 - 2.540006E+01 9.000000E+01 6 7.264190E-06 1.799989E+02 -7.264190E-06 1.444104E-10 - 2.550006E+01 0.000000E+00 1 5.209661E+01 8.990757E+01 8.404067E-02 5.209655E+01 - 2.550006E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.550006E+01 0.000000E+00 3 1.782248E+02 3.916592E-01 1.782206E+02 1.218289E+00 - 2.550006E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.550006E+01 0.000000E+00 5 5.196445E+02 8.990758E+01 8.382323E-01 5.196438E+02 - 2.550006E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.550006E+01 3.000000E+01 1 4.533051E+01 8.990759E+01 7.311536E-02 4.533046E+01 - 2.550006E+01 3.000000E+01 2 2.765651E+01 8.989123E+01 5.250428E-02 2.765646E+01 - 2.550006E+01 3.000000E+01 3 1.791780E+02 3.926268E-01 1.791738E+02 1.227831E+00 - 2.550006E+01 3.000000E+01 4 9.104112E+01 8.989027E+01 1.743610E-01 9.104095E+01 - 2.550006E+01 3.000000E+01 5 4.521271E+02 8.990759E+01 7.292583E-01 4.521265E+02 - 2.550006E+01 3.000000E+01 6 8.279195E+01 -1.670009E-03 8.279195E+01 -2.413150E-03 - 2.550006E+01 6.000000E+01 1 2.642026E+01 8.990761E+01 4.260239E-02 2.642022E+01 - 2.550006E+01 6.000000E+01 2 4.840344E+01 8.989120E+01 9.190919E-02 4.840335E+01 - 2.550006E+01 6.000000E+01 3 1.811003E+02 3.945653E-01 1.810961E+02 1.247131E+00 - 2.550006E+01 6.000000E+01 4 1.607382E+02 8.989120E+01 3.052194E-01 1.607379E+02 - 2.550006E+01 6.000000E+01 5 2.634714E+02 8.990760E+01 4.249104E-01 2.634711E+02 - 2.550006E+01 6.000000E+01 6 8.368171E+01 -1.663949E-03 8.368171E+01 -2.430232E-03 - 2.550006E+01 9.000000E+01 1 2.749541E-06 -9.005933E+01 -2.847323E-09 -2.749540E-06 - 2.550006E+01 9.000000E+01 2 5.618304E+01 8.989120E+01 1.066911E-01 5.618293E+01 - 2.550006E+01 9.000000E+01 3 1.820701E+02 3.955380E-01 1.820657E+02 1.256900E+00 - 2.550006E+01 9.000000E+01 4 1.873790E+02 8.989166E+01 3.543107E-01 1.873787E+02 - 2.550006E+01 9.000000E+01 5 1.250131E-04 -8.998538E+01 3.189593E-08 -1.250131E-04 - 2.550006E+01 9.000000E+01 6 7.202465E-06 1.799989E+02 -7.202465E-06 1.405721E-10 - 2.560006E+01 0.000000E+00 1 5.189355E+01 8.990837E+01 8.299110E-02 5.189349E+01 - 2.560006E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.560006E+01 0.000000E+00 3 1.784516E+02 3.884348E-01 1.784475E+02 1.209798E+00 - 2.560006E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.560006E+01 0.000000E+00 5 5.181401E+02 8.990838E+01 8.285958E-01 5.181395E+02 - 2.560006E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.560006E+01 3.000000E+01 1 4.515197E+01 8.990839E+01 7.219904E-02 4.515192E+01 - 2.560006E+01 3.000000E+01 2 2.754763E+01 8.989227E+01 5.180098E-02 2.754758E+01 - 2.560006E+01 3.000000E+01 3 1.793979E+02 3.893873E-01 1.793937E+02 1.219195E+00 - 2.560006E+01 3.000000E+01 4 9.065352E+01 8.989131E+01 1.719588E-01 9.065336E+01 - 2.560006E+01 3.000000E+01 5 4.508022E+02 8.990839E+01 7.208501E-01 4.508016E+02 - 2.560006E+01 3.000000E+01 6 8.210437E+01 -1.639471E-03 8.210437E+01 -2.349349E-03 - 2.560006E+01 6.000000E+01 1 2.631397E+01 8.990841E+01 4.206533E-02 2.631394E+01 - 2.560006E+01 6.000000E+01 2 4.820838E+01 8.989223E+01 9.066956E-02 4.820830E+01 - 2.560006E+01 6.000000E+01 3 1.813056E+02 3.912900E-01 1.813014E+02 1.238181E+00 - 2.560006E+01 6.000000E+01 4 1.600283E+02 8.989223E+01 3.009848E-01 1.600280E+02 - 2.560006E+01 6.000000E+01 5 2.626792E+02 8.990839E+01 4.199771E-01 2.626789E+02 - 2.560006E+01 6.000000E+01 6 8.297894E+01 -1.633574E-03 8.297894E+01 -2.365833E-03 - 2.560006E+01 9.000000E+01 1 2.738228E-06 -9.005901E+01 -2.819910E-09 -2.738226E-06 - 2.560006E+01 9.000000E+01 2 5.595417E+01 8.989223E+01 1.052474E-01 5.595407E+01 - 2.560006E+01 9.000000E+01 3 1.822680E+02 3.922426E-01 1.822638E+02 1.247784E+00 - 2.560006E+01 9.000000E+01 4 1.865367E+02 8.989268E+01 3.493795E-01 1.865363E+02 - 2.560006E+01 9.000000E+01 5 1.245393E-04 -8.998556E+01 3.138911E-08 -1.245393E-04 - 2.560006E+01 9.000000E+01 6 7.141562E-06 1.799989E+02 -7.141562E-06 1.368536E-10 - 2.570006E+01 0.000000E+00 1 5.169181E+01 8.990916E+01 8.195859E-02 5.169174E+01 - 2.570006E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.570006E+01 0.000000E+00 3 1.786752E+02 3.852565E-01 1.786711E+02 1.201402E+00 - 2.570006E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.570006E+01 0.000000E+00 5 5.166389E+02 8.990916E+01 8.191053E-01 5.166382E+02 - 2.570006E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.570006E+01 3.000000E+01 1 4.497443E+01 8.990917E+01 7.129841E-02 4.497437E+01 - 2.570006E+01 3.000000E+01 2 2.743947E+01 8.989327E+01 5.111049E-02 2.743943E+01 - 2.570006E+01 3.000000E+01 3 1.796143E+02 3.861879E-01 1.796102E+02 1.210636E+00 - 2.570006E+01 3.000000E+01 4 9.026964E+01 8.989235E+01 1.696022E-01 9.026948E+01 - 2.570006E+01 3.000000E+01 5 4.494815E+02 8.990917E+01 7.125678E-01 4.494809E+02 - 2.570006E+01 3.000000E+01 6 8.142542E+01 -1.609643E-03 8.142542E+01 -2.287530E-03 - 2.570006E+01 6.000000E+01 1 2.620855E+01 8.990919E+01 4.153742E-02 2.620851E+01 - 2.570006E+01 6.000000E+01 2 4.801499E+01 8.989326E+01 8.945265E-02 4.801491E+01 - 2.570006E+01 6.000000E+01 3 1.815072E+02 3.880599E-01 1.815030E+02 1.229325E+00 - 2.570006E+01 6.000000E+01 4 1.593258E+02 8.989326E+01 2.968335E-01 1.593255E+02 - 2.570006E+01 6.000000E+01 5 2.618866E+02 8.990918E+01 4.151195E-01 2.618863E+02 - 2.570006E+01 6.000000E+01 6 8.228532E+01 -1.603900E-03 8.228532E+01 -2.303440E-03 - 2.570006E+01 9.000000E+01 1 2.727010E-06 -9.005869E+01 -2.792771E-09 -2.727008E-06 - 2.570006E+01 9.000000E+01 2 5.572707E+01 8.989325E+01 1.038303E-01 5.572697E+01 - 2.570006E+01 9.000000E+01 3 1.824620E+02 3.889971E-01 1.824578E+02 1.238776E+00 - 2.570006E+01 9.000000E+01 4 1.857030E+02 8.989370E+01 3.445441E-01 1.857027E+02 - 2.570006E+01 9.000000E+01 5 1.240707E-04 -8.998573E+01 3.089279E-08 -1.240707E-04 - 2.570006E+01 9.000000E+01 6 7.081438E-06 1.799989E+02 -7.081438E-06 1.332513E-10 - 2.580006E+01 0.000000E+00 1 5.149174E+01 8.990993E+01 8.094350E-02 5.149168E+01 - 2.580006E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.580006E+01 0.000000E+00 3 1.788970E+02 3.821118E-01 1.788931E+02 1.193075E+00 - 2.580006E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.580006E+01 0.000000E+00 5 5.151501E+02 8.990994E+01 8.097555E-01 5.151495E+02 - 2.580006E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.580006E+01 3.000000E+01 1 4.479865E+01 8.990995E+01 7.041294E-02 4.479859E+01 - 2.580006E+01 3.000000E+01 2 2.733228E+01 8.989428E+01 5.043266E-02 2.733224E+01 - 2.580006E+01 3.000000E+01 3 1.798286E+02 3.830300E-01 1.798246E+02 1.202170E+00 - 2.580006E+01 3.000000E+01 4 8.988863E+01 8.989337E+01 1.672889E-01 8.988848E+01 - 2.580006E+01 3.000000E+01 5 4.481632E+02 8.990995E+01 7.044100E-01 4.481627E+02 - 2.580006E+01 3.000000E+01 6 8.075513E+01 -1.580509E-03 8.075513E+01 -2.227637E-03 - 2.580006E+01 6.000000E+01 1 2.610392E+01 8.990997E+01 4.101842E-02 2.610389E+01 - 2.580006E+01 6.000000E+01 2 4.782318E+01 8.989426E+01 8.825807E-02 4.782310E+01 - 2.580006E+01 6.000000E+01 3 1.817074E+02 3.848689E-01 1.817033E+02 1.220561E+00 - 2.580006E+01 6.000000E+01 4 1.586282E+02 8.989426E+01 2.927581E-01 1.586279E+02 - 2.580006E+01 6.000000E+01 5 2.610994E+02 8.990996E+01 4.103387E-01 2.610991E+02 - 2.580006E+01 6.000000E+01 6 8.160052E+01 -1.574919E-03 8.160052E+01 -2.242996E-03 - 2.580006E+01 9.000000E+01 1 2.715886E-06 -9.005836E+01 -2.765918E-09 -2.715885E-06 - 2.580006E+01 9.000000E+01 2 5.550196E+01 8.989425E+01 1.024391E-01 5.550187E+01 - 2.580006E+01 9.000000E+01 3 1.826550E+02 3.857875E-01 1.826509E+02 1.229855E+00 - 2.580006E+01 9.000000E+01 4 1.848768E+02 8.989470E+01 3.397984E-01 1.848765E+02 - 2.580006E+01 9.000000E+01 5 1.236045E-04 -8.998591E+01 3.040703E-08 -1.236045E-04 - 2.580006E+01 9.000000E+01 6 7.022090E-06 1.799989E+02 -7.022090E-06 1.297610E-10 - 2.590006E+01 0.000000E+00 1 5.129295E+01 8.991070E+01 7.994528E-02 5.129289E+01 - 2.590006E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.590006E+01 0.000000E+00 3 1.791144E+02 3.790093E-01 1.791105E+02 1.184826E+00 - 2.590006E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.590006E+01 0.000000E+00 5 5.136596E+02 8.991071E+01 8.005537E-01 5.136590E+02 - 2.590006E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.590006E+01 3.000000E+01 1 4.462414E+01 8.991071E+01 6.954189E-02 4.462409E+01 - 2.590006E+01 3.000000E+01 2 2.722587E+01 8.989527E+01 4.976699E-02 2.722582E+01 - 2.590006E+01 3.000000E+01 3 1.800397E+02 3.799113E-01 1.800357E+02 1.193781E+00 - 2.590006E+01 3.000000E+01 4 8.951101E+01 8.989437E+01 1.650197E-01 8.951086E+01 - 2.590006E+01 3.000000E+01 5 4.468538E+02 8.991071E+01 6.963717E-01 4.468533E+02 - 2.590006E+01 3.000000E+01 6 8.009295E+01 -1.552043E-03 8.009295E+01 -2.169579E-03 - 2.590006E+01 6.000000E+01 1 2.600018E+01 8.991074E+01 4.050803E-02 2.600015E+01 - 2.590006E+01 6.000000E+01 2 4.763277E+01 8.989525E+01 8.708522E-02 4.763269E+01 - 2.590006E+01 6.000000E+01 3 1.819051E+02 3.817146E-01 1.819011E+02 1.211875E+00 - 2.590006E+01 6.000000E+01 4 1.579380E+02 8.989525E+01 2.887590E-01 1.579378E+02 - 2.590006E+01 6.000000E+01 5 2.603143E+02 8.991072E+01 4.056258E-01 2.603140E+02 - 2.590006E+01 6.000000E+01 6 8.092432E+01 -1.546603E-03 8.092432E+01 -2.184416E-03 - 2.590006E+01 9.000000E+01 1 2.704857E-06 -9.005803E+01 -2.739347E-09 -2.704856E-06 - 2.590006E+01 9.000000E+01 2 5.527861E+01 8.989524E+01 1.010732E-01 5.527851E+01 - 2.590006E+01 9.000000E+01 3 1.828451E+02 3.826203E-01 1.828410E+02 1.221027E+00 - 2.590006E+01 9.000000E+01 4 1.840587E+02 8.989568E+01 3.351416E-01 1.840584E+02 - 2.590006E+01 9.000000E+01 5 1.231414E-04 -8.998608E+01 2.993141E-08 -1.231414E-04 - 2.590006E+01 9.000000E+01 6 6.963511E-06 1.799990E+02 -6.963511E-06 1.263779E-10 - 2.600006E+01 0.000000E+00 1 5.109602E+01 8.991145E+01 7.896393E-02 5.109596E+01 - 2.600006E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.600006E+01 0.000000E+00 3 1.793311E+02 3.759445E-01 1.793272E+02 1.176667E+00 - 2.600006E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.600006E+01 0.000000E+00 5 5.121817E+02 8.991146E+01 7.914839E-01 5.121811E+02 - 2.600006E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.600006E+01 3.000000E+01 1 4.445098E+01 8.991147E+01 6.868564E-02 4.445093E+01 - 2.600006E+01 3.000000E+01 2 2.712029E+01 8.989624E+01 4.911324E-02 2.712024E+01 - 2.600006E+01 3.000000E+01 3 1.802490E+02 3.768303E-01 1.802451E+02 1.185476E+00 - 2.600006E+01 3.000000E+01 4 8.913700E+01 8.989536E+01 1.627916E-01 8.913686E+01 - 2.600006E+01 3.000000E+01 5 4.455464E+02 8.991146E+01 6.884615E-01 4.455459E+02 - 2.600006E+01 3.000000E+01 6 7.943929E+01 -1.524229E-03 7.943929E+01 -2.113309E-03 - 2.600006E+01 6.000000E+01 1 2.589724E+01 8.991149E+01 4.000637E-02 2.589721E+01 - 2.600006E+01 6.000000E+01 2 4.744403E+01 8.989622E+01 8.593361E-02 4.744396E+01 - 2.600006E+01 6.000000E+01 3 1.820998E+02 3.786066E-01 1.820958E+02 1.203294E+00 - 2.600006E+01 6.000000E+01 4 1.572541E+02 8.989622E+01 2.848348E-01 1.572538E+02 - 2.600006E+01 6.000000E+01 5 2.595318E+02 8.991148E+01 4.009877E-01 2.595315E+02 - 2.600006E+01 6.000000E+01 6 8.025684E+01 -1.518931E-03 8.025684E+01 -2.127636E-03 - 2.600006E+01 9.000000E+01 1 2.693912E-06 -9.005771E+01 -2.713053E-09 -2.693911E-06 - 2.600006E+01 9.000000E+01 2 5.505724E+01 8.989621E+01 9.973222E-02 5.505715E+01 - 2.600006E+01 9.000000E+01 3 1.830339E+02 3.794927E-01 1.830299E+02 1.212297E+00 - 2.600006E+01 9.000000E+01 4 1.832482E+02 8.989664E+01 3.305736E-01 1.832479E+02 - 2.600006E+01 9.000000E+01 5 1.226827E-04 -8.998624E+01 2.946566E-08 -1.226827E-04 - 2.600006E+01 9.000000E+01 6 6.905673E-06 1.799990E+02 -6.905673E-06 1.230990E-10 - 2.610006E+01 0.000000E+00 1 5.090041E+01 8.991220E+01 7.799821E-02 5.090035E+01 - 2.610006E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.610006E+01 0.000000E+00 3 1.795460E+02 3.729165E-01 1.795422E+02 1.168588E+00 - 2.610006E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.610006E+01 0.000000E+00 5 5.107065E+02 8.991221E+01 7.825466E-01 5.107059E+02 - 2.610006E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.610006E+01 3.000000E+01 1 4.427908E+01 8.991222E+01 6.784350E-02 4.427903E+01 - 2.610006E+01 3.000000E+01 2 2.701556E+01 8.989720E+01 4.847119E-02 2.701551E+01 - 2.610006E+01 3.000000E+01 3 1.804570E+02 3.737855E-01 1.804531E+02 1.177255E+00 - 2.610006E+01 3.000000E+01 4 8.876540E+01 8.989633E+01 1.606045E-01 8.876526E+01 - 2.610006E+01 3.000000E+01 5 4.442437E+02 8.991222E+01 6.806616E-01 4.442431E+02 - 2.610006E+01 3.000000E+01 6 7.879364E+01 -1.497048E-03 7.879364E+01 -2.058754E-03 - 2.610006E+01 6.000000E+01 1 2.579519E+01 8.991224E+01 3.951291E-02 2.579516E+01 - 2.610006E+01 6.000000E+01 2 4.725676E+01 8.989718E+01 8.480272E-02 4.725668E+01 - 2.610006E+01 6.000000E+01 3 1.822945E+02 3.755299E-01 1.822906E+02 1.194792E+00 - 2.610006E+01 6.000000E+01 4 1.565759E+02 8.989718E+01 2.809838E-01 1.565756E+02 - 2.610006E+01 6.000000E+01 5 2.587555E+02 8.991222E+01 3.964159E-01 2.587552E+02 - 2.610006E+01 6.000000E+01 6 7.959760E+01 -1.491891E-03 7.959760E+01 -2.072594E-03 - 2.610006E+01 9.000000E+01 1 2.683070E-06 -9.005738E+01 -2.687030E-09 -2.683068E-06 - 2.610006E+01 9.000000E+01 2 5.483751E+01 8.989718E+01 9.841555E-02 5.483743E+01 - 2.610006E+01 9.000000E+01 3 1.832212E+02 3.764021E-01 1.832172E+02 1.203655E+00 - 2.610006E+01 9.000000E+01 4 1.824440E+02 8.989759E+01 3.260891E-01 1.824437E+02 - 2.610006E+01 9.000000E+01 5 1.222264E-04 -8.998640E+01 2.900953E-08 -1.222264E-04 - 2.610006E+01 9.000000E+01 6 6.848570E-06 1.799990E+02 -6.848570E-06 1.199204E-10 - 2.620006E+01 0.000000E+00 1 5.070644E+01 8.991294E+01 7.704881E-02 5.070638E+01 - 2.620006E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.620006E+01 0.000000E+00 3 1.797571E+02 3.699245E-01 1.797534E+02 1.160576E+00 - 2.620006E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.620006E+01 0.000000E+00 5 5.092314E+02 8.991295E+01 7.737415E-01 5.092308E+02 - 2.620006E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.620006E+01 3.000000E+01 1 4.410872E+01 8.991296E+01 6.701516E-02 4.410867E+01 - 2.620006E+01 3.000000E+01 2 2.691160E+01 8.989815E+01 4.784046E-02 2.691155E+01 - 2.620006E+01 3.000000E+01 3 1.806618E+02 3.707798E-01 1.806580E+02 1.169114E+00 - 2.620006E+01 3.000000E+01 4 8.839765E+01 8.989730E+01 1.584572E-01 8.839751E+01 - 2.620006E+01 3.000000E+01 5 4.429486E+02 8.991296E+01 6.729875E-01 4.429481E+02 - 2.620006E+01 3.000000E+01 6 7.815615E+01 -1.470482E-03 7.815615E+01 -2.005859E-03 - 2.620006E+01 6.000000E+01 1 2.569386E+01 8.991297E+01 3.902771E-02 2.569383E+01 - 2.620006E+01 6.000000E+01 2 4.707100E+01 8.989813E+01 8.369195E-02 4.707092E+01 - 2.620006E+01 6.000000E+01 3 1.824854E+02 3.724924E-01 1.824815E+02 1.186369E+00 - 2.620006E+01 6.000000E+01 4 1.559037E+02 8.989812E+01 2.772022E-01 1.559034E+02 - 2.620006E+01 6.000000E+01 5 2.579809E+02 8.991296E+01 3.919181E-01 2.579806E+02 - 2.620006E+01 6.000000E+01 6 7.894678E+01 -1.465459E-03 7.894678E+01 -2.019228E-03 - 2.620006E+01 9.000000E+01 1 2.672306E-06 -9.005706E+01 -2.661287E-09 -2.672305E-06 - 2.620006E+01 9.000000E+01 2 5.461969E+01 8.989812E+01 9.712229E-02 5.461960E+01 - 2.620006E+01 9.000000E+01 3 1.834053E+02 3.733473E-01 1.834014E+02 1.195086E+00 - 2.620006E+01 9.000000E+01 4 1.816475E+02 8.989854E+01 3.216880E-01 1.816472E+02 - 2.620006E+01 9.000000E+01 5 1.217739E-04 -8.998656E+01 2.856275E-08 -1.217739E-04 - 2.620006E+01 9.000000E+01 6 6.792188E-06 1.799990E+02 -6.792188E-06 1.168381E-10 - 2.630006E+01 0.000000E+00 1 5.051381E+01 8.991367E+01 7.611477E-02 5.051376E+01 - 2.630006E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.630006E+01 0.000000E+00 3 1.799664E+02 3.669711E-01 1.799627E+02 1.152651E+00 - 2.630006E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.630006E+01 0.000000E+00 5 5.077678E+02 8.991367E+01 7.650717E-01 5.077672E+02 - 2.630006E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.630006E+01 3.000000E+01 1 4.393940E+01 8.991367E+01 6.620029E-02 4.393935E+01 - 2.630006E+01 3.000000E+01 2 2.680844E+01 8.989908E+01 4.722099E-02 2.680840E+01 - 2.630006E+01 3.000000E+01 3 1.808641E+02 3.678109E-01 1.808603E+02 1.161051E+00 - 2.630006E+01 3.000000E+01 4 8.803287E+01 8.989824E+01 1.563495E-01 8.803273E+01 - 2.630006E+01 3.000000E+01 5 4.416592E+02 8.991367E+01 6.654167E-01 4.416587E+02 - 2.630006E+01 3.000000E+01 6 7.752633E+01 -1.444522E-03 7.752633E+01 -1.954567E-03 - 2.630006E+01 6.000000E+01 1 2.559350E+01 8.991370E+01 3.855051E-02 2.559347E+01 - 2.630006E+01 6.000000E+01 2 4.688665E+01 8.989906E+01 8.260126E-02 4.688658E+01 - 2.630006E+01 6.000000E+01 3 1.826747E+02 3.694938E-01 1.826709E+02 1.178040E+00 - 2.630006E+01 6.000000E+01 4 1.552378E+02 8.989906E+01 2.734921E-01 1.552376E+02 - 2.630006E+01 6.000000E+01 5 2.572104E+02 8.991368E+01 3.874862E-01 2.572101E+02 - 2.630006E+01 6.000000E+01 6 7.830399E+01 -1.439627E-03 7.830399E+01 -1.967484E-03 - 2.630006E+01 9.000000E+01 1 2.661636E-06 -9.005674E+01 -2.635820E-09 -2.661635E-06 - 2.630006E+01 9.000000E+01 2 5.440361E+01 8.989906E+01 9.585236E-02 5.440353E+01 - 2.630006E+01 9.000000E+01 3 1.835871E+02 3.703380E-01 1.835832E+02 1.186628E+00 - 2.630006E+01 9.000000E+01 4 1.808585E+02 8.989946E+01 3.173669E-01 1.808582E+02 - 2.630006E+01 9.000000E+01 5 1.213248E-04 -8.998672E+01 2.812506E-08 -1.213248E-04 - 2.630006E+01 9.000000E+01 6 6.736523E-06 1.799990E+02 -6.736523E-06 1.138494E-10 - 2.640006E+01 0.000000E+00 1 5.032254E+01 8.991439E+01 7.519586E-02 5.032248E+01 - 2.640006E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.640006E+01 0.000000E+00 3 1.801734E+02 3.640529E-01 1.801698E+02 1.144800E+00 - 2.640006E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.640006E+01 0.000000E+00 5 5.063096E+02 8.991439E+01 7.565247E-01 5.063090E+02 - 2.640006E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.640006E+01 3.000000E+01 1 4.377151E+01 8.991439E+01 6.539898E-02 4.377147E+01 - 2.640006E+01 3.000000E+01 2 2.670610E+01 8.989999E+01 4.661248E-02 2.670606E+01 - 2.640006E+01 3.000000E+01 3 1.810648E+02 3.648795E-01 1.810612E+02 1.153076E+00 - 2.640006E+01 3.000000E+01 4 8.767094E+01 8.989918E+01 1.542793E-01 8.767080E+01 - 2.640006E+01 3.000000E+01 5 4.403716E+02 8.991439E+01 6.579621E-01 4.403712E+02 - 2.640006E+01 3.000000E+01 6 7.690427E+01 -1.419140E-03 7.690427E+01 -1.904816E-03 - 2.640006E+01 6.000000E+01 1 2.549375E+01 8.991441E+01 3.808119E-02 2.549372E+01 - 2.640006E+01 6.000000E+01 2 4.670385E+01 8.989998E+01 8.152983E-02 4.670377E+01 - 2.640006E+01 6.000000E+01 3 1.828615E+02 3.665332E-01 1.828577E+02 1.169795E+00 - 2.640006E+01 6.000000E+01 4 1.545782E+02 8.989998E+01 2.698491E-01 1.545780E+02 - 2.640006E+01 6.000000E+01 5 2.564434E+02 8.991440E+01 3.831136E-01 2.564431E+02 - 2.640006E+01 6.000000E+01 6 7.766911E+01 -1.414375E-03 7.766911E+01 -1.917301E-03 - 2.640006E+01 9.000000E+01 1 2.651050E-06 -9.005642E+01 -2.610633E-09 -2.651049E-06 - 2.640006E+01 9.000000E+01 2 5.418918E+01 8.989998E+01 9.460504E-02 5.418909E+01 - 2.640006E+01 9.000000E+01 3 1.837673E+02 3.673604E-01 1.837635E+02 1.178243E+00 - 2.640006E+01 9.000000E+01 4 1.800775E+02 8.990038E+01 3.131272E-01 1.800772E+02 - 2.640006E+01 9.000000E+01 5 1.208786E-04 -8.998688E+01 2.769650E-08 -1.208786E-04 - 2.640006E+01 9.000000E+01 6 6.681551E-06 1.799991E+02 -6.681551E-06 1.109505E-10 - 2.650006E+01 0.000000E+00 1 5.013262E+01 8.991509E+01 7.429196E-02 5.013257E+01 - 2.650006E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.650006E+01 0.000000E+00 3 1.803780E+02 3.611699E-01 1.803744E+02 1.137024E+00 - 2.650006E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.650006E+01 0.000000E+00 5 5.048548E+02 8.991510E+01 7.481000E-01 5.048543E+02 - 2.650006E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.650006E+01 3.000000E+01 1 4.360493E+01 8.991511E+01 6.461056E-02 4.360489E+01 - 2.650006E+01 3.000000E+01 2 2.660445E+01 8.990090E+01 4.601443E-02 2.660441E+01 - 2.650006E+01 3.000000E+01 3 1.812630E+02 3.619791E-01 1.812593E+02 1.145162E+00 - 2.650006E+01 3.000000E+01 4 8.731237E+01 8.990009E+01 1.522471E-01 8.731224E+01 - 2.650006E+01 3.000000E+01 5 4.390908E+02 8.991511E+01 6.506217E-01 4.390903E+02 - 2.650006E+01 3.000000E+01 6 7.628987E+01 -1.394326E-03 7.628987E+01 -1.856558E-03 - 2.650006E+01 6.000000E+01 1 2.539485E+01 8.991512E+01 3.761959E-02 2.539482E+01 - 2.650006E+01 6.000000E+01 2 4.652246E+01 8.990089E+01 8.047722E-02 4.652239E+01 - 2.650006E+01 6.000000E+01 3 1.830477E+02 3.636064E-01 1.830440E+02 1.161637E+00 - 2.650006E+01 6.000000E+01 4 1.539234E+02 8.990089E+01 2.662709E-01 1.539231E+02 - 2.650006E+01 6.000000E+01 5 2.556804E+02 8.991511E+01 3.788157E-01 2.556801E+02 - 2.650006E+01 6.000000E+01 6 7.704235E+01 -1.389681E-03 7.704235E+01 -1.868624E-03 - 2.650006E+01 9.000000E+01 1 2.640545E-06 -9.005611E+01 -2.585707E-09 -2.640544E-06 - 2.650006E+01 9.000000E+01 2 5.397648E+01 8.990088E+01 9.337966E-02 5.397640E+01 - 2.650006E+01 9.000000E+01 3 1.839465E+02 3.644179E-01 1.839428E+02 1.169946E+00 - 2.650006E+01 9.000000E+01 4 1.793023E+02 8.990128E+01 3.089624E-01 1.793020E+02 - 2.650006E+01 9.000000E+01 5 1.204361E-04 -8.998702E+01 2.727646E-08 -1.204361E-04 - 2.650006E+01 9.000000E+01 6 6.627258E-06 1.799991E+02 -6.627258E-06 1.081387E-10 - 2.660007E+01 0.000000E+00 1 4.994437E+01 8.991579E+01 7.340250E-02 4.994431E+01 - 2.660007E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.660007E+01 0.000000E+00 3 1.805811E+02 3.583170E-01 1.805776E+02 1.129313E+00 - 2.660007E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.660007E+01 0.000000E+00 5 5.034080E+02 8.991580E+01 7.398058E-01 5.034074E+02 - 2.660007E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.660007E+01 3.000000E+01 1 4.343951E+01 8.991580E+01 6.383497E-02 4.343946E+01 - 2.660007E+01 3.000000E+01 2 2.650364E+01 8.990180E+01 4.542688E-02 2.650360E+01 - 2.660007E+01 3.000000E+01 3 1.814593E+02 3.591148E-01 1.814557E+02 1.137331E+00 - 2.660007E+01 3.000000E+01 4 8.695663E+01 8.990100E+01 1.502510E-01 8.695650E+01 - 2.660007E+01 3.000000E+01 5 4.378155E+02 8.991580E+01 6.433796E-01 4.378150E+02 - 2.660007E+01 3.000000E+01 6 7.568286E+01 -1.370062E-03 7.568286E+01 -1.809736E-03 - 2.660007E+01 6.000000E+01 1 2.529667E+01 8.991582E+01 3.716544E-02 2.529665E+01 - 2.660007E+01 6.000000E+01 2 4.634241E+01 8.990178E+01 7.944313E-02 4.634234E+01 - 2.660007E+01 6.000000E+01 3 1.832295E+02 3.607149E-01 1.832259E+02 1.153543E+00 - 2.660007E+01 6.000000E+01 4 1.532749E+02 8.990178E+01 2.627592E-01 1.532746E+02 - 2.660007E+01 6.000000E+01 5 2.549184E+02 8.991581E+01 3.745768E-01 2.549181E+02 - 2.660007E+01 6.000000E+01 6 7.642311E+01 -1.365538E-03 7.642311E+01 -1.821402E-03 - 2.660007E+01 9.000000E+01 1 2.630131E-06 -9.005579E+01 -2.561041E-09 -2.630130E-06 - 2.660007E+01 9.000000E+01 2 5.376562E+01 8.990177E+01 9.217608E-02 5.376554E+01 - 2.660007E+01 9.000000E+01 3 1.841226E+02 3.615143E-01 1.841189E+02 1.161735E+00 - 2.660007E+01 9.000000E+01 4 1.785347E+02 8.990216E+01 3.048739E-01 1.785345E+02 - 2.660007E+01 9.000000E+01 5 1.199960E-04 -8.998717E+01 2.686492E-08 -1.199960E-04 - 2.660007E+01 9.000000E+01 6 6.573651E-06 1.799991E+02 -6.573651E-06 1.054108E-10 - 2.670007E+01 0.000000E+00 1 4.975744E+01 8.991648E+01 7.252754E-02 4.975739E+01 - 2.670007E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.670007E+01 0.000000E+00 3 1.807815E+02 3.555000E-01 1.807780E+02 1.121678E+00 - 2.670007E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.670007E+01 0.000000E+00 5 5.019677E+02 8.991649E+01 7.316379E-01 5.019671E+02 - 2.670007E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.670007E+01 3.000000E+01 1 4.327540E+01 8.991650E+01 6.307177E-02 4.327536E+01 - 2.670007E+01 3.000000E+01 2 2.640359E+01 8.990268E+01 4.484951E-02 2.640355E+01 - 2.670007E+01 3.000000E+01 3 1.816536E+02 3.562858E-01 1.816501E+02 1.129580E+00 - 2.670007E+01 3.000000E+01 4 8.660397E+01 8.990189E+01 1.482904E-01 8.660384E+01 - 2.670007E+01 3.000000E+01 5 4.365475E+02 8.991649E+01 6.362560E-01 4.365471E+02 - 2.670007E+01 3.000000E+01 6 7.508324E+01 -1.346339E-03 7.508324E+01 -1.764310E-03 - 2.670007E+01 6.000000E+01 1 2.519938E+01 8.991651E+01 3.671863E-02 2.519935E+01 - 2.670007E+01 6.000000E+01 2 4.616380E+01 8.990266E+01 7.842716E-02 4.616373E+01 - 2.670007E+01 6.000000E+01 3 1.834113E+02 3.578544E-01 1.834077E+02 1.145531E+00 - 2.670007E+01 6.000000E+01 4 1.526322E+02 8.990266E+01 2.593098E-01 1.526319E+02 - 2.670007E+01 6.000000E+01 5 2.541618E+02 8.991650E+01 3.703984E-01 2.541615E+02 - 2.670007E+01 6.000000E+01 6 7.581155E+01 -1.341930E-03 7.581155E+01 -1.775589E-03 - 2.670007E+01 9.000000E+01 1 2.619800E-06 -9.005548E+01 -2.536655E-09 -2.619799E-06 - 2.670007E+01 9.000000E+01 2 5.355633E+01 8.990266E+01 9.099358E-02 5.355625E+01 - 2.670007E+01 9.000000E+01 3 1.842975E+02 3.586431E-01 1.842939E+02 1.153603E+00 - 2.670007E+01 9.000000E+01 4 1.777730E+02 8.990304E+01 3.008603E-01 1.777727E+02 - 2.670007E+01 9.000000E+01 5 1.195592E-04 -8.998732E+01 2.646168E-08 -1.195592E-04 - 2.670007E+01 9.000000E+01 6 6.520702E-06 1.799991E+02 -6.520702E-06 1.027639E-10 - 2.680007E+01 0.000000E+00 1 4.957199E+01 8.991717E+01 7.166658E-02 4.957193E+01 - 2.680007E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.680007E+01 0.000000E+00 3 1.809795E+02 3.527180E-01 1.809761E+02 1.114119E+00 - 2.680007E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.680007E+01 0.000000E+00 5 5.005284E+02 8.991718E+01 7.235785E-01 5.005278E+02 - 2.680007E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.680007E+01 3.000000E+01 1 4.311250E+01 8.991718E+01 6.232109E-02 4.311246E+01 - 2.680007E+01 3.000000E+01 2 2.630436E+01 8.990355E+01 4.428224E-02 2.630432E+01 - 2.680007E+01 3.000000E+01 3 1.818457E+02 3.534885E-01 1.818422E+02 1.121897E+00 - 2.680007E+01 3.000000E+01 4 8.625410E+01 8.990278E+01 1.463647E-01 8.625397E+01 - 2.680007E+01 3.000000E+01 5 4.352836E+02 8.991718E+01 6.292251E-01 4.352831E+02 - 2.680007E+01 3.000000E+01 6 7.449078E+01 -1.323138E-03 7.449078E+01 -1.720224E-03 - 2.680007E+01 6.000000E+01 1 2.510277E+01 8.991719E+01 3.627928E-02 2.510275E+01 - 2.680007E+01 6.000000E+01 2 4.598661E+01 8.990353E+01 7.742900E-02 4.598655E+01 - 2.680007E+01 6.000000E+01 3 1.835903E+02 3.550344E-01 1.835868E+02 1.137614E+00 - 2.680007E+01 6.000000E+01 4 1.519946E+02 8.990353E+01 2.559225E-01 1.519944E+02 - 2.680007E+01 6.000000E+01 5 2.534075E+02 8.991718E+01 3.662858E-01 2.534072E+02 - 2.680007E+01 6.000000E+01 6 7.520734E+01 -1.318840E-03 7.520734E+01 -1.731130E-03 - 2.680007E+01 9.000000E+01 1 2.609547E-06 -9.005516E+01 -2.512525E-09 -2.609546E-06 - 2.680007E+01 9.000000E+01 2 5.334876E+01 8.990352E+01 8.983179E-02 5.334868E+01 - 2.680007E+01 9.000000E+01 3 1.844700E+02 3.558068E-01 1.844665E+02 1.145552E+00 - 2.680007E+01 9.000000E+01 4 1.770188E+02 8.990389E+01 2.969182E-01 1.770186E+02 - 2.680007E+01 9.000000E+01 5 1.191260E-04 -8.998746E+01 2.606647E-08 -1.191260E-04 - 2.680007E+01 9.000000E+01 6 6.468401E-06 1.799991E+02 -6.468401E-06 1.001952E-10 - 2.690007E+01 0.000000E+00 1 4.938780E+01 8.991785E+01 7.081942E-02 4.938775E+01 - 2.690007E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.690007E+01 0.000000E+00 3 1.811754E+02 3.499687E-01 1.811720E+02 1.106632E+00 - 2.690007E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.690007E+01 0.000000E+00 5 4.990980E+02 8.991785E+01 7.156407E-01 4.990975E+02 - 2.690007E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.690007E+01 3.000000E+01 1 4.295082E+01 8.991785E+01 6.158246E-02 4.295078E+01 - 2.690007E+01 3.000000E+01 2 2.620577E+01 8.990440E+01 4.372468E-02 2.620573E+01 - 2.690007E+01 3.000000E+01 3 1.820351E+02 3.507273E-01 1.820317E+02 1.114293E+00 - 2.690007E+01 3.000000E+01 4 8.590702E+01 8.990364E+01 1.444738E-01 8.590690E+01 - 2.690007E+01 3.000000E+01 5 4.340239E+02 8.991785E+01 6.222978E-01 4.340234E+02 - 2.690007E+01 3.000000E+01 6 7.390546E+01 -1.300444E-03 7.390546E+01 -1.677434E-03 - 2.690007E+01 6.000000E+01 1 2.500688E+01 8.991787E+01 3.584683E-02 2.500686E+01 - 2.690007E+01 6.000000E+01 2 4.581085E+01 8.990439E+01 7.644784E-02 4.581078E+01 - 2.690007E+01 6.000000E+01 3 1.837681E+02 3.522452E-01 1.837646E+02 1.129770E+00 - 2.690007E+01 6.000000E+01 4 1.513629E+02 8.990439E+01 2.525952E-01 1.513627E+02 - 2.690007E+01 6.000000E+01 5 2.526579E+02 8.991785E+01 3.622274E-01 2.526577E+02 - 2.690007E+01 6.000000E+01 6 7.461059E+01 -1.296254E-03 7.461059E+01 -1.687982E-03 - 2.690007E+01 9.000000E+01 1 2.599385E-06 -9.005486E+01 -2.488661E-09 -2.599384E-06 - 2.690007E+01 9.000000E+01 2 5.314262E+01 8.990438E+01 8.869006E-02 5.314255E+01 - 2.690007E+01 9.000000E+01 3 1.846405E+02 3.530075E-01 1.846369E+02 1.137589E+00 - 2.690007E+01 9.000000E+01 4 1.762712E+02 8.990475E+01 2.930458E-01 1.762710E+02 - 2.690007E+01 9.000000E+01 5 1.186961E-04 -8.998761E+01 2.567913E-08 -1.186961E-04 - 2.690007E+01 9.000000E+01 6 6.416746E-06 1.799991E+02 -6.416746E-06 9.770214E-11 - 2.700007E+01 0.000000E+00 1 4.920490E+01 8.991850E+01 6.998554E-02 4.920485E+01 - 2.700007E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.700007E+01 0.000000E+00 3 1.813689E+02 3.472509E-01 1.813656E+02 1.099211E+00 - 2.700007E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.700007E+01 0.000000E+00 5 4.976733E+02 8.991851E+01 7.078170E-01 4.976729E+02 - 2.700007E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.700007E+01 3.000000E+01 1 4.279038E+01 8.991852E+01 6.085530E-02 4.279034E+01 - 2.700007E+01 3.000000E+01 2 2.610797E+01 8.990525E+01 4.317663E-02 2.610794E+01 - 2.700007E+01 3.000000E+01 3 1.822231E+02 3.479971E-01 1.822197E+02 1.106760E+00 - 2.700007E+01 3.000000E+01 4 8.556313E+01 8.990450E+01 1.426155E-01 8.556300E+01 - 2.700007E+01 3.000000E+01 5 4.327675E+02 8.991851E+01 6.154766E-01 4.327670E+02 - 2.700007E+01 3.000000E+01 6 7.332723E+01 -1.278245E-03 7.332723E+01 -1.635900E-03 - 2.700007E+01 6.000000E+01 1 2.491184E+01 8.991853E+01 3.542138E-02 2.491181E+01 - 2.700007E+01 6.000000E+01 2 4.563639E+01 8.990524E+01 7.548375E-02 4.563633E+01 - 2.700007E+01 6.000000E+01 3 1.839427E+02 3.494898E-01 1.839393E+02 1.121997E+00 - 2.700007E+01 6.000000E+01 4 1.507368E+02 8.990523E+01 2.493267E-01 1.507366E+02 - 2.700007E+01 6.000000E+01 5 2.519093E+02 8.991852E+01 3.582369E-01 2.519090E+02 - 2.700007E+01 6.000000E+01 6 7.402103E+01 -1.274159E-03 7.402103E+01 -1.646100E-03 - 2.700007E+01 9.000000E+01 1 2.589300E-06 -9.005455E+01 -2.465060E-09 -2.589299E-06 - 2.700007E+01 9.000000E+01 2 5.293827E+01 8.990523E+01 8.756818E-02 5.293820E+01 - 2.700007E+01 9.000000E+01 3 1.848093E+02 3.502394E-01 1.848058E+02 1.129701E+00 - 2.700007E+01 9.000000E+01 4 1.755305E+02 8.990559E+01 2.892429E-01 1.755303E+02 - 2.700007E+01 9.000000E+01 5 1.182691E-04 -8.998774E+01 2.529955E-08 -1.182691E-04 - 2.700007E+01 9.000000E+01 6 6.365723E-06 1.799991E+02 -6.365723E-06 9.528219E-11 - 2.710007E+01 0.000000E+00 1 4.902344E+01 8.991917E+01 6.916495E-02 4.902339E+01 - 2.710007E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.710007E+01 0.000000E+00 3 1.815618E+02 3.445647E-01 1.815585E+02 1.091867E+00 - 2.710007E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.710007E+01 0.000000E+00 5 4.962538E+02 8.991917E+01 7.001016E-01 4.962533E+02 - 2.710007E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.710007E+01 3.000000E+01 1 4.263114E+01 8.991917E+01 6.013989E-02 4.263110E+01 - 2.710007E+01 3.000000E+01 2 2.601083E+01 8.990608E+01 4.263784E-02 2.601079E+01 - 2.710007E+01 3.000000E+01 3 1.824096E+02 3.452974E-01 1.824062E+02 1.099298E+00 - 2.710007E+01 3.000000E+01 4 8.522180E+01 8.990534E+01 1.407893E-01 8.522169E+01 - 2.710007E+01 3.000000E+01 5 4.315216E+02 8.991917E+01 6.087543E-01 4.315212E+02 - 2.710007E+01 3.000000E+01 6 7.275581E+01 -1.256524E-03 7.275581E+01 -1.595569E-03 - 2.710007E+01 6.000000E+01 1 2.481732E+01 8.991919E+01 3.500267E-02 2.481729E+01 - 2.710007E+01 6.000000E+01 2 4.546335E+01 8.990607E+01 7.453614E-02 4.546329E+01 - 2.710007E+01 6.000000E+01 3 1.841169E+02 3.467660E-01 1.841135E+02 1.114307E+00 - 2.710007E+01 6.000000E+01 4 1.501154E+02 8.990606E+01 2.461157E-01 1.501152E+02 - 2.710007E+01 6.000000E+01 5 2.511670E+02 8.991918E+01 3.542949E-01 2.511668E+02 - 2.710007E+01 6.000000E+01 6 7.343852E+01 -1.252542E-03 7.343852E+01 -1.605438E-03 - 2.710007E+01 9.000000E+01 1 2.579291E-06 -9.005424E+01 -2.441710E-09 -2.579290E-06 - 2.710007E+01 9.000000E+01 2 5.273567E+01 8.990606E+01 8.646568E-02 5.273560E+01 - 2.710007E+01 9.000000E+01 3 1.849767E+02 3.475021E-01 1.849733E+02 1.121887E+00 - 2.710007E+01 9.000000E+01 4 1.747955E+02 8.990642E+01 2.855069E-01 1.747953E+02 - 2.710007E+01 9.000000E+01 5 1.178443E-04 -8.998788E+01 2.492732E-08 -1.178443E-04 - 2.710007E+01 9.000000E+01 6 6.315318E-06 1.799992E+02 -6.315318E-06 9.293270E-11 - 2.720007E+01 0.000000E+00 1 4.884344E+01 8.991982E+01 6.835720E-02 4.884339E+01 - 2.720007E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.720007E+01 0.000000E+00 3 1.817517E+02 3.419110E-01 1.817485E+02 1.084592E+00 - 2.720007E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.720007E+01 0.000000E+00 5 4.948399E+02 8.991982E+01 6.925036E-01 4.948394E+02 - 2.720007E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.720007E+01 3.000000E+01 1 4.247307E+01 8.991982E+01 5.943553E-02 4.247303E+01 - 2.720007E+01 3.000000E+01 2 2.591444E+01 8.990690E+01 4.210823E-02 2.591440E+01 - 2.720007E+01 3.000000E+01 3 1.825933E+02 3.426316E-01 1.825900E+02 1.091911E+00 - 2.720007E+01 3.000000E+01 4 8.488303E+01 8.990617E+01 1.389956E-01 8.488292E+01 - 2.720007E+01 3.000000E+01 5 4.302785E+02 8.991982E+01 6.021183E-01 4.302781E+02 - 2.720007E+01 3.000000E+01 6 7.219109E+01 -1.235276E-03 7.219109E+01 -1.556413E-03 - 2.720007E+01 6.000000E+01 1 2.472375E+01 8.991984E+01 3.459062E-02 2.472373E+01 - 2.720007E+01 6.000000E+01 2 4.529155E+01 8.990689E+01 7.360472E-02 4.529148E+01 - 2.720007E+01 6.000000E+01 3 1.842882E+02 3.440768E-01 1.842848E+02 1.106694E+00 - 2.720007E+01 6.000000E+01 4 1.494998E+02 8.990689E+01 2.429615E-01 1.494996E+02 - 2.720007E+01 6.000000E+01 5 2.504262E+02 8.991983E+01 3.504170E-01 2.504259E+02 - 2.720007E+01 6.000000E+01 6 7.286304E+01 -1.231394E-03 7.286304E+01 -1.565964E-03 - 2.720007E+01 9.000000E+01 1 2.569363E-06 -9.005393E+01 -2.418613E-09 -2.569362E-06 - 2.720007E+01 9.000000E+01 2 5.253433E+01 8.990688E+01 8.538185E-02 5.253426E+01 - 2.720007E+01 9.000000E+01 3 1.851433E+02 3.447990E-01 1.851400E+02 1.114163E+00 - 2.720007E+01 9.000000E+01 4 1.740674E+02 8.990723E+01 2.818376E-01 1.740672E+02 - 2.720007E+01 9.000000E+01 5 1.174236E-04 -8.998801E+01 2.456243E-08 -1.174236E-04 - 2.720007E+01 9.000000E+01 6 6.265522E-06 1.799992E+02 -6.265522E-06 9.065138E-11 - 2.730007E+01 0.000000E+00 1 4.866451E+01 8.992046E+01 6.756207E-02 4.866446E+01 - 2.730007E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.730007E+01 0.000000E+00 3 1.819394E+02 3.392879E-01 1.819362E+02 1.077383E+00 - 2.730007E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.730007E+01 0.000000E+00 5 4.934328E+02 8.992046E+01 6.850067E-01 4.934323E+02 - 2.730007E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.730007E+01 3.000000E+01 1 4.231627E+01 8.992046E+01 5.874249E-02 4.231622E+01 - 2.730007E+01 3.000000E+01 2 2.581881E+01 8.990771E+01 4.158749E-02 2.581878E+01 - 2.730007E+01 3.000000E+01 3 1.827751E+02 3.399976E-01 1.827719E+02 1.084595E+00 - 2.730007E+01 3.000000E+01 4 8.454766E+01 8.990701E+01 1.372326E-01 8.454755E+01 - 2.730007E+01 3.000000E+01 5 4.290386E+02 8.992046E+01 5.955858E-01 4.290382E+02 - 2.730007E+01 3.000000E+01 6 7.163303E+01 -1.214485E-03 7.163303E+01 -1.518388E-03 - 2.730007E+01 6.000000E+01 1 2.463076E+01 8.992048E+01 3.418513E-02 2.463073E+01 - 2.730007E+01 6.000000E+01 2 4.512109E+01 8.990770E+01 7.268921E-02 4.512103E+01 - 2.730007E+01 6.000000E+01 3 1.844582E+02 3.414169E-01 1.844549E+02 1.099152E+00 - 2.730007E+01 6.000000E+01 4 1.488900E+02 8.990770E+01 2.398632E-01 1.488898E+02 - 2.730007E+01 6.000000E+01 5 2.496882E+02 8.992046E+01 3.465922E-01 2.496879E+02 - 2.730007E+01 6.000000E+01 6 7.229449E+01 -1.210696E-03 7.229449E+01 -1.527628E-03 - 2.730007E+01 9.000000E+01 1 2.559514E-06 -9.005363E+01 -2.395775E-09 -2.559513E-06 - 2.730007E+01 9.000000E+01 2 5.233474E+01 8.990769E+01 8.431654E-02 5.233467E+01 - 2.730007E+01 9.000000E+01 3 1.853064E+02 3.421285E-01 1.853031E+02 1.106508E+00 - 2.730007E+01 9.000000E+01 4 1.733455E+02 8.990804E+01 2.782318E-01 1.733453E+02 - 2.730007E+01 9.000000E+01 5 1.170052E-04 -8.998814E+01 2.420465E-08 -1.170052E-04 - 2.730007E+01 9.000000E+01 6 6.216318E-06 1.799992E+02 -6.216318E-06 8.843600E-11 - 2.740007E+01 0.000000E+00 1 4.848690E+01 8.992109E+01 6.677949E-02 4.848685E+01 - 2.740007E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.740007E+01 0.000000E+00 3 1.821252E+02 3.366948E-01 1.821221E+02 1.070241E+00 - 2.740007E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.740007E+01 0.000000E+00 5 4.920308E+02 8.992110E+01 6.776208E-01 4.920303E+02 - 2.740007E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.740007E+01 3.000000E+01 1 4.216036E+01 8.992110E+01 5.806039E-02 4.216032E+01 - 2.740007E+01 3.000000E+01 2 2.572382E+01 8.990852E+01 4.107559E-02 2.572379E+01 - 2.740007E+01 3.000000E+01 3 1.829552E+02 3.373922E-01 1.829521E+02 1.077345E+00 - 2.740007E+01 3.000000E+01 4 8.421449E+01 8.990781E+01 1.355001E-01 8.421438E+01 - 2.740007E+01 3.000000E+01 5 4.278035E+02 8.992110E+01 5.891410E-01 4.278031E+02 - 2.740007E+01 3.000000E+01 6 7.108159E+01 -1.194137E-03 7.108159E+01 -1.481456E-03 - 2.740007E+01 6.000000E+01 1 2.453847E+01 8.992111E+01 3.378597E-02 2.453845E+01 - 2.740007E+01 6.000000E+01 2 4.495183E+01 8.990850E+01 7.178903E-02 4.495177E+01 - 2.740007E+01 6.000000E+01 3 1.846259E+02 3.387916E-01 1.846227E+02 1.091692E+00 - 2.740007E+01 6.000000E+01 4 1.482844E+02 8.990850E+01 2.368169E-01 1.482843E+02 - 2.740007E+01 6.000000E+01 5 2.489519E+02 8.992110E+01 3.428245E-01 2.489516E+02 - 2.740007E+01 6.000000E+01 6 7.173272E+01 -1.190445E-03 7.173272E+01 -1.490404E-03 - 2.740007E+01 9.000000E+01 1 2.549738E-06 -9.005333E+01 -2.373185E-09 -2.549737E-06 - 2.740007E+01 9.000000E+01 2 5.213666E+01 8.990849E+01 8.326934E-02 5.213660E+01 - 2.740007E+01 9.000000E+01 3 1.854675E+02 3.394896E-01 1.854642E+02 1.098928E+00 - 2.740007E+01 9.000000E+01 4 1.726298E+02 8.990884E+01 2.746894E-01 1.726296E+02 - 2.740007E+01 9.000000E+01 5 1.165900E-04 -8.998827E+01 2.385390E-08 -1.165900E-04 - 2.740007E+01 9.000000E+01 6 6.167719E-06 1.799992E+02 -6.167719E-06 8.628445E-11 - 2.750007E+01 0.000000E+00 1 4.831063E+01 8.992171E+01 6.600901E-02 4.831059E+01 - 2.750007E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.750007E+01 0.000000E+00 3 1.823094E+02 3.341334E-01 1.823063E+02 1.063173E+00 - 2.750007E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.750007E+01 0.000000E+00 5 4.906328E+02 8.992171E+01 6.703410E-01 4.906323E+02 - 2.750007E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.750007E+01 3.000000E+01 1 4.200584E+01 8.992172E+01 5.738883E-02 4.200580E+01 - 2.750007E+01 3.000000E+01 2 2.562960E+01 8.990930E+01 4.057218E-02 2.562957E+01 - 2.750007E+01 3.000000E+01 3 1.831329E+02 3.348190E-01 1.831297E+02 1.070166E+00 - 2.750007E+01 3.000000E+01 4 8.388406E+01 8.990862E+01 1.337978E-01 8.388396E+01 - 2.750007E+01 3.000000E+01 5 4.265785E+02 8.992172E+01 5.827969E-01 4.265781E+02 - 2.750007E+01 3.000000E+01 6 7.053657E+01 -1.174226E-03 7.053657E+01 -1.445584E-03 - 2.750007E+01 6.000000E+01 1 2.444687E+01 8.992174E+01 3.339313E-02 2.444685E+01 - 2.750007E+01 6.000000E+01 2 4.478394E+01 8.990929E+01 7.090422E-02 4.478388E+01 - 2.750007E+01 6.000000E+01 3 1.847924E+02 3.361934E-01 1.847893E+02 1.084297E+00 - 2.750007E+01 6.000000E+01 4 1.476844E+02 8.990929E+01 2.338234E-01 1.476842E+02 - 2.750007E+01 6.000000E+01 5 2.482252E+02 8.992173E+01 3.391076E-01 2.482250E+02 - 2.750007E+01 6.000000E+01 6 7.117751E+01 -1.170623E-03 7.117751E+01 -1.454244E-03 - 2.750007E+01 9.000000E+01 1 2.540039E-06 -9.005302E+01 -2.350846E-09 -2.540038E-06 - 2.750007E+01 9.000000E+01 2 5.194011E+01 8.990928E+01 8.223996E-02 5.194005E+01 - 2.750007E+01 9.000000E+01 3 1.856278E+02 3.368838E-01 1.856246E+02 1.091435E+00 - 2.750007E+01 9.000000E+01 4 1.719206E+02 8.990961E+01 2.712083E-01 1.719204E+02 - 2.750007E+01 9.000000E+01 5 1.161768E-04 -8.998840E+01 2.350978E-08 -1.161768E-04 - 2.750007E+01 9.000000E+01 6 6.119692E-06 1.799992E+02 -6.119692E-06 8.419448E-11 - 2.760007E+01 0.000000E+00 1 4.813564E+01 8.992233E+01 6.525052E-02 4.813560E+01 - 2.760007E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.760007E+01 0.000000E+00 3 1.824921E+02 3.315973E-01 1.824891E+02 1.056161E+00 - 2.760007E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.760007E+01 0.000000E+00 5 4.892461E+02 8.992234E+01 6.631604E-01 4.892456E+02 - 2.760007E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.760007E+01 3.000000E+01 1 4.185225E+01 8.992235E+01 5.672759E-02 4.185221E+01 - 2.760007E+01 3.000000E+01 2 2.553599E+01 8.991008E+01 4.007721E-02 2.553596E+01 - 2.760007E+01 3.000000E+01 3 1.833097E+02 3.322738E-01 1.833067E+02 1.063057E+00 - 2.760007E+01 3.000000E+01 4 8.355618E+01 8.990940E+01 1.321238E-01 8.355607E+01 - 2.760007E+01 3.000000E+01 5 4.253565E+02 8.992234E+01 5.765409E-01 4.253561E+02 - 2.760007E+01 3.000000E+01 6 6.999789E+01 -1.154733E-03 6.999789E+01 -1.410730E-03 - 2.760007E+01 6.000000E+01 1 2.435611E+01 8.992236E+01 3.300640E-02 2.435608E+01 - 2.760007E+01 6.000000E+01 2 4.461734E+01 8.991006E+01 7.003406E-02 4.461728E+01 - 2.760007E+01 6.000000E+01 3 1.849570E+02 3.336269E-01 1.849538E+02 1.076977E+00 - 2.760007E+01 6.000000E+01 4 1.470889E+02 8.991006E+01 2.308832E-01 1.470887E+02 - 2.760007E+01 6.000000E+01 5 2.474967E+02 8.992235E+01 3.354477E-01 2.474964E+02 - 2.760007E+01 6.000000E+01 6 7.062881E+01 -1.151217E-03 7.062881E+01 -1.419111E-03 - 2.760007E+01 9.000000E+01 1 2.530414E-06 -9.005273E+01 -2.328743E-09 -2.530413E-06 - 2.760007E+01 9.000000E+01 2 5.174487E+01 8.991006E+01 8.122753E-02 5.174480E+01 - 2.760007E+01 9.000000E+01 3 1.857875E+02 3.343015E-01 1.857844E+02 1.084001E+00 - 2.760007E+01 9.000000E+01 4 1.712166E+02 8.991039E+01 2.677870E-01 1.712164E+02 - 2.760007E+01 9.000000E+01 5 1.157683E-04 -8.998853E+01 2.317238E-08 -1.157683E-04 - 2.760007E+01 9.000000E+01 6 6.072243E-06 1.799992E+02 -6.072243E-06 8.216394E-11 - 2.770007E+01 0.000000E+00 1 4.796184E+01 8.992294E+01 6.450374E-02 4.796180E+01 - 2.770007E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.770007E+01 0.000000E+00 3 1.826720E+02 3.290921E-01 1.826689E+02 1.049214E+00 - 2.770007E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.770007E+01 0.000000E+00 5 4.878579E+02 8.992294E+01 6.560824E-01 4.878575E+02 - 2.770007E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.770007E+01 3.000000E+01 1 4.170002E+01 8.992295E+01 5.607668E-02 4.169999E+01 - 2.770007E+01 3.000000E+01 2 2.544310E+01 8.991085E+01 3.959041E-02 2.544307E+01 - 2.770007E+01 3.000000E+01 3 1.834834E+02 3.297578E-01 1.834803E+02 1.056007E+00 - 2.770007E+01 3.000000E+01 4 8.323134E+01 8.991018E+01 1.304788E-01 8.323124E+01 - 2.770007E+01 3.000000E+01 5 4.241356E+02 8.992295E+01 5.703716E-01 4.241352E+02 - 2.770007E+01 3.000000E+01 6 6.946550E+01 -1.135652E-03 6.946550E+01 -1.376866E-03 - 2.770007E+01 6.000000E+01 1 2.426589E+01 8.992297E+01 3.262576E-02 2.426587E+01 - 2.770007E+01 6.000000E+01 2 4.445199E+01 8.991084E+01 6.917854E-02 4.445193E+01 - 2.770007E+01 6.000000E+01 3 1.851198E+02 3.310885E-01 1.851167E+02 1.069724E+00 - 2.770007E+01 6.000000E+01 4 1.464987E+02 8.991084E+01 2.279924E-01 1.464985E+02 - 2.770007E+01 6.000000E+01 5 2.467748E+02 8.992295E+01 3.318392E-01 2.467746E+02 - 2.770007E+01 6.000000E+01 6 7.008666E+01 -1.132223E-03 7.008666E+01 -1.384983E-03 - 2.770007E+01 9.000000E+01 1 2.520866E-06 -9.005243E+01 -2.306889E-09 -2.520865E-06 - 2.770007E+01 9.000000E+01 2 5.155136E+01 8.991083E+01 8.023254E-02 5.155130E+01 - 2.770007E+01 9.000000E+01 3 1.859445E+02 3.317517E-01 1.859414E+02 1.076642E+00 - 2.770007E+01 9.000000E+01 4 1.705203E+02 8.991116E+01 2.644240E-01 1.705201E+02 - 2.770007E+01 9.000000E+01 5 1.153612E-04 -8.998866E+01 2.284139E-08 -1.153612E-04 - 2.770007E+01 9.000000E+01 6 6.025352E-06 1.799992E+02 -6.025352E-06 8.019128E-11 - 2.780007E+01 0.000000E+00 1 4.778943E+01 8.992355E+01 6.376842E-02 4.778939E+01 - 2.780007E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.780007E+01 0.000000E+00 3 1.828498E+02 3.266193E-01 1.828468E+02 1.042345E+00 - 2.780007E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.780007E+01 0.000000E+00 5 4.864798E+02 8.992355E+01 6.491061E-01 4.864794E+02 - 2.780007E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.780007E+01 3.000000E+01 1 4.154868E+01 8.992355E+01 5.543589E-02 4.154864E+01 - 2.780007E+01 3.000000E+01 2 2.535089E+01 8.991161E+01 3.911167E-02 2.535086E+01 - 2.780007E+01 3.000000E+01 3 1.836570E+02 3.272706E-01 1.836540E+02 1.049034E+00 - 2.780007E+01 3.000000E+01 4 8.290870E+01 8.991094E+01 1.288622E-01 8.290860E+01 - 2.780007E+01 3.000000E+01 5 4.229265E+02 8.992355E+01 5.642854E-01 4.229261E+02 - 2.780007E+01 3.000000E+01 6 6.893920E+01 -1.116972E-03 6.893920E+01 -1.343959E-03 - 2.780007E+01 6.000000E+01 1 2.417634E+01 8.992357E+01 3.225103E-02 2.417632E+01 - 2.780007E+01 6.000000E+01 2 4.428777E+01 8.991159E+01 6.833703E-02 4.428772E+01 - 2.780007E+01 6.000000E+01 3 1.852806E+02 3.285831E-01 1.852776E+02 1.062552E+00 - 2.780007E+01 6.000000E+01 4 1.459133E+02 8.991159E+01 2.251514E-01 1.459132E+02 - 2.780007E+01 6.000000E+01 5 2.460548E+02 8.992356E+01 3.282776E-01 2.460546E+02 - 2.780007E+01 6.000000E+01 6 6.955079E+01 -1.113628E-03 6.955079E+01 -1.351822E-03 - 2.780007E+01 9.000000E+01 1 2.511394E-06 -9.005214E+01 -2.285283E-09 -2.511393E-06 - 2.780007E+01 9.000000E+01 2 5.135925E+01 8.991158E+01 7.925393E-02 5.135918E+01 - 2.780007E+01 9.000000E+01 3 1.860998E+02 3.292342E-01 1.860967E+02 1.069365E+00 - 2.780007E+01 9.000000E+01 4 1.698282E+02 8.991191E+01 2.611189E-01 1.698280E+02 - 2.780007E+01 9.000000E+01 5 1.149569E-04 -8.998878E+01 2.251673E-08 -1.149569E-04 - 2.780007E+01 9.000000E+01 6 5.979010E-06 1.799993E+02 -5.979010E-06 7.827420E-11 - 2.790007E+01 0.000000E+00 1 4.761823E+01 8.992414E+01 6.304449E-02 4.761819E+01 - 2.790007E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.790007E+01 0.000000E+00 3 1.830271E+02 3.241700E-01 1.830242E+02 1.035532E+00 - 2.790007E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.790007E+01 0.000000E+00 5 4.851045E+02 8.992415E+01 6.422254E-01 4.851041E+02 - 2.790007E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.790007E+01 3.000000E+01 1 4.139865E+01 8.992416E+01 5.480478E-02 4.139861E+01 - 2.790007E+01 3.000000E+01 2 2.525932E+01 8.991235E+01 3.864074E-02 2.525929E+01 - 2.790007E+01 3.000000E+01 3 1.838277E+02 3.248135E-01 1.838247E+02 1.042126E+00 - 2.790007E+01 3.000000E+01 4 8.258921E+01 8.991171E+01 1.272726E-01 8.258911E+01 - 2.790007E+01 3.000000E+01 5 4.217174E+02 8.992415E+01 5.582868E-01 4.217170E+02 - 2.790007E+01 3.000000E+01 6 6.841891E+01 -1.098685E-03 6.841891E+01 -1.311978E-03 - 2.790007E+01 6.000000E+01 1 2.408754E+01 8.992417E+01 3.188213E-02 2.408752E+01 - 2.790007E+01 6.000000E+01 2 4.412487E+01 8.991234E+01 6.750953E-02 4.412482E+01 - 2.790007E+01 6.000000E+01 3 1.854400E+02 3.261012E-01 1.854370E+02 1.055433E+00 - 2.790007E+01 6.000000E+01 4 1.453328E+02 8.991234E+01 2.223575E-01 1.453327E+02 - 2.790007E+01 6.000000E+01 5 2.453364E+02 8.992416E+01 3.247714E-01 2.453362E+02 - 2.790007E+01 6.000000E+01 6 6.902113E+01 -1.095419E-03 6.902113E+01 -1.319592E-03 - 2.790007E+01 9.000000E+01 1 2.501991E-06 -9.005184E+01 -2.263919E-09 -2.501990E-06 - 2.790007E+01 9.000000E+01 2 5.116870E+01 8.991233E+01 7.829168E-02 5.116864E+01 - 2.790007E+01 9.000000E+01 3 1.862526E+02 3.267466E-01 1.862496E+02 1.062156E+00 - 2.790007E+01 9.000000E+01 4 1.691419E+02 8.991265E+01 2.578705E-01 1.691417E+02 - 2.790007E+01 9.000000E+01 5 1.145557E-04 -8.998890E+01 2.219828E-08 -1.145557E-04 - 2.790007E+01 9.000000E+01 6 5.933215E-06 1.799993E+02 -5.933215E-06 7.641110E-11 - 2.800007E+01 0.000000E+00 1 4.744809E+01 8.992474E+01 6.233130E-02 4.744805E+01 - 2.800007E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.800007E+01 0.000000E+00 3 1.832010E+02 3.217495E-01 1.831982E+02 1.028776E+00 - 2.800007E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.800007E+01 0.000000E+00 5 4.837372E+02 8.992474E+01 6.354414E-01 4.837368E+02 - 2.800007E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.800007E+01 3.000000E+01 1 4.124949E+01 8.992474E+01 5.418339E-02 4.124946E+01 - 2.800007E+01 3.000000E+01 2 2.516845E+01 8.991309E+01 3.817756E-02 2.516842E+01 - 2.800007E+01 3.000000E+01 3 1.839966E+02 3.223823E-01 1.839937E+02 1.035276E+00 - 2.800007E+01 3.000000E+01 4 8.227146E+01 8.991245E+01 1.257093E-01 8.227136E+01 - 2.800007E+01 3.000000E+01 5 4.205184E+02 8.992474E+01 5.523752E-01 4.205181E+02 - 2.800007E+01 3.000000E+01 6 6.790480E+01 -1.080773E-03 6.790480E+01 -1.280892E-03 - 2.800007E+01 6.000000E+01 1 2.399938E+01 8.992476E+01 3.151871E-02 2.399936E+01 - 2.800007E+01 6.000000E+01 2 4.396320E+01 8.991308E+01 6.669591E-02 4.396315E+01 - 2.800007E+01 6.000000E+01 3 1.855984E+02 3.236502E-01 1.855955E+02 1.048396E+00 - 2.800007E+01 6.000000E+01 4 1.447571E+02 8.991308E+01 2.196120E-01 1.447570E+02 - 2.800007E+01 6.000000E+01 5 2.446227E+02 8.992474E+01 3.213120E-01 2.446225E+02 - 2.800007E+01 6.000000E+01 6 6.849780E+01 -1.077585E-03 6.849780E+01 -1.288266E-03 - 2.800007E+01 9.000000E+01 1 2.492656E-06 -9.005155E+01 -2.242774E-09 -2.492656E-06 - 2.800007E+01 9.000000E+01 2 5.097934E+01 8.991308E+01 7.734487E-02 5.097928E+01 - 2.800007E+01 9.000000E+01 3 1.864052E+02 3.242849E-01 1.864023E+02 1.055018E+00 - 2.800007E+01 9.000000E+01 4 1.684627E+02 8.991338E+01 2.546772E-01 1.684625E+02 - 2.800007E+01 9.000000E+01 5 1.141573E-04 -8.998901E+01 2.188575E-08 -1.141573E-04 - 2.800007E+01 9.000000E+01 6 5.887949E-06 1.799993E+02 -5.887949E-06 7.460020E-11 - 2.810007E+01 0.000000E+00 1 4.727943E+01 8.992532E+01 6.162915E-02 4.727939E+01 - 2.810007E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.810007E+01 0.000000E+00 3 1.833738E+02 3.193567E-01 1.833709E+02 1.022088E+00 - 2.810007E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.810007E+01 0.000000E+00 5 4.823730E+02 8.992532E+01 6.287509E-01 4.823727E+02 - 2.810007E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.810007E+01 3.000000E+01 1 4.110149E+01 8.992532E+01 5.357149E-02 4.110145E+01 - 2.810007E+01 3.000000E+01 2 2.507817E+01 8.991382E+01 3.772182E-02 2.507814E+01 - 2.810007E+01 3.000000E+01 3 1.841638E+02 3.199789E-01 1.841610E+02 1.028492E+00 - 2.810007E+01 3.000000E+01 4 8.195668E+01 8.991319E+01 1.241722E-01 8.195659E+01 - 2.810007E+01 3.000000E+01 5 4.193215E+02 8.992532E+01 5.465394E-01 4.193211E+02 - 2.810007E+01 3.000000E+01 6 6.739633E+01 -1.063236E-03 6.739633E+01 -1.250672E-03 - 2.810007E+01 6.000000E+01 1 2.391177E+01 8.992534E+01 3.116108E-02 2.391175E+01 - 2.810007E+01 6.000000E+01 2 4.380273E+01 8.991380E+01 6.589521E-02 4.380268E+01 - 2.810007E+01 6.000000E+01 3 1.857555E+02 3.212252E-01 1.857526E+02 1.041421E+00 - 2.810007E+01 6.000000E+01 4 1.441860E+02 8.991380E+01 2.169119E-01 1.441858E+02 - 2.810007E+01 6.000000E+01 5 2.439112E+02 8.992532E+01 3.179022E-01 2.439110E+02 - 2.810007E+01 6.000000E+01 6 6.798024E+01 -1.060128E-03 6.798024E+01 -1.257820E-03 - 2.810007E+01 9.000000E+01 1 2.483399E-06 -9.005126E+01 -2.221880E-09 -2.483398E-06 - 2.810007E+01 9.000000E+01 2 5.079157E+01 8.991380E+01 7.641418E-02 5.079152E+01 - 2.810007E+01 9.000000E+01 3 1.865555E+02 3.218505E-01 1.865526E+02 1.047943E+00 - 2.810007E+01 9.000000E+01 4 1.677881E+02 8.991411E+01 2.515384E-01 1.677879E+02 - 2.810007E+01 9.000000E+01 5 1.137617E-04 -8.998913E+01 2.157909E-08 -1.137617E-04 - 2.810007E+01 9.000000E+01 6 5.843222E-06 1.799993E+02 -5.843222E-06 7.283976E-11 - 2.820007E+01 0.000000E+00 1 4.711179E+01 8.992589E+01 6.093765E-02 4.711176E+01 - 2.820007E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.820007E+01 0.000000E+00 3 1.835450E+02 3.169907E-01 1.835422E+02 1.015463E+00 - 2.820007E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.820007E+01 0.000000E+00 5 4.810190E+02 8.992590E+01 6.221502E-01 4.810186E+02 - 2.820007E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.820007E+01 3.000000E+01 1 4.095451E+01 8.992590E+01 5.296883E-02 4.095447E+01 - 2.820007E+01 3.000000E+01 2 2.498859E+01 8.991454E+01 3.727363E-02 2.498856E+01 - 2.820007E+01 3.000000E+01 3 1.843295E+02 3.176023E-01 1.843267E+02 1.021771E+00 - 2.820007E+01 3.000000E+01 4 8.164420E+01 8.991393E+01 1.226603E-01 8.164410E+01 - 2.820007E+01 3.000000E+01 5 4.181278E+02 8.992590E+01 5.407942E-01 4.181275E+02 - 2.820007E+01 3.000000E+01 6 6.689375E+01 -1.046059E-03 6.689375E+01 -1.221291E-03 - 2.820007E+01 6.000000E+01 1 2.382490E+01 8.992591E+01 3.080876E-02 2.382488E+01 - 2.820007E+01 6.000000E+01 2 4.364328E+01 8.991452E+01 6.510767E-02 4.364323E+01 - 2.820007E+01 6.000000E+01 3 1.859091E+02 3.188306E-01 1.859062E+02 1.034512E+00 - 2.820007E+01 6.000000E+01 4 1.436199E+02 8.991452E+01 2.142572E-01 1.436198E+02 - 2.820007E+01 6.000000E+01 5 2.432052E+02 8.992590E+01 3.145411E-01 2.432050E+02 - 2.820007E+01 6.000000E+01 6 6.746886E+01 -1.043021E-03 6.746886E+01 -1.228213E-03 - 2.820007E+01 9.000000E+01 1 2.474212E-06 -9.005098E+01 -2.201207E-09 -2.474211E-06 - 2.820007E+01 9.000000E+01 2 5.060510E+01 8.991452E+01 7.549848E-02 5.060505E+01 - 2.820007E+01 9.000000E+01 3 1.867050E+02 3.194449E-01 1.867021E+02 1.040943E+00 - 2.820007E+01 9.000000E+01 4 1.671197E+02 8.991483E+01 2.484505E-01 1.671196E+02 - 2.820007E+01 9.000000E+01 5 1.133686E-04 -8.998924E+01 2.127823E-08 -1.133686E-04 - 2.820007E+01 9.000000E+01 6 5.799000E-06 1.799993E+02 -5.799000E-06 7.112817E-11 - 2.830007E+01 0.000000E+00 1 4.694517E+01 8.992645E+01 6.025654E-02 4.694513E+01 - 2.830007E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.830007E+01 0.000000E+00 3 1.837143E+02 3.146522E-01 1.837115E+02 1.008901E+00 - 2.830007E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.830007E+01 0.000000E+00 5 4.796661E+02 8.992646E+01 6.156455E-01 4.796657E+02 - 2.830007E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.830007E+01 3.000000E+01 1 4.080869E+01 8.992646E+01 5.237546E-02 4.080865E+01 - 2.830007E+01 3.000000E+01 2 2.489963E+01 8.991525E+01 3.683248E-02 2.489960E+01 - 2.830007E+01 3.000000E+01 3 1.844937E+02 3.152546E-01 1.844909E+02 1.015122E+00 - 2.830007E+01 3.000000E+01 4 8.133396E+01 8.991464E+01 1.211739E-01 8.133387E+01 - 2.830007E+01 3.000000E+01 5 4.169438E+02 8.992646E+01 5.351219E-01 4.169435E+02 - 2.830007E+01 3.000000E+01 6 6.639690E+01 -1.029236E-03 6.639690E+01 -1.192724E-03 - 2.830007E+01 6.000000E+01 1 2.373865E+01 8.992648E+01 3.046190E-02 2.373863E+01 - 2.830007E+01 6.000000E+01 2 4.348512E+01 8.991524E+01 6.433313E-02 4.348507E+01 - 2.830007E+01 6.000000E+01 3 1.860634E+02 3.164616E-01 1.860605E+02 1.027678E+00 - 2.830007E+01 6.000000E+01 4 1.430579E+02 8.991524E+01 2.116471E-01 1.430577E+02 - 2.830007E+01 6.000000E+01 5 2.425011E+02 8.992647E+01 3.112257E-01 2.425009E+02 - 2.830007E+01 6.000000E+01 6 6.696328E+01 -1.026270E-03 6.696328E+01 -1.199433E-03 - 2.830007E+01 9.000000E+01 1 2.465086E-06 -9.005069E+01 -2.180761E-09 -2.465085E-06 - 2.830007E+01 9.000000E+01 2 5.042012E+01 8.991524E+01 7.459762E-02 5.042007E+01 - 2.830007E+01 9.000000E+01 3 1.868528E+02 3.170685E-01 1.868499E+02 1.034017E+00 - 2.830007E+01 9.000000E+01 4 1.664560E+02 8.991553E+01 2.454160E-01 1.664558E+02 - 2.830007E+01 9.000000E+01 5 1.129783E-04 -8.998936E+01 2.098303E-08 -1.129783E-04 - 2.830007E+01 9.000000E+01 6 5.755298E-06 1.799993E+02 -5.755298E-06 6.946392E-11 - 2.840007E+01 0.000000E+00 1 4.677987E+01 8.992702E+01 5.958563E-02 4.677983E+01 - 2.840007E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.840007E+01 0.000000E+00 3 1.838813E+02 3.123398E-01 1.838786E+02 1.002398E+00 - 2.840007E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.840007E+01 0.000000E+00 5 4.783223E+02 8.992702E+01 6.092303E-01 4.783219E+02 - 2.840007E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.840007E+01 3.000000E+01 1 4.066379E+01 8.992703E+01 5.179086E-02 4.066375E+01 - 2.840007E+01 3.000000E+01 2 2.481134E+01 8.991595E+01 3.639850E-02 2.481132E+01 - 2.840007E+01 3.000000E+01 3 1.846556E+02 3.129305E-01 1.846528E+02 1.008522E+00 - 2.840007E+01 3.000000E+01 4 8.102666E+01 8.991535E+01 1.197123E-01 8.102657E+01 - 2.840007E+01 3.000000E+01 5 4.157625E+02 8.992703E+01 5.295332E-01 4.157622E+02 - 2.840007E+01 3.000000E+01 6 6.590559E+01 -1.012755E-03 6.590559E+01 -1.164941E-03 - 2.840007E+01 6.000000E+01 1 2.365303E+01 8.992704E+01 3.012023E-02 2.365301E+01 - 2.840007E+01 6.000000E+01 2 4.332825E+01 8.991594E+01 6.357099E-02 4.332820E+01 - 2.840007E+01 6.000000E+01 3 1.862146E+02 3.141187E-01 1.862118E+02 1.020899E+00 - 2.840007E+01 6.000000E+01 4 1.425012E+02 8.991594E+01 2.090798E-01 1.425010E+02 - 2.840007E+01 6.000000E+01 5 2.418004E+02 8.992703E+01 3.079569E-01 2.418002E+02 - 2.840007E+01 6.000000E+01 6 6.646344E+01 -1.009861E-03 6.646344E+01 -1.171445E-03 - 2.840007E+01 9.000000E+01 1 2.456037E-06 -9.005040E+01 -2.160548E-09 -2.456036E-06 - 2.840007E+01 9.000000E+01 2 5.023649E+01 8.991593E+01 7.371149E-02 5.023643E+01 - 2.840007E+01 9.000000E+01 3 1.869987E+02 3.147150E-01 1.869958E+02 1.027143E+00 - 2.840007E+01 9.000000E+01 4 1.657985E+02 8.991622E+01 2.424307E-01 1.657984E+02 - 2.840007E+01 9.000000E+01 5 1.125906E-04 -8.998947E+01 2.069316E-08 -1.125906E-04 - 2.840007E+01 9.000000E+01 6 5.712103E-06 1.799993E+02 -5.712103E-06 6.784557E-11 - 2.850007E+01 0.000000E+00 1 4.661565E+01 8.992757E+01 5.892463E-02 4.661562E+01 - 2.850007E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.850007E+01 0.000000E+00 3 1.840484E+02 3.100492E-01 1.840457E+02 9.959512E-01 - 2.850007E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.850007E+01 0.000000E+00 5 4.769853E+02 8.992758E+01 6.029006E-01 4.769849E+02 - 2.850007E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.850007E+01 3.000000E+01 1 4.051995E+01 8.992758E+01 5.121486E-02 4.051992E+01 - 2.850007E+01 3.000000E+01 2 2.472359E+01 8.991664E+01 3.597154E-02 2.472357E+01 - 2.850007E+01 3.000000E+01 3 1.848165E+02 3.106342E-01 1.848137E+02 1.001994E+00 - 2.850007E+01 3.000000E+01 4 8.072145E+01 8.991605E+01 1.182747E-01 8.072137E+01 - 2.850007E+01 3.000000E+01 5 4.145861E+02 8.992758E+01 5.240204E-01 4.145857E+02 - 2.850007E+01 3.000000E+01 6 6.541982E+01 -9.966095E-04 6.541982E+01 -1.137920E-03 - 2.850007E+01 6.000000E+01 1 2.356802E+01 8.992760E+01 2.978378E-02 2.356800E+01 - 2.850007E+01 6.000000E+01 2 4.317225E+01 8.991663E+01 6.282101E-02 4.317220E+01 - 2.850007E+01 6.000000E+01 3 1.863645E+02 3.118035E-01 1.863618E+02 1.014191E+00 - 2.850007E+01 6.000000E+01 4 1.419480E+02 8.991663E+01 2.065548E-01 1.419479E+02 - 2.850007E+01 6.000000E+01 5 2.411035E+02 8.992758E+01 3.047306E-01 2.411033E+02 - 2.850007E+01 6.000000E+01 6 6.596940E+01 -9.937821E-04 6.596940E+01 -1.144224E-03 - 2.850007E+01 9.000000E+01 1 2.447048E-06 -9.005013E+01 -2.140565E-09 -2.447047E-06 - 2.850007E+01 9.000000E+01 2 5.005430E+01 8.991662E+01 7.283960E-02 5.005425E+01 - 2.850007E+01 9.000000E+01 3 1.871428E+02 3.123914E-01 1.871401E+02 1.020346E+00 - 2.850007E+01 9.000000E+01 4 1.651463E+02 8.991691E+01 2.394964E-01 1.651462E+02 - 2.850007E+01 9.000000E+01 5 1.122053E-04 -8.998958E+01 2.040873E-08 -1.122053E-04 - 2.850007E+01 9.000000E+01 6 5.669390E-06 1.799993E+02 -5.669390E-06 6.627149E-11 - 2.860007E+01 0.000000E+00 1 4.645269E+01 8.992812E+01 5.827371E-02 4.645265E+01 - 2.860007E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.860007E+01 0.000000E+00 3 1.842122E+02 3.077878E-01 1.842095E+02 9.895664E-01 - 2.860007E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.860007E+01 0.000000E+00 5 4.756524E+02 8.992813E+01 5.966589E-01 4.756520E+02 - 2.860007E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.860007E+01 3.000000E+01 1 4.037712E+01 8.992813E+01 5.064785E-02 4.037709E+01 - 2.860007E+01 3.000000E+01 2 2.463656E+01 8.991733E+01 3.555132E-02 2.463653E+01 - 2.860007E+01 3.000000E+01 3 1.849752E+02 3.083637E-01 1.849725E+02 9.955246E-01 - 2.860007E+01 3.000000E+01 4 8.041879E+01 8.991674E+01 1.168599E-01 8.041870E+01 - 2.860007E+01 3.000000E+01 5 4.134140E+02 8.992813E+01 5.185757E-01 4.134136E+02 - 2.860007E+01 3.000000E+01 6 6.493947E+01 -9.807913E-04 6.493947E+01 -1.111636E-03 - 2.860007E+01 6.000000E+01 1 2.348356E+01 8.992815E+01 2.945225E-02 2.348354E+01 - 2.860007E+01 6.000000E+01 2 4.301755E+01 8.991731E+01 6.208301E-02 4.301750E+01 - 2.860007E+01 6.000000E+01 3 1.865120E+02 3.095161E-01 1.865093E+02 1.007547E+00 - 2.860007E+01 6.000000E+01 4 1.413996E+02 8.991731E+01 2.040714E-01 1.413995E+02 - 2.860007E+01 6.000000E+01 5 2.404083E+02 8.992814E+01 3.015527E-01 2.404081E+02 - 2.860007E+01 6.000000E+01 6 6.548082E+01 -9.780284E-04 6.548082E+01 -1.117745E-03 - 2.860007E+01 9.000000E+01 1 2.438129E-06 -9.004984E+01 -2.120792E-09 -2.438128E-06 - 2.860007E+01 9.000000E+01 2 4.987325E+01 8.991730E+01 7.198154E-02 4.987319E+01 - 2.860007E+01 9.000000E+01 3 1.872858E+02 3.100912E-01 1.872831E+02 1.013607E+00 - 2.860007E+01 9.000000E+01 4 1.644998E+02 8.991759E+01 2.366087E-01 1.644997E+02 - 2.860007E+01 9.000000E+01 5 1.118234E-04 -8.998969E+01 2.012946E-08 -1.118234E-04 - 2.860007E+01 9.000000E+01 6 5.627169E-06 1.799993E+02 -5.627169E-06 6.474039E-11 - 2.870007E+01 0.000000E+00 1 4.629090E+01 8.992867E+01 5.763241E-02 4.629087E+01 - 2.870007E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.870007E+01 0.000000E+00 3 1.843742E+02 3.055500E-01 1.843716E+02 9.832358E-01 - 2.870007E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.870007E+01 0.000000E+00 5 4.743232E+02 8.992867E+01 5.905062E-01 4.743228E+02 - 2.870007E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.870007E+01 3.000000E+01 1 4.023531E+01 8.992867E+01 5.008899E-02 4.023528E+01 - 2.870007E+01 3.000000E+01 2 2.455005E+01 8.991799E+01 3.513776E-02 2.455002E+01 - 2.870007E+01 3.000000E+01 3 1.851326E+02 3.061164E-01 1.851300E+02 9.891106E-01 - 2.870007E+01 3.000000E+01 4 8.011801E+01 8.991743E+01 1.154684E-01 8.011793E+01 - 2.870007E+01 3.000000E+01 5 4.122494E+02 8.992867E+01 5.132151E-01 4.122491E+02 - 2.870007E+01 3.000000E+01 6 6.446452E+01 -9.652921E-04 6.446452E+01 -1.086068E-03 - 2.870007E+01 6.000000E+01 1 2.339984E+01 8.992868E+01 2.912585E-02 2.339982E+01 - 2.870007E+01 6.000000E+01 2 4.286395E+01 8.991798E+01 6.135697E-02 4.286390E+01 - 2.870007E+01 6.000000E+01 3 1.866599E+02 3.072492E-01 1.866572E+02 1.000961E+00 - 2.870007E+01 6.000000E+01 4 1.408558E+02 8.991798E+01 2.016285E-01 1.408556E+02 - 2.870007E+01 6.000000E+01 5 2.397190E+02 8.992867E+01 2.984205E-01 2.397188E+02 - 2.870007E+01 6.000000E+01 6 6.499773E+01 -9.625954E-04 6.499773E+01 -1.091992E-03 - 2.870007E+01 9.000000E+01 1 2.429276E-06 -9.004955E+01 -2.101240E-09 -2.429275E-06 - 2.870007E+01 9.000000E+01 2 4.969361E+01 8.991798E+01 7.113768E-02 4.969356E+01 - 2.870007E+01 9.000000E+01 3 1.874273E+02 3.078184E-01 1.874246E+02 1.006938E+00 - 2.870007E+01 9.000000E+01 4 1.638578E+02 8.991826E+01 2.337690E-01 1.638577E+02 - 2.870007E+01 9.000000E+01 5 1.114432E-04 -8.998979E+01 1.985536E-08 -1.114432E-04 - 2.870007E+01 9.000000E+01 6 5.585436E-06 1.799993E+02 -5.585436E-06 6.325095E-11 - 2.880007E+01 0.000000E+00 1 4.613022E+01 8.992920E+01 5.700032E-02 4.613018E+01 - 2.880007E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.880007E+01 0.000000E+00 3 1.845348E+02 3.033354E-01 1.845323E+02 9.769601E-01 - 2.880007E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.880007E+01 0.000000E+00 5 4.730033E+02 8.992921E+01 5.844322E-01 4.730029E+02 - 2.880007E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.880007E+01 3.000000E+01 1 4.009457E+01 8.992921E+01 4.953853E-02 4.009454E+01 - 2.880007E+01 3.000000E+01 2 2.446420E+01 8.991866E+01 3.473059E-02 2.446418E+01 - 2.880007E+01 3.000000E+01 3 1.852882E+02 3.038919E-01 1.852856E+02 9.827483E-01 - 2.880007E+01 3.000000E+01 4 7.981991E+01 8.991810E+01 1.140992E-01 7.981982E+01 - 2.880007E+01 3.000000E+01 5 4.110927E+02 8.992921E+01 5.079241E-01 4.110923E+02 - 2.880007E+01 3.000000E+01 6 6.399482E+01 -9.501004E-04 6.399482E+01 -1.061186E-03 - 2.880007E+01 6.000000E+01 1 2.331664E+01 8.992922E+01 2.880419E-02 2.331662E+01 - 2.880007E+01 6.000000E+01 2 4.271136E+01 8.991865E+01 6.064233E-02 4.271132E+01 - 2.880007E+01 6.000000E+01 3 1.868046E+02 3.050091E-01 1.868019E+02 9.944332E-01 - 2.880007E+01 6.000000E+01 4 1.403165E+02 8.991865E+01 1.992254E-01 1.403164E+02 - 2.880007E+01 6.000000E+01 5 2.390303E+02 8.992921E+01 2.953278E-01 2.390302E+02 - 2.880007E+01 6.000000E+01 6 6.452022E+01 -9.474657E-04 6.452022E+01 -1.066932E-03 - 2.880007E+01 9.000000E+01 1 2.420488E-06 -9.004929E+01 -2.081912E-09 -2.420487E-06 - 2.880007E+01 9.000000E+01 2 4.951539E+01 8.991865E+01 7.030696E-02 4.951534E+01 - 2.880007E+01 9.000000E+01 3 1.875682E+02 3.055684E-01 1.875655E+02 1.000329E+00 - 2.880007E+01 9.000000E+01 4 1.632213E+02 8.991892E+01 2.309761E-01 1.632211E+02 - 2.880007E+01 9.000000E+01 5 1.110659E-04 -8.998990E+01 1.958618E-08 -1.110659E-04 - 2.880007E+01 9.000000E+01 6 5.544158E-06 1.799994E+02 -5.544158E-06 6.180179E-11 - 2.890007E+01 0.000000E+00 1 4.597051E+01 8.992973E+01 5.637762E-02 4.597048E+01 - 2.890007E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.890007E+01 0.000000E+00 3 1.846951E+02 3.011470E-01 1.846926E+02 9.707543E-01 - 2.890007E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.890007E+01 0.000000E+00 5 4.716823E+02 8.992973E+01 5.784411E-01 4.716820E+02 - 2.890007E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.890007E+01 3.000000E+01 1 3.995467E+01 8.992974E+01 4.899608E-02 3.995464E+01 - 2.890007E+01 3.000000E+01 2 2.437893E+01 8.991932E+01 3.433002E-02 2.437890E+01 - 2.890007E+01 3.000000E+01 3 1.854426E+02 3.016971E-01 1.854400E+02 9.764636E-01 - 2.890007E+01 3.000000E+01 4 7.952345E+01 8.991876E+01 1.127526E-01 7.952338E+01 - 2.890007E+01 3.000000E+01 5 4.099373E+02 8.992974E+01 5.027046E-01 4.099370E+02 - 2.890007E+01 3.000000E+01 6 6.353027E+01 -9.352144E-04 6.353027E+01 -1.036977E-03 - 2.890007E+01 6.000000E+01 1 2.323405E+01 8.992975E+01 2.848738E-02 2.323404E+01 - 2.890007E+01 6.000000E+01 2 4.255993E+01 8.991931E+01 5.993906E-02 4.255989E+01 - 2.890007E+01 6.000000E+01 3 1.869487E+02 3.027964E-01 1.869461E+02 9.879808E-01 - 2.890007E+01 6.000000E+01 4 1.397805E+02 8.991930E+01 1.968617E-01 1.397803E+02 - 2.890007E+01 6.000000E+01 5 2.383465E+02 8.992974E+01 2.922797E-01 2.383463E+02 - 2.890007E+01 6.000000E+01 6 6.404784E+01 -9.326427E-04 6.404784E+01 -1.042551E-03 - 2.890007E+01 9.000000E+01 1 2.411764E-06 -9.004900E+01 -2.062795E-09 -2.411763E-06 - 2.890007E+01 9.000000E+01 2 4.933831E+01 8.991930E+01 6.948937E-02 4.933826E+01 - 2.890007E+01 9.000000E+01 3 1.877075E+02 3.033449E-01 1.877048E+02 9.937877E-01 - 2.890007E+01 9.000000E+01 4 1.625896E+02 8.991957E+01 2.282291E-01 1.625895E+02 - 2.890007E+01 9.000000E+01 5 1.106909E-04 -8.999000E+01 1.932194E-08 -1.106909E-04 - 2.890007E+01 9.000000E+01 6 5.503363E-06 1.799994E+02 -5.503363E-06 6.039165E-11 - 2.900007E+01 0.000000E+00 1 4.581194E+01 8.993026E+01 5.576444E-02 4.581190E+01 - 2.900007E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.900007E+01 0.000000E+00 3 1.848529E+02 2.989812E-01 1.848504E+02 9.645963E-01 - 2.900007E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.900007E+01 0.000000E+00 5 4.703759E+02 8.993026E+01 5.725312E-01 4.703756E+02 - 2.900007E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.900007E+01 3.000000E+01 1 3.981580E+01 8.993026E+01 4.846161E-02 3.981577E+01 - 2.900007E+01 3.000000E+01 2 2.429428E+01 8.991997E+01 3.393558E-02 2.429426E+01 - 2.900007E+01 3.000000E+01 3 1.855956E+02 2.995215E-01 1.855931E+02 9.702220E-01 - 2.900007E+01 3.000000E+01 4 7.922995E+01 8.991942E+01 1.114271E-01 7.922987E+01 - 2.900007E+01 3.000000E+01 5 4.087864E+02 8.993026E+01 4.975584E-01 4.087861E+02 - 2.900007E+01 3.000000E+01 6 6.307088E+01 -9.206262E-04 6.307088E+01 -1.013420E-03 - 2.900007E+01 6.000000E+01 1 2.315207E+01 8.993027E+01 2.817525E-02 2.315206E+01 - 2.900007E+01 6.000000E+01 2 4.240964E+01 8.991996E+01 5.924690E-02 4.240960E+01 - 2.900007E+01 6.000000E+01 3 1.870907E+02 3.006066E-01 1.870882E+02 9.815809E-01 - 2.900007E+01 6.000000E+01 4 1.392496E+02 8.991995E+01 1.945360E-01 1.392495E+02 - 2.900007E+01 6.000000E+01 5 2.376660E+02 8.993027E+01 2.892712E-01 2.376659E+02 - 2.900007E+01 6.000000E+01 6 6.358087E+01 -9.181129E-04 6.358087E+01 -1.018826E-03 - 2.900007E+01 9.000000E+01 1 2.403105E-06 -9.004873E+01 -2.043889E-09 -2.403104E-06 - 2.900007E+01 9.000000E+01 2 4.916262E+01 8.991995E+01 6.868486E-02 4.916257E+01 - 2.900007E+01 9.000000E+01 3 1.878439E+02 3.011484E-01 1.878413E+02 9.873088E-01 - 2.900007E+01 9.000000E+01 4 1.619632E+02 8.992022E+01 2.255255E-01 1.619631E+02 - 2.900007E+01 9.000000E+01 5 1.103186E-04 -8.999010E+01 1.906248E-08 -1.103186E-04 - 2.900007E+01 9.000000E+01 6 5.463011E-06 1.799994E+02 -5.463011E-06 5.901934E-11 - 2.910007E+01 0.000000E+00 1 4.565451E+01 8.993078E+01 5.515980E-02 4.565447E+01 - 2.910007E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.910007E+01 0.000000E+00 3 1.850083E+02 2.968405E-01 1.850058E+02 9.584949E-01 - 2.910007E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.910007E+01 0.000000E+00 5 4.690703E+02 8.993078E+01 5.667050E-01 4.690700E+02 - 2.910007E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.910007E+01 3.000000E+01 1 3.967776E+01 8.993078E+01 4.793527E-02 3.967773E+01 - 2.910007E+01 3.000000E+01 2 2.421017E+01 8.992061E+01 3.354733E-02 2.421014E+01 - 2.910007E+01 3.000000E+01 3 1.857465E+02 2.973713E-01 1.857440E+02 9.640398E-01 - 2.910007E+01 3.000000E+01 4 7.893834E+01 8.992007E+01 1.101233E-01 7.893826E+01 - 2.910007E+01 3.000000E+01 5 4.076400E+02 8.993078E+01 4.924771E-01 4.076396E+02 - 2.910007E+01 3.000000E+01 6 6.261650E+01 -9.063248E-04 6.261650E+01 -9.904898E-04 - 2.910007E+01 6.000000E+01 1 2.307065E+01 8.993079E+01 2.786764E-02 2.307064E+01 - 2.910007E+01 6.000000E+01 2 4.226030E+01 8.992059E+01 5.856558E-02 4.226025E+01 - 2.910007E+01 6.000000E+01 3 1.872321E+02 2.984377E-01 1.872296E+02 9.752351E-01 - 2.910007E+01 6.000000E+01 4 1.387225E+02 8.992059E+01 1.922476E-01 1.387224E+02 - 2.910007E+01 6.000000E+01 5 2.369875E+02 8.993078E+01 2.863030E-01 2.369873E+02 - 2.910007E+01 6.000000E+01 6 6.311901E+01 -9.038706E-04 6.311901E+01 -9.957352E-04 - 2.910007E+01 9.000000E+01 1 2.394512E-06 -9.004845E+01 -2.025197E-09 -2.394511E-06 - 2.910007E+01 9.000000E+01 2 4.898807E+01 8.992059E+01 6.789295E-02 4.898802E+01 - 2.910007E+01 9.000000E+01 3 1.879809E+02 2.989702E-01 1.879783E+02 9.808823E-01 - 2.910007E+01 9.000000E+01 4 1.613429E+02 8.992085E+01 2.228654E-01 1.613427E+02 - 2.910007E+01 9.000000E+01 5 1.099485E-04 -8.999020E+01 1.880766E-08 -1.099485E-04 - 2.910007E+01 9.000000E+01 6 5.423113E-06 1.799994E+02 -5.423113E-06 5.768371E-11 - 2.920008E+01 0.000000E+00 1 4.549806E+01 8.993128E+01 5.456414E-02 4.549802E+01 - 2.920008E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.920008E+01 0.000000E+00 3 1.851628E+02 2.947226E-01 1.851604E+02 9.524513E-01 - 2.920008E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.920008E+01 0.000000E+00 5 4.677693E+02 8.993129E+01 5.609504E-01 4.677689E+02 - 2.920008E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.920008E+01 3.000000E+01 1 3.954085E+01 8.993129E+01 4.741634E-02 3.954082E+01 - 2.920008E+01 3.000000E+01 2 2.412669E+01 8.992123E+01 3.316514E-02 2.412667E+01 - 2.920008E+01 3.000000E+01 3 1.858962E+02 2.952467E-01 1.858938E+02 9.579241E-01 - 2.920008E+01 3.000000E+01 4 7.864951E+01 8.992072E+01 1.088400E-01 7.864943E+01 - 2.920008E+01 3.000000E+01 5 4.065047E+02 8.993129E+01 4.874707E-01 4.065044E+02 - 2.920008E+01 3.000000E+01 6 6.216718E+01 -8.923067E-04 6.216718E+01 -9.681724E-04 - 2.920008E+01 6.000000E+01 1 2.298986E+01 8.993130E+01 2.756465E-02 2.298984E+01 - 2.920008E+01 6.000000E+01 2 4.211215E+01 8.992123E+01 5.789485E-02 4.211211E+01 - 2.920008E+01 6.000000E+01 3 1.873722E+02 2.962984E-01 1.873697E+02 9.689689E-01 - 2.920008E+01 6.000000E+01 4 1.382000E+02 8.992123E+01 1.899966E-01 1.381999E+02 - 2.920008E+01 6.000000E+01 5 2.363138E+02 8.993129E+01 2.833776E-01 2.363137E+02 - 2.920008E+01 6.000000E+01 6 6.266233E+01 -8.899080E-04 6.266233E+01 -9.732604E-04 - 2.920008E+01 9.000000E+01 1 2.385977E-06 -9.004819E+01 -2.006705E-09 -2.385976E-06 - 2.920008E+01 9.000000E+01 2 4.881489E+01 8.992123E+01 6.711344E-02 4.881485E+01 - 2.920008E+01 9.000000E+01 3 1.881146E+02 2.968224E-01 1.881121E+02 9.745286E-01 - 2.920008E+01 9.000000E+01 4 1.607267E+02 8.992149E+01 2.202494E-01 1.607265E+02 - 2.920008E+01 9.000000E+01 5 1.095814E-04 -8.999030E+01 1.855737E-08 -1.095814E-04 - 2.920008E+01 9.000000E+01 6 5.383661E-06 1.799994E+02 -5.383661E-06 5.638373E-11 - 2.930008E+01 0.000000E+00 1 4.534274E+01 8.993180E+01 5.397703E-02 4.534271E+01 - 2.930008E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.930008E+01 0.000000E+00 3 1.853160E+02 2.926262E-01 1.853136E+02 9.464585E-01 - 2.930008E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.930008E+01 0.000000E+00 5 4.664778E+02 8.993180E+01 5.552765E-01 4.664775E+02 - 2.930008E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.930008E+01 3.000000E+01 1 3.940488E+01 8.993180E+01 4.690501E-02 3.940486E+01 - 2.930008E+01 3.000000E+01 2 2.404375E+01 8.992187E+01 3.278877E-02 2.404373E+01 - 2.930008E+01 3.000000E+01 3 1.860446E+02 2.931412E-01 1.860421E+02 9.518520E-01 - 2.930008E+01 3.000000E+01 4 7.836202E+01 8.992135E+01 1.075768E-01 7.836195E+01 - 2.930008E+01 3.000000E+01 5 4.053678E+02 8.993180E+01 4.825287E-01 4.053676E+02 - 2.930008E+01 3.000000E+01 6 6.172264E+01 -8.785634E-04 6.172264E+01 -9.464441E-04 - 2.930008E+01 6.000000E+01 1 2.290953E+01 8.993181E+01 2.726608E-02 2.290951E+01 - 2.930008E+01 6.000000E+01 2 4.196497E+01 8.992186E+01 5.723463E-02 4.196493E+01 - 2.930008E+01 6.000000E+01 3 1.875102E+02 2.941777E-01 1.875077E+02 9.627420E-01 - 2.930008E+01 6.000000E+01 4 1.376808E+02 8.992186E+01 1.877802E-01 1.376807E+02 - 2.930008E+01 6.000000E+01 5 2.356416E+02 8.993180E+01 2.804900E-01 2.356414E+02 - 2.930008E+01 6.000000E+01 6 6.221064E+01 -8.762188E-04 6.221064E+01 -9.513813E-04 - 2.930008E+01 9.000000E+01 1 2.377505E-06 -9.004792E+01 -1.988428E-09 -2.377504E-06 - 2.930008E+01 9.000000E+01 2 4.864286E+01 8.992185E+01 6.634599E-02 4.864281E+01 - 2.930008E+01 9.000000E+01 3 1.882483E+02 2.946921E-01 1.882458E+02 9.682223E-01 - 2.930008E+01 9.000000E+01 4 1.601145E+02 8.992210E+01 2.176737E-01 1.601144E+02 - 2.930008E+01 9.000000E+01 5 1.092160E-04 -8.999039E+01 1.831153E-08 -1.092160E-04 - 2.930008E+01 9.000000E+01 6 5.344647E-06 1.799994E+02 -5.344647E-06 5.511807E-11 - 2.940008E+01 0.000000E+00 1 4.518850E+01 8.993230E+01 5.339843E-02 4.518847E+01 - 2.940008E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.940008E+01 0.000000E+00 3 1.854676E+02 2.905528E-01 1.854652E+02 9.405209E-01 - 2.940008E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.940008E+01 0.000000E+00 5 4.651899E+02 8.993230E+01 5.496780E-01 4.651896E+02 - 2.940008E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.940008E+01 3.000000E+01 1 3.926988E+01 8.993230E+01 4.640102E-02 3.926986E+01 - 2.940008E+01 3.000000E+01 2 2.396139E+01 8.992248E+01 3.241828E-02 2.396137E+01 - 2.940008E+01 3.000000E+01 3 1.861911E+02 2.910613E-01 1.861888E+02 9.458427E-01 - 2.940008E+01 3.000000E+01 4 7.807688E+01 8.992197E+01 1.063335E-01 7.807681E+01 - 2.940008E+01 3.000000E+01 5 4.042377E+02 8.993230E+01 4.776469E-01 4.042374E+02 - 2.940008E+01 3.000000E+01 6 6.128293E+01 -8.650887E-04 6.128293E+01 -9.252893E-04 - 2.940008E+01 6.000000E+01 1 2.282981E+01 8.993231E+01 2.697182E-02 2.282980E+01 - 2.940008E+01 6.000000E+01 2 4.181889E+01 8.992248E+01 5.658454E-02 4.181886E+01 - 2.940008E+01 6.000000E+01 3 1.876475E+02 2.920804E-01 1.876450E+02 9.565786E-01 - 2.940008E+01 6.000000E+01 4 1.371663E+02 8.992248E+01 1.855994E-01 1.371662E+02 - 2.940008E+01 6.000000E+01 5 2.349724E+02 8.993230E+01 2.776411E-01 2.349723E+02 - 2.940008E+01 6.000000E+01 6 6.176389E+01 -8.627969E-04 6.176389E+01 -9.300805E-04 - 2.940008E+01 9.000000E+01 1 2.369096E-06 -9.004765E+01 -1.970345E-09 -2.369095E-06 - 2.940008E+01 9.000000E+01 2 4.847226E+01 8.992248E+01 6.559054E-02 4.847221E+01 - 2.940008E+01 9.000000E+01 3 1.883794E+02 2.925909E-01 1.883770E+02 9.619884E-01 - 2.940008E+01 9.000000E+01 4 1.595086E+02 8.992272E+01 2.151389E-01 1.595084E+02 - 2.940008E+01 9.000000E+01 5 1.088531E-04 -8.999049E+01 1.807004E-08 -1.088531E-04 - 2.940008E+01 9.000000E+01 6 5.306068E-06 1.799994E+02 -5.306068E-06 5.388587E-11 - 2.950008E+01 0.000000E+00 1 4.503524E+01 8.993279E+01 5.282796E-02 4.503521E+01 - 2.950008E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.950008E+01 0.000000E+00 3 1.856178E+02 2.885004E-01 1.856155E+02 9.346341E-01 - 2.950008E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.950008E+01 0.000000E+00 5 4.639080E+02 8.993279E+01 5.441520E-01 4.639077E+02 - 2.950008E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.950008E+01 3.000000E+01 1 3.913564E+01 8.993279E+01 4.590441E-02 3.913562E+01 - 2.950008E+01 3.000000E+01 2 2.387957E+01 8.992310E+01 3.205346E-02 2.387955E+01 - 2.950008E+01 3.000000E+01 3 1.863369E+02 2.890021E-01 1.863346E+02 9.398865E-01 - 2.950008E+01 3.000000E+01 4 7.779379E+01 8.992258E+01 1.051103E-01 7.779372E+01 - 2.950008E+01 3.000000E+01 5 4.031126E+02 8.993279E+01 4.728397E-01 4.031123E+02 - 2.950008E+01 3.000000E+01 6 6.084794E+01 -8.518766E-04 6.084794E+01 -9.046903E-04 - 2.950008E+01 6.000000E+01 1 2.275075E+01 8.993281E+01 2.668183E-02 2.275074E+01 - 2.950008E+01 6.000000E+01 2 4.167384E+01 8.992308E+01 5.594446E-02 4.167380E+01 - 2.950008E+01 6.000000E+01 3 1.877826E+02 2.900069E-01 1.877802E+02 9.504718E-01 - 2.950008E+01 6.000000E+01 4 1.366552E+02 8.992308E+01 1.834532E-01 1.366551E+02 - 2.950008E+01 6.000000E+01 5 2.343090E+02 8.993279E+01 2.748291E-01 2.343089E+02 - 2.950008E+01 6.000000E+01 6 6.132202E+01 -8.496349E-04 6.132202E+01 -9.093396E-04 - 2.950008E+01 9.000000E+01 1 2.360742E-06 -9.004739E+01 -1.952473E-09 -2.360742E-06 - 2.950008E+01 9.000000E+01 2 4.830267E+01 8.992308E+01 6.484669E-02 4.830262E+01 - 2.950008E+01 9.000000E+01 3 1.885108E+02 2.905099E-01 1.885083E+02 9.558124E-01 - 2.950008E+01 9.000000E+01 4 1.589058E+02 8.992332E+01 2.126458E-01 1.589057E+02 - 2.950008E+01 9.000000E+01 5 1.084931E-04 -8.999059E+01 1.783283E-08 -1.084931E-04 - 2.950008E+01 9.000000E+01 6 5.267908E-06 1.799994E+02 -5.267908E-06 5.268607E-11 - 2.960008E+01 0.000000E+00 1 4.488310E+01 8.993328E+01 5.226607E-02 4.488307E+01 - 2.960008E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.960008E+01 0.000000E+00 3 1.857660E+02 2.864744E-01 1.857637E+02 9.288118E-01 - 2.960008E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.960008E+01 0.000000E+00 5 4.626335E+02 8.993329E+01 5.387046E-01 4.626332E+02 - 2.960008E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.960008E+01 3.000000E+01 1 3.900241E+01 8.993329E+01 4.541489E-02 3.900238E+01 - 2.960008E+01 3.000000E+01 2 2.379830E+01 8.992370E+01 3.169409E-02 2.379828E+01 - 2.960008E+01 3.000000E+01 3 1.864805E+02 2.869669E-01 1.864781E+02 9.339865E-01 - 2.960008E+01 3.000000E+01 4 7.751311E+01 8.992319E+01 1.039054E-01 7.751304E+01 - 2.960008E+01 3.000000E+01 5 4.019959E+02 8.993329E+01 4.680890E-01 4.019956E+02 - 2.960008E+01 3.000000E+01 6 6.041780E+01 -8.389194E-04 6.041780E+01 -8.846318E-04 - 2.960008E+01 6.000000E+01 1 2.267214E+01 8.993330E+01 2.639602E-02 2.267212E+01 - 2.960008E+01 6.000000E+01 2 4.152969E+01 8.992369E+01 5.531419E-02 4.152965E+01 - 2.960008E+01 6.000000E+01 3 1.879169E+02 2.879573E-01 1.879145E+02 9.444292E-01 - 2.960008E+01 6.000000E+01 4 1.361490E+02 8.992369E+01 1.813403E-01 1.361488E+02 - 2.960008E+01 6.000000E+01 5 2.336446E+02 8.993329E+01 2.720580E-01 2.336444E+02 - 2.960008E+01 6.000000E+01 6 6.088495E+01 -8.367306E-04 6.088495E+01 -8.891458E-04 - 2.960008E+01 9.000000E+01 1 2.352451E-06 -9.004713E+01 -1.934784E-09 -2.352450E-06 - 2.960008E+01 9.000000E+01 2 4.813428E+01 8.992368E+01 6.411441E-02 4.813424E+01 - 2.960008E+01 9.000000E+01 3 1.886402E+02 2.884483E-01 1.886378E+02 9.496808E-01 - 2.960008E+01 9.000000E+01 4 1.583091E+02 8.992393E+01 2.101913E-01 1.583089E+02 - 2.960008E+01 9.000000E+01 5 1.081352E-04 -8.999068E+01 1.759984E-08 -1.081352E-04 - 2.960008E+01 9.000000E+01 6 5.230166E-06 1.799994E+02 -5.230166E-06 5.151773E-11 - 2.970008E+01 0.000000E+00 1 4.473183E+01 8.993376E+01 5.171188E-02 4.473180E+01 - 2.970008E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.970008E+01 0.000000E+00 3 1.859136E+02 2.844649E-01 1.859113E+02 9.230294E-01 - 2.970008E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.970008E+01 0.000000E+00 5 4.613603E+02 8.993376E+01 5.333279E-01 4.613600E+02 - 2.970008E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.970008E+01 3.000000E+01 1 3.887003E+01 8.993377E+01 4.493246E-02 3.887001E+01 - 2.970008E+01 3.000000E+01 2 2.371763E+01 8.992429E+01 3.134031E-02 2.371761E+01 - 2.970008E+01 3.000000E+01 3 1.866223E+02 2.849506E-01 1.866200E+02 9.281297E-01 - 2.970008E+01 3.000000E+01 4 7.723470E+01 8.992380E+01 1.027199E-01 7.723463E+01 - 2.970008E+01 3.000000E+01 5 4.008798E+02 8.993377E+01 4.634041E-01 4.008795E+02 - 2.970008E+01 3.000000E+01 6 5.999210E+01 -8.262128E-04 5.999210E+01 -8.650940E-04 - 2.970008E+01 6.000000E+01 1 2.259411E+01 8.993378E+01 2.611432E-02 2.259409E+01 - 2.970008E+01 6.000000E+01 2 4.138663E+01 8.992429E+01 5.469355E-02 4.138660E+01 - 2.970008E+01 6.000000E+01 3 1.880501E+02 2.859252E-01 1.880478E+02 9.384295E-01 - 2.970008E+01 6.000000E+01 4 1.356459E+02 8.992429E+01 1.792611E-01 1.356457E+02 - 2.970008E+01 6.000000E+01 5 2.329868E+02 8.993377E+01 2.693222E-01 2.329866E+02 - 2.970008E+01 6.000000E+01 6 6.045265E+01 -8.240722E-04 6.045265E+01 -8.694767E-04 - 2.970008E+01 9.000000E+01 1 2.344221E-06 -9.004687E+01 -1.917299E-09 -2.344220E-06 - 2.970008E+01 9.000000E+01 2 4.796714E+01 8.992428E+01 6.339323E-02 4.796710E+01 - 2.970008E+01 9.000000E+01 3 1.887684E+02 2.864132E-01 1.887661E+02 9.436218E-01 - 2.970008E+01 9.000000E+01 4 1.577163E+02 8.992452E+01 2.077747E-01 1.577162E+02 - 2.970008E+01 9.000000E+01 5 1.077796E-04 -8.999077E+01 1.737087E-08 -1.077796E-04 - 2.970008E+01 9.000000E+01 6 5.192836E-06 1.799995E+02 -5.192836E-06 5.037978E-11 - 2.980008E+01 0.000000E+00 1 4.458161E+01 8.993424E+01 5.116573E-02 4.458158E+01 - 2.980008E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.980008E+01 0.000000E+00 3 1.860588E+02 2.824788E-01 1.860565E+02 9.173005E-01 - 2.980008E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.980008E+01 0.000000E+00 5 4.600951E+02 8.993425E+01 5.280202E-01 4.600948E+02 - 2.980008E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.980008E+01 3.000000E+01 1 3.873870E+01 8.993425E+01 4.445663E-02 3.873868E+01 - 2.980008E+01 3.000000E+01 2 2.363745E+01 8.992488E+01 3.099185E-02 2.363742E+01 - 2.980008E+01 3.000000E+01 3 1.867638E+02 2.829582E-01 1.867615E+02 9.223391E-01 - 2.980008E+01 3.000000E+01 4 7.695767E+01 8.992439E+01 1.015526E-01 7.695760E+01 - 2.980008E+01 3.000000E+01 5 3.997693E+02 8.993425E+01 4.587857E-01 3.997691E+02 - 2.980008E+01 3.000000E+01 6 5.957100E+01 -8.137521E-04 5.957100E+01 -8.460662E-04 - 2.980008E+01 6.000000E+01 1 2.251657E+01 8.993426E+01 2.583669E-02 2.251655E+01 - 2.980008E+01 6.000000E+01 2 4.124451E+01 8.992487E+01 5.408248E-02 4.124448E+01 - 2.980008E+01 6.000000E+01 3 1.881823E+02 2.839167E-01 1.881800E+02 9.324922E-01 - 2.980008E+01 6.000000E+01 4 1.351464E+02 8.992487E+01 1.772145E-01 1.351463E+02 - 2.980008E+01 6.000000E+01 5 2.323321E+02 8.993425E+01 2.666237E-01 2.323319E+02 - 2.980008E+01 6.000000E+01 6 6.002500E+01 -8.116572E-04 6.002500E+01 -8.503196E-04 - 2.980008E+01 9.000000E+01 1 2.336046E-06 -9.004660E+01 -1.900011E-09 -2.336046E-06 - 2.980008E+01 9.000000E+01 2 4.780128E+01 8.992487E+01 6.268329E-02 4.780124E+01 - 2.980008E+01 9.000000E+01 3 1.888957E+02 2.843975E-01 1.888934E+02 9.376126E-01 - 2.980008E+01 9.000000E+01 4 1.571293E+02 8.992510E+01 2.053965E-01 1.571291E+02 - 2.980008E+01 9.000000E+01 5 1.074264E-04 -8.999086E+01 1.714589E-08 -1.074264E-04 - 2.980008E+01 9.000000E+01 6 5.155914E-06 1.799995E+02 -5.155914E-06 4.927143E-11 - 2.990008E+01 0.000000E+00 1 4.443261E+01 8.993472E+01 5.062736E-02 4.443258E+01 - 2.990008E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.990008E+01 0.000000E+00 3 1.862035E+02 2.805118E-01 1.862012E+02 9.116213E-01 - 2.990008E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.990008E+01 0.000000E+00 5 4.588384E+02 8.993472E+01 5.227810E-01 4.588381E+02 - 2.990008E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 2.990008E+01 3.000000E+01 1 3.860804E+01 8.993472E+01 4.398783E-02 3.860802E+01 - 2.990008E+01 3.000000E+01 2 2.355785E+01 8.992546E+01 3.064860E-02 2.355783E+01 - 2.990008E+01 3.000000E+01 3 1.869043E+02 2.809834E-01 1.869021E+02 9.165912E-01 - 2.990008E+01 3.000000E+01 4 7.668298E+01 8.992498E+01 1.004033E-01 7.668291E+01 - 2.990008E+01 3.000000E+01 5 3.986673E+02 8.993472E+01 4.542212E-01 3.986671E+02 - 2.990008E+01 3.000000E+01 6 5.915438E+01 -8.015265E-04 5.915438E+01 -8.275269E-04 - 2.990008E+01 6.000000E+01 1 2.243959E+01 8.993473E+01 2.556304E-02 2.243958E+01 - 2.990008E+01 6.000000E+01 2 4.110343E+01 8.992545E+01 5.348057E-02 4.110339E+01 - 2.990008E+01 6.000000E+01 3 1.883131E+02 2.819290E-01 1.883108E+02 9.266077E-01 - 2.990008E+01 6.000000E+01 4 1.346508E+02 8.992545E+01 1.751986E-01 1.346507E+02 - 2.990008E+01 6.000000E+01 5 2.316790E+02 8.993472E+01 2.639591E-01 2.316788E+02 - 2.990008E+01 6.000000E+01 6 5.960191E+01 -7.994796E-04 5.960191E+01 -8.316583E-04 - 2.990008E+01 9.000000E+01 1 2.327931E-06 -9.004635E+01 -1.882912E-09 -2.327931E-06 - 2.990008E+01 9.000000E+01 2 4.763644E+01 8.992545E+01 6.198391E-02 4.763639E+01 - 2.990008E+01 9.000000E+01 3 1.890210E+02 2.824030E-01 1.890187E+02 9.316548E-01 - 2.990008E+01 9.000000E+01 4 1.565448E+02 8.992568E+01 2.030558E-01 1.565446E+02 - 2.990008E+01 9.000000E+01 5 1.070752E-04 -8.999094E+01 1.692479E-08 -1.070752E-04 - 2.990008E+01 9.000000E+01 6 5.119384E-06 1.799995E+02 -5.119384E-06 4.819163E-11 - 3.000008E+01 0.000000E+00 1 4.428444E+01 8.993519E+01 5.009654E-02 4.428441E+01 - 3.000008E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.000008E+01 0.000000E+00 3 1.863466E+02 2.785688E-01 1.863445E+02 9.060031E-01 - 3.000008E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.000008E+01 0.000000E+00 5 4.575834E+02 8.993519E+01 5.176095E-01 4.575831E+02 - 3.000008E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.000008E+01 3.000000E+01 1 3.847847E+01 8.993519E+01 4.352576E-02 3.847845E+01 - 3.000008E+01 3.000000E+01 2 2.347882E+01 8.992603E+01 3.031052E-02 2.347880E+01 - 3.000008E+01 3.000000E+01 3 1.870421E+02 2.790350E-01 1.870399E+02 9.109065E-01 - 3.000008E+01 3.000000E+01 4 7.640999E+01 8.992556E+01 9.927158E-02 7.640993E+01 - 3.000008E+01 3.000000E+01 5 3.975689E+02 8.993519E+01 4.497190E-01 3.975686E+02 - 3.000008E+01 3.000000E+01 6 5.874228E+01 -7.895360E-04 5.874228E+01 -8.094688E-04 - 3.000008E+01 6.000000E+01 1 2.236315E+01 8.993520E+01 2.529320E-02 2.236314E+01 - 3.000008E+01 6.000000E+01 2 4.096333E+01 8.992603E+01 5.288776E-02 4.096329E+01 - 3.000008E+01 6.000000E+01 3 1.884412E+02 2.799668E-01 1.884389E+02 9.207846E-01 - 3.000008E+01 6.000000E+01 4 1.341592E+02 8.992603E+01 1.732149E-01 1.341591E+02 - 3.000008E+01 6.000000E+01 5 2.310289E+02 8.993519E+01 2.613340E-01 2.310288E+02 - 3.000008E+01 6.000000E+01 6 5.918349E+01 -7.875339E-04 5.918349E+01 -8.134806E-04 - 3.000008E+01 9.000000E+01 1 2.319874E-06 -9.004609E+01 -1.866006E-09 -2.319874E-06 - 3.000008E+01 9.000000E+01 2 4.747283E+01 8.992603E+01 6.129526E-02 4.747279E+01 - 3.000008E+01 9.000000E+01 3 1.891457E+02 2.804316E-01 1.891434E+02 9.257614E-01 - 3.000008E+01 9.000000E+01 4 1.559664E+02 8.992625E+01 2.007503E-01 1.559662E+02 - 3.000008E+01 9.000000E+01 5 1.067263E-04 -8.999103E+01 1.670759E-08 -1.067263E-04 - 3.000008E+01 9.000000E+01 6 5.083257E-06 1.799995E+02 -5.083257E-06 4.713976E-11 - 3.010008E+01 0.000000E+00 1 4.413715E+01 8.993565E+01 4.957308E-02 4.413712E+01 - 3.010008E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.010008E+01 0.000000E+00 3 1.864881E+02 2.766453E-01 1.864859E+02 9.004302E-01 - 3.010008E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.010008E+01 0.000000E+00 5 4.563321E+02 8.993565E+01 5.125093E-01 4.563318E+02 - 3.010008E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.010008E+01 3.000000E+01 1 3.834960E+01 8.993565E+01 4.307000E-02 3.834958E+01 - 3.010008E+01 3.000000E+01 2 2.340023E+01 8.992660E+01 2.997750E-02 2.340022E+01 - 3.010008E+01 3.000000E+01 3 1.871787E+02 2.771035E-01 1.871766E+02 9.052616E-01 - 3.010008E+01 3.000000E+01 4 7.613928E+01 8.992613E+01 9.815692E-02 7.613922E+01 - 3.010008E+01 3.000000E+01 5 3.964720E+02 8.993565E+01 4.452759E-01 3.964718E+02 - 3.010008E+01 3.000000E+01 6 5.833445E+01 -7.777730E-04 5.833445E+01 -7.918726E-04 - 3.010008E+01 6.000000E+01 1 2.228726E+01 8.993566E+01 2.502731E-02 2.228725E+01 - 3.010008E+01 6.000000E+01 2 4.082419E+01 8.992659E+01 5.230393E-02 4.082416E+01 - 3.010008E+01 6.000000E+01 3 1.885693E+02 2.780216E-01 1.885671E+02 9.150085E-01 - 3.010008E+01 6.000000E+01 4 1.336717E+02 8.992659E+01 1.712611E-01 1.336716E+02 - 3.010008E+01 6.000000E+01 5 2.303822E+02 8.993565E+01 2.587382E-01 2.303821E+02 - 3.010008E+01 6.000000E+01 6 5.876945E+01 -7.758149E-04 5.876945E+01 -7.957692E-04 - 3.010008E+01 9.000000E+01 1 2.311875E-06 -9.004584E+01 -1.849279E-09 -2.311875E-06 - 3.010008E+01 9.000000E+01 2 4.731023E+01 8.992659E+01 6.061680E-02 4.731019E+01 - 3.010008E+01 9.000000E+01 3 1.892687E+02 2.784809E-01 1.892664E+02 9.199195E-01 - 3.010008E+01 9.000000E+01 4 1.553916E+02 8.992682E+01 1.984811E-01 1.553914E+02 - 3.010008E+01 9.000000E+01 5 1.063797E-04 -8.999112E+01 1.649406E-08 -1.063797E-04 - 3.010008E+01 9.000000E+01 6 5.047520E-06 1.799995E+02 -5.047520E-06 4.611490E-11 - 3.020008E+01 0.000000E+00 1 4.399104E+01 8.993610E+01 4.905705E-02 4.399102E+01 - 3.020008E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.020008E+01 0.000000E+00 3 1.866277E+02 2.747404E-01 1.866255E+02 8.948994E-01 - 3.020008E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.020008E+01 0.000000E+00 5 4.550890E+02 8.993610E+01 5.074785E-01 4.550887E+02 - 3.020008E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.020008E+01 3.000000E+01 1 3.822173E+01 8.993611E+01 4.262054E-02 3.822170E+01 - 3.020008E+01 3.000000E+01 2 2.332226E+01 8.992716E+01 2.964941E-02 2.332224E+01 - 3.020008E+01 3.000000E+01 3 1.873143E+02 2.751917E-01 1.873121E+02 8.996674E-01 - 3.020008E+01 3.000000E+01 4 7.587064E+01 8.992670E+01 9.705951E-02 7.587057E+01 - 3.020008E+01 3.000000E+01 5 3.953836E+02 8.993610E+01 4.408927E-01 3.953834E+02 - 3.020008E+01 3.000000E+01 6 5.793094E+01 -7.662302E-04 5.793094E+01 -7.747244E-04 - 3.020008E+01 6.000000E+01 1 2.221184E+01 8.993612E+01 2.476502E-02 2.221183E+01 - 3.020008E+01 6.000000E+01 2 4.068599E+01 8.992715E+01 5.172871E-02 4.068595E+01 - 3.020008E+01 6.000000E+01 3 1.886955E+02 2.760973E-01 1.886933E+02 9.092838E-01 - 3.020008E+01 6.000000E+01 4 1.331873E+02 8.992715E+01 1.693382E-01 1.331871E+02 - 3.020008E+01 6.000000E+01 5 2.297372E+02 8.993611E+01 2.561796E-01 2.297370E+02 - 3.020008E+01 6.000000E+01 6 5.835978E+01 -7.643160E-04 5.835978E+01 -7.785096E-04 - 3.020008E+01 9.000000E+01 1 2.303925E-06 -9.004558E+01 -1.832743E-09 -2.303924E-06 - 3.020008E+01 9.000000E+01 2 4.714886E+01 8.992715E+01 5.994865E-02 4.714883E+01 - 3.020008E+01 9.000000E+01 3 1.893911E+02 2.765493E-01 1.893889E+02 9.141296E-01 - 3.020008E+01 9.000000E+01 4 1.548217E+02 8.992738E+01 1.962462E-01 1.548215E+02 - 3.020008E+01 9.000000E+01 5 1.060351E-04 -8.999120E+01 1.628421E-08 -1.060351E-04 - 3.020008E+01 9.000000E+01 6 5.012160E-06 1.799995E+02 -5.012160E-06 4.511613E-11 - 3.030008E+01 0.000000E+00 1 4.384571E+01 8.993656E+01 4.854807E-02 4.384568E+01 - 3.030008E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.030008E+01 0.000000E+00 3 1.867672E+02 2.728531E-01 1.867651E+02 8.894166E-01 - 3.030008E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.030008E+01 0.000000E+00 5 4.538535E+02 8.993656E+01 5.025070E-01 4.538533E+02 - 3.030008E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.030008E+01 3.000000E+01 1 3.809455E+01 8.993656E+01 4.217757E-02 3.809453E+01 - 3.030008E+01 3.000000E+01 2 2.324474E+01 8.992771E+01 2.932620E-02 2.324472E+01 - 3.030008E+01 3.000000E+01 3 1.874488E+02 2.733010E-01 1.874466E+02 8.941275E-01 - 3.030008E+01 3.000000E+01 4 7.560383E+01 8.992726E+01 9.597894E-02 7.560377E+01 - 3.030008E+01 3.000000E+01 5 3.942994E+02 8.993656E+01 4.365642E-01 3.942992E+02 - 3.030008E+01 3.000000E+01 6 5.753164E+01 -7.549060E-04 5.753164E+01 -7.580137E-04 - 3.030008E+01 6.000000E+01 1 2.213692E+01 8.993657E+01 2.450664E-02 2.213691E+01 - 3.030008E+01 6.000000E+01 2 4.054869E+01 8.992770E+01 5.116217E-02 4.054866E+01 - 3.030008E+01 6.000000E+01 3 1.888214E+02 2.741920E-01 1.888193E+02 9.036114E-01 - 3.030008E+01 6.000000E+01 4 1.327063E+02 8.992770E+01 1.674437E-01 1.327062E+02 - 3.030008E+01 6.000000E+01 5 2.290964E+02 8.993656E+01 2.536536E-01 2.290963E+02 - 3.030008E+01 6.000000E+01 6 5.795443E+01 -7.530344E-04 5.795443E+01 -7.616910E-04 - 3.030008E+01 9.000000E+01 1 2.296035E-06 -9.004533E+01 -1.816389E-09 -2.296034E-06 - 3.030008E+01 9.000000E+01 2 4.698862E+01 8.992770E+01 5.929046E-02 4.698859E+01 - 3.030008E+01 9.000000E+01 3 1.895123E+02 2.746371E-01 1.895101E+02 9.083899E-01 - 3.030008E+01 9.000000E+01 4 1.542555E+02 8.992793E+01 1.940461E-01 1.542554E+02 - 3.030008E+01 9.000000E+01 5 1.056931E-04 -8.999129E+01 1.607786E-08 -1.056931E-04 - 3.030008E+01 9.000000E+01 6 4.977173E-06 1.799995E+02 -4.977173E-06 4.414284E-11 - 3.040008E+01 0.000000E+00 1 4.370139E+01 8.993701E+01 4.804649E-02 4.370137E+01 - 3.040008E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.040008E+01 0.000000E+00 3 1.869051E+02 2.709897E-01 1.869030E+02 8.839947E-01 - 3.040008E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.040008E+01 0.000000E+00 5 4.526188E+02 8.993701E+01 4.975999E-01 4.526185E+02 - 3.040008E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.040008E+01 3.000000E+01 1 3.796838E+01 8.993702E+01 4.174079E-02 3.796835E+01 - 3.040008E+01 3.000000E+01 2 2.316777E+01 8.992826E+01 2.900782E-02 2.316776E+01 - 3.040008E+01 3.000000E+01 3 1.875829E+02 2.714281E-01 1.875808E+02 8.886361E-01 - 3.040008E+01 3.000000E+01 4 7.533876E+01 8.992782E+01 9.491497E-02 7.533870E+01 - 3.040008E+01 3.000000E+01 5 3.932216E+02 8.993701E+01 4.322958E-01 3.932214E+02 - 3.040008E+01 3.000000E+01 6 5.713646E+01 -7.437957E-04 5.713646E+01 -7.417274E-04 - 3.040008E+01 6.000000E+01 1 2.206254E+01 8.993702E+01 2.425172E-02 2.206253E+01 - 3.040008E+01 6.000000E+01 2 4.041239E+01 8.992825E+01 5.060411E-02 4.041236E+01 - 3.040008E+01 6.000000E+01 3 1.889464E+02 2.723086E-01 1.889442E+02 8.979985E-01 - 3.040008E+01 6.000000E+01 4 1.322292E+02 8.992825E+01 1.655786E-01 1.322291E+02 - 3.040008E+01 6.000000E+01 5 2.284614E+02 8.993702E+01 2.511606E-01 2.284613E+02 - 3.040008E+01 6.000000E+01 6 5.755345E+01 -7.419637E-04 5.755345E+01 -7.453004E-04 - 3.040008E+01 9.000000E+01 1 2.288200E-06 -9.004507E+01 -1.800219E-09 -2.288199E-06 - 3.040008E+01 9.000000E+01 2 4.682941E+01 8.992825E+01 5.864220E-02 4.682937E+01 - 3.040008E+01 9.000000E+01 3 1.896316E+02 2.727475E-01 1.896294E+02 9.027076E-01 - 3.040008E+01 9.000000E+01 4 1.536942E+02 8.992847E+01 1.918793E-01 1.536940E+02 - 3.040008E+01 9.000000E+01 5 1.053537E-04 -8.999137E+01 1.587513E-08 -1.053537E-04 - 3.040008E+01 9.000000E+01 6 4.942566E-06 1.799995E+02 -4.942566E-06 4.319428E-11 - 3.050008E+01 0.000000E+00 1 4.355813E+01 8.993745E+01 4.755162E-02 4.355810E+01 - 3.050008E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.050008E+01 0.000000E+00 3 1.870413E+02 2.691429E-01 1.870393E+02 8.786101E-01 - 3.050008E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.050008E+01 0.000000E+00 5 4.513942E+02 8.993745E+01 4.927564E-01 4.513939E+02 - 3.050008E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.050008E+01 3.000000E+01 1 3.784296E+01 8.993745E+01 4.131014E-02 3.784294E+01 - 3.050008E+01 3.000000E+01 2 2.309130E+01 8.992880E+01 2.869410E-02 2.309128E+01 - 3.050008E+01 3.000000E+01 3 1.877141E+02 2.695771E-01 1.877121E+02 8.831933E-01 - 3.050008E+01 3.000000E+01 4 7.507595E+01 8.992836E+01 9.386633E-02 7.507589E+01 - 3.050008E+01 3.000000E+01 5 3.921465E+02 8.993745E+01 4.280784E-01 3.921463E+02 - 3.050008E+01 3.000000E+01 6 5.674545E+01 -7.328924E-04 5.674545E+01 -7.258530E-04 - 3.050008E+01 6.000000E+01 1 2.198871E+01 8.993747E+01 2.400045E-02 2.198870E+01 - 3.050008E+01 6.000000E+01 2 4.027695E+01 8.992880E+01 5.005425E-02 4.027692E+01 - 3.050008E+01 6.000000E+01 3 1.890693E+02 2.704426E-01 1.890672E+02 8.924252E-01 - 3.050008E+01 6.000000E+01 4 1.317560E+02 8.992880E+01 1.637411E-01 1.317559E+02 - 3.050008E+01 6.000000E+01 5 2.278264E+02 8.993745E+01 2.487008E-01 2.278262E+02 - 3.050008E+01 6.000000E+01 6 5.715665E+01 -7.310992E-04 5.715665E+01 -7.293238E-04 - 3.050008E+01 9.000000E+01 1 2.280426E-06 -9.004483E+01 -1.784220E-09 -2.280425E-06 - 3.050008E+01 9.000000E+01 2 4.667132E+01 8.992879E+01 5.800344E-02 4.667128E+01 - 3.050008E+01 9.000000E+01 3 1.897509E+02 2.708740E-01 1.897488E+02 8.970714E-01 - 3.050008E+01 9.000000E+01 4 1.531367E+02 8.992901E+01 1.897454E-01 1.531366E+02 - 3.050008E+01 9.000000E+01 5 1.050156E-04 -8.999145E+01 1.567574E-08 -1.050156E-04 - 3.050008E+01 9.000000E+01 6 4.908320E-06 1.799995E+02 -4.908320E-06 4.226957E-11 - 3.060008E+01 0.000000E+00 1 4.341547E+01 8.993789E+01 4.706380E-02 4.341545E+01 - 3.060008E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.060008E+01 0.000000E+00 3 1.871758E+02 2.673157E-01 1.871738E+02 8.732731E-01 - 3.060008E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.060008E+01 0.000000E+00 5 4.501742E+02 8.993790E+01 4.879782E-01 4.501739E+02 - 3.060008E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.060008E+01 3.000000E+01 1 3.771829E+01 8.993790E+01 4.088533E-02 3.771827E+01 - 3.060008E+01 3.000000E+01 2 2.301533E+01 8.992934E+01 2.838496E-02 2.301531E+01 - 3.060008E+01 3.000000E+01 3 1.878450E+02 2.677438E-01 1.878429E+02 8.777985E-01 - 3.060008E+01 3.000000E+01 4 7.481495E+01 8.992891E+01 9.283397E-02 7.481489E+01 - 3.060008E+01 3.000000E+01 5 3.910774E+02 8.993790E+01 4.239163E-01 3.910772E+02 - 3.060008E+01 3.000000E+01 6 5.635844E+01 -7.221899E-04 5.635844E+01 -7.103751E-04 - 3.060008E+01 6.000000E+01 1 2.191535E+01 8.993790E+01 2.375261E-02 2.191534E+01 - 3.060008E+01 6.000000E+01 2 4.014241E+01 8.992933E+01 4.951235E-02 4.014238E+01 - 3.060008E+01 6.000000E+01 3 1.891911E+02 2.685968E-01 1.891890E+02 8.869054E-01 - 3.060008E+01 6.000000E+01 4 1.312857E+02 8.992933E+01 1.619315E-01 1.312856E+02 - 3.060008E+01 6.000000E+01 5 2.271952E+02 8.993790E+01 2.462717E-01 2.271951E+02 - 3.060008E+01 6.000000E+01 6 5.676398E+01 -7.204352E-04 5.676398E+01 -7.137483E-04 - 3.060008E+01 9.000000E+01 1 2.272691E-06 -9.004459E+01 -1.768402E-09 -2.272690E-06 - 3.060008E+01 9.000000E+01 2 4.651435E+01 8.992933E+01 5.737413E-02 4.651432E+01 - 3.060008E+01 9.000000E+01 3 1.898685E+02 2.690236E-01 1.898664E+02 8.914955E-01 - 3.060008E+01 9.000000E+01 4 1.525838E+02 8.992954E+01 1.876438E-01 1.525837E+02 - 3.060008E+01 9.000000E+01 5 1.046796E-04 -8.999152E+01 1.547975E-08 -1.046796E-04 - 3.060008E+01 9.000000E+01 6 4.874436E-06 1.799995E+02 -4.874436E-06 4.136818E-11 - 3.070008E+01 0.000000E+00 1 4.327412E+01 8.993832E+01 4.658252E-02 4.327409E+01 - 3.070008E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.070008E+01 0.000000E+00 3 1.873088E+02 2.655096E-01 1.873068E+02 8.679889E-01 - 3.070008E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.070008E+01 0.000000E+00 5 4.489539E+02 8.993832E+01 4.832589E-01 4.489536E+02 - 3.070008E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.070008E+01 3.000000E+01 1 3.759457E+01 8.993832E+01 4.046637E-02 3.759455E+01 - 3.070008E+01 3.000000E+01 2 2.293990E+01 8.992986E+01 2.808030E-02 2.293988E+01 - 3.070008E+01 3.000000E+01 3 1.879740E+02 2.659305E-01 1.879720E+02 8.724524E-01 - 3.070008E+01 3.000000E+01 4 7.455549E+01 8.992944E+01 9.181644E-02 7.455544E+01 - 3.070008E+01 3.000000E+01 5 3.900139E+02 8.993832E+01 4.198111E-01 3.900136E+02 - 3.070008E+01 3.000000E+01 6 5.597549E+01 -7.116874E-04 5.597549E+01 -6.952877E-04 - 3.070008E+01 6.000000E+01 1 2.184251E+01 8.993833E+01 2.350826E-02 2.184250E+01 - 3.070008E+01 6.000000E+01 2 4.000882E+01 8.992986E+01 4.897862E-02 4.000879E+01 - 3.070008E+01 6.000000E+01 3 1.893117E+02 2.667704E-01 1.893097E+02 8.814362E-01 - 3.070008E+01 6.000000E+01 4 1.308191E+02 8.992986E+01 1.601499E-01 1.308190E+02 - 3.070008E+01 6.000000E+01 5 2.265663E+02 8.993832E+01 2.438751E-01 2.265661E+02 - 3.070008E+01 6.000000E+01 6 5.637542E+01 -7.099709E-04 5.637542E+01 -6.985664E-04 - 3.070008E+01 9.000000E+01 1 2.265018E-06 -9.004434E+01 -1.752754E-09 -2.265018E-06 - 3.070008E+01 9.000000E+01 2 4.635834E+01 8.992986E+01 5.675413E-02 4.635830E+01 - 3.070008E+01 9.000000E+01 3 1.899848E+02 2.671911E-01 1.899827E+02 8.859651E-01 - 3.070008E+01 9.000000E+01 4 1.520348E+02 8.993006E+01 1.855742E-01 1.520347E+02 - 3.070008E+01 9.000000E+01 5 1.043465E-04 -8.999161E+01 1.528707E-08 -1.043465E-04 - 3.070008E+01 9.000000E+01 6 4.840912E-06 1.799995E+02 -4.840912E-06 4.048949E-11 - 3.080008E+01 0.000000E+00 1 4.313348E+01 8.993876E+01 4.610780E-02 4.313346E+01 - 3.080008E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.080008E+01 0.000000E+00 3 1.874410E+02 2.637186E-01 1.874390E+02 8.627427E-01 - 3.080008E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.080008E+01 0.000000E+00 5 4.477463E+02 8.993876E+01 4.785979E-01 4.477460E+02 - 3.080008E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.080008E+01 3.000000E+01 1 3.747162E+01 8.993876E+01 4.005323E-02 3.747160E+01 - 3.080008E+01 3.000000E+01 2 2.286489E+01 8.993039E+01 2.778010E-02 2.286487E+01 - 3.080008E+01 3.000000E+01 3 1.881021E+02 2.641324E-01 1.881001E+02 8.671439E-01 - 3.080008E+01 3.000000E+01 4 7.429823E+01 8.992997E+01 9.081502E-02 7.429818E+01 - 3.080008E+01 3.000000E+01 5 3.889516E+02 8.993876E+01 4.157513E-01 3.889514E+02 - 3.080008E+01 3.000000E+01 6 5.559647E+01 -7.013758E-04 5.559647E+01 -6.805740E-04 - 3.080008E+01 6.000000E+01 1 2.177006E+01 8.993877E+01 2.326731E-02 2.177005E+01 - 3.080008E+01 6.000000E+01 2 3.987618E+01 8.993038E+01 4.845255E-02 3.987615E+01 - 3.080008E+01 6.000000E+01 3 1.894314E+02 2.649621E-01 1.894293E+02 8.760148E-01 - 3.080008E+01 6.000000E+01 4 1.303561E+02 8.993038E+01 1.583941E-01 1.303560E+02 - 3.080008E+01 6.000000E+01 5 2.259407E+02 8.993876E+01 2.415084E-01 2.259406E+02 - 3.080008E+01 6.000000E+01 6 5.599092E+01 -6.996971E-04 5.599092E+01 -6.837621E-04 - 3.080008E+01 9.000000E+01 1 2.257399E-06 -9.004409E+01 -1.737281E-09 -2.257398E-06 - 3.080008E+01 9.000000E+01 2 4.620346E+01 8.993037E+01 5.614324E-02 4.620343E+01 - 3.080008E+01 9.000000E+01 3 1.901001E+02 2.653768E-01 1.900981E+02 8.804832E-01 - 3.080008E+01 9.000000E+01 4 1.514902E+02 8.993059E+01 1.835350E-01 1.514901E+02 - 3.080008E+01 9.000000E+01 5 1.040144E-04 -8.999168E+01 1.509754E-08 -1.040144E-04 - 3.080008E+01 9.000000E+01 6 4.807736E-06 1.799995E+02 -4.807736E-06 3.963256E-11 - 3.090008E+01 0.000000E+00 1 4.299379E+01 8.993918E+01 4.563982E-02 4.299377E+01 - 3.090008E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.090008E+01 0.000000E+00 3 1.875726E+02 2.619484E-01 1.875706E+02 8.575530E-01 - 3.090008E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.090008E+01 0.000000E+00 5 4.465399E+02 8.993918E+01 4.739981E-01 4.465397E+02 - 3.090008E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.090008E+01 3.000000E+01 1 3.734951E+01 8.993918E+01 3.964584E-02 3.734948E+01 - 3.090008E+01 3.000000E+01 2 2.279037E+01 8.993090E+01 2.748421E-02 2.279035E+01 - 3.090008E+01 3.000000E+01 3 1.882289E+02 2.623577E-01 1.882269E+02 8.618982E-01 - 3.090008E+01 3.000000E+01 4 7.404259E+01 8.993050E+01 8.982762E-02 7.404254E+01 - 3.090008E+01 3.000000E+01 5 3.878961E+02 8.993918E+01 4.117511E-01 3.878959E+02 - 3.090008E+01 3.000000E+01 6 5.522128E+01 -6.912568E-04 5.522128E+01 -6.662285E-04 - 3.090008E+01 6.000000E+01 1 2.169816E+01 8.993919E+01 2.302962E-02 2.169815E+01 - 3.090008E+01 6.000000E+01 2 3.974430E+01 8.993089E+01 4.793413E-02 3.974427E+01 - 3.090008E+01 6.000000E+01 3 1.895503E+02 2.631741E-01 1.895483E+02 8.706501E-01 - 3.090008E+01 6.000000E+01 4 1.298961E+02 8.993089E+01 1.566642E-01 1.298960E+02 - 3.090008E+01 6.000000E+01 5 2.253170E+02 8.993918E+01 2.391713E-01 2.253169E+02 - 3.090008E+01 6.000000E+01 6 5.561031E+01 -6.896126E-04 5.561031E+01 -6.693262E-04 - 3.090008E+01 9.000000E+01 1 2.249829E-06 -9.004385E+01 -1.721973E-09 -2.249828E-06 - 3.090008E+01 9.000000E+01 2 4.604965E+01 8.993089E+01 5.554111E-02 4.604961E+01 - 3.090008E+01 9.000000E+01 3 1.902134E+02 2.635837E-01 1.902114E+02 8.750553E-01 - 3.090008E+01 9.000000E+01 4 1.509488E+02 8.993110E+01 1.815263E-01 1.509487E+02 - 3.090008E+01 9.000000E+01 5 1.036849E-04 -8.999176E+01 1.491125E-08 -1.036849E-04 - 3.090008E+01 9.000000E+01 6 4.774903E-06 1.799995E+02 -4.774903E-06 3.879698E-11 - 3.100008E+01 0.000000E+00 1 4.285502E+01 8.993960E+01 4.517803E-02 4.285500E+01 - 3.100008E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.100008E+01 0.000000E+00 3 1.877029E+02 2.601949E-01 1.877009E+02 8.524042E-01 - 3.100008E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.100008E+01 0.000000E+00 5 4.453406E+02 8.993961E+01 4.694585E-01 4.453404E+02 - 3.100008E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.100008E+01 3.000000E+01 1 3.722807E+01 8.993961E+01 3.924388E-02 3.722805E+01 - 3.100008E+01 3.000000E+01 2 2.271643E+01 8.993141E+01 2.719263E-02 2.271642E+01 - 3.100008E+01 3.000000E+01 3 1.883554E+02 2.605982E-01 1.883535E+02 8.566936E-01 - 3.100008E+01 3.000000E+01 4 7.378862E+01 8.993101E+01 8.885553E-02 7.378857E+01 - 3.100008E+01 3.000000E+01 5 3.868489E+02 8.993961E+01 4.077967E-01 3.868487E+02 - 3.100008E+01 3.000000E+01 6 5.485001E+01 -6.813236E-04 5.485001E+01 -6.522401E-04 - 3.100008E+01 6.000000E+01 1 2.162674E+01 8.993961E+01 2.279516E-02 2.162673E+01 - 3.100008E+01 6.000000E+01 2 3.961340E+01 8.993141E+01 4.742325E-02 3.961337E+01 - 3.100008E+01 6.000000E+01 3 1.896681E+02 2.614026E-01 1.896662E+02 8.653268E-01 - 3.100008E+01 6.000000E+01 4 1.294397E+02 8.993141E+01 1.549607E-01 1.294396E+02 - 3.100008E+01 6.000000E+01 5 2.246980E+02 8.993961E+01 2.368684E-01 2.246979E+02 - 3.100008E+01 6.000000E+01 6 5.523374E+01 -6.797137E-04 5.523374E+01 -6.552512E-04 - 3.100008E+01 9.000000E+01 1 2.242310E-06 -9.004362E+01 -1.706840E-09 -2.242310E-06 - 3.100008E+01 9.000000E+01 2 4.589690E+01 8.993141E+01 5.494807E-02 4.589687E+01 - 3.100008E+01 9.000000E+01 3 1.903277E+02 2.618063E-01 1.903257E+02 8.696770E-01 - 3.100008E+01 9.000000E+01 4 1.504123E+02 8.993160E+01 1.795485E-01 1.504122E+02 - 3.100008E+01 9.000000E+01 5 1.033579E-04 -8.999184E+01 1.472793E-08 -1.033579E-04 - 3.100008E+01 9.000000E+01 6 4.742417E-06 1.799995E+02 -4.742417E-06 3.798223E-11 - 3.110008E+01 0.000000E+00 1 4.271725E+01 8.994002E+01 4.472252E-02 4.271722E+01 - 3.110008E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.110008E+01 0.000000E+00 3 1.878313E+02 2.584578E-01 1.878293E+02 8.472925E-01 - 3.110008E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.110008E+01 0.000000E+00 5 4.441506E+02 8.994002E+01 4.649782E-01 4.441503E+02 - 3.110008E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.110008E+01 3.000000E+01 1 3.710766E+01 8.994002E+01 3.884733E-02 3.710764E+01 - 3.110008E+01 3.000000E+01 2 2.264285E+01 8.993192E+01 2.690524E-02 2.264283E+01 - 3.110008E+01 3.000000E+01 3 1.884795E+02 2.588557E-01 1.884776E+02 8.515257E-01 - 3.110008E+01 3.000000E+01 4 7.353658E+01 8.993152E+01 8.789667E-02 7.353653E+01 - 3.110008E+01 3.000000E+01 5 3.858040E+02 8.994002E+01 4.038925E-01 3.858038E+02 - 3.110008E+01 3.000000E+01 6 5.448254E+01 -6.715673E-04 5.448254E+01 -6.385931E-04 - 3.110008E+01 6.000000E+01 1 2.155575E+01 8.994003E+01 2.256396E-02 2.155574E+01 - 3.110008E+01 6.000000E+01 2 3.948326E+01 8.993192E+01 4.691983E-02 3.948323E+01 - 3.110008E+01 6.000000E+01 3 1.897842E+02 2.596489E-01 1.897823E+02 8.600475E-01 - 3.110008E+01 6.000000E+01 4 1.289867E+02 8.993192E+01 1.532820E-01 1.289866E+02 - 3.110008E+01 6.000000E+01 5 2.240822E+02 8.994002E+01 2.345902E-01 2.240821E+02 - 3.110008E+01 6.000000E+01 6 5.486097E+01 -6.699933E-04 5.486097E+01 -6.415217E-04 - 3.110008E+01 9.000000E+01 1 2.234839E-06 -9.004337E+01 -1.691864E-09 -2.234839E-06 - 3.110008E+01 9.000000E+01 2 4.574520E+01 8.993192E+01 5.436330E-02 4.574517E+01 - 3.110008E+01 9.000000E+01 3 1.904401E+02 2.600465E-01 1.904381E+02 8.643413E-01 - 3.110008E+01 9.000000E+01 4 1.498793E+02 8.993211E+01 1.775985E-01 1.498792E+02 - 3.110008E+01 9.000000E+01 5 1.030330E-04 -8.999191E+01 1.454769E-08 -1.030330E-04 - 3.110008E+01 9.000000E+01 6 4.710264E-06 1.799996E+02 -4.710264E-06 3.718752E-11 - 3.120008E+01 0.000000E+00 1 4.258026E+01 8.994042E+01 4.427331E-02 4.258024E+01 - 3.120008E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.120008E+01 0.000000E+00 3 1.879590E+02 2.567396E-01 1.879572E+02 8.422326E-01 - 3.120008E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.120008E+01 0.000000E+00 5 4.429591E+02 8.994043E+01 4.605506E-01 4.429588E+02 - 3.120008E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.120008E+01 3.000000E+01 1 3.698774E+01 8.994043E+01 3.845636E-02 3.698772E+01 - 3.120008E+01 3.000000E+01 2 2.256986E+01 8.993242E+01 2.662198E-02 2.256985E+01 - 3.120008E+01 3.000000E+01 3 1.886033E+02 2.571312E-01 1.886014E+02 8.464085E-01 - 3.120008E+01 3.000000E+01 4 7.328609E+01 8.993202E+01 8.695251E-02 7.328603E+01 - 3.120008E+01 3.000000E+01 5 3.847628E+02 8.994043E+01 4.000409E-01 3.847626E+02 - 3.120008E+01 3.000000E+01 6 5.411873E+01 -6.619911E-04 5.411873E+01 -6.252836E-04 - 3.120008E+01 6.000000E+01 1 2.148526E+01 8.994044E+01 2.233585E-02 2.148524E+01 - 3.120008E+01 6.000000E+01 2 3.935412E+01 8.993241E+01 4.642364E-02 3.935410E+01 - 3.120008E+01 6.000000E+01 3 1.898994E+02 2.579163E-01 1.898975E+02 8.548273E-01 - 3.120008E+01 6.000000E+01 4 1.285365E+02 8.993241E+01 1.516277E-01 1.285364E+02 - 3.120008E+01 6.000000E+01 5 2.234675E+02 8.994043E+01 2.323439E-01 2.234673E+02 - 3.120008E+01 6.000000E+01 6 5.449213E+01 -6.604489E-04 5.449213E+01 -6.281313E-04 - 3.120008E+01 9.000000E+01 1 2.227424E-06 -9.004314E+01 -1.677062E-09 -2.227424E-06 - 3.120008E+01 9.000000E+01 2 4.559439E+01 8.993241E+01 5.378699E-02 4.559436E+01 - 3.120008E+01 9.000000E+01 3 1.905505E+02 2.583078E-01 1.905486E+02 8.590598E-01 - 3.120008E+01 9.000000E+01 4 1.493502E+02 8.993260E+01 1.756782E-01 1.493501E+02 - 3.120008E+01 9.000000E+01 5 1.027095E-04 -8.999198E+01 1.437044E-08 -1.027095E-04 - 3.120008E+01 9.000000E+01 6 4.678442E-06 1.799996E+02 -4.678442E-06 3.641232E-11 - 3.130008E+01 0.000000E+00 1 4.244415E+01 8.994083E+01 4.383010E-02 4.244413E+01 - 3.130008E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.130008E+01 0.000000E+00 3 1.880849E+02 2.550395E-01 1.880830E+02 8.372157E-01 - 3.130008E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.130008E+01 0.000000E+00 5 4.417768E+02 8.994083E+01 4.561822E-01 4.417766E+02 - 3.130008E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.130008E+01 3.000000E+01 1 3.686876E+01 8.994084E+01 3.807050E-02 3.686874E+01 - 3.130008E+01 3.000000E+01 2 2.249725E+01 8.993291E+01 2.634262E-02 2.249723E+01 - 3.130008E+01 3.000000E+01 3 1.887257E+02 2.554244E-01 1.887238E+02 8.413358E-01 - 3.130008E+01 3.000000E+01 4 7.303760E+01 8.993252E+01 8.602200E-02 7.303754E+01 - 3.130008E+01 3.000000E+01 5 3.837261E+02 8.994084E+01 3.962370E-01 3.837259E+02 - 3.130008E+01 3.000000E+01 6 5.375858E+01 -6.525866E-04 5.375858E+01 -6.122987E-04 - 3.130008E+01 6.000000E+01 1 2.141525E+01 8.994085E+01 2.211093E-02 2.141524E+01 - 3.130008E+01 6.000000E+01 2 3.922577E+01 8.993291E+01 4.593449E-02 3.922575E+01 - 3.130008E+01 6.000000E+01 3 1.900133E+02 2.561975E-01 1.900114E+02 8.496398E-01 - 3.130008E+01 6.000000E+01 4 1.280902E+02 8.993291E+01 1.499988E-01 1.280901E+02 - 3.130008E+01 6.000000E+01 5 2.228578E+02 8.994083E+01 2.301247E-01 2.228577E+02 - 3.130008E+01 6.000000E+01 6 5.412697E+01 -6.510770E-04 5.412697E+01 -6.150684E-04 - 3.130008E+01 9.000000E+01 1 2.220058E-06 -9.004291E+01 -1.662420E-09 -2.220057E-06 - 3.130008E+01 9.000000E+01 2 4.544458E+01 8.993291E+01 5.321904E-02 4.544455E+01 - 3.130008E+01 9.000000E+01 3 1.906605E+02 2.565849E-01 1.906586E+02 8.538228E-01 - 3.130008E+01 9.000000E+01 4 1.488255E+02 8.993310E+01 1.737858E-01 1.488254E+02 - 3.130008E+01 9.000000E+01 5 1.023886E-04 -8.999206E+01 1.419605E-08 -1.023886E-04 - 3.130008E+01 9.000000E+01 6 4.646949E-06 1.799996E+02 -4.646949E-06 3.565608E-11 - 3.140008E+01 0.000000E+00 1 4.230868E+01 8.994124E+01 4.339260E-02 4.230866E+01 - 3.140008E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.140008E+01 0.000000E+00 3 1.882101E+02 2.533561E-01 1.882083E+02 8.322434E-01 - 3.140008E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.140008E+01 0.000000E+00 5 4.405977E+02 8.994125E+01 4.518622E-01 4.405974E+02 - 3.140008E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.140008E+01 3.000000E+01 1 3.675054E+01 8.994125E+01 3.768987E-02 3.675052E+01 - 3.140008E+01 3.000000E+01 2 2.242517E+01 8.993340E+01 2.606731E-02 2.242516E+01 - 3.140008E+01 3.000000E+01 3 1.888465E+02 2.537359E-01 1.888446E+02 8.363090E-01 - 3.140008E+01 3.000000E+01 4 7.279086E+01 8.993301E+01 8.510463E-02 7.279081E+01 - 3.140008E+01 3.000000E+01 5 3.826943E+02 8.994125E+01 3.924760E-01 3.826941E+02 - 3.140008E+01 3.000000E+01 6 5.340209E+01 -6.433519E-04 5.340209E+01 -5.996312E-04 - 3.140008E+01 6.000000E+01 1 2.134567E+01 8.994125E+01 2.188901E-02 2.134566E+01 - 3.140008E+01 6.000000E+01 2 3.909828E+01 8.993340E+01 4.545228E-02 3.909825E+01 - 3.140008E+01 6.000000E+01 3 1.901261E+02 2.544982E-01 1.901242E+02 8.445050E-01 - 3.140008E+01 6.000000E+01 4 1.276465E+02 8.993340E+01 1.483917E-01 1.276465E+02 - 3.140008E+01 6.000000E+01 5 2.222494E+02 8.994124E+01 2.279338E-01 2.222492E+02 - 3.140008E+01 6.000000E+01 6 5.376556E+01 -6.418732E-04 5.376556E+01 -6.023248E-04 - 3.140008E+01 9.000000E+01 1 2.212740E-06 -9.004267E+01 -1.647934E-09 -2.212739E-06 - 3.140008E+01 9.000000E+01 2 4.529589E+01 8.993339E+01 5.265917E-02 4.529586E+01 - 3.140008E+01 9.000000E+01 3 1.907693E+02 2.548800E-01 1.907674E+02 8.486333E-01 - 3.140008E+01 9.000000E+01 4 1.483038E+02 8.993358E+01 1.719213E-01 1.483037E+02 - 3.140008E+01 9.000000E+01 5 1.020689E-04 -8.999213E+01 1.402449E-08 -1.020689E-04 - 3.140008E+01 9.000000E+01 6 4.615771E-06 1.799996E+02 -4.615771E-06 3.491831E-11 - 3.150008E+01 0.000000E+00 1 4.217438E+01 8.994164E+01 4.296125E-02 4.217436E+01 - 3.150008E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.150008E+01 0.000000E+00 3 1.883341E+02 2.516885E-01 1.883323E+02 8.273101E-01 - 3.150008E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.150008E+01 0.000000E+00 5 4.394270E+02 8.994164E+01 4.476003E-01 4.394268E+02 - 3.150008E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.150008E+01 3.000000E+01 1 3.663300E+01 8.994164E+01 3.731441E-02 3.663298E+01 - 3.150008E+01 3.000000E+01 2 2.235349E+01 8.993388E+01 2.579601E-02 2.235347E+01 - 3.150008E+01 3.000000E+01 3 1.889663E+02 2.520641E-01 1.889645E+02 8.313261E-01 - 3.150008E+01 3.000000E+01 4 7.254544E+01 8.993349E+01 8.420121E-02 7.254539E+01 - 3.150008E+01 3.000000E+01 5 3.816672E+02 8.994164E+01 3.887678E-01 3.816670E+02 - 3.150008E+01 3.000000E+01 6 5.304921E+01 -6.342840E-04 5.304921E+01 -5.872730E-04 - 3.150008E+01 6.000000E+01 1 2.127658E+01 8.994164E+01 2.167005E-02 2.127657E+01 - 3.150008E+01 6.000000E+01 2 3.897163E+01 8.993388E+01 4.497702E-02 3.897160E+01 - 3.150008E+01 6.000000E+01 3 1.902381E+02 2.528161E-01 1.902362E+02 8.394178E-01 - 3.150008E+01 6.000000E+01 4 1.272065E+02 8.993388E+01 1.468103E-01 1.272064E+02 - 3.150008E+01 6.000000E+01 5 2.216435E+02 8.994164E+01 2.257711E-01 2.216434E+02 - 3.150008E+01 6.000000E+01 6 5.340778E+01 -6.328357E-04 5.340778E+01 -5.898924E-04 - 3.150008E+01 9.000000E+01 1 2.205470E-06 -9.004244E+01 -1.633608E-09 -2.205469E-06 - 3.150008E+01 9.000000E+01 2 4.514809E+01 8.993388E+01 5.210731E-02 4.514806E+01 - 3.150008E+01 9.000000E+01 3 1.908779E+02 2.531905E-01 1.908760E+02 8.434882E-01 - 3.150008E+01 9.000000E+01 4 1.477864E+02 8.993406E+01 1.700838E-01 1.477863E+02 - 3.150008E+01 9.000000E+01 5 1.017515E-04 -8.999220E+01 1.385574E-08 -1.017515E-04 - 3.150008E+01 9.000000E+01 6 4.584919E-06 1.799996E+02 -4.584919E-06 3.419857E-11 - 3.160008E+01 0.000000E+00 1 4.204083E+01 8.994203E+01 4.253544E-02 4.204081E+01 - 3.160008E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.160008E+01 0.000000E+00 3 1.884562E+02 2.500386E-01 1.884544E+02 8.224198E-01 - 3.160008E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.160008E+01 0.000000E+00 5 4.382549E+02 8.994204E+01 4.433883E-01 4.382547E+02 - 3.160008E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.160008E+01 3.000000E+01 1 3.651622E+01 8.994204E+01 3.694400E-02 3.651620E+01 - 3.160008E+01 3.000000E+01 2 2.228225E+01 8.993436E+01 2.552840E-02 2.228224E+01 - 3.160008E+01 3.000000E+01 3 1.890855E+02 2.504062E-01 1.890837E+02 8.263793E-01 - 3.160008E+01 3.000000E+01 4 7.230212E+01 8.993398E+01 8.331058E-02 7.230207E+01 - 3.160008E+01 3.000000E+01 5 3.806456E+02 8.994204E+01 3.851067E-01 3.806454E+02 - 3.160008E+01 3.000000E+01 6 5.269993E+01 -6.253745E-04 5.269993E+01 -5.752115E-04 - 3.160008E+01 6.000000E+01 1 2.120787E+01 8.994204E+01 2.145409E-02 2.120786E+01 - 3.160008E+01 6.000000E+01 2 3.884573E+01 8.993435E+01 4.450839E-02 3.884570E+01 - 3.160008E+01 6.000000E+01 3 1.903499E+02 2.511452E-01 1.903480E+02 8.343601E-01 - 3.160008E+01 6.000000E+01 4 1.267692E+02 8.993435E+01 1.452493E-01 1.267691E+02 - 3.160008E+01 6.000000E+01 5 2.210407E+02 8.994204E+01 2.236348E-01 2.210406E+02 - 3.160008E+01 6.000000E+01 6 5.305369E+01 -6.239574E-04 5.305369E+01 -5.777606E-04 - 3.160008E+01 9.000000E+01 1 2.198246E-06 -9.004221E+01 -1.619432E-09 -2.198245E-06 - 3.160008E+01 9.000000E+01 2 4.500122E+01 8.993435E+01 5.156337E-02 4.500119E+01 - 3.160008E+01 9.000000E+01 3 1.909846E+02 2.515182E-01 1.909828E+02 8.383856E-01 - 3.160008E+01 9.000000E+01 4 1.472733E+02 8.993454E+01 1.682731E-01 1.472732E+02 - 3.160008E+01 9.000000E+01 5 1.014360E-04 -8.999227E+01 1.368970E-08 -1.014360E-04 - 3.160008E+01 9.000000E+01 6 4.554380E-06 1.799996E+02 -4.554380E-06 3.349617E-11 - 3.170008E+01 0.000000E+00 1 4.190809E+01 8.994243E+01 4.211542E-02 4.190807E+01 - 3.170008E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.170008E+01 0.000000E+00 3 1.885789E+02 2.484026E-01 1.885771E+02 8.175706E-01 - 3.170008E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.170008E+01 0.000000E+00 5 4.370938E+02 8.994243E+01 4.392354E-01 4.370936E+02 - 3.170008E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.170008E+01 3.000000E+01 1 3.640022E+01 8.994243E+01 3.657847E-02 3.640020E+01 - 3.170008E+01 3.000000E+01 2 2.221152E+01 8.993483E+01 2.526463E-02 2.221151E+01 - 3.170008E+01 3.000000E+01 3 1.892030E+02 2.487685E-01 1.892012E+02 8.214847E-01 - 3.170008E+01 3.000000E+01 4 7.206001E+01 8.993446E+01 8.243237E-02 7.205997E+01 - 3.170008E+01 3.000000E+01 5 3.796264E+02 8.994243E+01 3.814907E-01 3.796263E+02 - 3.170008E+01 3.000000E+01 6 5.235402E+01 -6.166263E-04 5.235402E+01 -5.634424E-04 - 3.170008E+01 6.000000E+01 1 2.113974E+01 8.994243E+01 2.124105E-02 2.113973E+01 - 3.170008E+01 6.000000E+01 2 3.872069E+01 8.993482E+01 4.404656E-02 3.872066E+01 - 3.170008E+01 6.000000E+01 3 1.904602E+02 2.494981E-01 1.904584E+02 8.293681E-01 - 3.170008E+01 6.000000E+01 4 1.263347E+02 8.993482E+01 1.437122E-01 1.263346E+02 - 3.170008E+01 6.000000E+01 5 2.204412E+02 8.994243E+01 2.215249E-01 2.204411E+02 - 3.170008E+01 6.000000E+01 6 5.270306E+01 -6.152387E-04 5.270306E+01 -5.659224E-04 - 3.170008E+01 9.000000E+01 1 2.191076E-06 -9.004198E+01 -1.605421E-09 -2.191076E-06 - 3.170008E+01 9.000000E+01 2 4.485546E+01 8.993482E+01 5.102707E-02 4.485543E+01 - 3.170008E+01 9.000000E+01 3 1.910912E+02 2.498643E-01 1.910894E+02 8.333375E-01 - 3.170008E+01 9.000000E+01 4 1.467623E+02 8.993501E+01 1.664887E-01 1.467622E+02 - 3.170008E+01 9.000000E+01 5 1.011228E-04 -8.999234E+01 1.352632E-08 -1.011228E-04 - 3.170008E+01 9.000000E+01 6 4.524147E-06 1.799996E+02 -4.524147E-06 3.281071E-11 - 3.180009E+01 0.000000E+00 1 4.177626E+01 8.994281E+01 4.170094E-02 4.177624E+01 - 3.180009E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.180009E+01 0.000000E+00 3 1.886985E+02 2.467859E-01 1.886967E+02 8.127648E-01 - 3.180009E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.180009E+01 0.000000E+00 5 4.359382E+02 8.994282E+01 4.351280E-01 4.359380E+02 - 3.180009E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.180009E+01 3.000000E+01 1 3.628497E+01 8.994282E+01 3.621782E-02 3.628495E+01 - 3.180009E+01 3.000000E+01 2 2.214123E+01 8.993530E+01 2.500446E-02 2.214121E+01 - 3.180009E+01 3.000000E+01 3 1.893201E+02 2.471441E-01 1.893183E+02 8.166255E-01 - 3.180009E+01 3.000000E+01 4 7.182027E+01 8.993493E+01 8.156680E-02 7.182023E+01 - 3.180009E+01 3.000000E+01 5 3.786160E+02 8.994282E+01 3.779165E-01 3.786158E+02 - 3.180009E+01 3.000000E+01 6 5.201163E+01 -6.080327E-04 5.201163E+01 -5.519564E-04 - 3.180009E+01 6.000000E+01 1 2.107197E+01 8.994282E+01 2.103077E-02 2.107196E+01 - 3.180009E+01 6.000000E+01 2 3.859646E+01 8.993529E+01 4.359111E-02 3.859644E+01 - 3.180009E+01 6.000000E+01 3 1.905677E+02 2.478663E-01 1.905659E+02 8.244089E-01 - 3.180009E+01 6.000000E+01 4 1.259037E+02 8.993529E+01 1.421973E-01 1.259036E+02 - 3.180009E+01 6.000000E+01 5 2.198459E+02 8.994281E+01 2.194431E-01 2.198458E+02 - 3.180009E+01 6.000000E+01 6 5.235597E+01 -6.066744E-04 5.235597E+01 -5.543694E-04 - 3.180009E+01 9.000000E+01 1 2.183949E-06 -9.004176E+01 -1.591557E-09 -2.183949E-06 - 3.180009E+01 9.000000E+01 2 4.471059E+01 8.993529E+01 5.049825E-02 4.471057E+01 - 3.180009E+01 9.000000E+01 3 1.911960E+02 2.482258E-01 1.911942E+02 8.283267E-01 - 3.180009E+01 9.000000E+01 4 1.462562E+02 8.993546E+01 1.647293E-01 1.462561E+02 - 3.180009E+01 9.000000E+01 5 1.008110E-04 -8.999240E+01 1.336559E-08 -1.008110E-04 - 3.180009E+01 9.000000E+01 6 4.494217E-06 1.799996E+02 -4.494217E-06 3.214170E-11 - 3.190009E+01 0.000000E+00 1 4.164527E+01 8.994319E+01 4.129188E-02 4.164525E+01 - 3.190009E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.190009E+01 0.000000E+00 3 1.888182E+02 2.451834E-01 1.888164E+02 8.079990E-01 - 3.190009E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.190009E+01 0.000000E+00 5 4.347829E+02 8.994320E+01 4.310761E-01 4.347827E+02 - 3.190009E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.190009E+01 3.000000E+01 1 3.617052E+01 8.994320E+01 3.586186E-02 3.617050E+01 - 3.190009E+01 3.000000E+01 2 2.207140E+01 8.993576E+01 2.474802E-02 2.207138E+01 - 3.190009E+01 3.000000E+01 3 1.894362E+02 2.455358E-01 1.894345E+02 8.118090E-01 - 3.190009E+01 3.000000E+01 4 7.158137E+01 8.993539E+01 8.071379E-02 7.158132E+01 - 3.190009E+01 3.000000E+01 5 3.776061E+02 8.994320E+01 3.743875E-01 3.776059E+02 - 3.190009E+01 3.000000E+01 6 5.167256E+01 -5.995906E-04 5.167256E+01 -5.407446E-04 - 3.190009E+01 6.000000E+01 1 2.100459E+01 8.994320E+01 2.082334E-02 2.100458E+01 - 3.190009E+01 6.000000E+01 2 3.847307E+01 8.993575E+01 4.314199E-02 3.847305E+01 - 3.190009E+01 6.000000E+01 3 1.906760E+02 2.462474E-01 1.906742E+02 8.194901E-01 - 3.190009E+01 6.000000E+01 4 1.254759E+02 8.993575E+01 1.407038E-01 1.254758E+02 - 3.190009E+01 6.000000E+01 5 2.192515E+02 8.994319E+01 2.173868E-01 2.192514E+02 - 3.190009E+01 6.000000E+01 6 5.201238E+01 -5.982598E-04 5.201238E+01 -5.430927E-04 - 3.190009E+01 9.000000E+01 1 2.176870E-06 -9.004153E+01 -1.577846E-09 -2.176870E-06 - 3.190009E+01 9.000000E+01 2 4.456656E+01 8.993575E+01 4.997700E-02 4.456654E+01 - 3.190009E+01 9.000000E+01 3 1.912997E+02 2.466044E-01 1.912979E+02 8.233623E-01 - 3.190009E+01 9.000000E+01 4 1.457529E+02 8.993593E+01 1.629959E-01 1.457528E+02 - 3.190009E+01 9.000000E+01 5 1.005013E-04 -8.999247E+01 1.320738E-08 -1.005013E-04 - 3.190009E+01 9.000000E+01 6 4.464596E-06 1.799996E+02 -4.464596E-06 3.148874E-11 - 3.200008E+01 0.000000E+00 1 4.151496E+01 8.994357E+01 4.088827E-02 4.151494E+01 - 3.200008E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.200008E+01 0.000000E+00 3 1.889369E+02 2.435945E-01 1.889352E+02 8.032676E-01 - 3.200008E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.200008E+01 0.000000E+00 5 4.336381E+02 8.994357E+01 4.270725E-01 4.336379E+02 - 3.200008E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.200008E+01 3.000000E+01 1 3.605668E+01 8.994357E+01 3.551064E-02 3.605666E+01 - 3.200008E+01 3.000000E+01 2 2.200198E+01 8.993621E+01 2.449506E-02 2.200197E+01 - 3.200008E+01 3.000000E+01 3 1.895500E+02 2.439445E-01 1.895483E+02 8.070324E-01 - 3.200008E+01 3.000000E+01 4 7.134460E+01 8.993585E+01 7.987279E-02 7.134456E+01 - 3.200008E+01 3.000000E+01 5 3.766031E+02 8.994357E+01 3.709035E-01 3.766029E+02 - 3.200008E+01 3.000000E+01 6 5.133684E+01 -5.912976E-04 5.133684E+01 -5.298008E-04 - 3.200008E+01 6.000000E+01 1 2.093769E+01 8.994358E+01 2.061860E-02 2.093768E+01 - 3.200008E+01 6.000000E+01 2 3.835047E+01 8.993621E+01 4.269923E-02 3.835044E+01 - 3.200008E+01 6.000000E+01 3 1.907836E+02 2.446454E-01 1.907819E+02 8.146182E-01 - 3.200008E+01 6.000000E+01 4 1.250506E+02 8.993621E+01 1.392321E-01 1.250505E+02 - 3.200008E+01 6.000000E+01 5 2.186613E+02 8.994357E+01 2.153551E-01 2.186612E+02 - 3.200008E+01 6.000000E+01 6 5.167227E+01 -5.899935E-04 5.167227E+01 -5.320864E-04 - 3.200008E+01 9.000000E+01 1 2.169839E-06 -9.004131E+01 -1.564281E-09 -2.169839E-06 - 3.200008E+01 9.000000E+01 2 4.442363E+01 8.993620E+01 4.946293E-02 4.442361E+01 - 3.200008E+01 9.000000E+01 3 1.914030E+02 2.449974E-01 1.914012E+02 8.184388E-01 - 3.200008E+01 9.000000E+01 4 1.452537E+02 8.993638E+01 1.612873E-01 1.452536E+02 - 3.200008E+01 9.000000E+01 5 1.001939E-04 -8.999254E+01 1.305173E-08 -1.001939E-04 - 3.200008E+01 9.000000E+01 6 4.435266E-06 1.799996E+02 -4.435266E-06 3.085144E-11 - 3.210008E+01 0.000000E+00 1 4.138552E+01 8.994395E+01 4.049001E-02 4.138551E+01 - 3.210008E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.210008E+01 0.000000E+00 3 1.890545E+02 2.420243E-01 1.890528E+02 7.985864E-01 - 3.210008E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.210008E+01 0.000000E+00 5 4.324951E+02 8.994395E+01 4.231172E-01 4.324949E+02 - 3.210008E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.210008E+01 3.000000E+01 1 3.594356E+01 8.994395E+01 3.516399E-02 3.594354E+01 - 3.210008E+01 3.000000E+01 2 2.193302E+01 8.993667E+01 2.424563E-02 2.193301E+01 - 3.210008E+01 3.000000E+01 3 1.896640E+02 2.423693E-01 1.896624E+02 8.023036E-01 - 3.210008E+01 3.000000E+01 4 7.110902E+01 8.993631E+01 7.904386E-02 7.110898E+01 - 3.210008E+01 3.000000E+01 5 3.756074E+02 8.994395E+01 3.674622E-01 3.756072E+02 - 3.210008E+01 3.000000E+01 6 5.100443E+01 -5.831493E-04 5.100443E+01 -5.191167E-04 - 3.210008E+01 6.000000E+01 1 2.087120E+01 8.994395E+01 2.041666E-02 2.087119E+01 - 3.210008E+01 6.000000E+01 2 3.822867E+01 8.993666E+01 4.226264E-02 3.822865E+01 - 3.210008E+01 6.000000E+01 3 1.908896E+02 2.430616E-01 1.908879E+02 8.097945E-01 - 3.210008E+01 6.000000E+01 4 1.246291E+02 8.993666E+01 1.377807E-01 1.246290E+02 - 3.210008E+01 6.000000E+01 5 2.180737E+02 8.994395E+01 2.133478E-01 2.180736E+02 - 3.210008E+01 6.000000E+01 6 5.133543E+01 -5.818719E-04 5.133543E+01 -5.213410E-04 - 3.210008E+01 9.000000E+01 1 2.162853E-06 -9.004108E+01 -1.550861E-09 -2.162853E-06 - 3.210008E+01 9.000000E+01 2 4.428160E+01 8.993665E+01 4.895616E-02 4.428158E+01 - 3.210008E+01 9.000000E+01 3 1.915062E+02 2.434063E-01 1.915045E+02 8.135623E-01 - 3.210008E+01 9.000000E+01 4 1.447575E+02 8.993683E+01 1.596025E-01 1.447574E+02 - 3.210008E+01 9.000000E+01 5 9.988794E-05 -8.999260E+01 1.289854E-08 -9.988794E-05 - 3.210008E+01 9.000000E+01 6 4.406237E-06 1.799996E+02 -4.406237E-06 3.022927E-11 - 3.220008E+01 0.000000E+00 1 4.125680E+01 8.994432E+01 4.009678E-02 4.125678E+01 - 3.220008E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.220008E+01 0.000000E+00 3 1.891709E+02 2.404694E-01 1.891692E+02 7.939445E-01 - 3.220008E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.220008E+01 0.000000E+00 5 4.313605E+02 8.994432E+01 4.192114E-01 4.313603E+02 - 3.220008E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.220008E+01 3.000000E+01 1 3.583120E+01 8.994432E+01 3.482202E-02 3.583118E+01 - 3.220008E+01 3.000000E+01 2 2.186450E+01 8.993711E+01 2.399961E-02 2.186448E+01 - 3.220008E+01 3.000000E+01 3 1.897765E+02 2.408099E-01 1.897748E+02 7.976139E-01 - 3.220008E+01 3.000000E+01 4 7.087527E+01 8.993676E+01 7.822643E-02 7.087522E+01 - 3.220008E+01 3.000000E+01 5 3.746130E+02 8.994432E+01 3.640628E-01 3.746128E+02 - 3.220008E+01 3.000000E+01 6 5.067528E+01 -5.751448E-04 5.067528E+01 -5.086872E-04 - 3.220008E+01 6.000000E+01 1 2.080516E+01 8.994432E+01 2.021730E-02 2.080515E+01 - 3.220008E+01 6.000000E+01 2 3.810759E+01 8.993710E+01 4.183198E-02 3.810756E+01 - 3.220008E+01 6.000000E+01 3 1.909952E+02 2.414915E-01 1.909935E+02 8.050085E-01 - 3.220008E+01 6.000000E+01 4 1.242095E+02 8.993710E+01 1.363501E-01 1.242094E+02 - 3.220008E+01 6.000000E+01 5 2.174872E+02 8.994432E+01 2.113664E-01 2.174871E+02 - 3.220008E+01 6.000000E+01 6 5.100198E+01 -5.738919E-04 5.100198E+01 -5.108513E-04 - 3.220008E+01 9.000000E+01 1 2.155913E-06 -9.004086E+01 -1.537593E-09 -2.155913E-06 - 3.220008E+01 9.000000E+01 2 4.414053E+01 8.993710E+01 4.845633E-02 4.414050E+01 - 3.220008E+01 9.000000E+01 3 1.916070E+02 2.418338E-01 1.916053E+02 8.087315E-01 - 3.220008E+01 9.000000E+01 4 1.442664E+02 8.993728E+01 1.579417E-01 1.442663E+02 - 3.220008E+01 9.000000E+01 5 9.958397E-05 -8.999267E+01 1.274775E-08 -9.958397E-05 - 3.220008E+01 9.000000E+01 6 4.377488E-06 1.799996E+02 -4.377488E-06 2.962181E-11 - 3.230008E+01 0.000000E+00 1 4.112895E+01 8.994469E+01 3.970887E-02 4.112893E+01 - 3.230008E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.230008E+01 0.000000E+00 3 1.892857E+02 2.389284E-01 1.892840E+02 7.893355E-01 - 3.230008E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.230008E+01 0.000000E+00 5 4.302268E+02 8.994469E+01 4.153519E-01 4.302266E+02 - 3.230008E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.230008E+01 3.000000E+01 1 3.571948E+01 8.994469E+01 3.448439E-02 3.571946E+01 - 3.230008E+01 3.000000E+01 2 2.179637E+01 8.993755E+01 2.375698E-02 2.179636E+01 - 3.230008E+01 3.000000E+01 3 1.898883E+02 2.392633E-01 1.898867E+02 7.929583E-01 - 3.230008E+01 3.000000E+01 4 7.064333E+01 8.993721E+01 7.742055E-02 7.064329E+01 - 3.230008E+01 3.000000E+01 5 3.736209E+02 8.994469E+01 3.607068E-01 3.736207E+02 - 3.230008E+01 3.000000E+01 6 5.034934E+01 -5.672779E-04 5.034934E+01 -4.985021E-04 - 3.230008E+01 6.000000E+01 1 2.073949E+01 8.994469E+01 2.002059E-02 2.073948E+01 - 3.230008E+01 6.000000E+01 2 3.798725E+01 8.993755E+01 4.140727E-02 3.798723E+01 - 3.230008E+01 6.000000E+01 3 1.910985E+02 2.399381E-01 1.910968E+02 8.002629E-01 - 3.230008E+01 6.000000E+01 4 1.237939E+02 8.993755E+01 1.349392E-01 1.237938E+02 - 3.230008E+01 6.000000E+01 5 2.169046E+02 8.994469E+01 2.094097E-01 2.169044E+02 - 3.230008E+01 6.000000E+01 6 5.067178E+01 -5.660514E-04 5.067178E+01 -5.006098E-04 - 3.230008E+01 9.000000E+01 1 2.149018E-06 -9.004064E+01 -1.524460E-09 -2.149018E-06 - 3.230008E+01 9.000000E+01 2 4.400010E+01 8.993754E+01 4.796338E-02 4.400007E+01 - 3.230008E+01 9.000000E+01 3 1.917073E+02 2.402732E-01 1.917056E+02 8.039336E-01 - 3.230008E+01 9.000000E+01 4 1.437770E+02 8.993771E+01 1.563048E-01 1.437769E+02 - 3.230008E+01 9.000000E+01 5 9.928187E-05 -8.999273E+01 1.259932E-08 -9.928187E-05 - 3.230008E+01 9.000000E+01 6 4.349024E-06 1.799996E+02 -4.349024E-06 2.902866E-11 - 3.240008E+01 0.000000E+00 1 4.100199E+01 8.994505E+01 3.932587E-02 4.100197E+01 - 3.240008E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.240008E+01 0.000000E+00 3 1.894001E+02 2.374020E-01 1.893985E+02 7.847670E-01 - 3.240008E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.240008E+01 0.000000E+00 5 4.291011E+02 8.994505E+01 4.115402E-01 4.291009E+02 - 3.240008E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.240008E+01 3.000000E+01 1 3.560848E+01 8.994505E+01 3.415127E-02 3.560846E+01 - 3.240008E+01 3.000000E+01 2 2.172871E+01 8.993799E+01 2.351772E-02 2.172870E+01 - 3.240008E+01 3.000000E+01 3 1.899988E+02 2.377335E-01 1.899972E+02 7.883469E-01 - 3.240008E+01 3.000000E+01 4 7.041291E+01 8.993765E+01 7.662544E-02 7.041287E+01 - 3.240008E+01 3.000000E+01 5 3.726361E+02 8.994505E+01 3.573909E-01 3.726360E+02 - 3.240008E+01 3.000000E+01 6 5.002665E+01 -5.595473E-04 5.002665E+01 -4.885573E-04 - 3.240008E+01 6.000000E+01 1 2.067430E+01 8.994505E+01 1.982643E-02 2.067429E+01 - 3.240008E+01 6.000000E+01 2 3.786776E+01 8.993799E+01 4.098853E-02 3.786774E+01 - 3.240008E+01 6.000000E+01 3 1.912020E+02 2.383991E-01 1.912004E+02 7.955605E-01 - 3.240008E+01 6.000000E+01 4 1.233801E+02 8.993799E+01 1.335490E-01 1.233801E+02 - 3.240008E+01 6.000000E+01 5 2.163262E+02 8.994505E+01 2.074770E-01 2.163261E+02 - 3.240008E+01 6.000000E+01 6 5.034487E+01 -5.583456E-04 5.034487E+01 -4.906092E-04 - 3.240008E+01 9.000000E+01 1 2.142163E-06 -9.004043E+01 -1.511472E-09 -2.142163E-06 - 3.240008E+01 9.000000E+01 2 4.386096E+01 8.993798E+01 4.747720E-02 4.386093E+01 - 3.240008E+01 9.000000E+01 3 1.918069E+02 2.387314E-01 1.918052E+02 7.991897E-01 - 3.240008E+01 9.000000E+01 4 1.432912E+02 8.993815E+01 1.546903E-01 1.432911E+02 - 3.240008E+01 9.000000E+01 5 9.898109E-05 -8.999279E+01 1.245321E-08 -9.898109E-05 - 3.240008E+01 9.000000E+01 6 4.320847E-06 1.799996E+02 -4.320847E-06 2.844953E-11 - 3.250008E+01 0.000000E+00 1 4.087568E+01 8.994541E+01 3.894788E-02 4.087566E+01 - 3.250008E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.250008E+01 0.000000E+00 3 1.895135E+02 2.358895E-01 1.895119E+02 7.802342E-01 - 3.250008E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.250008E+01 0.000000E+00 5 4.279817E+02 8.994541E+01 4.077779E-01 4.279815E+02 - 3.250008E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.250008E+01 3.000000E+01 1 3.549810E+01 8.994541E+01 3.382239E-02 3.549809E+01 - 3.250008E+01 3.000000E+01 2 2.166137E+01 8.993842E+01 2.328165E-02 2.166136E+01 - 3.250008E+01 3.000000E+01 3 1.901080E+02 2.362162E-01 1.901064E+02 7.837657E-01 - 3.250008E+01 3.000000E+01 4 7.018360E+01 8.993809E+01 7.584215E-02 7.018356E+01 - 3.250008E+01 3.000000E+01 5 3.716557E+02 8.994541E+01 3.541102E-01 3.716555E+02 - 3.250008E+01 3.000000E+01 6 4.970701E+01 -5.519501E-04 4.970701E+01 -4.788449E-04 - 3.250008E+01 6.000000E+01 1 2.060950E+01 8.994542E+01 1.963478E-02 2.060949E+01 - 3.250008E+01 6.000000E+01 2 3.774897E+01 8.993842E+01 4.057537E-02 3.774894E+01 - 3.250008E+01 6.000000E+01 3 1.913042E+02 2.368745E-01 1.913026E+02 7.908953E-01 - 3.250008E+01 6.000000E+01 4 1.229697E+02 8.993842E+01 1.321773E-01 1.229697E+02 - 3.250008E+01 6.000000E+01 5 2.157487E+02 8.994541E+01 2.055700E-01 2.157487E+02 - 3.250008E+01 6.000000E+01 6 5.002107E+01 -5.507733E-04 5.002107E+01 -4.808429E-04 - 3.250008E+01 9.000000E+01 1 2.135361E-06 -9.004021E+01 -1.498625E-09 -2.135360E-06 - 3.250008E+01 9.000000E+01 2 4.372243E+01 8.993842E+01 4.699778E-02 4.372240E+01 - 3.250008E+01 9.000000E+01 3 1.919054E+02 2.372008E-01 1.919038E+02 7.944735E-01 - 3.250008E+01 9.000000E+01 4 1.428095E+02 8.993858E+01 1.530993E-01 1.428094E+02 - 3.250008E+01 9.000000E+01 5 9.868251E-05 -8.999285E+01 1.230938E-08 -9.868251E-05 - 3.250008E+01 9.000000E+01 6 4.292944E-06 1.799996E+02 -4.292944E-06 2.788391E-11 - 3.260007E+01 0.000000E+00 1 4.075017E+01 8.994576E+01 3.857466E-02 4.075015E+01 - 3.260007E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.260007E+01 0.000000E+00 3 1.896254E+02 2.343947E-01 1.896239E+02 7.757479E-01 - 3.260007E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.260007E+01 0.000000E+00 5 4.268635E+02 8.994576E+01 4.040548E-01 4.268633E+02 - 3.260007E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.260007E+01 3.000000E+01 1 3.538857E+01 8.994576E+01 3.349778E-02 3.538855E+01 - 3.260007E+01 3.000000E+01 2 2.159455E+01 8.993884E+01 2.304880E-02 2.159454E+01 - 3.260007E+01 3.000000E+01 3 1.902169E+02 2.347176E-01 1.902153E+02 7.792391E-01 - 3.260007E+01 3.000000E+01 4 6.995581E+01 8.993851E+01 7.506908E-02 6.995577E+01 - 3.260007E+01 3.000000E+01 5 3.706799E+02 8.994576E+01 3.508785E-01 3.706798E+02 - 3.260007E+01 3.000000E+01 6 4.939045E+01 -5.444839E-04 4.939045E+01 -4.693592E-04 - 3.260007E+01 6.000000E+01 1 2.054506E+01 8.994577E+01 1.944564E-02 2.054505E+01 - 3.260007E+01 6.000000E+01 2 3.763100E+01 8.993884E+01 4.016798E-02 3.763098E+01 - 3.260007E+01 6.000000E+01 3 1.914061E+02 2.353635E-01 1.914045E+02 7.862688E-01 - 3.260007E+01 6.000000E+01 4 1.225619E+02 8.993884E+01 1.308252E-01 1.225618E+02 - 3.260007E+01 6.000000E+01 5 2.151736E+02 8.994576E+01 2.036822E-01 2.151735E+02 - 3.260007E+01 6.000000E+01 6 4.970055E+01 -5.433299E-04 4.970055E+01 -4.713051E-04 - 3.260007E+01 9.000000E+01 1 2.128597E-06 -9.003999E+01 -1.485917E-09 -2.128596E-06 - 3.260007E+01 9.000000E+01 2 4.358488E+01 8.993884E+01 4.652485E-02 4.358485E+01 - 3.260007E+01 9.000000E+01 3 1.920032E+02 2.356875E-01 1.920016E+02 7.898074E-01 - 3.260007E+01 9.000000E+01 4 1.423310E+02 8.993900E+01 1.515296E-01 1.423309E+02 - 3.260007E+01 9.000000E+01 5 9.838604E-05 -8.999291E+01 1.216779E-08 -9.838604E-05 - 3.260007E+01 9.000000E+01 6 4.265306E-06 1.799996E+02 -4.265306E-06 2.733150E-11 - 3.270007E+01 0.000000E+00 1 4.062551E+01 8.994612E+01 3.820643E-02 4.062550E+01 - 3.270007E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.270007E+01 0.000000E+00 3 1.897361E+02 2.329117E-01 1.897345E+02 7.712896E-01 - 3.270007E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.270007E+01 0.000000E+00 5 4.257521E+02 8.994612E+01 4.003795E-01 4.257519E+02 - 3.270007E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.270007E+01 3.000000E+01 1 3.527961E+01 8.994612E+01 3.317728E-02 3.527960E+01 - 3.270007E+01 3.000000E+01 2 2.152806E+01 8.993927E+01 2.281912E-02 2.152805E+01 - 3.270007E+01 3.000000E+01 3 1.903243E+02 2.332301E-01 1.903228E+02 7.747384E-01 - 3.270007E+01 3.000000E+01 4 6.972990E+01 8.993894E+01 7.430685E-02 6.972986E+01 - 3.270007E+01 3.000000E+01 5 3.697094E+02 8.994612E+01 3.476809E-01 3.697092E+02 - 3.270007E+01 3.000000E+01 6 4.907703E+01 -5.371456E-04 4.907703E+01 -4.600952E-04 - 3.270007E+01 6.000000E+01 1 2.048114E+01 8.994613E+01 1.925889E-02 2.048113E+01 - 3.270007E+01 6.000000E+01 2 3.751371E+01 8.993926E+01 3.976609E-02 3.751369E+01 - 3.270007E+01 6.000000E+01 3 1.915064E+02 2.338690E-01 1.915048E+02 7.816854E-01 - 3.270007E+01 6.000000E+01 4 1.221573E+02 8.993926E+01 1.294923E-01 1.221572E+02 - 3.270007E+01 6.000000E+01 5 2.146027E+02 8.994612E+01 2.018178E-01 2.146026E+02 - 3.270007E+01 6.000000E+01 6 4.938311E+01 -5.360143E-04 4.938311E+01 -4.619896E-04 - 3.270007E+01 9.000000E+01 1 2.121884E-06 -9.003978E+01 -1.473344E-09 -2.121883E-06 - 3.270007E+01 9.000000E+01 2 4.344816E+01 8.993926E+01 4.605846E-02 4.344814E+01 - 3.270007E+01 9.000000E+01 3 1.921006E+02 2.341865E-01 1.920990E+02 7.851754E-01 - 3.270007E+01 9.000000E+01 4 1.418556E+02 8.993942E+01 1.499822E-01 1.418555E+02 - 3.270007E+01 9.000000E+01 5 9.809092E-05 -8.999297E+01 1.202839E-08 -9.809092E-05 - 3.270007E+01 9.000000E+01 6 4.237947E-06 1.799996E+02 -4.237947E-06 2.679195E-11 - 3.280007E+01 0.000000E+00 1 4.050157E+01 8.994647E+01 3.784274E-02 4.050155E+01 - 3.280007E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.280007E+01 0.000000E+00 3 1.898468E+02 2.314430E-01 1.898453E+02 7.668732E-01 - 3.280007E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.280007E+01 0.000000E+00 5 4.246447E+02 8.994647E+01 3.967502E-01 4.246445E+02 - 3.280007E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.280007E+01 3.000000E+01 1 3.517133E+01 8.994647E+01 3.286090E-02 3.517131E+01 - 3.280007E+01 3.000000E+01 2 2.146205E+01 8.993969E+01 2.259255E-02 2.146204E+01 - 3.280007E+01 3.000000E+01 3 1.904306E+02 2.317582E-01 1.904290E+02 7.702790E-01 - 3.280007E+01 3.000000E+01 4 6.950526E+01 8.993936E+01 7.355542E-02 6.950522E+01 - 3.280007E+01 3.000000E+01 5 3.687395E+02 8.994647E+01 3.445204E-01 3.687393E+02 - 3.280007E+01 3.000000E+01 6 4.876656E+01 -5.299335E-04 4.876656E+01 -4.510460E-04 - 3.280007E+01 6.000000E+01 1 2.041751E+01 8.994647E+01 1.907471E-02 2.041751E+01 - 3.280007E+01 6.000000E+01 2 3.739711E+01 8.993969E+01 3.936956E-02 3.739709E+01 - 3.280007E+01 6.000000E+01 3 1.916055E+02 2.323883E-01 1.916039E+02 7.771385E-01 - 3.280007E+01 6.000000E+01 4 1.217550E+02 8.993969E+01 1.281774E-01 1.217549E+02 - 3.280007E+01 6.000000E+01 5 2.140330E+02 8.994647E+01 1.999796E-01 2.140329E+02 - 3.280007E+01 6.000000E+01 6 4.906877E+01 -5.288246E-04 4.906877E+01 -4.528915E-04 - 3.280007E+01 9.000000E+01 1 2.115198E-06 -9.003957E+01 -1.460903E-09 -2.115197E-06 - 3.280007E+01 9.000000E+01 2 4.331230E+01 8.993968E+01 4.559829E-02 4.331228E+01 - 3.280007E+01 9.000000E+01 3 1.921956E+02 2.327027E-01 1.921940E+02 7.805864E-01 - 3.280007E+01 9.000000E+01 4 1.413835E+02 8.993983E+01 1.484559E-01 1.413834E+02 - 3.280007E+01 9.000000E+01 5 9.779726E-05 -8.999303E+01 1.189116E-08 -9.779726E-05 - 3.280007E+01 9.000000E+01 6 4.210858E-06 1.799996E+02 -4.210858E-06 2.626491E-11 - 3.290007E+01 0.000000E+00 1 4.037837E+01 8.994681E+01 3.748371E-02 4.037835E+01 - 3.290007E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.290007E+01 0.000000E+00 3 1.899555E+02 2.299896E-01 1.899539E+02 7.624938E-01 - 3.290007E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.290007E+01 0.000000E+00 5 4.235428E+02 8.994682E+01 3.931653E-01 4.235426E+02 - 3.290007E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.290007E+01 3.000000E+01 1 3.506364E+01 8.994682E+01 3.254865E-02 3.506363E+01 - 3.290007E+01 3.000000E+01 2 2.139643E+01 8.994010E+01 2.236903E-02 2.139642E+01 - 3.290007E+01 3.000000E+01 3 1.905367E+02 2.302989E-01 1.905351E+02 7.658550E-01 - 3.290007E+01 3.000000E+01 4 6.928204E+01 8.993978E+01 7.281420E-02 6.928200E+01 - 3.290007E+01 3.000000E+01 5 3.677775E+02 8.994682E+01 3.413959E-01 3.677773E+02 - 3.290007E+01 3.000000E+01 6 4.845910E+01 -5.228421E-04 4.845910E+01 -4.422046E-04 - 3.290007E+01 6.000000E+01 1 2.035437E+01 8.994682E+01 1.889274E-02 2.035436E+01 - 3.290007E+01 6.000000E+01 2 3.728128E+01 8.994009E+01 3.897846E-02 3.728126E+01 - 3.290007E+01 6.000000E+01 3 1.917040E+02 2.309203E-01 1.917024E+02 7.726262E-01 - 3.290007E+01 6.000000E+01 4 1.213558E+02 8.994009E+01 1.268805E-01 1.213557E+02 - 3.290007E+01 6.000000E+01 5 2.134662E+02 8.994681E+01 1.981611E-01 2.134661E+02 - 3.290007E+01 6.000000E+01 6 4.875742E+01 -5.217555E-04 4.875742E+01 -4.440022E-04 - 3.290007E+01 9.000000E+01 1 2.108570E-06 -9.003937E+01 -1.448598E-09 -2.108569E-06 - 3.290007E+01 9.000000E+01 2 4.317736E+01 8.994009E+01 4.514453E-02 4.317733E+01 - 3.290007E+01 9.000000E+01 3 1.922909E+02 2.312311E-01 1.922893E+02 7.760345E-01 - 3.290007E+01 9.000000E+01 4 1.409151E+02 8.994025E+01 1.469510E-01 1.409151E+02 - 3.290007E+01 9.000000E+01 5 9.750568E-05 -8.999309E+01 1.175602E-08 -9.750568E-05 - 3.290007E+01 9.000000E+01 6 4.184036E-06 1.799996E+02 -4.184036E-06 2.575009E-11 - 3.300007E+01 0.000000E+00 1 4.025585E+01 8.994716E+01 3.712926E-02 4.025583E+01 - 3.300007E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.300007E+01 0.000000E+00 3 1.900640E+02 2.285481E-01 1.900625E+02 7.581477E-01 - 3.300007E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.300007E+01 0.000000E+00 5 4.224463E+02 8.994716E+01 3.896166E-01 4.224461E+02 - 3.300007E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.300007E+01 3.000000E+01 1 3.495679E+01 8.994716E+01 3.224034E-02 3.495678E+01 - 3.300007E+01 3.000000E+01 2 2.133117E+01 8.994051E+01 2.214840E-02 2.133116E+01 - 3.300007E+01 3.000000E+01 3 1.906416E+02 2.288531E-01 1.906401E+02 7.614663E-01 - 3.300007E+01 3.000000E+01 4 6.906031E+01 8.994020E+01 7.208294E-02 6.906027E+01 - 3.300007E+01 3.000000E+01 5 3.668197E+02 8.994716E+01 3.383159E-01 3.668195E+02 - 3.300007E+01 3.000000E+01 6 4.815453E+01 -5.158705E-04 4.815453E+01 -4.335660E-04 - 3.300007E+01 6.000000E+01 1 2.029157E+01 8.994717E+01 1.871317E-02 2.029156E+01 - 3.300007E+01 6.000000E+01 2 3.716633E+01 8.994051E+01 3.859261E-02 3.716631E+01 - 3.300007E+01 6.000000E+01 3 1.918021E+02 2.294670E-01 1.918006E+02 7.681569E-01 - 3.300007E+01 6.000000E+01 4 1.209585E+02 8.994051E+01 1.256014E-01 1.209585E+02 - 3.300007E+01 6.000000E+01 5 2.129026E+02 8.994716E+01 1.963649E-01 2.129025E+02 - 3.300007E+01 6.000000E+01 6 4.844903E+01 -5.148064E-04 4.844903E+01 -4.353177E-04 - 3.300007E+01 9.000000E+01 1 2.101973E-06 -9.003915E+01 -1.436424E-09 -2.101973E-06 - 3.300007E+01 9.000000E+01 2 4.304322E+01 8.994051E+01 4.469663E-02 4.304320E+01 - 3.300007E+01 9.000000E+01 3 1.923854E+02 2.297733E-01 1.923839E+02 7.715214E-01 - 3.300007E+01 9.000000E+01 4 1.404492E+02 8.994066E+01 1.454666E-01 1.404491E+02 - 3.300007E+01 9.000000E+01 5 9.721555E-05 -8.999316E+01 1.162294E-08 -9.721555E-05 - 3.300007E+01 9.000000E+01 6 4.157459E-06 1.799996E+02 -4.157459E-06 2.524701E-11 - 3.310007E+01 0.000000E+00 1 4.013415E+01 8.994749E+01 3.677930E-02 4.013413E+01 - 3.310007E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.310007E+01 0.000000E+00 3 1.901713E+02 2.271214E-01 1.901698E+02 7.538400E-01 - 3.310007E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.310007E+01 0.000000E+00 5 4.213561E+02 8.994750E+01 3.861173E-01 4.213559E+02 - 3.310007E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.310007E+01 3.000000E+01 1 3.485051E+01 8.994750E+01 3.193597E-02 3.485050E+01 - 3.310007E+01 3.000000E+01 2 2.126639E+01 8.994092E+01 2.193080E-02 2.126638E+01 - 3.310007E+01 3.000000E+01 3 1.907446E+02 2.274259E-01 1.907431E+02 7.571262E-01 - 3.310007E+01 3.000000E+01 4 6.884032E+01 8.994061E+01 7.136160E-02 6.884028E+01 - 3.310007E+01 3.000000E+01 5 3.658636E+02 8.994749E+01 3.352709E-01 3.658634E+02 - 3.310007E+01 3.000000E+01 6 4.785292E+01 -5.090184E-04 4.785292E+01 -4.251276E-04 - 3.310007E+01 6.000000E+01 1 2.022916E+01 8.994750E+01 1.853587E-02 2.022915E+01 - 3.310007E+01 6.000000E+01 2 3.705191E+01 8.994091E+01 3.821192E-02 3.705189E+01 - 3.310007E+01 6.000000E+01 3 1.918990E+02 2.280288E-01 1.918974E+02 7.637275E-01 - 3.310007E+01 6.000000E+01 4 1.205647E+02 8.994091E+01 1.243399E-01 1.205647E+02 - 3.310007E+01 6.000000E+01 5 2.123428E+02 8.994749E+01 1.945905E-01 2.123427E+02 - 3.310007E+01 6.000000E+01 6 4.814366E+01 -5.079747E-04 4.814366E+01 -4.268336E-04 - 3.310007E+01 9.000000E+01 1 2.095427E-06 -9.003895E+01 -1.424380E-09 -2.095426E-06 - 3.310007E+01 9.000000E+01 2 4.290991E+01 8.994091E+01 4.425495E-02 4.290989E+01 - 3.310007E+01 9.000000E+01 3 1.924789E+02 2.283318E-01 1.924774E+02 7.670537E-01 - 3.310007E+01 9.000000E+01 4 1.399865E+02 8.994106E+01 1.440035E-01 1.399864E+02 - 3.310007E+01 9.000000E+01 5 9.692730E-05 -8.999321E+01 1.149185E-08 -9.692730E-05 - 3.310007E+01 9.000000E+01 6 4.131145E-06 1.799996E+02 -4.131145E-06 2.475558E-11 - 3.320007E+01 0.000000E+00 1 4.001321E+01 8.994783E+01 3.643377E-02 4.001320E+01 - 3.320007E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.320007E+01 0.000000E+00 3 1.902766E+02 2.257106E-01 1.902751E+02 7.495722E-01 - 3.320007E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.320007E+01 0.000000E+00 5 4.202658E+02 8.994784E+01 3.826576E-01 4.202656E+02 - 3.320007E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.320007E+01 3.000000E+01 1 3.474481E+01 8.994784E+01 3.163544E-02 3.474479E+01 - 3.320007E+01 3.000000E+01 2 2.120192E+01 8.994132E+01 2.171606E-02 2.120191E+01 - 3.320007E+01 3.000000E+01 3 1.908476E+02 2.260078E-01 1.908461E+02 7.528118E-01 - 3.320007E+01 3.000000E+01 4 6.862160E+01 8.994101E+01 7.065042E-02 6.862156E+01 - 3.320007E+01 3.000000E+01 5 3.649148E+02 8.994784E+01 3.322608E-01 3.649147E+02 - 3.320007E+01 3.000000E+01 6 4.755409E+01 -5.022815E-04 4.755409E+01 -4.168813E-04 - 3.320007E+01 6.000000E+01 1 2.016714E+01 8.994784E+01 1.836078E-02 2.016713E+01 - 3.320007E+01 6.000000E+01 2 3.693820E+01 8.994131E+01 3.783626E-02 3.693818E+01 - 3.320007E+01 6.000000E+01 3 1.919947E+02 2.266037E-01 1.919932E+02 7.593333E-01 - 3.320007E+01 6.000000E+01 4 1.201731E+02 8.994131E+01 1.230952E-01 1.201731E+02 - 3.320007E+01 6.000000E+01 5 2.117833E+02 8.994784E+01 1.928348E-01 2.117832E+02 - 3.320007E+01 6.000000E+01 6 4.784115E+01 -5.012579E-04 4.784115E+01 -4.185432E-04 - 3.320007E+01 9.000000E+01 1 2.088918E-06 -9.003874E+01 -1.412462E-09 -2.088917E-06 - 3.320007E+01 9.000000E+01 2 4.277749E+01 8.994131E+01 4.381904E-02 4.277747E+01 - 3.320007E+01 9.000000E+01 3 1.925713E+02 2.269027E-01 1.925698E+02 7.626185E-01 - 3.320007E+01 9.000000E+01 4 1.395276E+02 8.994146E+01 1.425587E-01 1.395276E+02 - 3.320007E+01 9.000000E+01 5 9.664099E-05 -8.999326E+01 1.136279E-08 -9.664099E-05 - 3.320007E+01 9.000000E+01 6 4.105087E-06 1.799997E+02 -4.105087E-06 2.427533E-11 - 3.330006E+01 0.000000E+00 1 3.989290E+01 8.994817E+01 3.609265E-02 3.989289E+01 - 3.330006E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.330006E+01 0.000000E+00 3 1.903828E+02 2.243082E-01 1.903813E+02 7.453308E-01 - 3.330006E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.330006E+01 0.000000E+00 5 4.191859E+02 8.994817E+01 3.792374E-01 4.191858E+02 - 3.330006E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.330006E+01 3.000000E+01 1 3.463985E+01 8.994817E+01 3.133862E-02 3.463984E+01 - 3.330006E+01 3.000000E+01 2 2.113789E+01 8.994171E+01 2.150420E-02 2.113788E+01 - 3.330006E+01 3.000000E+01 3 1.909505E+02 2.246025E-01 1.909490E+02 7.485340E-01 - 3.330006E+01 3.000000E+01 4 6.840399E+01 8.994141E+01 6.994873E-02 6.840395E+01 - 3.330006E+01 3.000000E+01 5 3.639682E+02 8.994817E+01 3.292862E-01 3.639681E+02 - 3.330006E+01 3.000000E+01 6 4.725818E+01 -4.956563E-04 4.725818E+01 -4.088227E-04 - 3.330006E+01 6.000000E+01 1 2.010546E+01 8.994817E+01 1.818799E-02 2.010545E+01 - 3.330006E+01 6.000000E+01 2 3.682528E+01 8.994171E+01 3.746574E-02 3.682526E+01 - 3.330006E+01 6.000000E+01 3 1.920908E+02 2.251912E-01 1.920893E+02 7.549779E-01 - 3.330006E+01 6.000000E+01 4 1.197841E+02 8.994171E+01 1.218680E-01 1.197840E+02 - 3.330006E+01 6.000000E+01 5 2.112272E+02 8.994817E+01 1.911036E-01 2.112271E+02 - 3.330006E+01 6.000000E+01 6 4.754157E+01 -4.946532E-04 4.754157E+01 -4.104419E-04 - 3.330006E+01 9.000000E+01 1 2.082450E-06 -9.003854E+01 -1.400675E-09 -2.082449E-06 - 3.330006E+01 9.000000E+01 2 4.264584E+01 8.994171E+01 4.338904E-02 4.264582E+01 - 3.330006E+01 9.000000E+01 3 1.926637E+02 2.254867E-01 1.926622E+02 7.582231E-01 - 3.330006E+01 9.000000E+01 4 1.390710E+02 8.994186E+01 1.411347E-01 1.390710E+02 - 3.330006E+01 9.000000E+01 5 9.635598E-05 -8.999332E+01 1.123567E-08 -9.635598E-05 - 3.330006E+01 9.000000E+01 6 4.079272E-06 1.799997E+02 -4.079272E-06 2.380602E-11 - 3.340006E+01 0.000000E+00 1 3.977332E+01 8.994849E+01 3.575583E-02 3.977330E+01 - 3.340006E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.340006E+01 0.000000E+00 3 1.904877E+02 2.229205E-01 1.904863E+02 7.411280E-01 - 3.340006E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.340006E+01 0.000000E+00 5 4.181083E+02 8.994849E+01 3.758605E-01 4.181081E+02 - 3.340006E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.340006E+01 3.000000E+01 1 3.453543E+01 8.994849E+01 3.104566E-02 3.453542E+01 - 3.340006E+01 3.000000E+01 2 2.107421E+01 8.994210E+01 2.129508E-02 2.107420E+01 - 3.340006E+01 3.000000E+01 3 1.910508E+02 2.232130E-01 1.910493E+02 7.442940E-01 - 3.340006E+01 3.000000E+01 4 6.818805E+01 8.994181E+01 6.925596E-02 6.818801E+01 - 3.340006E+01 3.000000E+01 5 3.630287E+02 8.994849E+01 3.263490E-01 3.630285E+02 - 3.340006E+01 3.000000E+01 6 4.696491E+01 -4.891424E-04 4.696491E+01 -4.009463E-04 - 3.340006E+01 6.000000E+01 1 2.004414E+01 8.994849E+01 1.801731E-02 2.004414E+01 - 3.340006E+01 6.000000E+01 2 3.671303E+01 8.994210E+01 3.709995E-02 3.671301E+01 - 3.340006E+01 6.000000E+01 3 1.921849E+02 2.237944E-01 1.921834E+02 7.506623E-01 - 3.340006E+01 6.000000E+01 4 1.193978E+02 8.994210E+01 1.206570E-01 1.193977E+02 - 3.340006E+01 6.000000E+01 5 2.106739E+02 8.994849E+01 1.893928E-01 2.106738E+02 - 3.340006E+01 6.000000E+01 6 4.724491E+01 -4.881580E-04 4.724491E+01 -4.025249E-04 - 3.340006E+01 9.000000E+01 1 2.076021E-06 -9.003834E+01 -1.389009E-09 -2.076020E-06 - 3.340006E+01 9.000000E+01 2 4.251513E+01 8.994210E+01 4.296470E-02 4.251511E+01 - 3.340006E+01 9.000000E+01 3 1.927546E+02 2.240849E-01 1.927531E+02 7.538652E-01 - 3.340006E+01 9.000000E+01 4 1.386183E+02 8.994225E+01 1.397293E-01 1.386183E+02 - 3.340006E+01 9.000000E+01 5 9.607337E-05 -8.999338E+01 1.111041E-08 -9.607337E-05 - 3.340006E+01 9.000000E+01 6 4.053707E-06 1.799997E+02 -4.053707E-06 2.334736E-11 - 3.350006E+01 0.000000E+00 1 3.965461E+01 8.994881E+01 3.542322E-02 3.965459E+01 - 3.350006E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.350006E+01 0.000000E+00 3 1.905910E+02 2.215475E-01 1.905896E+02 7.369626E-01 - 3.350006E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.350006E+01 0.000000E+00 5 4.170345E+02 8.994881E+01 3.725198E-01 4.170343E+02 - 3.350006E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.350006E+01 3.000000E+01 1 3.443173E+01 8.994881E+01 3.075631E-02 3.443172E+01 - 3.350006E+01 3.000000E+01 2 2.101094E+01 8.994249E+01 2.108870E-02 2.101093E+01 - 3.350006E+01 3.000000E+01 3 1.911513E+02 2.218343E-01 1.911499E+02 7.400862E-01 - 3.350006E+01 3.000000E+01 4 6.797367E+01 8.994220E+01 6.857287E-02 6.797363E+01 - 3.350006E+01 3.000000E+01 5 3.620924E+02 8.994881E+01 3.234438E-01 3.620922E+02 - 3.350006E+01 3.000000E+01 6 4.667448E+01 -4.827369E-04 4.667448E+01 -3.932487E-04 - 3.350006E+01 6.000000E+01 1 1.998332E+01 8.994882E+01 1.784883E-02 1.998331E+01 - 3.350006E+01 6.000000E+01 2 3.660141E+01 8.994249E+01 3.673913E-02 3.660139E+01 - 3.350006E+01 6.000000E+01 3 1.922785E+02 2.224091E-01 1.922771E+02 7.463794E-01 - 3.350006E+01 6.000000E+01 4 1.190141E+02 8.994249E+01 1.194625E-01 1.190140E+02 - 3.350006E+01 6.000000E+01 5 2.101224E+02 8.994881E+01 1.877010E-01 2.101223E+02 - 3.350006E+01 6.000000E+01 6 4.695098E+01 -4.817709E-04 4.695098E+01 -3.947868E-04 - 3.350006E+01 9.000000E+01 1 2.069632E-06 -9.003814E+01 -1.377468E-09 -2.069631E-06 - 3.350006E+01 9.000000E+01 2 4.238506E+01 8.994249E+01 4.254586E-02 4.238503E+01 - 3.350006E+01 9.000000E+01 3 1.928446E+02 2.226968E-01 1.928431E+02 7.495451E-01 - 3.350006E+01 9.000000E+01 4 1.381679E+02 8.994263E+01 1.383440E-01 1.381678E+02 - 3.350006E+01 9.000000E+01 5 9.579137E-05 -8.999342E+01 1.098708E-08 -9.579137E-05 - 3.350006E+01 9.000000E+01 6 4.028387E-06 1.799997E+02 -4.028387E-06 2.289907E-11 - 3.360006E+01 0.000000E+00 1 3.953648E+01 8.994914E+01 3.509463E-02 3.953646E+01 - 3.360006E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.360006E+01 0.000000E+00 3 1.906935E+02 2.201875E-01 1.906921E+02 7.328328E-01 - 3.360006E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.360006E+01 0.000000E+00 5 4.159681E+02 8.994914E+01 3.692213E-01 4.159680E+02 - 3.360006E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.360006E+01 3.000000E+01 1 3.432856E+01 8.994914E+01 3.047062E-02 3.432855E+01 - 3.360006E+01 3.000000E+01 2 2.094806E+01 8.994288E+01 2.088508E-02 2.094805E+01 - 3.360006E+01 3.000000E+01 3 1.912510E+02 2.204702E-01 1.912496E+02 7.359189E-01 - 3.360006E+01 3.000000E+01 4 6.776035E+01 8.994259E+01 6.789912E-02 6.776032E+01 - 3.360006E+01 3.000000E+01 5 3.611580E+02 8.994914E+01 3.205728E-01 3.611579E+02 - 3.360006E+01 3.000000E+01 6 4.638676E+01 -4.764366E-04 4.638676E+01 -3.857239E-04 - 3.360006E+01 6.000000E+01 1 1.992280E+01 8.994914E+01 1.768249E-02 1.992279E+01 - 3.360006E+01 6.000000E+01 2 3.649052E+01 8.994288E+01 3.638297E-02 3.649050E+01 - 3.360006E+01 6.000000E+01 3 1.923710E+02 2.210367E-01 1.923696E+02 7.421306E-01 - 3.360006E+01 6.000000E+01 4 1.186326E+02 8.994288E+01 1.182837E-01 1.186326E+02 - 3.360006E+01 6.000000E+01 5 2.095754E+02 8.994914E+01 1.860294E-01 2.095753E+02 - 3.360006E+01 6.000000E+01 6 4.665978E+01 -4.754898E-04 4.665978E+01 -3.872231E-04 - 3.360006E+01 9.000000E+01 1 2.063289E-06 -9.003794E+01 -1.366047E-09 -2.063289E-06 - 3.360006E+01 9.000000E+01 2 4.225586E+01 8.994287E+01 4.213268E-02 4.225583E+01 - 3.360006E+01 9.000000E+01 3 1.929343E+02 2.213204E-01 1.929328E+02 7.452589E-01 - 3.360006E+01 9.000000E+01 4 1.377205E+02 8.994302E+01 1.369766E-01 1.377205E+02 - 3.360006E+01 9.000000E+01 5 9.551140E-05 -8.999348E+01 1.086559E-08 -9.551140E-05 - 3.360006E+01 9.000000E+01 6 4.003303E-06 1.799997E+02 -4.003303E-06 2.246091E-11 - 3.370006E+01 0.000000E+00 1 3.941903E+01 8.994946E+01 3.477030E-02 3.941902E+01 - 3.370006E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.370006E+01 0.000000E+00 3 1.907948E+02 2.188378E-01 1.907935E+02 7.287277E-01 - 3.370006E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.370006E+01 0.000000E+00 5 4.149079E+02 8.994947E+01 3.659608E-01 4.149077E+02 - 3.370006E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.370006E+01 3.000000E+01 1 3.422599E+01 8.994947E+01 3.018847E-02 3.422598E+01 - 3.370006E+01 3.000000E+01 2 2.088553E+01 8.994326E+01 2.068408E-02 2.088552E+01 - 3.370006E+01 3.000000E+01 3 1.913493E+02 2.191173E-01 1.913479E+02 7.317789E-01 - 3.370006E+01 3.000000E+01 4 6.754848E+01 8.994297E+01 6.723402E-02 6.754845E+01 - 3.370006E+01 3.000000E+01 5 3.602292E+02 8.994947E+01 3.177367E-01 3.602291E+02 - 3.370006E+01 3.000000E+01 6 4.610175E+01 -4.702416E-04 4.610175E+01 -3.783692E-04 - 3.370006E+01 6.000000E+01 1 1.986265E+01 8.994947E+01 1.751814E-02 1.986264E+01 - 3.370006E+01 6.000000E+01 2 3.638029E+01 8.994325E+01 3.603162E-02 3.638027E+01 - 3.370006E+01 6.000000E+01 3 1.924628E+02 2.196764E-01 1.924614E+02 7.379153E-01 - 3.370006E+01 6.000000E+01 4 1.182544E+02 8.994325E+01 1.171209E-01 1.182544E+02 - 3.370006E+01 6.000000E+01 5 2.090304E+02 8.994946E+01 1.843785E-01 2.090303E+02 - 3.370006E+01 6.000000E+01 6 4.637133E+01 -4.693134E-04 4.637133E+01 -3.798305E-04 - 3.370006E+01 9.000000E+01 1 2.056978E-06 -9.003773E+01 -1.354751E-09 -2.056977E-06 - 3.370006E+01 9.000000E+01 2 4.212744E+01 8.994325E+01 4.172492E-02 4.212742E+01 - 3.370006E+01 9.000000E+01 3 1.930227E+02 2.199568E-01 1.930213E+02 7.410066E-01 - 3.370006E+01 9.000000E+01 4 1.372767E+02 8.994340E+01 1.356272E-01 1.372766E+02 - 3.370006E+01 9.000000E+01 5 9.523307E-05 -8.999354E+01 1.074594E-08 -9.523307E-05 - 3.370006E+01 9.000000E+01 6 3.978461E-06 1.799997E+02 -3.978461E-06 2.203259E-11 - 3.380006E+01 0.000000E+00 1 3.930218E+01 8.994978E+01 3.444978E-02 3.930216E+01 - 3.380006E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.380006E+01 0.000000E+00 3 1.908964E+02 2.174999E-01 1.908950E+02 7.246583E-01 - 3.380006E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.380006E+01 0.000000E+00 5 4.138488E+02 8.994978E+01 3.627357E-01 4.138487E+02 - 3.380006E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.380006E+01 3.000000E+01 1 3.412407E+01 8.994978E+01 2.990977E-02 3.412405E+01 - 3.380006E+01 3.000000E+01 2 2.082336E+01 8.994363E+01 2.048573E-02 2.082335E+01 - 3.380006E+01 3.000000E+01 3 1.914473E+02 2.177773E-01 1.914459E+02 7.276760E-01 - 3.380006E+01 3.000000E+01 4 6.733807E+01 8.994335E+01 6.657772E-02 6.733804E+01 - 3.380006E+01 3.000000E+01 5 3.593055E+02 8.994978E+01 3.149348E-01 3.593054E+02 - 3.380006E+01 3.000000E+01 6 4.581934E+01 -4.641483E-04 4.581934E+01 -3.711787E-04 - 3.380006E+01 6.000000E+01 1 1.980288E+01 8.994979E+01 1.735591E-02 1.980288E+01 - 3.380006E+01 6.000000E+01 2 3.627076E+01 8.994363E+01 3.568467E-02 3.627074E+01 - 3.380006E+01 6.000000E+01 3 1.925543E+02 2.183298E-01 1.925529E+02 7.337406E-01 - 3.380006E+01 6.000000E+01 4 1.178778E+02 8.994363E+01 1.159738E-01 1.178778E+02 - 3.380006E+01 6.000000E+01 5 2.084864E+02 8.994978E+01 1.827458E-01 2.084863E+02 - 3.380006E+01 6.000000E+01 6 4.608560E+01 -4.632380E-04 4.608560E+01 -3.726034E-04 - 3.380006E+01 9.000000E+01 1 2.050707E-06 -9.003754E+01 -1.343575E-09 -2.050706E-06 - 3.380006E+01 9.000000E+01 2 4.199990E+01 8.994363E+01 4.132249E-02 4.199989E+01 - 3.380006E+01 9.000000E+01 3 1.931105E+02 2.186055E-01 1.931091E+02 7.367893E-01 - 3.380006E+01 9.000000E+01 4 1.368353E+02 8.994377E+01 1.342966E-01 1.368352E+02 - 3.380006E+01 9.000000E+01 5 9.495654E-05 -8.999359E+01 1.062802E-08 -9.495654E-05 - 3.380006E+01 9.000000E+01 6 3.953850E-06 1.799997E+02 -3.953850E-06 2.161383E-11 - 3.390005E+01 0.000000E+00 1 3.918617E+01 8.995010E+01 3.413335E-02 3.918615E+01 - 3.390005E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.390005E+01 0.000000E+00 3 1.909960E+02 2.161779E-01 1.909947E+02 7.206295E-01 - 3.390005E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.390005E+01 0.000000E+00 5 4.127961E+02 8.995010E+01 3.595535E-01 4.127960E+02 - 3.390005E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.390005E+01 3.000000E+01 1 3.402280E+01 8.995010E+01 2.963470E-02 3.402279E+01 - 3.390005E+01 3.000000E+01 2 2.076159E+01 8.994401E+01 2.028989E-02 2.076159E+01 - 3.390005E+01 3.000000E+01 3 1.915440E+02 2.164503E-01 1.915426E+02 7.236077E-01 - 3.390005E+01 3.000000E+01 4 6.712875E+01 8.994373E+01 6.593039E-02 6.712872E+01 - 3.390005E+01 3.000000E+01 5 3.583869E+02 8.995010E+01 3.121656E-01 3.583867E+02 - 3.390005E+01 3.000000E+01 6 4.553960E+01 -4.581544E-04 4.553960E+01 -3.641484E-04 - 3.390005E+01 6.000000E+01 1 1.974346E+01 8.995010E+01 1.719568E-02 1.974345E+01 - 3.390005E+01 6.000000E+01 2 3.616187E+01 8.994400E+01 3.534235E-02 3.616185E+01 - 3.390005E+01 6.000000E+01 3 1.926449E+02 2.169954E-01 1.926435E+02 7.295989E-01 - 3.390005E+01 6.000000E+01 4 1.175042E+02 8.994400E+01 1.148419E-01 1.175042E+02 - 3.390005E+01 6.000000E+01 5 2.079469E+02 8.995010E+01 1.811315E-01 2.079469E+02 - 3.390005E+01 6.000000E+01 6 4.580251E+01 -4.572622E-04 4.580251E+01 -3.655375E-04 - 3.390005E+01 9.000000E+01 1 2.044483E-06 -9.003735E+01 -1.332509E-09 -2.044482E-06 - 3.390005E+01 9.000000E+01 2 4.187303E+01 8.994400E+01 4.092541E-02 4.187301E+01 - 3.390005E+01 9.000000E+01 3 1.931985E+02 2.172666E-01 1.931971E+02 7.326102E-01 - 3.390005E+01 9.000000E+01 4 1.363971E+02 8.994414E+01 1.329831E-01 1.363971E+02 - 3.390005E+01 9.000000E+01 5 9.468116E-05 -8.999364E+01 1.051181E-08 -9.468116E-05 - 3.390005E+01 9.000000E+01 6 3.929469E-06 1.799997E+02 -3.929469E-06 2.120445E-11 - 3.400005E+01 0.000000E+00 1 3.907083E+01 8.995040E+01 3.382083E-02 3.907082E+01 - 3.400005E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.400005E+01 0.000000E+00 3 1.910952E+02 2.148654E-01 1.910939E+02 7.166262E-01 - 3.400005E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.400005E+01 0.000000E+00 5 4.117466E+02 8.995041E+01 3.564029E-01 4.117465E+02 - 3.400005E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.400005E+01 3.000000E+01 1 3.392203E+01 8.995040E+01 2.936275E-02 3.392202E+01 - 3.400005E+01 3.000000E+01 2 2.070027E+01 8.994438E+01 2.009663E-02 2.070026E+01 - 3.400005E+01 3.000000E+01 3 1.916397E+02 2.151350E-01 1.916384E+02 7.195699E-01 - 3.400005E+01 3.000000E+01 4 6.692104E+01 8.994410E+01 6.529147E-02 6.692101E+01 - 3.400005E+01 3.000000E+01 5 3.574666E+02 8.995040E+01 3.094259E-01 3.574665E+02 - 3.400005E+01 3.000000E+01 6 4.526242E+01 -4.522591E-04 4.526242E+01 -3.572749E-04 - 3.400005E+01 6.000000E+01 1 1.968440E+01 8.995041E+01 1.703744E-02 1.968439E+01 - 3.400005E+01 6.000000E+01 2 3.605368E+01 8.994437E+01 3.500450E-02 3.605367E+01 - 3.400005E+01 6.000000E+01 3 1.927338E+02 2.156741E-01 1.927324E+02 7.254912E-01 - 3.400005E+01 6.000000E+01 4 1.171330E+02 8.994437E+01 1.137248E-01 1.171329E+02 - 3.400005E+01 6.000000E+01 5 2.074086E+02 8.995040E+01 1.795366E-01 2.074086E+02 - 3.400005E+01 6.000000E+01 6 4.552207E+01 -4.513839E-04 4.552207E+01 -3.586290E-04 - 3.400005E+01 9.000000E+01 1 2.038288E-06 -9.003716E+01 -1.321565E-09 -2.038288E-06 - 3.400005E+01 9.000000E+01 2 4.174704E+01 8.994437E+01 4.053334E-02 4.174702E+01 - 3.400005E+01 9.000000E+01 3 1.932842E+02 2.159432E-01 1.932829E+02 7.284712E-01 - 3.400005E+01 9.000000E+01 4 1.359620E+02 8.994451E+01 1.316872E-01 1.359619E+02 - 3.400005E+01 9.000000E+01 5 9.440799E-05 -8.999369E+01 1.039739E-08 -9.440799E-05 - 3.400005E+01 9.000000E+01 6 3.905322E-06 1.799997E+02 -3.905322E-06 2.080413E-11 - 3.410005E+01 0.000000E+00 1 3.895607E+01 8.995071E+01 3.351206E-02 3.895606E+01 - 3.410005E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.410005E+01 0.000000E+00 3 1.911934E+02 2.135657E-01 1.911921E+02 7.126575E-01 - 3.410005E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.410005E+01 0.000000E+00 5 4.107012E+02 8.995071E+01 3.532951E-01 4.107010E+02 - 3.410005E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.410005E+01 3.000000E+01 1 3.382191E+01 8.995071E+01 2.909433E-02 3.382190E+01 - 3.410005E+01 3.000000E+01 2 2.063913E+01 8.994474E+01 1.990585E-02 2.063912E+01 - 3.410005E+01 3.000000E+01 3 1.917356E+02 2.138311E-01 1.917343E+02 7.155666E-01 - 3.410005E+01 3.000000E+01 4 6.671435E+01 8.994447E+01 6.466094E-02 6.671432E+01 - 3.410005E+01 3.000000E+01 5 3.565597E+02 8.995071E+01 3.067199E-01 3.565596E+02 - 3.410005E+01 3.000000E+01 6 4.498774E+01 -4.464596E-04 4.498774E+01 -3.505531E-04 - 3.410005E+01 6.000000E+01 1 1.962566E+01 8.995071E+01 1.688116E-02 1.962565E+01 - 3.410005E+01 6.000000E+01 2 3.594605E+01 8.994474E+01 3.467092E-02 3.594604E+01 - 3.410005E+01 6.000000E+01 3 1.928227E+02 2.143649E-01 1.928214E+02 7.214200E-01 - 3.410005E+01 6.000000E+01 4 1.167640E+02 8.994474E+01 1.126223E-01 1.167640E+02 - 3.410005E+01 6.000000E+01 5 2.068734E+02 8.995071E+01 1.779629E-01 2.068734E+02 - 3.410005E+01 6.000000E+01 6 4.524427E+01 -4.456003E-04 4.524427E+01 -3.518733E-04 - 3.410005E+01 9.000000E+01 1 2.032130E-06 -9.003696E+01 -1.310731E-09 -2.032130E-06 - 3.410005E+01 9.000000E+01 2 4.162177E+01 8.994473E+01 4.014638E-02 4.162175E+01 - 3.410005E+01 9.000000E+01 3 1.933700E+02 2.146287E-01 1.933686E+02 7.243579E-01 - 3.410005E+01 9.000000E+01 4 1.355293E+02 8.994487E+01 1.304089E-01 1.355293E+02 - 3.410005E+01 9.000000E+01 5 9.413626E-05 -8.999374E+01 1.028458E-08 -9.413626E-05 - 3.410005E+01 9.000000E+01 6 3.881387E-06 1.799997E+02 -3.881387E-06 2.041273E-11 - 3.420005E+01 0.000000E+00 1 3.884214E+01 8.995102E+01 3.320713E-02 3.884213E+01 - 3.420005E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.420005E+01 0.000000E+00 3 1.912910E+02 2.122780E-01 1.912897E+02 7.087221E-01 - 3.420005E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.420005E+01 0.000000E+00 5 4.096624E+02 8.995102E+01 3.502164E-01 4.096622E+02 - 3.420005E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.420005E+01 3.000000E+01 1 3.372246E+01 8.995102E+01 2.882922E-02 3.372245E+01 - 3.420005E+01 3.000000E+01 2 2.057844E+01 8.994510E+01 1.971754E-02 2.057843E+01 - 3.420005E+01 3.000000E+01 3 1.918292E+02 2.125403E-01 1.918279E+02 7.115940E-01 - 3.420005E+01 3.000000E+01 4 6.650908E+01 8.994484E+01 6.403850E-02 6.650905E+01 - 3.420005E+01 3.000000E+01 5 3.556488E+02 8.995102E+01 3.040474E-01 3.556487E+02 - 3.420005E+01 3.000000E+01 6 4.471568E+01 -4.407538E-04 4.471568E+01 -3.439801E-04 - 3.420005E+01 6.000000E+01 1 1.956731E+01 8.995103E+01 1.672681E-02 1.956731E+01 - 3.420005E+01 6.000000E+01 2 3.583922E+01 8.994510E+01 3.434163E-02 3.583920E+01 - 3.420005E+01 6.000000E+01 3 1.929110E+02 2.130659E-01 1.929097E+02 7.173767E-01 - 3.420005E+01 6.000000E+01 4 1.163975E+02 8.994510E+01 1.115347E-01 1.163975E+02 - 3.420005E+01 6.000000E+01 5 2.063403E+02 8.995102E+01 1.764052E-01 2.063403E+02 - 3.420005E+01 6.000000E+01 6 4.496900E+01 -4.399107E-04 4.496900E+01 -3.452670E-04 - 3.420005E+01 9.000000E+01 1 2.026014E-06 -9.003677E+01 -1.300017E-09 -2.026014E-06 - 3.420005E+01 9.000000E+01 2 4.149716E+01 8.994510E+01 3.976450E-02 4.149714E+01 - 3.420005E+01 9.000000E+01 3 1.934550E+02 2.133281E-01 1.934536E+02 7.202849E-01 - 3.420005E+01 9.000000E+01 4 1.350997E+02 8.994523E+01 1.291466E-01 1.350996E+02 - 3.420005E+01 9.000000E+01 5 9.386538E-05 -8.999379E+01 1.017344E-08 -9.386538E-05 - 3.420005E+01 9.000000E+01 6 3.857687E-06 1.799997E+02 -3.857687E-06 2.002991E-11 - 3.430005E+01 0.000000E+00 1 3.872882E+01 8.995132E+01 3.290593E-02 3.872881E+01 - 3.430005E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.430005E+01 0.000000E+00 3 1.913871E+02 2.110021E-01 1.913858E+02 7.048159E-01 - 3.430005E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.430005E+01 0.000000E+00 5 4.086259E+02 8.995132E+01 3.471771E-01 4.086258E+02 - 3.430005E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.430005E+01 3.000000E+01 1 3.362355E+01 8.995132E+01 2.856727E-02 3.362354E+01 - 3.430005E+01 3.000000E+01 2 2.051813E+01 8.994546E+01 1.953158E-02 2.051812E+01 - 3.430005E+01 3.000000E+01 3 1.919223E+02 2.112613E-01 1.919209E+02 7.076553E-01 - 3.430005E+01 3.000000E+01 4 6.630528E+01 8.994520E+01 6.342429E-02 6.630525E+01 - 3.430005E+01 3.000000E+01 5 3.547445E+02 8.995132E+01 3.014019E-01 3.547444E+02 - 3.430005E+01 3.000000E+01 6 4.444604E+01 -4.351407E-04 4.444604E+01 -3.375516E-04 - 3.430005E+01 6.000000E+01 1 1.950934E+01 8.995132E+01 1.657432E-02 1.950933E+01 - 3.430005E+01 6.000000E+01 2 3.573286E+01 8.994546E+01 3.401675E-02 3.573285E+01 - 3.430005E+01 6.000000E+01 3 1.929984E+02 2.117788E-01 1.929971E+02 7.133664E-01 - 3.430005E+01 6.000000E+01 4 1.160334E+02 8.994546E+01 1.104610E-01 1.160334E+02 - 3.430005E+01 6.000000E+01 5 2.058100E+02 8.995132E+01 1.748671E-01 2.058099E+02 - 3.430005E+01 6.000000E+01 6 4.469635E+01 -4.343129E-04 4.469635E+01 -3.388068E-04 - 3.430005E+01 9.000000E+01 1 2.019941E-06 -9.003658E+01 -1.289411E-09 -2.019940E-06 - 3.430005E+01 9.000000E+01 2 4.137342E+01 8.994546E+01 3.938750E-02 4.137340E+01 - 3.430005E+01 9.000000E+01 3 1.935388E+02 2.120385E-01 1.935375E+02 7.162409E-01 - 3.430005E+01 9.000000E+01 4 1.346734E+02 8.994559E+01 1.279012E-01 1.346734E+02 - 3.430005E+01 9.000000E+01 5 9.359654E-05 -8.999384E+01 1.006393E-08 -9.359654E-05 - 3.430005E+01 9.000000E+01 6 3.834203E-06 1.799997E+02 -3.834203E-06 1.965557E-11 - 3.440005E+01 0.000000E+00 1 3.861600E+01 8.995162E+01 3.260842E-02 3.861599E+01 - 3.440005E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.440005E+01 0.000000E+00 3 1.914837E+02 2.097367E-01 1.914825E+02 7.009432E-01 - 3.440005E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.440005E+01 0.000000E+00 5 4.076013E+02 8.995162E+01 3.441715E-01 4.076011E+02 - 3.440005E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.440005E+01 3.000000E+01 1 3.352515E+01 8.995162E+01 2.830854E-02 3.352514E+01 - 3.440005E+01 3.000000E+01 2 2.045809E+01 8.994582E+01 1.934802E-02 2.045808E+01 - 3.440005E+01 3.000000E+01 3 1.920156E+02 2.099940E-01 1.920143E+02 7.037520E-01 - 3.440005E+01 3.000000E+01 4 6.610255E+01 8.994556E+01 6.281795E-02 6.610252E+01 - 3.440005E+01 3.000000E+01 5 3.538477E+02 8.995162E+01 2.987881E-01 3.538476E+02 - 3.440005E+01 3.000000E+01 6 4.417879E+01 -4.296174E-04 4.417879E+01 -3.312631E-04 - 3.440005E+01 6.000000E+01 1 1.945168E+01 8.995162E+01 1.642371E-02 1.945168E+01 - 3.440005E+01 6.000000E+01 2 3.562713E+01 8.994582E+01 3.369583E-02 3.562711E+01 - 3.440005E+01 6.000000E+01 3 1.930847E+02 2.105051E-01 1.930835E+02 7.093930E-01 - 3.440005E+01 6.000000E+01 4 1.156715E+02 8.994582E+01 1.094015E-01 1.156714E+02 - 3.440005E+01 6.000000E+01 5 2.052818E+02 8.995162E+01 1.733446E-01 2.052818E+02 - 3.440005E+01 6.000000E+01 6 4.442604E+01 -4.288058E-04 4.442604E+01 -3.324877E-04 - 3.440005E+01 9.000000E+01 1 2.013890E-06 -9.003638E+01 -1.278914E-09 -2.013890E-06 - 3.440005E+01 9.000000E+01 2 4.125039E+01 8.994582E+01 3.901527E-02 4.125037E+01 - 3.440005E+01 9.000000E+01 3 1.936228E+02 2.107600E-01 1.936215E+02 7.122312E-01 - 3.440005E+01 9.000000E+01 4 1.342484E+02 8.994594E+01 1.266718E-01 1.342483E+02 - 3.440005E+01 9.000000E+01 5 9.332901E-05 -8.999389E+01 9.955983E-09 -9.332901E-05 - 3.440005E+01 9.000000E+01 6 3.810930E-06 1.799997E+02 -3.810930E-06 1.928943E-11 - 3.450005E+01 0.000000E+00 1 3.850412E+01 8.995192E+01 3.231448E-02 3.850410E+01 - 3.450005E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.450005E+01 0.000000E+00 3 1.915782E+02 2.084854E-01 1.915769E+02 6.971048E-01 - 3.450005E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.450005E+01 0.000000E+00 5 4.065757E+02 8.995192E+01 3.412012E-01 4.065756E+02 - 3.450005E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.450005E+01 3.000000E+01 1 3.342742E+01 8.995192E+01 2.805291E-02 3.342741E+01 - 3.450005E+01 3.000000E+01 2 2.039851E+01 8.994617E+01 1.916681E-02 2.039850E+01 - 3.450005E+01 3.000000E+01 3 1.921078E+02 2.087367E-01 1.921066E+02 6.998748E-01 - 3.450005E+01 3.000000E+01 4 6.590118E+01 8.994591E+01 6.221944E-02 6.590115E+01 - 3.450005E+01 3.000000E+01 5 3.529504E+02 8.995192E+01 2.962039E-01 3.529503E+02 - 3.450005E+01 3.000000E+01 6 4.391412E+01 -4.241830E-04 4.391412E+01 -3.251134E-04 - 3.450005E+01 6.000000E+01 1 1.939433E+01 8.995192E+01 1.627497E-02 1.939432E+01 - 3.450005E+01 6.000000E+01 2 3.552214E+01 8.994616E+01 3.337909E-02 3.552212E+01 - 3.450005E+01 6.000000E+01 3 1.931709E+02 2.092436E-01 1.931696E+02 7.054566E-01 - 3.450005E+01 6.000000E+01 4 1.153121E+02 8.994616E+01 1.083552E-01 1.153121E+02 - 3.450005E+01 6.000000E+01 5 2.047556E+02 8.995192E+01 1.718409E-01 2.047555E+02 - 3.450005E+01 6.000000E+01 6 4.415838E+01 -4.233874E-04 4.415838E+01 -3.263085E-04 - 3.450005E+01 9.000000E+01 1 2.007891E-06 -9.003619E+01 -1.268531E-09 -2.007891E-06 - 3.450005E+01 9.000000E+01 2 4.112812E+01 8.994616E+01 3.864783E-02 4.112811E+01 - 3.450005E+01 9.000000E+01 3 1.937057E+02 2.094953E-01 1.937044E+02 7.082606E-01 - 3.450005E+01 9.000000E+01 4 1.338276E+02 8.994629E+01 1.254597E-01 1.338276E+02 - 3.450005E+01 9.000000E+01 5 9.306328E-05 -8.999393E+01 9.849639E-09 -9.306328E-05 - 3.450005E+01 9.000000E+01 6 3.787876E-06 1.799997E+02 -3.787876E-06 1.893127E-11 - 3.460004E+01 0.000000E+00 1 3.839270E+01 8.995221E+01 3.202403E-02 3.839268E+01 - 3.460004E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.460004E+01 0.000000E+00 3 1.916720E+02 2.072441E-01 1.916708E+02 6.932938E-01 - 3.460004E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.460004E+01 0.000000E+00 5 4.055526E+02 8.995221E+01 3.382632E-01 4.055524E+02 - 3.460004E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.460004E+01 3.000000E+01 1 3.333018E+01 8.995221E+01 2.780049E-02 3.333017E+01 - 3.460004E+01 3.000000E+01 2 2.033922E+01 8.994651E+01 1.898784E-02 2.033921E+01 - 3.460004E+01 3.000000E+01 3 1.921990E+02 2.074935E-01 1.921977E+02 6.960364E-01 - 3.460004E+01 3.000000E+01 4 6.570105E+01 8.994626E+01 6.162897E-02 6.570102E+01 - 3.460004E+01 3.000000E+01 5 3.520589E+02 8.995221E+01 2.936520E-01 3.520588E+02 - 3.460004E+01 3.000000E+01 6 4.365172E+01 -4.188360E-04 4.365172E+01 -3.190970E-04 - 3.460004E+01 6.000000E+01 1 1.933741E+01 8.995221E+01 1.612801E-02 1.933740E+01 - 3.460004E+01 6.000000E+01 2 3.541766E+01 8.994651E+01 3.306628E-02 3.541765E+01 - 3.460004E+01 6.000000E+01 3 1.932563E+02 2.079926E-01 1.932550E+02 7.015489E-01 - 3.460004E+01 6.000000E+01 4 1.149547E+02 8.994651E+01 1.073231E-01 1.149546E+02 - 3.460004E+01 6.000000E+01 5 2.042325E+02 8.995221E+01 1.703553E-01 2.042324E+02 - 3.460004E+01 6.000000E+01 6 4.389307E+01 -4.180543E-04 4.389307E+01 -3.202625E-04 - 3.460004E+01 9.000000E+01 1 2.001920E-06 -9.003601E+01 -1.258253E-09 -2.001919E-06 - 3.460004E+01 9.000000E+01 2 4.100655E+01 8.994651E+01 3.828514E-02 4.100653E+01 - 3.460004E+01 9.000000E+01 3 1.937877E+02 2.082420E-01 1.937864E+02 7.043214E-01 - 3.460004E+01 9.000000E+01 4 1.334088E+02 8.994663E+01 1.242620E-01 1.334087E+02 - 3.460004E+01 9.000000E+01 5 9.279925E-05 -8.999399E+01 9.744760E-09 -9.279925E-05 - 3.460004E+01 9.000000E+01 6 3.765038E-06 1.799997E+02 -3.765038E-06 1.858096E-11 - 3.470004E+01 0.000000E+00 1 3.828198E+01 8.995250E+01 3.173710E-02 3.828197E+01 - 3.470004E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.470004E+01 0.000000E+00 3 1.917661E+02 2.060119E-01 1.917648E+02 6.895097E-01 - 3.470004E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.470004E+01 0.000000E+00 5 4.045352E+02 8.995250E+01 3.353630E-01 4.045350E+02 - 3.470004E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.470004E+01 3.000000E+01 1 3.323360E+01 8.995250E+01 2.755093E-02 3.323359E+01 - 3.470004E+01 3.000000E+01 2 2.028024E+01 8.994686E+01 1.881117E-02 2.028024E+01 - 3.470004E+01 3.000000E+01 3 1.922891E+02 2.062576E-01 1.922878E+02 6.922148E-01 - 3.470004E+01 3.000000E+01 4 6.550204E+01 8.994660E+01 6.104593E-02 6.550201E+01 - 3.470004E+01 3.000000E+01 5 3.511710E+02 8.995250E+01 2.911268E-01 3.511709E+02 - 3.470004E+01 3.000000E+01 6 4.339181E+01 -4.135736E-04 4.339181E+01 -3.132117E-04 - 3.470004E+01 6.000000E+01 1 1.928073E+01 8.995251E+01 1.598278E-02 1.928073E+01 - 3.470004E+01 6.000000E+01 2 3.531391E+01 8.994685E+01 3.275752E-02 3.531390E+01 - 3.470004E+01 6.000000E+01 3 1.933406E+02 2.067509E-01 1.933394E+02 6.976652E-01 - 3.470004E+01 6.000000E+01 4 1.145994E+02 8.994685E+01 1.063041E-01 1.145993E+02 - 3.470004E+01 6.000000E+01 5 2.037125E+02 8.995250E+01 1.688858E-01 2.037124E+02 - 3.470004E+01 6.000000E+01 6 4.363018E+01 -4.128074E-04 4.363018E+01 -3.143488E-04 - 3.470004E+01 9.000000E+01 1 1.995988E-06 -9.003583E+01 -1.248082E-09 -1.995987E-06 - 3.470004E+01 9.000000E+01 2 4.088573E+01 8.994685E+01 3.792702E-02 4.088572E+01 - 3.470004E+01 9.000000E+01 3 1.938689E+02 2.069982E-01 1.938677E+02 7.004082E-01 - 3.470004E+01 9.000000E+01 4 1.329931E+02 8.994698E+01 1.230801E-01 1.329930E+02 - 3.470004E+01 9.000000E+01 5 9.253614E-05 -8.999403E+01 9.641385E-09 -9.253614E-05 - 3.470004E+01 9.000000E+01 6 3.742401E-06 1.799997E+02 -3.742401E-06 1.823821E-11 - 3.480004E+01 0.000000E+00 1 3.817182E+01 8.995279E+01 3.145370E-02 3.817181E+01 - 3.480004E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.480004E+01 0.000000E+00 3 1.918590E+02 2.047918E-01 1.918578E+02 6.857587E-01 - 3.480004E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.480004E+01 0.000000E+00 5 4.035247E+02 8.995280E+01 3.324912E-01 4.035246E+02 - 3.480004E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.480004E+01 3.000000E+01 1 3.313750E+01 8.995280E+01 2.730451E-02 3.313749E+01 - 3.480004E+01 3.000000E+01 2 2.022166E+01 8.994720E+01 1.863669E-02 2.022165E+01 - 3.480004E+01 3.000000E+01 3 1.923790E+02 2.050359E-01 1.923777E+02 6.884367E-01 - 3.480004E+01 3.000000E+01 4 6.530428E+01 8.994695E+01 6.047025E-02 6.530425E+01 - 3.480004E+01 3.000000E+01 5 3.502878E+02 8.995280E+01 2.886325E-01 3.502877E+02 - 3.480004E+01 3.000000E+01 6 4.313417E+01 -4.083954E-04 4.313417E+01 -3.074537E-04 - 3.480004E+01 6.000000E+01 1 1.922439E+01 8.995280E+01 1.583939E-02 1.922439E+01 - 3.480004E+01 6.000000E+01 2 3.521078E+01 8.994719E+01 3.245264E-02 3.521076E+01 - 3.480004E+01 6.000000E+01 3 1.934247E+02 2.055226E-01 1.934235E+02 6.938217E-01 - 3.480004E+01 6.000000E+01 4 1.142474E+02 8.994719E+01 1.052982E-01 1.142474E+02 - 3.480004E+01 6.000000E+01 5 2.031938E+02 8.995279E+01 1.674338E-01 2.031937E+02 - 3.480004E+01 6.000000E+01 6 4.336976E+01 -4.076424E-04 4.336976E+01 -3.085629E-04 - 3.480004E+01 9.000000E+01 1 1.990087E-06 -9.003564E+01 -1.238019E-09 -1.990086E-06 - 3.480004E+01 9.000000E+01 2 4.076549E+01 8.994719E+01 3.757337E-02 4.076547E+01 - 3.480004E+01 9.000000E+01 3 1.939492E+02 2.057671E-01 1.939480E+02 6.965309E-01 - 3.480004E+01 9.000000E+01 4 1.325797E+02 8.994732E+01 1.219134E-01 1.325796E+02 - 3.480004E+01 9.000000E+01 5 9.227471E-05 -8.999407E+01 9.539542E-09 -9.227471E-05 - 3.480004E+01 9.000000E+01 6 3.719979E-06 1.799997E+02 -3.719979E-06 1.790291E-11 - 3.490004E+01 0.000000E+00 1 3.806224E+01 8.995307E+01 3.117362E-02 3.806223E+01 - 3.490004E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.490004E+01 0.000000E+00 3 1.919511E+02 2.035830E-01 1.919499E+02 6.820379E-01 - 3.490004E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.490004E+01 0.000000E+00 5 4.025160E+02 8.995307E+01 3.296574E-01 4.025159E+02 - 3.490004E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.490004E+01 3.000000E+01 1 3.304195E+01 8.995307E+01 2.706098E-02 3.304194E+01 - 3.490004E+01 3.000000E+01 2 2.016346E+01 8.994753E+01 1.846446E-02 2.016346E+01 - 3.490004E+01 3.000000E+01 3 1.924683E+02 2.038238E-01 1.924671E+02 6.846845E-01 - 3.490004E+01 3.000000E+01 4 6.510779E+01 8.994729E+01 5.990160E-02 6.510776E+01 - 3.490004E+01 3.000000E+01 5 3.494085E+02 8.995307E+01 2.861628E-01 3.494084E+02 - 3.490004E+01 3.000000E+01 6 4.287885E+01 -4.032986E-04 4.287885E+01 -3.018194E-04 - 3.490004E+01 6.000000E+01 1 1.916846E+01 8.995308E+01 1.569767E-02 1.916845E+01 - 3.490004E+01 6.000000E+01 2 3.510817E+01 8.994753E+01 3.215162E-02 3.510815E+01 - 3.490004E+01 6.000000E+01 3 1.935076E+02 2.043044E-01 1.935064E+02 6.900049E-01 - 3.490004E+01 6.000000E+01 4 1.138965E+02 8.994753E+01 1.043052E-01 1.138964E+02 - 3.490004E+01 6.000000E+01 5 2.026765E+02 8.995307E+01 1.659977E-01 2.026764E+02 - 3.490004E+01 6.000000E+01 6 4.311163E+01 -4.025592E-04 4.311163E+01 -3.029016E-04 - 3.490004E+01 9.000000E+01 1 1.984223E-06 -9.003546E+01 -1.228055E-09 -1.984222E-06 - 3.490004E+01 9.000000E+01 2 4.064616E+01 8.994753E+01 3.722418E-02 4.064615E+01 - 3.490004E+01 9.000000E+01 3 1.940294E+02 2.045455E-01 1.940282E+02 6.926820E-01 - 3.490004E+01 9.000000E+01 4 1.321692E+02 8.994765E+01 1.207615E-01 1.321692E+02 - 3.490004E+01 9.000000E+01 5 9.201452E-05 -8.999413E+01 9.439129E-09 -9.201452E-05 - 3.490004E+01 9.000000E+01 6 3.697755E-06 1.799997E+02 -3.697755E-06 1.757481E-11 - 3.500004E+01 0.000000E+00 1 3.795351E+01 8.995336E+01 3.089688E-02 3.795350E+01 - 3.500004E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.500004E+01 0.000000E+00 3 1.920423E+02 2.023840E-01 1.920411E+02 6.783434E-01 - 3.500004E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.500004E+01 0.000000E+00 5 4.015163E+02 8.995336E+01 3.268485E-01 4.015162E+02 - 3.500004E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.500004E+01 3.000000E+01 1 3.294705E+01 8.995336E+01 2.682038E-02 3.294704E+01 - 3.500004E+01 3.000000E+01 2 2.010550E+01 8.994787E+01 1.829428E-02 2.010549E+01 - 3.500004E+01 3.000000E+01 3 1.925567E+02 2.026219E-01 1.925555E+02 6.809596E-01 - 3.500004E+01 3.000000E+01 4 6.491261E+01 8.994762E+01 5.934080E-02 6.491257E+01 - 3.500004E+01 3.000000E+01 5 3.485332E+02 8.995336E+01 2.837231E-01 3.485331E+02 - 3.500004E+01 3.000000E+01 6 4.262578E+01 -3.982828E-04 4.262578E+01 -2.963066E-04 - 3.500004E+01 6.000000E+01 1 1.911280E+01 8.995336E+01 1.555773E-02 1.911280E+01 - 3.500004E+01 6.000000E+01 2 3.500626E+01 8.994786E+01 3.185429E-02 3.500624E+01 - 3.500004E+01 6.000000E+01 3 1.935907E+02 2.030970E-01 1.935895E+02 6.862218E-01 - 3.500004E+01 6.000000E+01 4 1.135478E+02 8.994786E+01 1.033246E-01 1.135478E+02 - 3.500004E+01 6.000000E+01 5 2.021646E+02 8.995336E+01 1.645771E-01 2.021646E+02 - 3.500004E+01 6.000000E+01 6 4.285572E+01 -3.975577E-04 4.285572E+01 -2.973626E-04 - 3.500004E+01 9.000000E+01 1 1.978392E-06 -9.003528E+01 -1.218199E-09 -1.978391E-06 - 3.500004E+01 9.000000E+01 2 4.052742E+01 8.994786E+01 3.687941E-02 4.052741E+01 - 3.500004E+01 9.000000E+01 3 1.941088E+02 2.033347E-01 1.941076E+02 6.888635E-01 - 3.500004E+01 9.000000E+01 4 1.317611E+02 8.994798E+01 1.196246E-01 1.317610E+02 - 3.500004E+01 9.000000E+01 5 9.175624E-05 -8.999417E+01 9.340133E-09 -9.175624E-05 - 3.500004E+01 9.000000E+01 6 3.675732E-06 1.799997E+02 -3.675732E-06 1.725378E-11 - 3.510004E+01 0.000000E+00 1 3.784522E+01 8.995364E+01 3.062340E-02 3.784521E+01 - 3.510004E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.510004E+01 0.000000E+00 3 1.921323E+02 2.011986E-01 1.921311E+02 6.746861E-01 - 3.510004E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.510004E+01 0.000000E+00 5 4.005159E+02 8.995364E+01 3.240772E-01 4.005157E+02 - 3.510004E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.510004E+01 3.000000E+01 1 3.285258E+01 8.995364E+01 2.658270E-02 3.285257E+01 - 3.510004E+01 3.000000E+01 2 2.004789E+01 8.994820E+01 1.812631E-02 2.004788E+01 - 3.510004E+01 3.000000E+01 3 1.926437E+02 2.014320E-01 1.926425E+02 6.772668E-01 - 3.510004E+01 3.000000E+01 4 6.471822E+01 8.994796E+01 5.878688E-02 6.471820E+01 - 3.510004E+01 3.000000E+01 5 3.476617E+02 8.995364E+01 2.813121E-01 3.476616E+02 - 3.510004E+01 3.000000E+01 6 4.237505E+01 -3.933454E-04 4.237505E+01 -2.909121E-04 - 3.510004E+01 6.000000E+01 1 1.905746E+01 8.995364E+01 1.541935E-02 1.905745E+01 - 3.510004E+01 6.000000E+01 2 3.490485E+01 8.994820E+01 3.156079E-02 3.490484E+01 - 3.510004E+01 6.000000E+01 3 1.936721E+02 2.019015E-01 1.936709E+02 6.824692E-01 - 3.510004E+01 6.000000E+01 4 1.132020E+02 8.994820E+01 1.023572E-01 1.132019E+02 - 3.510004E+01 6.000000E+01 5 2.016539E+02 8.995364E+01 1.631736E-01 2.016539E+02 - 3.510004E+01 6.000000E+01 6 4.260228E+01 -3.926331E-04 4.260228E+01 -2.919424E-04 - 3.510004E+01 9.000000E+01 1 1.972597E-06 -9.003510E+01 -1.208441E-09 -1.972596E-06 - 3.510004E+01 9.000000E+01 2 4.040936E+01 8.994819E+01 3.653902E-02 4.040934E+01 - 3.510004E+01 9.000000E+01 3 1.941877E+02 2.021375E-01 1.941865E+02 6.850861E-01 - 3.510004E+01 9.000000E+01 4 1.313557E+02 8.994831E+01 1.185021E-01 1.313557E+02 - 3.510004E+01 9.000000E+01 5 9.149918E-05 -8.999421E+01 9.242510E-09 -9.149918E-05 - 3.510004E+01 9.000000E+01 6 3.653911E-06 1.799997E+02 -3.653911E-06 1.693964E-11 - 3.520004E+01 0.000000E+00 1 3.773761E+01 8.995391E+01 3.035335E-02 3.773759E+01 - 3.520004E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.520004E+01 0.000000E+00 3 1.922220E+02 2.000209E-01 1.922208E+02 6.710501E-01 - 3.520004E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.520004E+01 0.000000E+00 5 3.995221E+02 8.995392E+01 3.213328E-01 3.995220E+02 - 3.520004E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.520004E+01 3.000000E+01 1 3.275866E+01 8.995392E+01 2.634779E-02 3.275865E+01 - 3.520004E+01 3.000000E+01 2 1.999064E+01 8.994852E+01 1.796036E-02 1.999063E+01 - 3.520004E+01 3.000000E+01 3 1.927310E+02 2.002532E-01 1.927299E+02 6.736085E-01 - 3.520004E+01 3.000000E+01 4 6.452542E+01 8.994829E+01 5.823993E-02 6.452540E+01 - 3.520004E+01 3.000000E+01 5 3.467957E+02 8.995392E+01 2.789291E-01 3.467956E+02 - 3.520004E+01 3.000000E+01 6 4.212649E+01 -3.884865E-04 4.212649E+01 -2.856331E-04 - 3.520004E+01 6.000000E+01 1 1.900245E+01 8.995392E+01 1.528268E-02 1.900244E+01 - 3.520004E+01 6.000000E+01 2 3.480407E+01 8.994852E+01 3.127093E-02 3.480406E+01 - 3.520004E+01 6.000000E+01 3 1.937533E+02 2.007143E-01 1.937521E+02 6.787407E-01 - 3.520004E+01 6.000000E+01 4 1.128584E+02 8.994852E+01 1.014013E-01 1.128583E+02 - 3.520004E+01 6.000000E+01 5 2.011441E+02 8.995391E+01 1.617859E-01 2.011441E+02 - 3.520004E+01 6.000000E+01 6 4.235104E+01 -3.877869E-04 4.235104E+01 -2.866386E-04 - 3.520004E+01 9.000000E+01 1 1.966843E-06 -9.003492E+01 -1.198787E-09 -1.966843E-06 - 3.520004E+01 9.000000E+01 2 4.029213E+01 8.994852E+01 3.620280E-02 4.029211E+01 - 3.520004E+01 9.000000E+01 3 1.942664E+02 2.009482E-01 1.942653E+02 6.813314E-01 - 3.520004E+01 9.000000E+01 4 1.309527E+02 8.994864E+01 1.173940E-01 1.309526E+02 - 3.520004E+01 9.000000E+01 5 9.124355E-05 -8.999426E+01 9.146307E-09 -9.124355E-05 - 3.520004E+01 9.000000E+01 6 3.632280E-06 1.799997E+02 -3.632280E-06 1.663220E-11 - 3.530003E+01 0.000000E+00 1 3.763055E+01 8.995419E+01 3.008623E-02 3.763054E+01 - 3.530003E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.530003E+01 0.000000E+00 3 1.923106E+02 1.988533E-01 1.923095E+02 6.674405E-01 - 3.530003E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.530003E+01 0.000000E+00 5 3.985317E+02 8.995419E+01 3.186210E-01 3.985316E+02 - 3.530003E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.530003E+01 3.000000E+01 1 3.266527E+01 8.995419E+01 2.611567E-02 3.266526E+01 - 3.530003E+01 3.000000E+01 2 1.993369E+01 8.994884E+01 1.779652E-02 1.993368E+01 - 3.530003E+01 3.000000E+01 3 1.928163E+02 1.990832E-01 1.928151E+02 6.699691E-01 - 3.530003E+01 3.000000E+01 4 6.433378E+01 8.994862E+01 5.769991E-02 6.433376E+01 - 3.530003E+01 3.000000E+01 5 3.459283E+02 8.995419E+01 2.765716E-01 3.459282E+02 - 3.530003E+01 3.000000E+01 6 4.188017E+01 -3.837014E-04 4.188017E+01 -2.804653E-04 - 3.530003E+01 6.000000E+01 1 1.894780E+01 8.995419E+01 1.514764E-02 1.894779E+01 - 3.530003E+01 6.000000E+01 2 3.470378E+01 8.994884E+01 3.098455E-02 3.470377E+01 - 3.530003E+01 6.000000E+01 3 1.938325E+02 1.995412E-01 1.938313E+02 6.750494E-01 - 3.530003E+01 6.000000E+01 4 1.125162E+02 8.994884E+01 1.004579E-01 1.125162E+02 - 3.530003E+01 6.000000E+01 5 2.006375E+02 8.995419E+01 1.604136E-01 2.006374E+02 - 3.530003E+01 6.000000E+01 6 4.210201E+01 -3.830161E-04 4.210201E+01 -2.814473E-04 - 3.530003E+01 9.000000E+01 1 1.961117E-06 -9.003475E+01 -1.189225E-09 -1.961117E-06 - 3.530003E+01 9.000000E+01 2 4.017547E+01 8.994884E+01 3.587072E-02 4.017545E+01 - 3.530003E+01 9.000000E+01 3 1.943434E+02 1.997693E-01 1.943422E+02 6.776026E-01 - 3.530003E+01 9.000000E+01 4 1.305525E+02 8.994896E+01 1.162998E-01 1.305525E+02 - 3.530003E+01 9.000000E+01 5 9.098926E-05 -8.999430E+01 9.051415E-09 -9.098926E-05 - 3.530003E+01 9.000000E+01 6 3.610850E-06 1.799997E+02 -3.610850E-06 1.633129E-11 - 3.540003E+01 0.000000E+00 1 3.752418E+01 8.995447E+01 2.982253E-02 3.752417E+01 - 3.540003E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.540003E+01 0.000000E+00 3 1.923982E+02 1.976994E-01 1.923971E+02 6.638698E-01 - 3.540003E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.540003E+01 0.000000E+00 5 3.975461E+02 8.995447E+01 3.159379E-01 3.975459E+02 - 3.540003E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.540003E+01 3.000000E+01 1 3.257248E+01 8.995447E+01 2.588621E-02 3.257247E+01 - 3.540003E+01 3.000000E+01 2 1.987711E+01 8.994917E+01 1.763467E-02 1.987710E+01 - 3.540003E+01 3.000000E+01 3 1.929014E+02 1.979246E-01 1.929002E+02 6.663642E-01 - 3.540003E+01 3.000000E+01 4 6.414345E+01 8.994894E+01 5.716662E-02 6.414342E+01 - 3.540003E+01 3.000000E+01 5 3.450691E+02 8.995447E+01 2.742382E-01 3.450690E+02 - 3.540003E+01 3.000000E+01 6 4.163603E+01 -3.789929E-04 4.163603E+01 -2.754088E-04 - 3.540003E+01 6.000000E+01 1 1.889341E+01 8.995447E+01 1.501421E-02 1.889340E+01 - 3.540003E+01 6.000000E+01 2 3.460426E+01 8.994917E+01 3.070184E-02 3.460424E+01 - 3.540003E+01 6.000000E+01 3 1.939129E+02 1.983769E-01 1.939117E+02 6.713892E-01 - 3.540003E+01 6.000000E+01 4 1.121770E+02 8.994917E+01 9.952672E-02 1.121769E+02 - 3.540003E+01 6.000000E+01 5 2.001317E+02 8.995447E+01 1.590576E-01 2.001316E+02 - 3.540003E+01 6.000000E+01 6 4.185524E+01 -3.783190E-04 4.185524E+01 -2.763665E-04 - 3.540003E+01 9.000000E+01 1 1.955424E-06 -9.003457E+01 -1.179767E-09 -1.955423E-06 - 3.540003E+01 9.000000E+01 2 4.005956E+01 8.994917E+01 3.554284E-02 4.005954E+01 - 3.540003E+01 9.000000E+01 3 1.944197E+02 1.986047E-01 1.944185E+02 6.739168E-01 - 3.540003E+01 9.000000E+01 4 1.301551E+02 8.994928E+01 1.152196E-01 1.301550E+02 - 3.540003E+01 9.000000E+01 5 9.073657E-05 -8.999434E+01 8.957885E-09 -9.073657E-05 - 3.540003E+01 9.000000E+01 6 3.589610E-06 1.799997E+02 -3.589610E-06 1.603677E-11 - 3.550003E+01 0.000000E+00 1 3.741840E+01 8.995473E+01 2.956179E-02 3.741839E+01 - 3.550003E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.550003E+01 0.000000E+00 3 1.924855E+02 1.965533E-01 1.924844E+02 6.603207E-01 - 3.550003E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.550003E+01 0.000000E+00 5 3.965663E+02 8.995474E+01 3.132882E-01 3.965662E+02 - 3.550003E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.550003E+01 3.000000E+01 1 3.248018E+01 8.995474E+01 2.565960E-02 3.248017E+01 - 3.550003E+01 3.000000E+01 2 1.982079E+01 8.994949E+01 1.747475E-02 1.982078E+01 - 3.550003E+01 3.000000E+01 3 1.929865E+02 1.967766E-01 1.929853E+02 6.627911E-01 - 3.550003E+01 3.000000E+01 4 6.395364E+01 8.994926E+01 5.664000E-02 6.395361E+01 - 3.550003E+01 3.000000E+01 5 3.442131E+02 8.995473E+01 2.719341E-01 3.442130E+02 - 3.550003E+01 3.000000E+01 6 4.139398E+01 -3.743564E-04 4.139398E+01 -2.704580E-04 - 3.550003E+01 6.000000E+01 1 1.883936E+01 8.995474E+01 1.488230E-02 1.883935E+01 - 3.550003E+01 6.000000E+01 2 3.450518E+01 8.994949E+01 3.042253E-02 3.450517E+01 - 3.550003E+01 6.000000E+01 3 1.939920E+02 1.972226E-01 1.939909E+02 6.677548E-01 - 3.550003E+01 6.000000E+01 4 1.118389E+02 8.994949E+01 9.860662E-02 1.118388E+02 - 3.550003E+01 6.000000E+01 5 1.996325E+02 8.995473E+01 1.577173E-01 1.996324E+02 - 3.550003E+01 6.000000E+01 6 4.161071E+01 -3.736948E-04 4.161071E+01 -2.713936E-04 - 3.550003E+01 9.000000E+01 1 1.949764E-06 -9.003439E+01 -1.170405E-09 -1.949764E-06 - 3.550003E+01 9.000000E+01 2 3.994423E+01 8.994948E+01 3.521904E-02 3.994421E+01 - 3.550003E+01 9.000000E+01 3 1.944955E+02 1.974477E-01 1.944943E+02 6.702519E-01 - 3.550003E+01 9.000000E+01 4 1.297594E+02 8.994960E+01 1.141529E-01 1.297593E+02 - 3.550003E+01 9.000000E+01 5 9.048496E-05 -8.999439E+01 8.865646E-09 -9.048496E-05 - 3.550003E+01 9.000000E+01 6 3.568554E-06 1.799997E+02 -3.568554E-06 1.574851E-11 - 3.560003E+01 0.000000E+00 1 3.731315E+01 8.995501E+01 2.930408E-02 3.731314E+01 - 3.560003E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.560003E+01 0.000000E+00 3 1.925725E+02 1.954165E-01 1.925714E+02 6.567985E-01 - 3.560003E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.560003E+01 0.000000E+00 5 3.955910E+02 8.995501E+01 3.106649E-01 3.955909E+02 - 3.560003E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.560003E+01 3.000000E+01 1 3.238846E+01 8.995501E+01 2.543555E-02 3.238845E+01 - 3.560003E+01 3.000000E+01 2 1.976484E+01 8.994980E+01 1.731684E-02 1.976483E+01 - 3.560003E+01 3.000000E+01 3 1.930702E+02 1.956372E-01 1.930690E+02 6.592395E-01 - 3.560003E+01 3.000000E+01 4 6.376530E+01 8.994958E+01 5.611995E-02 6.376528E+01 - 3.560003E+01 3.000000E+01 5 3.433607E+02 8.995501E+01 2.696547E-01 3.433606E+02 - 3.560003E+01 3.000000E+01 6 4.115409E+01 -3.697917E-04 4.115409E+01 -2.656119E-04 - 3.560003E+01 6.000000E+01 1 1.878559E+01 8.995501E+01 1.475204E-02 1.878558E+01 - 3.560003E+01 6.000000E+01 2 3.440669E+01 8.994980E+01 3.014669E-02 3.440668E+01 - 3.560003E+01 6.000000E+01 3 1.940701E+02 1.960781E-01 1.940690E+02 6.641473E-01 - 3.560003E+01 6.000000E+01 4 1.115035E+02 8.994980E+01 9.769826E-02 1.115035E+02 - 3.560003E+01 6.000000E+01 5 1.991318E+02 8.995501E+01 1.563908E-01 1.991317E+02 - 3.560003E+01 6.000000E+01 6 4.136828E+01 -3.691419E-04 4.136828E+01 -2.665252E-04 - 3.560003E+01 9.000000E+01 1 1.944139E-06 -9.003423E+01 -1.161135E-09 -1.944139E-06 - 3.560003E+01 9.000000E+01 2 3.982970E+01 8.994980E+01 3.489913E-02 3.982968E+01 - 3.560003E+01 9.000000E+01 3 1.945722E+02 1.962985E-01 1.945710E+02 6.666135E-01 - 3.560003E+01 9.000000E+01 4 1.293665E+02 8.994991E+01 1.130998E-01 1.293664E+02 - 3.560003E+01 9.000000E+01 5 9.023506E-05 -8.999443E+01 8.774662E-09 -9.023506E-05 - 3.560003E+01 9.000000E+01 6 3.547692E-06 1.799997E+02 -3.547692E-06 1.546635E-11 - 3.570003E+01 0.000000E+00 1 3.720853E+01 8.995527E+01 2.904937E-02 3.720852E+01 - 3.570003E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.570003E+01 0.000000E+00 3 1.926582E+02 1.942910E-01 1.926571E+02 6.533061E-01 - 3.570003E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.570003E+01 0.000000E+00 5 3.946154E+02 8.995527E+01 3.080730E-01 3.946153E+02 - 3.570003E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.570003E+01 3.000000E+01 1 3.229712E+01 8.995527E+01 2.521421E-02 3.229711E+01 - 3.570003E+01 3.000000E+01 2 1.970915E+01 8.995012E+01 1.716087E-02 1.970914E+01 - 3.570003E+01 3.000000E+01 3 1.931540E+02 1.945079E-01 1.931529E+02 6.557187E-01 - 3.570003E+01 3.000000E+01 4 6.357809E+01 8.994989E+01 5.560630E-02 6.357807E+01 - 3.570003E+01 3.000000E+01 5 3.425139E+02 8.995527E+01 2.673998E-01 3.425138E+02 - 3.570003E+01 3.000000E+01 6 4.091636E+01 -3.652969E-04 4.091636E+01 -2.608677E-04 - 3.570003E+01 6.000000E+01 1 1.873211E+01 8.995527E+01 1.462321E-02 1.873211E+01 - 3.570003E+01 6.000000E+01 2 3.430878E+01 8.995011E+01 2.987421E-02 3.430877E+01 - 3.570003E+01 6.000000E+01 3 1.941476E+02 1.949451E-01 1.941465E+02 6.605732E-01 - 3.570003E+01 6.000000E+01 4 1.111703E+02 8.995011E+01 9.680121E-02 1.111702E+02 - 3.570003E+01 6.000000E+01 5 1.986332E+02 8.995527E+01 1.550790E-01 1.986331E+02 - 3.570003E+01 6.000000E+01 6 4.112794E+01 -3.646594E-04 4.112794E+01 -2.617591E-04 - 3.570003E+01 9.000000E+01 1 1.938544E-06 -9.003404E+01 -1.151964E-09 -1.938543E-06 - 3.570003E+01 9.000000E+01 2 3.971572E+01 8.995011E+01 3.458322E-02 3.971570E+01 - 3.570003E+01 9.000000E+01 3 1.946469E+02 1.951629E-01 1.946458E+02 6.630120E-01 - 3.570003E+01 9.000000E+01 4 1.289766E+02 8.995022E+01 1.120595E-01 1.289766E+02 - 3.570003E+01 9.000000E+01 5 8.998632E-05 -8.999447E+01 8.684960E-09 -8.998632E-05 - 3.570003E+01 9.000000E+01 6 3.527016E-06 1.799998E+02 -3.527016E-06 1.519010E-11 - 3.580003E+01 0.000000E+00 1 3.710444E+01 8.995554E+01 2.879764E-02 3.710443E+01 - 3.580003E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.580003E+01 0.000000E+00 3 1.927434E+02 1.931735E-01 1.927423E+02 6.498357E-01 - 3.580003E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.580003E+01 0.000000E+00 5 3.936500E+02 8.995554E+01 3.055085E-01 3.936499E+02 - 3.580003E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.580003E+01 3.000000E+01 1 3.220644E+01 8.995554E+01 2.499547E-02 3.220643E+01 - 3.580003E+01 3.000000E+01 2 1.965380E+01 8.995042E+01 1.700681E-02 1.965379E+01 - 3.580003E+01 3.000000E+01 3 1.932356E+02 1.933892E-01 1.932345E+02 6.522228E-01 - 3.580003E+01 3.000000E+01 4 6.339210E+01 8.995020E+01 5.509906E-02 6.339207E+01 - 3.580003E+01 3.000000E+01 5 3.416677E+02 8.995554E+01 2.651704E-01 3.416676E+02 - 3.580003E+01 3.000000E+01 6 4.068060E+01 -3.608723E-04 4.068060E+01 -2.562231E-04 - 3.580003E+01 6.000000E+01 1 1.867904E+01 8.995554E+01 1.449593E-02 1.867904E+01 - 3.580003E+01 6.000000E+01 2 3.421143E+01 8.995042E+01 2.960512E-02 3.421142E+01 - 3.580003E+01 6.000000E+01 3 1.942248E+02 1.938199E-01 1.942237E+02 6.570213E-01 - 3.580003E+01 6.000000E+01 4 1.108390E+02 8.995042E+01 9.591527E-02 1.108389E+02 - 3.580003E+01 6.000000E+01 5 1.981366E+02 8.995554E+01 1.537814E-01 1.981365E+02 - 3.580003E+01 6.000000E+01 6 4.088980E+01 -3.602456E-04 4.088980E+01 -2.570935E-04 - 3.580003E+01 9.000000E+01 1 1.932983E-06 -9.003387E+01 -1.142886E-09 -1.932982E-06 - 3.580003E+01 9.000000E+01 2 3.960241E+01 8.995042E+01 3.427111E-02 3.960239E+01 - 3.580003E+01 9.000000E+01 3 1.947211E+02 1.940352E-01 1.947200E+02 6.594324E-01 - 3.580003E+01 9.000000E+01 4 1.285885E+02 8.995052E+01 1.110324E-01 1.285885E+02 - 3.580003E+01 9.000000E+01 5 8.973895E-05 -8.999451E+01 8.596469E-09 -8.973895E-05 - 3.580003E+01 9.000000E+01 6 3.506517E-06 1.799998E+02 -3.506517E-06 1.491962E-11 - 3.590002E+01 0.000000E+00 1 3.700101E+01 8.995580E+01 2.854883E-02 3.700100E+01 - 3.590002E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.590002E+01 0.000000E+00 3 1.928284E+02 1.920665E-01 1.928274E+02 6.463969E-01 - 3.590002E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.590002E+01 0.000000E+00 5 3.926839E+02 8.995580E+01 3.029725E-01 3.926838E+02 - 3.590002E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.590002E+01 3.000000E+01 1 3.211624E+01 8.995580E+01 2.477914E-02 3.211623E+01 - 3.590002E+01 3.000000E+01 2 1.959876E+01 8.995073E+01 1.685455E-02 1.959876E+01 - 3.590002E+01 3.000000E+01 3 1.933183E+02 1.922779E-01 1.933172E+02 6.487524E-01 - 3.590002E+01 3.000000E+01 4 6.320710E+01 8.995052E+01 5.459804E-02 6.320708E+01 - 3.590002E+01 3.000000E+01 5 3.408278E+02 8.995580E+01 2.629664E-01 3.408277E+02 - 3.590002E+01 3.000000E+01 6 4.044693E+01 -3.565148E-04 4.044693E+01 -2.516752E-04 - 3.590002E+01 6.000000E+01 1 1.862624E+01 8.995580E+01 1.437013E-02 1.862623E+01 - 3.590002E+01 6.000000E+01 2 3.411459E+01 8.995072E+01 2.933923E-02 3.411458E+01 - 3.590002E+01 6.000000E+01 3 1.943020E+02 1.927044E-01 1.943009E+02 6.534997E-01 - 3.590002E+01 6.000000E+01 4 1.105094E+02 8.995072E+01 9.504028E-02 1.105094E+02 - 3.590002E+01 6.000000E+01 5 1.976456E+02 8.995580E+01 1.524990E-01 1.976455E+02 - 3.590002E+01 6.000000E+01 6 4.065371E+01 -3.558997E-04 4.065371E+01 -2.525255E-04 - 3.590002E+01 9.000000E+01 1 1.927459E-06 -9.003371E+01 -1.133897E-09 -1.927459E-06 - 3.590002E+01 9.000000E+01 2 3.948977E+01 8.995072E+01 3.396285E-02 3.948975E+01 - 3.590002E+01 9.000000E+01 3 1.947946E+02 1.929185E-01 1.947935E+02 6.558845E-01 - 3.590002E+01 9.000000E+01 4 1.282025E+02 8.995084E+01 1.100178E-01 1.282025E+02 - 3.590002E+01 9.000000E+01 5 8.949287E-05 -8.999455E+01 8.509219E-09 -8.949287E-05 - 3.590002E+01 9.000000E+01 6 3.486200E-06 1.799998E+02 -3.486200E-06 1.465479E-11 - 3.600002E+01 0.000000E+00 1 3.689823E+01 8.995605E+01 2.830295E-02 3.689822E+01 - 3.600002E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.600002E+01 0.000000E+00 3 1.929125E+02 1.909696E-01 1.929114E+02 6.429854E-01 - 3.600002E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.600002E+01 0.000000E+00 5 3.917276E+02 8.995605E+01 3.004604E-01 3.917275E+02 - 3.600002E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.600002E+01 3.000000E+01 1 3.202650E+01 8.995605E+01 2.456541E-02 3.202649E+01 - 3.600002E+01 3.000000E+01 2 1.954401E+01 8.995103E+01 1.670416E-02 1.954401E+01 - 3.600002E+01 3.000000E+01 3 1.933998E+02 1.911795E-01 1.933987E+02 6.453182E-01 - 3.600002E+01 3.000000E+01 4 6.302334E+01 8.995081E+01 5.410337E-02 6.302332E+01 - 3.600002E+01 3.000000E+01 5 3.399887E+02 8.995605E+01 2.607855E-01 3.399886E+02 - 3.600002E+01 3.000000E+01 6 4.021523E+01 -3.522242E-04 4.021523E+01 -2.472220E-04 - 3.600002E+01 6.000000E+01 1 1.857365E+01 8.995605E+01 1.424583E-02 1.857364E+01 - 3.600002E+01 6.000000E+01 2 3.401836E+01 8.995103E+01 2.907652E-02 3.401834E+01 - 3.600002E+01 6.000000E+01 3 1.943775E+02 1.916006E-01 1.943764E+02 6.500092E-01 - 3.600002E+01 6.000000E+01 4 1.101818E+02 8.995103E+01 9.417623E-02 1.101818E+02 - 3.600002E+01 6.000000E+01 5 1.971542E+02 8.995605E+01 1.512313E-01 1.971541E+02 - 3.600002E+01 6.000000E+01 6 4.041957E+01 -3.516201E-04 4.041957E+01 -2.480520E-04 - 3.600002E+01 9.000000E+01 1 1.921960E-06 -9.003354E+01 -1.125001E-09 -1.921960E-06 - 3.600002E+01 9.000000E+01 2 3.937778E+01 8.995103E+01 3.365833E-02 3.937777E+01 - 3.600002E+01 9.000000E+01 3 1.948680E+02 1.918119E-01 1.948669E+02 6.523678E-01 - 3.600002E+01 9.000000E+01 4 1.278193E+02 8.995113E+01 1.090161E-01 1.278193E+02 - 3.600002E+01 9.000000E+01 5 8.924866E-05 -8.999459E+01 8.423156E-09 -8.924866E-05 - 3.600002E+01 9.000000E+01 6 3.466062E-06 1.799998E+02 -3.466062E-06 1.439546E-11 - 3.610002E+01 0.000000E+00 1 3.679582E+01 8.995631E+01 2.805987E-02 3.679581E+01 - 3.610002E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.610002E+01 0.000000E+00 3 1.929950E+02 1.898817E-01 1.929939E+02 6.395960E-01 - 3.610002E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.610002E+01 0.000000E+00 5 3.907667E+02 8.995631E+01 2.979841E-01 3.907665E+02 - 3.610002E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.610002E+01 3.000000E+01 1 3.193724E+01 8.995631E+01 2.435412E-02 3.193723E+01 - 3.610002E+01 3.000000E+01 2 1.948962E+01 8.995133E+01 1.655562E-02 1.948961E+01 - 3.610002E+01 3.000000E+01 3 1.934799E+02 1.900889E-01 1.934788E+02 6.419027E-01 - 3.610002E+01 3.000000E+01 4 6.284051E+01 8.995112E+01 5.361466E-02 6.284049E+01 - 3.610002E+01 3.000000E+01 5 3.391558E+02 8.995631E+01 2.586276E-01 3.391557E+02 - 3.610002E+01 3.000000E+01 6 3.998563E+01 -3.479987E-04 3.998563E+01 -2.428617E-04 - 3.610002E+01 6.000000E+01 1 1.852148E+01 8.995631E+01 1.412293E-02 1.852147E+01 - 3.610002E+01 6.000000E+01 2 3.392264E+01 8.995133E+01 2.881715E-02 3.392263E+01 - 3.610002E+01 6.000000E+01 3 1.944521E+02 1.905053E-01 1.944511E+02 6.465414E-01 - 3.610002E+01 6.000000E+01 4 1.098569E+02 8.995133E+01 9.332321E-02 1.098569E+02 - 3.610002E+01 6.000000E+01 5 1.966663E+02 8.995631E+01 1.499770E-01 1.966662E+02 - 3.610002E+01 6.000000E+01 6 4.018764E+01 -3.474052E-04 4.018764E+01 -2.436724E-04 - 3.610002E+01 9.000000E+01 1 1.916497E-06 -9.003337E+01 -1.116193E-09 -1.916497E-06 - 3.610002E+01 9.000000E+01 2 3.926650E+01 8.995132E+01 3.335751E-02 3.926648E+01 - 3.610002E+01 9.000000E+01 3 1.949404E+02 1.907122E-01 1.949393E+02 6.488689E-01 - 3.610002E+01 9.000000E+01 4 1.274387E+02 8.995143E+01 1.080264E-01 1.274386E+02 - 3.610002E+01 9.000000E+01 5 8.900501E-05 -8.999464E+01 8.338271E-09 -8.900501E-05 - 3.610002E+01 9.000000E+01 6 3.446104E-06 1.799998E+02 -3.446104E-06 1.414156E-11 - 3.620002E+01 0.000000E+00 1 3.669408E+01 8.995657E+01 2.781959E-02 3.669407E+01 - 3.620002E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.620002E+01 0.000000E+00 3 1.930782E+02 1.888036E-01 1.930771E+02 6.362386E-01 - 3.620002E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.620002E+01 0.000000E+00 5 3.898209E+02 8.995657E+01 2.955300E-01 3.898207E+02 - 3.620002E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.620002E+01 3.000000E+01 1 3.184851E+01 8.995657E+01 2.414526E-02 3.184850E+01 - 3.620002E+01 3.000000E+01 2 1.943553E+01 8.995162E+01 1.640883E-02 1.943553E+01 - 3.620002E+01 3.000000E+01 3 1.935594E+02 1.890092E-01 1.935584E+02 6.385192E-01 - 3.620002E+01 3.000000E+01 4 6.265878E+01 8.995142E+01 5.313190E-02 6.265875E+01 - 3.620002E+01 3.000000E+01 5 3.383251E+02 8.995657E+01 2.564960E-01 3.383250E+02 - 3.620002E+01 3.000000E+01 6 3.975798E+01 -3.438369E-04 3.975798E+01 -2.385911E-04 - 3.620002E+01 6.000000E+01 1 1.846953E+01 8.995657E+01 1.400147E-02 1.846952E+01 - 3.620002E+01 6.000000E+01 2 3.382750E+01 8.995162E+01 2.856081E-02 3.382749E+01 - 3.620002E+01 6.000000E+01 3 1.945269E+02 1.894189E-01 1.945258E+02 6.431016E-01 - 3.620002E+01 6.000000E+01 4 1.095331E+02 8.995162E+01 9.247953E-02 1.095331E+02 - 3.620002E+01 6.000000E+01 5 1.961805E+02 8.995657E+01 1.487358E-01 1.961804E+02 - 3.620002E+01 6.000000E+01 6 3.995770E+01 -3.432540E-04 3.995770E+01 -2.393830E-04 - 3.620002E+01 9.000000E+01 1 1.911062E-06 -9.003320E+01 -1.107475E-09 -1.911062E-06 - 3.620002E+01 9.000000E+01 2 3.915574E+01 8.995162E+01 3.306032E-02 3.915572E+01 - 3.620002E+01 9.000000E+01 3 1.950125E+02 1.896253E-01 1.950114E+02 6.454095E-01 - 3.620002E+01 9.000000E+01 4 1.270602E+02 8.995173E+01 1.070489E-01 1.270602E+02 - 3.620002E+01 9.000000E+01 5 8.876305E-05 -8.999467E+01 8.254527E-09 -8.876305E-05 - 3.620002E+01 9.000000E+01 6 3.426316E-06 1.799998E+02 -3.426316E-06 1.389287E-11 - 3.630002E+01 0.000000E+00 1 3.659297E+01 8.995682E+01 2.758211E-02 3.659296E+01 - 3.630002E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.630002E+01 0.000000E+00 3 1.931599E+02 1.877341E-01 1.931589E+02 6.329024E-01 - 3.630002E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.630002E+01 0.000000E+00 5 3.888706E+02 8.995682E+01 2.931029E-01 3.888705E+02 - 3.630002E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.630002E+01 3.000000E+01 1 3.176025E+01 8.995682E+01 2.393882E-02 3.176024E+01 - 3.630002E+01 3.000000E+01 2 1.938172E+01 8.995193E+01 1.626377E-02 1.938171E+01 - 3.630002E+01 3.000000E+01 3 1.936391E+02 1.879366E-01 1.936380E+02 6.351566E-01 - 3.630002E+01 3.000000E+01 4 6.247813E+01 8.995171E+01 5.265464E-02 6.247811E+01 - 3.630002E+01 3.000000E+01 5 3.375006E+02 8.995682E+01 2.543879E-01 3.375005E+02 - 3.630002E+01 3.000000E+01 6 3.953231E+01 -3.397380E-04 3.953231E+01 -2.344087E-04 - 3.630002E+01 6.000000E+01 1 1.841787E+01 8.995682E+01 1.388142E-02 1.841787E+01 - 3.630002E+01 6.000000E+01 2 3.373294E+01 8.995192E+01 2.830754E-02 3.373293E+01 - 3.630002E+01 6.000000E+01 3 1.946010E+02 1.883430E-01 1.946000E+02 6.396926E-01 - 3.630002E+01 6.000000E+01 4 1.092118E+02 8.995192E+01 9.164707E-02 1.092118E+02 - 3.630002E+01 6.000000E+01 5 1.956963E+02 8.995682E+01 1.475096E-01 1.956962E+02 - 3.630002E+01 6.000000E+01 6 3.972966E+01 -3.391659E-04 3.972966E+01 -2.351822E-04 - 3.630002E+01 9.000000E+01 1 1.905662E-06 -9.003304E+01 -1.098845E-09 -1.905662E-06 - 3.630002E+01 9.000000E+01 2 3.904569E+01 8.995192E+01 3.276663E-02 3.904568E+01 - 3.630002E+01 9.000000E+01 3 1.950837E+02 1.885462E-01 1.950827E+02 6.419712E-01 - 3.630002E+01 9.000000E+01 4 1.266842E+02 8.995202E+01 1.060835E-01 1.266842E+02 - 3.630002E+01 9.000000E+01 5 8.852229E-05 -8.999471E+01 8.171919E-09 -8.852229E-05 - 3.630002E+01 9.000000E+01 6 3.406700E-06 1.799998E+02 -3.406700E-06 1.364934E-11 - 3.640002E+01 0.000000E+00 1 3.649230E+01 8.995706E+01 2.734727E-02 3.649229E+01 - 3.640002E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.640002E+01 0.000000E+00 3 1.932409E+02 1.866754E-01 1.932399E+02 6.295972E-01 - 3.640002E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.640002E+01 0.000000E+00 5 3.879283E+02 8.995706E+01 2.907011E-01 3.879281E+02 - 3.640002E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.640002E+01 3.000000E+01 1 3.167256E+01 8.995706E+01 2.373479E-02 3.167255E+01 - 3.640002E+01 3.000000E+01 2 1.932821E+01 8.995221E+01 1.612047E-02 1.932820E+01 - 3.640002E+01 3.000000E+01 3 1.937179E+02 1.868748E-01 1.937168E+02 6.318254E-01 - 3.640002E+01 3.000000E+01 4 6.229844E+01 8.995201E+01 5.218397E-02 6.229842E+01 - 3.640002E+01 3.000000E+01 5 3.366772E+02 8.995706E+01 2.522999E-01 3.366771E+02 - 3.640002E+01 3.000000E+01 6 3.930856E+01 -3.357013E-04 3.930856E+01 -2.303125E-04 - 3.640002E+01 6.000000E+01 1 1.836656E+01 8.995707E+01 1.376274E-02 1.836655E+01 - 3.640002E+01 6.000000E+01 2 3.363881E+01 8.995221E+01 2.805732E-02 3.363880E+01 - 3.640002E+01 6.000000E+01 3 1.946739E+02 1.872777E-01 1.946728E+02 6.363124E-01 - 3.640002E+01 6.000000E+01 4 1.088920E+02 8.995221E+01 9.082424E-02 1.088919E+02 - 3.640002E+01 6.000000E+01 5 1.952157E+02 8.995706E+01 1.462976E-01 1.952156E+02 - 3.640002E+01 6.000000E+01 6 3.950373E+01 -3.351382E-04 3.950373E+01 -2.310678E-04 - 3.640002E+01 9.000000E+01 1 1.900292E-06 -9.003288E+01 -1.090306E-09 -1.900291E-06 - 3.640002E+01 9.000000E+01 2 3.893615E+01 8.995221E+01 3.247654E-02 3.893613E+01 - 3.640002E+01 9.000000E+01 3 1.951549E+02 1.874767E-01 1.951539E+02 6.385625E-01 - 3.640002E+01 9.000000E+01 4 1.263099E+02 8.995232E+01 1.051301E-01 1.263099E+02 - 3.640002E+01 9.000000E+01 5 8.828314E-05 -8.999475E+01 8.090429E-09 -8.828314E-05 - 3.640002E+01 9.000000E+01 6 3.387258E-06 1.799998E+02 -3.387258E-06 1.341080E-11 - 3.650002E+01 0.000000E+00 1 3.639219E+01 8.995731E+01 2.711521E-02 3.639218E+01 - 3.650002E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.650002E+01 0.000000E+00 3 1.933211E+02 1.856236E-01 1.933201E+02 6.263095E-01 - 3.650002E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.650002E+01 0.000000E+00 5 3.869905E+02 8.995731E+01 2.883295E-01 3.869904E+02 - 3.650002E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.650002E+01 3.000000E+01 1 3.158527E+01 8.995731E+01 2.353300E-02 3.158526E+01 - 3.650002E+01 3.000000E+01 2 1.927492E+01 8.995251E+01 1.597885E-02 1.927491E+01 - 3.650002E+01 3.000000E+01 3 1.937955E+02 1.858225E-01 1.937944E+02 6.285192E-01 - 3.650002E+01 3.000000E+01 4 6.212008E+01 8.995230E+01 5.171850E-02 6.212006E+01 - 3.650002E+01 3.000000E+01 5 3.358566E+02 8.995731E+01 2.502373E-01 3.358565E+02 - 3.650002E+01 3.000000E+01 6 3.908673E+01 -3.317248E-04 3.908673E+01 -2.263001E-04 - 3.650002E+01 6.000000E+01 1 1.831544E+01 8.995731E+01 1.364543E-02 1.831544E+01 - 3.650002E+01 6.000000E+01 2 3.354522E+01 8.995250E+01 2.781012E-02 3.354521E+01 - 3.650002E+01 6.000000E+01 3 1.947467E+02 1.862186E-01 1.947456E+02 6.329504E-01 - 3.650002E+01 6.000000E+01 4 1.085748E+02 8.995250E+01 9.001180E-02 1.085747E+02 - 3.650002E+01 6.000000E+01 5 1.947344E+02 8.995731E+01 1.450961E-01 1.947343E+02 - 3.650002E+01 6.000000E+01 6 3.927964E+01 -3.311723E-04 3.927964E+01 -2.270382E-04 - 3.650002E+01 9.000000E+01 1 1.894949E-06 -9.003271E+01 -1.081844E-09 -1.894949E-06 - 3.650002E+01 9.000000E+01 2 3.882741E+01 8.995250E+01 3.218987E-02 3.882740E+01 - 3.650002E+01 9.000000E+01 3 1.952245E+02 1.864177E-01 1.952235E+02 6.351821E-01 - 3.650002E+01 9.000000E+01 4 1.259385E+02 8.995260E+01 1.041880E-01 1.259385E+02 - 3.650002E+01 9.000000E+01 5 8.804460E-05 -8.999478E+01 8.010020E-09 -8.804460E-05 - 3.650002E+01 9.000000E+01 6 3.367978E-06 1.799998E+02 -3.367978E-06 1.317715E-11 - 3.660001E+01 0.000000E+00 1 3.629268E+01 8.995756E+01 2.688573E-02 3.629267E+01 - 3.660001E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.660001E+01 0.000000E+00 3 1.934017E+02 1.845804E-01 1.934007E+02 6.230494E-01 - 3.660001E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.660001E+01 0.000000E+00 5 3.860558E+02 8.995756E+01 2.859814E-01 3.860557E+02 - 3.660001E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.660001E+01 3.000000E+01 1 3.149850E+01 8.995756E+01 2.333347E-02 3.149849E+01 - 3.660001E+01 3.000000E+01 2 1.922201E+01 8.995279E+01 1.583892E-02 1.922200E+01 - 3.660001E+01 3.000000E+01 3 1.938728E+02 1.847774E-01 1.938718E+02 6.252338E-01 - 3.660001E+01 3.000000E+01 4 6.194261E+01 8.995259E+01 5.125874E-02 6.194259E+01 - 3.660001E+01 3.000000E+01 5 3.350448E+02 8.995756E+01 2.481959E-01 3.350447E+02 - 3.660001E+01 3.000000E+01 6 3.886675E+01 -3.278083E-04 3.886675E+01 -2.223697E-04 - 3.660001E+01 6.000000E+01 1 1.826464E+01 8.995756E+01 1.352943E-02 1.826464E+01 - 3.660001E+01 6.000000E+01 2 3.345223E+01 8.995279E+01 2.756577E-02 3.345222E+01 - 3.660001E+01 6.000000E+01 3 1.948195E+02 1.851693E-01 1.948185E+02 6.296191E-01 - 3.660001E+01 6.000000E+01 4 1.082585E+02 8.995279E+01 8.920918E-02 1.082584E+02 - 3.660001E+01 6.000000E+01 5 1.942572E+02 8.995756E+01 1.439083E-01 1.942571E+02 - 3.660001E+01 6.000000E+01 6 3.905750E+01 -3.272648E-04 3.905750E+01 -2.230905E-04 - 3.660001E+01 9.000000E+01 1 1.889641E-06 -9.003255E+01 -1.073472E-09 -1.889641E-06 - 3.660001E+01 9.000000E+01 2 3.871917E+01 8.995279E+01 3.190666E-02 3.871916E+01 - 3.660001E+01 9.000000E+01 3 1.952944E+02 1.853659E-01 1.952933E+02 6.318239E-01 - 3.660001E+01 9.000000E+01 4 1.255691E+02 8.995289E+01 1.032575E-01 1.255690E+02 - 3.660001E+01 9.000000E+01 5 8.780773E-05 -8.999483E+01 7.930714E-09 -8.780773E-05 - 3.660001E+01 9.000000E+01 6 3.348868E-06 1.799998E+02 -3.348868E-06 1.294828E-11 - 3.670001E+01 0.000000E+00 1 3.619368E+01 8.995780E+01 2.665881E-02 3.619366E+01 - 3.670001E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.670001E+01 0.000000E+00 3 1.934808E+02 1.835479E-01 1.934798E+02 6.198175E-01 - 3.670001E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.670001E+01 0.000000E+00 5 3.851220E+02 8.995780E+01 2.836561E-01 3.851219E+02 - 3.670001E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.670001E+01 3.000000E+01 1 3.141212E+01 8.995780E+01 2.313636E-02 3.141212E+01 - 3.670001E+01 3.000000E+01 2 1.916936E+01 8.995307E+01 1.570067E-02 1.916935E+01 - 3.670001E+01 3.000000E+01 3 1.939490E+02 1.837421E-01 1.939480E+02 6.219749E-01 - 3.670001E+01 3.000000E+01 4 6.176599E+01 8.995287E+01 5.080429E-02 6.176597E+01 - 3.670001E+01 3.000000E+01 5 3.342333E+02 8.995780E+01 2.461769E-01 3.342332E+02 - 3.670001E+01 3.000000E+01 6 3.864867E+01 -3.239498E-04 3.864867E+01 -2.185192E-04 - 3.670001E+01 6.000000E+01 1 1.821420E+01 8.995780E+01 1.341476E-02 1.821419E+01 - 3.670001E+01 6.000000E+01 2 3.335966E+01 8.995307E+01 2.732434E-02 3.335965E+01 - 3.670001E+01 6.000000E+01 3 1.948910E+02 1.841283E-01 1.948900E+02 6.263096E-01 - 3.670001E+01 6.000000E+01 4 1.079451E+02 8.995307E+01 8.841609E-02 1.079451E+02 - 3.670001E+01 6.000000E+01 5 1.937811E+02 8.995780E+01 1.427354E-01 1.937810E+02 - 3.670001E+01 6.000000E+01 6 3.883728E+01 -3.234157E-04 3.883728E+01 -2.192236E-04 - 3.670001E+01 9.000000E+01 1 1.884358E-06 -9.003239E+01 -1.065184E-09 -1.884358E-06 - 3.670001E+01 9.000000E+01 2 3.861162E+01 8.995307E+01 3.162677E-02 3.861161E+01 - 3.670001E+01 9.000000E+01 3 1.953642E+02 1.843226E-01 1.953632E+02 6.284927E-01 - 3.670001E+01 9.000000E+01 4 1.252020E+02 8.995317E+01 1.023381E-01 1.252020E+02 - 3.670001E+01 9.000000E+01 5 8.757207E-05 -8.999486E+01 7.852456E-09 -8.757207E-05 - 3.670001E+01 9.000000E+01 6 3.329919E-06 1.799998E+02 -3.329919E-06 1.272406E-11 - 3.680001E+01 0.000000E+00 1 3.609518E+01 8.995804E+01 2.643451E-02 3.609517E+01 - 3.680001E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.680001E+01 0.000000E+00 3 1.935592E+02 1.825232E-01 1.935582E+02 6.166071E-01 - 3.680001E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.680001E+01 0.000000E+00 5 3.841978E+02 8.995804E+01 2.813598E-01 3.841977E+02 - 3.680001E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.680001E+01 3.000000E+01 1 3.132634E+01 8.995804E+01 2.294147E-02 3.132633E+01 - 3.680001E+01 3.000000E+01 2 1.911706E+01 8.995335E+01 1.556402E-02 1.911705E+01 - 3.680001E+01 3.000000E+01 3 1.940258E+02 1.827141E-01 1.940249E+02 6.187401E-01 - 3.680001E+01 3.000000E+01 4 6.159063E+01 8.995316E+01 5.035570E-02 6.159061E+01 - 3.680001E+01 3.000000E+01 5 3.334243E+02 8.995804E+01 2.441790E-01 3.334242E+02 - 3.680001E+01 3.000000E+01 6 3.843254E+01 -3.201480E-04 3.843254E+01 -2.147471E-04 - 3.680001E+01 6.000000E+01 1 1.816397E+01 8.995805E+01 1.330144E-02 1.816397E+01 - 3.680001E+01 6.000000E+01 2 3.326767E+01 8.995335E+01 2.708580E-02 3.326765E+01 - 3.680001E+01 6.000000E+01 3 1.949625E+02 1.830970E-01 1.949615E+02 6.230302E-01 - 3.680001E+01 6.000000E+01 4 1.076324E+02 8.995335E+01 8.763277E-02 1.076324E+02 - 3.680001E+01 6.000000E+01 5 1.933075E+02 8.995804E+01 1.415731E-01 1.933075E+02 - 3.680001E+01 6.000000E+01 6 3.861890E+01 -3.196244E-04 3.861890E+01 -2.154355E-04 - 3.680001E+01 9.000000E+01 1 1.879113E-06 -9.003223E+01 -1.056974E-09 -1.879113E-06 - 3.680001E+01 9.000000E+01 2 3.850458E+01 8.995335E+01 3.135026E-02 3.850457E+01 - 3.680001E+01 9.000000E+01 3 1.954319E+02 1.832886E-01 1.954308E+02 6.251832E-01 - 3.680001E+01 9.000000E+01 4 1.248370E+02 8.995345E+01 1.014297E-01 1.248370E+02 - 3.680001E+01 9.000000E+01 5 8.733774E-05 -8.999490E+01 7.775218E-09 -8.733774E-05 - 3.680001E+01 9.000000E+01 6 3.311137E-06 1.799998E+02 -3.311137E-06 1.250442E-11 - 3.690001E+01 0.000000E+00 1 3.599728E+01 8.995827E+01 2.621271E-02 3.599727E+01 - 3.690001E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.690001E+01 0.000000E+00 3 1.936374E+02 1.815081E-01 1.936364E+02 6.134256E-01 - 3.690001E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.690001E+01 0.000000E+00 5 3.832786E+02 8.995827E+01 2.790852E-01 3.832785E+02 - 3.690001E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.690001E+01 3.000000E+01 1 3.124096E+01 8.995827E+01 2.274868E-02 3.124096E+01 - 3.690001E+01 3.000000E+01 2 1.906494E+01 8.995364E+01 1.542901E-02 1.906494E+01 - 3.690001E+01 3.000000E+01 3 1.941015E+02 1.816968E-01 1.941005E+02 6.155351E-01 - 3.690001E+01 3.000000E+01 4 6.141599E+01 8.995344E+01 4.991201E-02 6.141597E+01 - 3.690001E+01 3.000000E+01 5 3.326176E+02 8.995827E+01 2.422045E-01 3.326175E+02 - 3.690001E+01 3.000000E+01 6 3.821808E+01 -3.164035E-04 3.821808E+01 -2.110511E-04 - 3.690001E+01 6.000000E+01 1 1.811399E+01 8.995828E+01 1.318936E-02 1.811398E+01 - 3.690001E+01 6.000000E+01 2 3.317612E+01 8.995364E+01 2.685007E-02 3.317611E+01 - 3.690001E+01 6.000000E+01 3 1.950322E+02 1.820760E-01 1.950312E+02 6.197773E-01 - 3.690001E+01 6.000000E+01 4 1.073225E+02 8.995364E+01 8.685882E-02 1.073224E+02 - 3.690001E+01 6.000000E+01 5 1.928387E+02 8.995827E+01 1.404242E-01 1.928387E+02 - 3.690001E+01 6.000000E+01 6 3.840244E+01 -3.158883E-04 3.840244E+01 -2.117238E-04 - 3.690001E+01 9.000000E+01 1 1.873892E-06 -9.003207E+01 -1.048851E-09 -1.873891E-06 - 3.690001E+01 9.000000E+01 2 3.839815E+01 8.995363E+01 3.107703E-02 3.839814E+01 - 3.690001E+01 9.000000E+01 3 1.954996E+02 1.822653E-01 1.954986E+02 6.219084E-01 - 3.690001E+01 9.000000E+01 4 1.244742E+02 8.995373E+01 1.005322E-01 1.244741E+02 - 3.690001E+01 9.000000E+01 5 8.710453E-05 -8.999493E+01 7.699029E-09 -8.710453E-05 - 3.690001E+01 9.000000E+01 6 3.292510E-06 1.799998E+02 -3.292510E-06 1.228920E-11 - 3.700001E+01 0.000000E+00 1 3.589978E+01 8.995852E+01 2.599344E-02 3.589977E+01 - 3.700001E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.700001E+01 0.000000E+00 3 1.937148E+02 1.805010E-01 1.937138E+02 6.102659E-01 - 3.700001E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.700001E+01 0.000000E+00 5 3.823571E+02 8.995852E+01 2.768368E-01 3.823570E+02 - 3.700001E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.700001E+01 3.000000E+01 1 3.115604E+01 8.995852E+01 2.255808E-02 3.115603E+01 - 3.700001E+01 3.000000E+01 2 1.901317E+01 8.995390E+01 1.529554E-02 1.901317E+01 - 3.700001E+01 3.000000E+01 3 1.941762E+02 1.806874E-01 1.941752E+02 6.123512E-01 - 3.700001E+01 3.000000E+01 4 6.124279E+01 8.995371E+01 4.947377E-02 6.124277E+01 - 3.700001E+01 3.000000E+01 5 3.318172E+02 8.995852E+01 2.402489E-01 3.318171E+02 - 3.700001E+01 3.000000E+01 6 3.800550E+01 -3.127140E-04 3.800550E+01 -2.074298E-04 - 3.700001E+01 6.000000E+01 1 1.806436E+01 8.995852E+01 1.307851E-02 1.806435E+01 - 3.700001E+01 6.000000E+01 2 3.308511E+01 8.995390E+01 2.661712E-02 3.308510E+01 - 3.700001E+01 6.000000E+01 3 1.951026E+02 1.810615E-01 1.951017E+02 6.165468E-01 - 3.700001E+01 6.000000E+01 4 1.070143E+02 8.995390E+01 8.609351E-02 1.070143E+02 - 3.700001E+01 6.000000E+01 5 1.923697E+02 8.995852E+01 1.392885E-01 1.923696E+02 - 3.700001E+01 6.000000E+01 6 3.818773E+01 -3.122081E-04 3.818773E+01 -2.080872E-04 - 3.700001E+01 9.000000E+01 1 1.868694E-06 -9.003191E+01 -1.040809E-09 -1.868694E-06 - 3.700001E+01 9.000000E+01 2 3.829226E+01 8.995390E+01 3.080693E-02 3.829224E+01 - 3.700001E+01 9.000000E+01 3 1.955675E+02 1.812486E-01 1.955665E+02 6.186541E-01 - 3.700001E+01 9.000000E+01 4 1.241135E+02 8.995400E+01 9.964576E-02 1.241135E+02 - 3.700001E+01 9.000000E+01 5 8.687268E-05 -8.999497E+01 7.623820E-09 -8.687268E-05 - 3.700001E+01 9.000000E+01 6 3.274045E-06 1.799998E+02 -3.274045E-06 1.207833E-11 - 3.710001E+01 0.000000E+00 1 3.580303E+01 8.995875E+01 2.577649E-02 3.580302E+01 - 3.710001E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.710001E+01 0.000000E+00 3 1.937917E+02 1.795006E-01 1.937907E+02 6.071245E-01 - 3.710001E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.710001E+01 0.000000E+00 5 3.814402E+02 8.995875E+01 2.746114E-01 3.814401E+02 - 3.710001E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.710001E+01 3.000000E+01 1 3.107160E+01 8.995875E+01 2.236967E-02 3.107159E+01 - 3.710001E+01 3.000000E+01 2 1.896167E+01 8.995418E+01 1.516363E-02 1.896166E+01 - 3.710001E+01 3.000000E+01 3 1.942503E+02 1.796866E-01 1.942493E+02 6.091916E-01 - 3.710001E+01 3.000000E+01 4 6.107037E+01 8.995399E+01 4.904100E-02 6.107035E+01 - 3.710001E+01 3.000000E+01 5 3.310197E+02 8.995875E+01 2.383163E-01 3.310196E+02 - 3.710001E+01 3.000000E+01 6 3.779467E+01 -3.090784E-04 3.779467E+01 -2.038809E-04 - 3.710001E+01 6.000000E+01 1 1.801499E+01 8.995876E+01 1.296894E-02 1.801498E+01 - 3.710001E+01 6.000000E+01 2 3.299469E+01 8.995418E+01 2.638684E-02 3.299468E+01 - 3.710001E+01 6.000000E+01 3 1.951720E+02 1.800560E-01 1.951711E+02 6.133407E-01 - 3.710001E+01 6.000000E+01 4 1.067082E+02 8.995418E+01 8.533775E-02 1.067082E+02 - 3.710001E+01 6.000000E+01 5 1.919026E+02 8.995875E+01 1.381631E-01 1.919025E+02 - 3.710001E+01 6.000000E+01 6 3.797492E+01 -3.085806E-04 3.797492E+01 -2.045233E-04 - 3.710001E+01 9.000000E+01 1 1.863535E-06 -9.003175E+01 -1.032844E-09 -1.863535E-06 - 3.710001E+01 9.000000E+01 2 3.818700E+01 8.995418E+01 3.054006E-02 3.818699E+01 - 3.710001E+01 9.000000E+01 3 1.956349E+02 1.802405E-01 1.956339E+02 6.154253E-01 - 3.710001E+01 9.000000E+01 4 1.237551E+02 8.995428E+01 9.876946E-02 1.237550E+02 - 3.710001E+01 9.000000E+01 5 8.664217E-05 -8.999501E+01 7.549617E-09 -8.664217E-05 - 3.710001E+01 9.000000E+01 6 3.255738E-06 1.799998E+02 -3.255738E-06 1.187168E-11 - 3.720000E+01 0.000000E+00 1 3.570667E+01 8.995898E+01 2.556218E-02 3.570666E+01 - 3.720000E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.720000E+01 0.000000E+00 3 1.938675E+02 1.785106E-01 1.938665E+02 6.040121E-01 - 3.720000E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.720000E+01 0.000000E+00 5 3.805318E+02 8.995899E+01 2.724096E-01 3.805317E+02 - 3.720000E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.720000E+01 3.000000E+01 1 3.098772E+01 8.995898E+01 2.218330E-02 3.098772E+01 - 3.720000E+01 3.000000E+01 2 1.891045E+01 8.995445E+01 1.503326E-02 1.891044E+01 - 3.720000E+01 3.000000E+01 3 1.943250E+02 1.786926E-01 1.943240E+02 6.060547E-01 - 3.720000E+01 3.000000E+01 4 6.089897E+01 8.995426E+01 4.861289E-02 6.089895E+01 - 3.720000E+01 3.000000E+01 5 3.302250E+02 8.995898E+01 2.364022E-01 3.302249E+02 - 3.720000E+01 3.000000E+01 6 3.758564E+01 -3.054968E-04 3.758564E+01 -2.004038E-04 - 3.720000E+01 6.000000E+01 1 1.796583E+01 8.995899E+01 1.286062E-02 1.796583E+01 - 3.720000E+01 6.000000E+01 2 3.290464E+01 8.995445E+01 2.615929E-02 3.290462E+01 - 3.720000E+01 6.000000E+01 3 1.952406E+02 1.790596E-01 1.952397E+02 6.101611E-01 - 3.720000E+01 6.000000E+01 4 1.064036E+02 8.995445E+01 8.459132E-02 1.064035E+02 - 3.720000E+01 6.000000E+01 5 1.914371E+02 8.995898E+01 1.370518E-01 1.914371E+02 - 3.720000E+01 6.000000E+01 6 3.776382E+01 -3.050082E-04 3.776382E+01 -2.010318E-04 - 3.720000E+01 9.000000E+01 1 1.858400E-06 -9.003160E+01 -1.024959E-09 -1.858399E-06 - 3.720000E+01 9.000000E+01 2 3.808233E+01 8.995445E+01 3.027625E-02 3.808232E+01 - 3.720000E+01 9.000000E+01 3 1.957003E+02 1.792426E-01 1.956993E+02 6.122227E-01 - 3.720000E+01 9.000000E+01 4 1.233988E+02 8.995454E+01 9.790403E-02 1.233987E+02 - 3.720000E+01 9.000000E+01 5 8.641278E-05 -8.999505E+01 7.476406E-09 -8.641278E-05 - 3.720000E+01 9.000000E+01 6 3.237583E-06 1.799998E+02 -3.237583E-06 1.166921E-11 - 3.730000E+01 0.000000E+00 1 3.561084E+01 8.995921E+01 2.535003E-02 3.561084E+01 - 3.730000E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.730000E+01 0.000000E+00 3 1.939441E+02 1.775283E-01 1.939431E+02 6.009256E-01 - 3.730000E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.730000E+01 0.000000E+00 5 3.796246E+02 8.995921E+01 2.702333E-01 3.796245E+02 - 3.730000E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.730000E+01 3.000000E+01 1 3.090408E+01 8.995921E+01 2.199898E-02 3.090407E+01 - 3.730000E+01 3.000000E+01 2 1.885950E+01 8.995472E+01 1.490441E-02 1.885950E+01 - 3.730000E+01 3.000000E+01 3 1.943984E+02 1.777083E-01 1.943975E+02 6.029441E-01 - 3.730000E+01 3.000000E+01 4 6.072842E+01 8.995454E+01 4.819021E-02 6.072840E+01 - 3.730000E+01 3.000000E+01 5 3.294380E+02 8.995921E+01 2.345089E-01 3.294380E+02 - 3.730000E+01 3.000000E+01 6 3.737830E+01 -3.019680E-04 3.737830E+01 -1.969962E-04 - 3.730000E+01 6.000000E+01 1 1.791701E+01 8.995922E+01 1.275356E-02 1.791700E+01 - 3.730000E+01 6.000000E+01 2 3.281517E+01 8.995472E+01 2.593441E-02 3.281516E+01 - 3.730000E+01 6.000000E+01 3 1.953093E+02 1.780708E-01 1.953084E+02 6.070051E-01 - 3.730000E+01 6.000000E+01 4 1.060998E+02 8.995472E+01 8.385316E-02 1.060997E+02 - 3.730000E+01 6.000000E+01 5 1.909745E+02 8.995921E+01 1.359511E-01 1.909745E+02 - 3.730000E+01 6.000000E+01 6 3.755458E+01 -3.014875E-04 3.755458E+01 -1.976103E-04 - 3.730000E+01 9.000000E+01 1 1.853295E-06 -9.003145E+01 -1.017150E-09 -1.853295E-06 - 3.730000E+01 9.000000E+01 2 3.797836E+01 8.995472E+01 3.001556E-02 3.797834E+01 - 3.730000E+01 9.000000E+01 3 1.957673E+02 1.782511E-01 1.957663E+02 6.090444E-01 - 3.730000E+01 9.000000E+01 4 1.230442E+02 8.995481E+01 9.704840E-02 1.230442E+02 - 3.730000E+01 9.000000E+01 5 8.618405E-05 -8.999508E+01 7.404151E-09 -8.618405E-05 - 3.730000E+01 9.000000E+01 6 3.219585E-06 1.799998E+02 -3.219585E-06 1.147080E-11 - 3.740000E+01 0.000000E+00 1 3.551552E+01 8.995944E+01 2.514040E-02 3.551551E+01 - 3.740000E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.740000E+01 0.000000E+00 3 1.940185E+02 1.765533E-01 1.940176E+02 5.978546E-01 - 3.740000E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.740000E+01 0.000000E+00 5 3.787233E+02 8.995944E+01 2.680781E-01 3.787232E+02 - 3.740000E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.740000E+01 3.000000E+01 1 3.082098E+01 8.995944E+01 2.181681E-02 3.082097E+01 - 3.740000E+01 3.000000E+01 2 1.880880E+01 8.995499E+01 1.477704E-02 1.880879E+01 - 3.740000E+01 3.000000E+01 3 1.944707E+02 1.767317E-01 1.944698E+02 5.998538E-01 - 3.740000E+01 3.000000E+01 4 6.055895E+01 8.995480E+01 4.777238E-02 6.055893E+01 - 3.740000E+01 3.000000E+01 5 3.286491E+02 8.995944E+01 2.326372E-01 3.286490E+02 - 3.740000E+01 3.000000E+01 6 3.717279E+01 -2.984897E-04 3.717279E+01 -1.936564E-04 - 3.740000E+01 6.000000E+01 1 1.786840E+01 8.995944E+01 1.264762E-02 1.786839E+01 - 3.740000E+01 6.000000E+01 2 3.272618E+01 8.995499E+01 2.571209E-02 3.272617E+01 - 3.740000E+01 6.000000E+01 3 1.953771E+02 1.770899E-01 1.953762E+02 6.038708E-01 - 3.740000E+01 6.000000E+01 4 1.057991E+02 8.995499E+01 8.312398E-02 1.057991E+02 - 3.740000E+01 6.000000E+01 5 1.905139E+02 8.995944E+01 1.348622E-01 1.905138E+02 - 3.740000E+01 6.000000E+01 6 3.734701E+01 -2.980173E-04 3.734701E+01 -1.942562E-04 - 3.740000E+01 9.000000E+01 1 1.848217E-06 -9.003130E+01 -1.009421E-09 -1.848216E-06 - 3.740000E+01 9.000000E+01 2 3.787478E+01 8.995499E+01 2.975787E-02 3.787477E+01 - 3.740000E+01 9.000000E+01 3 1.958323E+02 1.772688E-01 1.958314E+02 6.058893E-01 - 3.740000E+01 9.000000E+01 4 1.226922E+02 8.995508E+01 9.620330E-02 1.226922E+02 - 3.740000E+01 9.000000E+01 5 8.595712E-05 -8.999511E+01 7.332817E-09 -8.595712E-05 - 3.740000E+01 9.000000E+01 6 3.201735E-06 1.799998E+02 -3.201735E-06 1.127630E-11 - 3.750000E+01 0.000000E+00 1 3.542072E+01 8.995967E+01 2.493308E-02 3.542071E+01 - 3.750000E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.750000E+01 0.000000E+00 3 1.940933E+02 1.755875E-01 1.940924E+02 5.948136E-01 - 3.750000E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.750000E+01 0.000000E+00 5 3.778259E+02 8.995967E+01 2.659465E-01 3.778258E+02 - 3.750000E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.750000E+01 3.000000E+01 1 3.073839E+01 8.995967E+01 2.163660E-02 3.073838E+01 - 3.750000E+01 3.000000E+01 2 1.875841E+01 8.995525E+01 1.465115E-02 1.875840E+01 - 3.750000E+01 3.000000E+01 3 1.945428E+02 1.757639E-01 1.945419E+02 5.967901E-01 - 3.750000E+01 3.000000E+01 4 6.039027E+01 8.995507E+01 4.735931E-02 6.039025E+01 - 3.750000E+01 3.000000E+01 5 3.278664E+02 8.995967E+01 2.307838E-01 3.278663E+02 - 3.750000E+01 3.000000E+01 6 3.696891E+01 -2.950625E-04 3.696891E+01 -1.903830E-04 - 3.750000E+01 6.000000E+01 1 1.782012E+01 8.995967E+01 1.254284E-02 1.782011E+01 - 3.750000E+01 6.000000E+01 2 3.263757E+01 8.995525E+01 2.549235E-02 3.263755E+01 - 3.750000E+01 6.000000E+01 3 1.954447E+02 1.761179E-01 1.954438E+02 6.007640E-01 - 3.750000E+01 6.000000E+01 4 1.054997E+02 8.995525E+01 8.240302E-02 1.054997E+02 - 3.750000E+01 6.000000E+01 5 1.900555E+02 8.995967E+01 1.337853E-01 1.900555E+02 - 3.750000E+01 6.000000E+01 6 3.714124E+01 -2.945984E-04 3.714124E+01 -1.909695E-04 - 3.750000E+01 9.000000E+01 1 1.843173E-06 -9.003114E+01 -1.001765E-09 -1.843173E-06 - 3.750000E+01 9.000000E+01 2 3.777192E+01 8.995525E+01 2.950320E-02 3.777191E+01 - 3.750000E+01 9.000000E+01 3 1.958978E+02 1.762942E-01 1.958969E+02 6.027599E-01 - 3.750000E+01 9.000000E+01 4 1.223418E+02 8.995534E+01 9.536795E-02 1.223418E+02 - 3.750000E+01 9.000000E+01 5 8.573143E-05 -8.999515E+01 7.262398E-09 -8.573143E-05 - 3.750000E+01 9.000000E+01 6 3.184033E-06 1.799998E+02 -3.184033E-06 1.108569E-11 - 3.760000E+01 0.000000E+00 1 3.532641E+01 8.995990E+01 2.472806E-02 3.532640E+01 - 3.760000E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.760000E+01 0.000000E+00 3 1.941674E+02 1.746290E-01 1.941665E+02 5.917922E-01 - 3.760000E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.760000E+01 0.000000E+00 5 3.769309E+02 8.995990E+01 2.638378E-01 3.769308E+02 - 3.760000E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.760000E+01 3.000000E+01 1 3.065624E+01 8.995990E+01 2.145841E-02 3.065624E+01 - 3.760000E+01 3.000000E+01 2 1.870827E+01 8.995551E+01 1.452670E-02 1.870827E+01 - 3.760000E+01 3.000000E+01 3 1.946130E+02 1.748050E-01 1.946121E+02 5.937486E-01 - 3.760000E+01 3.000000E+01 4 6.022271E+01 8.995534E+01 4.695121E-02 6.022269E+01 - 3.760000E+01 3.000000E+01 5 3.270844E+02 8.995990E+01 2.289510E-01 3.270843E+02 - 3.760000E+01 3.000000E+01 6 3.676674E+01 -2.916853E-04 3.676674E+01 -1.871746E-04 - 3.760000E+01 6.000000E+01 1 1.777201E+01 8.995990E+01 1.243931E-02 1.777201E+01 - 3.760000E+01 6.000000E+01 2 3.254964E+01 8.995551E+01 2.527520E-02 3.254963E+01 - 3.760000E+01 6.000000E+01 3 1.955117E+02 1.751526E-01 1.955108E+02 5.976764E-01 - 3.760000E+01 6.000000E+01 4 1.052019E+02 8.995551E+01 8.169108E-02 1.052018E+02 - 3.760000E+01 6.000000E+01 5 1.895983E+02 8.995990E+01 1.327199E-01 1.895982E+02 - 3.760000E+01 6.000000E+01 6 3.693717E+01 -2.912291E-04 3.693717E+01 -1.877482E-04 - 3.760000E+01 9.000000E+01 1 1.838151E-06 -9.003099E+01 -9.941880E-10 -1.838151E-06 - 3.760000E+01 9.000000E+01 2 3.766951E+01 8.995551E+01 2.925150E-02 3.766950E+01 - 3.760000E+01 9.000000E+01 3 1.959611E+02 1.753282E-01 1.959602E+02 5.996506E-01 - 3.760000E+01 9.000000E+01 4 1.219939E+02 8.995560E+01 9.454259E-02 1.219939E+02 - 3.760000E+01 9.000000E+01 5 8.550697E-05 -8.999518E+01 7.192929E-09 -8.550697E-05 - 3.760000E+01 9.000000E+01 6 3.166490E-06 1.799998E+02 -3.166490E-06 1.089889E-11 - 3.770000E+01 0.000000E+00 1 3.523265E+01 8.996011E+01 2.452518E-02 3.523264E+01 - 3.770000E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.770000E+01 0.000000E+00 3 1.942398E+02 1.736797E-01 1.942389E+02 5.887948E-01 - 3.770000E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.770000E+01 0.000000E+00 5 3.760396E+02 8.996012E+01 2.617493E-01 3.760395E+02 - 3.770000E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.770000E+01 3.000000E+01 1 3.057445E+01 8.996011E+01 2.128232E-02 3.057444E+01 - 3.770000E+01 3.000000E+01 2 1.865842E+01 8.995577E+01 1.440366E-02 1.865842E+01 - 3.770000E+01 3.000000E+01 3 1.946850E+02 1.738515E-01 1.946841E+02 5.907283E-01 - 3.770000E+01 3.000000E+01 4 6.005615E+01 8.995560E+01 4.654782E-02 6.005613E+01 - 3.770000E+01 3.000000E+01 5 3.263070E+02 8.996011E+01 2.271385E-01 3.263069E+02 - 3.770000E+01 3.000000E+01 6 3.656622E+01 -2.883568E-04 3.656622E+01 -1.840296E-04 - 3.770000E+01 6.000000E+01 1 1.772424E+01 8.996012E+01 1.233690E-02 1.772424E+01 - 3.770000E+01 6.000000E+01 2 3.246197E+01 8.995577E+01 2.506052E-02 3.246196E+01 - 3.770000E+01 6.000000E+01 3 1.955773E+02 1.741974E-01 1.955764E+02 5.946164E-01 - 3.770000E+01 6.000000E+01 4 1.049062E+02 8.995577E+01 8.098717E-02 1.049062E+02 - 3.770000E+01 6.000000E+01 5 1.891437E+02 8.996011E+01 1.316649E-01 1.891437E+02 - 3.770000E+01 6.000000E+01 6 3.673475E+01 -2.879080E-04 3.673475E+01 -1.845900E-04 - 3.770000E+01 9.000000E+01 1 1.833153E-06 -9.003085E+01 -9.866805E-10 -1.833153E-06 - 3.770000E+01 9.000000E+01 2 3.756766E+01 8.995577E+01 2.900263E-02 3.756765E+01 - 3.770000E+01 9.000000E+01 3 1.960254E+02 1.743704E-01 1.960245E+02 5.965705E-01 - 3.770000E+01 9.000000E+01 4 1.216478E+02 8.995586E+01 9.372678E-02 1.216478E+02 - 3.770000E+01 9.000000E+01 5 8.528346E-05 -8.999522E+01 7.124344E-09 -8.528346E-05 - 3.770000E+01 9.000000E+01 6 3.149081E-06 1.799998E+02 -3.149081E-06 1.071572E-11 - 3.780000E+01 0.000000E+00 1 3.513924E+01 8.996034E+01 2.432460E-02 3.513923E+01 - 3.780000E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.780000E+01 0.000000E+00 3 1.943123E+02 1.727374E-01 1.943114E+02 5.858189E-01 - 3.780000E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.780000E+01 0.000000E+00 5 3.751520E+02 8.996034E+01 2.596821E-01 3.751519E+02 - 3.780000E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.780000E+01 3.000000E+01 1 3.049315E+01 8.996034E+01 2.110793E-02 3.049315E+01 - 3.780000E+01 3.000000E+01 2 1.860884E+01 8.995602E+01 1.428207E-02 1.860883E+01 - 3.780000E+01 3.000000E+01 3 1.947545E+02 1.729080E-01 1.947536E+02 5.877321E-01 - 3.780000E+01 3.000000E+01 4 5.989046E+01 8.995586E+01 4.614917E-02 5.989045E+01 - 3.780000E+01 3.000000E+01 5 3.255338E+02 8.996034E+01 2.253425E-01 3.255337E+02 - 3.780000E+01 3.000000E+01 6 3.636741E+01 -2.850756E-04 3.636741E+01 -1.809463E-04 - 3.780000E+01 6.000000E+01 1 1.767672E+01 8.996034E+01 1.223558E-02 1.767672E+01 - 3.780000E+01 6.000000E+01 2 3.237489E+01 8.995602E+01 2.484830E-02 3.237488E+01 - 3.780000E+01 6.000000E+01 3 1.956429E+02 1.732492E-01 1.956420E+02 5.915777E-01 - 3.780000E+01 6.000000E+01 4 1.046122E+02 8.995602E+01 8.029181E-02 1.046122E+02 - 3.780000E+01 6.000000E+01 5 1.886924E+02 8.996034E+01 1.306212E-01 1.886924E+02 - 3.780000E+01 6.000000E+01 6 3.653410E+01 -2.846348E-04 3.653410E+01 -1.814946E-04 - 3.780000E+01 9.000000E+01 1 1.828188E-06 -9.003069E+01 -9.792515E-10 -1.828188E-06 - 3.780000E+01 9.000000E+01 2 3.746643E+01 8.995602E+01 2.875663E-02 3.746642E+01 - 3.780000E+01 9.000000E+01 3 1.960886E+02 1.734206E-01 1.960877E+02 5.935124E-01 - 3.780000E+01 9.000000E+01 4 1.213039E+02 8.995612E+01 9.292052E-02 1.213038E+02 - 3.780000E+01 9.000000E+01 5 8.506112E-05 -8.999525E+01 7.056638E-09 -8.506112E-05 - 3.780000E+01 9.000000E+01 6 3.131823E-06 1.799998E+02 -3.131823E-06 1.053619E-11 - 3.789999E+01 0.000000E+00 1 3.504645E+01 8.996056E+01 2.412626E-02 3.504644E+01 - 3.789999E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.789999E+01 0.000000E+00 3 1.943845E+02 1.718028E-01 1.943837E+02 5.828659E-01 - 3.789999E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.789999E+01 0.000000E+00 5 3.742676E+02 8.996056E+01 2.576386E-01 3.742675E+02 - 3.789999E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.789999E+01 3.000000E+01 1 3.041226E+01 8.996056E+01 2.093559E-02 3.041225E+01 - 3.789999E+01 3.000000E+01 2 1.855947E+01 8.995628E+01 1.416183E-02 1.855946E+01 - 3.789999E+01 3.000000E+01 3 1.948246E+02 1.719720E-01 1.948237E+02 5.847607E-01 - 3.789999E+01 3.000000E+01 4 5.972560E+01 8.995611E+01 4.575526E-02 5.972558E+01 - 3.789999E+01 3.000000E+01 5 3.247654E+02 8.996056E+01 2.235660E-01 3.247654E+02 - 3.789999E+01 3.000000E+01 6 3.617013E+01 -2.818428E-04 3.617013E+01 -1.779240E-04 - 3.789999E+01 6.000000E+01 1 1.762939E+01 8.996056E+01 1.213540E-02 1.762938E+01 - 3.789999E+01 6.000000E+01 2 3.228830E+01 8.995628E+01 2.463846E-02 3.228829E+01 - 3.789999E+01 6.000000E+01 3 1.957083E+02 1.723089E-01 1.957074E+02 5.885640E-01 - 3.789999E+01 6.000000E+01 4 1.043195E+02 8.995628E+01 7.960381E-02 1.043195E+02 - 3.789999E+01 6.000000E+01 5 1.882422E+02 8.996056E+01 1.295894E-01 1.882421E+02 - 3.789999E+01 6.000000E+01 6 3.633500E+01 -2.814091E-04 3.633500E+01 -1.784599E-04 - 3.789999E+01 9.000000E+01 1 1.823248E-06 -9.003054E+01 -9.718899E-10 -1.823248E-06 - 3.789999E+01 9.000000E+01 2 3.736568E+01 8.995628E+01 2.851348E-02 3.736567E+01 - 3.789999E+01 9.000000E+01 3 1.961514E+02 1.724782E-01 1.961505E+02 5.904762E-01 - 3.789999E+01 9.000000E+01 4 1.209620E+02 8.995637E+01 9.212315E-02 1.209620E+02 - 3.789999E+01 9.000000E+01 5 8.483945E-05 -8.999529E+01 6.989779E-09 -8.483945E-05 - 3.789999E+01 9.000000E+01 6 3.114706E-06 1.799998E+02 -3.114706E-06 1.036019E-11 - 3.799999E+01 0.000000E+00 1 3.495421E+01 8.996078E+01 2.393005E-02 3.495420E+01 - 3.799999E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.799999E+01 0.000000E+00 3 1.944568E+02 1.708748E-01 1.944559E+02 5.799330E-01 - 3.799999E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.799999E+01 0.000000E+00 5 3.733889E+02 8.996078E+01 2.556180E-01 3.733888E+02 - 3.799999E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.799999E+01 3.000000E+01 1 3.033183E+01 8.996078E+01 2.076511E-02 3.033182E+01 - 3.799999E+01 3.000000E+01 2 1.851044E+01 8.995654E+01 1.404292E-02 1.851043E+01 - 3.799999E+01 3.000000E+01 3 1.948943E+02 1.710430E-01 1.948935E+02 5.818102E-01 - 3.799999E+01 3.000000E+01 4 5.956176E+01 8.995636E+01 4.536559E-02 5.956174E+01 - 3.799999E+01 3.000000E+01 5 3.239963E+02 8.996078E+01 2.218107E-01 3.239962E+02 - 3.799999E+01 3.000000E+01 6 3.597455E+01 -2.786547E-04 3.597455E+01 -1.749601E-04 - 3.799999E+01 6.000000E+01 1 1.758238E+01 8.996078E+01 1.203630E-02 1.758238E+01 - 3.799999E+01 6.000000E+01 2 3.220208E+01 8.995653E+01 2.443106E-02 3.220208E+01 - 3.799999E+01 6.000000E+01 3 1.957732E+02 1.713764E-01 1.957723E+02 5.855727E-01 - 3.799999E+01 6.000000E+01 4 1.040285E+02 8.995653E+01 7.892429E-02 1.040284E+02 - 3.799999E+01 6.000000E+01 5 1.877928E+02 8.996078E+01 1.285691E-01 1.877927E+02 - 3.799999E+01 6.000000E+01 6 3.613800E+01 -2.782307E-04 3.613800E+01 -1.754876E-04 - 3.799999E+01 9.000000E+01 1 1.818341E-06 -9.003040E+01 -9.646056E-10 -1.818340E-06 - 3.799999E+01 9.000000E+01 2 3.726551E+01 8.995653E+01 2.827307E-02 3.726550E+01 - 3.799999E+01 9.000000E+01 3 1.962141E+02 1.715433E-01 1.962132E+02 5.874630E-01 - 3.799999E+01 9.000000E+01 4 1.206220E+02 8.995662E+01 9.133600E-02 1.206219E+02 - 3.799999E+01 9.000000E+01 5 8.461963E-05 -8.999531E+01 6.923800E-09 -8.461963E-05 - 3.799999E+01 9.000000E+01 6 3.097734E-06 1.799998E+02 -3.097734E-06 1.018763E-11 - 3.809999E+01 0.000000E+00 1 3.486228E+01 8.996099E+01 2.373597E-02 3.486227E+01 - 3.809999E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.809999E+01 0.000000E+00 3 1.945269E+02 1.699565E-01 1.945260E+02 5.770244E-01 - 3.809999E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.809999E+01 0.000000E+00 5 3.725117E+02 8.996099E+01 2.536160E-01 3.725117E+02 - 3.809999E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.809999E+01 3.000000E+01 1 3.025176E+01 8.996099E+01 2.059648E-02 3.025176E+01 - 3.809999E+01 3.000000E+01 2 1.846157E+01 8.995678E+01 1.392544E-02 1.846156E+01 - 3.809999E+01 3.000000E+01 3 1.949627E+02 1.701212E-01 1.949619E+02 5.788776E-01 - 3.809999E+01 3.000000E+01 4 5.939889E+01 8.995661E+01 4.498062E-02 5.939887E+01 - 3.809999E+01 3.000000E+01 5 3.232348E+02 8.996099E+01 2.200700E-01 3.232347E+02 - 3.809999E+01 3.000000E+01 6 3.578088E+01 -2.755157E-04 3.578088E+01 -1.720579E-04 - 3.809999E+01 6.000000E+01 1 1.753559E+01 8.996100E+01 1.193830E-02 1.753559E+01 - 3.809999E+01 6.000000E+01 2 3.211641E+01 8.995678E+01 2.422601E-02 3.211641E+01 - 3.809999E+01 6.000000E+01 3 1.958373E+02 1.704507E-01 1.958364E+02 5.826007E-01 - 3.809999E+01 6.000000E+01 4 1.037392E+02 8.995678E+01 7.825250E-02 1.037392E+02 - 3.809999E+01 6.000000E+01 5 1.873469E+02 8.996099E+01 1.275576E-01 1.873468E+02 - 3.809999E+01 6.000000E+01 6 3.594220E+01 -2.750968E-04 3.594220E+01 -1.725709E-04 - 3.809999E+01 9.000000E+01 1 1.813455E-06 -9.003025E+01 -9.573888E-10 -1.813455E-06 - 3.809999E+01 9.000000E+01 2 3.716589E+01 8.995678E+01 2.803547E-02 3.716588E+01 - 3.809999E+01 9.000000E+01 3 1.962754E+02 1.706165E-01 1.962745E+02 5.844717E-01 - 3.809999E+01 9.000000E+01 4 1.202840E+02 8.995686E+01 9.055747E-02 1.202840E+02 - 3.809999E+01 9.000000E+01 5 8.440075E-05 -8.999535E+01 6.858656E-09 -8.440075E-05 - 3.809999E+01 9.000000E+01 6 3.080899E-06 1.799998E+02 -3.080899E-06 1.001845E-11 - 3.819999E+01 0.000000E+00 1 3.477097E+01 8.996120E+01 2.354402E-02 3.477096E+01 - 3.819999E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.819999E+01 0.000000E+00 3 1.945977E+02 1.690437E-01 1.945969E+02 5.741343E-01 - 3.819999E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.819999E+01 0.000000E+00 5 3.716402E+02 8.996120E+01 2.516356E-01 3.716401E+02 - 3.819999E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.819999E+01 3.000000E+01 1 3.017216E+01 8.996120E+01 2.042966E-02 3.017216E+01 - 3.819999E+01 3.000000E+01 2 1.841299E+01 8.995703E+01 1.380922E-02 1.841298E+01 - 3.819999E+01 3.000000E+01 3 1.950316E+02 1.692058E-01 1.950308E+02 5.759662E-01 - 3.819999E+01 3.000000E+01 4 5.923672E+01 8.995686E+01 4.459998E-02 5.923670E+01 - 3.819999E+01 3.000000E+01 5 3.224754E+02 8.996120E+01 2.183504E-01 3.224753E+02 - 3.819999E+01 3.000000E+01 6 3.558846E+01 -2.724184E-04 3.558846E+01 -1.692088E-04 - 3.819999E+01 6.000000E+01 1 1.748909E+01 8.996120E+01 1.184138E-02 1.748909E+01 - 3.819999E+01 6.000000E+01 2 3.203118E+01 8.995703E+01 2.402324E-02 3.203117E+01 - 3.819999E+01 6.000000E+01 3 1.959011E+02 1.695328E-01 1.959003E+02 5.796521E-01 - 3.819999E+01 6.000000E+01 4 1.034517E+02 8.995703E+01 7.758854E-02 1.034517E+02 - 3.819999E+01 6.000000E+01 5 1.869014E+02 8.996120E+01 1.265575E-01 1.869014E+02 - 3.819999E+01 6.000000E+01 6 3.574800E+01 -2.720069E-04 3.574800E+01 -1.697106E-04 - 3.819999E+01 9.000000E+01 1 1.808592E-06 -9.003011E+01 -9.502413E-10 -1.808592E-06 - 3.819999E+01 9.000000E+01 2 3.706679E+01 8.995703E+01 2.780049E-02 3.706678E+01 - 3.819999E+01 9.000000E+01 3 1.963370E+02 1.696968E-01 1.963362E+02 5.815037E-01 - 3.819999E+01 9.000000E+01 4 1.199473E+02 8.995711E+01 8.978783E-02 1.199473E+02 - 3.819999E+01 9.000000E+01 5 8.418305E-05 -8.999538E+01 6.794342E-09 -8.418305E-05 - 3.819999E+01 9.000000E+01 6 3.064201E-06 1.799998E+02 -3.064201E-06 9.852551E-12 - 3.829999E+01 0.000000E+00 1 3.468003E+01 8.996142E+01 2.335418E-02 3.468002E+01 - 3.829999E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.829999E+01 0.000000E+00 3 1.946672E+02 1.681380E-01 1.946664E+02 5.712622E-01 - 3.829999E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.829999E+01 0.000000E+00 5 3.707715E+02 8.996142E+01 2.496768E-01 3.707714E+02 - 3.829999E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.829999E+01 3.000000E+01 1 3.009303E+01 8.996142E+01 2.026470E-02 3.009303E+01 - 3.829999E+01 3.000000E+01 2 1.836469E+01 8.995728E+01 1.369432E-02 1.836468E+01 - 3.829999E+01 3.000000E+01 3 1.950982E+02 1.683000E-01 1.950974E+02 5.730785E-01 - 3.829999E+01 3.000000E+01 4 5.907571E+01 8.995711E+01 4.422360E-02 5.907570E+01 - 3.829999E+01 3.000000E+01 5 3.217174E+02 8.996142E+01 2.166486E-01 3.217173E+02 - 3.829999E+01 3.000000E+01 6 3.539756E+01 -2.693656E-04 3.539756E+01 -1.664151E-04 - 3.829999E+01 6.000000E+01 1 1.744281E+01 8.996142E+01 1.174549E-02 1.744281E+01 - 3.829999E+01 6.000000E+01 2 3.194634E+01 8.995728E+01 2.382282E-02 3.194633E+01 - 3.829999E+01 6.000000E+01 3 1.959636E+02 1.686223E-01 1.959627E+02 5.767229E-01 - 3.829999E+01 6.000000E+01 4 1.031661E+02 8.995728E+01 7.693203E-02 1.031660E+02 - 3.829999E+01 6.000000E+01 5 1.864578E+02 8.996141E+01 1.255679E-01 1.864578E+02 - 3.829999E+01 6.000000E+01 6 3.555539E+01 -2.689601E-04 3.555539E+01 -1.669055E-04 - 3.829999E+01 9.000000E+01 1 1.803759E-06 -9.002996E+01 -9.431657E-10 -1.803759E-06 - 3.829999E+01 9.000000E+01 2 3.696821E+01 8.995728E+01 2.756819E-02 3.696820E+01 - 3.829999E+01 9.000000E+01 3 1.963979E+02 1.687841E-01 1.963970E+02 5.785557E-01 - 3.829999E+01 9.000000E+01 4 1.196137E+02 8.995736E+01 8.902670E-02 1.196137E+02 - 3.829999E+01 9.000000E+01 5 8.396599E-05 -8.999541E+01 6.730840E-09 -8.396599E-05 - 3.829999E+01 9.000000E+01 6 3.047637E-06 1.799998E+02 -3.047637E-06 9.689864E-12 - 3.839999E+01 0.000000E+00 1 3.458966E+01 8.996162E+01 2.316631E-02 3.458965E+01 - 3.839999E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.839999E+01 0.000000E+00 3 1.947369E+02 1.672419E-01 1.947361E+02 5.684209E-01 - 3.839999E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.839999E+01 0.000000E+00 5 3.699066E+02 8.996163E+01 2.477349E-01 3.699065E+02 - 3.839999E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.839999E+01 3.000000E+01 1 3.001420E+01 8.996163E+01 2.010148E-02 3.001419E+01 - 3.839999E+01 3.000000E+01 2 1.831668E+01 8.995752E+01 1.358072E-02 1.831667E+01 - 3.839999E+01 3.000000E+01 3 1.951666E+02 1.674010E-01 1.951657E+02 5.702170E-01 - 3.839999E+01 3.000000E+01 4 5.891519E+01 8.995736E+01 4.385172E-02 5.891518E+01 - 3.839999E+01 3.000000E+01 5 3.209645E+02 8.996163E+01 2.149600E-01 3.209644E+02 - 3.839999E+01 3.000000E+01 6 3.520827E+01 -2.663557E-04 3.520827E+01 -1.636756E-04 - 3.839999E+01 6.000000E+01 1 1.739679E+01 8.996163E+01 1.165067E-02 1.739678E+01 - 3.839999E+01 6.000000E+01 2 3.186199E+01 8.995752E+01 2.362458E-02 3.186198E+01 - 3.839999E+01 6.000000E+01 3 1.960269E+02 1.677210E-01 1.960261E+02 5.738257E-01 - 3.839999E+01 6.000000E+01 4 1.028811E+02 8.995752E+01 7.628284E-02 1.028811E+02 - 3.839999E+01 6.000000E+01 5 1.860197E+02 8.996162E+01 1.245880E-01 1.860196E+02 - 3.839999E+01 6.000000E+01 6 3.536435E+01 -2.659573E-04 3.536435E+01 -1.641553E-04 - 3.839999E+01 9.000000E+01 1 1.798952E-06 -9.002982E+01 -9.361557E-10 -1.798952E-06 - 3.839999E+01 9.000000E+01 2 3.687025E+01 8.995752E+01 2.733845E-02 3.687024E+01 - 3.839999E+01 9.000000E+01 3 1.964591E+02 1.678807E-01 1.964582E+02 5.756382E-01 - 3.839999E+01 9.000000E+01 4 1.192811E+02 8.995760E+01 8.827484E-02 1.192811E+02 - 3.839999E+01 9.000000E+01 5 8.374990E-05 -8.999544E+01 6.668135E-09 -8.374990E-05 - 3.839999E+01 9.000000E+01 6 3.031218E-06 1.799998E+02 -3.031218E-06 9.530353E-12 - 3.849998E+01 0.000000E+00 1 3.449977E+01 8.996184E+01 2.298047E-02 3.449976E+01 - 3.849998E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.849998E+01 0.000000E+00 3 1.948059E+02 1.663502E-01 1.948051E+02 5.655909E-01 - 3.849998E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.849998E+01 0.000000E+00 5 3.690460E+02 8.996184E+01 2.458162E-01 3.690459E+02 - 3.849998E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.849998E+01 3.000000E+01 1 2.993586E+01 8.996184E+01 1.994009E-02 2.993586E+01 - 3.849998E+01 3.000000E+01 2 1.826886E+01 8.995776E+01 1.346837E-02 1.826886E+01 - 3.849998E+01 3.000000E+01 3 1.952324E+02 1.665085E-01 1.952316E+02 5.673683E-01 - 3.849998E+01 3.000000E+01 4 5.875619E+01 8.995760E+01 4.348381E-02 5.875618E+01 - 3.849998E+01 3.000000E+01 5 3.202123E+02 8.996184E+01 2.132935E-01 3.202122E+02 - 3.849998E+01 3.000000E+01 6 3.502040E+01 -2.633889E-04 3.502040E+01 -1.609889E-04 - 3.849998E+01 6.000000E+01 1 1.735099E+01 8.996184E+01 1.155688E-02 1.735098E+01 - 3.849998E+01 6.000000E+01 2 3.177813E+01 8.995776E+01 2.342860E-02 3.177812E+01 - 3.849998E+01 6.000000E+01 3 1.960889E+02 1.668241E-01 1.960880E+02 5.709372E-01 - 3.849998E+01 6.000000E+01 4 1.025988E+02 8.995776E+01 7.564160E-02 1.025988E+02 - 3.849998E+01 6.000000E+01 5 1.855794E+02 8.996184E+01 1.236184E-01 1.855794E+02 - 3.849998E+01 6.000000E+01 6 3.517489E+01 -2.629961E-04 3.517489E+01 -1.614580E-04 - 3.849998E+01 9.000000E+01 1 1.794170E-06 -9.002967E+01 -9.292148E-10 -1.794169E-06 - 3.849998E+01 9.000000E+01 2 3.677270E+01 8.995776E+01 2.711136E-02 3.677269E+01 - 3.849998E+01 9.000000E+01 3 1.965185E+02 1.669825E-01 1.965177E+02 5.727317E-01 - 3.849998E+01 9.000000E+01 4 1.189512E+02 8.995784E+01 8.753150E-02 1.189511E+02 - 3.849998E+01 9.000000E+01 5 8.353601E-05 -8.999547E+01 6.606227E-09 -8.353601E-05 - 3.849998E+01 9.000000E+01 6 3.014928E-06 1.799998E+02 -3.014928E-06 9.373904E-12 - 3.859998E+01 0.000000E+00 1 3.441029E+01 8.996204E+01 2.279671E-02 3.441029E+01 - 3.859998E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.859998E+01 0.000000E+00 3 1.948741E+02 1.654676E-01 1.948733E+02 5.627869E-01 - 3.859998E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.859998E+01 0.000000E+00 5 3.681898E+02 8.996204E+01 2.439158E-01 3.681897E+02 - 3.859998E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.859998E+01 3.000000E+01 1 2.985792E+01 8.996204E+01 1.978032E-02 2.985792E+01 - 3.859998E+01 3.000000E+01 2 1.822135E+01 8.995800E+01 1.335728E-02 1.822134E+01 - 3.859998E+01 3.000000E+01 3 1.952984E+02 1.656235E-01 1.952976E+02 5.645435E-01 - 3.859998E+01 3.000000E+01 4 5.859755E+01 8.995784E+01 4.312038E-02 5.859753E+01 - 3.859998E+01 3.000000E+01 5 3.194663E+02 8.996204E+01 2.116415E-01 3.194662E+02 - 3.859998E+01 3.000000E+01 6 3.483408E+01 -2.604633E-04 3.483408E+01 -1.583537E-04 - 3.859998E+01 6.000000E+01 1 1.730544E+01 8.996205E+01 1.146407E-02 1.730544E+01 - 3.859998E+01 6.000000E+01 2 3.169465E+01 8.995800E+01 2.323485E-02 3.169464E+01 - 3.859998E+01 6.000000E+01 3 1.961509E+02 1.659355E-01 1.961501E+02 5.680760E-01 - 3.859998E+01 6.000000E+01 4 1.023174E+02 8.995800E+01 7.500722E-02 1.023173E+02 - 3.859998E+01 6.000000E+01 5 1.851430E+02 8.996204E+01 1.226605E-01 1.851430E+02 - 3.859998E+01 6.000000E+01 6 3.498689E+01 -2.600776E-04 3.498689E+01 -1.588128E-04 - 3.859998E+01 9.000000E+01 1 1.789424E-06 -9.002953E+01 -9.223416E-10 -1.789424E-06 - 3.859998E+01 9.000000E+01 2 3.667565E+01 8.995800E+01 2.688683E-02 3.667564E+01 - 3.859998E+01 9.000000E+01 3 1.965779E+02 1.660928E-01 1.965770E+02 5.698522E-01 - 3.859998E+01 9.000000E+01 4 1.186225E+02 8.995808E+01 8.679637E-02 1.186225E+02 - 3.859998E+01 9.000000E+01 5 8.332237E-05 -8.999550E+01 6.545080E-09 -8.332237E-05 - 3.859998E+01 9.000000E+01 6 2.998770E-06 1.799998E+02 -2.998770E-06 9.220468E-12 - 3.869998E+01 0.000000E+00 1 3.432128E+01 8.996225E+01 2.261486E-02 3.432127E+01 - 3.869998E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.869998E+01 0.000000E+00 3 1.949422E+02 1.645907E-01 1.949414E+02 5.600000E-01 - 3.869998E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.869998E+01 0.000000E+00 5 3.673383E+02 8.996225E+01 2.420353E-01 3.673383E+02 - 3.869998E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.869998E+01 3.000000E+01 1 2.978041E+01 8.996225E+01 1.962240E-02 2.978041E+01 - 3.869998E+01 3.000000E+01 2 1.817397E+01 8.995824E+01 1.324745E-02 1.817397E+01 - 3.869998E+01 3.000000E+01 3 1.953644E+02 1.647459E-01 1.953636E+02 5.617420E-01 - 3.869998E+01 3.000000E+01 4 5.843998E+01 8.995808E+01 4.276097E-02 5.843997E+01 - 3.869998E+01 3.000000E+01 5 3.187232E+02 8.996225E+01 2.100082E-01 3.187231E+02 - 3.869998E+01 3.000000E+01 6 3.464930E+01 -2.575781E-04 3.464930E+01 -1.557689E-04 - 3.869998E+01 6.000000E+01 1 1.726012E+01 8.996225E+01 1.137227E-02 1.726012E+01 - 3.869998E+01 6.000000E+01 2 3.161165E+01 8.995824E+01 2.304325E-02 3.161164E+01 - 3.869998E+01 6.000000E+01 3 1.962120E+02 1.650551E-01 1.962112E+02 5.652379E-01 - 3.869998E+01 6.000000E+01 4 1.020378E+02 8.995824E+01 7.438006E-02 1.020377E+02 - 3.869998E+01 6.000000E+01 5 1.847064E+02 8.996225E+01 1.217106E-01 1.847063E+02 - 3.869998E+01 6.000000E+01 6 3.480049E+01 -2.571990E-04 3.480049E+01 -1.562183E-04 - 3.869998E+01 9.000000E+01 1 1.784687E-06 -9.002940E+01 -9.155313E-10 -1.784687E-06 - 3.869998E+01 9.000000E+01 2 3.657920E+01 8.995824E+01 2.666473E-02 3.657919E+01 - 3.869998E+01 9.000000E+01 3 1.966374E+02 1.652094E-01 1.966366E+02 5.669930E-01 - 3.869998E+01 9.000000E+01 4 1.182951E+02 8.995831E+01 8.606980E-02 1.182951E+02 - 3.869998E+01 9.000000E+01 5 8.310971E-05 -8.999553E+01 6.484684E-09 -8.310971E-05 - 3.869998E+01 9.000000E+01 6 2.982742E-06 1.799998E+02 -2.982742E-06 9.069962E-12 - 3.879998E+01 0.000000E+00 1 3.423267E+01 8.996245E+01 2.243490E-02 3.423266E+01 - 3.879998E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.879998E+01 0.000000E+00 3 1.950095E+02 1.637224E-01 1.950087E+02 5.572378E-01 - 3.879998E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.879998E+01 0.000000E+00 5 3.664887E+02 8.996245E+01 2.401737E-01 3.664886E+02 - 3.879998E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.879998E+01 3.000000E+01 1 2.970324E+01 8.996245E+01 1.946608E-02 2.970324E+01 - 3.879998E+01 3.000000E+01 2 1.812698E+01 8.995847E+01 1.313880E-02 1.812697E+01 - 3.879998E+01 3.000000E+01 3 1.954297E+02 1.638752E-01 1.954289E+02 5.589599E-01 - 3.879998E+01 3.000000E+01 4 5.828310E+01 8.995831E+01 4.240539E-02 5.828309E+01 - 3.879998E+01 3.000000E+01 5 3.179832E+02 8.996245E+01 2.083906E-01 3.179831E+02 - 3.879998E+01 3.000000E+01 6 3.446599E+01 -2.547337E-04 3.446599E+01 -1.532338E-04 - 3.879998E+01 6.000000E+01 1 1.721502E+01 8.996245E+01 1.128144E-02 1.721502E+01 - 3.879998E+01 6.000000E+01 2 3.152910E+01 8.995847E+01 2.285371E-02 3.152909E+01 - 3.879998E+01 6.000000E+01 3 1.962736E+02 1.641803E-01 1.962728E+02 5.624187E-01 - 3.879998E+01 6.000000E+01 4 1.017596E+02 8.995847E+01 7.376023E-02 1.017596E+02 - 3.879998E+01 6.000000E+01 5 1.842768E+02 8.996245E+01 1.207709E-01 1.842768E+02 - 3.879998E+01 6.000000E+01 6 3.461555E+01 -2.543607E-04 3.461555E+01 -1.536734E-04 - 3.879998E+01 9.000000E+01 1 1.779986E-06 -9.002926E+01 -9.087877E-10 -1.779985E-06 - 3.879998E+01 9.000000E+01 2 3.648320E+01 8.995847E+01 2.644516E-02 3.648318E+01 - 3.879998E+01 9.000000E+01 3 1.966966E+02 1.643332E-01 1.966958E+02 5.641557E-01 - 3.879998E+01 9.000000E+01 4 1.179707E+02 8.995854E+01 8.535144E-02 1.179706E+02 - 3.879998E+01 9.000000E+01 5 8.289875E-05 -8.999556E+01 6.425076E-09 -8.289875E-05 - 3.879998E+01 9.000000E+01 6 2.966845E-06 1.799998E+02 -2.966845E-06 8.922348E-12 - 3.889998E+01 0.000000E+00 1 3.414457E+01 8.996265E+01 2.225692E-02 3.414457E+01 - 3.889998E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.889998E+01 0.000000E+00 3 1.950762E+02 1.628608E-01 1.950754E+02 5.544951E-01 - 3.889998E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.889998E+01 0.000000E+00 5 3.656395E+02 8.996265E+01 2.383312E-01 3.656394E+02 - 3.889998E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.889998E+01 3.000000E+01 1 2.962646E+01 8.996265E+01 1.931144E-02 2.962645E+01 - 3.889998E+01 3.000000E+01 2 1.808017E+01 8.995871E+01 1.303136E-02 1.808017E+01 - 3.889998E+01 3.000000E+01 3 1.954939E+02 1.630118E-01 1.954931E+02 5.561976E-01 - 3.889998E+01 3.000000E+01 4 5.812726E+01 8.995855E+01 4.205388E-02 5.812724E+01 - 3.889998E+01 3.000000E+01 5 3.172439E+02 8.996265E+01 2.067901E-01 3.172438E+02 - 3.889998E+01 3.000000E+01 6 3.428415E+01 -2.519286E-04 3.428415E+01 -1.507468E-04 - 3.889998E+01 6.000000E+01 1 1.717017E+01 8.996265E+01 1.119160E-02 1.717017E+01 - 3.889998E+01 6.000000E+01 2 3.144697E+01 8.995870E+01 2.266631E-02 3.144696E+01 - 3.889998E+01 6.000000E+01 3 1.963335E+02 1.633135E-01 1.963327E+02 5.596203E-01 - 3.889998E+01 6.000000E+01 4 1.014834E+02 8.995870E+01 7.314708E-02 1.014833E+02 - 3.889998E+01 6.000000E+01 5 1.838428E+02 8.996265E+01 1.198407E-01 1.838428E+02 - 3.889998E+01 6.000000E+01 6 3.443210E+01 -2.515617E-04 3.443210E+01 -1.511769E-04 - 3.889998E+01 9.000000E+01 1 1.775305E-06 -9.002911E+01 -9.021112E-10 -1.775304E-06 - 3.889998E+01 9.000000E+01 2 3.638785E+01 8.995870E+01 2.622797E-02 3.638784E+01 - 3.889998E+01 9.000000E+01 3 1.967545E+02 1.634650E-01 1.967537E+02 5.613403E-01 - 3.889998E+01 9.000000E+01 4 1.176478E+02 8.995878E+01 8.464115E-02 1.176478E+02 - 3.889998E+01 9.000000E+01 5 8.268830E-05 -8.999559E+01 6.366200E-09 -8.268830E-05 - 3.889998E+01 9.000000E+01 6 2.951078E-06 1.799998E+02 -2.951078E-06 8.777554E-12 - 3.899998E+01 0.000000E+00 1 3.405686E+01 8.996285E+01 2.208090E-02 3.405685E+01 - 3.899998E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.899998E+01 0.000000E+00 3 1.951421E+02 1.620051E-01 1.951413E+02 5.517677E-01 - 3.899998E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.899998E+01 0.000000E+00 5 3.647970E+02 8.996285E+01 2.365089E-01 3.647969E+02 - 3.899998E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.899998E+01 3.000000E+01 1 2.955007E+01 8.996285E+01 1.915849E-02 2.955006E+01 - 3.899998E+01 3.000000E+01 2 1.803357E+01 8.995893E+01 1.292512E-02 1.803357E+01 - 3.899998E+01 3.000000E+01 3 1.955587E+02 1.621533E-01 1.955579E+02 5.534516E-01 - 3.899998E+01 3.000000E+01 4 5.797203E+01 8.995879E+01 4.170631E-02 5.797201E+01 - 3.899998E+01 3.000000E+01 5 3.165098E+02 8.996285E+01 2.052068E-01 3.165097E+02 - 3.899998E+01 3.000000E+01 6 3.410376E+01 -2.491638E-04 3.410376E+01 -1.483080E-04 - 3.899998E+01 6.000000E+01 1 1.712564E+01 8.996285E+01 1.110271E-02 1.712564E+01 - 3.899998E+01 6.000000E+01 2 3.136529E+01 8.995893E+01 2.248104E-02 3.136529E+01 - 3.899998E+01 6.000000E+01 3 1.963934E+02 1.624531E-01 1.963926E+02 5.568416E-01 - 3.899998E+01 6.000000E+01 4 1.012081E+02 8.995893E+01 7.254077E-02 1.012081E+02 - 3.899998E+01 6.000000E+01 5 1.834148E+02 8.996285E+01 1.189201E-01 1.834147E+02 - 3.899998E+01 6.000000E+01 6 3.425019E+01 -2.488024E-04 3.425019E+01 -1.487288E-04 - 3.899998E+01 9.000000E+01 1 1.770651E-06 -9.002898E+01 -8.954974E-10 -1.770651E-06 - 3.899998E+01 9.000000E+01 2 3.629293E+01 8.995893E+01 2.601330E-02 3.629293E+01 - 3.899998E+01 9.000000E+01 3 1.968125E+02 1.626020E-01 1.968117E+02 5.585414E-01 - 3.899998E+01 9.000000E+01 4 1.173267E+02 8.995901E+01 8.393834E-02 1.173267E+02 - 3.899998E+01 9.000000E+01 5 8.247911E-05 -8.999562E+01 6.308041E-09 -8.247911E-05 - 3.899998E+01 9.000000E+01 6 2.935438E-06 1.799998E+02 -2.935438E-06 8.635521E-12 - 3.909998E+01 0.000000E+00 1 3.396978E+01 8.996305E+01 2.190661E-02 3.396977E+01 - 3.909998E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.909998E+01 0.000000E+00 3 1.952079E+02 1.611567E-01 1.952072E+02 5.490637E-01 - 3.909998E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.909998E+01 0.000000E+00 5 3.639585E+02 8.996305E+01 2.347051E-01 3.639584E+02 - 3.909998E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.909998E+01 3.000000E+01 1 2.947422E+01 8.996305E+01 1.900715E-02 2.947422E+01 - 3.909998E+01 3.000000E+01 2 1.798721E+01 8.995917E+01 1.282006E-02 1.798721E+01 - 3.909998E+01 3.000000E+01 3 1.956223E+02 1.613045E-01 1.956215E+02 5.507337E-01 - 3.909998E+01 3.000000E+01 4 5.781799E+01 8.995901E+01 4.136275E-02 5.781797E+01 - 3.909998E+01 3.000000E+01 5 3.157769E+02 8.996305E+01 2.036388E-01 3.157769E+02 - 3.909998E+01 3.000000E+01 6 3.392479E+01 -2.464363E-04 3.392479E+01 -1.459147E-04 - 3.909998E+01 6.000000E+01 1 1.708125E+01 8.996305E+01 1.101480E-02 1.708125E+01 - 3.909998E+01 6.000000E+01 2 3.128394E+01 8.995917E+01 2.229775E-02 3.128393E+01 - 3.909998E+01 6.000000E+01 3 1.964524E+02 1.616001E-01 1.964516E+02 5.540842E-01 - 3.909998E+01 6.000000E+01 4 1.009349E+02 8.995917E+01 7.194161E-02 1.009349E+02 - 3.909998E+01 6.000000E+01 5 1.829868E+02 8.996305E+01 1.180084E-01 1.829867E+02 - 3.909998E+01 6.000000E+01 6 3.406966E+01 -2.460813E-04 3.406966E+01 -1.463267E-04 - 3.909998E+01 9.000000E+01 1 1.766017E-06 -9.002884E+01 -8.889448E-10 -1.766017E-06 - 3.909998E+01 9.000000E+01 2 3.619840E+01 8.995917E+01 2.580091E-02 3.619839E+01 - 3.909998E+01 9.000000E+01 3 1.968699E+02 1.617472E-01 1.968691E+02 5.557670E-01 - 3.909998E+01 9.000000E+01 4 1.170073E+02 8.995924E+01 8.324438E-02 1.170073E+02 - 3.909998E+01 9.000000E+01 5 8.227113E-05 -8.999564E+01 6.250598E-09 -8.227113E-05 - 3.909998E+01 9.000000E+01 6 2.919919E-06 1.799998E+02 -2.919919E-06 8.496176E-12 - 3.919997E+01 0.000000E+00 1 3.388295E+01 8.996325E+01 2.173422E-02 3.388294E+01 - 3.919997E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.919997E+01 0.000000E+00 3 1.952734E+02 1.603131E-01 1.952726E+02 5.463727E-01 - 3.919997E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.919997E+01 0.000000E+00 5 3.631222E+02 8.996325E+01 2.329175E-01 3.631221E+02 - 3.919997E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.919997E+01 3.000000E+01 1 2.939861E+01 8.996325E+01 1.885731E-02 2.939861E+01 - 3.919997E+01 3.000000E+01 2 1.794117E+01 8.995939E+01 1.271612E-02 1.794117E+01 - 3.919997E+01 3.000000E+01 3 1.956850E+02 1.604601E-01 1.956842E+02 5.480261E-01 - 3.919997E+01 3.000000E+01 4 5.766457E+01 8.995924E+01 4.102307E-02 5.766455E+01 - 3.919997E+01 3.000000E+01 5 3.150517E+02 8.996325E+01 2.020848E-01 3.150516E+02 - 3.919997E+01 3.000000E+01 6 3.374725E+01 -2.437465E-04 3.374725E+01 -1.435669E-04 - 3.919997E+01 6.000000E+01 1 1.703708E+01 8.996325E+01 1.092779E-02 1.703708E+01 - 3.919997E+01 6.000000E+01 2 3.120308E+01 8.995939E+01 2.211652E-02 3.120308E+01 - 3.919997E+01 6.000000E+01 3 1.965120E+02 1.607524E-01 1.965112E+02 5.513449E-01 - 3.919997E+01 6.000000E+01 4 1.006631E+02 8.995939E+01 7.134892E-02 1.006630E+02 - 3.919997E+01 6.000000E+01 5 1.825623E+02 8.996325E+01 1.171067E-01 1.825623E+02 - 3.919997E+01 6.000000E+01 6 3.389055E+01 -2.433969E-04 3.389055E+01 -1.439697E-04 - 3.919997E+01 9.000000E+01 1 1.761410E-06 -9.002870E+01 -8.824554E-10 -1.761410E-06 - 3.919997E+01 9.000000E+01 2 3.610443E+01 8.995939E+01 2.559089E-02 3.610442E+01 - 3.919997E+01 9.000000E+01 3 1.969265E+02 1.608983E-01 1.969257E+02 5.530092E-01 - 3.919997E+01 9.000000E+01 4 1.166896E+02 8.995947E+01 8.255763E-02 1.166896E+02 - 3.919997E+01 9.000000E+01 5 8.206412E-05 -8.999567E+01 6.193852E-09 -8.206412E-05 - 3.919997E+01 9.000000E+01 6 2.904526E-06 1.799998E+02 -2.904526E-06 8.359447E-12 - 3.929997E+01 0.000000E+00 1 3.379663E+01 8.996344E+01 2.156364E-02 3.379663E+01 - 3.929997E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.929997E+01 0.000000E+00 3 1.953394E+02 1.594785E-01 1.953386E+02 5.437119E-01 - 3.929997E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.929997E+01 0.000000E+00 5 3.622920E+02 8.996345E+01 2.311483E-01 3.622919E+02 - 3.929997E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.929997E+01 3.000000E+01 1 2.932339E+01 8.996344E+01 1.870916E-02 2.932339E+01 - 3.929997E+01 3.000000E+01 2 1.789528E+01 8.995962E+01 1.261331E-02 1.789528E+01 - 3.929997E+01 3.000000E+01 3 1.957492E+02 1.596229E-01 1.957484E+02 5.453456E-01 - 3.929997E+01 3.000000E+01 4 5.751168E+01 8.995947E+01 4.068685E-02 5.751167E+01 - 3.929997E+01 3.000000E+01 5 3.143284E+02 8.996344E+01 2.005516E-01 3.143284E+02 - 3.929997E+01 3.000000E+01 6 3.357107E+01 -2.410939E-04 3.357107E+01 -1.412631E-04 - 3.929997E+01 6.000000E+01 1 1.699323E+01 8.996345E+01 1.084175E-02 1.699322E+01 - 3.929997E+01 6.000000E+01 2 3.112264E+01 8.995962E+01 2.193721E-02 3.112263E+01 - 3.929997E+01 6.000000E+01 3 1.965709E+02 1.599131E-01 1.965702E+02 5.486308E-01 - 3.929997E+01 6.000000E+01 4 1.003924E+02 8.995962E+01 7.076288E-02 1.003924E+02 - 3.929997E+01 6.000000E+01 5 1.821382E+02 8.996344E+01 1.162149E-01 1.821382E+02 - 3.929997E+01 6.000000E+01 6 3.371286E+01 -2.407503E-04 3.371286E+01 -1.416576E-04 - 3.929997E+01 9.000000E+01 1 1.756834E-06 -9.002857E+01 -8.760297E-10 -1.756833E-06 - 3.929997E+01 9.000000E+01 2 3.601104E+01 8.995962E+01 2.538322E-02 3.601103E+01 - 3.929997E+01 9.000000E+01 3 1.969830E+02 1.600578E-01 1.969823E+02 5.502785E-01 - 3.929997E+01 9.000000E+01 4 1.163734E+02 8.995969E+01 8.187878E-02 1.163734E+02 - 3.929997E+01 9.000000E+01 5 8.185828E-05 -8.999570E+01 6.137809E-09 -8.185828E-05 - 3.929997E+01 9.000000E+01 6 2.889259E-06 1.799998E+02 -2.889259E-06 8.225309E-12 - 3.939997E+01 0.000000E+00 1 3.371078E+01 8.996364E+01 2.139489E-02 3.371077E+01 - 3.939997E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.939997E+01 0.000000E+00 3 1.954022E+02 1.586507E-01 1.954014E+02 5.410634E-01 - 3.939997E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.939997E+01 0.000000E+00 5 3.614624E+02 8.996364E+01 2.293965E-01 3.614623E+02 - 3.939997E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.939997E+01 3.000000E+01 1 2.924857E+01 8.996364E+01 1.856255E-02 2.924856E+01 - 3.939997E+01 3.000000E+01 2 1.784966E+01 8.995984E+01 1.251166E-02 1.784965E+01 - 3.939997E+01 3.000000E+01 3 1.958103E+02 1.587934E-01 1.958095E+02 5.426812E-01 - 3.939997E+01 3.000000E+01 4 5.736006E+01 8.995969E+01 4.035443E-02 5.736004E+01 - 3.939997E+01 3.000000E+01 5 3.136049E+02 8.996364E+01 1.990298E-01 3.136048E+02 - 3.939997E+01 3.000000E+01 6 3.339635E+01 -2.384769E-04 3.339635E+01 -1.390025E-04 - 3.939997E+01 6.000000E+01 1 1.694951E+01 8.996364E+01 1.075653E-02 1.694951E+01 - 3.939997E+01 6.000000E+01 2 3.104264E+01 8.995984E+01 2.175990E-02 3.104263E+01 - 3.939997E+01 6.000000E+01 3 1.966287E+02 1.590798E-01 1.966279E+02 5.459322E-01 - 3.939997E+01 6.000000E+01 4 1.001236E+02 8.995984E+01 7.018323E-02 1.001236E+02 - 3.939997E+01 6.000000E+01 5 1.817164E+02 8.996364E+01 1.153312E-01 1.817164E+02 - 3.939997E+01 6.000000E+01 6 3.353666E+01 -2.381391E-04 3.353666E+01 -1.393888E-04 - 3.939997E+01 9.000000E+01 1 1.752274E-06 -9.002843E+01 -8.696640E-10 -1.752274E-06 - 3.939997E+01 9.000000E+01 2 3.591804E+01 8.995984E+01 2.517774E-02 3.591803E+01 - 3.939997E+01 9.000000E+01 3 1.970393E+02 1.592227E-01 1.970385E+02 5.475637E-01 - 3.939997E+01 9.000000E+01 4 1.160600E+02 8.995991E+01 8.120712E-02 1.160599E+02 - 3.939997E+01 9.000000E+01 5 8.165303E-05 -8.999574E+01 6.082472E-09 -8.165303E-05 - 3.939997E+01 9.000000E+01 6 2.874111E-06 1.799998E+02 -2.874111E-06 8.093693E-12 - 3.949997E+01 0.000000E+00 1 3.362540E+01 8.996383E+01 2.122781E-02 3.362540E+01 - 3.949997E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.949997E+01 0.000000E+00 3 1.954662E+02 1.578299E-01 1.954655E+02 5.384407E-01 - 3.949997E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.949997E+01 0.000000E+00 5 3.606382E+02 8.996383E+01 2.276646E-01 3.606382E+02 - 3.949997E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.949997E+01 3.000000E+01 1 2.917422E+01 8.996383E+01 1.841743E-02 2.917421E+01 - 3.949997E+01 3.000000E+01 2 1.780424E+01 8.996006E+01 1.241106E-02 1.780424E+01 - 3.949997E+01 3.000000E+01 3 1.958724E+02 1.579709E-01 1.958716E+02 5.400416E-01 - 3.949997E+01 3.000000E+01 4 5.720912E+01 8.995992E+01 4.002571E-02 5.720910E+01 - 3.949997E+01 3.000000E+01 5 3.128855E+02 8.996383E+01 1.975245E-01 3.128854E+02 - 3.949997E+01 3.000000E+01 6 3.322294E+01 -2.358966E-04 3.322294E+01 -1.367846E-04 - 3.949997E+01 6.000000E+01 1 1.690606E+01 8.996383E+01 1.067225E-02 1.690606E+01 - 3.949997E+01 6.000000E+01 2 3.096300E+01 8.996006E+01 2.158453E-02 3.096299E+01 - 3.949997E+01 6.000000E+01 3 1.966864E+02 1.582534E-01 1.966857E+02 5.432558E-01 - 3.949997E+01 6.000000E+01 4 9.985601E+01 8.996006E+01 6.961045E-02 9.985599E+01 - 3.949997E+01 6.000000E+01 5 1.812978E+02 8.996383E+01 1.144561E-01 1.812977E+02 - 3.949997E+01 6.000000E+01 6 3.336178E+01 -2.355634E-04 3.336178E+01 -1.371622E-04 - 3.949997E+01 9.000000E+01 1 1.747740E-06 -9.002830E+01 -8.633546E-10 -1.747740E-06 - 3.949997E+01 9.000000E+01 2 3.582547E+01 8.996006E+01 2.497452E-02 3.582546E+01 - 3.949997E+01 9.000000E+01 3 1.970947E+02 1.583952E-01 1.970939E+02 5.448712E-01 - 3.949997E+01 9.000000E+01 4 1.157473E+02 8.996013E+01 8.054294E-02 1.157473E+02 - 3.949997E+01 9.000000E+01 5 8.144906E-05 -8.999577E+01 6.027777E-09 -8.144906E-05 - 3.949997E+01 9.000000E+01 6 2.859083E-06 1.799998E+02 -2.859083E-06 7.964525E-12 - 3.959997E+01 0.000000E+00 1 3.354033E+01 8.996402E+01 2.106253E-02 3.354033E+01 - 3.959997E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.959997E+01 0.000000E+00 3 1.955294E+02 1.570129E-01 1.955287E+02 5.358268E-01 - 3.959997E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.959997E+01 0.000000E+00 5 3.598151E+02 8.996402E+01 2.259508E-01 3.598151E+02 - 3.959997E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.959997E+01 3.000000E+01 1 2.910024E+01 8.996402E+01 1.827392E-02 2.910023E+01 - 3.959997E+01 3.000000E+01 2 1.775911E+01 8.996028E+01 1.231158E-02 1.775911E+01 - 3.959997E+01 3.000000E+01 3 1.959340E+02 1.571523E-01 1.959333E+02 5.374121E-01 - 3.959997E+01 3.000000E+01 4 5.705909E+01 8.996014E+01 3.970068E-02 5.705908E+01 - 3.959997E+01 3.000000E+01 5 3.121678E+02 8.996402E+01 1.960340E-01 3.121678E+02 - 3.959997E+01 3.000000E+01 6 3.305095E+01 -2.333516E-04 3.305095E+01 -1.346084E-04 - 3.959997E+01 6.000000E+01 1 1.686282E+01 8.996402E+01 1.058887E-02 1.686282E+01 - 3.959997E+01 6.000000E+01 2 3.088385E+01 8.996028E+01 2.141110E-02 3.088384E+01 - 3.959997E+01 6.000000E+01 3 1.967436E+02 1.574331E-01 1.967428E+02 5.405967E-01 - 3.959997E+01 6.000000E+01 4 9.959005E+01 8.996028E+01 6.904355E-02 9.959003E+01 - 3.959997E+01 6.000000E+01 5 1.808781E+02 8.996402E+01 1.135908E-01 1.808781E+02 - 3.959997E+01 6.000000E+01 6 3.318834E+01 -2.330239E-04 3.318834E+01 -1.349781E-04 - 3.959997E+01 9.000000E+01 1 1.743232E-06 -9.002817E+01 -8.571087E-10 -1.743231E-06 - 3.959997E+01 9.000000E+01 2 3.573349E+01 8.996028E+01 2.477355E-02 3.573348E+01 - 3.959997E+01 9.000000E+01 3 1.971499E+02 1.575725E-01 1.971491E+02 5.421928E-01 - 3.959997E+01 9.000000E+01 4 1.154367E+02 8.996035E+01 7.988608E-02 1.154367E+02 - 3.959997E+01 9.000000E+01 5 8.124601E-05 -8.999579E+01 5.973753E-09 -8.124601E-05 - 3.959997E+01 9.000000E+01 6 2.844173E-06 1.799998E+02 -2.844173E-06 7.837810E-12 - 3.969997E+01 0.000000E+00 1 3.345576E+01 8.996420E+01 2.089904E-02 3.345575E+01 - 3.969997E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.969997E+01 0.000000E+00 3 1.955931E+02 1.562038E-01 1.955923E+02 5.332388E-01 - 3.969997E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.969997E+01 0.000000E+00 5 3.590002E+02 8.996421E+01 2.242514E-01 3.590001E+02 - 3.969997E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.969997E+01 3.000000E+01 1 2.902649E+01 8.996421E+01 1.813183E-02 2.902649E+01 - 3.969997E+01 3.000000E+01 2 1.771418E+01 8.996049E+01 1.221318E-02 1.771418E+01 - 3.969997E+01 3.000000E+01 3 1.959948E+02 1.563422E-01 1.959940E+02 5.348075E-01 - 3.969997E+01 3.000000E+01 4 5.690964E+01 8.996036E+01 3.937916E-02 5.690963E+01 - 3.969997E+01 3.000000E+01 5 3.114583E+02 8.996421E+01 1.945570E-01 3.114583E+02 - 3.969997E+01 3.000000E+01 6 3.288022E+01 -2.308407E-04 3.288022E+01 -1.324721E-04 - 3.969997E+01 6.000000E+01 1 1.681982E+01 8.996421E+01 1.050632E-02 1.681982E+01 - 3.969997E+01 6.000000E+01 2 3.080498E+01 8.996049E+01 2.123948E-02 3.080497E+01 - 3.969997E+01 6.000000E+01 3 1.968004E+02 1.566199E-01 1.967996E+02 5.379595E-01 - 3.969997E+01 6.000000E+01 4 9.932550E+01 8.996049E+01 6.848279E-02 9.932548E+01 - 3.969997E+01 6.000000E+01 5 1.804632E+02 8.996420E+01 1.127336E-01 1.804632E+02 - 3.969997E+01 6.000000E+01 6 3.301622E+01 -2.305184E-04 3.301622E+01 -1.328343E-04 - 3.969997E+01 9.000000E+01 1 1.738743E-06 -9.002804E+01 -8.509217E-10 -1.738743E-06 - 3.969997E+01 9.000000E+01 2 3.564193E+01 8.996049E+01 2.457472E-02 3.564192E+01 - 3.969997E+01 9.000000E+01 3 1.972052E+02 1.567585E-01 1.972045E+02 5.395434E-01 - 3.969997E+01 9.000000E+01 4 1.151276E+02 8.996056E+01 7.923673E-02 1.151276E+02 - 3.969997E+01 9.000000E+01 5 8.104412E-05 -8.999582E+01 5.920403E-09 -8.104412E-05 - 3.969997E+01 9.000000E+01 6 2.829380E-06 1.799998E+02 -2.829380E-06 7.713447E-12 - 3.979996E+01 0.000000E+00 1 3.337165E+01 8.996440E+01 2.073719E-02 3.337165E+01 - 3.979996E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.979996E+01 0.000000E+00 3 1.956555E+02 1.554000E-01 1.956548E+02 5.306646E-01 - 3.979996E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.979996E+01 0.000000E+00 5 3.581830E+02 8.996440E+01 2.225686E-01 3.581829E+02 - 3.979996E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.979996E+01 3.000000E+01 1 2.895323E+01 8.996440E+01 1.799129E-02 2.895322E+01 - 3.979996E+01 3.000000E+01 2 1.766949E+01 8.996072E+01 1.211583E-02 1.766948E+01 - 3.979996E+01 3.000000E+01 3 1.960547E+02 1.555372E-01 1.960539E+02 5.322164E-01 - 3.979996E+01 3.000000E+01 4 5.676097E+01 8.996057E+01 3.906113E-02 5.676096E+01 - 3.979996E+01 3.000000E+01 5 3.107473E+02 8.996440E+01 1.930959E-01 3.107473E+02 - 3.979996E+01 3.000000E+01 6 3.271090E+01 -2.283640E-04 3.271090E+01 -1.303760E-04 - 3.979996E+01 6.000000E+01 1 1.677704E+01 8.996440E+01 1.042467E-02 1.677704E+01 - 3.979996E+01 6.000000E+01 2 3.072663E+01 8.996071E+01 2.106973E-02 3.072662E+01 - 3.979996E+01 6.000000E+01 3 1.968573E+02 1.558108E-01 1.968566E+02 5.353352E-01 - 3.979996E+01 6.000000E+01 4 9.906238E+01 8.996071E+01 6.792869E-02 9.906236E+01 - 3.979996E+01 6.000000E+01 5 1.800471E+02 8.996440E+01 1.118849E-01 1.800470E+02 - 3.979996E+01 6.000000E+01 6 3.284549E+01 -2.280467E-04 3.284549E+01 -1.307305E-04 - 3.979996E+01 9.000000E+01 1 1.734281E-06 -9.002791E+01 -8.447912E-10 -1.734280E-06 - 3.979996E+01 9.000000E+01 2 3.555087E+01 8.996071E+01 2.437809E-02 3.555086E+01 - 3.979996E+01 9.000000E+01 3 1.972593E+02 1.559485E-01 1.972585E+02 5.369024E-01 - 3.979996E+01 9.000000E+01 4 1.148204E+02 8.996078E+01 7.859468E-02 1.148204E+02 - 3.979996E+01 9.000000E+01 5 8.084311E-05 -8.999584E+01 5.867694E-09 -8.084311E-05 - 3.979996E+01 9.000000E+01 6 2.814705E-06 1.799998E+02 -2.814705E-06 7.591388E-12 - 3.989996E+01 0.000000E+00 1 3.328785E+01 8.996458E+01 2.057702E-02 3.328784E+01 - 3.989996E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.989996E+01 0.000000E+00 3 1.957177E+02 1.546028E-01 1.957170E+02 5.281100E-01 - 3.989996E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.989996E+01 0.000000E+00 5 3.573719E+02 8.996458E+01 2.209041E-01 3.573719E+02 - 3.989996E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.989996E+01 3.000000E+01 1 2.888029E+01 8.996458E+01 1.785210E-02 2.888028E+01 - 3.989996E+01 3.000000E+01 2 1.762500E+01 8.996093E+01 1.201955E-02 1.762499E+01 - 3.989996E+01 3.000000E+01 3 1.961149E+02 1.547392E-01 1.961142E+02 5.296485E-01 - 3.989996E+01 3.000000E+01 4 5.661314E+01 8.996078E+01 3.874672E-02 5.661313E+01 - 3.989996E+01 3.000000E+01 5 3.100419E+02 8.996458E+01 1.916507E-01 3.100419E+02 - 3.989996E+01 3.000000E+01 6 3.254287E+01 -2.259212E-04 3.254287E+01 -1.283188E-04 - 3.989996E+01 6.000000E+01 1 1.673446E+01 8.996458E+01 1.034388E-02 1.673446E+01 - 3.989996E+01 6.000000E+01 2 3.064868E+01 8.996093E+01 2.090178E-02 3.064867E+01 - 3.989996E+01 6.000000E+01 3 1.969134E+02 1.550093E-01 1.969127E+02 5.327333E-01 - 3.989996E+01 6.000000E+01 4 9.880065E+01 8.996093E+01 6.738003E-02 9.880063E+01 - 3.989996E+01 6.000000E+01 5 1.796355E+02 8.996458E+01 1.110448E-01 1.796355E+02 - 3.989996E+01 6.000000E+01 6 3.267602E+01 -2.256090E-04 3.267602E+01 -1.286658E-04 - 3.989996E+01 9.000000E+01 1 1.729837E-06 -9.002778E+01 -8.387184E-10 -1.729837E-06 - 3.989996E+01 9.000000E+01 2 3.546024E+01 8.996093E+01 2.418354E-02 3.546024E+01 - 3.989996E+01 9.000000E+01 3 1.973143E+02 1.551450E-01 1.973135E+02 5.342851E-01 - 3.989996E+01 9.000000E+01 4 1.145147E+02 8.996100E+01 7.795913E-02 1.145147E+02 - 3.989996E+01 9.000000E+01 5 8.064335E-05 -8.999587E+01 5.815583E-09 -8.064335E-05 - 3.989996E+01 9.000000E+01 6 2.800145E-06 1.799998E+02 -2.800145E-06 7.471601E-12 - 3.999996E+01 0.000000E+00 1 3.320465E+01 8.996477E+01 2.041850E-02 3.320465E+01 - 3.999996E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.999996E+01 0.000000E+00 3 1.957785E+02 1.538118E-01 1.957778E+02 5.255712E-01 - 3.999996E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.999996E+01 0.000000E+00 5 3.565649E+02 8.996477E+01 2.192550E-01 3.565648E+02 - 3.999996E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 3.999996E+01 3.000000E+01 1 2.880771E+01 8.996477E+01 1.771444E-02 2.880770E+01 - 3.999996E+01 3.000000E+01 2 1.758072E+01 8.996114E+01 1.192426E-02 1.758072E+01 - 3.999996E+01 3.000000E+01 3 1.961747E+02 1.539455E-01 1.961740E+02 5.270925E-01 - 3.999996E+01 3.000000E+01 4 5.646617E+01 8.996101E+01 3.843560E-02 5.646616E+01 - 3.999996E+01 3.000000E+01 5 3.093363E+02 8.996477E+01 1.902190E-01 3.093362E+02 - 3.999996E+01 3.000000E+01 6 3.237609E+01 -2.235112E-04 3.237609E+01 -1.262993E-04 - 3.999996E+01 6.000000E+01 1 1.669209E+01 8.996478E+01 1.026392E-02 1.669209E+01 - 3.999996E+01 6.000000E+01 2 3.057104E+01 8.996114E+01 2.073569E-02 3.057104E+01 - 3.999996E+01 6.000000E+01 3 1.969688E+02 1.542149E-01 1.969681E+02 5.301523E-01 - 3.999996E+01 6.000000E+01 4 9.854043E+01 8.996114E+01 6.683791E-02 9.854041E+01 - 3.999996E+01 6.000000E+01 5 1.792234E+02 8.996477E+01 1.102135E-01 1.792234E+02 - 3.999996E+01 6.000000E+01 6 3.250790E+01 -2.232043E-04 3.250790E+01 -1.266394E-04 - 3.999996E+01 9.000000E+01 1 1.725425E-06 -9.002765E+01 -8.327025E-10 -1.725425E-06 - 3.999996E+01 9.000000E+01 2 3.537007E+01 8.996114E+01 2.399109E-02 3.537006E+01 - 3.999996E+01 9.000000E+01 3 1.973673E+02 1.543482E-01 1.973666E+02 5.316841E-01 - 3.999996E+01 9.000000E+01 4 1.142105E+02 8.996120E+01 7.733064E-02 1.142104E+02 - 3.999996E+01 9.000000E+01 5 8.044456E-05 -8.999590E+01 5.764136E-09 -8.044456E-05 - 3.999996E+01 9.000000E+01 6 2.785697E-06 1.799999E+02 -2.785697E-06 7.354008E-12 - 4.009996E+01 0.000000E+00 1 3.312164E+01 8.996495E+01 2.026160E-02 3.312163E+01 - 4.009996E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 4.009996E+01 0.000000E+00 3 1.958400E+02 1.530287E-01 1.958392E+02 5.230594E-01 - 4.009996E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 4.009996E+01 0.000000E+00 5 3.557611E+02 8.996495E+01 2.176235E-01 3.557611E+02 - 4.009996E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 4.009996E+01 3.000000E+01 1 2.873561E+01 8.996495E+01 1.757813E-02 2.873560E+01 - 4.009996E+01 3.000000E+01 2 1.753668E+01 8.996135E+01 1.183001E-02 1.753667E+01 - 4.009996E+01 3.000000E+01 3 1.962338E+02 1.531619E-01 1.962331E+02 5.245677E-01 - 4.009996E+01 3.000000E+01 4 5.631999E+01 8.996121E+01 3.812789E-02 5.631998E+01 - 4.009996E+01 3.000000E+01 5 3.086360E+02 8.996495E+01 1.887998E-01 3.086359E+02 - 4.009996E+01 3.000000E+01 6 3.221068E+01 -2.211336E-04 3.221068E+01 -1.243174E-04 - 4.009996E+01 6.000000E+01 1 1.665001E+01 8.996495E+01 1.018477E-02 1.665000E+01 - 4.009996E+01 6.000000E+01 2 3.049393E+01 8.996135E+01 2.057135E-02 3.049392E+01 - 4.009996E+01 6.000000E+01 3 1.970240E+02 1.534273E-01 1.970233E+02 5.275925E-01 - 4.009996E+01 6.000000E+01 4 9.828146E+01 8.996135E+01 6.630120E-02 9.828143E+01 - 4.009996E+01 6.000000E+01 5 1.788146E+02 8.996495E+01 1.093894E-01 1.788146E+02 - 4.009996E+01 6.000000E+01 6 3.234111E+01 -2.208314E-04 3.234111E+01 -1.246502E-04 - 4.009996E+01 9.000000E+01 1 1.721028E-06 -9.002752E+01 -8.267444E-10 -1.721028E-06 - 4.009996E+01 9.000000E+01 2 3.528042E+01 8.996135E+01 2.380072E-02 3.528041E+01 - 4.009996E+01 9.000000E+01 3 1.974205E+02 1.535598E-01 1.974198E+02 5.291107E-01 - 4.009996E+01 9.000000E+01 4 1.139085E+02 8.996142E+01 7.670912E-02 1.139085E+02 - 4.009996E+01 9.000000E+01 5 8.024606E-05 -8.999592E+01 5.713281E-09 -8.024606E-05 - 4.009996E+01 9.000000E+01 6 2.771365E-06 1.799999E+02 -2.771365E-06 7.238607E-12 - 4.019996E+01 0.000000E+00 1 3.303928E+01 8.996513E+01 2.010638E-02 3.303927E+01 - 4.019996E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 4.019996E+01 0.000000E+00 3 1.959009E+02 1.522496E-01 1.959002E+02 5.205586E-01 - 4.019996E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 4.019996E+01 0.000000E+00 5 3.549574E+02 8.996513E+01 2.160077E-01 3.549573E+02 - 4.019996E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 4.019996E+01 3.000000E+01 1 2.866374E+01 8.996513E+01 1.744330E-02 2.866374E+01 - 4.019996E+01 3.000000E+01 2 1.749287E+01 8.996156E+01 1.173675E-02 1.749286E+01 - 4.019996E+01 3.000000E+01 3 1.962927E+02 1.523809E-01 1.962921E+02 5.220496E-01 - 4.019996E+01 3.000000E+01 4 5.617453E+01 8.996142E+01 3.782352E-02 5.617452E+01 - 4.019996E+01 3.000000E+01 5 3.079387E+02 8.996513E+01 1.873970E-01 3.079387E+02 - 4.019996E+01 3.000000E+01 6 3.204650E+01 -2.187878E-04 3.204650E+01 -1.223717E-04 - 4.019996E+01 6.000000E+01 1 1.660806E+01 8.996513E+01 1.010648E-02 1.660806E+01 - 4.019996E+01 6.000000E+01 2 3.041706E+01 8.996156E+01 2.040876E-02 3.041706E+01 - 4.019996E+01 6.000000E+01 3 1.970783E+02 1.526451E-01 1.970776E+02 5.250474E-01 - 4.019996E+01 6.000000E+01 4 9.802399E+01 8.996156E+01 6.577053E-02 9.802396E+01 - 4.019996E+01 6.000000E+01 5 1.784067E+02 8.996513E+01 1.085742E-01 1.784067E+02 - 4.019996E+01 6.000000E+01 6 3.217555E+01 -2.184905E-04 3.217555E+01 -1.226976E-04 - 4.019996E+01 9.000000E+01 1 1.716656E-06 -9.002740E+01 -8.208414E-10 -1.716656E-06 - 4.019996E+01 9.000000E+01 2 3.519121E+01 8.996156E+01 2.361234E-02 3.519120E+01 - 4.019996E+01 9.000000E+01 3 1.974738E+02 1.527754E-01 1.974731E+02 5.265502E-01 - 4.019996E+01 9.000000E+01 4 1.136077E+02 8.996162E+01 7.609409E-02 1.136077E+02 - 4.019996E+01 9.000000E+01 5 8.004906E-05 -8.999595E+01 5.663037E-09 -8.004906E-05 - 4.019996E+01 9.000000E+01 6 2.757139E-06 1.799999E+02 -2.757139E-06 7.125311E-12 - 4.029996E+01 0.000000E+00 1 3.295703E+01 8.996532E+01 1.995263E-02 3.295702E+01 - 4.029996E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 4.029996E+01 0.000000E+00 3 1.959606E+02 1.514774E-01 1.959600E+02 5.180761E-01 - 4.029996E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 4.029996E+01 0.000000E+00 5 3.541636E+02 8.996532E+01 2.144059E-01 3.541636E+02 - 4.029996E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 4.029996E+01 3.000000E+01 1 2.859224E+01 8.996532E+01 1.730978E-02 2.859224E+01 - 4.029996E+01 3.000000E+01 2 1.744927E+01 8.996177E+01 1.164448E-02 1.744927E+01 - 4.029996E+01 3.000000E+01 3 1.963510E+02 1.516075E-01 1.963503E+02 5.195538E-01 - 4.029996E+01 3.000000E+01 4 5.602977E+01 8.996163E+01 3.752217E-02 5.602976E+01 - 4.029996E+01 3.000000E+01 5 3.072437E+02 8.996532E+01 1.860085E-01 3.072437E+02 - 4.029996E+01 3.000000E+01 6 3.188359E+01 -2.164738E-04 3.188359E+01 -1.204619E-04 - 4.029996E+01 6.000000E+01 1 1.656636E+01 8.996532E+01 1.002894E-02 1.656636E+01 - 4.029996E+01 6.000000E+01 2 3.034069E+01 8.996176E+01 2.024794E-02 3.034068E+01 - 4.029996E+01 6.000000E+01 3 1.971331E+02 1.518685E-01 1.971324E+02 5.225213E-01 - 4.029996E+01 6.000000E+01 4 9.776756E+01 8.996176E+01 6.524529E-02 9.776753E+01 - 4.029996E+01 6.000000E+01 5 1.780007E+02 8.996532E+01 1.077677E-01 1.780007E+02 - 4.029996E+01 6.000000E+01 6 3.201136E+01 -2.161809E-04 3.201136E+01 -1.207811E-04 - 4.029996E+01 9.000000E+01 1 1.712306E-06 -9.002727E+01 -8.149911E-10 -1.712306E-06 - 4.029996E+01 9.000000E+01 2 3.510244E+01 8.996176E+01 2.342605E-02 3.510243E+01 - 4.029996E+01 9.000000E+01 3 1.975260E+02 1.519973E-01 1.975253E+02 5.240071E-01 - 4.029996E+01 9.000000E+01 4 1.133087E+02 8.996183E+01 7.548621E-02 1.133086E+02 - 4.029996E+01 9.000000E+01 5 7.985276E-05 -8.999597E+01 5.613394E-09 -7.985276E-05 - 4.029996E+01 9.000000E+01 6 2.743030E-06 1.799999E+02 -2.743030E-06 7.014102E-12 - 4.039996E+01 0.000000E+00 1 3.287546E+01 8.996549E+01 1.980058E-02 3.287545E+01 - 4.039996E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 4.039996E+01 0.000000E+00 3 1.960204E+02 1.507102E-01 1.960197E+02 5.156092E-01 - 4.039996E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 4.039996E+01 0.000000E+00 5 3.533676E+02 8.996549E+01 2.128220E-01 3.533676E+02 - 4.039996E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 4.039996E+01 3.000000E+01 1 2.852114E+01 8.996549E+01 1.717774E-02 2.852114E+01 - 4.039996E+01 3.000000E+01 2 1.740592E+01 8.996198E+01 1.155320E-02 1.740591E+01 - 4.039996E+01 3.000000E+01 3 1.964086E+02 1.508387E-01 1.964080E+02 5.170711E-01 - 4.039996E+01 3.000000E+01 4 5.588592E+01 8.996184E+01 3.722446E-02 5.588591E+01 - 4.039996E+01 3.000000E+01 5 3.065521E+02 8.996549E+01 1.846313E-01 3.065520E+02 - 4.039996E+01 3.000000E+01 6 3.172192E+01 -2.141900E-04 3.172192E+01 -1.185867E-04 - 4.039996E+01 6.000000E+01 1 1.652482E+01 8.996550E+01 9.952208E-03 1.652481E+01 - 4.039996E+01 6.000000E+01 2 3.026465E+01 8.996198E+01 2.008883E-02 3.026465E+01 - 4.039996E+01 6.000000E+01 3 1.971876E+02 1.510966E-01 1.971869E+02 5.200093E-01 - 4.039996E+01 6.000000E+01 4 9.751318E+01 8.996198E+01 6.472613E-02 9.751316E+01 - 4.039996E+01 6.000000E+01 5 1.775966E+02 8.996549E+01 1.069684E-01 1.775965E+02 - 4.039996E+01 6.000000E+01 6 3.184841E+01 -2.139018E-04 3.184841E+01 -1.188994E-04 - 4.039996E+01 9.000000E+01 1 1.707981E-06 -9.002715E+01 -8.092000E-10 -1.707981E-06 - 4.039996E+01 9.000000E+01 2 3.501406E+01 8.996197E+01 2.324169E-02 3.501406E+01 - 4.039996E+01 9.000000E+01 3 1.975780E+02 1.512246E-01 1.975773E+02 5.214803E-01 - 4.039996E+01 9.000000E+01 4 1.130111E+02 8.996204E+01 7.488450E-02 1.130111E+02 - 4.039996E+01 9.000000E+01 5 7.965770E-05 -8.999600E+01 5.564346E-09 -7.965770E-05 - 4.039996E+01 9.000000E+01 6 2.729023E-06 1.799999E+02 -2.729023E-06 6.904941E-12 - 4.049995E+01 0.000000E+00 1 3.279421E+01 8.996567E+01 1.964999E-02 3.279420E+01 - 4.049995E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 4.049995E+01 0.000000E+00 3 1.960799E+02 1.499503E-01 1.960792E+02 5.131652E-01 - 4.049995E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 4.049995E+01 0.000000E+00 5 3.525754E+02 8.996567E+01 2.112527E-01 3.525753E+02 - 4.049995E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 4.049995E+01 3.000000E+01 1 2.845046E+01 8.996567E+01 1.704697E-02 2.845045E+01 - 4.049995E+01 3.000000E+01 2 1.736274E+01 8.996217E+01 1.146286E-02 1.736274E+01 - 4.049995E+01 3.000000E+01 3 1.964659E+02 1.500772E-01 1.964653E+02 5.146107E-01 - 4.049995E+01 3.000000E+01 4 5.574275E+01 8.996204E+01 3.692957E-02 5.574274E+01 - 4.049995E+01 3.000000E+01 5 3.058630E+02 8.996567E+01 1.832678E-01 3.058629E+02 - 4.049995E+01 3.000000E+01 6 3.156149E+01 -2.119369E-04 3.156149E+01 -1.167458E-04 - 4.049995E+01 6.000000E+01 1 1.648354E+01 8.996568E+01 9.876294E-03 1.648354E+01 - 4.049995E+01 6.000000E+01 2 3.018898E+01 8.996217E+01 1.993131E-02 3.018898E+01 - 4.049995E+01 6.000000E+01 3 1.972407E+02 1.503313E-01 1.972400E+02 5.175146E-01 - 4.049995E+01 6.000000E+01 4 9.725953E+01 8.996217E+01 6.421261E-02 9.725951E+01 - 4.049995E+01 6.000000E+01 5 1.771948E+02 8.996567E+01 1.061767E-01 1.771948E+02 - 4.049995E+01 6.000000E+01 6 3.168669E+01 -2.116531E-04 3.168669E+01 -1.170520E-04 - 4.049995E+01 9.000000E+01 1 1.703676E-06 -9.002702E+01 -8.034552E-10 -1.703675E-06 - 4.049995E+01 9.000000E+01 2 3.492622E+01 8.996217E+01 2.305922E-02 3.492622E+01 - 4.049995E+01 9.000000E+01 3 1.976297E+02 1.504593E-01 1.976290E+02 5.189769E-01 - 4.049995E+01 9.000000E+01 4 1.127156E+02 8.996224E+01 7.428924E-02 1.127155E+02 - 4.049995E+01 9.000000E+01 5 7.946385E-05 -8.999603E+01 5.515868E-09 -7.946385E-05 - 4.049995E+01 9.000000E+01 6 2.715130E-06 1.799999E+02 -2.715130E-06 6.797745E-12 - 4.059995E+01 0.000000E+00 1 3.271325E+01 8.996584E+01 1.950096E-02 3.271324E+01 - 4.059995E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 4.059995E+01 0.000000E+00 3 1.961385E+02 1.491946E-01 1.961378E+02 5.107317E-01 - 4.059995E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 4.059995E+01 0.000000E+00 5 3.517873E+02 8.996584E+01 2.096995E-01 3.517872E+02 - 4.059995E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 4.059995E+01 3.000000E+01 1 2.837998E+01 8.996584E+01 1.691754E-02 2.837998E+01 - 4.059995E+01 3.000000E+01 2 1.731980E+01 8.996238E+01 1.137349E-02 1.731979E+01 - 4.059995E+01 3.000000E+01 3 1.965233E+02 1.493207E-01 1.965226E+02 5.121662E-01 - 4.059995E+01 3.000000E+01 4 5.560034E+01 8.996225E+01 3.663821E-02 5.560033E+01 - 4.059995E+01 3.000000E+01 5 3.051753E+02 8.996584E+01 1.819187E-01 3.051753E+02 - 4.059995E+01 3.000000E+01 6 3.140228E+01 -2.097140E-04 3.140228E+01 -1.149386E-04 - 4.059995E+01 6.000000E+01 1 1.644245E+01 8.996584E+01 9.801122E-03 1.644245E+01 - 4.059995E+01 6.000000E+01 2 3.011368E+01 8.996238E+01 1.977553E-02 3.011367E+01 - 4.059995E+01 6.000000E+01 3 1.972942E+02 1.495721E-01 1.972936E+02 5.150411E-01 - 4.059995E+01 6.000000E+01 4 9.700747E+01 8.996238E+01 6.370434E-02 9.700745E+01 - 4.059995E+01 6.000000E+01 5 1.767935E+02 8.996584E+01 1.053927E-01 1.767935E+02 - 4.059995E+01 6.000000E+01 6 3.152621E+01 -2.094345E-04 3.152621E+01 -1.152385E-04 - 4.059995E+01 9.000000E+01 1 1.699390E-06 -9.002690E+01 -7.977697E-10 -1.699390E-06 - 4.059995E+01 9.000000E+01 2 3.483888E+01 8.996238E+01 2.287880E-02 3.483887E+01 - 4.059995E+01 9.000000E+01 3 1.976806E+02 1.496988E-01 1.976799E+02 5.164867E-01 - 4.059995E+01 9.000000E+01 4 1.124213E+02 8.996244E+01 7.370064E-02 1.124213E+02 - 4.059995E+01 9.000000E+01 5 7.927052E-05 -8.999605E+01 5.467943E-09 -7.927052E-05 - 4.059995E+01 9.000000E+01 6 2.701340E-06 1.799999E+02 -2.701340E-06 6.692506E-12 - 4.069995E+01 0.000000E+00 1 3.263289E+01 8.996603E+01 1.935353E-02 3.263288E+01 - 4.069995E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 4.069995E+01 0.000000E+00 3 1.961976E+02 1.484455E-01 1.961970E+02 5.083206E-01 - 4.069995E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 4.069995E+01 0.000000E+00 5 3.510041E+02 8.996603E+01 2.081631E-01 3.510041E+02 - 4.069995E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 4.069995E+01 3.000000E+01 1 2.830993E+01 8.996603E+01 1.678942E-02 2.830993E+01 - 4.069995E+01 3.000000E+01 2 1.727706E+01 8.996258E+01 1.128505E-02 1.727706E+01 - 4.069995E+01 3.000000E+01 3 1.965800E+02 1.485692E-01 1.965794E+02 5.097358E-01 - 4.069995E+01 3.000000E+01 4 5.545845E+01 8.996245E+01 3.634970E-02 5.545844E+01 - 4.069995E+01 3.000000E+01 5 3.044943E+02 8.996603E+01 1.805845E-01 3.044942E+02 - 4.069995E+01 3.000000E+01 6 3.124430E+01 -2.075199E-04 3.124430E+01 -1.131639E-04 - 4.069995E+01 6.000000E+01 1 1.640158E+01 8.996603E+01 9.726741E-03 1.640157E+01 - 4.069995E+01 6.000000E+01 2 3.003879E+01 8.996258E+01 1.962136E-02 3.003879E+01 - 4.069995E+01 6.000000E+01 3 1.973477E+02 1.488191E-01 1.973470E+02 5.125871E-01 - 4.069995E+01 6.000000E+01 4 9.675658E+01 8.996258E+01 6.320155E-02 9.675656E+01 - 4.069995E+01 6.000000E+01 5 1.763951E+02 8.996603E+01 1.046166E-01 1.763950E+02 - 4.069995E+01 6.000000E+01 6 3.136693E+01 -2.072453E-04 3.136693E+01 -1.134577E-04 - 4.069995E+01 9.000000E+01 1 1.695126E-06 -9.002678E+01 -7.921360E-10 -1.695126E-06 - 4.069995E+01 9.000000E+01 2 3.475193E+01 8.996258E+01 2.270026E-02 3.475192E+01 - 4.069995E+01 9.000000E+01 3 1.977326E+02 1.489436E-01 1.977319E+02 5.140165E-01 - 4.069995E+01 9.000000E+01 4 1.121284E+02 8.996264E+01 7.311802E-02 1.121284E+02 - 4.069995E+01 9.000000E+01 5 7.907810E-05 -8.999608E+01 5.420604E-09 -7.907810E-05 - 4.069995E+01 9.000000E+01 6 2.687661E-06 1.799999E+02 -2.687661E-06 6.589171E-12 - 4.079995E+01 0.000000E+00 1 3.255276E+01 8.996619E+01 1.920751E-02 3.255275E+01 - 4.079995E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 4.079995E+01 0.000000E+00 3 1.962558E+02 1.477009E-01 1.962551E+02 5.059208E-01 - 4.079995E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 4.079995E+01 0.000000E+00 5 3.502239E+02 8.996619E+01 2.066392E-01 3.502238E+02 - 4.079995E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 4.079995E+01 3.000000E+01 1 2.824017E+01 8.996619E+01 1.666256E-02 2.824016E+01 - 4.079995E+01 3.000000E+01 2 1.723453E+01 8.996277E+01 1.119755E-02 1.723453E+01 - 4.079995E+01 3.000000E+01 3 1.966361E+02 1.478246E-01 1.966355E+02 5.073256E-01 - 4.079995E+01 3.000000E+01 4 5.531755E+01 8.996265E+01 3.606433E-02 5.531754E+01 - 4.079995E+01 3.000000E+01 5 3.038132E+02 8.996619E+01 1.792597E-01 3.038131E+02 - 4.079995E+01 3.000000E+01 6 3.108752E+01 -2.053552E-04 3.108752E+01 -1.114216E-04 - 4.079995E+01 6.000000E+01 1 1.636086E+01 8.996619E+01 9.653110E-03 1.636086E+01 - 4.079995E+01 6.000000E+01 2 2.996427E+01 8.996277E+01 1.946885E-02 2.996426E+01 - 4.079995E+01 6.000000E+01 3 1.973997E+02 1.480717E-01 1.973990E+02 5.101469E-01 - 4.079995E+01 6.000000E+01 4 9.650729E+01 8.996277E+01 6.270389E-02 9.650727E+01 - 4.079995E+01 6.000000E+01 5 1.759977E+02 8.996619E+01 1.038493E-01 1.759977E+02 - 4.079995E+01 6.000000E+01 6 3.120890E+01 -2.050848E-04 3.120890E+01 -1.117093E-04 - 4.079995E+01 9.000000E+01 1 1.690887E-06 -9.002666E+01 -7.865527E-10 -1.690886E-06 - 4.079995E+01 9.000000E+01 2 3.466522E+01 8.996277E+01 2.252354E-02 3.466521E+01 - 4.079995E+01 9.000000E+01 3 1.977833E+02 1.481944E-01 1.977827E+02 5.115621E-01 - 4.079995E+01 9.000000E+01 4 1.118374E+02 8.996284E+01 7.254177E-02 1.118374E+02 - 4.079995E+01 9.000000E+01 5 7.888634E-05 -8.999609E+01 5.373834E-09 -7.888634E-05 - 4.079995E+01 9.000000E+01 6 2.674085E-06 1.799999E+02 -2.674085E-06 6.487719E-12 - 4.089995E+01 0.000000E+00 1 3.247310E+01 8.996636E+01 1.906293E-02 3.247309E+01 - 4.089995E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 4.089995E+01 0.000000E+00 3 1.963145E+02 1.469615E-01 1.963138E+02 5.035388E-01 - 4.089995E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 4.089995E+01 0.000000E+00 5 3.494464E+02 8.996636E+01 2.051320E-01 3.494464E+02 - 4.089995E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 4.089995E+01 3.000000E+01 1 2.817088E+01 8.996636E+01 1.653707E-02 2.817087E+01 - 4.089995E+01 3.000000E+01 2 1.719222E+01 8.996297E+01 1.111097E-02 1.719222E+01 - 4.089995E+01 3.000000E+01 3 1.966925E+02 1.470845E-01 1.966918E+02 5.049306E-01 - 4.089995E+01 3.000000E+01 4 5.517721E+01 8.996284E+01 3.578190E-02 5.517720E+01 - 4.089995E+01 3.000000E+01 5 3.031367E+02 8.996636E+01 1.779512E-01 3.031367E+02 - 4.089995E+01 3.000000E+01 6 3.093188E+01 -2.032194E-04 3.093188E+01 -1.097107E-04 - 4.089995E+01 6.000000E+01 1 1.632039E+01 8.996636E+01 9.580210E-03 1.632039E+01 - 4.089995E+01 6.000000E+01 2 2.989011E+01 8.996297E+01 1.931791E-02 2.989010E+01 - 4.089995E+01 6.000000E+01 3 1.974520E+02 1.473293E-01 1.974513E+02 5.077238E-01 - 4.089995E+01 6.000000E+01 4 9.625885E+01 8.996297E+01 6.221196E-02 9.625883E+01 - 4.089995E+01 6.000000E+01 5 1.756040E+02 8.996636E+01 1.030882E-01 1.756040E+02 - 4.089995E+01 6.000000E+01 6 3.105209E+01 -2.029524E-04 3.105209E+01 -1.099923E-04 - 4.089995E+01 9.000000E+01 1 1.686668E-06 -9.002654E+01 -7.810206E-10 -1.686668E-06 - 4.089995E+01 9.000000E+01 2 3.457918E+01 8.996297E+01 2.234869E-02 3.457917E+01 - 4.089995E+01 9.000000E+01 3 1.978335E+02 1.474513E-01 1.978328E+02 5.091259E-01 - 4.089995E+01 9.000000E+01 4 1.115479E+02 8.996303E+01 7.197204E-02 1.115479E+02 - 4.089995E+01 9.000000E+01 5 7.869596E-05 -8.999612E+01 5.327563E-09 -7.869596E-05 - 4.089995E+01 9.000000E+01 6 2.660611E-06 1.799999E+02 -2.660611E-06 6.388090E-12 - 4.099995E+01 0.000000E+00 1 3.239382E+01 8.996654E+01 1.891988E-02 3.239382E+01 - 4.099995E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 4.099995E+01 0.000000E+00 3 1.963704E+02 1.462304E-01 1.963698E+02 5.011762E-01 - 4.099995E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 4.099995E+01 0.000000E+00 5 3.486714E+02 8.996654E+01 2.036370E-01 3.486713E+02 - 4.099995E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 4.099995E+01 3.000000E+01 1 2.810176E+01 8.996654E+01 1.641283E-02 2.810175E+01 - 4.099995E+01 3.000000E+01 2 1.715014E+01 8.996317E+01 1.102528E-02 1.715014E+01 - 4.099995E+01 3.000000E+01 3 1.967476E+02 1.463505E-01 1.967469E+02 5.025514E-01 - 4.099995E+01 3.000000E+01 4 5.503794E+01 8.996304E+01 3.550260E-02 5.503793E+01 - 4.099995E+01 3.000000E+01 5 3.024617E+02 8.996654E+01 1.766532E-01 3.024617E+02 - 4.099995E+01 3.000000E+01 6 3.077749E+01 -2.011104E-04 3.077749E+01 -1.080302E-04 - 4.099995E+01 6.000000E+01 1 1.628016E+01 8.996654E+01 9.508057E-03 1.628015E+01 - 4.099995E+01 6.000000E+01 2 2.981628E+01 8.996317E+01 1.916851E-02 2.981628E+01 - 4.099995E+01 6.000000E+01 3 1.975037E+02 1.465924E-01 1.975031E+02 5.053167E-01 - 4.099995E+01 6.000000E+01 4 9.601196E+01 8.996317E+01 6.172496E-02 9.601194E+01 - 4.099995E+01 6.000000E+01 5 1.752095E+02 8.996654E+01 1.023354E-01 1.752095E+02 - 4.099995E+01 6.000000E+01 6 3.089643E+01 -2.008485E-04 3.089643E+01 -1.083064E-04 - 4.099995E+01 9.000000E+01 1 1.682470E-06 -9.002641E+01 -7.755393E-10 -1.682470E-06 - 4.099995E+01 9.000000E+01 2 3.449349E+01 8.996317E+01 2.217570E-02 3.449348E+01 - 4.099995E+01 9.000000E+01 3 1.978830E+02 1.467138E-01 1.978823E+02 5.067064E-01 - 4.099995E+01 9.000000E+01 4 1.112597E+02 8.996323E+01 7.140781E-02 1.112596E+02 - 4.099995E+01 9.000000E+01 5 7.850649E-05 -8.999615E+01 5.281842E-09 -7.850649E-05 - 4.099995E+01 9.000000E+01 6 2.647239E-06 1.799999E+02 -2.647239E-06 6.290251E-12 - 4.109995E+01 0.000000E+00 1 3.231490E+01 8.996671E+01 1.877822E-02 3.231489E+01 - 4.109995E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 4.109995E+01 0.000000E+00 3 1.964281E+02 1.455039E-01 1.964275E+02 4.988329E-01 - 4.109995E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 4.109995E+01 0.000000E+00 5 3.479012E+02 8.996671E+01 2.021575E-01 3.479011E+02 - 4.109995E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 4.109995E+01 3.000000E+01 1 2.803311E+01 8.996671E+01 1.628979E-02 2.803311E+01 - 4.109995E+01 3.000000E+01 2 1.710815E+01 8.996336E+01 1.094047E-02 1.710815E+01 - 4.109995E+01 3.000000E+01 3 1.968031E+02 1.456230E-01 1.968025E+02 5.001945E-01 - 4.109995E+01 3.000000E+01 4 5.489897E+01 8.996323E+01 3.522610E-02 5.489896E+01 - 4.109995E+01 3.000000E+01 5 3.017893E+02 8.996671E+01 1.753680E-01 3.017892E+02 - 4.109995E+01 3.000000E+01 6 3.062420E+01 -1.990296E-04 3.062420E+01 -1.063799E-04 - 4.109995E+01 6.000000E+01 1 1.624005E+01 8.996671E+01 9.436644E-03 1.624005E+01 - 4.109995E+01 6.000000E+01 2 2.974290E+01 8.996336E+01 1.902069E-02 2.974290E+01 - 4.109995E+01 6.000000E+01 3 1.975564E+02 1.458618E-01 1.975558E+02 5.029322E-01 - 4.109995E+01 6.000000E+01 4 9.576618E+01 8.996336E+01 6.124310E-02 9.576616E+01 - 4.109995E+01 6.000000E+01 5 1.748182E+02 8.996671E+01 1.015888E-01 1.748182E+02 - 4.109995E+01 6.000000E+01 6 3.074196E+01 -1.987714E-04 3.074196E+01 -1.066505E-04 - 4.109995E+01 9.000000E+01 1 1.678294E-06 -9.002629E+01 -7.701091E-10 -1.678294E-06 - 4.109995E+01 9.000000E+01 2 3.440830E+01 8.996336E+01 2.200449E-02 3.440829E+01 - 4.109995E+01 9.000000E+01 3 1.979326E+02 1.459821E-01 1.979320E+02 5.043058E-01 - 4.109995E+01 9.000000E+01 4 1.109734E+02 8.996342E+01 7.084974E-02 1.109734E+02 - 4.109995E+01 9.000000E+01 5 7.831767E-05 -8.999617E+01 5.236675E-09 -7.831767E-05 - 4.109995E+01 9.000000E+01 6 2.633970E-06 1.799999E+02 -2.633970E-06 6.194161E-12 - 4.119994E+01 0.000000E+00 1 3.223639E+01 8.996688E+01 1.863800E-02 3.223639E+01 - 4.119994E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 4.119994E+01 0.000000E+00 3 1.964843E+02 1.447822E-01 1.964837E+02 4.965008E-01 - 4.119994E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 4.119994E+01 0.000000E+00 5 3.471302E+02 8.996688E+01 2.006911E-01 3.471302E+02 - 4.119994E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 4.119994E+01 3.000000E+01 1 2.796481E+01 8.996688E+01 1.616803E-02 2.796480E+01 - 4.119994E+01 3.000000E+01 2 1.706651E+01 8.996355E+01 1.085656E-02 1.706650E+01 - 4.119994E+01 3.000000E+01 3 1.968574E+02 1.449003E-01 1.968568E+02 4.978493E-01 - 4.119994E+01 3.000000E+01 4 5.476097E+01 8.996342E+01 3.495253E-02 5.476096E+01 - 4.119994E+01 3.000000E+01 5 3.011182E+02 8.996688E+01 1.740967E-01 3.011181E+02 - 4.119994E+01 3.000000E+01 6 3.047206E+01 -1.969765E-04 3.047206E+01 -1.047596E-04 - 4.119994E+01 6.000000E+01 1 1.620018E+01 8.996688E+01 9.365939E-03 1.620017E+01 - 4.119994E+01 6.000000E+01 2 2.966987E+01 8.996355E+01 1.887443E-02 2.966987E+01 - 4.119994E+01 6.000000E+01 3 1.976069E+02 1.451368E-01 1.976063E+02 5.005605E-01 - 4.119994E+01 6.000000E+01 4 9.552213E+01 8.996355E+01 6.076624E-02 9.552210E+01 - 4.119994E+01 6.000000E+01 5 1.744270E+02 8.996687E+01 1.008510E-01 1.744269E+02 - 4.119994E+01 6.000000E+01 6 3.058869E+01 -1.967219E-04 3.058869E+01 -1.050246E-04 - 4.119994E+01 9.000000E+01 1 1.674138E-06 -9.002617E+01 -7.647286E-10 -1.674137E-06 - 4.119994E+01 9.000000E+01 2 3.432342E+01 8.996355E+01 2.183509E-02 3.432341E+01 - 4.119994E+01 9.000000E+01 3 1.979819E+02 1.452558E-01 1.979812E+02 5.019214E-01 - 4.119994E+01 9.000000E+01 4 1.106882E+02 8.996362E+01 7.029747E-02 1.106882E+02 - 4.119994E+01 9.000000E+01 5 7.813003E-05 -8.999619E+01 5.192008E-09 -7.813003E-05 - 4.119994E+01 9.000000E+01 6 2.620804E-06 1.799999E+02 -2.620804E-06 6.099818E-12 - 4.129994E+01 0.000000E+00 1 3.215831E+01 8.996704E+01 1.849917E-02 3.215830E+01 - 4.129994E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 4.129994E+01 0.000000E+00 3 1.965396E+02 1.440657E-01 1.965389E+02 4.941826E-01 - 4.129994E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 4.129994E+01 0.000000E+00 5 3.463657E+02 8.996704E+01 1.992409E-01 3.463656E+02 - 4.129994E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 4.129994E+01 3.000000E+01 1 2.789677E+01 8.996704E+01 1.604749E-02 2.789677E+01 - 4.129994E+01 3.000000E+01 2 1.702501E+01 8.996375E+01 1.077350E-02 1.702500E+01 - 4.129994E+01 3.000000E+01 3 1.969117E+02 1.441831E-01 1.969111E+02 4.955220E-01 - 4.129994E+01 3.000000E+01 4 5.462371E+01 8.996362E+01 3.468196E-02 5.462370E+01 - 4.129994E+01 3.000000E+01 5 3.004536E+02 8.996704E+01 1.728359E-01 3.004535E+02 - 4.129994E+01 3.000000E+01 6 3.032113E+01 -1.949495E-04 3.032113E+01 -1.031679E-04 - 4.129994E+01 6.000000E+01 1 1.616049E+01 8.996704E+01 9.295954E-03 1.616048E+01 - 4.129994E+01 6.000000E+01 2 2.959719E+01 8.996375E+01 1.872970E-02 2.959719E+01 - 4.129994E+01 6.000000E+01 3 1.976570E+02 1.444177E-01 1.976563E+02 4.982067E-01 - 4.129994E+01 6.000000E+01 4 9.527947E+01 8.996375E+01 6.029442E-02 9.527945E+01 - 4.129994E+01 6.000000E+01 5 1.740376E+02 8.996704E+01 1.001183E-01 1.740376E+02 - 4.129994E+01 6.000000E+01 6 3.043653E+01 -1.946994E-04 3.043653E+01 -1.034277E-04 - 4.129994E+01 9.000000E+01 1 1.670004E-06 -9.002605E+01 -7.593959E-10 -1.670004E-06 - 4.129994E+01 9.000000E+01 2 3.423899E+01 8.996375E+01 2.166739E-02 3.423898E+01 - 4.129994E+01 9.000000E+01 3 1.980305E+02 1.445356E-01 1.980299E+02 4.995557E-01 - 4.129994E+01 9.000000E+01 4 1.104047E+02 8.996381E+01 6.975102E-02 1.104047E+02 - 4.129994E+01 9.000000E+01 5 7.794305E-05 -8.999622E+01 5.147867E-09 -7.794305E-05 - 4.129994E+01 9.000000E+01 6 2.607728E-06 1.799999E+02 -2.607728E-06 6.007129E-12 - 4.139994E+01 0.000000E+00 1 3.208051E+01 8.996720E+01 1.836172E-02 3.208050E+01 - 4.139994E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 4.139994E+01 0.000000E+00 3 1.965956E+02 1.433545E-01 1.965950E+02 4.918833E-01 - 4.139994E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 4.139994E+01 0.000000E+00 5 3.456003E+02 8.996720E+01 1.978056E-01 3.456002E+02 - 4.139994E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 4.139994E+01 3.000000E+01 1 2.782909E+01 8.996720E+01 1.592808E-02 2.782909E+01 - 4.139994E+01 3.000000E+01 2 1.698372E+01 8.996394E+01 1.069130E-02 1.698371E+01 - 4.139994E+01 3.000000E+01 3 1.969649E+02 1.434706E-01 1.969643E+02 4.932063E-01 - 4.139994E+01 3.000000E+01 4 5.448686E+01 8.996381E+01 3.441423E-02 5.448685E+01 - 4.139994E+01 3.000000E+01 5 2.997913E+02 8.996720E+01 1.715882E-01 2.997912E+02 - 4.139994E+01 3.000000E+01 6 3.017126E+01 -1.929491E-04 3.017126E+01 -1.016046E-04 - 4.139994E+01 6.000000E+01 1 1.612102E+01 8.996721E+01 9.226641E-03 1.612101E+01 - 4.139994E+01 6.000000E+01 2 2.952482E+01 8.996394E+01 1.858645E-02 2.952482E+01 - 4.139994E+01 6.000000E+01 3 1.977071E+02 1.437027E-01 1.977065E+02 4.958657E-01 - 4.139994E+01 6.000000E+01 4 9.503753E+01 8.996394E+01 5.982786E-02 9.503751E+01 - 4.139994E+01 6.000000E+01 5 1.736500E+02 8.996720E+01 9.939387E-02 1.736499E+02 - 4.139994E+01 6.000000E+01 6 3.028553E+01 -1.927027E-04 3.028553E+01 -1.018592E-04 - 4.139994E+01 9.000000E+01 1 1.665889E-06 -9.002594E+01 -7.541124E-10 -1.665889E-06 - 4.139994E+01 9.000000E+01 2 3.415503E+01 8.996394E+01 2.150146E-02 3.415503E+01 - 4.139994E+01 9.000000E+01 3 1.980793E+02 1.438184E-01 1.980787E+02 4.971993E-01 - 4.139994E+01 9.000000E+01 4 1.101234E+02 8.996400E+01 6.921072E-02 1.101233E+02 - 4.139994E+01 9.000000E+01 5 7.775707E-05 -8.999624E+01 5.104229E-09 -7.775707E-05 - 4.139994E+01 9.000000E+01 6 2.594763E-06 1.799999E+02 -2.594763E-06 5.916115E-12 - 4.149994E+01 0.000000E+00 1 3.200307E+01 8.996737E+01 1.822561E-02 3.200307E+01 - 4.149994E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 4.149994E+01 0.000000E+00 3 1.966507E+02 1.426483E-01 1.966501E+02 4.895974E-01 - 4.149994E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 4.149994E+01 0.000000E+00 5 3.448411E+02 8.996737E+01 1.963807E-01 3.448410E+02 - 4.149994E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 4.149994E+01 3.000000E+01 1 2.776168E+01 8.996737E+01 1.580994E-02 2.776168E+01 - 4.149994E+01 3.000000E+01 2 1.694263E+01 8.996412E+01 1.060992E-02 1.694263E+01 - 4.149994E+01 3.000000E+01 3 1.970181E+02 1.427636E-01 1.970174E+02 4.909084E-01 - 4.149994E+01 3.000000E+01 4 5.435096E+01 8.996400E+01 3.414890E-02 5.435095E+01 - 4.149994E+01 3.000000E+01 5 2.991281E+02 8.996737E+01 1.703518E-01 2.991280E+02 - 4.149994E+01 3.000000E+01 6 3.002252E+01 -1.909746E-04 3.002252E+01 -1.000691E-04 - 4.149994E+01 6.000000E+01 1 1.608171E+01 8.996738E+01 9.158031E-03 1.608171E+01 - 4.149994E+01 6.000000E+01 2 2.945286E+01 8.996412E+01 1.844464E-02 2.945286E+01 - 4.149994E+01 6.000000E+01 3 1.977572E+02 1.429930E-01 1.977566E+02 4.935420E-01 - 4.149994E+01 6.000000E+01 4 9.479705E+01 8.996412E+01 5.936589E-02 9.479704E+01 - 4.149994E+01 6.000000E+01 5 1.732650E+02 8.996737E+01 9.867683E-02 1.732650E+02 - 4.149994E+01 6.000000E+01 6 3.013568E+01 -1.907316E-04 3.013568E+01 -1.003185E-04 - 4.149994E+01 9.000000E+01 1 1.661794E-06 -9.002582E+01 -7.488778E-10 -1.661794E-06 - 4.149994E+01 9.000000E+01 2 3.407139E+01 8.996412E+01 2.133723E-02 3.407138E+01 - 4.149994E+01 9.000000E+01 3 1.981269E+02 1.431084E-01 1.981263E+02 4.948636E-01 - 4.149994E+01 9.000000E+01 4 1.098428E+02 8.996418E+01 6.867573E-02 1.098428E+02 - 4.149994E+01 9.000000E+01 5 7.757172E-05 -8.999626E+01 5.061101E-09 -7.757172E-05 - 4.149994E+01 9.000000E+01 6 2.581888E-06 1.799999E+02 -2.581888E-06 5.826696E-12 - 4.159994E+01 0.000000E+00 1 3.192614E+01 8.996753E+01 1.809090E-02 3.192613E+01 - 4.159994E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 4.159994E+01 0.000000E+00 3 1.967056E+02 1.419500E-01 1.967050E+02 4.873366E-01 - 4.159994E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 4.159994E+01 0.000000E+00 5 3.440872E+02 8.996753E+01 1.949723E-01 3.440872E+02 - 4.159994E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 4.159994E+01 3.000000E+01 1 2.769471E+01 8.996753E+01 1.569294E-02 2.769471E+01 - 4.159994E+01 3.000000E+01 2 1.690174E+01 8.996431E+01 1.052938E-02 1.690174E+01 - 4.159994E+01 3.000000E+01 3 1.970720E+02 1.420630E-01 1.970714E+02 4.886332E-01 - 4.159994E+01 3.000000E+01 4 5.421552E+01 8.996419E+01 3.388662E-02 5.421551E+01 - 4.159994E+01 3.000000E+01 5 2.984710E+02 8.996753E+01 1.691272E-01 2.984709E+02 - 4.159994E+01 3.000000E+01 6 2.987486E+01 -1.890252E-04 2.987486E+01 -9.856051E-05 - 4.159994E+01 6.000000E+01 1 1.604262E+01 8.996753E+01 9.090105E-03 1.604262E+01 - 4.159994E+01 6.000000E+01 2 2.938123E+01 8.996431E+01 1.830431E-02 2.938122E+01 - 4.159994E+01 6.000000E+01 3 1.978063E+02 1.422910E-01 1.978056E+02 4.912407E-01 - 4.159994E+01 6.000000E+01 4 9.455788E+01 8.996431E+01 5.890870E-02 9.455786E+01 - 4.159994E+01 6.000000E+01 5 1.728810E+02 8.996753E+01 9.796600E-02 1.728810E+02 - 4.159994E+01 6.000000E+01 6 2.998695E+01 -1.887858E-04 2.998695E+01 -9.880501E-05 - 4.159994E+01 9.000000E+01 1 1.657723E-06 -9.002570E+01 -7.436894E-10 -1.657723E-06 - 4.159994E+01 9.000000E+01 2 3.398825E+01 8.996431E+01 2.117467E-02 3.398825E+01 - 4.159994E+01 9.000000E+01 3 1.981756E+02 1.424040E-01 1.981750E+02 4.925489E-01 - 4.159994E+01 9.000000E+01 4 1.095636E+02 8.996436E+01 6.814620E-02 1.095636E+02 - 4.159994E+01 9.000000E+01 5 7.738743E-05 -8.999628E+01 5.018445E-09 -7.738743E-05 - 4.159994E+01 9.000000E+01 6 2.569109E-06 1.799999E+02 -2.569109E-06 5.738859E-12 - 4.169994E+01 0.000000E+00 1 3.184952E+01 8.996770E+01 1.795752E-02 3.184951E+01 - 4.169994E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 4.169994E+01 0.000000E+00 3 1.967602E+02 1.412541E-01 1.967596E+02 4.850822E-01 - 4.169994E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 4.169994E+01 0.000000E+00 5 3.433343E+02 8.996770E+01 1.935746E-01 3.433342E+02 - 4.169994E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 4.169994E+01 3.000000E+01 1 2.762793E+01 8.996770E+01 1.557708E-02 2.762793E+01 - 4.169994E+01 3.000000E+01 2 1.686105E+01 8.996449E+01 1.044969E-02 1.686105E+01 - 4.169994E+01 3.000000E+01 3 1.971250E+02 1.413667E-01 1.971244E+02 4.863688E-01 - 4.169994E+01 3.000000E+01 4 5.408092E+01 8.996438E+01 3.362707E-02 5.408091E+01 - 4.169994E+01 3.000000E+01 5 2.978172E+02 8.996770E+01 1.679160E-01 2.978172E+02 - 4.169994E+01 3.000000E+01 6 2.972837E+01 -1.871010E-04 2.972837E+01 -9.707885E-05 - 4.169994E+01 6.000000E+01 1 1.600369E+01 8.996770E+01 9.022900E-03 1.600369E+01 - 4.169994E+01 6.000000E+01 2 2.930994E+01 8.996449E+01 1.816543E-02 2.930993E+01 - 4.169994E+01 6.000000E+01 3 1.978561E+02 1.415912E-01 1.978555E+02 4.889480E-01 - 4.169994E+01 6.000000E+01 4 9.431992E+01 8.996449E+01 5.845638E-02 9.431990E+01 - 4.169994E+01 6.000000E+01 5 1.724973E+02 8.996770E+01 9.726115E-02 1.724973E+02 - 4.169994E+01 6.000000E+01 6 2.983928E+01 -1.868654E-04 2.983928E+01 -9.731831E-05 - 4.169994E+01 9.000000E+01 1 1.653668E-06 -9.002559E+01 -7.385495E-10 -1.653668E-06 - 4.169994E+01 9.000000E+01 2 3.390548E+01 8.996449E+01 2.101381E-02 3.390548E+01 - 4.169994E+01 9.000000E+01 3 1.982223E+02 1.417046E-01 1.982217E+02 4.902453E-01 - 4.169994E+01 9.000000E+01 4 1.092858E+02 8.996455E+01 6.762217E-02 1.092858E+02 - 4.169994E+01 9.000000E+01 5 7.720428E-05 -8.999631E+01 4.976278E-09 -7.720428E-05 - 4.169994E+01 9.000000E+01 6 2.556429E-06 1.799999E+02 -2.556429E-06 5.652582E-12 - 4.179993E+01 0.000000E+00 1 3.177319E+01 8.996786E+01 1.782549E-02 3.177319E+01 - 4.179993E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 4.179993E+01 0.000000E+00 3 1.968141E+02 1.405636E-01 1.968135E+02 4.828432E-01 - 4.179993E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 4.179993E+01 0.000000E+00 5 3.425842E+02 8.996786E+01 1.921921E-01 3.425841E+02 - 4.179993E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 4.179993E+01 3.000000E+01 1 2.756153E+01 8.996786E+01 1.546244E-02 2.756153E+01 - 4.179993E+01 3.000000E+01 2 1.682053E+01 8.996468E+01 1.037080E-02 1.682053E+01 - 4.179993E+01 3.000000E+01 3 1.971770E+02 1.406749E-01 1.971764E+02 4.841162E-01 - 4.179993E+01 3.000000E+01 4 5.394693E+01 8.996456E+01 3.337028E-02 5.394692E+01 - 4.179993E+01 3.000000E+01 5 2.971655E+02 8.996786E+01 1.667133E-01 2.971654E+02 - 4.179993E+01 3.000000E+01 6 2.958294E+01 -1.852015E-04 2.958294E+01 -9.562315E-05 - 4.179993E+01 6.000000E+01 1 1.596499E+01 8.996786E+01 8.956323E-03 1.596499E+01 - 4.179993E+01 6.000000E+01 2 2.923900E+01 8.996467E+01 1.802796E-02 2.923900E+01 - 4.179993E+01 6.000000E+01 3 1.979050E+02 1.408982E-01 1.979044E+02 4.866752E-01 - 4.179993E+01 6.000000E+01 4 9.408327E+01 8.996467E+01 5.800894E-02 9.408326E+01 - 4.179993E+01 6.000000E+01 5 1.721169E+02 8.996786E+01 9.656462E-02 1.721168E+02 - 4.179993E+01 6.000000E+01 6 2.969277E+01 -1.849691E-04 2.969277E+01 -9.585775E-05 - 4.179993E+01 9.000000E+01 1 1.649634E-06 -9.002547E+01 -7.334572E-10 -1.649634E-06 - 4.179993E+01 9.000000E+01 2 3.382306E+01 8.996467E+01 2.085456E-02 3.382305E+01 - 4.179993E+01 9.000000E+01 3 1.982701E+02 1.410097E-01 1.982695E+02 4.879587E-01 - 4.179993E+01 9.000000E+01 4 1.090095E+02 8.996473E+01 6.710392E-02 1.090095E+02 - 4.179993E+01 9.000000E+01 5 7.702148E-05 -8.999633E+01 4.934618E-09 -7.702148E-05 - 4.179993E+01 9.000000E+01 6 2.543847E-06 1.799999E+02 -2.543847E-06 5.567821E-12 - 4.189993E+01 0.000000E+00 1 3.169726E+01 8.996802E+01 1.769472E-02 3.169726E+01 - 4.189993E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 4.189993E+01 0.000000E+00 3 1.968671E+02 1.398788E-01 1.968665E+02 4.806201E-01 - 4.189993E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 4.189993E+01 0.000000E+00 5 3.418394E+02 8.996802E+01 1.908225E-01 3.418393E+02 - 4.189993E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 4.189993E+01 3.000000E+01 1 2.749547E+01 8.996802E+01 1.534886E-02 2.749546E+01 - 4.189993E+01 3.000000E+01 2 1.678023E+01 8.996486E+01 1.029271E-02 1.678022E+01 - 4.189993E+01 3.000000E+01 3 1.972283E+02 1.399894E-01 1.972278E+02 4.818829E-01 - 4.189993E+01 3.000000E+01 4 5.381390E+01 8.996474E+01 3.311593E-02 5.381388E+01 - 4.189993E+01 3.000000E+01 5 2.965127E+02 8.996802E+01 1.655249E-01 2.965127E+02 - 4.189993E+01 3.000000E+01 6 2.943853E+01 -1.833262E-04 2.943853E+01 -9.419290E-05 - 4.189993E+01 6.000000E+01 1 1.592647E+01 8.996802E+01 8.890377E-03 1.592647E+01 - 4.189993E+01 6.000000E+01 2 2.916839E+01 8.996486E+01 1.789187E-02 2.916839E+01 - 4.189993E+01 6.000000E+01 3 1.979532E+02 1.402093E-01 1.979526E+02 4.844135E-01 - 4.189993E+01 6.000000E+01 4 9.384766E+01 8.996486E+01 5.756581E-02 9.384765E+01 - 4.189993E+01 6.000000E+01 5 1.717385E+02 8.996802E+01 9.587416E-02 1.717384E+02 - 4.189993E+01 6.000000E+01 6 2.954734E+01 -1.830975E-04 2.954734E+01 -9.442304E-05 - 4.189993E+01 9.000000E+01 1 1.645620E-06 -9.002537E+01 -7.284074E-10 -1.645620E-06 - 4.189993E+01 9.000000E+01 2 3.374107E+01 8.996486E+01 2.069700E-02 3.374106E+01 - 4.189993E+01 9.000000E+01 3 1.983167E+02 1.403194E-01 1.983161E+02 4.856843E-01 - 4.189993E+01 9.000000E+01 4 1.087346E+02 8.996491E+01 6.659083E-02 1.087346E+02 - 4.189993E+01 9.000000E+01 5 7.684010E-05 -8.999635E+01 4.893390E-09 -7.684010E-05 - 4.189993E+01 9.000000E+01 6 2.531352E-06 1.799999E+02 -2.531352E-06 5.484548E-12 - 4.199993E+01 0.000000E+00 1 3.162169E+01 8.996818E+01 1.756517E-02 3.162169E+01 - 4.199993E+01 0.000000E+00 2 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 4.199993E+01 0.000000E+00 3 1.969216E+02 1.391986E-01 1.969211E+02 4.784157E-01 - 4.199993E+01 0.000000E+00 4 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 4.199993E+01 0.000000E+00 5 3.410953E+02 8.996818E+01 1.894655E-01 3.410952E+02 - 4.199993E+01 0.000000E+00 6 0.000000E+00 9.000000E+01 0.000000E+00 0.000000E+00 - 4.199993E+01 3.000000E+01 1 2.742975E+01 8.996818E+01 1.523634E-02 2.742974E+01 - 4.199993E+01 3.000000E+01 2 1.674008E+01 8.996504E+01 1.021539E-02 1.674008E+01 - 4.199993E+01 3.000000E+01 3 1.972803E+02 1.393080E-01 1.972797E+02 4.796635E-01 - 4.199993E+01 3.000000E+01 4 5.368106E+01 8.996492E+01 3.286424E-02 5.368105E+01 - 4.199993E+01 3.000000E+01 5 2.958658E+02 8.996818E+01 1.643461E-01 2.958658E+02 - 4.199993E+01 3.000000E+01 6 2.929523E+01 -1.814753E-04 2.929523E+01 -9.278800E-05 - 4.199993E+01 6.000000E+01 1 1.588813E+01 8.996818E+01 8.825126E-03 1.588813E+01 - 4.199993E+01 6.000000E+01 2 2.909819E+01 8.996503E+01 1.775723E-02 2.909819E+01 - 4.199993E+01 6.000000E+01 3 1.980013E+02 1.395273E-01 1.980007E+02 4.821744E-01 - 4.199993E+01 6.000000E+01 4 9.361299E+01 8.996503E+01 5.712739E-02 9.361298E+01 - 4.199993E+01 6.000000E+01 5 1.713600E+02 8.996818E+01 9.519084E-02 1.713600E+02 - 4.199993E+01 6.000000E+01 6 2.940291E+01 -1.812501E-04 2.940291E+01 -9.301350E-05 - 4.199993E+01 9.000000E+01 1 1.641623E-06 -9.002525E+01 -7.234043E-10 -1.641623E-06 - 4.199993E+01 9.000000E+01 2 3.365955E+01 8.996503E+01 2.054098E-02 3.365954E+01 - 4.199993E+01 9.000000E+01 3 1.983625E+02 1.396369E-01 1.983619E+02 4.834336E-01 - 4.199993E+01 9.000000E+01 4 1.084613E+02 8.996510E+01 6.608290E-02 1.084613E+02 - 4.199993E+01 9.000000E+01 5 7.665897E-05 -8.999638E+01 4.852652E-09 -7.665897E-05 - 4.199993E+01 9.000000E+01 6 2.518950E-06 1.799999E+02 -2.518950E-06 5.402741E-12 \ No newline at end of file diff --git a/Test_Cases/MHK_RM1/MHK_RM1_Floating.fst b/Test_Cases/MHK_RM1/MHK_RM1_Floating.fst deleted file mode 100644 index a19bf661..00000000 --- a/Test_Cases/MHK_RM1/MHK_RM1_Floating.fst +++ /dev/null @@ -1,71 +0,0 @@ -------- OpenFAST EXAMPLE INPUT FILE -------------------------------------------- -Floating MHK turbine, based on the RM1 tidal current rotor ----------------------- SIMULATION CONTROL -------------------------------------- -False Echo - Echo input data to .ech (flag) -"FATAL" AbortLevel - Error level when simulation should abort (string) {"WARNING", "SEVERE", "FATAL"} - 100 TMax - Total run time (s) - 0.01 DT - Recommended module time step (s) - 2 InterpOrder - Interpolation order for input/output time history (-) {1=linear, 2=quadratic} - 2 NumCrctn - Number of correction iterations (-) {0=explicit calculation, i.e., no corrections} - 1 DT_UJac - Time between calls to get Jacobians (s) - 1E+06 UJacSclFact - Scaling factor used in Jacobians (-) ----------------------- FEATURE SWITCHES AND FLAGS ------------------------------ - 1 CompElast - Compute structural dynamics (switch) {1=ElastoDyn; 2=ElastoDyn + BeamDyn for blades} - 1 CompInflow - Compute inflow wind velocities (switch) {0=still air; 1=InflowWind; 2=external from OpenFOAM} - 2 CompAero - Compute aerodynamic loads (switch) {0=None; 1=AeroDyn v14; 2=AeroDyn v15} - 1 CompServo - Compute control and electrical-drive dynamics (switch) {0=None; 1=ServoDyn} - 1 CompHydro - Compute hydrodynamic loads (switch) {0=None; 1=HydroDyn} - 0 CompSub - Compute sub-structural dynamics (switch) {0=None; 1=SubDyn; 2=External Platform MCKF} - 3 CompMooring - Compute mooring system (switch) {0=None; 1=MAP++; 2=FEAMooring; 3=MoorDyn; 4=OrcaFlex} - 0 CompIce - Compute ice loads (switch) {0=None; 1=IceFloe; 2=IceDyn} - 2 MHK - MHK turbine type (switch) {0=Not an MHK turbine; 1=Fixed MHK turbine; 2=Floating MHK turbine} ----------------------- ENVIRONMENTAL CONDITIONS -------------------------------- - 9.80665 Gravity - Gravitational acceleration (m/s^2) - 1.225 AirDens - Air density (kg/m^3) - 1025.0 WtrDens - Water density (kg/m^3) - 1.06E-06 KinVisc - Kinematic viscosity of working fluid (m^2/s) - 1500 SpdSound - Speed of sound in working fluid (m/s) - 101325 Patm - Atmospheric pressure (Pa) [used only for an MHK turbine cavitation check] - 2500 Pvap - Vapour pressure of working fluid (Pa) [used only for an MHK turbine cavitation check] - 50 WtrDpth - Water depth (m) - 0 MSL2SWL - Offset between still-water level and mean sea level (m) [positive upward] ----------------------- INPUT FILES --------------------------------------------- -"MHK_RM1_Floating_ElastoDyn.dat" EDFile - Name of file containing ElastoDyn input parameters (quoted string) -"unused" BDBldFile(1) - Name of file containing BeamDyn input parameters for blade 1 (quoted string) -"unused" BDBldFile(2) - Name of file containing BeamDyn input parameters for blade 2 (quoted string) -"unused" BDBldFile(3) - Name of file containing BeamDyn input parameters for blade 3 (quoted string) -"MHK_RM1_Floating_InflowWind.dat" InflowFile - Name of file containing inflow wind input parameters (quoted string) -"MHK_RM1_Floating_AeroDyn15.dat" AeroFile - Name of file containing aerodynamic input parameters (quoted string) -"MHK_RM1_ServoDyn.dat" ServoFile - Name of file containing control and electrical-drive input parameters (quoted string) -"MHK_RM1_Floating_HydroDyn.dat" HydroFile - Name of file containing hydrodynamic input parameters (quoted string) -"unused" SubFile - Name of file containing sub-structural input parameters (quoted string) -"MHK_RM1_Floating_MoorDyn.dat" MooringFile - Name of file containing mooring system input parameters (quoted string) -"unused" IceFile - Name of file containing ice input parameters (quoted string) ----------------------- OUTPUT -------------------------------------------------- -True SumPrint - Print summary data to ".sum" (flag) - 5 SttsTime - Amount of time between screen status messages (s) - 99999 ChkptTime - Amount of time between creating checkpoint files for potential restart (s) - default DT_Out - Time step for tabular output (s) (or "default") - 0 TStart - Time to begin tabular output (s) - 3 OutFileFmt - Format for tabular (time-marching) output file (switch) {0: uncompressed binary [.outb], 1: text file [.out], 2: binary file [.outb], 3: both 1 and 2} -True TabDelim - Use tab delimiters in text tabular output file? (flag) {uses spaces if false} -"ES10.3E2" OutFmt - Format used for text tabular output, excluding the time channel. Resulting field should be 10 characters. (quoted string) ----------------------- LINEARIZATION ------------------------------------------- -False Linearize - Linearization analysis (flag) -False CalcSteady - Calculate a steady-state periodic operating point before linearization? [unused if Linearize=False] (flag) - 1 TrimCase - Controller parameter to be trimmed {1:yaw; 2:torque; 3:pitch} [used only if CalcSteady=True] (-) - 0.01 TrimTol - Tolerance for the rotational speed convergence [used only if CalcSteady=True] (-) - 0.01 TrimGain - Proportional gain for the rotational speed error (>0) [used only if CalcSteady=True] (rad/(rad/s) for yaw or pitch; Nm/(rad/s) for torque) - 0 Twr_Kdmp - Damping factor for the tower [used only if CalcSteady=True] (N/(m/s)) - 0 Bld_Kdmp - Damping factor for the blades [used only if CalcSteady=True] (N/(m/s)) - 0 NLinTimes - Number of times to linearize (-) [>=1] [unused if Linearize=False] - 0 LinTimes - List of times at which to linearize (s) [1 to NLinTimes] [used only when Linearize=True and CalcSteady=False] - 0 LinInputs - Inputs included in linearization (switch) {0=none; 1=standard; 2=all module inputs (debug)} [unused if Linearize=False] - 0 LinOutputs - Outputs included in linearization (switch) {0=none; 1=from OutList(s); 2=all module outputs (debug)} [unused if Linearize=False] -False LinOutJac - Include full Jacobians in linearization output (for debug) (flag) [unused if Linearize=False; used only if LinInputs=LinOutputs=2] -False LinOutMod - Write module-level linearization output files in addition to output for full system? (flag) [unused if Linearize=False] ----------------------- VISUALIZATION ------------------------------------------- - 0 WrVTK - VTK visualization data output: (switch) {0=none; 1=initialization data only; 2=animation; 3=mode shapes} - 1 VTK_type - Type of VTK visualization data: (switch) {1=surfaces; 2=basic meshes (lines/points); 3=all meshes (debug)} [unused if WrVTK=0] -False VTK_fields - Write mesh fields to VTK data files? (flag) {true/false} [unused if WrVTK=0] - 0 VTK_fps - Frame rate for VTK output (frames per second){will use closest integer multiple of DT} [used only if WrVTK=2 or WrVTK=3] diff --git a/Test_Cases/MHK_RM1/MHK_RM1_Floating.hst b/Test_Cases/MHK_RM1/MHK_RM1_Floating.hst deleted file mode 100644 index 7f6dc63e..00000000 --- a/Test_Cases/MHK_RM1/MHK_RM1_Floating.hst +++ /dev/null @@ -1,36 +0,0 @@ - 1 1 0.000000E+00 - 1 2 0.000000E+00 - 1 3 0.000000E+00 - 1 4 0.000000E+00 - 1 5 0.000000E+00 - 1 6 0.000000E+00 - 2 1 0.000000E+00 - 2 2 0.000000E+00 - 2 3 0.000000E+00 - 2 4 0.000000E+00 - 2 5 0.000000E+00 - 2 6 0.000000E+00 - 3 1 0.000000E+00 - 3 2 0.000000E+00 - 3 3 2.083175E+02 - 3 4 0.000000E+00 - 3 5 0.000000E+00 - 3 6 0.000000E+00 - 4 1 0.000000E+00 - 4 2 0.000000E+00 - 4 3 0.000000E+00 - 4 4 -1.035433E+03 - 4 5 0.000000E+00 - 4 6 0.000000E+00 - 5 1 0.000000E+00 - 5 2 0.000000E+00 - 5 3 0.000000E+00 - 5 4 0.000000E+00 - 5 5 6.307686E+04 - 5 6 0.000000E+00 - 6 1 0.000000E+00 - 6 2 0.000000E+00 - 6 3 0.000000E+00 - 6 4 0.000000E+00 - 6 5 0.000000E+00 - 6 6 0.000000E+00 \ No newline at end of file diff --git a/Test_Cases/MHK_RM1/MHK_RM1_Floating_AeroDyn15.dat b/Test_Cases/MHK_RM1/MHK_RM1_Floating_AeroDyn15.dat deleted file mode 100644 index 707ba8d9..00000000 --- a/Test_Cases/MHK_RM1/MHK_RM1_Floating_AeroDyn15.dat +++ /dev/null @@ -1,123 +0,0 @@ -------- AERODYN v15 for OpenFAST INPUT FILE --------------------------------------------------------- -Floating MHK turbine hydrodynamic input properties, based on the RM1 tidal current rotor -====== General Options ============================================================================ -False Echo - Echo the input to ".AD.ech"? (flag) -"default" DTAero - Time interval for aerodynamic calculations {or "default"} (s) - 2 WakeMod - Type of wake/induction model (switch) {0=none, 1=BEMT, 2=DBEMT, 3=OLAF} [WakeMod cannot be 2 or 3 when linearizing] - 1 AFAeroMod - Type of blade airfoil aerodynamics model (switch) {1=steady model, 2=Beddoes-Leishman unsteady model} [AFAeroMod must be 1 when linearizing] - 1 TwrPotent - Type tower influence on wind based on potential flow around the tower (switch) {0=none, 1=baseline potential flow, 2=potential flow with Bak correction} - 0 TwrShadow - Calculate tower influence on wind based on downstream tower shadow (switch) {0=none, 1=Powles model, 2=Eames model} -True TwrAero - Calculate tower aerodynamic loads? (flag) -False FrozenWake - Assume frozen wake during linearization? (flag) [used only when WakeMod=1 and when linearizing] -True CavitCheck - Perform cavitation check? (flag) [AFAeroMod must be 1 when CavitCheck=true] -True Buoyancy - Include buoyancy effects? (flag) -False CompAA - Flag to compute AeroAcoustics calculation [used only when WakeMod = 1 or 2] -"unused" AA_InputFile - AeroAcoustics input file [used only when CompAA=true] -====== Environmental Conditions =================================================================== -"default" AirDens - Air density (kg/m^3) -"default" KinVisc - Kinematic viscosity of working fluid (m^2/s) -"default" SpdSound - Speed of sound in working fluid (m/s) -"default" Patm - Atmospheric pressure (Pa) [used only when CavitCheck=True] -"default" Pvap - Vapour pressure of working fluid (Pa) [used only when CavitCheck=True] -====== Blade-Element/Momentum Theory Options ====================================================== [unused when WakeMod=0 or 3] - 2 SkewMod - Type of skewed-wake correction model (switch) {1=uncoupled, 2=Pitt/Peters, 3=coupled} [unused when WakeMod=0 or 3] -"default" SkewModFactor - Constant used in Pitt/Peters skewed wake model {or "default" is 15/32*pi} (-) [used only when SkewMod=2; unused when WakeMod=0 or 3] -True TipLoss - Use the Prandtl tip-loss model? (flag) [unused when WakeMod=0 or 3] -True HubLoss - Use the Prandtl hub-loss model? (flag) [unused when WakeMod=0 or 3] -True TanInd - Include tangential induction in BEMT calculations? (flag) [unused when WakeMod=0 or 3] -True AIDrag - Include the drag term in the axial-induction calculation? (flag) [unused when WakeMod=0 or 3] -True TIDrag - Include the drag term in the tangential-induction calculation? (flag) [unused when WakeMod=0,3 or TanInd=FALSE] -"default" IndToler - Convergence tolerance for BEMT nonlinear solve residual equation {or "default"} (-) [unused when WakeMod=0 or 3] - 1000 MaxIter - Maximum number of iteration steps (-) [unused when WakeMod=0] -====== Dynamic Blade-Element/Momentum Theory Options ============================================== [used only when WakeMod=2] - 2 DBEMT_Mod - Type of dynamic BEMT (DBEMT) model {1=constant tau1, 2=time-dependent tau1} (-) [used only when WakeMod=2] - 4 tau1_const - Time constant for DBEMT (s) [used only when WakeMod=2 and DBEMT_Mod=1] -====== OLAF -- cOnvecting LAgrangian Filaments (Free Vortex Wake) Theory Options ================== [used only when WakeMod=3] -"unused" OLAFInputFileName - Input file for OLAF [used only when WakeMod=3] -====== Beddoes-Leishman Unsteady Airfoil Aerodynamics Options ===================================== [used only when AFAeroMod=2] - 3 UAMod - Unsteady Aero Model Switch (switch) {1=Baseline model (Original), 2=Gonzalez's variant (changes in Cn,Cc,Cm), 3=Minnema/Pierce variant (changes in Cc and Cm)} [used only when AFAeroMod=2] -True FLookup - Flag to indicate whether a lookup for f' will be calculated (TRUE) or whether best-fit exponential equations will be used (FALSE); if FALSE S1-S4 must be provided in airfoil input files (flag) [used only when AFAeroMod=2] -====== Airfoil Information ========================================================================= - 2 AFTabMod - Interpolation method for multiple airfoil tables {1=1D interpolation on AoA (first table only); 2=2D interpolation on AoA and Re; 3=2D interpolation on AoA and UserProp} (-) - 1 InCol_Alfa - The column in the airfoil tables that contains the angle of attack (-) - 2 InCol_Cl - The column in the airfoil tables that contains the lift coefficient (-) - 3 InCol_Cd - The column in the airfoil tables that contains the drag coefficient (-) - 0 InCol_Cm - The column in the airfoil tables that contains the pitching-moment coefficient; use zero if there is no Cm column (-) - 4 InCol_Cpmin - The column in the airfoil tables that contains the Cpmin coefficient; use zero if there is no Cpmin column (-) - 9 NumAFfiles - Number of airfoil files used (-) -"Airfoils/NACA6_1000.dat" AFNames - Airfoil file names (NumAFfiles lines) (quoted strings) -"Airfoils/NACA6_0864.dat" -"Airfoils/NACA6_0629.dat" -"Airfoils/NACA6_0444.dat" -"Airfoils/NACA6_0329.dat" -"Airfoils/NACA6_0276.dat" -"Airfoils/NACA6_0259.dat" -"Airfoils/NACA6_0247.dat" -"Airfoils/NACA6_0240.dat" -====== Rotor/Blade Properties ===================================================================== -False UseBlCm - Include aerodynamic pitching moment in calculations? (flag) -"MHK_RM1_AeroDyn15_Blade.dat" ADBlFile(1) - Name of file containing distributed aerodynamic properties for Blade #1 (-) -"MHK_RM1_AeroDyn15_Blade.dat" ADBlFile(2) - Name of file containing distributed aerodynamic properties for Blade #2 (-) [unused if NumBl < 2] -"unused" ADBlFile(3) - Name of file containing distributed aerodynamic properties for Blade #3 (-) [unused if NumBl < 3] -====== Hub Properties ============================================================================== [used only when Buoyancy=True] -7.2 VolHub - Hub volume (m^3) -0.2222 HubCenBx - Hub center of buoyancy x direction offset (m) -====== Nacelle Properties ========================================================================== [used only when Buoyancy=True] -38.6 VolNac - Nacelle volume (m^3) -0.43,0,0 NacCenB - Position of nacelle center of buoyancy from yaw bearing in nacelle coordinates (m) -====== Tail fin Aerodynamics ======================================================================== -False TFinAero - Calculate tail fin aerodynamics model (flag) -"unused" TFinFile - Input file for tail fin aerodynamics [used only when TFinAero=True] -====== Tower Influence and Aerodynamics ============================================================ [used only when TwrPotent/=0, TwrShadow/=0, TwrAero=True, or Buoyancy=True] - 4 NumTwrNds - Number of tower nodes used in the analysis (-) [used only when TwrPotent/=0, TwrShadow/=0, TwrAero=True, or Buoyancy=True] -TwrElev TwrDiam TwrCd TwrTI TwrCb !TwrTI used only with TwrShadow=2, TwrCb used only with Buoyancy=True -(m) (m) (-) (-) (-) --9 0.3253 0.2 0.0 1.0 --14 0.3253 0.2 0.0 1.0 --19 0.3253 0.2 0.0 1.0 --24 0.3253 0.2 0.0 1.0 -====== Outputs ==================================================================================== -True SumPrint - Generate a summary file listing input options and interpolated properties to ".AD.sum"? (flag) - 9 NBlOuts - Number of blade node outputs [0 - 9] (-) -1,5,9,13,17,21,25,27,30 BlOutNd - Blade nodes whose values will be output (-) - 4 NTwOuts - Number of tower node outputs [0 - 9] (-) - 1,2,3,4 TwOutNd - Tower nodes whose values will be output (-) - OutList - The next line(s) contains a list of output parameters. See OutListParameters.xlsx for a listing of available output channels. -"TwN1Fbx" - x-component of buoyant force per unit length at Tw node 1 -"TwN3Fby" - y-component of buoyant force per unit length at Tw node 3 -"TwN4Fbz" - z-component of buoyant force per unit length at Tw node 4 -"TwN1Mbx" - x-component of buoyant moment per unit length at Tw node 6 -"TwN2Mby" - y-component of buoyant moment per unit length at Tw node 5 -"TwN3Mbz" - z-component of buoyant moment per unit length at Tw node 2 -"B2N4Fbn" - Buoyant force normal to chord per unit length at blade 2 node 4 -"B1N7Fbt" - Buoyant force tangential to chord per unit length at blade 1 node 7 -"B2N8Fbs" - Buoyant spanwise force per unit length at blade 2 node 8 -"B1N2Mbn" - Buoyant moment normal to chord per unit length at blade 1 node 2 -"B2N3Mbt" - Buoyant moment tangential to chord per unit length at blade 2 node 3 -"B1N6Mbs" - Buoyant spanwise moment per unit length at blade 1 node 6 -"B1FldFz" - Total blade aerodynamic/hydrodynamic load for blade 1 (force in z-direction) -"B2FldMx" - Total blade aerodynamic/hydrodynamic load for blade 2 (moment in x-direction) -"HbFbx" - x-component of buoyant force at hub node -"HbFby" - y-component of buoyant force at hub node -"HbFbz" - z-component of buoyant force at hub node -"HbMbx" - x-component of buoyant moment at hub node -"HbMby" - y-component of buoyant moment at hub node -"HbMbz" - z-component of buoyant moment at hub node -"NcFbx" - x-component of buoyant force at nacelle node -"NcFby" - y-component of buoyant force at nacelle node -"NcFbz" - z-component of buoyant force at nacelle node -"NcMbx" - x-component of buoyant moment at nacelle node -"NcMby" - y-component of buoyant moment at nacelle node -"NcMbz" - z-component of buoyant moment at nacelle node -"RtFldFxh" - Total rotor aerodynamic/hydrodynamic and buoyant load (force in x direction) -"RtFldFyh" - Total rotor aerodynamic/hydrodynamic and buoyant load (force in y direction) -"RtFldFzg" - Total rotor aerodynamic/hydrodynamic and buoyant load (force in global z direction) -"RtFldMxh" - Total rotor aerodynamic/hydrodynamic and buoyant load (moment in x direction) -"RtFldMyg" - Total rotor aerodynamic/hydrodynamic and buoyant load (moment in global y direction) -"RtFldMzh" - Total rotor aerodynamic/hydrodynamic and buoyant load (moment in z direction) -"B1N3SigCr" - Critical cavitation number blade 1 node 3 -"B2N5SigCr" - Critical cavitation number blade 2 node 5 -"B1N2SgCav" - Cavitation number blade 1 node 2 -"B2N6SgCav" - Cavitation number blade 2 node 6 -END of input file (the word "END" must appear in the first 3 columns of this last OutList line) ------------------------------------------------------------------------------------------------------ diff --git a/Test_Cases/MHK_RM1/MHK_RM1_Floating_ElastoDyn.dat b/Test_Cases/MHK_RM1/MHK_RM1_Floating_ElastoDyn.dat deleted file mode 100644 index 5a79e239..00000000 --- a/Test_Cases/MHK_RM1/MHK_RM1_Floating_ElastoDyn.dat +++ /dev/null @@ -1,134 +0,0 @@ -------- ELASTODYN for OpenFAST INPUT FILE -------------------------------------- -Floating MHK turbine structural input properties, based on the RM1 tidal current rotor ----------------------- SIMULATION CONTROL -------------------------------------- -False Echo - Echo input data to ".ech" (flag) - 3 Method - Integration method: {1: RK4, 2: AB4, or 3: ABM4} (-) -"default" DT - Integration time step (s) ----------------------- DEGREES OF FREEDOM -------------------------------------- -False FlapDOF1 - First flapwise blade mode DOF (flag) -False FlapDOF2 - Second flapwise blade mode DOF (flag) -False EdgeDOF - First edgewise blade mode DOF (flag) -False TeetDOF - Rotor-teeter DOF (flag) [unused for 3 blades] -False DrTrDOF - Drivetrain rotational-flexibility DOF (flag) -True GenDOF - Generator DOF (flag) -False YawDOF - Yaw DOF (flag) -False TwFADOF1 - First fore-aft tower bending-mode DOF (flag) -False TwFADOF2 - Second fore-aft tower bending-mode DOF (flag) -False TwSSDOF1 - First side-to-side tower bending-mode DOF (flag) -False TwSSDOF2 - Second side-to-side tower bending-mode DOF (flag) -True PtfmSgDOF - Platform horizontal surge translation DOF (flag) -True PtfmSwDOF - Platform horizontal sway translation DOF (flag) -True PtfmHvDOF - Platform vertical heave translation DOF (flag) -True PtfmRDOF - Platform roll tilt rotation DOF (flag) -True PtfmPDOF - Platform pitch tilt rotation DOF (flag) -True PtfmYDOF - Platform yaw rotation DOF (flag) ----------------------- INITIAL CONDITIONS -------------------------------------- - 0 OoPDefl - Initial out-of-plane blade-tip displacement (meters) - 0 IPDefl - Initial in-plane blade-tip deflection (meters) - 10 BlPitch(1) - Blade 1 initial pitch (degrees) - 10 BlPitch(2) - Blade 2 initial pitch (degrees) - 10 BlPitch(3) - Blade 3 initial pitch (degrees) [unused for 2 blades] - 0 TeetDefl - Initial or fixed teeter angle (degrees) [unused for 3 blades] - 0 Azimuth - Initial azimuth angle for blade 1 (degrees) - 11.50 RotSpeed - Initial or fixed rotor speed (rpm) - 0 NacYaw - Initial or fixed nacelle-yaw angle (degrees) - 0 TTDspFA - Initial fore-aft tower-top displacement (meters) - 0 TTDspSS - Initial side-to-side tower-top displacement (meters) - 20 PtfmSurge - Initial or fixed horizontal surge translational displacement of platform (meters) - 0 PtfmSway - Initial or fixed horizontal sway translational displacement of platform (meters) - 0 PtfmHeave - Initial or fixed vertical heave translational displacement of platform (meters) - 0 PtfmRoll - Initial or fixed roll tilt rotational displacement of platform (degrees) - 0 PtfmPitch - Initial or fixed pitch tilt rotational displacement of platform (degrees) - 0 PtfmYaw - Initial or fixed yaw rotational displacement of platform (degrees) ----------------------- TURBINE CONFIGURATION ----------------------------------- - 2 NumBl - Number of blades (-) - 10.0 TipRad - The distance from the rotor apex to the blade tip (meters) - 1.0 HubRad - The distance from the rotor apex to the blade root (meters) - 0.0 PreCone(1) - Blade 1 cone angle (degrees) - 0.0 PreCone(2) - Blade 2 cone angle (degrees) - 0.0 PreCone(3) - Blade 3 cone angle (degrees) [unused for 2 blades] - 0.2222 HubCM - Distance from rotor apex to hub mass [positive downwind] (meters) - 0 UndSling - Undersling length [distance from teeter pin to the rotor apex] (meters) [unused for 3 blades] - 0 Delta3 - Delta-3 angle for teetering rotors (degrees) [unused for 3 blades] - 0 AzimB1Up - Azimuth value to use for I/O when blade 1 points up (degrees) - -4.91 OverHang - Distance from yaw axis to rotor apex [3 blades] or teeter pin [2 blades] (meters) - 0 ShftGagL - Distance from rotor apex [3 blades] or teeter pin [2 blades] to shaft strain gages [positive for upwind rotors] (meters) - 0 ShftTilt - Rotor shaft tilt angle (degrees) - 0.43 NacCMxn - Downwind distance from the tower-top to the nacelle CM (meters) - 0 NacCMyn - Lateral distance from the tower-top to the nacelle CM (meters) - -1.2 NacCMzn - Vertical distance from the tower-top to the nacelle CM (meters) - 0 NcIMUxn - Downwind distance from the tower-top to the nacelle IMU (meters) - 0 NcIMUyn - Lateral distance from the tower-top to the nacelle IMU (meters) - -1.2 NcIMUzn - Vertical distance from the tower-top to the nacelle IMU (meters) - -1.2 Twr2Shft - Vertical distance from the tower-top to the rotor shaft (meters) - -24.0 TowerHt - Height of tower relative to ground level [onshore], MSL [offshore wind or floating MHK], or seabed [fixed MHK] (meters) - -9.0 TowerBsHt - Height of tower base relative to ground level [onshore], MSL [offshore wind or floating MHK], or seabed [fixed MHK] (meters) - 0 PtfmCMxt - Downwind distance from the ground level [onshore], MSL [offshore wind or floating MHK], or seabed [fixed MHK] to the platform CM (meters) - 0 PtfmCMyt - Lateral distance from the ground level [onshore], MSL [offshore wind or floating MHK], or seabed [fixed MHK] to the platform CM (meters) - -6.09 PtfmCMzt - Vertical distance from the ground level [onshore], MSL [offshore wind or floating MHK], or seabed [fixed MHK] to the platform CM (meters) - 0 PtfmRefzt - Vertical distance from the ground level [onshore], MSL [offshore wind or floating MHK], or seabed [fixed MHK] to the platform reference point (meters) ----------------------- MASS AND INERTIA ---------------------------------------- - 0 TipMass(1) - Tip-brake mass, blade 1 (kg) - 0 TipMass(2) - Tip-brake mass, blade 2 (kg) - 0 TipMass(3) - Tip-brake mass, blade 3 (kg) [unused for 2 blades] - 140 HubMass - Hub mass (kg) - 79.6 HubIner - Hub inertia about rotor axis [3 blades] or teeter axis [2 blades] (kg m^2) - 139.50 GenIner - Generator inertia about HSS (kg m^2) - 40100 NacMass - Nacelle mass (kg) - 244643 NacYIner - Nacelle inertia about yaw axis (kg m^2) - 0 YawBrMass - Yaw bearing mass (kg) - 2525214 PtfmMass - Platform mass (kg) - 195242474 PtfmRIner - Platform inertia for roll tilt rotation about the platform CM (kg m^2) - 919435755 PtfmPIner - Platform inertia for pitch tilt rotation about the platform CM (kg m^2) - 1053535885 PtfmYIner - Platform inertia for yaw rotation about the platform CM (kg m^2) ----------------------- BLADE --------------------------------------------------- - 8 BldNodes - Number of blade nodes (per blade) used for analysis (-) -"MHK_RM1_ElastoDyn_Blade.dat" BldFile(1) - Name of file containing properties for blade 1 (quoted string) -"MHK_RM1_ElastoDyn_Blade.dat" BldFile(2) - Name of file containing properties for blade 2 (quoted string) -"unused" BldFile(3) - Name of file containing properties for blade 3 (quoted string) [unused for 2 blades] ----------------------- ROTOR-TEETER -------------------------------------------- - 0 TeetMod - Rotor-teeter spring/damper model {0: none, 1: standard, 2: user-defined from routine UserTeet} (switch) [unused for 3 blades] - 0 TeetDmpP - Rotor-teeter damper position (degrees) [used only for 2 blades and when TeetMod=1] - 0 TeetDmp - Rotor-teeter damping constant (N-m/(rad/s)) [used only for 2 blades and when TeetMod=1] - 0 TeetCDmp - Rotor-teeter rate-independent Coulomb-damping moment (N-m) [used only for 2 blades and when TeetMod=1] - 0 TeetSStP - Rotor-teeter soft-stop position (degrees) [used only for 2 blades and when TeetMod=1] - 0 TeetHStP - Rotor-teeter hard-stop position (degrees) [used only for 2 blades and when TeetMod=1] - 0 TeetSSSp - Rotor-teeter soft-stop linear-spring constant (N-m/rad) [used only for 2 blades and when TeetMod=1] - 0 TeetHSSp - Rotor-teeter hard-stop linear-spring constant (N-m/rad) [used only for 2 blades and when TeetMod=1] ----------------------- DRIVETRAIN ---------------------------------------------- - 92 GBoxEff - Gearbox efficiency (%) - 53 GBRatio - Gearbox ratio (-) - 600000 DTTorSpr - Drivetrain torsional spring (N-m/rad) - 100000 DTTorDmp - Drivetrain torsional damper (N-m/(rad/s)) ----------------------- FURLING ------------------------------------------------- -False Furling - Read in additional model properties for furling turbine (flag) [must currently be FALSE) -"unused" FurlFile - Name of file containing furling properties (quoted string) [unused when Furling=False] ----------------------- TOWER --------------------------------------------------- - 2 TwrNodes - Number of tower nodes used for analysis (-) -"MHK_RM1_ElastoDyn_Tower.dat" TwrFile - Name of file containing tower properties (quoted string) ----------------------- OUTPUT -------------------------------------------------- -True SumPrint - Print summary data to ".sum" (flag) - 1 OutFile - Switch to determine where output will be placed: {1: in module output file only; 2: in glue code output file only; 3: both} (currently unused) -True TabDelim - Use tab delimiters in text tabular output file? (flag) (currently unused) -"ES10.3E2" OutFmt - Format used for text tabular output (except time). Resulting field should be 10 characters. (quoted string) (currently unused) - 0 TStart - Time to begin tabular output (s) (currently unused) - 1 DecFact - Decimation factor for tabular output {1: output every time step} (-) (currently unused) - 0 NTwGages - Number of tower nodes that have strain gages for output [0 to 9] (-) - 0 TwrGagNd - List of tower nodes that have strain gages [1 to TwrNodes] (-) [unused if NTwGages=0] - 0 NBlGages - Number of blade nodes that have strain gages for output [0 to 9] (-) - 0 BldGagNd - List of blade nodes that have strain gages [1 to BldNodes] (-) [unused if NBlGages=0] - OutList - The next line(s) contains a list of output parameters. See OutListParameters.xlsx for a listing of available output channels, (-) -"PtfmSurge" -"PtfmSway" -"PtfmHeave" -"PtfmRoll" -"PtfmPitch" -"PtfmYaw" -"TwrTpTDxi" -"TwrTpTDyi" -"TwrTpTDzi" -"OoPDefl1" -"RotSpeed" -"GenSpeed" -END of input file (the word "END" must appear in the first 3 columns of this last OutList line) --------------------------------------------------------------------------------- diff --git a/Test_Cases/MHK_RM1/MHK_RM1_Floating_HydroDyn.dat b/Test_Cases/MHK_RM1/MHK_RM1_Floating_HydroDyn.dat deleted file mode 100644 index 336853a1..00000000 --- a/Test_Cases/MHK_RM1/MHK_RM1_Floating_HydroDyn.dat +++ /dev/null @@ -1,207 +0,0 @@ -------- HydroDyn Input File ---------------------------------------------------- -Floating MHK turbine hydrodynamic support structure input properties, based on the RM1 tidal current rotor with a quad-style floating platform -False Echo - Echo the input file data (flag) ----------------------- ENVIRONMENTAL CONDITIONS -------------------------------- -"DEFAULT" WtrDens - Water density (kg/m^3) -"DEFAULT" WtrDpth - Water depth (meters) -"DEFAULT" MSL2SWL - Offset between still-water level and mean sea level (meters) [positive upward; unused when WaveMod = 6; must be zero if PotMod=1 or 2] ----------------------- WAVES --------------------------------------------------- - 0 WaveMod - Incident wave kinematics model {0: none=still water, 1: regular (periodic), 1P#: regular with user-specified phase, 2: JONSWAP/Pierson-Moskowitz spectrum (irregular), 3: White noise spectrum (irregular), 4: user-defined spectrum from routine UserWaveSpctrm (irregular), 5: Externally generated wave-elevation time series, 6: Externally generated full wave-kinematics time series [option 6 is invalid for PotMod/=0]} (switch) - 0 WaveStMod - Model for stretching incident wave kinematics to instantaneous free surface {0: none=no stretching, 1: vertical stretching, 2: extrapolation stretching, 3: Wheeler stretching} (switch) [unused when WaveMod=0 or when PotMod/=0] - 3600 WaveTMax - Analysis time for incident wave calculations (sec) [unused when WaveMod=0; determines WaveDOmega=2Pi/WaveTMax in the IFFT] - 0.1 WaveDT - Time step for incident wave calculations (sec) [unused when WaveMod=0; 0.1<=WaveDT<=1.0 recommended; determines WaveOmegaMax=Pi/WaveDT in the IFFT] - 1.0 WaveHs - Significant wave height of incident waves (meters) [used only when WaveMod=1, 2, or 3] - 10 WaveTp - Peak-spectral period of incident waves (sec) [used only when WaveMod=1 or 2] -"DEFAULT" WavePkShp - Peak-shape parameter of incident wave spectrum (-) or DEFAULT (string) [used only when WaveMod=2; use 1.0 for Pierson-Moskowitz] - 0.314159 WvLowCOff - Low cut-off frequency or lower frequency limit of the wave spectrum beyond which the wave spectrum is zeroed (rad/s) [unused when WaveMod=0, 1, or 6] - 1.570796 WvHiCOff - High cut-off frequency or upper frequency limit of the wave spectrum beyond which the wave spectrum is zeroed (rad/s) [unused when WaveMod=0, 1, or 6] - 0 WaveDir - Incident wave propagation heading direction (degrees) [unused when WaveMod=0 or 6] - 0 WaveDirMod - Directional spreading function {0: none, 1: COS2S} (-) [only used when WaveMod=2,3, or 4] - 1 WaveDirSpread - Wave direction spreading coefficient ( > 0 ) (-) [only used when WaveMod=2,3, or 4 and WaveDirMod=1] - 1 WaveNDir - Number of wave directions (-) [only used when WaveMod=2,3, or 4 and WaveDirMod=1; odd number only] - 0 WaveDirRange - Range of wave directions (full range: WaveDir +/- 1/2*WaveDirRange) (degrees) [only used when WaveMod=2,3,or 4 and WaveDirMod=1] - 123456789 WaveSeed(1) - First random seed of incident waves [-2147483648 to 2147483647] (-) [unused when WaveMod=0, 5, or 6] - RANLUX WaveSeed(2) - Second random seed of incident waves [-2147483648 to 2147483647] for intrinsic pRNG, or an alternative pRNG: "RanLux" (-) [unused when WaveMod=0, 5, or 6] -FALSE WaveNDAmp - Flag for normally distributed amplitudes (flag) [only used when WaveMod=2, 3, or 4] -"" WvKinFile - Root name of externally generated wave data file(s) (quoted string) [used only when WaveMod=5 or 6] - 1 NWaveElev - Number of points where the incident wave elevations can be computed (-) [maximum of 9 output locations] - 0 WaveElevxi - List of xi-coordinates for points where the incident wave elevations can be output (meters) [NWaveElev points, separated by commas or white space; usused if NWaveElev = 0] - 0 WaveElevyi - List of yi-coordinates for points where the incident wave elevations can be output (meters) [NWaveElev points, separated by commas or white space; usused if NWaveElev = 0] ----------------------- 2ND-ORDER WAVES ----------------------------------------- [unused with WaveMod=0 or 6] -FALSE WvDiffQTF - Full difference-frequency 2nd-order wave kinematics (flag) -FALSE WvSumQTF - Full summation-frequency 2nd-order wave kinematics (flag) - 0 WvLowCOffD - Low frequency cutoff used in the difference-frequencies (rad/s) [Only used with a difference-frequency method] - 1.256637 WvHiCOffD - High frequency cutoff used in the difference-frequencies (rad/s) [Only used with a difference-frequency method] - 0.618319 WvLowCOffS - Low frequency cutoff used in the summation-frequencies (rad/s) [Only used with a summation-frequency method] - 3.141593 WvHiCOffS - High frequency cutoff used in the summation-frequencies (rad/s) [Only used with a summation-frequency method] ----------------------- CURRENT ------------------------------------------------- [unused with WaveMod=6] - 1 CurrMod - Current profile model {0: none=no current, 1: standard, 2: user-defined from routine UserCurrent} (switch) - 0 CurrSSV0 - Sub-surface current velocity at still water level (m/s) [used only when CurrMod=1] - 0 CurrSSDir - Sub-surface current heading direction (degrees) or DEFAULT (string) [used only when CurrMod=1] - 12.2 CurrNSRef - Near-surface current reference depth (meters) [used only when CurrMod=1] - 0 CurrNSV0 - Near-surface current velocity at still water level (m/s) [used only when CurrMod=1] - 0 CurrNSDir - Near-surface current heading direction (degrees) [used only when CurrMod=1] - 1.9 CurrDIV - Depth-independent current velocity (m/s) [used only when CurrMod=1] - 0 CurrDIDir - Depth-independent current heading direction (degrees) [used only when CurrMod=1] ----------------------- FLOATING PLATFORM --------------------------------------- [unused with WaveMod=6] - 1 PotMod - Potential-flow model {0: none=no potential flow, 1: frequency-to-time-domain transforms based on WAMIT output, 2: fluid-impulse theory (FIT)} (switch) - 1 ExctnMod - Wave-excitation model {0: no wave-excitation calculation, 1: DFT, 2: state-space} (switch) [only used when PotMod=1; STATE-SPACE REQUIRES *.ssexctn INPUT FILE] - 1 RdtnMod - Radiation memory-effect model {0: no memory-effect calculation, 1: convolution, 2: state-space} (switch) [only used when PotMod=1; STATE-SPACE REQUIRES *.ss INPUT FILE] - 60 RdtnTMax - Analysis time for wave radiation kernel calculations (sec) [only used when PotMod=1 and RdtnMod=1; determines RdtnDOmega=Pi/RdtnTMax in the cosine transform; MAKE SURE THIS IS LONG ENOUGH FOR THE RADIATION IMPULSE RESPONSE FUNCTIONS TO DECAY TO NEAR-ZERO FOR THE GIVEN PLATFORM!] - "DEFAULT" RdtnDT - Time step for wave radiation kernel calculations (sec) [only used when PotMod=1 and ExctnMod>1 or RdtnMod>0; DT<=RdtnDT<=0.1 recommended; determines RdtnOmegaMax=Pi/RdtnDT in the cosine transform] - 1 NBody - Number of WAMIT bodies to be used (-) [>=1; only used when PotMod=1. If NBodyMod=1, the WAMIT data contains a vector of size 6*NBody x 1 and matrices of size 6*NBody x 6*NBody; if NBodyMod>1, there are NBody sets of WAMIT data each with a vector of size 6 x 1 and matrices of size 6 x 6] - 2 NBodyMod - Body coupling model {1: include coupling terms between each body and NBody in HydroDyn equals NBODY in WAMIT, 2: neglect coupling terms between each body and NBODY=1 with XBODY=0 in WAMIT, 3: Neglect coupling terms between each body and NBODY=1 with XBODY=/0 in WAMIT} (switch) [only used when PotMod=1] -"MHK_RM1_Floating" PotFile - Root name of potential-flow model data; WAMIT output files containing the linear, nondimensionalized, hydrostatic restoring matrix (.hst), frequency-dependent hydrodynamic added mass matrix and damping matrix (.1), and frequency- and direction-dependent wave excitation force vector per unit wave amplitude (.3) (quoted string) [1 to NBody if NBodyMod>1] [only used when PotMod=1 and ExctnMod>0 or RdtnMod>0] [MAKE SURE THE FREQUENCIES INHERENT IN THESE WAMIT FILES SPAN THE PHYSICALLY-SIGNIFICANT RANGE OF FREQUENCIES FOR THE GIVEN PLATFORM; THEY MUST CONTAIN THE ZERO- AND INFINITE-FREQUENCY LIMITS!] - 1 WAMITULEN - Characteristic body length scale used to redimensionalize WAMIT output (meters) [1 to NBody if NBodyMod>1] [only used when PotMod=1 and ExctnMod=1 or RdtnMod=1] - 0 PtfmRefxt - The xt offset of the body reference point(s) from (0,0,0) (meters) [1 to NBody] [only used when PotMod=1] - 0 PtfmRefyt - The yt offset of the body reference point(s) from (0,0,0) (meters) [1 to NBody] [only used when PotMod=1] - 0 PtfmRefzt - The zt offset of the body reference point(s) from (0,0,0) (meters) [1 to NBody] [only used when PotMod=1. If NBodyMod=2,PtfmRefzt=0.0] - 0 PtfmRefztRot - The rotation about zt of the body reference frame(s) from xt/yt (degrees) [1 to NBody] [only used when PotMod=1] - 2671.85 PtfmVol0 - **Note - 2672.6 from WAMIT with -0.748 correction for missing tower base hydrostatic pressure ** Displaced volume of water when the body is in its undisplaced position (m^3) [1 to NBody] [only used when PotMod=1; USE THE SAME VALUE COMPUTED BY WAMIT AS OUTPUT IN THE .OUT FILE!] - 0 PtfmCOBxt - The xt offset of the center of buoyancy (COB) from (0,0) (meters) [1 to NBody] [only used when PotMod=1] - 0 PtfmCOByt - The yt offset of the center of buoyancy (COB) from (0,0) (meters) [1 to NBody] [only used when PotMod=1] ----------------------- 2ND-ORDER FLOATING PLATFORM FORCES ---------------------- [unused with WaveMod=0 or 6, or PotMod=0 or 2] - 0 MnDrift - Mean-drift 2nd-order forces computed {0: None; [7, 8, 9, 10, 11, or 12]: WAMIT file to use} [Only one of MnDrift, NewmanApp, or DiffQTF can be non-zero. If NBody>1, MnDrift /=8] - 0 NewmanApp - Mean- and slow-drift 2nd-order forces computed with Newman's approximation {0: None; [7, 8, 9, 10, 11, or 12]: WAMIT file to use} [Only one of MnDrift, NewmanApp, or DiffQTF can be non-zero. If NBody>1, NewmanApp/=8. Used only when WaveDirMod=0] - 0 DiffQTF - Full difference-frequency 2nd-order forces computed with full QTF {0: None; [10, 11, or 12]: WAMIT file to use} [Only one of MnDrift, NewmanApp, or DiffQTF can be non-zero] - 0 SumQTF - Full summation -frequency 2nd-order forces computed with full QTF {0: None; [10, 11, or 12]: WAMIT file to use} ----------------------- PLATFORM ADDITIONAL STIFFNESS AND DAMPING -------------- [unused with PotMod=0 or 2] - 0 AddF0 - Additional preload (N, N-m) [If NBodyMod=1, one size 6*NBody x 1 vector; if NBodyMod>1, NBody size 6 x 1 vectors] - 0 - 0 - 0 - 0 - 0 - 0 0 0 0 0 0 AddCLin - Additional linear stiffness (N/m, N/rad, N-m/m, N-m/rad) [If NBodyMod=1, one size 6*NBody x 6*NBody matrix; if NBodyMod>1, NBody size 6 x 6 matrices] - 0 0 0 0 0 0 - 0 0 0 0 0 0 - 0 0 0 0 0 0 - 0 0 0 0 0 0 - 0 0 0 0 0 0 - 0 0 0 0 0 0 AddBLin - Additional linear damping(N/(m/s), N/(rad/s), N-m/(m/s), N-m/(rad/s)) [If NBodyMod=1, one size 6*NBody x 6*NBody matrix; if NBodyMod>1, NBody size 6 x 6 matrices] - 0 0 0 0 0 0 - 0 0 0 0 0 0 - 0 0 0 0 0 0 - 0 0 0 0 0 0 - 0 0 0 0 0 0 - 0 0 0 0 0 0 AddBQuad - Additional quadratic drag(N/(m/s)^2, N/(rad/s)^2, N-m(m/s)^2, N-m/(rad/s)^2) [If NBodyMod=1, one size 6*NBody x 6*NBody matrix; if NBodyMod>1, NBody size 6 x 6 matrices] - 0 0 0 0 0 0 - 0 0 0 0 0 0 - 0 0 0 0 0 0 - 0 0 0 0 0 0 - 0 0 0 0 0 0 ----------------------- AXIAL COEFFICIENTS -------------------------------------- - 2 NAxCoef - Number of axial coefficients (-) -AxCoefID AxCd AxCa AxCp -(-) (-) (-) (-) -1 0.00 0.00 0.00 ! Columns / Braces (no exposed member ends) -2 1.00 1.00 1.00 ! Heave Plates ----------------------- MEMBER JOINTS ------------------------------------------- - 33 NJoints - Number of joints (-) [must be exactly 0 or at least 2] -JointID Jointxi Jointyi Jointzi JointAxID JointOvrlp [JointOvrlp= 0: do nothing at joint, 1: eliminate overlaps by calculating super member] -(-) (m) (m) (m) (-) (switch) -0 28.0 0 -10 1 0 ! Downstream Column -1 28.0 0 6 1 0 -2 -28.0 0 -10 1 0 ! Upstream Column -3 -28.0 0 6 1 0 -4 0 -12.0 -10 1 0 ! Starboard Column -5 0 -12.0 6 1 0 -6 0 12.0 -10 1 0 ! Port Column -7 0 12.0 6 1 0 -8 3.67658 10.4243 4.5 1 0 ! Upper Braces -9 24.3234 1.57568 4.5 1 0 -10 3.67658 -10.4243 4.5 1 0 -11 24.3234 -1.57568 4.5 1 0 -12 -3.67658 10.4243 4.5 1 0 -13 -24.3234 1.57568 4.5 1 0 -14 -3.67658 -10.4243 4.5 1 0 -15 -24.3234 -1.57568 4.5 1 0 -16 3.67658 10.4243 -8.5 1 0 ! Lower Braces -17 24.3234 1.57568 -8.5 1 0 -18 3.67658 -10.4243 -8.5 1 0 -19 24.3234 -1.57568 -8.5 1 0 -20 -3.67658 10.4243 -8.5 1 0 -21 -24.3234 1.57568 -8.5 1 0 -22 -3.67658 -10.4243 -8.5 1 0 -23 -24.3234 -1.57568 -8.5 1 0 -24 0 -8 4.5 1 0 ! Tower Braces -25 0 8 4.5 1 0 -26 0 -8 -8.5 1 0 -27 0 8 -8.5 1 0 -28 0 0 -8.5 1 0 -29 28.0 0 -10.5 2 0 ! Heave Plates -30 -28.0 0 -10.5 2 0 -31 0 -12.0 -10.5 2 0 -32 0 12.0 -10.5 2 0 ----------------------- MEMBER CROSS-SECTION PROPERTIES ------------------------- - 4 NPropSets - Number of member property sets (-) -PropSetID PropD PropThck -(-) (m) (m) -0 8.0 0.02 ! Columns -1 2.0 0.02 ! Braces -2 2.0 0.081 ! Flooded Braces (not flooded in hydrodyn) -3 12.0 0.3925 ! Flooded Heave Plates (not flooded in hydrodyn) ----------------------- SIMPLE HYDRODYNAMIC COEFFICIENTS (model 1) -------------- -SimplCd SimplCdMG SimplCa SimplCaMG SimplCp SimplCpMG SimplAxCd SimplAxCdMG SimplAxCa SimplAxCaMG SimplAxCp SimplAxCpMG -(-) (-) (-) (-) (-) (-) (-) (-) (-) (-) (-) (-) -1.2 0.00 1.00 0.00 1.00 1.00 0.00 0.00 0.00 0.00 1.00 1.00 ----------------------- DEPTH-BASED HYDRODYNAMIC COEFFICIENTS (model 2) --------- - 0 NCoefDpth - Number of depth-dependent coefficients (-) -Dpth DpthCd DpthCdMG DpthCa DpthCaMG DpthCp DpthCpMG DpthAxCd DpthAxCdMG DpthAxCa DpthAxCaMG DpthAxCp DpthAxCpMG -(m) (-) (-) (-) (-) (-) (-) (-) (-) (-) (-) (-) (-) ----------------------- MEMBER-BASED HYDRODYNAMIC COEFFICIENTS (model 3) -------- - 0 NCoefMembers - Number of member-based coefficients (-) -MemberID MemberCd1 MemberCd2 MemberCdMG1 MemberCdMG2 MemberCa1 MemberCa2 MemberCaMG1 MemberCaMG2 MemberCp1 MemberCp2 MemberCpMG1 MemberCpMG2 MemberAxCd1 MemberAxCd2 MemberAxCdMG1 MemberAxCdMG2 MemberAxCa1 MemberAxCa2 MemberAxCaMG1 MemberAxCaMG2 MemberAxCp1 MemberAxCp2 MemberAxCpMG1 MemberAxCpMG2 -(-) (-) (-) (-) (-) (-) (-) (-) (-) (-) (-) (-) (-) (-) (-) (-) (-) (-) (-) (-) (-) (-) (-) (-) (-) --------------------- MEMBERS --------------------------------------------------- - 20 NMembers - Number of members (-) -MemberID MJointID1 MJointID2 MPropSetID1 MPropSetID2 MDivSize MCoefMod PropPot [MCoefMod=1: use simple coeff table, 2: use depth-based coeff table, 3: use member-based coeff table] [ PropPot/=0 if member is modeled with potential-flow theory] -(-) (-) (-) (-) (-) (m) (switch) (flag) -0 0 1 0 0 0.1 1 TRUE ! Columns -1 2 3 0 0 0.1 1 TRUE -2 4 5 0 0 0.1 1 TRUE -3 6 7 0 0 0.1 1 TRUE -4 8 9 1 1 0.1 1 TRUE ! Upper Braces -5 10 11 1 1 0.1 1 TRUE -6 12 13 1 1 0.1 1 TRUE -7 14 15 1 1 0.1 1 TRUE -8 16 17 2 2 0.1 1 TRUE ! Lower Braces -9 18 19 2 2 0.1 1 TRUE -10 20 21 2 2 0.1 1 TRUE -11 22 23 2 2 0.1 1 TRUE -12 24 25 1 1 0.1 1 TRUE ! Tower Braces -13 26 27 1 1 0.1 1 TRUE -14 24 28 1 1 0.1 1 TRUE -15 25 28 1 1 0.1 1 TRUE -16 0 29 3 3 0.1 1 TRUE ! Heave Plates -17 2 30 3 3 0.1 1 TRUE -18 4 31 3 3 0.1 1 TRUE -19 6 32 3 3 0.1 1 TRUE ----------------------- FILLED MEMBERS ------------------------------------------ - 0 NFillGroups - Number of filled member groups (-) [If FillDens = DEFAULT, then FillDens = WtrDens; FillFSLoc is related to MSL2SWL] -FillNumM FillMList FillFSLoc FillDens -(-) (-) (m) (kg/m^3) ----------------------- MARINE GROWTH ------------------------------------------- - 0 NMGDepths - Number of -growth depths specified (-) -MGDpth MGThck MGDens -(m) (m) (kg/m^3) ----------------------- MEMBER OUTPUT LIST -------------------------------------- - 0 NMOutputs - Number of member outputs (-) [must be < 10] -MemberID NOutLoc NodeLocs [NOutLoc < 10; node locations are normalized distance from the start of the member, and must be >=0 and <= 1] [unused if NMOutputs=0] -(-) (-) (-) ----------------------- JOINT OUTPUT LIST --------------------------------------- - 0 NJOutputs - Number of joint outputs [Must be < 10] - 0 JOutLst - List of JointIDs which are to be output (-)[unused if NJOutputs=0] ----------------------- OUTPUT -------------------------------------------------- -True HDSum - Output a summary file [flag] -False OutAll - Output all user-specified member and joint loads (only at each member end, not interior locations) [flag] - 2 OutSwtch - Output requested channels to: [1=Hydrodyn.out, 2=GlueCode.out, 3=both files] -"E15.7e2" OutFmt - Output format for numerical results (quoted string) [not checked for validity!] -"A11" OutSFmt - Output format for header strings (quoted string) [not checked for validity!] ----------------------- OUTPUT CHANNELS ----------------------------------------- -"Wave1Elev" - Wave elevation at the platform reference point (0, 0) -"HydroFxi" - Buoyancy force [N] in the X direction. -"HydroFyi" - Buoyancy force [N] in the Y direction. -"HydroFzi" - Buoyancy force [N] in the vertical direction (Z). -END of output channels and end of file. (the word "END" must appear in the first 3 columns of this line) - diff --git a/Test_Cases/MHK_RM1/MHK_RM1_Floating_InflowWind.dat b/Test_Cases/MHK_RM1/MHK_RM1_Floating_InflowWind.dat deleted file mode 100644 index 73c0b2f7..00000000 --- a/Test_Cases/MHK_RM1/MHK_RM1_Floating_InflowWind.dat +++ /dev/null @@ -1,69 +0,0 @@ -------- InflowWind INPUT FILE --------------------------------------------------------------------------------- -Steady 1.9 m/s inflow for floating MHK turbine, based on the RM1 tidal current rotor ---------------------------------------------------------------------------------------------------------------- -False Echo - Echo input data to .ech (flag) - 1 WindType - Switch for wind file type (1=steady; 2=uniform; 3=binary TurbSim FF; 4=binary Bladed-style FF; 5=HAWC format; 6=User defined; 7=native Bladed FF) - 0 PropagationDir - Direction of wind propagation (meteorological rotation from aligned with X (positive rotates towards -Y) -- degrees) (not used for native Bladed format WindType=7) - 0 VFlowAng - Upflow angle (degrees) (not used for native Bladed format WindType=7) -False VelInterpCubic - Use cubic interpolation for velocity in time (false=linear, true=cubic) [Used with WindType=2,3,4,5,7] - 1 NWindVel - Number of points to output the wind velocity (0 to 9) - 0 WindVxiList - List of coordinates in the inertial X direction (m) - 0 WindVyiList - List of coordinates in the inertial Y direction (m) - 12.2 WindVziList - List of coordinates in the inertial Z direction (m) -================== Parameters for Steady Wind Conditions [used only for WindType = 1] ======================= - 1.9 HWindSpeed - Horizontal wind speed (m/s) - 12.2 RefHt - Reference height for horizontal wind speed (m) - 0 PLExp - Power law exponent (-) -================== Parameters for Uniform wind file [used only for WindType = 2] ============================ -"unused" Filename_Uni - Filename of time series data for uniform wind field. (-) - 30 RefHt_Uni - Reference height for horizontal wind speed (m) - 125.88 RefLength - Reference length for linear horizontal and vertical sheer (-) -================== Parameters for Binary TurbSim Full-Field files [used only for WindType = 3] ============== -"unused" FileName_BTS - Name of the Full field wind file to use (.bts) -================== Parameters for Binary Bladed-style Full-Field files [used only for WindType = 4 or WindType = 7] ======= -"unused" FileNameRoot - WindType=4: Rootname of the full-field wind file to use (.wnd, .sum); WindType=7: name of the intermediate file with wind scaling values -False TowerFile - Have tower file (.twr) (flag) ignored when WindType = 7 -================== Parameters for HAWC-format binary files [Only used with WindType = 5] ==================== -"unused" FileName_u - name of the file containing the u-component fluctuating wind (.bin) -"unused" FileName_v - name of the file containing the v-component fluctuating wind (.bin) -"unused" FileName_w - name of the file containing the w-component fluctuating wind (.bin) - 64 nx - number of grids in the x direction (in the 3 files above) (-) - 32 ny - number of grids in the y direction (in the 3 files above) (-) - 32 nz - number of grids in the z direction (in the 3 files above) (-) - 16 dx - distance (in meters) between points in the x direction (m) - 3 dy - distance (in meters) between points in the y direction (m) - 3 dz - distance (in meters) between points in the z direction (m) - 90 RefHt_Hawc - reference height; the height (in meters) of the vertical center of the grid (m) - ------------- Scaling parameters for turbulence --------------------------------------------------------- - 1 ScaleMethod - Turbulence scaling method [0 = none, 1 = direct scaling, 2 = calculate scaling factor based on a desired standard deviation] - 1 SFx - Turbulence scaling factor for the x direction (-) [ScaleMethod=1] - 1 SFy - Turbulence scaling factor for the y direction (-) [ScaleMethod=1] - 1 SFz - Turbulence scaling factor for the z direction (-) [ScaleMethod=1] - 1 SigmaFx - Turbulence standard deviation to calculate scaling from in x direction (m/s) [ScaleMethod=2] - 1 SigmaFy - Turbulence standard deviation to calculate scaling from in y direction (m/s) [ScaleMethod=2] - 1 SigmaFz - Turbulence standard deviation to calculate scaling from in z direction (m/s) [ScaleMethod=2] - ------------- Mean wind profile parameters (added to HAWC-format files) --------------------------------- - 5 URef - Mean u-component wind speed at the reference height (m/s) - 2 WindProfile - Wind profile type (0=constant;1=logarithmic,2=power law) - 0 PLExp_Hawc - Power law exponent (-) (used for PL wind profile type only) - 0.03 Z0 - Surface roughness length (m) (used for LG wind profile type only) - 0 XOffset - Initial offset in +x direction (shift of wind box) -================== LIDAR Parameters =========================================================================== -0 SensorType - Switch for lidar configuration (0 = None, 1 = Single Point Beam(s), 2 = Continuous, 3 = Pulsed) -0 NumPulseGate - Number of lidar measurement gates (used when SensorType = 3) -30 PulseSpacing - Distance between range gates (m) (used when SensorType = 3) -0 NumBeam - Number of lidar measurement beams (0-5)(used when SensorType = 1) --200 FocalDistanceX - Focal distance co-ordinates of the lidar beam in the x direction (relative to hub height) (only first coordinate used for SensorType 2 and 3) (m) -0 FocalDistanceY - Focal distance co-ordinates of the lidar beam in the y direction (relative to hub height) (only first coordinate used for SensorType 2 and 3) (m) -0 FocalDistanceZ - Focal distance co-ordinates of the lidar beam in the z direction (relative to hub height) (only first coordinate used for SensorType 2 and 3) (m) -0.0 0.0 0.0 RotorApexOffsetPos - Offset of the lidar from hub height (m) -17 URefLid - Reference average wind speed for the lidar[m/s] -0.25 MeasurementInterval - Time between each measurement [s] -False LidRadialVel - TRUE => return radial component, FALSE => return 'x' direction estimate -1 ConsiderHubMotion - Flag whether to consider the hub motion's impact on Lidar measurements -================== OUTPUT ===================================================================================== -True SumPrint - Print summary data to .IfW.sum (flag) - OutList - The next line(s) contains a list of output parameters. See OutListParameters.xlsx for a listing of available output channels, (-) -Wind1VelX -END of input file (the word "END" must appear in the first 3 columns of this last OutList line) ---------------------------------------------------------------------------------------------------------------- diff --git a/Test_Cases/MHK_RM1/MHK_RM1_Floating_MoorDyn.dat b/Test_Cases/MHK_RM1/MHK_RM1_Floating_MoorDyn.dat deleted file mode 100644 index 89e416dc..00000000 --- a/Test_Cases/MHK_RM1/MHK_RM1_Floating_MoorDyn.dat +++ /dev/null @@ -1,58 +0,0 @@ ---------------------- MoorDyn Input File ------------------------------------ -Floating MHK turbine mooring input properties, based on the RM1 tidal current rotor with a quad-style floating platform -FALSE Echo - echo the input file data (flag) ------------------------ LINE TYPES Chain studless 0.018m -------------------- -Name Diam MassDen EA BA/-zeta EI Cd Ca CdAx CaAx -(-) (m) (kg/m) (N) (N-s/-) (-) (-) (-) (-) (-) -main 0.324 644.8 85.4e8 -0.8 0.8 2.4 1.0 1.15 0.5 ----------------------- POINTS ----------------------------------------------- -Node Type X Y Z M V CdA CA -(-) (-) (m) (m) (m) (kg) (m^3) (m^2) (-) -1 Fixed -152.0 -50.0 -50.0 0 0 0 0 -2 Fixed -152.0 0.0 -50.0 0 0 0 0 -3 Fixed -152.0 50.0 -50.0 0 0 0 0 -4 Fixed 152.0 -50.0 -50.0 0 0 0 0 -5 Fixed 152.0 0.0 -50.0 0 0 0 0 -6 Fixed 152.0 50.0 -50.0 0 0 0 0 -7 Vessel -34.0 0.0 -10.0 0 0 0 0 -8 Vessel -34.0 0.0 -10.0 0 0 0 0 -9 Vessel -34.0 0.0 -10.0 0 0 0 0 -10 Vessel 34.0 0.0 -10.0 0 0 0 0 -11 Vessel 34.0 0.0 -10.0 0 0 0 0 -12 Vessel 34.0 0.0 -10.0 0 0 0 0 ----------------------- LINES ------------------------------------------------ -Line LineType AttachA AttachB UnstrLen NumSegs Outputs -(-) (-) (-) (-) (m) (-) (-) -1 main 1 7 160.0 30 - -2 main 2 8 152.0 30 - -3 main 3 9 160.0 30 - -4 main 4 10 160.0 30 - -5 main 5 11 152.0 30 - -6 main 6 12 160.0 30 - ----------------------- SOLVER OPTIONS --------------------------------------- -0.5e-4 dtM - time step to use in mooring integration (s) -3.0e6 kbot - bottom stiffness (Pa/m) -3.0e5 cbot - bottom damping (Pa-s/m) -1.0 dtIC - time interval for analyzing convergence during IC gen (s) -10.0 TmaxIC - max time for ic gen (s) -4.0 CdScaleIC - factor by which to scale drag coefficients during dynamic relaxation (-) -0.1 threshIC - threshold for IC convergence (-) ------------------------- OUTPUTS -------------------------------------------- -FairTen1 FairTen2 FairTen3 FairTen4 FairTen5 FairTen6 -AnchTen1 AnchTen2 AnchTen3 AnchTen4 AnchTen5 AnchTen6 -Con1fX Con1fY Con1fZ -Con2fX Con2fY Con2fZ -Con3fX Con3fY Con3fZ -Con4fX Con4fY Con4fZ -Con5fX Con5fY Con5fZ -Con6fX Con6fY Con6fZ -Con7fX Con7fY Con7fZ Con7pX Con7pY Con7pZ -Con8fX Con8fY Con8fZ Con8pX Con8pY Con8pZ -Con9fX Con9fY Con9fZ Con9pX Con9pY Con9pZ -Con10fX Con10fY Con10fZ Con10pX Con10pY Con10pZ -Con11fX Con11fY Con11fZ Con11pX Con11pY Con11pZ -Con12fX Con12fY Con12fZ Con12pX Con12pY Con12pZ -L1N1pZ L1N2pZ L1N3pZ L1N4pZ L1N5pZ L1N6pZ L1N7pZ L1N8pZ L1N9pZ L1N10pZ L1N11pZ L1N12pZ L1N13pZ L1N14pZ L1N15pZ L1N16pZ L1N17pZ L1N18pZ L1N19pZ L1N20pZ L1N21pZ L1N22pZ L1N23pZ L1N24pZ L1N25pZ L1N26pZ L1N27pZ L1N28pZ L1N29pZ L1N30pZ -L2N1pZ L2N2pZ L2N3pZ L2N4pZ L2N5pZ L2N6pZ L2N7pZ L2N8pZ L2N9pZ L2N10pZ L2N11pZ L2N12pZ L2N13pZ L2N14pZ L2N15pZ L2N16pZ L2N17pZ L2N18pZ L2N19pZ L2N20pZ L2N21pZ L2N22pZ L2N23pZ L2N24pZ L2N25pZ L2N26pZ L2N27pZ L2N28pZ L2N29pZ L2N30pZ -END -------------------------- need this line ------------------------------------ diff --git a/Test_Cases/MHK_RM1/MHK_RM1_ServoDyn.dat b/Test_Cases/MHK_RM1/MHK_RM1_ServoDyn.dat deleted file mode 100644 index 1e9b8ff8..00000000 --- a/Test_Cases/MHK_RM1/MHK_RM1_ServoDyn.dat +++ /dev/null @@ -1,111 +0,0 @@ -------- SERVODYN v1.05.* INPUT FILE -------------------------------------------- -NREL 5.0 MW Baseline Wind Turbine for Use in Offshore Analysis. Properties from Dutch Offshore Wind Energy Converter (DOWEC) 6MW Pre-Design (10046_009.pdf) and REpower 5M 5MW (5m_uk.pdf) ----------------------- SIMULATION CONTROL -------------------------------------- -False Echo - Echo input data to .ech (flag) -"default" DT - Communication interval for controllers (s) (or "default") ----------------------- PITCH CONTROL ------------------------------------------- - 5 PCMode - Pitch control mode {0: none, 3: user-defined from routine PitchCntrl, 4: user-defined from Simulink/Labview, 5: user-defined from Bladed-style DLL} (switch) - 0 TPCOn - Time to enable active pitch control (s) [unused when PCMode=0] - 9999.9 TPitManS(1) - Time to start override pitch maneuver for blade 1 and end standard pitch control (s) - 9999.9 TPitManS(2) - Time to start override pitch maneuver for blade 2 and end standard pitch control (s) - 9999.9 TPitManS(3) - Time to start override pitch maneuver for blade 3 and end standard pitch control (s) [unused for 2 blades] - 2 PitManRat(1) - Pitch rate at which override pitch maneuver heads toward final pitch angle for blade 1 (deg/s) - 2 PitManRat(2) - Pitch rate at which override pitch maneuver heads toward final pitch angle for blade 2 (deg/s) - 2 PitManRat(3) - Pitch rate at which override pitch maneuver heads toward final pitch angle for blade 3 (deg/s) [unused for 2 blades] - 0 BlPitchF(1) - Blade 1 final pitch for pitch maneuvers (degrees) - 0 BlPitchF(2) - Blade 2 final pitch for pitch maneuvers (degrees) - 0 BlPitchF(3) - Blade 3 final pitch for pitch maneuvers (degrees) [unused for 2 blades] ----------------------- GENERATOR AND TORQUE CONTROL ---------------------------- - 5 VSContrl - Variable-speed control mode {0: none, 1: simple VS, 3: user-defined from routine UserVSCont, 4: user-defined from Simulink/Labview, 5: user-defined from Bladed-style DLL} (switch) - 2 GenModel - Generator model {1: simple, 2: Thevenin, 3: user-defined from routine UserGen} (switch) [used only when VSContrl=0] - 94.4 GenEff - Generator efficiency [ignored by the Thevenin and user-defined generator models] (%) -True GenTiStr - Method to start the generator {T: timed using TimGenOn, F: generator speed using SpdGenOn} (flag) -True GenTiStp - Method to stop the generator {T: timed using TimGenOf, F: when generator power = 0} (flag) - 9999.9 SpdGenOn - Generator speed to turn on the generator for a startup (HSS speed) (rpm) [used only when GenTiStr=False] - 0 TimGenOn - Time to turn on the generator for a startup (s) [used only when GenTiStr=True] - 9999.9 TimGenOf - Time to turn off the generator (s) [used only when GenTiStp=True] ----------------------- SIMPLE VARIABLE-SPEED TORQUE CONTROL -------------------- - 9999.9 VS_RtGnSp - Rated generator speed for simple variable-speed generator control (HSS side) (rpm) [used only when VSContrl=1] - 9999.9 VS_RtTq - Rated generator torque/constant generator torque in Region 3 for simple variable-speed generator control (HSS side) (N-m) [used only when VSContrl=1] - 9999.9 VS_Rgn2K - Generator torque constant in Region 2 for simple variable-speed generator control (HSS side) (N-m/rpm^2) [used only when VSContrl=1] - 9999.9 VS_SlPc - Rated generator slip percentage in Region 2 1/2 for simple variable-speed generator control (%) [used only when VSContrl=1] ----------------------- SIMPLE INDUCTION GENERATOR ------------------------------ - 9999.9 SIG_SlPc - Rated generator slip percentage (%) [used only when VSContrl=0 and GenModel=1] - 9999.9 SIG_SySp - Synchronous (zero-torque) generator speed (rpm) [used only when VSContrl=0 and GenModel=1] - 9999.9 SIG_RtTq - Rated torque (N-m) [used only when VSContrl=0 and GenModel=1] - 9999.9 SIG_PORt - Pull-out ratio (Tpullout/Trated) (-) [used only when VSContrl=0 and GenModel=1] ----------------------- THEVENIN-EQUIVALENT INDUCTION GENERATOR ----------------- - 9999.9 TEC_Freq - Line frequency [50 or 60] (Hz) [used only when VSContrl=0 and GenModel=2] - 9998 TEC_NPol - Number of poles [even integer > 0] (-) [used only when VSContrl=0 and GenModel=2] - 9999.9 TEC_SRes - Stator resistance (ohms) [used only when VSContrl=0 and GenModel=2] - 9999.9 TEC_RRes - Rotor resistance (ohms) [used only when VSContrl=0 and GenModel=2] - 9999.9 TEC_VLL - Line-to-line RMS voltage (volts) [used only when VSContrl=0 and GenModel=2] - 9999.9 TEC_SLR - Stator leakage reactance (ohms) [used only when VSContrl=0 and GenModel=2] - 9999.9 TEC_RLR - Rotor leakage reactance (ohms) [used only when VSContrl=0 and GenModel=2] - 9999.9 TEC_MR - Magnetizing reactance (ohms) [used only when VSContrl=0 and GenModel=2] ----------------------- HIGH-SPEED SHAFT BRAKE ---------------------------------- - 0 HSSBrMode - HSS brake model {0: none, 1: simple, 3: user-defined from routine UserHSSBr, 4: user-defined from Simulink/Labview, 5: user-defined from Bladed-style DLL} (switch) - 9999.9 THSSBrDp - Time to initiate deployment of the HSS brake (s) - 0.6 HSSBrDT - Time for HSS-brake to reach full deployment once initiated (sec) [used only when HSSBrMode=1] - 28116.2 HSSBrTqF - Fully deployed HSS-brake torque (N-m) ----------------------- NACELLE-YAW CONTROL ------------------------------------- - 0 YCMode - Yaw control mode {0: none, 3: user-defined from routine UserYawCont, 4: user-defined from Simulink/Labview, 5: user-defined from Bladed-style DLL} (switch) - 9999.9 TYCOn - Time to enable active yaw control (s) [unused when YCMode=0] - 0 YawNeut - Neutral yaw position--yaw spring force is zero at this yaw (degrees) -9.02832E+09 YawSpr - Nacelle-yaw spring constant (N-m/rad) - 1.916E+07 YawDamp - Nacelle-yaw damping constant (N-m/(rad/s)) - 9999.9 TYawManS - Time to start override yaw maneuver and end standard yaw control (s) - 2 YawManRat - Yaw maneuver rate (in absolute value) (deg/s) - 0 NacYawF - Final yaw angle for override yaw maneuvers (degrees) ----------------------- AERODYNAMIC FLOW CONTROL -------------------------------- - 0 AfCmode - Airfoil control mode {0: none, 1: cosine wave cycle, 4: user-defined from Simulink/Labview, 5: user-defined from Bladed-style DLL} (switch) - 0 AfC_Mean - Mean level for cosine cycling or steady value (-) [used only with AfCmode==1] - 0 AfC_Amp - Amplitude for for cosine cycling of flap signal (-) [used only with AfCmode==1] - 0 AfC_Phase - Phase relative to the blade azimuth (0 is vertical) for for cosine cycling of flap signal (deg) [used only with AfCmode==1] ----------------------- STRUCTURAL CONTROL -------------------------------------- -0 NumBStC - Number of blade structural controllers (integer) -"unused" BStCfiles - Name of the files for blade structural controllers (quoted strings) [unused when NumBStC==0] -0 NumNStC - Number of nacelle structural controllers (integer) -"unused" NStCfiles - Name of the files for nacelle structural controllers (quoted strings) [unused when NumNStC==0] -0 NumTStC - Number of tower structural controllers (integer) -"unused" TStCfiles - Name of the files for tower structural controllers (quoted strings) [unused when NumTStC==0] -0 NumSStC - Number of substructure structural controllers (integer) -"unused" SStCfiles - Name of the files for substructure structural controllers (quoted strings) [unused when NumSStC==0] ----------------------- CABLE CONTROL ------------------------------------------- - 0 CCmode - Cable control mode {0: none, 4: user-defined from Simulink/Labview, 5: user-defined from Bladed-style DLL} (switch) ----------------------- BLADED INTERFACE ---------------------------------------- [used only with Bladed Interface] -"../../ROSCO/install/lib/libdiscon.so" DLL_FileName - Name/location of the dynamic library {.dll [Windows] or .so [Linux]} in the Bladed-DLL format (-) [used only with Bladed Interface] -"MHK_RM1_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] -false DLL_Ramp - Whether a linear ramp should be used between DLL_DT time steps [introduces time shift when true] (flag) [used only with Bladed Interface] - 9999.9 BPCutoff - Cutoff frequency for low-pass filter on blade pitch from DLL (Hz) [used only with Bladed Interface] - 0 NacYaw_North - Reference yaw angle of the nacelle when the upwind end points due North (deg) [used only with Bladed Interface] - 1 Ptch_Cntrl - Record 28: Use individual pitch control {0: collective pitch; 1: individual pitch control} (switch) [used only with Bladed Interface] - 0 Ptch_SetPnt - Record 5: Below-rated pitch angle set-point (deg) [used only with Bladed Interface] - 0 Ptch_Min - Record 6: Minimum pitch angle (deg) [used only with Bladed Interface] - 0 Ptch_Max - Record 7: Maximum pitch angle (deg) [used only with Bladed Interface] - 0 PtchRate_Min - Record 8: Minimum pitch rate (most negative value allowed) (deg/s) [used only with Bladed Interface] - 0 PtchRate_Max - Record 9: Maximum pitch rate (deg/s) [used only with Bladed Interface] - 0 Gain_OM - Record 16: Optimal mode gain (Nm/(rad/s)^2) [used only with Bladed Interface] - 0 GenSpd_MinOM - Record 17: Minimum generator speed (rpm) [used only with Bladed Interface] - 0 GenSpd_MaxOM - Record 18: Optimal mode maximum speed (rpm) [used only with Bladed Interface] - 0 GenSpd_Dem - Record 19: Demanded generator speed above rated (rpm) [used only with Bladed Interface] - 0 GenTrq_Dem - Record 22: Demanded generator torque above rated (Nm) [used only with Bladed Interface] - 0 GenPwr_Dem - Record 13: Demanded power (W) [used only with Bladed Interface] ----------------------- BLADED INTERFACE TORQUE-SPEED LOOK-UP TABLE ------------- - 0 DLL_NumTrq - Record 26: No. of points in torque-speed look-up table {0 = none and use the optimal mode parameters; nonzero = ignore the optimal mode PARAMETERs by setting Record 16 to 0.0} (-) [used only with Bladed Interface] - GenSpd_TLU GenTrq_TLU - (rpm) (Nm) ----------------------- OUTPUT -------------------------------------------------- -True SumPrint - Print summary data to .sum (flag) (currently unused) - 1 OutFile - Switch to determine where output will be placed: {1: in module output file only; 2: in glue code output file only; 3: both} (currently unused) -True TabDelim - Use tab delimiters in text tabular output file? (flag) (currently unused) -"ES10.3E2" OutFmt - Format used for text tabular output (except time). Resulting field should be 10 characters. (quoted string) (currently unused) - 0 TStart - Time to begin tabular output (s) (currently unused) - OutList - The next line(s) contains a list of output parameters. See OutListParameters.xlsx for a listing of available output channels, (-) -"GenPwr" - Electrical generator power and torque -"GenTq" - Electrical generator power and torque -"GenSpeed" -END of input file (the word "END" must appear in the first 3 columns of this last OutList line) ---------------------------------------------------------------------------------------- From 2787ff93e3211f9ab68c13ed0a6df9ee7b00bafb Mon Sep 17 00:00:00 2001 From: David Stockhouse Date: Fri, 10 May 2024 10:29:46 -0600 Subject: [PATCH 140/224] Expanded test script and made cc-blade Cp surface generation extend to smaller TSR values --- Examples/29_marine_hydro_fbp.py | 115 +++++++++++----- Test_Cases/MHK_RM1/MHK_RM1_Cp_Ct_Cq.txt | 171 +++++++++++++----------- rosco/toolbox/controller.py | 6 +- rosco/toolbox/turbine.py | 4 +- 4 files changed, 182 insertions(+), 114 deletions(-) diff --git a/Examples/29_marine_hydro_fbp.py b/Examples/29_marine_hydro_fbp.py index 08a6764d..7f5bc2f1 100644 --- a/Examples/29_marine_hydro_fbp.py +++ b/Examples/29_marine_hydro_fbp.py @@ -12,6 +12,7 @@ from rosco.toolbox.ofTools.fast_io import output_processing from rosco.toolbox import controller as ROSCO_controller from rosco.toolbox import turbine as ROSCO_turbine +from rosco.toolbox import utilities as ROSCO_utilities from rosco.toolbox.utilities import write_DISCON from rosco.toolbox.inputs.validation import load_rosco_yaml import matplotlib.pyplot as plt @@ -47,15 +48,69 @@ def main(): # Load turbine data from OpenFAST and rotor performance text file cp_filename = os.path.join(this_dir,path_params['rotor_performance_filename']) - turbine.load_from_fast( - path_params['FAST_InputFile'], - os.path.join(this_dir,path_params['FAST_directory']), - rot_source='txt',txt_filename= cp_filename - ) + if False: + turbine.load_from_fast( + path_params['FAST_InputFile'], + os.path.join(this_dir, path_params['FAST_directory']), + rot_source='cc-blade', txt_filename=cp_filename + ) + ROSCO_utilities.write_rotor_performance(turbine, cp_filename) + else: + turbine.load_from_fast( + path_params['FAST_InputFile'], + os.path.join(this_dir, path_params['FAST_directory']), + rot_source='txt', txt_filename= cp_filename + ) + + # Tune controller cases + controller.tune_controller(turbine) + + fig, axs = plt.subplots(3,1) + axs[0].plot(controller.v, controller.power_op, label='Gen Power') + axs[0].set_xlabel('Gen Power [W]') + axs[1].plot(controller.v, controller.omega_gen_op, label='Gen Speed') + axs[0].set_xlabel('Gen Speed [rad/s]') + axs[2].plot(controller.v, controller.tau_op ,label='Gen Torque') + axs[0].set_xlabel('Gen Torque [N m]') + fig.suptitle('Constant Power') + + + controller_params['FBP_P'] = [1.0, 2.0] + controller = ROSCO_controller.Controller(controller_params) + controller.tune_controller(turbine) + + fig, axs = plt.subplots(3,1) + axs[0].plot(controller.v, controller.power_op, label='Gen Power') + axs[0].set_xlabel('Gen Power [W]') + axs[1].plot(controller.v, controller.omega_gen_op, label='Gen Speed') + axs[0].set_xlabel('Gen Speed [rad/s]') + axs[2].plot(controller.v, controller.tau_op ,label='Gen Torque') + axs[0].set_xlabel('Gen Torque [N m]') + fig.suptitle('Linear Increasing Power') + - # Tune controller + controller_params['FBP_U'] = [2.0, 3.0] + controller_params['FBP_P'] = [1.0, 2.0] + controller = ROSCO_controller.Controller(controller_params) controller.tune_controller(turbine) + fig, axs = plt.subplots(3,1) + axs[0].plot(controller.v, controller.power_op, label='Gen Power') + axs[0].set_xlabel('Gen Power [W]') + axs[1].plot(controller.v, controller.omega_gen_op, label='Gen Speed') + axs[0].set_xlabel('Gen Speed [rad/s]') + axs[2].plot(controller.v, controller.tau_op ,label='Gen Torque') + axs[0].set_xlabel('Gen Torque [N m]') + fig.suptitle('Linear Increasing Leveled Power') + + + if True: + # plt.show() + plt.show(block=False) + 0 + else: + plt.savefig(os.path.join(example_out_dir,'29_marine_hydro_fbp_sched.png')) + # Write parameter input file param_file = os.path.join(run_dir,'DISCON.IN') write_DISCON(turbine, @@ -84,30 +139,30 @@ def main(): # plt.suptitle('Pitch Controller Gains') - # simulation set up - r = run_FAST_ROSCO() - r.tuning_yaml = parameter_filename - # r.wind_case_fcn = cl.simp_step # single step wind input - r.wind_case_fcn = cl.power_curve - r.wind_case_opts = { - 'U': [3.5], - 'TMax': 100.0, - } - r.case_inputs = {} - # r.fst_vt = reader.fst_vt - # r.controller_params = controller_params - r.save_dir = run_dir - r.rosco_dir = rosco_dir - - r.run_FAST() - - op = output_processing.output_processing() - fast_out = op.load_fast_out([os.path.join(run_dir,'RM1_MHK_FBP/power_curve/base/RM1_MHK_FBP_0.out')], tmin=0) - fig, axs = plt.subplots(4,1) - axs[0].plot(fast_out[0]['Time'],fast_out[0]['Wind1VelX'],label='Flow Speed') - axs[1].plot(fast_out[0]['Time'],fast_out[0]['GenSpeed'],label='Gen Speed') - axs[2].plot(fast_out[0]['Time'],fast_out[0]['GenTq'],label='Gen Torque') - axs[3].plot(fast_out[0]['Time'],fast_out[0]['GenPwr'],label='Gen Power') + # # simulation set up + # r = run_FAST_ROSCO() + # r.tuning_yaml = parameter_filename + # # r.wind_case_fcn = cl.simp_step # single step wind input + # r.wind_case_fcn = cl.power_curve + # r.wind_case_opts = { + # 'U': [3.5], + # 'TMax': 100.0, + # } + # r.case_inputs = {} + # # r.fst_vt = reader.fst_vt + # # r.controller_params = controller_params + # r.save_dir = run_dir + # r.rosco_dir = rosco_dir + + # r.run_FAST() + + # op = output_processing.output_processing() + # fast_out = op.load_fast_out([os.path.join(run_dir,'RM1_MHK_FBP/power_curve/base/RM1_MHK_FBP_0.out')], tmin=0) + # fig, axs = plt.subplots(4,1) + # axs[0].plot(fast_out[0]['Time'],fast_out[0]['Wind1VelX'],label='Flow Speed') + # axs[1].plot(fast_out[0]['Time'],fast_out[0]['GenSpeed'],label='Gen Speed') + # axs[2].plot(fast_out[0]['Time'],fast_out[0]['GenTq'],label='Gen Torque') + # axs[3].plot(fast_out[0]['Time'],fast_out[0]['GenPwr'],label='Gen Power') # op = output_processing.output_processing() diff --git a/Test_Cases/MHK_RM1/MHK_RM1_Cp_Ct_Cq.txt b/Test_Cases/MHK_RM1/MHK_RM1_Cp_Ct_Cq.txt index da7445bf..fab56c49 100644 --- a/Test_Cases/MHK_RM1/MHK_RM1_Cp_Ct_Cq.txt +++ b/Test_Cases/MHK_RM1/MHK_RM1_Cp_Ct_Cq.txt @@ -1,99 +1,108 @@ # ----- Rotor performance tables for the MHK_RM1_Floating wind turbine ----- -# ------------ Written on Apr-12-23 using the ROSCO toolbox ------------ +# ------------ Written on May-10-24 using the ROSCO toolbox ------------ # Pitch angle vector, 36 entries - x axis (matrix columns) (deg) -5.0 -4.0 -3.0 -2.0 -1.0 0.0 1.0 2.0 3.0 4.0 5.0 6.0 7.0 8.0 9.0 10.0 11.0 12.0 13.0 14.0 15.0 16.0 17.0 18.0 19.0 20.0 21.0 22.0 23.0 24.0 25.0 26.0 27.0 28.0 29.0 30.0 -# TSR vector, 26 entries - y axis (matrix rows) (-) -2.0 2.5 3.0 3.5 4.0 4.5 5.0 5.5 6.0 6.5 7.0 7.5 8.0 8.5 9.0 9.5 10.0 10.5 11.0 11.5 12.0 12.5 13.0 13.5 14.0 14.5 +# TSR vector, 29 entries - y axis (matrix rows) (-) +0.5 1.0 1.5 2.0 2.5 3.0 3.5 4.0 4.5 5.0 5.5 6.0 6.5 7.0 7.5 8.0 8.5 9.0 9.5 10.0 10.5 11.0 11.5 12.0 12.5 13.0 13.5 14.0 14.5 # Wind speed vector - z axis (m/s) 2.0 # Power coefficient -0.074944 0.079726 0.084378 0.088881 0.093217 0.097364 0.101301 0.105005 0.108455 0.111627 0.114499 0.117048 0.119254 0.121097 0.122559 0.123624 0.124278 0.124507 0.124300 0.123645 0.122533 0.120953 0.118899 0.116363 0.113340 0.109825 0.105817 0.101315 0.096316 0.090822 0.084833 0.078355 0.071398 0.063985 0.056154 0.047964 -0.130952 0.137109 0.142870 0.148203 0.153074 0.157453 0.161312 0.164628 0.167372 0.169517 0.171039 0.171924 0.172157 0.171726 0.170619 0.168827 0.166341 0.163154 0.159260 0.154654 0.149334 0.143297 0.136543 0.129071 0.120881 0.111975 0.102356 0.092036 0.081046 0.069441 0.057307 0.044758 0.031932 0.018970 0.006005 -0.006847 -0.195638 0.202139 0.207875 0.212814 0.216927 0.220183 0.222553 0.224026 0.224594 0.224263 0.222996 0.220777 0.217599 0.213457 0.208343 0.202253 0.195185 0.187134 0.178099 0.168078 0.157067 0.145065 0.132070 0.118086 0.103136 0.087277 0.070607 0.053271 0.035454 0.017370 -0.000779 -0.018814 -0.036579 -0.053937 -0.070772 -0.086985 -0.262033 0.267729 0.272255 0.275602 0.277770 0.278772 0.278626 0.277286 0.274722 0.270950 0.265956 0.259691 0.252150 0.243325 0.233208 0.221791 0.209065 0.195021 0.179649 0.162940 0.144884 0.125492 0.104814 0.082960 0.060099 0.036466 0.012350 -0.011952 -0.036178 -0.060102 -0.083527 -0.106282 -0.128227 -0.149248 -0.169259 -0.188203 -0.322926 0.327173 0.329927 0.331189 0.330966 0.329268 0.326118 0.321556 0.315485 0.307866 0.298685 0.287857 0.275361 0.261178 0.245286 0.227663 0.208287 0.187132 0.164179 0.139430 0.112946 0.084868 0.055418 0.024908 -0.006270 -0.037714 -0.069075 -0.100049 -0.130376 -0.159832 -0.188230 -0.215422 -0.241296 -0.265780 -0.288840 -0.310479 -0.372380 0.375319 0.376595 0.376163 0.373941 0.369893 0.364015 0.356336 0.346830 0.335323 0.321769 0.306044 0.288110 0.267928 0.245459 0.220662 0.193502 0.163952 0.132049 0.097926 0.061824 0.024095 -0.014788 -0.054287 -0.093913 -0.133250 -0.171936 -0.209660 -0.246161 -0.281224 -0.314687 -0.346436 -0.376411 -0.404602 -0.431047 -0.455838 -0.405840 0.408981 0.410112 0.409159 0.406069 0.400647 0.392786 0.382501 0.369826 0.354510 0.336432 0.315446 0.291501 0.264544 0.234524 0.201389 0.165121 0.125794 0.083613 0.038921 -0.007794 -0.055894 -0.104692 -0.153592 -0.202082 -0.249721 -0.296127 -0.340984 -0.384037 -0.425096 -0.464037 -0.500803 -0.535402 -0.567911 -0.598467 -0.627270 -0.419815 0.426133 0.429721 0.430398 0.428020 0.422533 0.413665 0.401397 0.385844 0.366737 0.343872 0.317114 0.286411 0.251710 0.212957 0.170136 0.123352 0.072872 0.019131 -0.037250 -0.095463 -0.154643 -0.214052 -0.273053 -0.331092 -0.387697 -0.442469 -0.495093 -0.545333 -0.593039 -0.638145 -0.680670 -0.720718 -0.758469 -0.794184 -0.828187 -0.416203 0.426901 0.435700 0.440694 0.441121 0.436927 0.428055 0.414373 0.396136 0.373105 0.345026 0.311802 0.273402 0.229785 0.180939 0.126984 0.068233 0.005200 -0.061381 -0.130534 -0.201181 -0.272387 -0.343354 -0.413383 -0.481873 -0.548318 -0.612312 -0.673550 -0.731832 -0.787064 -0.839260 -0.888535 -0.935107 -0.979287 -1.021467 -1.062112 -0.405435 0.418564 0.430778 0.441391 0.446693 0.445250 0.437234 0.422572 0.401692 0.374435 0.340533 0.299965 0.252737 0.198854 0.138441 0.071834 -0.000397 -0.077426 -0.158137 -0.241210 -0.325451 -0.409848 -0.493517 -0.575688 -0.655711 -0.733053 -0.807309 -0.878198 -0.945571 -1.009410 -1.069825 -1.127051 -1.181434 -1.233429 -1.283586 -1.332529 -0.390503 0.406666 0.421413 0.435076 0.446065 0.448699 0.442235 0.426873 0.403229 0.371269 0.330765 0.281798 0.224440 0.158821 0.085281 0.004419 -0.082876 -0.175390 -0.271577 -0.369910 -0.469102 -0.568030 -0.665710 -0.761300 -0.854102 -0.943564 -1.029289 -1.111036 -1.188722 -1.262423 -1.332361 -1.398905 -1.462560 -1.523949 -1.583795 -1.642861 -0.371667 0.391683 0.409587 0.425790 0.440553 0.448186 0.443843 0.427902 0.401216 0.363917 0.315877 0.257305 0.188389 0.109467 0.021145 -0.075662 -0.179678 -0.289215 -0.402371 -0.517492 -0.633155 -0.748106 -0.861259 -0.971696 -1.078673 -1.181626 -1.280179 -1.374141 -1.463512 -1.548474 -1.629388 -1.706786 -1.781347 -1.853884 -1.925308 -1.996461 -0.348976 0.373677 0.395430 0.414664 0.431984 0.444452 0.442628 0.426075 0.395932 0.352522 0.295876 0.226363 0.144361 0.050473 -0.054383 -0.168912 -0.291369 -0.419564 -0.551360 -0.684950 -0.818747 -0.951358 -1.081586 -1.208436 -1.331122 -1.449075 -1.561948 -1.669615 -1.772174 -1.869941 -1.963438 -2.053377 -2.140642 -2.226257 -2.311298 -2.396626 -0.322447 0.352671 0.378963 0.401764 0.421785 0.438064 0.438990 0.421654 0.387518 0.337104 0.270664 0.188770 0.092059 -0.018557 -0.141791 -0.275900 -0.418590 -0.567224 -0.719482 -0.873361 -1.027094 -1.179135 -1.328171 -1.473129 -1.613185 -1.747771 -1.876578 -1.999566 -2.116951 -2.229204 -2.337032 -2.441358 -2.543286 -2.644065 -2.744885 -2.846626 -0.292104 0.328674 0.360194 0.387092 0.410155 0.429464 0.433189 0.414787 0.376018 0.317600 0.240072 0.144265 0.031127 -0.098072 -0.241618 -0.397243 -0.562049 -0.733059 -0.907740 -1.083862 -1.259459 -1.432826 -1.602527 -1.767409 -1.926613 -2.079580 -2.226059 -2.366108 -2.500086 -2.628644 -2.752697 -2.873398 -2.992099 -3.110271 -3.229166 -3.349696 -0.257934 0.301688 0.339118 0.370637 0.397092 0.419035 0.425380 0.405542 0.361401 0.293886 0.203884 0.092545 -0.038828 -0.188556 -0.354435 -0.533590 -0.722527 -0.917988 -1.117178 -1.317621 -1.517135 -1.713843 -1.906181 -2.092918 -2.273163 -2.446378 -2.612385 -2.771358 -2.923825 -3.070638 -3.212946 -3.352157 -3.489890 -3.627813 -3.767210 -3.909048 -0.219932 0.271699 0.315725 0.352385 0.382573 0.407064 0.415649 0.393924 0.343586 0.265797 0.161855 0.033279 -0.118226 -0.290520 -0.480838 -0.685625 -0.900846 -1.122958 -1.348868 -1.575829 -1.801429 -2.023608 -2.240672 -2.451307 -2.654600 -2.850044 -3.037549 -3.217434 -3.390412 -3.557560 -3.720288 -3.880284 -4.039448 -4.199603 -4.362066 -4.527873 -0.178135 0.238694 0.290002 0.332317 0.366567 0.393662 0.404032 0.379897 0.322460 0.233142 0.113714 -0.033886 -0.207507 -0.404491 -0.621444 -0.854066 -1.097853 -1.348937 -1.603896 -1.859687 -2.113658 -2.363555 -2.607543 -2.844231 -3.072689 -3.292456 -3.503551 -3.706453 -3.902085 -4.091779 -4.277226 -4.460416 -4.643543 -4.828535 -5.016766 -5.209342 -0.132703 0.202667 0.261930 0.310408 0.349034 0.378811 0.390525 0.363396 0.297884 0.195706 0.059174 -0.109316 -0.307124 -0.531014 -0.776881 -1.039657 -1.314414 -1.596907 -1.883356 -2.170409 -2.455151 -2.735120 -3.008340 -3.273345 -3.529196 -3.775497 -4.012387 -4.240529 -4.461083 -4.675657 -4.886250 -5.095180 -5.304925 -5.517492 -5.734327 -5.956614 -0.084224 0.163639 0.231485 0.286625 0.329931 0.362460 0.375097 0.344332 0.269698 0.153266 -0.002060 -0.193389 -0.417541 -0.670640 -0.947787 -1.243159 -1.551402 -1.867855 -2.188355 -2.509214 -2.827235 -3.139741 -3.444611 -3.740306 -4.025892 -4.301046 -4.566051 -4.821776 -5.069639 -5.311551 -5.549845 -5.787192 -6.026332 -6.269342 -6.517755 -6.772836 -0.034952 0.121693 0.198644 0.260932 0.309208 0.344544 0.357698 0.322599 0.237730 0.105587 -0.070294 -0.286489 -0.539230 -0.823928 -1.134814 -1.465339 -1.809699 -2.162779 -2.520003 -2.877323 -3.231243 -3.578859 -3.917904 -4.246774 -4.564545 -4.870985 -5.166539 -5.452304 -5.729981 -6.001811 -6.270488 -6.539057 -6.810494 -7.086946 -7.370046 -7.661142 --0.011115 0.077127 0.163389 0.233290 0.286813 0.324991 0.338262 0.298075 0.201799 0.052429 -0.145838 -0.389008 -0.672666 -0.991441 -1.338622 -1.706972 -2.090192 -2.482680 -2.879417 -3.275962 -3.668506 -4.053914 -4.429770 -4.794407 -5.146925 -5.487194 -5.815843 -6.134218 -6.444332 -6.748781 -7.050649 -7.353371 -7.660131 -7.973156 -8.294185 -8.624661 --0.050911 0.031047 0.125717 0.203658 0.262692 0.303728 0.316707 0.270625 0.161721 -0.006451 -0.229008 -0.501339 -0.818328 -1.173745 -1.559880 -1.968838 -2.393776 -2.828568 -3.267710 -3.706353 -4.140357 -4.566348 -4.981760 -5.384866 -5.774799 -6.151551 -6.515951 -6.869621 -7.214911 -7.554801 -7.892791 -8.232723 -8.577956 -8.930816 -9.293154 -9.666511 --0.083826 -0.014210 0.085661 0.171992 0.236785 0.280676 0.292937 0.240111 0.117308 -0.071300 -0.320120 -0.623879 -0.976697 -1.371406 -1.799263 -2.251722 -2.721350 -3.201448 -3.685999 -4.169721 -4.648130 -5.117604 -5.575423 -6.019808 -6.449935 -6.865932 -7.268850 -7.660612 -8.043932 -8.422205 -8.799374 -9.179693 -9.566677 -9.962766 -10.369925 -10.789805 --0.112321 -0.056414 0.043373 0.138247 0.209032 0.255752 0.266847 0.206391 0.068370 -0.142368 -0.419492 -0.757024 -1.148255 -1.584993 -2.057449 -2.556414 -3.073813 -3.602329 -4.135402 -4.667292 -5.193160 -5.709124 -6.212312 -6.700894 -7.174100 -7.632211 -8.076523 -8.509287 -8.933609 -9.353325 -9.772854 -10.196858 -10.628998 -11.071839 -11.527466 -11.997652 --0.138289 -0.094091 -0.000597 0.102378 0.179367 0.228869 0.238326 0.169319 0.014717 -0.219903 -0.527445 -0.901172 -1.333484 -1.815079 -2.335120 -2.883708 -3.452066 -4.032220 -4.617034 -5.200293 -5.776782 -6.342352 -6.893976 -7.429778 -7.949056 -8.452259 -8.940954 -9.417741 -9.886149 -10.350489 -10.815681 -11.286791 -11.767617 -12.260864 -12.768741 -13.293158 +0.001293 0.001766 0.002244 0.002727 0.003215 0.003707 0.004204 0.004705 0.005209 0.005718 0.006229 0.006745 0.007263 0.007783 0.008307 0.008833 0.009360 0.009890 0.010421 0.010953 0.011486 0.012020 0.012553 0.013087 0.013619 0.014151 0.014680 0.015208 0.015733 0.016254 0.016772 0.017285 0.017793 0.018295 0.018792 0.019281 +0.010080 0.011521 0.012968 0.014422 0.015879 0.017341 0.018804 0.020268 0.021732 0.023193 0.024651 0.026103 0.027549 0.028986 0.030413 0.031827 0.033226 0.034608 0.035970 0.037308 0.038619 0.039898 0.041140 0.042339 0.043489 0.044583 0.045614 0.046574 0.047455 0.048249 0.048948 0.049542 0.050025 0.050386 0.050617 0.050710 +0.033747 0.036725 0.039681 0.042612 0.045513 0.048378 0.051202 0.053978 0.056699 0.059357 0.061941 0.064441 0.066847 0.069144 0.071321 0.073365 0.075261 0.076995 0.078554 0.079924 0.081092 0.082044 0.082768 0.083253 0.083489 0.083464 0.083169 0.082596 0.081734 0.080577 0.079117 0.077350 0.075270 0.072875 0.070163 0.067131 +0.074806 0.079567 0.084197 0.088679 0.092992 0.097117 0.101031 0.104714 0.108141 0.111292 0.114143 0.116674 0.118862 0.120689 0.122137 0.123189 0.123832 0.124052 0.123837 0.123176 0.122059 0.120475 0.118418 0.115881 0.112858 0.109345 0.105340 0.100841 0.095846 0.090358 0.084377 0.077911 0.070973 0.063588 0.055795 0.047652 +0.130596 0.136723 0.142455 0.147758 0.152602 0.156956 0.160792 0.164086 0.166811 0.168939 0.170449 0.171323 0.171548 0.171110 0.169999 0.168204 0.165716 0.162529 0.158637 0.154034 0.148718 0.142687 0.135939 0.128475 0.120294 0.111398 0.101794 0.091497 0.080541 0.068981 0.056903 0.044420 0.031661 0.018763 0.005858 -0.006939 +0.195014 0.201486 0.207193 0.212103 0.216188 0.219425 0.221786 0.223251 0.223815 0.223480 0.222213 0.219996 0.216821 0.212683 0.207576 0.201494 0.194434 0.186394 0.177370 0.167360 0.156361 0.144372 0.131393 0.117431 0.102515 0.086701 0.070090 0.052827 0.035091 0.017084 -0.000992 -0.018960 -0.036661 -0.053960 -0.070741 -0.086905 +0.261074 0.266757 0.271275 0.274620 0.276791 0.277800 0.277654 0.276321 0.273768 0.270009 0.265027 0.258777 0.251251 0.242441 0.232340 0.220939 0.208230 0.194203 0.178849 0.162158 0.144125 0.124766 0.104135 0.082341 0.059555 0.036011 0.011986 -0.012231 -0.036378 -0.060227 -0.083581 -0.106271 -0.128157 -0.149125 -0.169090 -0.187994 +0.321644 0.325896 0.328675 0.329966 0.329773 0.328104 0.324984 0.320445 0.314402 0.306810 0.297654 0.286849 0.274377 0.260217 0.244348 0.226748 0.207393 0.186261 0.163334 0.138623 0.112191 0.084178 0.054810 0.024399 -0.006678 -0.038028 -0.069300 -0.100190 -0.130438 -0.159821 -0.188151 -0.215282 -0.241102 -0.265541 -0.288563 -0.310175 +0.370783 0.373798 0.375127 0.374735 0.372574 0.368582 0.362755 0.355123 0.345655 0.334186 0.320665 0.304971 0.287066 0.266912 0.244470 0.219699 0.192566 0.163052 0.131199 0.097141 0.061119 0.023489 -0.015282 -0.054676 -0.094203 -0.133445 -0.172042 -0.209681 -0.246102 -0.281093 -0.314491 -0.346185 -0.376113 -0.404267 -0.430686 -0.455462 +0.403941 0.407195 0.408433 0.407594 0.404573 0.399229 0.391438 0.381213 0.368587 0.353316 0.335276 0.314324 0.290411 0.263485 0.233494 0.200391 0.164166 0.124896 0.082788 0.038186 -0.008419 -0.056401 -0.105088 -0.153881 -0.202269 -0.249810 -0.296124 -0.340894 -0.383868 -0.424857 -0.463738 -0.500453 -0.535014 -0.567496 -0.598038 -0.626838 +0.417840 0.424161 0.427894 0.428700 0.426448 0.421041 0.412258 0.400058 0.384561 0.365500 0.342676 0.315953 0.285283 0.250614 0.211895 0.169120 0.122396 0.071993 0.018347 -0.037917 -0.096003 -0.155066 -0.214361 -0.273251 -0.331184 -0.387686 -0.442364 -0.494900 -0.545062 -0.592700 -0.637750 -0.680232 -0.720249 -0.757984 -0.793695 -0.827709 +0.414764 0.425361 0.433875 0.438929 0.439478 0.435400 0.426610 0.413000 0.394820 0.371836 0.343795 0.310606 0.272240 0.228657 0.179857 0.125963 0.067288 0.004350 -0.062111 -0.131131 -0.201652 -0.272736 -0.343582 -0.413495 -0.481873 -0.548213 -0.612108 -0.673258 -0.731463 -0.786631 -0.838775 -0.888013 -0.934564 -0.978737 -1.020925 -1.061593 +0.403947 0.417135 0.429387 0.439695 0.445031 0.443699 0.435766 0.421176 0.400352 0.373137 0.339272 0.298737 0.251542 0.197702 0.137346 0.070813 -0.001326 -0.078238 -0.158811 -0.241749 -0.325858 -0.410126 -0.493668 -0.575716 -0.655621 -0.732854 -0.807009 -0.877809 -0.945106 -1.008884 -1.069253 -1.126449 -1.180820 -1.232819 -1.282996 -1.331968 +0.388968 0.405195 0.419998 0.433694 0.444420 0.447133 0.440754 0.425460 0.401868 0.369945 0.329473 0.280538 0.223218 0.157650 0.084176 0.003401 -0.083784 -0.176160 -0.272203 -0.370397 -0.469450 -0.568240 -0.665785 -0.761245 -0.853923 -0.943271 -1.028893 -1.110550 -1.188163 -1.261805 -1.331703 -1.398226 -1.461877 -1.523280 -1.583156 -1.642254 +0.370102 0.390185 0.408148 0.424398 0.439066 0.446632 0.442359 0.426476 0.399835 0.362567 0.314555 0.256014 0.187141 0.108277 0.020032 -0.076674 -0.180561 -0.289947 -0.402956 -0.517930 -0.633444 -0.748248 -0.861257 -0.971557 -1.078404 -1.181239 -1.279687 -1.373559 -1.462858 -1.547765 -1.628646 -1.706029 -1.780596 -1.853157 -1.924617 -1.995805 +0.347394 0.372165 0.393978 0.413259 0.430608 0.442916 0.441147 0.424638 0.394531 0.351144 0.294523 0.225042 0.143088 0.049265 -0.055503 -0.169917 -0.292226 -0.420265 -0.551906 -0.685338 -0.818977 -0.951431 -1.081507 -1.208212 -1.330762 -1.448593 -1.561358 -1.668935 -1.771423 -1.869140 -1.962609 -2.052542 -2.139822 -2.225471 -2.310550 -2.395921 +0.320860 0.351155 0.377507 0.400355 0.420406 0.436562 0.437510 0.420206 0.386096 0.335697 0.269278 0.187418 0.090759 -0.019784 -0.142919 -0.276896 -0.419423 -0.567896 -0.719989 -0.873701 -1.027264 -1.179139 -1.328013 -1.472819 -1.612733 -1.747191 -1.875889 -1.998786 -2.116103 -2.228311 -2.336117 -2.440444 -2.542396 -2.643215 -2.744078 -2.845867 +0.290524 0.327163 0.358742 0.385685 0.408776 0.428012 0.431711 0.413328 0.374572 0.316162 0.238653 0.142881 0.029799 -0.099318 -0.242752 -0.398227 -0.562865 -0.733704 -0.908209 -1.084152 -1.259569 -1.432758 -1.602288 -1.767009 -1.926065 -2.078900 -2.225268 -2.365227 -2.499139 -2.627655 -2.751693 -2.872404 -2.991138 -3.109355 -3.228298 -3.348883 +0.256375 0.300189 0.337676 0.369238 0.395716 0.417633 0.423904 0.404070 0.359929 0.292415 0.202430 0.091128 -0.040184 -0.189821 -0.355575 -0.534564 -0.723326 -0.918606 -1.117608 -1.317860 -1.517182 -1.713701 -1.905858 -2.092426 -2.272517 -2.445597 -2.611489 -2.770373 -2.922776 -3.069553 -3.211852 -3.351081 -3.488855 -3.626826 -3.766278 -3.908179 +0.218419 0.270222 0.314299 0.350998 0.381204 0.405683 0.414176 0.392438 0.342087 0.264292 0.160364 0.031827 -0.119611 -0.291805 -0.481983 -0.686592 -0.901629 -1.123548 -1.349258 -1.576015 -1.801411 -2.023390 -2.240263 -2.450721 -2.653853 -2.849157 -3.036546 -3.216342 -3.389258 -3.556375 -3.719101 -3.879123 -4.038336 -4.198543 -4.361068 -4.526945 +0.176728 0.237251 0.288598 0.330945 0.365207 0.392286 0.402559 0.378396 0.320931 0.231599 0.112184 -0.035374 -0.208922 -0.405796 -0.622593 -0.855028 -1.098621 -1.349500 -1.604245 -1.859819 -2.113573 -2.363259 -2.607045 -2.843547 -3.071838 -3.291461 -3.502438 -3.705251 -3.900825 -4.090492 -4.275944 -4.459168 -4.642349 -4.827400 -5.015699 -5.208354 +0.131609 0.201278 0.260552 0.309054 0.347686 0.377439 0.389052 0.361877 0.296321 0.194125 0.057605 -0.110842 -0.308570 -0.532338 -0.778033 -1.040616 -1.315166 -1.597441 -1.883663 -2.170485 -2.454996 -2.734742 -3.007751 -3.272561 -3.528238 -3.774390 -4.011160 -4.239214 -4.459713 -4.674265 -4.884870 -5.093843 -5.303645 -5.516278 -5.733190 -5.955563 +0.084326 0.162348 0.230142 0.285293 0.328596 0.361092 0.373624 0.342792 0.268100 0.151644 -0.003672 -0.194953 -0.419018 -0.671983 -0.948945 -1.244114 -1.552139 -1.868359 -2.188617 -2.509231 -2.827009 -3.139280 -3.443927 -3.739418 -4.024823 -4.299825 -4.564708 -4.820345 -5.068156 -5.310052 -5.548365 -5.785762 -6.024964 -6.268047 -6.516544 -6.771720 +0.037494 0.120635 0.197345 0.259625 0.307888 0.343181 0.356222 0.321035 0.236094 0.103922 -0.071949 -0.288093 -0.540739 -0.825291 -1.135979 -1.466291 -1.810419 -2.163251 -2.520220 -2.877280 -3.230942 -3.578311 -3.917123 -4.245779 -4.563363 -4.869645 -5.165076 -5.450754 -5.728382 -6.000201 -6.268904 -6.537530 -6.809035 -7.085567 -7.368759 -7.659959 +-0.007006 0.076838 0.162151 0.232011 0.285509 0.323633 0.336779 0.296483 0.200124 0.050720 -0.147537 -0.390653 -0.674207 -0.992823 -1.339796 -1.707920 -2.090894 -2.483121 -2.879585 -3.275855 -3.668129 -4.053276 -4.428888 -4.793302 -5.145625 -5.485733 -5.814256 -6.132545 -6.442613 -6.747057 -7.048957 -7.351743 -7.658577 -7.971690 -8.292820 -8.623409 +-0.047191 0.032491 0.124573 0.202410 0.261405 0.302374 0.315213 0.269005 0.160005 -0.008205 -0.230753 -0.503025 -0.819901 -1.175145 -1.561063 -1.969782 -2.394460 -2.828974 -3.267829 -3.706182 -4.139901 -4.565617 -4.980773 -5.383647 -5.773379 -6.149965 -6.514237 -6.867822 -7.213069 -7.552959 -7.890989 -8.230991 -8.576304 -8.929260 -9.291707 -9.665187 +-0.081402 -0.011084 0.084719 0.170780 0.235516 0.279325 0.291430 0.238459 0.115549 -0.073102 -0.321911 -0.625607 -0.978304 -1.372825 -1.800455 -2.252662 -2.722014 -3.201819 -3.686067 -4.169483 -4.647592 -5.116778 -5.574329 -6.018473 -6.448391 -6.864217 -7.267005 -7.658683 -8.041964 -8.420242 -8.797460 -9.177853 -9.564925 -9.961118 -10.368394 -10.788407 +-0.110596 -0.052701 0.042985 0.137076 0.207782 0.254403 0.265323 0.204705 0.066567 -0.144218 -0.421331 -0.758794 -1.149895 -1.586432 -2.058651 -2.557350 -3.074456 -3.602663 -4.135416 -4.666984 -5.192537 -5.708199 -6.211107 -6.699437 -7.172428 -7.630363 -8.074545 -8.507225 -8.931510 -9.351238 -9.770823 -10.194907 -10.627142 -11.070095 -11.525849 -11.996178 +-0.136894 -0.091028 0.000152 0.101257 0.178137 0.227520 0.236784 0.167598 0.012868 -0.221802 -0.529332 -0.902987 -1.335157 -1.816539 -2.336332 -2.884638 -3.452688 -4.032515 -4.616992 -5.199912 -5.776070 -6.341325 -6.892656 -7.428198 -7.947252 -8.450276 -8.938837 -9.415541 -9.883917 -10.348275 -10.813529 -11.284725 -11.765654 -12.259021 -12.767035 -13.291606 # Thrust coefficient -0.173936 0.174545 0.175105 0.175604 0.176027 0.176357 0.176576 0.176665 0.176604 0.176373 0.175951 0.175317 0.174451 0.173333 0.171944 0.170267 0.168285 0.165982 0.163343 0.160355 0.157004 0.153277 0.149165 0.144659 0.139751 0.134439 0.128718 0.122589 0.116054 0.109113 0.101773 0.094042 0.085936 0.077488 0.068744 0.059773 -0.244110 0.244807 0.245270 0.245468 0.245368 0.244940 0.244155 0.242988 0.241410 0.239388 0.236896 0.233914 0.230421 0.226400 0.221834 0.216710 0.211014 0.204738 0.197875 0.190421 0.182376 0.173742 0.164522 0.154724 0.144354 0.133423 0.121945 0.109944 0.097467 0.084590 0.071416 0.058076 0.044718 0.031490 0.018521 0.005920 -0.329058 0.328652 0.327699 0.326163 0.324010 0.321203 0.317708 0.313503 0.308574 0.302916 0.296490 0.289274 0.281258 0.272437 0.262806 0.252366 0.241123 0.229082 0.216256 0.202654 0.188292 0.173184 0.157347 0.140807 0.123614 0.105857 0.087669 0.069222 0.050725 0.032400 0.014449 -0.002964 -0.019698 -0.035638 -0.050689 -0.064777 -0.423724 0.420631 0.416601 0.411609 0.405640 0.398694 0.390781 0.381862 0.371916 0.360960 0.348987 0.335961 0.321889 0.306782 0.290656 0.273525 0.255410 0.236329 0.216303 0.195352 0.173503 0.150806 0.127362 0.103332 0.078936 0.054443 0.030163 0.006389 -0.016641 -0.038731 -0.059724 -0.079492 -0.097938 -0.114987 -0.130589 -0.144718 -0.522708 0.515320 0.506632 0.496639 0.485349 0.472781 0.458970 0.443976 0.427746 0.410278 0.391592 0.371635 0.350431 0.328001 0.304369 0.279560 0.253599 0.226508 0.198319 0.169094 0.138969 0.108161 0.076963 0.045733 0.014882 -0.015203 -0.044217 -0.071919 -0.098118 -0.122660 -0.145431 -0.166347 -0.185356 -0.202436 -0.217593 -0.230865 -0.620986 0.607920 0.593333 0.577234 0.559606 0.540466 0.519860 0.497874 0.474551 0.449800 0.423636 0.395993 0.366897 0.336377 0.304459 0.271170 0.236538 0.200616 0.163534 0.125537 0.086962 0.048236 0.009863 -0.027633 -0.063829 -0.098403 -0.131103 -0.161729 -0.190133 -0.216204 -0.239873 -0.261109 -0.279917 -0.296336 -0.310444 -0.322349 -0.714037 0.694660 0.673585 0.650833 0.626441 0.600346 0.572544 0.543137 0.512256 0.479758 0.445598 0.409704 0.372107 0.332841 0.291934 0.249425 0.205397 0.160063 0.113768 0.066972 0.020233 -0.025799 -0.070499 -0.113396 -0.154133 -0.192434 -0.228087 -0.260935 -0.290868 -0.317827 -0.341795 -0.362800 -0.380914 -0.396253 -0.408976 -0.419282 -0.797619 0.772416 0.745286 0.716196 0.685139 0.652162 0.617157 0.580209 0.541535 0.500976 0.458403 0.413758 0.367089 0.318440 0.267859 0.215464 0.161536 0.106521 0.050989 -0.004371 -0.058762 -0.111433 -0.161837 -0.209563 -0.254300 -0.295806 -0.333907 -0.368486 -0.399482 -0.426887 -0.450748 -0.471165 -0.488287 -0.502317 -0.513506 -0.522151 -0.870407 0.839307 0.807149 0.772800 0.735851 0.696368 0.654402 0.609945 0.563343 0.514447 0.463055 0.409157 0.352830 0.294145 0.233245 0.170467 0.106342 0.041549 -0.023101 -0.086663 -0.148218 -0.207098 -0.262819 -0.315010 -0.363387 -0.407744 -0.447945 -0.483917 -0.515653 -0.543208 -0.566698 -0.586303 -0.602262 -0.614871 -0.624481 -0.631491 -0.937801 0.898777 0.859871 0.820832 0.779117 0.733820 0.685207 0.633320 0.578660 0.521127 0.460477 0.396782 0.330166 0.260796 0.189045 0.115524 0.041008 -0.033579 -0.107154 -0.178587 -0.247028 -0.311881 -0.372693 -0.429119 -0.480906 -0.527879 -0.569945 -0.607081 -0.639338 -0.666842 -0.689787 -0.708441 -0.723135 -0.734268 -0.742302 -0.747750 -1.002272 0.954818 0.907800 0.861790 0.815766 0.765455 0.710516 0.651256 0.588370 0.521837 0.451428 0.377331 0.299768 0.219135 0.136104 0.051544 -0.033517 -0.117878 -0.200191 -0.279333 -0.354544 -0.425257 -0.491041 -0.551574 -0.606630 -0.656072 -0.699848 -0.737992 -0.770621 -0.797933 -0.820208 -0.837806 -0.851169 -0.860810 -0.867314 -0.871279 -1.064598 1.008390 0.952917 0.898894 0.846816 0.792132 0.731177 0.664544 0.593190 0.517221 0.436491 0.351342 0.262208 0.169811 0.075110 -0.020766 -0.116510 -0.210609 -0.301585 -0.388416 -0.470381 -0.546930 -0.617647 -0.682232 -0.740484 -0.792304 -0.837690 -0.876733 -0.909619 -0.936626 -0.958130 -0.974602 -0.986598 -0.994763 -0.999805 -1.002335 -1.125286 1.060007 0.995803 0.933481 0.873901 0.814638 0.747903 0.673814 0.593683 0.507777 0.416109 0.319252 0.217981 0.113352 0.006598 -0.100867 -0.207420 -0.311262 -0.410956 -0.505547 -0.594326 -0.676752 -0.752421 -0.821050 -0.882469 -0.936617 -0.983541 -1.023394 -1.056440 -1.083052 -1.103712 -1.119007 -1.129628 -1.136358 -1.139998 -1.141107 -1.184710 1.110050 1.036840 0.965984 0.898504 0.833644 0.761274 0.679565 0.590284 0.493877 0.390619 0.281434 0.167495 0.050167 -0.069022 -0.188346 -0.305833 -0.419523 -0.528075 -0.630559 -0.726266 -0.814657 -0.895336 -0.968037 -1.032619 -1.089062 -1.137468 -1.178060 -1.211191 -1.237335 -1.257092 -1.271183 -1.280440 -1.285786 -1.288054 -1.287742 -1.243183 1.158809 1.076317 0.996699 0.921110 0.849734 0.771746 0.682183 0.583321 0.475803 0.360302 0.238207 0.111071 -0.019424 -0.151434 -0.282888 -0.411466 -0.535198 -0.652809 -0.763367 -0.866154 -0.960628 -1.046399 -1.123218 -1.190975 -1.249694 -1.299539 -1.340814 -1.373965 -1.399583 -1.418398 -1.431272 -1.439187 -1.443198 -1.444104 -1.442358 -1.300910 1.206519 1.114465 1.025858 0.941977 0.863452 0.779673 0.681967 0.573037 0.453771 0.325405 0.189827 0.048963 -0.095175 -0.240399 -0.384254 -0.524144 -0.658173 -0.785084 -0.903927 -1.013972 -1.114667 -1.205628 -1.286626 -1.357580 -1.418567 -1.469819 -1.511728 -1.544850 -1.569899 -1.587742 -1.599395 -1.606003 -1.608709 -1.608248 -1.605042 -1.358030 1.253357 1.151469 1.053649 0.961301 0.875262 0.785334 0.679149 0.559618 0.427966 0.286133 0.136500 -0.018634 -0.176899 -0.335733 -0.492272 -0.643762 -0.788382 -0.924861 -1.052225 -1.169720 -1.276789 -1.373051 -1.458293 -1.532476 -1.595730 -1.648366 -1.690874 -1.723926 -1.748368 -1.765221 -1.775661 -1.780996 -1.782408 -1.780566 -1.775864 -1.414606 1.299461 1.187483 1.080229 0.979241 0.885469 0.788952 0.673911 0.543212 0.398553 0.242657 0.078384 -0.091569 -0.264451 -0.437297 -0.606831 -0.770255 -0.925787 -1.072124 -1.208256 -1.333409 -1.447015 -1.548693 -1.638256 -1.715703 -1.781230 -1.835235 -1.878313 -1.911261 -1.935071 -1.950921 -1.960159 -1.964252 -1.964367 -1.961118 -1.954875 -1.470532 1.344931 1.222636 1.105728 0.995928 0.894246 0.790705 0.666394 0.523941 0.365671 0.195109 0.015606 -0.169725 -0.357724 -0.544986 -0.727861 -0.903585 -1.070368 -1.226864 -1.372026 -1.505055 -1.625365 -1.732582 -1.826543 -1.907297 -1.975112 -2.030478 -2.074103 -2.106920 -2.130075 -2.144914 -2.152966 -2.155836 -2.154640 -2.149953 -2.142116 -1.525176 1.389818 1.257032 1.130259 1.011475 0.901713 0.790737 0.656712 0.501917 0.329434 0.143594 -0.051741 -0.253016 -0.456636 -0.658718 -0.855321 -1.043728 -1.222114 -1.389084 -1.543550 -1.684675 -1.811862 -1.924743 -2.023186 -2.107295 -2.177416 -2.234138 -2.278294 -2.310959 -2.333441 -2.347264 -2.354147 -2.355801 -2.353275 -2.347110 -2.337621 -1.576091 1.434083 1.290759 1.153917 1.025975 0.907968 0.789164 0.644957 0.477240 0.289934 0.088194 -0.123583 -0.341376 -0.561121 -0.778437 -0.989180 -1.190668 -1.381024 -1.558795 -1.722840 -1.872286 -2.006525 -2.125198 -2.228212 -2.315729 -2.388179 -2.446258 -2.490931 -2.523425 -2.545218 -2.558024 -2.563754 -2.564189 -2.560306 -2.552619 -2.541411 -1.619386 1.477421 1.323881 1.176784 1.039511 0.913087 0.786080 0.631211 0.449991 0.247242 0.028971 -0.199866 -0.434753 -0.671127 -0.904104 -1.129421 -1.344401 -1.547104 -1.736007 -1.909909 -2.067905 -2.209372 -2.333972 -2.441648 -2.532629 -2.607434 -2.666876 -2.712055 -2.744361 -2.765452 -2.777239 -2.781831 -2.781036 -2.775765 -2.766503 -2.753507 -1.652707 1.518703 1.356434 1.198932 1.052154 0.917137 0.781560 0.615550 0.420232 0.201412 -0.034029 -0.280547 -0.533104 -0.786614 -1.035692 -1.276032 -1.504928 -1.720362 -1.920730 -2.104772 -2.271546 -2.420424 -2.551086 -2.663519 -2.758022 -2.835212 -2.896022 -2.941699 -2.973802 -2.994180 -3.004949 -3.008412 -3.006369 -2.999674 -2.988782 -2.973920 -1.676548 1.555748 1.388396 1.220422 1.063964 0.920174 0.775668 0.598036 0.388014 0.152485 -0.100769 -0.365591 -0.636398 -0.907545 -1.173186 -1.429010 -1.672256 -1.900808 -2.112976 -2.307439 -2.483223 -2.639696 -2.776559 -2.893846 -2.991934 -3.071540 -3.133725 -3.179893 -3.211780 -3.231435 -3.241187 -3.243526 -3.240212 -3.232052 -3.219469 -3.202660 -1.694200 1.586793 1.419603 1.241302 1.074992 0.922243 0.768461 0.578719 0.353374 0.100493 -0.171219 -0.454970 -0.744605 -1.033891 -1.316576 -1.588357 -1.846391 -2.088450 -2.312754 -2.517922 -2.702952 -2.867206 -3.010409 -3.132651 -3.234386 -3.316440 -3.380010 -3.426664 -3.458323 -3.477245 -3.485985 -3.487195 -3.482585 -3.472915 -3.458574 -3.439733 -1.707980 1.611070 1.449551 1.261610 1.085283 0.923387 0.759987 0.557635 0.316341 0.045462 -0.245357 -0.548663 -0.857703 -1.165632 -1.465857 -1.754078 -2.027339 -2.283295 -2.520073 -2.736234 -2.930745 -3.102968 -3.252655 -3.379952 -3.485399 -3.569934 -3.634900 -3.682034 -3.713454 -3.731636 -3.739365 -3.739440 -3.733504 -3.722276 -3.706107 -3.685146 +0.076030 0.075632 0.075204 0.074745 0.074258 0.073742 0.073199 0.072630 0.072035 0.071414 0.070769 0.070101 0.069409 0.068695 0.067959 0.067203 0.066426 0.065630 0.064816 0.063984 0.063135 0.062271 0.061393 0.060502 0.059601 0.058690 0.057773 0.056853 0.055931 0.055010 0.054093 0.053181 0.052279 0.051387 0.050509 0.049646 +0.090630 0.090326 0.090001 0.089655 0.089288 0.088903 0.088499 0.088079 0.087643 0.087193 0.086730 0.086256 0.085772 0.085280 0.084780 0.084276 0.083767 0.083255 0.082742 0.082227 0.081710 0.081189 0.080664 0.080130 0.079585 0.079025 0.078445 0.077840 0.077203 0.076528 0.075810 0.075040 0.074211 0.073315 0.072343 0.071286 +0.122479 0.122548 0.122604 0.122648 0.122680 0.122699 0.122705 0.122697 0.122670 0.122622 0.122547 0.122437 0.122286 0.122085 0.121824 0.121492 0.121078 0.120570 0.119957 0.119226 0.118366 0.117364 0.116207 0.114886 0.113387 0.111700 0.109814 0.107717 0.105398 0.102849 0.100060 0.097023 0.093734 0.090188 0.086381 0.082312 +0.173874 0.174473 0.175022 0.175507 0.175914 0.176227 0.176428 0.176498 0.176417 0.176164 0.175720 0.175063 0.174174 0.173033 0.171622 0.169923 0.167919 0.165595 0.162935 0.159926 0.156556 0.152811 0.148681 0.144158 0.139235 0.133909 0.128175 0.122035 0.115488 0.108538 0.101191 0.093458 0.085361 0.076931 0.068218 0.059289 +0.243966 0.244636 0.245071 0.245239 0.245109 0.244650 0.243835 0.242635 0.241024 0.238973 0.236452 0.233442 0.229922 0.225874 0.221283 0.216134 0.210415 0.204117 0.197234 0.189762 0.181700 0.173050 0.163816 0.154004 0.143623 0.132683 0.121201 0.109207 0.096752 0.083910 0.070786 0.057508 0.044215 0.031049 0.018140 0.005597 +0.328764 0.328316 0.327321 0.325740 0.323541 0.320694 0.317164 0.312925 0.307963 0.302273 0.295818 0.288574 0.280532 0.271686 0.262032 0.251572 0.240309 0.228252 0.215409 0.201793 0.187418 0.172298 0.156453 0.139915 0.122738 0.105014 0.086875 0.068495 0.050075 0.031826 0.013946 -0.003397 -0.020065 -0.035941 -0.050933 -0.064964 +0.423199 0.420058 0.415983 0.410948 0.404940 0.397958 0.390003 0.381053 0.371077 0.360095 0.348098 0.335050 0.320957 0.305832 0.289688 0.272542 0.254413 0.235319 0.215280 0.194319 0.172468 0.149783 0.126370 0.102389 0.078059 0.053652 0.029460 0.005768 -0.017182 -0.039196 -0.060116 -0.079815 -0.098194 -0.115182 -0.130727 -0.144805 +0.521908 0.514469 0.505743 0.495717 0.484398 0.471802 0.457967 0.442946 0.426697 0.409212 0.390511 0.370540 0.349322 0.326879 0.303236 0.278416 0.252444 0.225344 0.197153 0.167944 0.137853 0.107100 0.075975 0.044839 0.014086 -0.015908 -0.044835 -0.072453 -0.098571 -0.123037 -0.145734 -0.166582 -0.185527 -0.202549 -0.217655 -0.230881 +0.619868 0.606783 0.592169 0.576040 0.558402 0.539254 0.518641 0.496648 0.473317 0.448561 0.422391 0.394740 0.365637 0.335109 0.303183 0.269885 0.235248 0.199336 0.162286 0.124339 0.085835 0.047202 0.008937 -0.028458 -0.064559 -0.099041 -0.131652 -0.162194 -0.190516 -0.216509 -0.240107 -0.261276 -0.280023 -0.296389 -0.310451 -0.322320 +0.712539 0.693173 0.672113 0.649387 0.624997 0.598918 0.571132 0.541736 0.510862 0.478370 0.444211 0.408315 0.370715 0.331443 0.290531 0.248022 0.204014 0.158720 0.112486 0.065772 0.019138 -0.026780 -0.071376 -0.114172 -0.154812 -0.193019 -0.228582 -0.261343 -0.291195 -0.318076 -0.341973 -0.362914 -0.380971 -0.396263 -0.408948 -0.419224 +0.795785 0.770562 0.743502 0.714476 0.683482 0.650540 0.615576 0.578657 0.540005 0.499459 0.456893 0.412250 0.365580 0.316928 0.266350 0.213980 0.160098 0.105148 0.049703 -0.005546 -0.059817 -0.112379 -0.162677 -0.210302 -0.254939 -0.296350 -0.334358 -0.368849 -0.399763 -0.427092 -0.450883 -0.471239 -0.488309 -0.502296 -0.513454 -0.522078 +0.868704 0.837482 0.805121 0.770834 0.733982 0.694583 0.652674 0.608264 0.561694 0.512819 0.461437 0.407543 0.351216 0.292536 0.231661 0.168929 0.104870 0.040165 -0.024373 -0.087810 -0.149250 -0.208020 -0.263634 -0.315720 -0.363995 -0.408255 -0.448361 -0.484244 -0.515897 -0.543376 -0.566798 -0.586345 -0.602256 -0.614829 -0.624414 -0.631412 +0.935950 0.896909 0.857981 0.818713 0.777069 0.731887 0.683352 0.631527 0.576909 0.519400 0.458762 0.395071 0.328459 0.259112 0.187406 0.113948 0.039516 -0.034963 -0.108408 -0.179720 -0.248047 -0.312787 -0.373489 -0.429808 -0.481489 -0.528362 -0.570332 -0.607378 -0.639552 -0.666980 -0.689860 -0.708458 -0.723109 -0.734211 -0.742227 -0.747666 +1.000270 0.952810 0.905789 0.859770 0.813571 0.763385 0.708549 0.649365 0.586528 0.520020 0.449623 0.375531 0.297986 0.217393 0.134420 0.049938 -0.035023 -0.119255 -0.201439 -0.280462 -0.355555 -0.426153 -0.491823 -0.552245 -0.607194 -0.656532 -0.700211 -0.738263 -0.770808 -0.798046 -0.820257 -0.837804 -0.851127 -0.860743 -0.867235 -0.871188 +1.062453 1.006245 0.950778 0.896768 0.844609 0.789952 0.729115 0.662566 0.591267 0.515322 0.434603 0.349465 0.260365 0.168020 0.073388 -0.022397 -0.118024 -0.211985 -0.302836 -0.389546 -0.471391 -0.547821 -0.618421 -0.682891 -0.741032 -0.792746 -0.838032 -0.876982 -0.909784 -0.936717 -0.958160 -0.974583 -0.986545 -0.994690 -0.999720 -1.002235 +1.123001 1.057731 0.993542 0.931242 0.871686 0.812362 0.745759 0.671759 0.591686 0.505800 0.414143 0.317311 0.216085 0.111516 0.004842 -0.102519 -0.208938 -0.312647 -0.412215 -0.506681 -0.595337 -0.677640 -0.753189 -0.821699 -0.883004 -0.937043 -0.983864 -1.023624 -1.056586 -1.083126 -1.103725 -1.118975 -1.129566 -1.136280 -1.139905 -1.140997 +1.182290 1.107648 1.034462 0.963638 0.896198 0.831295 0.759054 0.677440 0.588217 0.491827 0.388586 0.279437 0.165549 0.048289 -0.070810 -0.190017 -0.307362 -0.420922 -0.529346 -0.631702 -0.727282 -0.815546 -0.896099 -0.968679 -1.033143 -1.089474 -1.137776 -1.178274 -1.211320 -1.237392 -1.257091 -1.271140 -1.280371 -1.285703 -1.287953 -1.287624 +1.240628 1.156284 1.073827 0.994252 0.918715 0.847339 0.769458 0.679994 0.581185 0.473684 0.358211 0.236157 0.109078 -0.021342 -0.153253 -0.284577 -0.413014 -0.536614 -0.654094 -0.764520 -0.867175 -0.961518 -1.047160 -1.123853 -1.191490 -1.250094 -1.299833 -1.341012 -1.374079 -1.399627 -1.418386 -1.431221 -1.439114 -1.443108 -1.443995 -1.442230 +1.298214 1.203873 1.111866 1.023314 0.939498 0.861024 0.777323 0.679718 0.570837 0.451591 0.323259 0.187727 0.046923 -0.097133 -0.242248 -0.385962 -0.525714 -0.659609 -0.786385 -0.905092 -1.015001 -1.115561 -1.206389 -1.287256 -1.358086 -1.418957 -1.470101 -1.511914 -1.544951 -1.569930 -1.587720 -1.599337 -1.605925 -1.608612 -1.608131 -1.604905 +1.355177 1.250592 1.148765 1.051012 0.958742 0.872784 0.782927 0.676845 0.557357 0.425732 0.283935 0.134349 -0.020720 -0.178897 -0.337611 -0.494004 -0.645357 -0.789840 -0.926180 -1.053404 -1.170758 -1.277687 -1.373812 -1.458921 -1.532976 -1.596111 -1.648637 -1.691047 -1.724015 -1.748389 -1.765190 -1.775597 -1.780913 -1.782304 -1.780440 -1.775716 +1.411534 1.296572 1.184677 1.077502 0.976605 0.882933 0.786493 0.671553 0.540894 0.396266 0.240406 0.076184 -0.093701 -0.266488 -0.439203 -0.608591 -0.771877 -0.927268 -1.073462 -1.209449 -1.334457 -1.447918 -1.549455 -1.638881 -1.716197 -1.781603 -1.835497 -1.878476 -1.911340 -1.935082 -1.950882 -1.960090 -1.964163 -1.964254 -1.960983 -1.954717 +1.466987 1.341905 1.219728 1.102916 0.993220 0.891652 0.788199 0.663986 0.521572 0.363332 0.192807 0.013355 -0.171903 -0.359799 -0.546921 -0.729653 -0.905235 -1.071873 -1.228222 -1.373235 -1.506114 -1.626275 -1.733347 -1.827167 -1.907787 -1.975478 -2.030731 -2.074256 -2.106989 -2.130078 -2.144869 -2.152893 -2.155741 -2.154520 -2.149809 -2.141949 +1.520131 1.386611 1.254024 1.127363 1.008698 0.899065 0.788187 0.654256 0.499500 0.327045 0.141241 -0.054041 -0.255239 -0.458749 -0.660685 -0.857144 -1.045406 -1.223644 -1.390463 -1.544774 -1.685745 -1.812779 -1.925510 -2.023809 -2.107782 -2.177776 -2.234383 -2.278438 -2.311019 -2.333435 -2.347213 -2.354069 -2.355699 -2.353147 -2.346957 -2.337443 +1.568337 1.430531 1.287646 1.150940 1.023132 0.905267 0.786572 0.642457 0.474775 0.287494 0.085789 -0.125933 -0.343644 -0.563272 -0.780439 -0.991037 -1.192377 -1.382580 -1.560194 -1.724081 -1.873369 -2.007450 -2.125970 -2.228835 -2.316213 -2.388534 -2.446496 -2.491068 -2.523478 -2.545206 -2.557967 -2.563672 -2.564080 -2.560171 -2.552457 -2.541223 +1.610109 1.472947 1.320651 1.173728 1.036604 0.910337 0.783447 0.628671 0.447477 0.244751 0.026515 -0.202266 -0.437066 -0.673316 -0.906142 -1.131311 -1.346140 -1.548686 -1.737428 -1.911167 -2.069000 -2.210306 -2.334748 -2.442272 -2.533110 -2.607784 -2.667107 -2.712184 -2.744406 -2.765433 -2.777177 -2.781743 -2.780919 -2.775621 -2.766332 -2.753308 +1.644035 1.512411 1.353049 1.195798 1.049186 0.914340 0.778889 0.612971 0.417670 0.198869 -0.036537 -0.282996 -0.535463 -0.788840 -1.037768 -1.277958 -1.506699 -1.721971 -1.922174 -2.106047 -2.272654 -2.421366 -2.551866 -2.664144 -2.758502 -2.835558 -2.896247 -2.941821 -2.973840 -2.994154 -3.004882 -3.008319 -3.006245 -2.999522 -2.988601 -2.973711 +1.669291 1.547849 1.384739 1.217210 1.060936 0.917330 0.772961 0.595418 0.385404 0.149891 -0.103328 -0.368089 -0.638801 -0.909809 -1.175300 -1.430972 -1.674058 -1.902444 -2.114442 -2.308732 -2.484344 -2.640648 -2.777344 -2.894473 -2.992413 -3.071882 -3.133945 -3.180009 -3.211811 -3.231403 -3.241117 -3.243426 -3.240082 -3.231892 -3.219278 -3.202440 +1.687687 1.578468 1.415356 1.238011 1.071907 0.919357 0.765720 0.576060 0.350715 0.097847 -0.173830 -0.457519 -0.747054 -1.036194 -1.318729 -1.590355 -1.848224 -2.090113 -2.314243 -2.519235 -2.704087 -2.868167 -3.011201 -3.133281 -3.234864 -3.316779 -3.380226 -3.426774 -3.458348 -3.477208 -3.485910 -3.487089 -3.482447 -3.472747 -3.458375 -3.439503 +1.701820 1.603482 1.444239 1.258233 1.082143 0.920461 0.757212 0.554935 0.313634 0.042765 -0.248020 -0.551261 -0.860196 -1.167977 -1.468050 -1.756112 -2.029205 -2.284986 -2.521586 -2.737565 -2.931895 -3.103939 -3.253453 -3.380585 -3.485876 -3.570270 -3.635111 -3.682138 -3.713474 -3.731594 -3.739286 -3.739329 -3.733359 -3.722099 -3.705898 -3.684905 # Torque coefficient -0.037472 0.039863 0.042189 0.044441 0.046608 0.048682 0.050650 0.052503 0.054227 0.055813 0.057249 0.058524 0.059627 0.060548 0.061279 0.061812 0.062139 0.062254 0.062150 0.061823 0.061266 0.060477 0.059449 0.058181 0.056670 0.054913 0.052909 0.050657 0.048158 0.045411 0.042417 0.039178 0.035699 0.031992 0.028077 0.023982 -0.052381 0.054844 0.057148 0.059281 0.061230 0.062981 0.064525 0.065851 0.066949 0.067807 0.068416 0.068770 0.068863 0.068690 0.068248 0.067531 0.066537 0.065262 0.063704 0.061862 0.059734 0.057319 0.054617 0.051628 0.048352 0.044790 0.040942 0.036815 0.032418 0.027777 0.022923 0.017903 0.012773 0.007588 0.002402 -0.002739 -0.065213 0.067380 0.069292 0.070938 0.072309 0.073394 0.074184 0.074675 0.074865 0.074754 0.074332 0.073592 0.072533 0.071152 0.069448 0.067418 0.065062 0.062378 0.059366 0.056026 0.052356 0.048355 0.044023 0.039362 0.034379 0.029092 0.023536 0.017757 0.011818 0.005790 -0.000260 -0.006271 -0.012193 -0.017979 -0.023591 -0.028995 -0.074866 0.076494 0.077787 0.078743 0.079363 0.079649 0.079608 0.079225 0.078492 0.077414 0.075987 0.074198 0.072043 0.069521 0.066631 0.063369 0.059733 0.055720 0.051328 0.046554 0.041395 0.035855 0.029947 0.023703 0.017171 0.010419 0.003529 -0.003415 -0.010337 -0.017172 -0.023865 -0.030366 -0.036636 -0.042642 -0.048360 -0.053772 -0.080732 0.081793 0.082482 0.082797 0.082742 0.082317 0.081529 0.080389 0.078871 0.076967 0.074671 0.071964 0.068840 0.065294 0.061321 0.056916 0.052072 0.046783 0.041045 0.034858 0.028237 0.021217 0.013854 0.006227 -0.001568 -0.009429 -0.017269 -0.025012 -0.032594 -0.039958 -0.047058 -0.053856 -0.060324 -0.066445 -0.072210 -0.077620 -0.082751 0.083404 0.083688 0.083592 0.083098 0.082198 0.080892 0.079186 0.077073 0.074516 0.071504 0.068010 0.064024 0.059540 0.054546 0.049036 0.043000 0.036434 0.029344 0.021761 0.013739 0.005354 -0.003286 -0.012064 -0.020870 -0.029611 -0.038208 -0.046591 -0.054702 -0.062494 -0.069930 -0.076986 -0.083647 -0.089911 -0.095788 -0.101297 -0.081168 0.081796 0.082022 0.081832 0.081214 0.080129 0.078557 0.076500 0.073965 0.070902 0.067286 0.063089 0.058300 0.052909 0.046905 0.040278 0.033024 0.025159 0.016723 0.007784 -0.001559 -0.011179 -0.020938 -0.030718 -0.040416 -0.049944 -0.059225 -0.068197 -0.076807 -0.085019 -0.092807 -0.100161 -0.107080 -0.113582 -0.119693 -0.125454 -0.076330 0.077479 0.078131 0.078254 0.077822 0.076824 0.075212 0.072981 0.070153 0.066679 0.062522 0.057657 0.052075 0.045766 0.038719 0.030934 0.022428 0.013249 0.003478 -0.006773 -0.017357 -0.028117 -0.038919 -0.049646 -0.060199 -0.070490 -0.080449 -0.090017 -0.099151 -0.107825 -0.116026 -0.123758 -0.131040 -0.137904 -0.144397 -0.150580 -0.069367 0.071150 0.072617 0.073449 0.073520 0.072821 0.071343 0.069062 0.066023 0.062184 0.057504 0.051967 0.045567 0.038298 0.030157 0.021164 0.011372 0.000867 -0.010230 -0.021756 -0.033530 -0.045398 -0.057226 -0.068897 -0.080312 -0.091386 -0.102052 -0.112258 -0.121972 -0.131177 -0.139877 -0.148089 -0.155851 -0.163214 -0.170244 -0.177019 -0.062375 0.064394 0.066274 0.067906 0.068722 0.068500 0.067267 0.065011 0.061799 0.057605 0.052390 0.046148 0.038883 0.030593 0.021299 0.011051 -0.000061 -0.011912 -0.024329 -0.037109 -0.050069 -0.063054 -0.075926 -0.088567 -0.100879 -0.112777 -0.124201 -0.135107 -0.145472 -0.155294 -0.164589 -0.173392 -0.181759 -0.189758 -0.197475 -0.205004 -0.055786 0.058095 0.060202 0.062154 0.063724 0.064100 0.063176 0.060982 0.057604 0.053038 0.047252 0.040257 0.032063 0.022689 0.012183 0.000631 -0.011839 -0.025056 -0.038797 -0.052844 -0.067015 -0.081147 -0.095101 -0.108757 -0.122015 -0.134795 -0.147041 -0.158719 -0.169817 -0.180346 -0.190337 -0.199844 -0.208937 -0.217707 -0.226256 -0.234694 -0.049556 0.052224 0.054612 0.056772 0.058740 0.059758 0.059179 0.057054 0.053496 0.048522 0.042117 0.034307 0.025119 0.014596 0.002819 -0.010088 -0.023957 -0.038562 -0.053649 -0.068999 -0.084421 -0.099747 -0.114835 -0.129559 -0.143823 -0.157550 -0.170690 -0.183219 -0.195135 -0.206463 -0.217252 -0.227571 -0.237513 -0.247185 -0.256708 -0.266195 -0.043622 0.046710 0.049429 0.051833 0.053998 0.055556 0.055329 0.053259 0.049491 0.044065 0.036985 0.028295 0.018045 0.006309 -0.006798 -0.021114 -0.036421 -0.052446 -0.068920 -0.085619 -0.102343 -0.118920 -0.135198 -0.151054 -0.166390 -0.181134 -0.195243 -0.208702 -0.221522 -0.233743 -0.245430 -0.256672 -0.267580 -0.278282 -0.288912 -0.299578 -0.037935 0.041491 0.044584 0.047266 0.049622 0.051537 0.051646 0.049606 0.045590 0.039659 0.031843 0.022208 0.010830 -0.002183 -0.016681 -0.032459 -0.049246 -0.066732 -0.084645 -0.102748 -0.120835 -0.138722 -0.156255 -0.173309 -0.189786 -0.205620 -0.220774 -0.235243 -0.249053 -0.262259 -0.274945 -0.287219 -0.299210 -0.311066 -0.322928 -0.334897 -0.032456 0.036519 0.040022 0.043010 0.045573 0.047718 0.048132 0.046087 0.041780 0.035289 0.026675 0.016029 0.003459 -0.010897 -0.026846 -0.044138 -0.062450 -0.081451 -0.100860 -0.120429 -0.139940 -0.159203 -0.178059 -0.196379 -0.214068 -0.231064 -0.247340 -0.262901 -0.277787 -0.292072 -0.305855 -0.319266 -0.332455 -0.345586 -0.358796 -0.372188 -0.027151 0.031757 0.035697 0.039014 0.041799 0.044109 0.044777 0.042689 0.038042 0.030935 0.021462 0.009742 -0.004087 -0.019848 -0.037309 -0.056167 -0.076055 -0.096630 -0.117598 -0.138697 -0.159698 -0.180404 -0.200651 -0.220307 -0.239280 -0.257514 -0.274988 -0.291722 -0.307771 -0.323225 -0.338205 -0.352859 -0.367357 -0.381875 -0.396548 -0.411479 -0.021993 0.027170 0.031573 0.035239 0.038257 0.040706 0.041565 0.039392 0.034359 0.026580 0.016186 0.003328 -0.011823 -0.029052 -0.048084 -0.068562 -0.090085 -0.112296 -0.134887 -0.157583 -0.180143 -0.202361 -0.224067 -0.245131 -0.265460 -0.285004 -0.303755 -0.321743 -0.339041 -0.355756 -0.372029 -0.388028 -0.403945 -0.419960 -0.436207 -0.452787 -0.016965 0.022733 0.027619 0.031649 0.034911 0.037492 0.038479 0.036181 0.030710 0.022204 0.010830 -0.003227 -0.019763 -0.038523 -0.059185 -0.081340 -0.104557 -0.128470 -0.152752 -0.177113 -0.201301 -0.225100 -0.248337 -0.270879 -0.292637 -0.313567 -0.333672 -0.352996 -0.371627 -0.389693 -0.407355 -0.424802 -0.442242 -0.459860 -0.477787 -0.496128 -0.012064 0.018424 0.023812 0.028219 0.031730 0.034437 0.035502 0.033036 0.027080 0.017791 0.005379 -0.009938 -0.027920 -0.048274 -0.070626 -0.094514 -0.119492 -0.145173 -0.171214 -0.197310 -0.223196 -0.248647 -0.273485 -0.297577 -0.320836 -0.343227 -0.364762 -0.385503 -0.405553 -0.425060 -0.444205 -0.463198 -0.482266 -0.501590 -0.521302 -0.541510 -0.007324 0.014229 0.020129 0.024924 0.028690 0.031518 0.032617 0.029942 0.023452 0.013327 -0.000179 -0.016816 -0.036308 -0.058317 -0.082416 -0.108101 -0.134905 -0.162422 -0.190292 -0.218192 -0.245847 -0.273021 -0.299531 -0.325244 -0.350078 -0.374004 -0.397048 -0.419285 -0.440838 -0.461874 -0.482595 -0.503234 -0.524029 -0.545160 -0.566761 -0.588942 -0.002913 0.010141 0.016554 0.021744 0.025767 0.028712 0.029808 0.026883 0.019811 0.008799 -0.005858 -0.023874 -0.044936 -0.068661 -0.094568 -0.122112 -0.150808 -0.180232 -0.210000 -0.239777 -0.269270 -0.298238 -0.326492 -0.353898 -0.380379 -0.405915 -0.430545 -0.454359 -0.477498 -0.500151 -0.522541 -0.544921 -0.567541 -0.590579 -0.614170 -0.638429 --0.000889 0.006170 0.013071 0.018663 0.022945 0.025999 0.027061 0.023846 0.016144 0.004194 -0.011667 -0.031121 -0.053813 -0.079315 -0.107090 -0.136558 -0.167215 -0.198614 -0.230353 -0.262077 -0.293480 -0.324313 -0.354382 -0.383553 -0.411754 -0.438976 -0.465267 -0.490737 -0.515547 -0.539903 -0.564052 -0.588270 -0.612810 -0.637852 -0.663535 -0.689973 --0.003916 0.002388 0.009671 0.015666 0.020207 0.023364 0.024362 0.020817 0.012440 -0.000496 -0.017616 -0.038565 -0.062948 -0.090288 -0.119991 -0.151449 -0.184137 -0.217582 -0.251362 -0.285104 -0.318489 -0.351258 -0.383212 -0.414220 -0.444215 -0.473196 -0.501227 -0.528432 -0.554993 -0.581139 -0.607138 -0.633286 -0.659843 -0.686986 -0.714858 -0.743578 --0.006209 -0.001053 0.006345 0.012740 0.017540 0.020791 0.021699 0.017786 0.008689 -0.005281 -0.023713 -0.046213 -0.072348 -0.101586 -0.133279 -0.166794 -0.201581 -0.237144 -0.273037 -0.308868 -0.344306 -0.379082 -0.412994 -0.445912 -0.477773 -0.508588 -0.538433 -0.567453 -0.595847 -0.623867 -0.651805 -0.679977 -0.708643 -0.737983 -0.768143 -0.799245 --0.008023 -0.004030 0.003098 0.009875 0.014931 0.018268 0.019060 0.014742 0.004884 -0.010169 -0.029964 -0.054073 -0.082018 -0.113214 -0.146961 -0.182601 -0.219558 -0.257309 -0.295386 -0.333378 -0.370940 -0.407795 -0.443737 -0.478635 -0.512436 -0.545158 -0.576895 -0.607806 -0.638115 -0.668095 -0.698061 -0.728347 -0.759214 -0.790846 -0.823390 -0.856975 --0.009537 -0.006489 -0.000041 0.007061 0.012370 0.015784 0.016436 0.011677 0.001015 -0.015166 -0.036375 -0.062150 -0.091964 -0.125178 -0.161043 -0.198876 -0.238074 -0.278084 -0.318416 -0.358641 -0.398399 -0.437404 -0.475447 -0.512399 -0.548211 -0.582914 -0.616617 -0.649499 -0.681803 -0.713827 -0.745909 -0.778399 -0.811560 -0.845577 -0.880603 -0.916770 +0.002585 0.003531 0.004488 0.005454 0.006430 0.007414 0.008408 0.009409 0.010419 0.011435 0.012459 0.013489 0.014525 0.015567 0.016614 0.017665 0.018721 0.019780 0.020842 0.021906 0.022972 0.024040 0.025107 0.026174 0.027239 0.028302 0.029361 0.030416 0.031465 0.032508 0.033543 0.034569 0.035586 0.036591 0.037583 0.038561 +0.010080 0.011521 0.012968 0.014422 0.015879 0.017341 0.018804 0.020268 0.021732 0.023193 0.024651 0.026103 0.027549 0.028986 0.030413 0.031827 0.033226 0.034608 0.035970 0.037308 0.038619 0.039898 0.041140 0.042339 0.043489 0.044583 0.045614 0.046574 0.047455 0.048249 0.048948 0.049542 0.050025 0.050386 0.050617 0.050710 +0.022498 0.024483 0.026454 0.028408 0.030342 0.032252 0.034135 0.035986 0.037800 0.039571 0.041294 0.042961 0.044564 0.046096 0.047548 0.048910 0.050174 0.051330 0.052370 0.053283 0.054061 0.054696 0.055179 0.055502 0.055659 0.055643 0.055446 0.055064 0.054489 0.053718 0.052745 0.051566 0.050180 0.048584 0.046775 0.044754 +0.037403 0.039784 0.042099 0.044339 0.046496 0.048558 0.050516 0.052357 0.054071 0.055646 0.057072 0.058337 0.059431 0.060344 0.061068 0.061595 0.061916 0.062026 0.061919 0.061588 0.061029 0.060238 0.059209 0.057941 0.056429 0.054673 0.052670 0.050420 0.047923 0.045179 0.042189 0.038955 0.035486 0.031794 0.027897 0.023826 +0.052238 0.054689 0.056982 0.059103 0.061041 0.062782 0.064317 0.065634 0.066724 0.067576 0.068180 0.068529 0.068619 0.068444 0.067999 0.067281 0.066287 0.065012 0.063455 0.061614 0.059487 0.057075 0.054376 0.051390 0.048118 0.044559 0.040718 0.036599 0.032216 0.027592 0.022761 0.017768 0.012664 0.007505 0.002343 -0.002776 +0.065005 0.067162 0.069064 0.070701 0.072063 0.073142 0.073929 0.074417 0.074605 0.074493 0.074071 0.073332 0.072274 0.070894 0.069192 0.067165 0.064811 0.062131 0.059123 0.055787 0.052120 0.048124 0.043798 0.039144 0.034172 0.028900 0.023363 0.017609 0.011697 0.005695 -0.000331 -0.006320 -0.012220 -0.017987 -0.023580 -0.028968 +0.074593 0.076216 0.077507 0.078463 0.079083 0.079371 0.079330 0.078949 0.078219 0.077145 0.075722 0.073936 0.071786 0.069269 0.066383 0.063126 0.059494 0.055487 0.051100 0.046331 0.041179 0.035647 0.029753 0.023526 0.017016 0.010289 0.003425 -0.003495 -0.010394 -0.017208 -0.023880 -0.030363 -0.036616 -0.042607 -0.048311 -0.053713 +0.080411 0.081474 0.082169 0.082491 0.082443 0.082026 0.081246 0.080111 0.078600 0.076702 0.074413 0.071712 0.068594 0.065054 0.061087 0.056687 0.051848 0.046565 0.040834 0.034656 0.028048 0.021045 0.013703 0.006100 -0.001670 -0.009507 -0.017325 -0.025048 -0.032610 -0.039955 -0.047038 -0.053820 -0.060276 -0.066385 -0.072141 -0.077544 +0.082396 0.083066 0.083362 0.083274 0.082794 0.081907 0.080612 0.078916 0.076812 0.074264 0.071259 0.067771 0.063792 0.059314 0.054327 0.048822 0.042792 0.036234 0.029155 0.021587 0.013582 0.005220 -0.003396 -0.012150 -0.020934 -0.029655 -0.038231 -0.046596 -0.054689 -0.062465 -0.069887 -0.076930 -0.083581 -0.089837 -0.095708 -0.101214 +0.080788 0.081439 0.081687 0.081519 0.080915 0.079846 0.078288 0.076243 0.073717 0.070663 0.067055 0.062865 0.058082 0.052697 0.046699 0.040078 0.032833 0.024979 0.016558 0.007637 -0.001684 -0.011280 -0.021018 -0.030776 -0.040454 -0.049962 -0.059225 -0.068179 -0.076774 -0.084971 -0.092748 -0.100091 -0.107003 -0.113499 -0.119608 -0.125368 +0.075971 0.077120 0.077799 0.077945 0.077536 0.076553 0.074956 0.072738 0.069920 0.066455 0.062305 0.057446 0.051870 0.045566 0.038526 0.030749 0.022254 0.013090 0.003336 -0.006894 -0.017455 -0.028194 -0.038975 -0.049682 -0.060215 -0.070488 -0.080430 -0.089982 -0.099102 -0.107764 -0.115955 -0.123679 -0.130954 -0.137815 -0.144308 -0.150492 +0.069127 0.070894 0.072312 0.073155 0.073246 0.072567 0.071102 0.068833 0.065803 0.061973 0.057299 0.051768 0.045373 0.038110 0.029976 0.020994 0.011215 0.000725 -0.010352 -0.021855 -0.033609 -0.045456 -0.057264 -0.068916 -0.080312 -0.091369 -0.102018 -0.112210 -0.121910 -0.131105 -0.139796 -0.148002 -0.155761 -0.163123 -0.170154 -0.176932 +0.062146 0.064175 0.066059 0.067645 0.068466 0.068261 0.067041 0.064796 0.061593 0.057406 0.052196 0.045960 0.038699 0.030416 0.021130 0.010894 -0.000204 -0.012037 -0.024432 -0.037192 -0.050132 -0.063096 -0.075949 -0.088572 -0.100865 -0.112747 -0.124155 -0.135048 -0.145401 -0.155213 -0.164501 -0.173300 -0.181665 -0.189664 -0.197384 -0.204918 +0.055567 0.057885 0.060000 0.061956 0.063489 0.063876 0.062965 0.060780 0.057410 0.052849 0.047068 0.040077 0.031888 0.022521 0.012025 0.000486 -0.011969 -0.025166 -0.038886 -0.052914 -0.067064 -0.081177 -0.095112 -0.108749 -0.121989 -0.134753 -0.146985 -0.158650 -0.169738 -0.180258 -0.190243 -0.199747 -0.208840 -0.217611 -0.226165 -0.234608 +0.049347 0.052025 0.054420 0.056586 0.058542 0.059551 0.058981 0.056863 0.053311 0.048342 0.041941 0.034135 0.024952 0.014437 0.002671 -0.010223 -0.024075 -0.038660 -0.053727 -0.069057 -0.084459 -0.099766 -0.114834 -0.129541 -0.143787 -0.157499 -0.170625 -0.183141 -0.195048 -0.206369 -0.217153 -0.227471 -0.237413 -0.247088 -0.256616 -0.266107 +0.043424 0.046521 0.049247 0.051657 0.053826 0.055365 0.055143 0.053080 0.049316 0.043893 0.036815 0.028130 0.017886 0.006158 -0.006938 -0.021240 -0.036528 -0.052533 -0.068988 -0.085667 -0.102372 -0.118929 -0.135188 -0.151026 -0.166345 -0.181074 -0.195170 -0.208617 -0.221428 -0.233643 -0.245326 -0.256568 -0.267478 -0.278184 -0.288819 -0.299490 +0.037748 0.041312 0.044413 0.047101 0.049460 0.051360 0.051472 0.049436 0.045423 0.039494 0.031680 0.022049 0.010677 -0.002328 -0.016814 -0.032576 -0.049344 -0.066811 -0.084705 -0.102788 -0.120855 -0.138722 -0.156237 -0.173273 -0.189733 -0.205552 -0.220693 -0.235151 -0.248953 -0.262154 -0.274837 -0.287111 -0.299105 -0.310966 -0.322833 -0.334808 +0.032280 0.036351 0.039860 0.042854 0.045420 0.047557 0.047968 0.045925 0.041619 0.035129 0.026517 0.015876 0.003311 -0.011035 -0.026972 -0.044247 -0.062541 -0.081523 -0.100912 -0.120461 -0.139952 -0.159195 -0.178032 -0.196334 -0.214007 -0.230989 -0.247252 -0.262803 -0.277682 -0.291962 -0.305744 -0.319156 -0.332349 -0.345484 -0.358700 -0.372098 +0.026987 0.031599 0.035545 0.038867 0.041654 0.043961 0.044621 0.042534 0.037887 0.030781 0.021308 0.009592 -0.004230 -0.019981 -0.037429 -0.056270 -0.076140 -0.096695 -0.117643 -0.138722 -0.159703 -0.180390 -0.200617 -0.220255 -0.239212 -0.257431 -0.274894 -0.291618 -0.307661 -0.323111 -0.338090 -0.352745 -0.367248 -0.381771 -0.396450 -0.411387 +0.021842 0.027022 0.031430 0.035100 0.038120 0.040568 0.041418 0.039244 0.034209 0.026429 0.016036 0.003183 -0.011961 -0.029180 -0.048198 -0.068659 -0.090163 -0.112355 -0.134926 -0.157601 -0.180141 -0.202339 -0.224026 -0.245072 -0.265385 -0.284916 -0.303655 -0.321634 -0.338926 -0.355638 -0.371910 -0.387912 -0.403834 -0.419854 -0.436107 -0.452695 +0.016831 0.022595 0.027486 0.031519 0.034782 0.037361 0.038339 0.036038 0.030565 0.022057 0.010684 -0.003369 -0.019897 -0.038647 -0.059295 -0.081431 -0.104631 -0.128524 -0.152785 -0.177126 -0.201293 -0.225072 -0.248290 -0.270814 -0.292556 -0.313472 -0.333566 -0.352881 -0.371507 -0.389571 -0.407233 -0.424683 -0.442128 -0.459752 -0.477686 -0.496034 +0.011964 0.018298 0.023687 0.028096 0.031608 0.034313 0.035368 0.032898 0.026938 0.017648 0.005237 -0.010077 -0.028052 -0.048394 -0.070730 -0.094601 -0.119561 -0.145222 -0.171242 -0.197317 -0.223181 -0.248613 -0.273432 -0.297506 -0.320749 -0.343126 -0.364651 -0.385383 -0.405428 -0.424933 -0.444079 -0.463077 -0.482150 -0.501480 -0.521199 -0.541415 +0.007333 0.014117 0.020012 0.024808 0.028574 0.031399 0.032489 0.029808 0.023313 0.013186 -0.000319 -0.016952 -0.036436 -0.058433 -0.082517 -0.108184 -0.134969 -0.162466 -0.190315 -0.218194 -0.245827 -0.272981 -0.299472 -0.325167 -0.349985 -0.373898 -0.396931 -0.419160 -0.440709 -0.461744 -0.482467 -0.503110 -0.523910 -0.545048 -0.566656 -0.588845 +0.003124 0.010053 0.016445 0.021635 0.025657 0.028598 0.029685 0.026753 0.019674 0.008660 -0.005996 -0.024008 -0.045062 -0.068774 -0.094665 -0.122191 -0.150868 -0.180271 -0.210018 -0.239773 -0.269245 -0.298193 -0.326427 -0.353815 -0.380280 -0.405804 -0.430423 -0.454229 -0.477365 -0.500017 -0.522409 -0.544794 -0.567420 -0.590464 -0.614063 -0.638330 +-0.000560 0.006147 0.012972 0.018561 0.022841 0.025891 0.026942 0.023719 0.016010 0.004058 -0.011803 -0.031252 -0.053937 -0.079426 -0.107184 -0.136634 -0.167272 -0.198650 -0.230367 -0.262068 -0.293450 -0.324262 -0.354311 -0.383464 -0.411650 -0.438859 -0.465140 -0.490604 -0.515409 -0.539765 -0.563917 -0.588139 -0.612686 -0.637735 -0.663426 -0.689873 +-0.003630 0.002499 0.009583 0.015570 0.020108 0.023260 0.024247 0.020693 0.012308 -0.000631 -0.017750 -0.038694 -0.063069 -0.090396 -0.120082 -0.151522 -0.184189 -0.217613 -0.251371 -0.285091 -0.318454 -0.351201 -0.383136 -0.414127 -0.444106 -0.473074 -0.501095 -0.528294 -0.554851 -0.580997 -0.606999 -0.633153 -0.659716 -0.686866 -0.714747 -0.743476 +-0.006030 -0.000821 0.006275 0.012650 0.017446 0.020691 0.021587 0.017664 0.008559 -0.005415 -0.023845 -0.046341 -0.072467 -0.101691 -0.133367 -0.166864 -0.201631 -0.237172 -0.273042 -0.308851 -0.344266 -0.379021 -0.412913 -0.445813 -0.477659 -0.508460 -0.538297 -0.567310 -0.595701 -0.623722 -0.651664 -0.679841 -0.708513 -0.737861 -0.768029 -0.799141 +-0.007900 -0.003764 0.003070 0.009791 0.014842 0.018172 0.018952 0.014622 0.004755 -0.010301 -0.030095 -0.054200 -0.082135 -0.113317 -0.147046 -0.182668 -0.219604 -0.257333 -0.295387 -0.333356 -0.370895 -0.407729 -0.443650 -0.478531 -0.512316 -0.545026 -0.576753 -0.607659 -0.637965 -0.667946 -0.697916 -0.728208 -0.759082 -0.790721 -0.823275 -0.856870 +-0.009441 -0.006278 0.000010 0.006983 0.012285 0.015691 0.016330 0.011558 0.000887 -0.015297 -0.036506 -0.062275 -0.092080 -0.125279 -0.161126 -0.198941 -0.238116 -0.278104 -0.318413 -0.358615 -0.398350 -0.437333 -0.475356 -0.512290 -0.548086 -0.582778 -0.616472 -0.649348 -0.681649 -0.713674 -0.745761 -0.778257 -0.811424 -0.845450 -0.880485 -0.916662 diff --git a/rosco/toolbox/controller.py b/rosco/toolbox/controller.py index 2d0e3a67..37582c54 100644 --- a/rosco/toolbox/controller.py +++ b/rosco/toolbox/controller.py @@ -261,8 +261,12 @@ def tune_controller(self, turbine): # Identify TSR matching the Cp values Cp_FBP = np.ndarray.flatten(turbine.Cp.interp_surface(0, turbine.TSR_initial)) # all Cp values for fine blade pitch (assumed 0) Cp_maxidx = Cp_FBP.argmax() - Cp_op = np.clip(Cp_op, np.min(Cp_FBP[Cp_maxidx:]), np.max(Cp_FBP[Cp_maxidx:])) # saturate Cp values to be on Cp surface # Find maximum Cp value for this TSR + # if underspeed + Cp_op = np.clip(Cp_op, np.min(Cp_FBP[:Cp_maxidx+1]), np.max(Cp_FBP[:Cp_maxidx+1])) # saturate Cp values to be on Cp surface # Find maximum Cp value for this TSR f_cp_TSR = interpolate.interp1d(Cp_FBP[:Cp_maxidx+1], turbine.TSR_initial[:Cp_maxidx+1]) # interpolate function for Cp(tsr) values + # if overspeed + # Cp_op = np.clip(Cp_op, np.min(Cp_FBP[Cp_maxidx:]), np.max(Cp_FBP[Cp_maxidx:])) # saturate Cp values to be on Cp surface # Find maximum Cp value for this TSR + # f_cp_TSR = interpolate.interp1d(Cp_FBP[Cp_maxidx:], turbine.TSR_initial[Cp_maxidx:]) # interpolate function for Cp(tsr) values TSR_op = f_cp_TSR(Cp_op) TSR_op_br = TSR_op[:len(v_below_rated)] TSR_op_ar = TSR_op[len(v_below_rated):] diff --git a/rosco/toolbox/turbine.py b/rosco/toolbox/turbine.py index 73965285..616c925d 100644 --- a/rosco/toolbox/turbine.py +++ b/rosco/toolbox/turbine.py @@ -294,8 +294,8 @@ def load_from_ccblade(self): self.load_blade_info() # Generate the look-up tables, mesh the grid and flatten the arrays for cc_rotor aerodynamic analysis - TSR_initial = np.arange(2, 15,0.5) - pitch_initial = np.arange(-5,31,1.) + TSR_initial = np.arange(0.5, 15, 0.5) + pitch_initial = np.arange(-5, 31, 1.) pitch_initial_rad = pitch_initial * deg2rad ws_array = np.ones_like(TSR_initial) * self.v_rated # evaluate at rated wind speed omega_array = (TSR_initial * ws_array / self.rotor_radius) * RadSec2rpm From 32ecfc8336b9dfeafe5e710dbe0a23f338bdcc2d Mon Sep 17 00:00:00 2001 From: David Stockhouse Date: Fri, 10 May 2024 10:42:40 -0600 Subject: [PATCH 141/224] updated DISCONs --- Examples/Test_Cases/BAR_10/BAR_10_DISCON.IN | 11 +++++-- .../DISCON-UMaineSemi.IN | 11 +++++-- Examples/Test_Cases/MHK_RM1/MHK_RM1_DISCON.IN | 33 +++++++++++-------- Examples/Test_Cases/NREL-5MW/DISCON.IN | 11 +++++-- .../NREL_2p8_127/NREL-2p8-127_DISCON.IN | 11 +++++-- 5 files changed, 56 insertions(+), 21 deletions(-) diff --git a/Examples/Test_Cases/BAR_10/BAR_10_DISCON.IN b/Examples/Test_Cases/BAR_10/BAR_10_DISCON.IN index ebbc56f5..c353edb6 100644 --- a/Examples/Test_Cases/BAR_10/BAR_10_DISCON.IN +++ b/Examples/Test_Cases/BAR_10/BAR_10_DISCON.IN @@ -1,10 +1,10 @@ ! Controller parameter input file for the BAR_10 wind turbine -! - File written using ROSCO version 2.8.0 controller tuning logic on 01/05/24 +! - File written using ROSCO version 2.9.0 controller tuning logic on 05/10/24 !------- SIMULATION CONTROL ------------------------------------------------------------ 1 ! LoggingLevel - {0: write no debug files, 1: write standard output .dbg-file, 2: LoggingLevel 1 + ROSCO LocalVars (.dbg2) 3: LoggingLevel 2 + complete avrSWAP-array (.dbg3)} 0 ! DT_Out - {Time step to output .dbg* files, or 0 to match sampling period of OpenFAST} -1 ! Ext_Interface - (0 - use standard bladed interface, 1 - Use the extened DLL interface introduced in OpenFAST 3.5.0.) +1 ! Ext_Interface - (0 - use standard bladed interface, 1 - Use the extened DLL interface introduced in OpenFAST 3.5.0.) 0 ! Echo - (0 - no Echo, 1 - Echo input data to .echo) !------- CONTROLLER FLAGS ------------------------------------------------- @@ -91,6 +91,13 @@ 9.76 ! VS_TSRopt - Power-maximizing region 2 tip-speed-ratio. Only used in VS_ControlMode = 2. 0.314000000000 ! VS_PwrFiltF - Low pass filter on power used to determine generator speed set point. Only used in VS_ControlMode = 3. +!------- FIXED PITCH REGION 3 TORQUE CONTROL ------------------------------------------------ +0 ! FBP_RefMode - Reference control mode (0 - Use wind speed estimator, 1 - Use torque feedback) +60 ! FBP_n - Number of gain-scheduling table entries +3.000000 3.181847 3.363694 3.545541 3.727388 3.909234 4.091081 4.272928 4.454775 4.636622 4.818469 5.000316 5.182163 5.364010 5.545857 5.727703 5.909550 6.091397 6.273244 6.455091 6.636938 6.818785 7.000632 7.182479 7.364326 7.546172 7.728019 7.909866 8.091713 8.273560 8.831108 9.388656 9.946204 10.503752 11.061300 11.618848 12.176396 12.733944 13.291492 13.849040 14.406588 14.964136 15.521684 16.079232 16.636780 17.194328 17.751876 18.309424 18.866972 19.424520 19.982068 20.539616 21.097164 21.654712 22.212260 22.769808 23.327356 23.884904 24.442452 25.000000 ! FBP_U - Operating schedule table: Wind speeds [m/s]. +27.497174 29.163932 30.830691 32.497450 34.164208 35.830967 37.497725 39.164484 40.831243 42.498001 44.164760 45.831518 47.498277 49.165035 50.831794 52.498553 54.165311 55.832070 57.498828 59.165587 60.832346 62.499104 64.165863 65.832621 67.499380 69.166138 70.832897 72.499656 74.166414 79.853125 79.853125 79.853125 79.853125 79.853125 79.853125 79.853125 79.853125 79.853125 79.853125 79.853125 79.853125 79.853125 79.853125 79.853125 79.853125 79.853125 79.853125 79.853125 79.853125 79.853125 79.853125 79.853125 79.853125 79.853125 79.853125 79.853125 79.853125 79.853125 79.853125 79.853125 ! FBP_Omega - Operating schedule table: Generator speeds [rad/s]. +9102.377387 10239.314561 11443.140643 12713.855635 14051.459535 15455.952344 16927.334062 18465.604688 20070.764223 21742.812668 23481.750020 25287.576282 27160.291453 29099.895532 31106.388520 33179.770417 35320.041223 37527.200937 39801.249560 42142.187093 44550.013533 47024.728883 49566.333142 52174.826309 54850.208385 57592.479370 60401.639263 63277.688066 66220.625777 65712.002182 65712.002182 65712.002182 65712.002182 65712.002182 65712.002182 65712.002182 65712.002182 65712.002182 65712.002182 65712.002182 65712.002182 65712.002182 65712.002182 65712.002182 65712.002182 65712.002182 65712.002182 65712.002182 65712.002182 65712.002182 65712.002182 65712.002182 65712.002182 65712.002182 65712.002182 65712.002182 65712.002182 65712.002182 65712.002182 65712.002182 ! FBP_Tau - Operating schedule table: Generator torques [N m]. + !------- SETPOINT SMOOTHER --------------------------------------------- 1.00000 ! SS_VSGain - Variable speed torque controller setpoint smoother gain, [-]. 0.00100 ! SS_PCGain - Collective pitch controller setpoint smoother gain, [-]. diff --git a/Examples/Test_Cases/IEA-15-240-RWT-UMaineSemi/DISCON-UMaineSemi.IN b/Examples/Test_Cases/IEA-15-240-RWT-UMaineSemi/DISCON-UMaineSemi.IN index cd58ccf8..d347385c 100644 --- a/Examples/Test_Cases/IEA-15-240-RWT-UMaineSemi/DISCON-UMaineSemi.IN +++ b/Examples/Test_Cases/IEA-15-240-RWT-UMaineSemi/DISCON-UMaineSemi.IN @@ -1,10 +1,10 @@ ! Controller parameter input file for the IEA-15-240-RWT-UMaineSemi wind turbine -! - File written using ROSCO version 2.8.0 controller tuning logic on 01/05/24 +! - File written using ROSCO version 2.9.0 controller tuning logic on 05/10/24 !------- SIMULATION CONTROL ------------------------------------------------------------ 2 ! LoggingLevel - {0: write no debug files, 1: write standard output .dbg-file, 2: LoggingLevel 1 + ROSCO LocalVars (.dbg2) 3: LoggingLevel 2 + complete avrSWAP-array (.dbg3)} 0 ! DT_Out - {Time step to output .dbg* files, or 0 to match sampling period of OpenFAST} -1 ! Ext_Interface - (0 - use standard bladed interface, 1 - Use the extened DLL interface introduced in OpenFAST 3.5.0.) +1 ! Ext_Interface - (0 - use standard bladed interface, 1 - Use the extened DLL interface introduced in OpenFAST 3.5.0.) 0 ! Echo - (0 - no Echo, 1 - Echo input data to .echo) !------- CONTROLLER FLAGS ------------------------------------------------- @@ -91,6 +91,13 @@ 9.00 ! VS_TSRopt - Power-maximizing region 2 tip-speed-ratio. Only used in VS_ControlMode = 2. 0.314000000000 ! VS_PwrFiltF - Low pass filter on power used to determine generator speed set point. Only used in VS_ControlMode = 3. +!------- FIXED PITCH REGION 3 TORQUE CONTROL ------------------------------------------------ +0 ! FBP_RefMode - Reference control mode (0 - Use wind speed estimator, 1 - Use torque feedback) +60 ! FBP_n - Number of gain-scheduling table entries +3.000000 3.266897 3.533793 3.800690 4.067586 4.334483 4.601379 4.868276 5.135172 5.402069 5.668966 5.935862 6.202759 6.469655 6.736552 7.003448 7.270345 7.537241 7.804138 8.071034 8.337931 8.604828 8.871724 9.138621 9.405517 9.672414 9.939310 10.206207 10.473103 10.740000 11.215333 11.690667 12.166000 12.641333 13.116667 13.592000 14.067333 14.542667 15.018000 15.493333 15.968667 16.444000 16.919333 17.394667 17.870000 18.345333 18.820667 19.296000 19.771333 20.246667 20.722000 21.197333 21.672667 22.148000 22.623333 23.098667 23.574000 24.049333 24.524667 25.000000 ! FBP_U - Operating schedule table: Wind speeds [m/s]. +0.523599 0.523599 0.523599 0.523599 0.523599 0.523599 0.523599 0.523599 0.523599 0.523599 0.523599 0.523599 0.523599 0.523599 0.523599 0.525259 0.545276 0.565293 0.585310 0.605328 0.625345 0.645362 0.665379 0.685397 0.705414 0.725431 0.745448 0.765466 0.785483 0.791681 0.791681 0.791681 0.791681 0.791681 0.791681 0.791681 0.791681 0.791681 0.791681 0.791681 0.791681 0.791681 0.791681 0.791681 0.791681 0.791681 0.791681 0.791681 0.791681 0.791681 0.791681 0.791681 0.791681 0.791681 0.791681 0.791681 0.791681 0.791681 0.791681 0.791681 ! FBP_Omega - Operating schedule table: Generator speeds [rad/s]. +670491.743806 865836.356288 1095854.831758 1363379.930396 1671244.412384 2022281.037902 2419322.567131 2865201.760252 3362751.377446 3914804.178893 4524192.924774 5193750.375270 5926309.290562 6724702.430830 7591762.556256 8503366.146143 9163830.508856 9848994.075161 10558856.845058 11293418.818547 12052679.995627 12836640.376300 13645299.960564 14478658.748420 15336716.739867 16219473.934907 17126930.333538 18059085.935762 19015940.741577 20378439.244242 20378439.244242 20378439.244242 20378439.244242 20378439.244242 20378439.244242 20378439.244242 20378439.244242 20378439.244242 20378439.244242 20378439.244242 20378439.244242 20378439.244242 20378439.244242 20378439.244242 20378439.244242 20378439.244242 20378439.244242 20378439.244242 20378439.244242 20378439.244242 20378439.244242 20378439.244242 20378439.244242 20378439.244242 20378439.244242 20378439.244242 20378439.244242 20378439.244242 20378439.244242 20378439.244242 ! FBP_Tau - Operating schedule table: Generator torques [N m]. + !------- SETPOINT SMOOTHER --------------------------------------------- 1.00000 ! SS_VSGain - Variable speed torque controller setpoint smoother gain, [-]. 0.00100 ! SS_PCGain - Collective pitch controller setpoint smoother gain, [-]. diff --git a/Examples/Test_Cases/MHK_RM1/MHK_RM1_DISCON.IN b/Examples/Test_Cases/MHK_RM1/MHK_RM1_DISCON.IN index 322213ff..a11607be 100644 --- a/Examples/Test_Cases/MHK_RM1/MHK_RM1_DISCON.IN +++ b/Examples/Test_Cases/MHK_RM1/MHK_RM1_DISCON.IN @@ -1,10 +1,10 @@ ! Controller parameter input file for the MHK_RM1_Floating wind turbine -! - File written using ROSCO version 2.8.0 controller tuning logic on 01/05/24 +! - File written using ROSCO version 2.9.0 controller tuning logic on 05/10/24 !------- SIMULATION CONTROL ------------------------------------------------------------ 2 ! LoggingLevel - {0: write no debug files, 1: write standard output .dbg-file, 2: LoggingLevel 1 + ROSCO LocalVars (.dbg2) 3: LoggingLevel 2 + complete avrSWAP-array (.dbg3)} 0 ! DT_Out - {Time step to output .dbg* files, or 0 to match sampling period of OpenFAST} -1 ! Ext_Interface - (0 - use standard bladed interface, 1 - Use the extened DLL interface introduced in OpenFAST 3.5.0.) +1 ! Ext_Interface - (0 - use standard bladed interface, 1 - Use the extened DLL interface introduced in OpenFAST 3.5.0.) 0 ! Echo - (0 - no Echo, 1 - Echo input data to .echo) !------- CONTROLLER FLAGS ------------------------------------------------- @@ -52,17 +52,17 @@ !------- BLADE PITCH CONTROL ---------------------------------------------- 30 ! PC_GS_n - Amount of gain-scheduling table entries -0.030335 0.049075 0.063610 0.076093 0.087460 0.097196 0.106672 0.115225 0.123634 0.131302 0.139019 0.146056 0.153083 0.159873 0.166338 0.172854 0.178999 0.185046 0.191143 0.196863 0.202559 0.208301 0.213742 0.219137 0.224575 0.229836 0.234972 0.240145 0.245291 0.250200 ! PC_GS_angles - Gain-schedule table: pitch angles [rad]. --0.010178 -0.008780 -0.007625 -0.006655 -0.005829 -0.005116 -0.004495 -0.003950 -0.003467 -0.003036 -0.002650 -0.002301 -0.001984 -0.001696 -0.001432 -0.001190 -0.000966 -0.000760 -0.000568 -0.000390 -0.000225 -0.000069 0.000076 0.000212 0.000340 0.000461 0.000575 0.000682 0.000784 0.000881 ! PC_GS_KP - Gain-schedule table: pitch controller kp gains [s]. --0.005272 -0.004770 -0.004355 -0.004007 -0.003710 -0.003454 -0.003232 -0.003036 -0.002862 -0.002708 -0.002569 -0.002443 -0.002330 -0.002226 -0.002132 -0.002045 -0.001964 -0.001890 -0.001822 -0.001758 -0.001698 -0.001642 -0.001590 -0.001541 -0.001495 -0.001452 -0.001411 -0.001372 -0.001336 -0.001301 ! PC_GS_KI - Gain-schedule table: pitch controller ki gains [-]. +0.030421 0.049144 0.063652 0.076112 0.087461 0.097179 0.106641 0.115177 0.123576 0.131228 0.138929 0.145961 0.152973 0.159760 0.166211 0.172713 0.178857 0.184892 0.190976 0.196697 0.202382 0.208113 0.213557 0.218943 0.224369 0.229635 0.234763 0.239926 0.245078 0.249980 ! PC_GS_angles - Gain-schedule table: pitch angles [rad]. +-0.010190 -0.008794 -0.007640 -0.006670 -0.005844 -0.005132 -0.004511 -0.003966 -0.003483 -0.003052 -0.002665 -0.002315 -0.001999 -0.001710 -0.001446 -0.001203 -0.000980 -0.000773 -0.000582 -0.000403 -0.000237 -0.000082 0.000064 0.000200 0.000328 0.000449 0.000563 0.000671 0.000773 0.000870 ! PC_GS_KP - Gain-schedule table: pitch controller kp gains [s]. +-0.005276 -0.004774 -0.004360 -0.004012 -0.003715 -0.003459 -0.003237 -0.003041 -0.002867 -0.002712 -0.002573 -0.002448 -0.002334 -0.002231 -0.002136 -0.002049 -0.001969 -0.001894 -0.001825 -0.001762 -0.001702 -0.001646 -0.001594 -0.001545 -0.001499 -0.001455 -0.001414 -0.001376 -0.001339 -0.001304 ! PC_GS_KI - Gain-schedule table: pitch controller ki gains [-]. 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 ! PC_GS_KD - Gain-schedule table: pitch controller kd gains 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 ! PC_GS_TF - Gain-schedule table: pitch controller tf gains (derivative filter) 1.570000000000 ! PC_MaxPit - Maximum physical pitch limit, [rad]. -0.000690000000 ! PC_MinPit - Minimum physical pitch limit, [rad]. +0.000710000000 ! PC_MinPit - Minimum physical pitch limit, [rad]. 0.174500000000 ! PC_MaxRat - Maximum pitch rate (in absolute value) in pitch controller, [rad/s]. -0.17450000000 ! PC_MinRat - Minimum pitch rate (in absolute value) in pitch controller, [rad/s]. 63.81200000000 ! PC_RefSpd - Desired (reference) HSS speed for pitch controller, [rad/s]. -0.000690000000 ! PC_FinePit - Record 5: Below-rated pitch angle set-point, [rad] +0.000710000000 ! PC_FinePit - Record 5: Below-rated pitch angle set-point, [rad] 0.017450000000 ! PC_Switch - Angle above lowest minimum pitch angle for switch, [rad] !------- INDIVIDUAL PITCH CONTROL ----------------------------------------- @@ -80,17 +80,24 @@ 1500000.000000 ! VS_MaxRat - Maximum torque rate (in absolute value) in torque controller, [Nm/s]. 12450.50344000 ! VS_MaxTq - Maximum generator torque in Region 3 (HSS side), [Nm]. 0.000000000000 ! VS_MinTq - Minimum generator torque (HSS side), [Nm]. -19.00309000000 ! VS_MinOMSpd - Minimum generator speed [rad/s] -1.142870000000 ! VS_Rgn2K - Generator torque constant in Region 2 (HSS side). Only used in VS_ControlMode = 1,3 +19.01313000000 ! VS_MinOMSpd - Minimum generator speed [rad/s] +1.137080000000 ! VS_Rgn2K - Generator torque constant in Region 2 (HSS side). Only used in VS_ControlMode = 1,3 500000.0000000 ! VS_RtPwr - Wind turbine rated power [W] 8300.335630000 ! VS_RtTq - Rated torque, [Nm]. 63.81200000000 ! VS_RefSpd - Rated generator speed [rad/s] 1 ! VS_n - Number of generator PI torque controller gains --63.8796200000 ! VS_KP - Proportional gain for generator PI torque controller [-]. (Only used in the transitional 2.5 region if VS_ControlMode =/ 2) +-64.2578900000 ! VS_KP - Proportional gain for generator PI torque controller [-]. (Only used in the transitional 2.5 region if VS_ControlMode =/ 2) -84.4329000000 ! VS_KI - Integral gain for generator PI torque controller [s]. (Only used in the transitional 2.5 region if VS_ControlMode =/ 2) 7.17 ! VS_TSRopt - Power-maximizing region 2 tip-speed-ratio. Only used in VS_ControlMode = 2. 0.314000000000 ! VS_PwrFiltF - Low pass filter on power used to determine generator speed set point. Only used in VS_ControlMode = 3. +!------- FIXED PITCH REGION 3 TORQUE CONTROL ------------------------------------------------ +0 ! FBP_RefMode - Reference control mode (0 - Use wind speed estimator, 1 - Use torque feedback) +60 ! FBP_n - Number of gain-scheduling table entries +0.500000 0.551724 0.603448 0.655172 0.706897 0.758621 0.810345 0.862069 0.913793 0.965517 1.017241 1.068966 1.120690 1.172414 1.224138 1.275862 1.327586 1.379310 1.431034 1.482759 1.534483 1.586207 1.637931 1.689655 1.741379 1.793103 1.844828 1.896552 1.948276 2.000000 2.033333 2.066667 2.100000 2.133333 2.166667 2.200000 2.233333 2.266667 2.300000 2.333333 2.366667 2.400000 2.433333 2.466667 2.500000 2.533333 2.566667 2.600000 2.633333 2.666667 2.700000 2.733333 2.766667 2.800000 2.833333 2.866667 2.900000 2.933333 2.966667 3.000000 ! FBP_U - Operating schedule table: Wind speeds [m/s]. +19.013134 20.980010 22.946886 24.913762 26.880638 28.847514 30.814390 32.781266 34.748142 36.715018 38.681894 40.648770 42.615646 44.582522 46.549398 48.516274 50.483150 52.450026 54.416902 56.383778 58.350654 60.317530 62.284406 63.812000 63.812000 63.812000 63.812000 63.812000 63.812000 63.812000 63.812000 63.812000 63.812000 63.812000 63.812000 63.812000 63.812000 63.812000 63.812000 63.812000 63.812000 63.812000 63.812000 63.812000 63.812000 63.812000 63.812000 63.812000 63.812000 63.812000 63.812000 63.812000 63.812000 63.812000 63.812000 63.812000 63.812000 63.812000 63.812000 63.812000 ! FBP_Omega - Operating schedule table: Generator speeds [rad/s]. +473.300280 576.289520 689.408850 812.658269 946.037777 1089.547374 1243.187061 1406.956837 1580.856702 1764.886656 1959.046699 2163.336832 2377.757054 2602.307365 2836.987765 3081.798255 3336.738834 3601.809502 3877.010259 4162.341105 4457.802041 4763.393066 5079.114180 5442.173156 5953.593744 6483.496857 7051.903239 7643.209401 8252.348857 8797.474880 8797.474880 8797.474880 8797.474880 8797.474880 8797.474880 8797.474880 8797.474880 8797.474880 8797.474880 8797.474880 8797.474880 8797.474880 8797.474880 8797.474880 8797.474880 8797.474880 8797.474880 8797.474880 8797.474880 8797.474880 8797.474880 8797.474880 8797.474880 8797.474880 8797.474880 8797.474880 8797.474880 8797.474880 8797.474880 8797.474880 ! FBP_Tau - Operating schedule table: Generator torques [N m]. + !------- SETPOINT SMOOTHER --------------------------------------------- 1.00000 ! SS_VSGain - Variable speed torque controller setpoint smoother gain, [-]. 0.00100 ! SS_PCGain - Collective pitch controller setpoint smoother gain, [-]. @@ -110,10 +117,10 @@ 484024.50000 ! WE_Jtot - Total drivetrain inertia, including blades, hub and casted generator inertia to LSS, [kg m^2] 1025.000 ! WE_RhoAir - Air density, [kg m^-3] "MHK_RM1_Cp_Ct_Cq.txt" ! PerfFileName - File containing rotor performance tables (Cp,Ct,Cq) (absolute path or relative to this file) -36 26 ! PerfTableSize - Size of rotor performance tables, first number refers to number of blade pitch angles, second number referse to number of tip-speed ratios +36 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 60 ! WE_FOPoles_N - Number of first-order system poles used in EKF 0.5000 0.5517 0.6034 0.6552 0.7069 0.7586 0.8103 0.8621 0.9138 0.9655 1.0172 1.0690 1.1207 1.1724 1.2241 1.2759 1.3276 1.3793 1.4310 1.4828 1.5345 1.5862 1.6379 1.6897 1.7414 1.7931 1.8448 1.8966 1.9483 2.0000 2.0333 2.0667 2.1000 2.1333 2.1667 2.2000 2.2333 2.2667 2.3000 2.3333 2.3667 2.4000 2.4333 2.4667 2.5000 2.5333 2.5667 2.6000 2.6333 2.6667 2.7000 2.7333 2.7667 2.8000 2.8333 2.8667 2.9000 2.9333 2.9667 3.0000 ! WE_FOPoles_v - Wind speeds corresponding to first-order system poles [m/s] --0.14364445 -0.15850422 -0.17336400 -0.18822377 -0.20308354 -0.21794331 -0.23280308 -0.24766285 -0.26252262 -0.27738239 -0.29224216 -0.30710193 -0.32196171 -0.33682148 -0.35168125 -0.36654102 -0.38140079 -0.39626056 -0.41112033 -0.42598010 -0.44083987 -0.45569965 -0.47055942 -0.48666545 -0.50602877 -0.52082936 -0.60274133 -0.60720589 -0.60927938 -0.55668516 0.17844923 0.15174296 0.10860051 0.05753679 0.00176535 -0.05812003 -0.11803585 -0.18146508 -0.24666701 -0.31440662 -0.38335107 -0.45418067 -0.52480063 -0.59662243 -0.67000720 -0.74481113 -0.82056059 -0.89753628 -0.97589183 -1.05446405 -1.13345094 -1.21374047 -1.29379323 -1.37507241 -1.45808464 -1.54093580 -1.62426617 -1.70957888 -1.79610923 -1.88140848 ! WE_FOPoles - First order system poles [1/s] +-0.14308393 -0.15788571 -0.17268750 -0.18748928 -0.20229107 -0.21709285 -0.23189464 -0.24669643 -0.26149821 -0.27630000 -0.29110178 -0.30590357 -0.32070535 -0.33550714 -0.35030892 -0.36511071 -0.37991250 -0.39471428 -0.40951607 -0.42431785 -0.43911964 -0.45392142 -0.46872321 -0.48487459 -0.50420905 -0.51897473 -0.60027681 -0.60489437 -0.60708415 -0.55452329 0.18039231 0.15353375 0.11034116 0.05930222 0.00360074 -0.05616070 -0.11594248 -0.17921755 -0.24424769 -0.31180903 -0.38057365 -0.45117734 -0.52158847 -0.59317066 -0.66628530 -0.74082760 -0.81629342 -0.89295334 -0.97099163 -1.04925592 -1.12788429 -1.20781665 -1.28757103 -1.36845961 -1.45107295 -1.53364806 -1.61655483 -1.70142184 -1.78767141 -1.87248964 ! WE_FOPoles - First order system poles [1/s] !------- YAW CONTROL ------------------------------------------------------ 0.00000 ! Y_uSwitch - Wind speed to switch between Y_ErrThresh. If zero, only the second value of Y_ErrThresh is used [m/s] @@ -143,7 +150,7 @@ !------- Floating ----------------------------------------------------------- 1 ! Fl_n - Number of Fl_Kp gains in gain scheduling, optional with default of 1 --0.3999 ! Fl_Kp - Nacelle velocity proportional feedback gain [s] +-0.3993 ! Fl_Kp - Nacelle velocity proportional feedback gain [s] 2.1000 ! Fl_U - Wind speeds for scheduling Fl_Kp, optional if Fl_Kp is single value [m/s] !------- FLAP ACTUATION ----------------------------------------------------- diff --git a/Examples/Test_Cases/NREL-5MW/DISCON.IN b/Examples/Test_Cases/NREL-5MW/DISCON.IN index 0d8024d1..bb6d8c4e 100644 --- a/Examples/Test_Cases/NREL-5MW/DISCON.IN +++ b/Examples/Test_Cases/NREL-5MW/DISCON.IN @@ -1,10 +1,10 @@ ! Controller parameter input file for the NREL-5MW wind turbine -! - File written using ROSCO version 2.8.0 controller tuning logic on 01/05/24 +! - File written using ROSCO version 2.9.0 controller tuning logic on 05/10/24 !------- SIMULATION CONTROL ------------------------------------------------------------ 1 ! LoggingLevel - {0: write no debug files, 1: write standard output .dbg-file, 2: LoggingLevel 1 + ROSCO LocalVars (.dbg2) 3: LoggingLevel 2 + complete avrSWAP-array (.dbg3)} 0 ! DT_Out - {Time step to output .dbg* files, or 0 to match sampling period of OpenFAST} -1 ! Ext_Interface - (0 - use standard bladed interface, 1 - Use the extened DLL interface introduced in OpenFAST 3.5.0.) +1 ! Ext_Interface - (0 - use standard bladed interface, 1 - Use the extened DLL interface introduced in OpenFAST 3.5.0.) 0 ! Echo - (0 - no Echo, 1 - Echo input data to .echo) !------- CONTROLLER FLAGS ------------------------------------------------- @@ -91,6 +91,13 @@ 7.64 ! VS_TSRopt - Power-maximizing region 2 tip-speed-ratio. Only used in VS_ControlMode = 2. 0.314000000000 ! VS_PwrFiltF - Low pass filter on power used to determine generator speed set point. Only used in VS_ControlMode = 3. +!------- FIXED PITCH REGION 3 TORQUE CONTROL ------------------------------------------------ +0 ! FBP_RefMode - Reference control mode (0 - Use wind speed estimator, 1 - Use torque feedback) +60 ! FBP_n - Number of gain-scheduling table entries +3.000000 3.289655 3.579310 3.868966 4.158621 4.448276 4.737931 5.027586 5.317241 5.606897 5.896552 6.186207 6.475862 6.765517 7.055172 7.344828 7.634483 7.924138 8.213793 8.503448 8.793103 9.082759 9.372414 9.662069 9.951724 10.241379 10.531034 10.820690 11.110345 11.400000 11.853333 12.306667 12.760000 13.213333 13.666667 14.120000 14.573333 15.026667 15.480000 15.933333 16.386667 16.840000 17.293333 17.746667 18.200000 18.653333 19.106667 19.560000 20.013333 20.466667 20.920000 21.373333 21.826667 22.280000 22.733333 23.186667 23.640000 24.093333 24.546667 25.000000 ! FBP_U - Operating schedule table: Wind speeds [m/s]. +35.290063 38.697380 42.104696 45.512012 48.919329 52.326645 55.733962 59.141278 62.548595 65.955911 69.363228 72.770544 76.177860 79.585177 82.992493 86.399810 89.807126 93.214443 96.621759 100.029076 103.436392 106.843708 110.251025 113.658341 117.065658 120.472974 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 ! FBP_Omega - Operating schedule table: Generator speeds [rad/s]. +2722.104214 3273.128021 3874.904020 4527.432212 5230.712597 5984.745175 6789.529945 7645.066908 8551.356064 9508.397412 10516.190954 11574.736688 12684.034614 13844.084733 15054.887046 16316.441550 17628.748248 18991.807138 20405.618221 21870.181497 23385.496965 24951.564626 26568.384480 28235.956527 29954.280766 31723.357198 33808.077172 36640.947188 39612.510839 42557.267110 42557.267110 42557.267110 42557.267110 42557.267110 42557.267110 42557.267110 42557.267110 42557.267110 42557.267110 42557.267110 42557.267110 42557.267110 42557.267110 42557.267110 42557.267110 42557.267110 42557.267110 42557.267110 42557.267110 42557.267110 42557.267110 42557.267110 42557.267110 42557.267110 42557.267110 42557.267110 42557.267110 42557.267110 42557.267110 42557.267110 ! FBP_Tau - Operating schedule table: Generator torques [N m]. + !------- SETPOINT SMOOTHER --------------------------------------------- 1.00000 ! SS_VSGain - Variable speed torque controller setpoint smoother gain, [-]. 0.00100 ! SS_PCGain - Collective pitch controller setpoint smoother gain, [-]. diff --git a/Examples/Test_Cases/NREL_2p8_127/NREL-2p8-127_DISCON.IN b/Examples/Test_Cases/NREL_2p8_127/NREL-2p8-127_DISCON.IN index 31d0ed79..5d9ae259 100644 --- a/Examples/Test_Cases/NREL_2p8_127/NREL-2p8-127_DISCON.IN +++ b/Examples/Test_Cases/NREL_2p8_127/NREL-2p8-127_DISCON.IN @@ -1,10 +1,10 @@ ! Controller parameter input file for the NREL-2p8-127 wind turbine -! - File written using ROSCO version 2.8.0 controller tuning logic on 01/05/24 +! - File written using ROSCO version 2.9.0 controller tuning logic on 05/10/24 !------- SIMULATION CONTROL ------------------------------------------------------------ 2 ! LoggingLevel - {0: write no debug files, 1: write standard output .dbg-file, 2: LoggingLevel 1 + ROSCO LocalVars (.dbg2) 3: LoggingLevel 2 + complete avrSWAP-array (.dbg3)} 0 ! DT_Out - {Time step to output .dbg* files, or 0 to match sampling period of OpenFAST} -1 ! Ext_Interface - (0 - use standard bladed interface, 1 - Use the extened DLL interface introduced in OpenFAST 3.5.0.) +1 ! Ext_Interface - (0 - use standard bladed interface, 1 - Use the extened DLL interface introduced in OpenFAST 3.5.0.) 0 ! Echo - (0 - no Echo, 1 - Echo input data to .echo) !------- CONTROLLER FLAGS ------------------------------------------------- @@ -91,6 +91,13 @@ 8.25 ! VS_TSRopt - Power-maximizing region 2 tip-speed-ratio. Only used in VS_ControlMode = 2. 0.314000000000 ! VS_PwrFiltF - Low pass filter on power used to determine generator speed set point. Only used in VS_ControlMode = 3. +!------- FIXED PITCH REGION 3 TORQUE CONTROL ------------------------------------------------ +0 ! FBP_RefMode - Reference control mode (0 - Use wind speed estimator, 1 - Use torque feedback) +60 ! FBP_n - Number of gain-scheduling table entries +3.000000 3.289655 3.579310 3.868966 4.158621 4.448276 4.737931 5.027586 5.317241 5.606897 5.896552 6.186207 6.475862 6.765517 7.055172 7.344828 7.634483 7.924138 8.213793 8.503448 8.793103 9.082759 9.372414 9.662069 9.951724 10.241379 10.531034 10.820690 11.110345 11.400000 11.853333 12.306667 12.760000 13.213333 13.666667 14.120000 14.573333 15.026667 15.480000 15.933333 16.386667 16.840000 17.293333 17.746667 18.200000 18.653333 19.106667 19.560000 20.013333 20.466667 20.920000 21.373333 21.826667 22.280000 22.733333 23.186667 23.640000 24.093333 24.546667 25.000000 ! FBP_U - Operating schedule table: Wind speeds [m/s]. +37.815619 41.466782 45.117946 48.769109 52.420272 56.071435 59.722599 63.373762 67.024925 70.676088 74.327252 77.978415 81.629578 85.280741 88.931905 92.583068 96.234231 99.885394 103.536557 107.187721 110.838884 114.490047 118.141210 121.792374 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 ! FBP_Omega - Operating schedule table: Generator speeds [rad/s]. +2637.346056 3171.212635 3754.251136 4386.461558 5067.843901 5798.398167 6578.124354 7407.022463 8285.092494 9212.334446 10188.748320 11214.334116 12289.091834 13413.021473 14586.123034 15808.396517 17079.841921 18400.459247 19770.248495 21189.209665 22657.342756 24174.647769 25741.124704 27356.773561 29584.316737 32095.342171 34687.873109 37276.821338 39798.060940 42179.037757 42179.037757 42179.037757 42179.037757 42179.037757 42179.037757 42179.037757 42179.037757 42179.037757 42179.037757 42179.037757 42179.037757 42179.037757 42179.037757 42179.037757 42179.037757 42179.037757 42179.037757 42179.037757 42179.037757 42179.037757 42179.037757 42179.037757 42179.037757 42179.037757 42179.037757 42179.037757 42179.037757 42179.037757 42179.037757 42179.037757 ! FBP_Tau - Operating schedule table: Generator torques [N m]. + !------- SETPOINT SMOOTHER --------------------------------------------- 1.00000 ! SS_VSGain - Variable speed torque controller setpoint smoother gain, [-]. 0.00100 ! SS_PCGain - Collective pitch controller setpoint smoother gain, [-]. From 8c57a3161224623f7f42c28ceb00fa5fdbdb8bc0 Mon Sep 17 00:00:00 2001 From: dzalkind Date: Fri, 10 May 2024 10:42:41 -0600 Subject: [PATCH 142/224] Remove extra RefSpd localvars --- rosco/controller/rosco_registry/rosco_types.yaml | 6 ------ 1 file changed, 6 deletions(-) diff --git a/rosco/controller/rosco_registry/rosco_types.yaml b/rosco/controller/rosco_registry/rosco_types.yaml index 936112ba..6f888f81 100644 --- a/rosco/controller/rosco_registry/rosco_types.yaml +++ b/rosco/controller/rosco_registry/rosco_types.yaml @@ -1037,12 +1037,6 @@ LocalVariables: RotSpeedF: <<: *real description: Filtered LSS (generator) speed [rad/s]. - VS_RefSpd: - <<: *real - description: Generator speed set point of torque controller [rad/s] - PC_RefSpd: - <<: *real - description: Generator speed set point of pitch controller [rad/s] GenSpeedF: <<: *real description: Filtered HSS (generator) speed [rad/s]. From de4f6a7755e214154b4d8ddfda6f871833ec6a89 Mon Sep 17 00:00:00 2001 From: David Stockhouse Date: Fri, 10 May 2024 11:33:49 -0600 Subject: [PATCH 143/224] Added overspeed config option and expanded Cp surface again --- Examples/29_marine_hydro_fbp.py | 15 +++++ .../Test_Cases/MHK_RM1/MHK_RM1_Cp_Ct_Cq.txt | 64 ++++++++++++++++++- rosco/toolbox/controller.py | 21 +++--- rosco/toolbox/inputs/toolbox_schema.yaml | 10 ++- rosco/toolbox/turbine.py | 2 +- 5 files changed, 97 insertions(+), 15 deletions(-) diff --git a/Examples/29_marine_hydro_fbp.py b/Examples/29_marine_hydro_fbp.py index ad0a082f..fabed8bc 100644 --- a/Examples/29_marine_hydro_fbp.py +++ b/Examples/29_marine_hydro_fbp.py @@ -76,6 +76,21 @@ def main(): fig.suptitle('Constant Power') + controller_params['FBP_speed_mode'] = 1 + controller = ROSCO_controller.Controller(controller_params) + controller.tune_controller(turbine) + + fig, axs = plt.subplots(3,1) + axs[0].plot(controller.v, controller.power_op, label='Gen Power') + axs[0].set_xlabel('Gen Power [W]') + axs[1].plot(controller.v, controller.omega_gen_op, label='Gen Speed') + axs[0].set_xlabel('Gen Speed [rad/s]') + axs[2].plot(controller.v, controller.tau_op ,label='Gen Torque') + axs[0].set_xlabel('Gen Torque [N m]') + fig.suptitle('Constant Power Overspeed') + + + controller_params['FBP_speed_mode'] = 0 controller_params['FBP_P'] = [1.0, 2.0] controller = ROSCO_controller.Controller(controller_params) controller.tune_controller(turbine) diff --git a/Examples/Test_Cases/MHK_RM1/MHK_RM1_Cp_Ct_Cq.txt b/Examples/Test_Cases/MHK_RM1/MHK_RM1_Cp_Ct_Cq.txt index fab56c49..58e2f6aa 100644 --- a/Examples/Test_Cases/MHK_RM1/MHK_RM1_Cp_Ct_Cq.txt +++ b/Examples/Test_Cases/MHK_RM1/MHK_RM1_Cp_Ct_Cq.txt @@ -3,8 +3,8 @@ # Pitch angle vector, 36 entries - x axis (matrix columns) (deg) -5.0 -4.0 -3.0 -2.0 -1.0 0.0 1.0 2.0 3.0 4.0 5.0 6.0 7.0 8.0 9.0 10.0 11.0 12.0 13.0 14.0 15.0 16.0 17.0 18.0 19.0 20.0 21.0 22.0 23.0 24.0 25.0 26.0 27.0 28.0 29.0 30.0 -# TSR vector, 29 entries - y axis (matrix rows) (-) -0.5 1.0 1.5 2.0 2.5 3.0 3.5 4.0 4.5 5.0 5.5 6.0 6.5 7.0 7.5 8.0 8.5 9.0 9.5 10.0 10.5 11.0 11.5 12.0 12.5 13.0 13.5 14.0 14.5 +# TSR vector, 49 entries - y axis (matrix rows) (-) +0.5 1.0 1.5 2.0 2.5 3.0 3.5 4.0 4.5 5.0 5.5 6.0 6.5 7.0 7.5 8.0 8.5 9.0 9.5 10.0 10.5 11.0 11.5 12.0 12.5 13.0 13.5 14.0 14.5 15.0 15.5 16.0 16.5 17.0 17.5 18.0 18.5 19.0 19.5 20.0 20.5 21.0 21.5 22.0 22.5 23.0 23.5 24.0 24.5 # Wind speed vector - z axis (m/s) 2.0 @@ -39,6 +39,26 @@ -0.081402 -0.011084 0.084719 0.170780 0.235516 0.279325 0.291430 0.238459 0.115549 -0.073102 -0.321911 -0.625607 -0.978304 -1.372825 -1.800455 -2.252662 -2.722014 -3.201819 -3.686067 -4.169483 -4.647592 -5.116778 -5.574329 -6.018473 -6.448391 -6.864217 -7.267005 -7.658683 -8.041964 -8.420242 -8.797460 -9.177853 -9.564925 -9.961118 -10.368394 -10.788407 -0.110596 -0.052701 0.042985 0.137076 0.207782 0.254403 0.265323 0.204705 0.066567 -0.144218 -0.421331 -0.758794 -1.149895 -1.586432 -2.058651 -2.557350 -3.074456 -3.602663 -4.135416 -4.666984 -5.192537 -5.708199 -6.211107 -6.699437 -7.172428 -7.630363 -8.074545 -8.507225 -8.931510 -9.351238 -9.770823 -10.194907 -10.627142 -11.070095 -11.525849 -11.996178 -0.136894 -0.091028 0.000152 0.101257 0.178137 0.227520 0.236784 0.167598 0.012868 -0.221802 -0.529332 -0.902987 -1.335157 -1.816539 -2.336332 -2.884638 -3.452688 -4.032515 -4.616992 -5.199912 -5.776070 -6.341325 -6.892656 -7.428198 -7.947252 -8.450276 -8.938837 -9.415541 -9.883917 -10.348275 -10.813529 -11.284725 -11.765654 -12.259021 -12.767035 -13.291606 +-0.161485 -0.125436 -0.043034 0.063293 0.146516 0.198584 0.205701 0.126991 -0.045740 -0.306106 -0.646235 -1.058582 -1.534575 -2.063724 -2.634184 -3.235321 -3.857609 -4.492384 -5.131914 -5.769494 -6.399527 -7.017598 -7.620528 -8.206411 -8.774628 -9.325825 -9.861861 -10.385723 -10.901391 -11.413677 -11.928027 -12.449875 -12.983156 -13.530721 -14.094912 -14.677794 +-0.185017 -0.156903 -0.085926 0.023183 0.112849 0.167504 0.171960 0.082738 -0.109447 -0.397379 -0.772358 -1.225980 -1.748634 -2.328567 -2.952895 -3.610194 -4.290121 -4.983278 -5.681299 -6.376956 -7.064243 -7.738460 -8.396269 -9.035731 -9.656316 -10.258879 -10.845597 -11.419861 -11.986135 -12.549767 -13.116760 -13.692923 -14.282340 -14.888017 -15.512436 -16.157842 +-0.207893 -0.186547 -0.127763 -0.018990 0.077063 0.134187 0.135448 0.034693 -0.178447 -0.495871 -0.908024 -1.405580 -1.977819 -2.611650 -3.293157 -4.010051 -4.751125 -5.506207 -6.266266 -7.023523 -7.771551 -8.505352 -9.221428 -9.917811 -10.594077 -11.251307 -11.892019 -12.520042 -13.140353 -13.758865 -14.382168 -15.016432 -15.665895 -16.333725 -17.022564 -17.734849 +-0.230382 -0.215060 -0.167868 -0.063006 0.039084 0.098539 0.096051 -0.017290 -0.252930 -0.601833 -1.053552 -1.597784 -2.222617 -2.913559 -3.655658 -4.435687 -5.241523 -6.062180 -6.887932 -7.710424 -8.522786 -9.319716 -10.097552 -10.854305 -11.589669 -12.304975 -13.003104 -13.688353 -14.366244 -15.043290 -15.726690 -16.422961 -17.136507 -17.870661 -18.628250 -19.411908 +-0.252682 -0.242875 -0.206158 -0.108545 -0.001160 0.060470 0.053659 -0.073360 -0.333087 -0.715516 -1.209263 -1.802991 -2.483514 -3.234881 -4.041090 -4.887896 -5.762214 -6.652208 -7.547416 -8.438885 -9.319282 -10.182991 -11.026186 -11.846865 -12.644852 -13.421747 -14.180825 -14.926878 -15.666007 -16.405358 -17.152760 -17.915069 -18.696859 -19.501641 -20.332444 -21.192115 +-0.274940 -0.270296 -0.243126 -0.155317 -0.043738 0.019887 0.008157 -0.133659 -0.419111 -0.837170 -1.375480 -2.021604 -2.760996 -3.576206 -4.450143 -5.367474 -6.314103 -7.277299 -8.245836 -9.210130 -10.162371 -11.096617 -12.008877 -12.897142 -13.761382 -14.603488 -15.427154 -16.237701 -17.041839 -17.847383 -18.662814 -19.495312 -20.349633 -21.229477 -22.138097 -23.078562 +-0.297267 -0.297543 -0.279278 -0.203025 -0.088721 -0.023298 -0.040565 -0.198334 -0.511192 -0.967045 -1.552524 -2.254022 -3.055552 -3.938123 -4.883507 -5.875214 -6.898090 -7.938464 -8.984309 -10.025386 -11.053386 -12.062033 -13.047169 -14.006786 -14.941016 -15.852062 -16.744064 -17.622903 -18.495937 -19.371680 -20.259283 -21.166245 -22.097508 -23.056981 -24.048157 -25.074340 +-0.319756 -0.324785 -0.314994 -0.251336 -0.136174 -0.069177 -0.092618 -0.267530 -0.609520 -1.105393 -1.740716 -2.500649 -3.367669 -4.321222 -5.341874 -6.411913 -7.515077 -8.636713 -9.763954 -10.885878 -11.993659 -13.080677 -14.142607 -15.177448 -16.185510 -17.169331 -18.133526 -19.084568 -20.030494 -20.980560 -21.944599 -22.930420 -23.943163 -24.986965 -26.065570 -27.182541 +-0.342486 -0.352156 -0.350552 -0.299930 -0.186160 -0.117838 -0.148115 -0.341391 -0.714288 -1.252464 -1.940377 -2.761884 -3.697838 -4.726093 -5.825933 -6.978366 -8.165966 -9.373054 -10.585886 -11.792831 -12.984522 -14.153988 -15.296734 -16.410777 -17.496619 -18.557156 -19.597509 -20.624774 -21.647706 -22.676334 -23.721191 -24.790390 -25.889274 -27.022235 -28.193285 -29.406257 +-0.365517 -0.379764 -0.386165 -0.348610 -0.238723 -0.169370 -0.207164 -0.420064 -0.825685 -1.408508 -2.151829 -3.038129 -4.046550 -5.153325 -6.336375 -7.575367 -8.851658 -10.148497 -11.451224 -12.747468 -14.027306 -15.283403 -16.511095 -17.708423 -18.876098 -20.017400 -21.137982 -22.245601 -23.349764 -24.461312 -25.591487 -26.748705 -27.938521 -29.165602 -30.434246 -31.748578 +-0.388907 -0.407699 -0.421995 -0.397403 -0.293887 -0.223861 -0.269877 -0.503692 -0.943903 -1.573776 -2.375394 -3.329786 -4.414298 -5.603509 -6.873892 -8.203712 -9.573056 -10.964050 -12.361084 -13.751014 -15.123343 -16.470360 -17.787232 -19.072033 -20.325702 -21.551923 -22.756915 -23.949129 -25.138862 -26.337803 -27.557916 -28.807912 -30.093577 -31.419871 -32.791402 -34.212594 +-0.412704 -0.436038 -0.458173 -0.446469 -0.351640 -0.281399 -0.336362 -0.592417 -1.069131 -1.748518 -2.611392 -3.637255 -4.801576 -6.077233 -7.439173 -8.864196 -10.331060 -11.820723 -13.316582 -14.804693 -16.273962 -17.716295 -19.126688 -20.503256 -21.847182 -23.162584 -24.456275 -25.737435 -27.017190 -28.308116 -29.622905 -30.970560 -32.357117 -33.787851 -35.267697 -36.801395 +-0.436951 -0.464839 -0.494812 -0.495988 -0.411935 -0.342071 -0.406729 -0.686384 -1.201560 -1.932984 -2.860146 -3.960939 -5.208876 -6.575087 -8.032910 -9.557613 -11.126572 -12.719524 -14.318834 -15.909728 -17.480495 -19.022646 -20.531005 -22.003739 -23.442294 -24.851244 -26.238030 -27.612597 -28.986939 -30.374557 -31.788878 -33.239195 -34.731815 -36.272349 -37.866077 -39.518072 +-0.461689 -0.494158 -0.532007 -0.546122 -0.474710 -0.405964 -0.481088 -0.785735 -1.341379 -2.127424 -3.121975 -4.301239 -5.636693 -7.097661 -8.655793 -10.284759 -11.960492 -13.661461 -15.368957 -17.067343 -18.744272 -20.390848 -22.001725 -23.575130 -25.112790 -26.619762 -28.104146 -29.576691 -31.050299 -32.539434 -34.058262 -35.616366 -37.220345 -38.876171 -40.589487 -42.365713 +-0.486956 -0.524043 -0.569836 -0.597020 -0.539916 -0.473165 -0.559546 -0.890614 -1.488780 -2.332088 -3.397202 -4.658556 -6.085520 -7.645545 -9.308512 -11.046428 -12.833722 -14.647543 -16.468066 -18.278761 -20.066623 -21.822338 -23.540391 -25.219076 -26.860422 -28.469996 -30.056590 -31.631796 -33.209459 -34.805052 -36.433481 -38.104616 -39.825380 -41.602125 -43.440874 -45.347408 +-0.512784 -0.554538 -0.608367 -0.648797 -0.607491 -0.543760 -0.642214 -1.001162 -1.643950 -2.547226 -3.686147 -5.033293 -6.555849 -8.219328 -9.991758 -11.843415 -13.747162 -15.678776 -17.617276 -19.545205 -21.448877 -23.318552 -25.148542 -26.937223 -28.686942 -30.403804 -32.097329 -33.779985 -35.466610 -37.173716 -38.916958 -40.706492 -42.549593 -44.453016 -46.423181 -48.466246 +-0.539198 -0.585685 -0.647662 -0.701557 -0.677348 -0.617836 -0.729200 -1.117522 -1.807081 -2.773088 -3.989131 -5.425853 -7.048176 -8.819600 -10.706222 -12.676514 -14.701712 -16.756170 -18.817703 -20.867898 -22.892365 -24.880926 -26.827721 -28.731218 -30.594103 -32.423045 -34.228327 -36.023336 -37.823939 -39.647731 -41.511116 -43.424538 -45.395657 -47.431651 -49.539353 -51.725317 +-0.566221 -0.617522 -0.687783 -0.755395 -0.749411 -0.695478 -0.820611 -1.239835 -1.978361 -3.009922 -4.306475 -5.836637 -7.562991 -9.446950 -11.452593 -13.546519 -15.698273 -17.880731 -20.070462 -22.248062 -24.398415 -26.510894 -28.579469 -30.602707 -32.583655 -34.529576 -36.451550 -38.363923 -40.283635 -42.229402 -44.218377 -46.261298 -48.366245 -50.540836 -52.792336 -55.127707 +-0.593869 -0.650089 -0.728780 -0.810398 -0.823619 -0.776774 -0.916557 -1.368245 -2.157980 -3.257980 -4.638501 -6.266047 -8.100790 -10.101968 -12.231561 -14.454224 -16.737746 -19.053467 -21.376669 -23.686920 -25.968356 -28.209892 -30.405326 -32.553337 -34.657351 -36.725256 -38.768964 -40.803822 -42.847886 -44.921032 -47.041161 -49.219317 -51.464030 -53.783377 -56.185074 -58.676508 +-0.622165 -0.683415 -0.770696 -0.866646 -0.899917 -0.861806 -1.017144 -1.502892 -2.346127 -3.517509 -4.985530 -6.714488 -8.662066 -10.785242 -13.043818 -15.400424 -17.821030 -20.275386 -22.737438 -25.185693 -27.603519 -29.979356 -32.306833 -34.584752 -36.816940 -39.011940 -41.182533 -43.345107 -45.518879 -47.724925 -49.981890 -52.301140 -54.691684 -57.162081 -59.720511 -62.374806 # Thrust coefficient @@ -72,6 +92,26 @@ 1.669291 1.547849 1.384739 1.217210 1.060936 0.917330 0.772961 0.595418 0.385404 0.149891 -0.103328 -0.368089 -0.638801 -0.909809 -1.175300 -1.430972 -1.674058 -1.902444 -2.114442 -2.308732 -2.484344 -2.640648 -2.777344 -2.894473 -2.992413 -3.071882 -3.133945 -3.180009 -3.211811 -3.231403 -3.241117 -3.243426 -3.240082 -3.231892 -3.219278 -3.202440 1.687687 1.578468 1.415356 1.238011 1.071907 0.919357 0.765720 0.576060 0.350715 0.097847 -0.173830 -0.457519 -0.747054 -1.036194 -1.318729 -1.590355 -1.848224 -2.090113 -2.314243 -2.519235 -2.704087 -2.868167 -3.011201 -3.133281 -3.234864 -3.316779 -3.380226 -3.426774 -3.458348 -3.477208 -3.485910 -3.487089 -3.482447 -3.472747 -3.458375 -3.439503 1.701820 1.603482 1.444239 1.258233 1.082143 0.920461 0.757212 0.554935 0.313634 0.042765 -0.248020 -0.551261 -0.860196 -1.167977 -1.468050 -1.756112 -2.029205 -2.284986 -2.521586 -2.737565 -2.931895 -3.103939 -3.253453 -3.380585 -3.485876 -3.570270 -3.635111 -3.682138 -3.713474 -3.731594 -3.739286 -3.739329 -3.733359 -3.722099 -3.705898 -3.684905 +1.713122 1.622861 1.470818 1.277892 1.091686 0.920680 0.747476 0.532070 0.274183 -0.015336 -0.325877 -0.649297 -0.978211 -1.305142 -1.623263 -1.928248 -2.217007 -2.487071 -2.736479 -2.963735 -3.167780 -3.347978 -3.504116 -3.636401 -3.745465 -3.832373 -3.898619 -3.946123 -3.977210 -3.994582 -4.001267 -4.000160 -3.992830 -3.979957 -3.961852 -3.938653 +1.722385 1.637961 1.494703 1.296974 1.100572 0.920048 0.736544 0.507489 0.232382 -0.076438 -0.407386 -0.751612 -1.101082 -1.447681 -1.784369 -2.106768 -2.411635 -2.696374 -2.958933 -3.197755 -3.411754 -3.600297 -3.763203 -3.900744 -4.013647 -4.103104 -4.170768 -4.218746 -4.249575 -4.266193 -4.271871 -4.269598 -4.260871 -4.246328 -4.226244 -4.200749 +1.730104 1.650091 1.515469 1.315406 1.108833 0.918594 0.724439 0.481208 0.188245 -0.140528 -0.492535 -0.858193 -1.228796 -1.595589 -1.951373 -2.291678 -2.613097 -2.912904 -3.188955 -3.439634 -3.663828 -3.860908 -4.030727 -4.173627 -4.290435 -4.382478 -4.451574 -4.500023 -4.530585 -4.546442 -4.551113 -4.547654 -4.537490 -4.521216 -4.499076 -4.471196 +1.736615 1.660057 1.532828 1.333014 1.116494 0.916339 0.711182 0.453240 0.141785 -0.207596 -0.581312 -0.969030 -1.361345 -1.748866 -2.124280 -2.482982 -2.821397 -3.136667 -3.426553 -3.689382 -3.924012 -4.129820 -4.306699 -4.455061 -4.575843 -4.670508 -4.741049 -4.789968 -4.820256 -4.835345 -4.839006 -4.834338 -4.822695 -4.804627 -4.780352 -4.749996 +1.742159 1.668364 1.546971 1.349563 1.123580 0.913306 0.696789 0.423594 0.093010 -0.277631 -0.673709 -1.084115 -1.498717 -1.907512 -2.303093 -2.680686 -3.036541 -3.367669 -3.671736 -3.947007 -4.192314 -4.407043 -4.591127 -4.745057 -4.869880 -4.967206 -5.039205 -5.088594 -5.118600 -5.132914 -5.135561 -5.129659 -5.116492 -5.096562 -5.070074 -5.037150 +1.746913 1.675360 1.558522 1.364868 1.130110 0.909512 0.681275 0.392280 0.041930 -0.350626 -0.769720 -1.203441 -1.640908 -2.071530 -2.487816 -2.884794 -3.258536 -3.605918 -3.924510 -4.212516 -4.468743 -4.692585 -4.884022 -5.043624 -5.172556 -5.272581 -5.346055 -5.395912 -5.425628 -5.439162 -5.440786 -5.433623 -5.418883 -5.397025 -5.368243 -5.332657 +1.751012 1.681296 1.568053 1.378780 1.136101 0.904971 0.664649 0.359305 -0.011450 -0.426577 -0.869338 -1.327002 -1.787910 -2.240923 -2.678452 -3.095309 -3.487385 -3.851419 -4.184881 -4.485916 -4.753305 -4.986454 -5.185391 -5.350771 -5.483881 -5.586643 -5.661607 -5.711933 -5.741351 -5.754099 -5.754692 -5.746236 -5.729872 -5.706017 -5.674861 -5.636518 +1.754563 1.686359 1.575983 1.391148 1.141560 0.899698 0.646922 0.324673 -0.067123 -0.505477 -0.972560 -1.454794 -1.939720 -2.415695 -2.875007 -3.312237 -3.723095 -4.104177 -4.452856 -4.767213 -5.046007 -5.288657 -5.495242 -5.666505 -5.803863 -5.909400 -5.985870 -6.036665 -6.065778 -6.077733 -6.077283 -6.067504 -6.049460 -6.023541 -5.989927 -5.948735 +1.757652 1.690686 1.582610 1.401846 1.146493 0.893703 0.628101 0.288388 -0.125087 -0.587323 -1.079381 -1.586812 -2.096336 -2.595848 -3.077482 -3.535582 -3.965669 -4.364198 -4.728440 -5.056414 -5.346855 -5.599199 -5.813580 -5.990834 -6.132508 -6.240861 -6.318851 -6.370116 -6.398918 -6.410073 -6.408567 -6.397430 -6.377651 -6.349596 -6.313442 -6.269306 +1.760346 1.694385 1.588159 1.410834 1.150900 0.886996 0.608192 0.250452 -0.185338 -0.672113 -1.189798 -1.723053 -2.257759 -2.781386 -3.285882 -3.765348 -4.215112 -4.631486 -5.011637 -5.353522 -5.655855 -5.918088 -6.140412 -6.323762 -6.469824 -6.581031 -6.660560 -6.712294 -6.740777 -6.751127 -6.748548 -6.736016 -6.714446 -6.684184 -6.645406 -6.598233 +1.762697 1.697544 1.592792 1.418221 1.154773 0.879585 0.587200 0.210867 -0.247873 -0.759843 -1.303809 -1.863515 -2.423989 -2.972311 -3.500209 -4.001537 -4.471429 -4.906046 -5.302453 -5.658544 -5.973011 -6.245327 -6.475743 -6.665297 -6.815816 -6.929918 -7.011000 -7.063205 -7.091362 -7.100899 -7.097231 -7.083266 -7.059845 -7.027305 -6.985820 -6.935516 +1.764745 1.700237 1.596634 1.424199 1.158085 0.871479 0.565130 0.169636 -0.312691 -0.850512 -1.421411 -2.008194 -2.595030 -3.168625 -3.720467 -4.244155 -4.734623 -5.187882 -5.600890 -5.971482 -6.298328 -6.580922 -6.819579 -7.015443 -7.170490 -7.287526 -7.370179 -7.422855 -7.450679 -7.459397 -7.454620 -7.439179 -7.413850 -7.378958 -7.334683 -7.281155 +1.766529 1.702520 1.599786 1.428959 1.160792 0.862682 0.541986 0.126760 -0.379790 -0.944118 -1.542603 -2.157089 -2.770883 -3.370332 -3.946659 -4.493203 -5.004696 -5.476996 -5.906954 -6.292341 -6.631809 -6.924876 -7.171924 -7.374205 -7.533850 -7.653862 -7.738102 -7.791250 -7.818734 -7.826624 -7.820719 -7.803759 -7.776461 -7.739145 -7.691996 -7.635150 +1.768082 1.704441 1.602333 1.432658 1.162852 0.853202 0.517771 0.082240 -0.449168 -1.040659 -1.667383 -2.310198 -2.951550 -3.577434 -4.178788 -4.748686 -5.281654 -5.773393 -6.220647 -6.621125 -6.973459 -7.277194 -7.532781 -7.741588 -7.905902 -8.028929 -8.114773 -8.168394 -8.195530 -8.202586 -8.195529 -8.177005 -8.147677 -8.107865 -8.057760 -7.997502 +1.769432 1.706040 1.604343 1.435432 1.164229 0.843042 0.492486 0.036077 -0.520826 -1.140135 -1.795750 -2.467521 -3.137033 -3.789933 -4.416855 -5.010606 -5.565498 -6.077075 -6.541973 -6.957836 -7.323281 -7.637879 -7.902156 -8.117595 -8.286649 -8.412732 -8.500197 -8.554291 -8.581074 -8.587286 -8.579053 -8.558918 -8.527500 -8.485119 -8.431974 -8.368210 +1.770603 1.707352 1.605872 1.437379 1.164898 0.832206 0.466134 -0.011729 -0.594761 -1.242544 -1.927703 -2.629056 -3.327334 -4.007831 -4.660865 -5.278965 -5.856231 -6.388046 -6.870934 -7.302478 -7.681278 -8.006935 -8.280050 -8.502230 -8.676096 -8.805275 -8.894378 -8.948947 -8.975368 -8.980727 -8.971294 -8.949500 -8.915929 -8.870906 -8.814639 -8.747275 +1.771610 1.708402 1.606970 1.438582 1.164823 0.820699 0.438715 -0.061177 -0.670974 -1.347887 -2.063241 -2.794805 -3.522455 -4.231131 -4.910818 -5.553766 -6.153856 -6.706307 -7.207533 -7.655054 -8.047454 -8.384365 -8.666468 -8.895496 -9.074245 -9.206561 -9.297319 -9.352364 -9.378416 -9.382912 -9.372252 -9.348749 -9.312964 -9.265228 -9.205755 -9.134697 +1.772463 1.709214 1.607681 1.439111 1.163974 0.808521 0.410230 -0.112267 -0.749464 -1.456162 -2.202364 -2.964766 -3.722397 -4.459835 -5.166718 -5.835012 -6.458374 -7.031861 -7.551773 -8.015566 -8.421810 -8.770171 -9.061412 -9.297397 -9.481100 -9.616594 -9.709024 -9.764545 -9.790221 -9.793844 -9.781927 -9.756667 -9.718606 -9.668084 -9.605321 -9.530476 +1.773175 1.709804 1.608035 1.439026 1.162332 0.795677 0.380680 -0.164999 -0.830231 -1.567369 -2.345071 -3.138939 -3.927163 -4.693944 -5.428566 -6.122703 -6.769789 -7.364711 -7.903655 -8.384016 -8.804350 -9.164357 -9.464885 -9.707935 -9.896663 -10.035376 -10.129496 -10.185494 -10.210786 -10.213525 -10.200322 -10.173253 -10.132855 -10.079474 -10.013338 -9.934612 +1.773757 1.710189 1.608058 1.438380 1.159881 0.782169 0.350066 -0.219373 -0.913276 -1.681508 -2.491361 -3.317326 -4.136754 -4.933461 -5.696364 -6.416843 -7.088101 -7.704857 -8.263183 -8.760407 -9.195075 -9.566924 -9.876890 -10.127113 -10.320938 -10.462911 -10.558737 -10.615214 -10.640114 -10.641957 -10.627435 -10.598507 -10.555711 -10.499398 -10.429807 -10.347105 # Torque coefficient @@ -105,4 +145,24 @@ -0.006030 -0.000821 0.006275 0.012650 0.017446 0.020691 0.021587 0.017664 0.008559 -0.005415 -0.023845 -0.046341 -0.072467 -0.101691 -0.133367 -0.166864 -0.201631 -0.237172 -0.273042 -0.308851 -0.344266 -0.379021 -0.412913 -0.445813 -0.477659 -0.508460 -0.538297 -0.567310 -0.595701 -0.623722 -0.651664 -0.679841 -0.708513 -0.737861 -0.768029 -0.799141 -0.007900 -0.003764 0.003070 0.009791 0.014842 0.018172 0.018952 0.014622 0.004755 -0.010301 -0.030095 -0.054200 -0.082135 -0.113317 -0.147046 -0.182668 -0.219604 -0.257333 -0.295387 -0.333356 -0.370895 -0.407729 -0.443650 -0.478531 -0.512316 -0.545026 -0.576753 -0.607659 -0.637965 -0.667946 -0.697916 -0.728208 -0.759082 -0.790721 -0.823275 -0.856870 -0.009441 -0.006278 0.000010 0.006983 0.012285 0.015691 0.016330 0.011558 0.000887 -0.015297 -0.036506 -0.062275 -0.092080 -0.125279 -0.161126 -0.198941 -0.238116 -0.278104 -0.318413 -0.358615 -0.398350 -0.437333 -0.475356 -0.512290 -0.548086 -0.582778 -0.616472 -0.649348 -0.681649 -0.713674 -0.745761 -0.778257 -0.811424 -0.845450 -0.880485 -0.916662 +-0.010766 -0.008362 -0.002869 0.004220 0.009768 0.013239 0.013713 0.008466 -0.003049 -0.020407 -0.043082 -0.070572 -0.102305 -0.137582 -0.175612 -0.215688 -0.257174 -0.299492 -0.342128 -0.384633 -0.426635 -0.467840 -0.508035 -0.547094 -0.584975 -0.621722 -0.657457 -0.692382 -0.726759 -0.760912 -0.795202 -0.829992 -0.865544 -0.902048 -0.939661 -0.978520 +-0.011937 -0.010123 -0.005544 0.001496 0.007281 0.010807 0.011094 0.005338 -0.007061 -0.025637 -0.049830 -0.079095 -0.112815 -0.150230 -0.190509 -0.232916 -0.276782 -0.321502 -0.366535 -0.411416 -0.455758 -0.499255 -0.541695 -0.582950 -0.622988 -0.661863 -0.699716 -0.736765 -0.773299 -0.809662 -0.846243 -0.883414 -0.921441 -0.960517 -1.000802 -1.042441 +-0.012993 -0.011659 -0.007985 -0.001187 0.004816 0.008387 0.008465 0.002168 -0.011153 -0.030992 -0.056751 -0.087849 -0.123614 -0.163228 -0.205822 -0.250628 -0.296945 -0.344138 -0.391642 -0.438970 -0.485722 -0.531585 -0.576339 -0.619863 -0.662130 -0.703207 -0.743251 -0.782503 -0.821272 -0.859929 -0.898886 -0.938527 -0.979118 -1.020858 -1.063910 -1.108428 +-0.013963 -0.013034 -0.010174 -0.003819 0.002369 0.005972 0.005821 -0.001048 -0.015329 -0.036475 -0.063852 -0.096835 -0.134704 -0.176579 -0.221555 -0.268830 -0.317668 -0.367405 -0.417450 -0.467298 -0.516532 -0.564831 -0.611973 -0.657837 -0.702404 -0.745756 -0.788067 -0.829597 -0.870681 -0.911715 -0.953133 -0.995331 -1.038576 -1.083070 -1.128985 -1.176479 +-0.014864 -0.014287 -0.012127 -0.006385 -0.000068 0.003557 0.003156 -0.004315 -0.019593 -0.042089 -0.071133 -0.106058 -0.146089 -0.190287 -0.237711 -0.287523 -0.338954 -0.391306 -0.443966 -0.496405 -0.548193 -0.598999 -0.648599 -0.696874 -0.743815 -0.789515 -0.834166 -0.878052 -0.921530 -0.965021 -1.008986 -1.053828 -1.099815 -1.147155 -1.196026 -1.246595 +-0.015711 -0.015445 -0.013893 -0.008875 -0.002499 0.001136 0.000466 -0.007638 -0.023949 -0.047838 -0.078599 -0.115520 -0.157771 -0.204355 -0.254294 -0.306713 -0.360806 -0.415846 -0.471191 -0.526293 -0.580707 -0.634092 -0.686222 -0.736980 -0.786365 -0.834485 -0.881552 -0.927869 -0.973819 -1.019850 -1.066447 -1.114018 -1.162836 -1.213113 -1.265034 -1.318775 +-0.016515 -0.016530 -0.015515 -0.011279 -0.004929 -0.001294 -0.002254 -0.011019 -0.028400 -0.053725 -0.086251 -0.125223 -0.169753 -0.218785 -0.271306 -0.326401 -0.383227 -0.441026 -0.499128 -0.556966 -0.614077 -0.670113 -0.724843 -0.778155 -0.830056 -0.880670 -0.930226 -0.979050 -1.027552 -1.076204 -1.125516 -1.175902 -1.227639 -1.280943 -1.336009 -1.393019 +-0.017284 -0.017556 -0.017027 -0.013586 -0.007361 -0.003739 -0.005006 -0.014461 -0.032947 -0.059751 -0.094093 -0.135170 -0.182036 -0.233580 -0.288750 -0.346590 -0.406220 -0.466849 -0.527781 -0.588426 -0.648306 -0.707064 -0.764465 -0.820403 -0.874892 -0.928072 -0.980191 -1.031598 -1.082729 -1.134084 -1.186195 -1.239482 -1.294225 -1.350647 -1.408950 -1.469327 +-0.018026 -0.018535 -0.018450 -0.015786 -0.009798 -0.006202 -0.007796 -0.017968 -0.037594 -0.065919 -0.102125 -0.145362 -0.194623 -0.248742 -0.306628 -0.367282 -0.429788 -0.493319 -0.557152 -0.620675 -0.683396 -0.744947 -0.805091 -0.863725 -0.920875 -0.976692 -1.031448 -1.085514 -1.139353 -1.193491 -1.248484 -1.304757 -1.362593 -1.422223 -1.483857 -1.547698 +-0.018744 -0.019475 -0.019803 -0.017877 -0.012242 -0.008686 -0.010624 -0.021542 -0.042343 -0.072231 -0.110350 -0.155801 -0.207515 -0.264273 -0.324942 -0.388480 -0.453931 -0.520436 -0.587242 -0.653716 -0.719349 -0.783764 -0.846723 -0.908124 -0.968005 -1.026533 -1.083999 -1.140800 -1.197424 -1.254426 -1.312384 -1.371728 -1.432745 -1.495672 -1.560731 -1.628132 +-0.019445 -0.020385 -0.021100 -0.019870 -0.014694 -0.011193 -0.013494 -0.025185 -0.047195 -0.078689 -0.118770 -0.166489 -0.220715 -0.280175 -0.343695 -0.410186 -0.478653 -0.548203 -0.618054 -0.687551 -0.756167 -0.823518 -0.889362 -0.953602 -1.016285 -1.077596 -1.137846 -1.197456 -1.256943 -1.316890 -1.377896 -1.440396 -1.504679 -1.570994 -1.639570 -1.710630 +-0.020132 -0.021270 -0.022350 -0.021779 -0.017153 -0.013727 -0.016408 -0.028898 -0.052153 -0.085294 -0.127385 -0.177427 -0.234223 -0.296450 -0.362887 -0.432400 -0.503954 -0.576621 -0.649589 -0.722180 -0.793852 -0.864210 -0.933009 -1.000159 -1.065716 -1.129882 -1.192989 -1.255485 -1.317912 -1.380884 -1.445020 -1.510759 -1.578396 -1.648188 -1.720375 -1.795190 +-0.020807 -0.022135 -0.023562 -0.023618 -0.019616 -0.016289 -0.019368 -0.032685 -0.057217 -0.092047 -0.136197 -0.188616 -0.248042 -0.313099 -0.382520 -0.455124 -0.529837 -0.605692 -0.681849 -0.757606 -0.832405 -0.905840 -0.977667 -1.047797 -1.116300 -1.183393 -1.249430 -1.314886 -1.380330 -1.446407 -1.513756 -1.582819 -1.653896 -1.727255 -1.803147 -1.881813 +-0.021474 -0.022984 -0.024745 -0.025401 -0.022080 -0.018882 -0.022376 -0.036546 -0.062390 -0.098950 -0.145208 -0.200058 -0.262172 -0.330124 -0.402595 -0.478361 -0.556302 -0.635417 -0.714835 -0.793830 -0.871827 -0.948412 -1.023336 -1.096518 -1.168037 -1.238128 -1.307170 -1.375660 -1.444200 -1.513462 -1.584105 -1.656575 -1.731179 -1.808194 -1.887883 -1.970498 +-0.022134 -0.023820 -0.025902 -0.027137 -0.024542 -0.021507 -0.025434 -0.040482 -0.067672 -0.106004 -0.154418 -0.211753 -0.276615 -0.347525 -0.423114 -0.502110 -0.583351 -0.665797 -0.748548 -0.830853 -0.912119 -0.991924 -1.070018 -1.146322 -1.220928 -1.294091 -1.366209 -1.437809 -1.509521 -1.582048 -1.656067 -1.732028 -1.810245 -1.891006 -1.974585 -2.061246 +-0.022790 -0.024646 -0.027039 -0.028835 -0.027000 -0.024167 -0.028543 -0.044496 -0.073064 -0.113210 -0.163829 -0.223702 -0.291371 -0.365303 -0.444078 -0.526374 -0.610985 -0.696834 -0.782990 -0.868676 -0.953283 -1.036380 -1.117713 -1.197210 -1.274975 -1.351280 -1.426548 -1.501333 -1.576294 -1.652165 -1.729643 -1.809177 -1.891093 -1.975690 -2.063252 -2.154055 +-0.023443 -0.025465 -0.028159 -0.030502 -0.029450 -0.026862 -0.031704 -0.048588 -0.078569 -0.120569 -0.173440 -0.235907 -0.306442 -0.383461 -0.465488 -0.551153 -0.639205 -0.728529 -0.818161 -0.907300 -0.995320 -1.081779 -1.166423 -1.249183 -1.330178 -1.409698 -1.488188 -1.566232 -1.644519 -1.723814 -1.804831 -1.888023 -1.973724 -2.062246 -2.153885 -2.248927 +-0.024094 -0.026278 -0.029267 -0.032144 -0.031890 -0.029595 -0.034920 -0.052759 -0.084186 -0.128082 -0.183254 -0.248368 -0.321829 -0.401998 -0.487344 -0.576448 -0.668012 -0.760882 -0.854062 -0.946726 -1.038230 -1.128123 -1.216148 -1.302243 -1.386539 -1.469344 -1.551130 -1.632507 -1.714197 -1.796996 -1.881633 -1.968566 -2.058138 -2.150674 -2.246482 -2.345860 +-0.024745 -0.027087 -0.030366 -0.033767 -0.034317 -0.032366 -0.038190 -0.057010 -0.089916 -0.135749 -0.193271 -0.261085 -0.337533 -0.420915 -0.509648 -0.602259 -0.697406 -0.793894 -0.890695 -0.986955 -1.082015 -1.175412 -1.266889 -1.356389 -1.444056 -1.530219 -1.615374 -1.700159 -1.785329 -1.871710 -1.960048 -2.050805 -2.144335 -2.240974 -2.341045 -2.444854 +-0.025394 -0.027895 -0.031457 -0.035373 -0.036731 -0.035176 -0.041516 -0.061343 -0.095760 -0.143572 -0.203491 -0.274061 -0.353554 -0.440214 -0.532401 -0.628589 -0.727389 -0.827567 -0.928059 -1.027987 -1.126674 -1.223647 -1.318646 -1.411623 -1.502732 -1.592324 -1.680920 -1.769188 -1.857913 -1.947956 -2.040077 -2.134740 -2.232314 -2.333146 -2.437572 -2.545910 diff --git a/rosco/toolbox/controller.py b/rosco/toolbox/controller.py index 37582c54..6a462a70 100644 --- a/rosco/toolbox/controller.py +++ b/rosco/toolbox/controller.py @@ -103,7 +103,8 @@ def __init__(self, controller_params): if self.VS_ControlMode == 4: try: self.fbp_ref_mode = controller_params['FBP_ref_mode'] - self.fbp_P_mode = controller_params['FBP_P_mode'] + self.fbp_power_mode = controller_params['FBP_power_mode'] + self.fbp_speed_mode = controller_params['FBP_speed_mode'] self.fbp_U = controller_params['FBP_U'] # Should we set this default based on rated speed? self.fbp_P = controller_params['FBP_P'] except: @@ -250,7 +251,7 @@ def tune_controller(self, turbine): # Begin with user-defined power curve f_P_user_defined = interpolate.interp1d(self.fbp_U, self.fbp_P, fill_value=(self.fbp_P[0], self.fbp_P[-1]), bounds_error=False) P_user_defined = f_P_user_defined(v) - if self.fbp_P_mode == 0: + if self.fbp_power_mode == 0: P_user_defined *= turbine.rated_power P_max = 0.5 * turbine.rho * np.pi*turbine.rotor_radius**2 * turbine.Cp.max * v**3 * turbine.GBoxEff/100 * turbine.GenEff/100 P_op = np.min([P_user_defined, P_max], axis=0) @@ -261,15 +262,15 @@ def tune_controller(self, turbine): # Identify TSR matching the Cp values Cp_FBP = np.ndarray.flatten(turbine.Cp.interp_surface(0, turbine.TSR_initial)) # all Cp values for fine blade pitch (assumed 0) Cp_maxidx = Cp_FBP.argmax() - # if underspeed - Cp_op = np.clip(Cp_op, np.min(Cp_FBP[:Cp_maxidx+1]), np.max(Cp_FBP[:Cp_maxidx+1])) # saturate Cp values to be on Cp surface # Find maximum Cp value for this TSR - f_cp_TSR = interpolate.interp1d(Cp_FBP[:Cp_maxidx+1], turbine.TSR_initial[:Cp_maxidx+1]) # interpolate function for Cp(tsr) values - # if overspeed - # Cp_op = np.clip(Cp_op, np.min(Cp_FBP[Cp_maxidx:]), np.max(Cp_FBP[Cp_maxidx:])) # saturate Cp values to be on Cp surface # Find maximum Cp value for this TSR - # f_cp_TSR = interpolate.interp1d(Cp_FBP[Cp_maxidx:], turbine.TSR_initial[Cp_maxidx:]) # interpolate function for Cp(tsr) values + if self.fbp_speed_mode: # Overspeed + Cp_op = np.clip(Cp_op, np.min(Cp_FBP[Cp_maxidx:]), np.max(Cp_FBP[Cp_maxidx:])) # saturate Cp values to be on Cp surface # Find maximum Cp value for this TSR + f_cp_TSR = interpolate.interp1d(Cp_FBP[Cp_maxidx:], turbine.TSR_initial[Cp_maxidx:]) # interpolate function for Cp(tsr) values + else: # Underspeed + Cp_op = np.clip(Cp_op, np.min(Cp_FBP[:Cp_maxidx+1]), np.max(Cp_FBP[:Cp_maxidx+1])) # saturate Cp values to be on Cp surface # Find maximum Cp value for this TSR + f_cp_TSR = interpolate.interp1d(Cp_FBP[:Cp_maxidx+1], turbine.TSR_initial[:Cp_maxidx+1]) # interpolate function for Cp(tsr) values TSR_op = f_cp_TSR(Cp_op) - TSR_op_br = TSR_op[:len(v_below_rated)] - TSR_op_ar = TSR_op[len(v_below_rated):] + TSR_below_rated = TSR_op[:len(v_below_rated)] + TSR_above_rated = TSR_op[len(v_below_rated):] # initialize variables diff --git a/rosco/toolbox/inputs/toolbox_schema.yaml b/rosco/toolbox/inputs/toolbox_schema.yaml index 5ddfe7eb..35c78ae0 100644 --- a/rosco/toolbox/inputs/toolbox_schema.yaml +++ b/rosco/toolbox/inputs/toolbox_schema.yaml @@ -439,9 +439,15 @@ properties: description: Method of identifying operating point reference during operation (0- Use WSE, 1- Use filtered torque signal) minimum: 0 maximum: 1 - FBP_P_mode: + FBP_power_mode: type: number - description: Interpretation mode for P_FBP (0- scale relative to rated power, 1- absolute power) + description: Interpretation mode for FBP_P (0- scale relative to rated power, 1- absolute power) + default: 0 + minimum: 0 + maximum: 1 + FBP_speed_mode: + type: number + description: Overspeed or underspeed operating schedule (0- underspeed, 1- overspeed) default: 0 minimum: 0 maximum: 1 diff --git a/rosco/toolbox/turbine.py b/rosco/toolbox/turbine.py index 616c925d..6384d644 100644 --- a/rosco/toolbox/turbine.py +++ b/rosco/toolbox/turbine.py @@ -294,7 +294,7 @@ def load_from_ccblade(self): self.load_blade_info() # Generate the look-up tables, mesh the grid and flatten the arrays for cc_rotor aerodynamic analysis - TSR_initial = np.arange(0.5, 15, 0.5) + TSR_initial = np.arange(0.5, 25, 0.5) pitch_initial = np.arange(-5, 31, 1.) pitch_initial_rad = pitch_initial * deg2rad ws_array = np.ones_like(TSR_initial) * self.v_rated # evaluate at rated wind speed From ae07303fc92e27630307899cc019e57f505832c1 Mon Sep 17 00:00:00 2001 From: dzalkind Date: Fri, 10 May 2024 11:55:22 -0600 Subject: [PATCH 144/224] Add constants for various VS_Control modes --- rosco/controller/src/Constants.f90 | 9 +++++++++ rosco/controller/src/ControllerBlocks.f90 | 10 ++++++---- rosco/controller/src/Controllers.f90 | 10 ++++++---- rosco/controller/src/ReadSetParameters.f90 | 14 +++++++------- 4 files changed, 28 insertions(+), 15 deletions(-) diff --git a/rosco/controller/src/Constants.f90 b/rosco/controller/src/Constants.f90 index 56298879..2f9b7258 100644 --- a/rosco/controller/src/Constants.f90 +++ b/rosco/controller/src/Constants.f90 @@ -37,4 +37,13 @@ MODULE Constants CHARACTER(1), PARAMETER :: Tab = CHAR( 9 ) + ! Control Modes + + ! VS_ControlMode + INTEGER(IntKi), PARAMETER :: VS_Mode_Disabled = 0 + INTEGER(IntKi), PARAMETER :: VS_Mode_KOmega = 1 + INTEGER(IntKi), PARAMETER :: VS_Mode_WSE_TSR = 2 + INTEGER(IntKi), PARAMETER :: VS_Mode_Power_TSR = 3 + INTEGER(IntKi), PARAMETER :: VS_Mode_FBP = 4 + END MODULE Constants diff --git a/rosco/controller/src/ControllerBlocks.f90 b/rosco/controller/src/ControllerBlocks.f90 index 02b9a9c1..2da718de 100644 --- a/rosco/controller/src/ControllerBlocks.f90 +++ b/rosco/controller/src/ControllerBlocks.f90 @@ -60,12 +60,12 @@ SUBROUTINE ComputeVariablesSetpoints(CntrPar, LocalVar, objInst, DebugVar, ErrVa ! ----- Torque controller reference errors ----- ! Define VS reference generator speed [rad/s] - IF (CntrPar%VS_ControlMode == 2) THEN + IF (CntrPar%VS_ControlMode == VS_Mode_WSE_TSR) THEN LocalVar%VS_RefSpd_TSR = (CntrPar%VS_TSRopt * LocalVar%We_Vw_F / CntrPar%WE_BladeRadius) * CntrPar%WE_GearboxRatio - ELSEIF (CntrPar%VS_ControlMode == 3) THEN + ELSEIF (CntrPar%VS_ControlMode == VS_Mode_Power_TSR) THEN LocalVar%VS_GenPwrF = LPFilter(LocalVar%VS_GenPwr, LocalVar%DT, CntrPar%VS_PwrFiltF, LocalVar%FP, LocalVar%iStatus, LocalVar%restart, objInst%instLPF) LocalVar%VS_RefSpd_TSR = (LocalVar%VS_GenPwrF/CntrPar%VS_Rgn2K)**(1./3.) ! Genspeed reference that doesn't depend on wind speed estimate (https://doi.org/10.2172/1259805) - ELSEIF (CntrPar%VS_ControlMode == 4) THEN + ELSEIF (CntrPar%VS_ControlMode == VS_Mode_FBP) THEN IF (CntrPar%FBP_RefMode == 0) THEN ! Use WSE to look up speed reference VS_RefSpdRaw = interp1d(CntrPar%FBP_U, CntrPar%FBP_Omega, LocalVar%WE_Vw, ErrVar) @@ -112,7 +112,9 @@ SUBROUTINE ComputeVariablesSetpoints(CntrPar, LocalVar, objInst, DebugVar, ErrVa LocalVar%VS_RefSpd = max(LocalVar%VS_RefSpd, CntrPar%VS_MinOmSpd) ! Reference error - IF ((CntrPar%VS_ControlMode == 2) .OR. (CntrPar%VS_ControlMode == 3) .OR. (CntrPar%VS_ControlMode == 4)) THEN + IF ((CntrPar%VS_ControlMode == VS_Mode_WSE_TSR) .OR. \ + (CntrPar%VS_ControlMode == VS_Mode_Power_TSR) .OR. \ + (CntrPar%VS_ControlMode == VS_Mode_FBP)) THEN LocalVar%VS_SpdErr = LocalVar%VS_RefSpd - LocalVar%GenSpeedF ENDIF diff --git a/rosco/controller/src/Controllers.f90 b/rosco/controller/src/Controllers.f90 index 9fe102eb..6765acd3 100644 --- a/rosco/controller/src/Controllers.f90 +++ b/rosco/controller/src/Controllers.f90 @@ -50,7 +50,7 @@ SUBROUTINE PitchControl(avrSWAP, CntrPar, LocalVar, objInst, DebugVar, ErrVar) LocalVar%PC_MaxPit = CntrPar%PC_FinePit END IF - IF (CntrPar%VS_ControlMode .NE. 4) THEN + IF (CntrPar%VS_ControlMode .NE. VS_Mode_FBP) THEN ! Compute (interpolate) the gains based on previously commanded blade pitch angles and lookup table: LocalVar%PC_KP = interp1d(CntrPar%PC_GS_angles, CntrPar%PC_GS_KP, LocalVar%PC_PitComTF, ErrVar) ! Proportional gain LocalVar%PC_KI = interp1d(CntrPar%PC_GS_angles, CntrPar%PC_GS_KI, LocalVar%PC_PitComTF, ErrVar) ! Integral gain @@ -226,13 +226,15 @@ SUBROUTINE VariableSpeedControl(avrSWAP, CntrPar, LocalVar, objInst, ErrVar) ENDIF ! Optimal Tip-Speed-Ratio tracking controller - IF ((CntrPar%VS_ControlMode == 2) .OR. (CntrPar%VS_ControlMode == 3) .OR. (CntrPar%VS_ControlMode == 4)) THEN + IF ((CntrPar%VS_ControlMode == VS_Mode_WSE_TSR) .OR. \ + (CntrPar%VS_ControlMode == VS_Mode_Power_TSR) .OR. \ + (CntrPar%VS_ControlMode == VS_Mode_FBP)) THEN ! Constant Power, update VS_MaxTq IF (CntrPar%VS_ConstPower == 1) THEN LocalVar%VS_MaxTq = min((CntrPar%VS_RtPwr/(CntrPar%VS_GenEff/100.0))/LocalVar%GenSpeedF, CntrPar%VS_MaxTq) END IF - IF (CntrPar%VS_ControlMode == 4) THEN + IF (CntrPar%VS_ControlMode == VS_Mode_FBP) THEN ! DBS: In the future, look into combining FBP with constant power LocalVar%VS_MaxTq = CntrPar%VS_MaxTq END IF @@ -247,7 +249,7 @@ SUBROUTINE VariableSpeedControl(avrSWAP, CntrPar, LocalVar, objInst, ErrVar) LocalVar%GenTq = saturate(LocalVar%GenTq, CntrPar%VS_MinTq, LocalVar%VS_MaxTq) ! K*Omega^2 control law with PI torque control in transition regions - ELSEIF (CntrPar%VS_ControlMode == 1) THEN + ELSEIF (CntrPar%VS_ControlMode == VS_Mode_KOmega) THEN ! 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_MaxOMTq, LocalVar%piP, LocalVar%restart, objInst%instPI) LocalVar%GenBrTq = PIController(LocalVar%VS_SpdErrBr, CntrPar%VS_KP(1), CntrPar%VS_KI(1), CntrPar%VS_MinTq, CntrPar%VS_MinOMTq, LocalVar%DT, CntrPar%VS_MinOMTq, LocalVar%piP, LocalVar%restart, objInst%instPI) diff --git a/rosco/controller/src/ReadSetParameters.f90 b/rosco/controller/src/ReadSetParameters.f90 index 619e1dd9..2a22a9e6 100644 --- a/rosco/controller/src/ReadSetParameters.f90 +++ b/rosco/controller/src/ReadSetParameters.f90 @@ -221,7 +221,7 @@ SUBROUTINE SetParameters(avrSWAP, accINFILE, size_avcMSG, CntrPar, LocalVar, obj ! Setpoint Smoother initialization to zero LocalVar%SS_DelOmegaF = 0 - IF (CntrPar%VS_ControlMode < 4) THEN + IF (CntrPar%VS_ControlMode < VS_Mode_FBP) THEN ! Generator Torque at K omega^2 or rated IF (LocalVar%GenSpeed > 0.98 * CntrPar%PC_RefSpd) THEN LocalVar%GenTq = CntrPar%VS_RtTq @@ -440,11 +440,11 @@ SUBROUTINE ReadControlParameterFileSub(CntrPar, LocalVar, accINFILE, accINFILE_s IF (ErrVar%aviFAIL < 0) RETURN !------------ Fixed-Pitch Region 3 Control ------------ - CALL ParseInput(FileLines, 'FBP_RefMode', CntrPar%FBP_RefMode, accINFILE(1), ErrVar, CntrPar%VS_ControlMode < 4, UnEc) - CALL ParseInput(FileLines, 'FBP_n', CntrPar%FBP_n, accINFILE(1), ErrVar, CntrPar%VS_ControlMode < 4, UnEc) - CALL ParseAry( FileLines, 'FBP_U', CntrPar%FBP_U, CntrPar%FBP_n, accINFILE(1), ErrVar, CntrPar%VS_ControlMode < 4, UnEc) - CALL ParseAry( FileLines, 'FBP_Omega', CntrPar%FBP_Omega, CntrPar%FBP_n, accINFILE(1), ErrVar, CntrPar%VS_ControlMode < 4, UnEc) - CALL ParseAry( FileLines, 'FBP_Tau', CntrPar%FBP_Tau, CntrPar%FBP_n, accINFILE(1), ErrVar, CntrPar%VS_ControlMode < 4, UnEc) + CALL ParseInput(FileLines, 'FBP_RefMode', CntrPar%FBP_RefMode, accINFILE(1), ErrVar, CntrPar%VS_ControlMode .NE. VS_Mode_FBP, UnEc) + CALL ParseInput(FileLines, 'FBP_n', CntrPar%FBP_n, accINFILE(1), ErrVar, CntrPar%VS_ControlMode .NE. VS_Mode_FBP, UnEc) + CALL ParseAry( FileLines, 'FBP_U', CntrPar%FBP_U, CntrPar%FBP_n, accINFILE(1), ErrVar, CntrPar%VS_ControlMode .NE. VS_Mode_FBP, UnEc) + CALL ParseAry( FileLines, 'FBP_Omega', CntrPar%FBP_Omega, CntrPar%FBP_n, accINFILE(1), ErrVar, CntrPar%VS_ControlMode .NE. VS_Mode_FBP, UnEc) + CALL ParseAry( FileLines, 'FBP_Tau', CntrPar%FBP_Tau, CntrPar%FBP_n, accINFILE(1), ErrVar, CntrPar%VS_ControlMode .NE. VS_Mode_FBP, UnEc) IF (ErrVar%aviFAIL < 0) RETURN !------- Setpoint Smoother -------------------------------- @@ -1282,7 +1282,7 @@ SUBROUTINE CheckInputs(LocalVar, CntrPar, avrSWAP, ErrVar, size_avcMSG) ErrVar%ErrMsg = 'TRA_RateLimit must be greater than 0.' END IF - IF ( .NOT. ((CntrPar%VS_ControlMode == 2) .OR. (CntrPar%VS_ControlMode == 3) )) THEN + IF ( .NOT. ((CntrPar%VS_ControlMode == VS_Mode_WSE_TSR) .OR. (CntrPar%VS_ControlMode == VS_Mode_Power_TSR) )) THEN ErrVar%aviFAIL = -1 ErrVar%ErrMsg = 'VS_ControlMode must be 2 or 3 to use frequency avoidance control.' END IF From 2df9e54b23cd82e7135b4783185ca8cf5327c944 Mon Sep 17 00:00:00 2001 From: dzalkind Date: Fri, 10 May 2024 11:58:35 -0600 Subject: [PATCH 145/224] Regen registry --- rosco/controller/src/ROSCO_IO.f90 | 2 +- rosco/controller/src/ROSCO_Types.f90 | 10 +++++----- 2 files changed, 6 insertions(+), 6 deletions(-) diff --git a/rosco/controller/src/ROSCO_IO.f90 b/rosco/controller/src/ROSCO_IO.f90 index ab1ec3ea..a4f44283 100644 --- a/rosco/controller/src/ROSCO_IO.f90 +++ b/rosco/controller/src/ROSCO_IO.f90 @@ -945,4 +945,4 @@ SUBROUTINE Debug(LocalVar, CntrPar, DebugVar, ErrVar, avrSWAP, RootName, size_av ENDIF END SUBROUTINE Debug -END MODULE ROSCO_IO +END MODULE ROSCO_IO \ No newline at end of file diff --git a/rosco/controller/src/ROSCO_Types.f90 b/rosco/controller/src/ROSCO_Types.f90 index fbf73281..6f21a077 100644 --- a/rosco/controller/src/ROSCO_Types.f90 +++ b/rosco/controller/src/ROSCO_Types.f90 @@ -81,9 +81,9 @@ MODULE ROSCO_Types REAL(DbKi) :: VS_PwrFiltF ! Cut-off frequency of filter on generator power for power-based tsr tracking control INTEGER(IntKi) :: FBP_RefMode ! Fixed blade pitch reference interpolation mode (0 for WSE, 1 for torque feedback) INTEGER(IntKi) :: FBP_n ! Amount of fixed blade pitch operating schedule table entries - REAL(DbKi), DIMENSION(:), ALLOCATABLE :: FBP_U ! FBP Operating-schedule table - Wind speeds - REAL(DbKi), DIMENSION(:), ALLOCATABLE :: FBP_Omega ! FBP Operating-schedule table - Generator speeds - REAL(DbKi), DIMENSION(:), ALLOCATABLE :: FBP_Tau ! FBP Operating-schedule table - Generator torques + INTEGER(IntKi), DIMENSION(:), ALLOCATABLE :: FBP_U ! FBP Operating-schedule table - Wind speeds + INTEGER(IntKi), DIMENSION(:), ALLOCATABLE :: FBP_Omega ! FBP Operating-schedule table - Generator speeds + INTEGER(IntKi), DIMENSION(:), ALLOCATABLE :: FBP_Tau ! FBP Operating-schedule table - Generator torques INTEGER(IntKi) :: SS_Mode ! Setpoint Smoother mode {0 - no setpoint smoothing, 1 - introduce setpoint smoothing} REAL(DbKi) :: SS_VSGain ! Variable speed torque controller setpoint smoother gain, [-]. REAL(DbKi) :: SS_PCGain ! Collective pitch controller setpoint smoother gain, [-]. @@ -301,7 +301,7 @@ MODULE ROSCO_Types REAL(DbKi) :: PC_TF ! First-order filter parameter for derivative action REAL(DbKi) :: PC_MaxPit ! Maximum pitch setting in pitch controller (variable) [rad]. REAL(DbKi) :: PC_MinPit ! Minimum pitch setting in pitch controller (variable) [rad]. - REAL(DbKi) :: PC_PitComT ! Collective pitch commmand from PI control [rad]. + REAL(DbKi) :: PC_PitComT ! Total command pitch based on the sum of the proportional and integral terms [rad]. REAL(DbKi) :: PC_PitComT_Last ! Last total command pitch based on the sum of the proportional and integral terms [rad]. REAL(DbKi) :: PC_PitComTF ! Filtered Total command pitch based on the sum of the proportional and integral terms [rad]. REAL(DbKi) :: PC_PitComT_IPC(3) ! Total command pitch based on the sum of the proportional and integral terms, including IPC term [rad]. @@ -453,4 +453,4 @@ MODULE ROSCO_Types REAL(ReKi), DIMENSION(:), ALLOCATABLE :: avrSWAP ! The swap array- used to pass data to and from the DLL controller [see Bladed DLL documentation] END TYPE ExtControlType -END MODULE ROSCO_Types +END MODULE ROSCO_Types \ No newline at end of file From 8eab998f4b87521ef998821ea519cb0519d13ed5 Mon Sep 17 00:00:00 2001 From: David Stockhouse Date: Fri, 10 May 2024 12:05:56 -0600 Subject: [PATCH 146/224] Cleaned up fixed pitch example script --- Examples/29_marine_hydro_fbp.py | 223 +++++++++++++------------------- 1 file changed, 88 insertions(+), 135 deletions(-) diff --git a/Examples/29_marine_hydro_fbp.py b/Examples/29_marine_hydro_fbp.py index fabed8bc..90e8e008 100644 --- a/Examples/29_marine_hydro_fbp.py +++ b/Examples/29_marine_hydro_fbp.py @@ -16,6 +16,7 @@ from rosco.toolbox.utilities import write_DISCON from rosco.toolbox.inputs.validation import load_rosco_yaml import matplotlib.pyplot as plt +import numpy as np ''' Run MHK turbine in OpenFAST with ROSCO torque controller @@ -34,7 +35,7 @@ def main(): # Input yaml and output directory parameter_filename = os.path.join(this_dir, 'Tune_Cases/RM1_MHK_FBP.yaml') - param_dir = os.path.dirname(parameter_filename) + tune_dir = os.path.dirname(parameter_filename) run_dir = os.path.join(example_out_dir, '29_MHK/0_baseline') os.makedirs(run_dir,exist_ok=True) @@ -48,162 +49,114 @@ def main(): controller = ROSCO_controller.Controller(controller_params) # Load turbine data from OpenFAST and rotor performance text file - cp_filename = os.path.join(param_dir, path_params['rotor_performance_filename']) - if False: - turbine.load_from_fast( - path_params['FAST_InputFile'], - os.path.join(param_dir, path_params['FAST_directory']), - rot_source='cc-blade', txt_filename=cp_filename - ) - ROSCO_utilities.write_rotor_performance(turbine, cp_filename) - else: - turbine.load_from_fast( - path_params['FAST_InputFile'], - os.path.join(param_dir, path_params['FAST_directory']), - rot_source='txt', txt_filename= cp_filename - ) + cp_filename = os.path.join(tune_dir, path_params['rotor_performance_filename']) + turbine.load_from_fast( + path_params['FAST_InputFile'], + os.path.join(tune_dir, path_params['FAST_directory']), + rot_source='txt', txt_filename= cp_filename + ) - # Tune controller cases - controller.tune_controller(turbine) - - fig, axs = plt.subplots(3,1) - axs[0].plot(controller.v, controller.power_op, label='Gen Power') - axs[0].set_xlabel('Gen Power [W]') - axs[1].plot(controller.v, controller.omega_gen_op, label='Gen Speed') - axs[0].set_xlabel('Gen Speed [rad/s]') - axs[2].plot(controller.v, controller.tau_op ,label='Gen Torque') - axs[0].set_xlabel('Gen Torque [N m]') - fig.suptitle('Constant Power') + ### Tune controller cases + # Constant power underspeed + controller_params['FBP_speed_mode'] = 0 + controller_params['FBP_P'] = [1.0, 1.0] + controller_1 = ROSCO_controller.Controller(controller_params) + controller_1.tune_controller(turbine) + # Constant power overspeedspeed controller_params['FBP_speed_mode'] = 1 - controller = ROSCO_controller.Controller(controller_params) - controller.tune_controller(turbine) - - fig, axs = plt.subplots(3,1) - axs[0].plot(controller.v, controller.power_op, label='Gen Power') - axs[0].set_xlabel('Gen Power [W]') - axs[1].plot(controller.v, controller.omega_gen_op, label='Gen Speed') - axs[0].set_xlabel('Gen Speed [rad/s]') - axs[2].plot(controller.v, controller.tau_op ,label='Gen Torque') - axs[0].set_xlabel('Gen Torque [N m]') - fig.suptitle('Constant Power Overspeed') - + controller_params['FBP_P'] = [1.0, 1.0] + controller_2 = ROSCO_controller.Controller(controller_params) + controller_2.tune_controller(turbine) + # Linear increasing power controller_params['FBP_speed_mode'] = 0 controller_params['FBP_P'] = [1.0, 2.0] - controller = ROSCO_controller.Controller(controller_params) - controller.tune_controller(turbine) - - fig, axs = plt.subplots(3,1) - axs[0].plot(controller.v, controller.power_op, label='Gen Power') - axs[0].set_xlabel('Gen Power [W]') - axs[1].plot(controller.v, controller.omega_gen_op, label='Gen Speed') - axs[0].set_xlabel('Gen Speed [rad/s]') - axs[2].plot(controller.v, controller.tau_op ,label='Gen Torque') - axs[0].set_xlabel('Gen Torque [N m]') - fig.suptitle('Linear Increasing Power') - + controller_3 = ROSCO_controller.Controller(controller_params) + controller_3.tune_controller(turbine) + # Linear increasing power, leveling out controller_params['FBP_U'] = [2.0, 3.0] controller_params['FBP_P'] = [1.0, 2.0] - controller = ROSCO_controller.Controller(controller_params) - controller.tune_controller(turbine) + controller_4 = ROSCO_controller.Controller(controller_params) + controller_4.tune_controller(turbine) + fig, axs = plt.subplots(3,1) - axs[0].plot(controller.v, controller.power_op, label='Gen Power') - axs[0].set_xlabel('Gen Power [W]') - axs[1].plot(controller.v, controller.omega_gen_op, label='Gen Speed') - axs[0].set_xlabel('Gen Speed [rad/s]') - axs[2].plot(controller.v, controller.tau_op ,label='Gen Torque') - axs[0].set_xlabel('Gen Torque [N m]') - fig.suptitle('Linear Increasing Leveled Power') - - - if True: - # plt.show() - plt.show(block=False) - 0 + axs[0].plot(controller_1.v, controller_1.power_op, label='Constant Power Underspeed') + axs[0].plot(controller_2.v, controller_2.power_op, linestyle='--', label='Constant Power Overspeed') + axs[0].plot(controller_3.v, controller_3.power_op, label='Linear Increasing Power') + axs[0].plot(controller_4.v, controller_4.power_op, label='Increasing Leveled Power') + axs[0].set_ylabel('Gen Power [W]') + axs[1].plot(controller_1.v, controller_1.omega_gen_op, label='Constant Power Underspeed') + axs[1].plot(controller_2.v, controller_2.omega_gen_op, linestyle='--', label='Constant Power Overspeed') + axs[1].plot(controller_3.v, controller_3.omega_gen_op, label='Linear Increasing Power') + axs[1].plot(controller_4.v, controller_4.omega_gen_op, label='Increasing Leveled Power') + axs[1].set_ylabel('Gen Speed [rad/s]') + axs[2].plot(controller_1.v, controller_1.tau_op, label='Constant Power Underspeed') + axs[2].plot(controller_2.v, controller_2.tau_op, linestyle='--', label='Constant Power Overspeed') + axs[2].plot(controller_3.v, controller_3.tau_op, label='Linear Increasing Power') + axs[2].plot(controller_4.v, controller_4.tau_op, label='Increasing Leveled Power') + axs[2].set_ylabel('Gen Torque [N m]') + axs[2].set_xlabel('Flow Speed [m/s]') + axs[0].legend(loc='upper left') + + if False: + plt.show() else: - plt.savefig(os.path.join(example_out_dir,'29_marine_hydro_fbp_sched.png')) + fig_fname = os.path.join(example_out_dir, '29_marine_hydro_fbp_sched.png') + print('Saving figure ' + fig_fname) + plt.savefig(fig_fname) - # Write parameter input file + # Write parameter input file for constant power underspeed controller param_file = os.path.join(run_dir,'DISCON.IN') write_DISCON(turbine, - controller, + controller_1, param_file=param_file, txt_filename=cp_filename ) - # # Plot operating schedule - # fig, ax = plt.subplots(2,2,constrained_layout=True,sharex=True) - # ax = ax.flatten() - # ax[0].plot(controller.v[len(controller.v_below_rated)+1:], controller.omega_pc_U) - # ax[0].set_ylabel('omega_pc') - # ax[1].plot(controller.v[len(controller.v_below_rated)+1:], controller.zeta_pc_U) - # ax[1].set_ylabel('zeta_pc') - - # ax[2].plot(controller.v[len(controller.v_below_rated)+1:], controller.pc_gain_schedule.Kp) - # ax[2].set_xlabel('Wind Speed') - # ax[2].set_ylabel('Proportional Gain') - - # ax[3].plot(controller.v[len(controller.v_below_rated)+1:], controller.pc_gain_schedule.Ki) - # ax[3].set_xlabel('Wind Speed') - # ax[3].set_ylabel('Integral Gain') - - # plt.suptitle('Pitch Controller Gains') - - - # # simulation set up - # r = run_FAST_ROSCO() - # r.tuning_yaml = parameter_filename - # # r.wind_case_fcn = cl.simp_step # single step wind input - # r.wind_case_fcn = cl.power_curve - # r.wind_case_opts = { - # 'U': [3.5], - # 'TMax': 100.0, - # } - # r.case_inputs = {} - # # r.fst_vt = reader.fst_vt - # # r.controller_params = controller_params - # r.save_dir = run_dir - # r.rosco_dir = rosco_dir - - # r.run_FAST() - - # op = output_processing.output_processing() - # fast_out = op.load_fast_out([os.path.join(run_dir,'RM1_MHK_FBP/power_curve/base/RM1_MHK_FBP_0.out')], tmin=0) - # fig, axs = plt.subplots(4,1) - # axs[0].plot(fast_out[0]['Time'],fast_out[0]['Wind1VelX'],label='Flow Speed') - # axs[1].plot(fast_out[0]['Time'],fast_out[0]['GenSpeed'],label='Gen Speed') - # axs[2].plot(fast_out[0]['Time'],fast_out[0]['GenTq'],label='Gen Torque') - # axs[3].plot(fast_out[0]['Time'],fast_out[0]['GenPwr'],label='Gen Power') - - - # op = output_processing.output_processing() - # op2 = output_processing.output_processing() - - # md_out = op.load_fast_out([os.path.join(run_dir,'IEA15MW_cable/power_curve/base/IEA15MW_cable_0.MD.Line1.out')], tmin=0) - # local_vars = op2.load_fast_out([os.path.join(run_dir,'IEA15MW_cable/power_curve/base/IEA15MW_cable_0.RO.dbg2')], tmin=0) - - # fig, axs = plt.subplots(4,1) - # axs[0].plot(local_vars[0]['Time'],local_vars[0]['CC_DesiredL'],label='CC_DesiredL') - # axs[1].plot(local_vars[0]['Time'],local_vars[0]['CC_ActuatedL'],label='CC_ActuatedL') - # axs[2].plot(local_vars[0]['Time'],local_vars[0]['CC_ActuatedDL'],label='CC_ActuatedDL') - # axs[3].plot(md_out[0]['Time'],md_out[0]['Seg20Lst'],label='Seg20Lst') - - # [a.legend() for a in axs] - # [a.grid() for a in axs] - - # if False: - # plt.show() - # else: - # plt.savefig(os.path.join(example_out_dir,'22_cable_control.png')) - - # # Check that the last segment of line 1 shrinks by 10 m - # # np.testing.assert_almost_equal(md_out[0]['Seg20Lst'][-1] - md_out[0]['Seg20Lst'][0], line_ends[0], 2) + # simulation set up + # TODO: simulate multiple controller configurations in parallel + r = run_FAST_ROSCO() + r.tuning_yaml = parameter_filename + # r.wind_case_fcn = cl.simp_step # single step wind input + r.wind_case_fcn = cl.power_curve + r.wind_case_opts = { + 'U': [3.0], + 'TMax': 60.0, + } + r.case_inputs = {} + # r.fst_vt = reader.fst_vt + # r.controller_params = controller_params + r.save_dir = run_dir + r.rosco_dir = rosco_dir + + r.run_FAST() + + op = output_processing.output_processing() + fast_out = op.load_fast_out([os.path.join(run_dir,'RM1_MHK_FBP/power_curve/base/RM1_MHK_FBP_0.out')], tmin=0) + fig, axs = plt.subplots(4,1) + axs[0].plot(fast_out[0]['Time'], fast_out[0]['Wind1VelX'], label='Constant Power Underspeed') + axs[0].set_ylabel('Flow Speed [m/s]') + axs[1].plot(fast_out[0]['Time'], fast_out[0]['GenSpeed'] * 2*np.pi/60, label='Constant Power Underspeed') + axs[1].set_ylabel('Gen Speed [rad/s]') + axs[2].plot(fast_out[0]['Time'], fast_out[0]['GenTq'] * 1e3, label='Constant Power Underspeed') + axs[2].set_ylabel('Gen Torque [N m]') + axs[3].plot(fast_out[0]['Time'], fast_out[0]['GenPwr'] * 1e3, label='Constant Power Underspeed') + axs[3].set_ylabel('Gen Power [W]') + axs[3].set_xlabel('Time [s]') + + # TODO: Compare result to desired operating schedule + if False: + plt.show() + else: + fig_fname = os.path.join(example_out_dir, '29_marine_hydro_fbp_sim.png') + print('Saving figure ' + fig_fname) + plt.savefig(fig_fname) if __name__=="__main__": From 1008cc65becf3667ce1f627df3b711a831da4bf2 Mon Sep 17 00:00:00 2001 From: David Stockhouse Date: Mon, 13 May 2024 12:24:42 -0600 Subject: [PATCH 147/224] Added comments to fixed pitch controller tuning, rearranged torque controller reference filtering approach, in the process of renaming generator speed filter frequency parameter --- Examples/29_marine_hydro_fbp.py | 2 +- .../rosco_registry/rosco_types.yaml | 6 +- rosco/controller/src/ControllerBlocks.f90 | 31 +++-- rosco/controller/src/Controllers.f90 | 16 +-- rosco/controller/src/ReadSetParameters.f90 | 2 +- rosco/toolbox/controller.py | 107 +++++++++++------- 6 files changed, 89 insertions(+), 75 deletions(-) diff --git a/Examples/29_marine_hydro_fbp.py b/Examples/29_marine_hydro_fbp.py index 90e8e008..af9752fe 100644 --- a/Examples/29_marine_hydro_fbp.py +++ b/Examples/29_marine_hydro_fbp.py @@ -64,7 +64,7 @@ def main(): controller_1 = ROSCO_controller.Controller(controller_params) controller_1.tune_controller(turbine) - # Constant power overspeedspeed + # Constant power overspeed controller_params['FBP_speed_mode'] = 1 controller_params['FBP_P'] = [1.0, 1.0] controller_2 = ROSCO_controller.Controller(controller_params) diff --git a/rosco/controller/rosco_registry/rosco_types.yaml b/rosco/controller/rosco_registry/rosco_types.yaml index 936112ba..b0caa136 100644 --- a/rosco/controller/rosco_registry/rosco_types.yaml +++ b/rosco/controller/rosco_registry/rosco_types.yaml @@ -158,6 +158,9 @@ ControlParameters: <<: *real description: Corner frequency (-3dB point) in the second order low pass filter of the blade root bending moment for flap control [rad/s]. allocatable: True + F_VSRefSpdCornerFreq: + <<: *real + description: Corner frequency (-3dB point) in the first order low pass filter of the generator speed reference used for TSR tracking torque control [rad/s]. # Tower fore-aft damping TRA_Mode: @@ -315,9 +318,6 @@ ControlParameters: VS_TSRopt: <<: *real description: Power-maximizing region 2 tip-speed ratio [rad] - VS_PwrFiltF: - <<: *real - description: Cut-off frequency of filter on generator power for power-based tsr tracking control # Setpoint Smoother SS_Mode: diff --git a/rosco/controller/src/ControllerBlocks.f90 b/rosco/controller/src/ControllerBlocks.f90 index 02b9a9c1..e53ccb40 100644 --- a/rosco/controller/src/ControllerBlocks.f90 +++ b/rosco/controller/src/ControllerBlocks.f90 @@ -61,29 +61,26 @@ SUBROUTINE ComputeVariablesSetpoints(CntrPar, LocalVar, objInst, DebugVar, ErrVa ! ----- Torque controller reference errors ----- ! Define VS reference generator speed [rad/s] IF (CntrPar%VS_ControlMode == 2) THEN - LocalVar%VS_RefSpd_TSR = (CntrPar%VS_TSRopt * LocalVar%We_Vw_F / CntrPar%WE_BladeRadius) * CntrPar%WE_GearboxRatio - ELSEIF (CntrPar%VS_ControlMode == 3) THEN - LocalVar%VS_GenPwrF = LPFilter(LocalVar%VS_GenPwr, LocalVar%DT, CntrPar%VS_PwrFiltF, LocalVar%FP, LocalVar%iStatus, LocalVar%restart, objInst%instLPF) - LocalVar%VS_RefSpd_TSR = (LocalVar%VS_GenPwrF/CntrPar%VS_Rgn2K)**(1./3.) ! Genspeed reference that doesn't depend on wind speed estimate (https://doi.org/10.2172/1259805) - ELSEIF (CntrPar%VS_ControlMode == 4) THEN - IF (CntrPar%FBP_RefMode == 0) THEN - ! Use WSE to look up speed reference + ! LocalVar%VS_RefSpd_TSR = (CntrPar%VS_TSRopt * LocalVar%We_Vw_F / CntrPar%WE_BladeRadius) * CntrPar%WE_GearboxRatio + ! Use unfiltered wind speed estimate, then filter below + LocalVar%VS_RefSpd_TSR = (CntrPar%VS_TSRopt * LocalVar%WE_Vw / CntrPar%WE_BladeRadius) * CntrPar%WE_GearboxRatio + + ELSEIF (CntrPar%VS_ControlMode == 3) THEN ! Genspeed reference that doesn't depend on wind speed estimate (https://doi.org/10.2172/1259805) + LocalVar%VS_RefSpd_TSR = (LocalVar%VS_GenPwr/CntrPar%VS_Rgn2K)**(1./3.) + + ELSEIF (CntrPar%VS_ControlMode == 4) THEN ! Generic lookup table for genspeed reference + IF (CntrPar%FBP_RefMode == 0) THEN ! Use WSE to look up speed reference VS_RefSpdRaw = interp1d(CntrPar%FBP_U, CntrPar%FBP_Omega, LocalVar%WE_Vw, ErrVar) - ELSEIF (CntrPar%FBP_RefMode == 1) THEN - ! Use LocalVar%GenTq or LocalVar%GenTqMeas, Omega must be expressed as a function of Tau + ELSEIF (CntrPar%FBP_RefMode == 1) THEN ! Use LocalVar%GenTq or LocalVar%GenTqMeas, Omega must be expressed as a function of Tau VS_RefSpdRaw = interp1d(CntrPar%FBP_Tau, CntrPar%FBP_Omega, LocalVar%GenTq, ErrVar) ENDIF - ! VS_RefSpdRaw = (LocalVar%GenTq/CntrPar%VS_Rgn2K)**(1./2.) ! WSE-independent below-rated generator speed reference based on torque instead of power - ! VS_RefSpdRaw = min(VS_RefSpdRaw, (CntrPar%VS_RtPwr/(CntrPar%VS_GenEff/100.0))/LocalVar%GenTq) ! Above-rated underspeed reference - ! VS_RefSpdRaw = min(VS_RefSpdRaw, CntrPar%VS_RefSpd) ! Saturate to rated speed - - LocalVar%VS_RefSpd_TSR = LPFilter(VS_RefSpdRaw, LocalVar%DT, CntrPar%VS_PwrFiltF, LocalVar%FP, LocalVar%iStatus, LocalVar%restart, objInst%instLPF) - ELSE + ELSE ! Generate constant reference LocalVar%VS_RefSpd_TSR = CntrPar%VS_RefSpd ENDIF - LocalVar%VS_RefSpd = LocalVar%VS_RefSpd_TSR + ! Filter reference signal + LocalVar%VS_RefSpd = LPFilter(LocalVar%VS_RefSpd_TSR, LocalVar%DT, CntrPar%VS_RefSpdFiltF, LocalVar%FP, LocalVar%iStatus, LocalVar%restart, objInst%instLPF) ! Exclude reference speeds specified by user IF (CntrPar%TRA_Mode > 0) THEN @@ -111,7 +108,7 @@ SUBROUTINE ComputeVariablesSetpoints(CntrPar, LocalVar, objInst, DebugVar, ErrVa ! Force minimum rotor speed LocalVar%VS_RefSpd = max(LocalVar%VS_RefSpd, CntrPar%VS_MinOmSpd) - ! Reference error + ! Compute speed error from reference IF ((CntrPar%VS_ControlMode == 2) .OR. (CntrPar%VS_ControlMode == 3) .OR. (CntrPar%VS_ControlMode == 4)) THEN LocalVar%VS_SpdErr = LocalVar%VS_RefSpd - LocalVar%GenSpeedF ENDIF diff --git a/rosco/controller/src/Controllers.f90 b/rosco/controller/src/Controllers.f90 index 9fe102eb..66827702 100644 --- a/rosco/controller/src/Controllers.f90 +++ b/rosco/controller/src/Controllers.f90 @@ -244,14 +244,13 @@ SUBROUTINE VariableSpeedControl(avrSWAP, CntrPar, LocalVar, objInst, ErrVar) CntrPar%VS_KI(1), & CntrPar%VS_MinTq, LocalVar%VS_MaxTq, & LocalVar%DT, LocalVar%VS_LastGenTrq, LocalVar%piP, LocalVar%restart, objInst%instPI) - LocalVar%GenTq = saturate(LocalVar%GenTq, CntrPar%VS_MinTq, LocalVar%VS_MaxTq) ! K*Omega^2 control law with PI torque control in transition regions ELSEIF (CntrPar%VS_ControlMode == 1) THEN ! 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_MaxOMTq, LocalVar%piP, LocalVar%restart, objInst%instPI) LocalVar%GenBrTq = PIController(LocalVar%VS_SpdErrBr, CntrPar%VS_KP(1), CntrPar%VS_KI(1), CntrPar%VS_MinTq, CntrPar%VS_MinOMTq, LocalVar%DT, CntrPar%VS_MinOMTq, LocalVar%piP, LocalVar%restart, objInst%instPI) - + ! The action IF (LocalVar%VS_State == 1) THEN ! Region 1.5 LocalVar%GenTq = LocalVar%GenBrTq @@ -264,20 +263,17 @@ SUBROUTINE VariableSpeedControl(avrSWAP, CntrPar, LocalVar, objInst, ErrVar) ELSEIF (LocalVar%VS_State == 5) THEN ! Region 3, constant power LocalVar%GenTq = (CntrPar%VS_RtPwr/(CntrPar%VS_GenEff/100.0))/LocalVar%GenSpeedF END IF - - ! Saturate - LocalVar%GenTq = saturate(LocalVar%GenTq, CntrPar%VS_MinTq, CntrPar%VS_MaxTq) + ELSE ! VS_ControlMode of 0 LocalVar%GenTq = 0 ENDIF + ! Saturate based on most stringent defined maximum + LocalVar%GenTq = saturate(LocalVar%GenTq, CntrPar%VS_MinTq, MIN(CntrPar%VS_MaxTq, LocalVar%VS_MaxTq)) - ! Saturate the commanded torque using the maximum torque limit: - LocalVar%GenTq = MIN(LocalVar%GenTq, CntrPar%VS_MaxTq) ! Saturate the command using the maximum torque limit - - ! Saturate the commanded torque using the torque rate limit: + ! Saturate the commanded torque using the torque rate limit LocalVar%GenTq = ratelimit(LocalVar%GenTq, -CntrPar%VS_MaxRat, CntrPar%VS_MaxRat, LocalVar%DT, LocalVar%restart, LocalVar%rlP,objInst%instRL) ! Saturate the command using the torque rate limit - + ! Open loop torque control IF ((CntrPar%OL_Mode > 0) .AND. (CntrPar%Ind_GenTq > 0)) THEN ! Get current OL GenTq, applies for OL_Mode 1 and 2 diff --git a/rosco/controller/src/ReadSetParameters.f90 b/rosco/controller/src/ReadSetParameters.f90 index 619e1dd9..5f1fb073 100644 --- a/rosco/controller/src/ReadSetParameters.f90 +++ b/rosco/controller/src/ReadSetParameters.f90 @@ -234,7 +234,7 @@ SUBROUTINE SetParameters(avrSWAP, accINFILE, size_avcMSG, CntrPar, LocalVar, obj ENDIF LocalVar%VS_LastGenTrq = LocalVar%GenTq LocalVar%VS_MaxTq = CntrPar%VS_MaxTq - LocalVar%VS_GenPwr = LocalVar%GenTq * LocalVar%GenSpeed + LocalVar%VS_GenPwr = LocalVar%GenTq * LocalVar%GenSpeed * CntrPar%VS_GenEff/100.0 ! Initialize variables LocalVar%CC_DesiredL = 0 diff --git a/rosco/toolbox/controller.py b/rosco/toolbox/controller.py index 6a462a70..8bbafcba 100644 --- a/rosco/toolbox/controller.py +++ b/rosco/toolbox/controller.py @@ -101,32 +101,39 @@ def __init__(self, controller_params): # Optional parameters without defaults if self.VS_ControlMode == 4: - try: + + # Fail if generator torque enabled in Region 3 but pitch control not disabled (may enable these modes to operate together in the future) + if self.PC_ControlMode != 0: + raise Exception( + 'rosco.toolbox:controller: PC_ControlMode must be 0 if VS_ControlMode == 4') + + if 'FBP_ref_mode' in controller_params: self.fbp_ref_mode = controller_params['FBP_ref_mode'] - self.fbp_power_mode = controller_params['FBP_power_mode'] - self.fbp_speed_mode = controller_params['FBP_speed_mode'] - self.fbp_U = controller_params['FBP_U'] # Should we set this default based on rated speed? - self.fbp_P = controller_params['FBP_P'] - except: + else: raise Exception( 'rosco.toolbox:controller: FBP options (FBP_ref_mode) must be set if VS_ControlMode == 4') + + # Defaults to constant power, underspeed + self.fbp_power_mode = controller_params['FBP_power_mode'] + self.fbp_speed_mode = controller_params['FBP_speed_mode'] + self.fbp_U = controller_params['FBP_U'] # Should we set this default based on rated speed? + self.fbp_P = controller_params['FBP_P'] else: self.fbp_ref_mode = 0 - if self.Flp_Mode > 0: - try: + if 'flp_kp_norm' in controller_params and 'flp_tau' in controller_params: self.flp_kp_norm = controller_params['flp_kp_norm'] self.flp_tau = controller_params['flp_tau'] - except: + else: raise Exception( 'rosco.toolbox:controller: flp_kp_norm and flp_tau must be set if Flp_Mode > 0') if self.Fl_Mode > 0: - try: + if 'twr_freq' in controller_params and 'ptfm_freq' in controller_params: self.twr_freq = controller_params['twr_freq'] self.ptfm_freq = controller_params['ptfm_freq'] - except: + else: raise Exception('rosco.toolbox:controller: twr_freq and ptfm_freq must be set if Fl_Mode > 0') # Kp_float direct setting @@ -229,49 +236,58 @@ def tune_controller(self, turbine): v_above_rated = np.linspace(turbine.v_rated,turbine.v_max, num=self.PC_GS_n+1) # above rated v = np.concatenate((v_below_rated, v_above_rated)) - if self.VS_ControlMode < 4: - # separate TSRs by operations regions - TSR_below_rated = [min(turbine.TSR_operational, rated_rotor_speed*R/v) for v in v_below_rated] # below rated - TSR_above_rated = rated_rotor_speed*R/v_above_rated # above rated - TSR_op = np.concatenate((TSR_below_rated, TSR_above_rated)) # operational TSRs - - # Find expected operational Cp values - Cp_above_rated = turbine.Cp.interp_surface(0,TSR_above_rated[0]) # Cp during rated operation (not optimal). Assumes cut-in bld pitch to be 0 - Cp_op_br = np.ones(len(v_below_rated)) * turbine.Cp.max # below rated - Cp_op_ar = Cp_above_rated * (TSR_above_rated/TSR_rated)**3 # above rated - Cp_op = np.concatenate((Cp_op_br, Cp_op_ar)) # operational CPs to linearize around + # Construct power schedule differently based on pitch control configuration + if self.VS_ControlMode == 4: # If using torque control in Region 3 - else: - # Check if blade pitch control disabled (may be implemented to work concurrently in the future) - if self.PC_ControlMode != 0: - raise Exception("PC_ControlMode must be 0 when VS_ControlMode == 4") + # Check if constant power control disabled (may be implemented to work concurrently in the future) if self.VS_ConstPower != 0: raise Exception("VS_ConstPower must be 0 when VS_ControlMode == 4") - # Begin with user-defined power curve + # Begin with user-defined power curve from input yaml (default constant rated power) f_P_user_defined = interpolate.interp1d(self.fbp_U, self.fbp_P, fill_value=(self.fbp_P[0], self.fbp_P[-1]), bounds_error=False) P_user_defined = f_P_user_defined(v) if self.fbp_power_mode == 0: P_user_defined *= turbine.rated_power - P_max = 0.5 * turbine.rho * np.pi*turbine.rotor_radius**2 * turbine.Cp.max * v**3 * turbine.GBoxEff/100 * turbine.GenEff/100 + # Maximum potential power from MPPT (extending Region 2 power curve to cut-out) + P_max = 0.5 * turbine.rho * np.pi*turbine.rotor_radius**2 * turbine.Cp.max * v**3 \ + * turbine.GBoxEff/100 * turbine.GenEff/100 # Includes generator efficiency reduction from available inflow power + # Take minimum P_op = np.min([P_user_defined, P_max], axis=0) - Cp_op = P_op / P_max * turbine.Cp.max + # Operation along Cp surface (with fixed pitch) + Cp_op = (P_op / P_max) * turbine.Cp.max Cp_op_br = Cp_op[:len(v_below_rated)] Cp_op_ar = Cp_op[len(v_below_rated):] - # Identify TSR matching the Cp values + # Identify TSR matching the Cp values (similar to variable pitch angle interpolation below) Cp_FBP = np.ndarray.flatten(turbine.Cp.interp_surface(0, turbine.TSR_initial)) # all Cp values for fine blade pitch (assumed 0) - Cp_maxidx = Cp_FBP.argmax() + Cp_maxidx = Cp_FBP.argmax() + # When we depart from Cp_max, our TSR has to fall to either above or below TSR_opt, leading to overspeed and underspeed configurations if self.fbp_speed_mode: # Overspeed + # Interpolate inverse Cp surface slice with TSR >= TSR_opt Cp_op = np.clip(Cp_op, np.min(Cp_FBP[Cp_maxidx:]), np.max(Cp_FBP[Cp_maxidx:])) # saturate Cp values to be on Cp surface # Find maximum Cp value for this TSR f_cp_TSR = interpolate.interp1d(Cp_FBP[Cp_maxidx:], turbine.TSR_initial[Cp_maxidx:]) # interpolate function for Cp(tsr) values else: # Underspeed + # Interpolate inverse Cp surface slice with TSR <= TSR_opt Cp_op = np.clip(Cp_op, np.min(Cp_FBP[:Cp_maxidx+1]), np.max(Cp_FBP[:Cp_maxidx+1])) # saturate Cp values to be on Cp surface # Find maximum Cp value for this TSR f_cp_TSR = interpolate.interp1d(Cp_FBP[:Cp_maxidx+1], turbine.TSR_initial[:Cp_maxidx+1]) # interpolate function for Cp(tsr) values TSR_op = f_cp_TSR(Cp_op) TSR_below_rated = TSR_op[:len(v_below_rated)] TSR_above_rated = TSR_op[len(v_below_rated):] + # elif self.PC_ControlMode > 0: # If using pitch control in Region 3 + else: # Default here even if pitch control disabled + + # separate TSRs by operations regions + TSR_below_rated = [min(turbine.TSR_operational, rated_rotor_speed*R/v) for v in v_below_rated] # below rated + TSR_above_rated = rated_rotor_speed*R/v_above_rated # above rated + TSR_op = np.concatenate((TSR_below_rated, TSR_above_rated)) # operational TSRs + + # Find expected operational Cp values + Cp_above_rated = turbine.Cp.interp_surface(0,TSR_above_rated[0]) # Cp during rated operation (not optimal). Assumes cut-in bld pitch to be 0 + Cp_op_br = np.ones(len(v_below_rated)) * turbine.Cp.max # below rated + Cp_op_ar = Cp_above_rated * (TSR_above_rated/TSR_rated)**3 # above rated + Cp_op = np.concatenate((Cp_op_br, Cp_op_ar)) # operational CPs to linearize around + # initialize variables pitch_initial_rad = turbine.pitch_initial_rad @@ -287,7 +303,16 @@ def tune_controller(self, turbine): # At each operating point for i in range(len(TSR_op)): - if self.VS_ControlMode < 4: + if self.VS_ControlMode == 4: # Fixed pitch control in Region 3 + + if isinstance(self.min_pitch, float): + pitch_op[i] = self.min_pitch + else: + # pitch_op[i] = 0 # Assume zero pitch + pitch_op[i] = turbine.pitch_initial_rad[turbine.Cp.max_ind[1]] # Take optimal pitch from Cp surface + + else: # Variable pitch control in Region 3 (default) + # Find pitch angle as a function of expected operating CP for each TSR operating point Cp_TSR = np.ndarray.flatten(turbine.Cp.interp_surface(turbine.pitch_initial_rad, TSR_op[i])) # all Cp values for a given tsr Cp_maxidx = Cp_TSR.argmax() @@ -301,12 +326,6 @@ def tune_controller(self, turbine): pitch_op[i] = max(self.min_pitch, f_cp_pitch(Cp_op[i])) else: # no defined minimum pitch schedule pitch_op[i] = f_cp_pitch(Cp_op[i]) - else: - if isinstance(self.min_pitch, float): - pitch_op[i] = self.min_pitch - else: - # Take optimal pitch from Cp surface - pitch_op[i] = turbine.pitch_initial_rad[turbine.Cp.max_ind[1]] # Calculate Cp Surface gradients dCp_beta[i], dCp_TSR[i] = turbine.Cp.interp_gradient(pitch_op[i],TSR_op[i]) @@ -324,16 +343,18 @@ def tune_controller(self, turbine): # Compute generator speed and torque operating schedule P_op = 0.5 * turbine.rho * np.pi*turbine.rotor_radius**2 * Cp_op * v**3 * turbine.GBoxEff/100 * turbine.GenEff/100 - if self.VS_ControlMode < 4: + if self.VS_ControlMode < 4: # Saturate between min speed and rated if variable pitch in Region 3 omega_op = np.maximum(np.minimum(turbine.rated_rotor_speed, TSR_op*v/R), self.vs_minspd) - else: + else: # Only saturate min pitch if torque control in Region 3 omega_op = np.maximum(TSR_op*v/R, self.vs_minspd) omega_gen_op = omega_op * Ng - tau_op = P_op / omega_gen_op / (turbine.GBoxEff/100 * turbine.GenEff/100) + tau_op = P_op / omega_gen_op \ + / (turbine.GBoxEff/100 * turbine.GenEff/100) # Includes increase to counteract generator efficiency loss # Check if maximum torque leaves enough leeway to control the system - if np.max(tau_op) > turbine.max_torque: # turbine.max_torque * 1.2 + if np.max(tau_op) > turbine.max_torque: # turbine.max_torque * 1.2 # DBS: Should we include additional margin? print('WARNING: Torque operating schedule is above maximum generator torque and may not be realizable within saturation limits.') + # DBS: Do we want to saturate maximum torque and recompute equilibrium points? # Full Cx surface gradients @@ -396,7 +417,7 @@ def tune_controller(self, turbine): self.vs_gain_schedule.second_order_PI(self.zeta_vs, self.omega_vs,A,B_tau,linearize=False,v=v) # -- Find K for Komega_g^2 -- - self.vs_rgn2K = (pi*rho*R**5.0 * turbine.Cp.max * turbine.GBoxEff/100 * turbine.GenEff/100) / \ + self.vs_rgn2K = (pi*rho*R**5.0 * turbine.Cp.max) / \ (2.0 * turbine.Cp.TSR_opt**3 * Ng**3) * self.controller_params['rgn2k_factor'] self.vs_refspd = min(turbine.TSR_operational * turbine.v_rated/R, turbine.rated_rotor_speed) * Ng From 25001e0d3517ea648fce11186997142bfbe94970 Mon Sep 17 00:00:00 2001 From: David Stockhouse Date: Mon, 13 May 2024 13:28:33 -0600 Subject: [PATCH 148/224] Finished renaming FBP variables and VS ref speed filter --- Examples/29_marine_hydro_fbp.py | 25 +++++++------- Examples/Tune_Cases/RM1_MHK_FBP.yaml | 10 +++--- .../rosco_registry/rosco_types.yaml | 27 +++++++++++---- .../rosco_registry/write_registry.py | 4 +-- rosco/controller/src/ControllerBlocks.f90 | 10 +++--- rosco/controller/src/ROSCO_Types.f90 | 16 ++++----- rosco/controller/src/ReadSetParameters.f90 | 14 ++++---- rosco/toolbox/controller.py | 21 ++++++++---- rosco/toolbox/inputs/toolbox_schema.yaml | 33 +++++++++++-------- rosco/toolbox/utilities.py | 23 ++++++------- 10 files changed, 106 insertions(+), 77 deletions(-) diff --git a/Examples/29_marine_hydro_fbp.py b/Examples/29_marine_hydro_fbp.py index af9752fe..f53ec301 100644 --- a/Examples/29_marine_hydro_fbp.py +++ b/Examples/29_marine_hydro_fbp.py @@ -1,6 +1,6 @@ ''' ------------ 26_marine_hydro ------------------------ -Run openfast with ROSCO and a MHK turbine +----------- 29_marine_hydro_fbp --------------- +Run openfast with ROSCO and a MHK turbine with fixed blade pitch control ----------------------------------------------- @@ -58,30 +58,31 @@ def main(): ### Tune controller cases - # Constant power underspeed - controller_params['FBP_speed_mode'] = 0 - controller_params['FBP_P'] = [1.0, 1.0] + # Constant power underspeed (should be the default) + controller_params['VS_FBP_speed_mode'] = 0 + controller_params['VS_FBP_P'] = [1.0, 1.0] controller_1 = ROSCO_controller.Controller(controller_params) controller_1.tune_controller(turbine) # Constant power overspeed - controller_params['FBP_speed_mode'] = 1 - controller_params['FBP_P'] = [1.0, 1.0] + controller_params['VS_FBP_ref_mode'] = 0 # Switch to WSE reference + controller_params['VS_FBP_speed_mode'] = 1 + controller_params['VS_FBP_P'] = [1.0, 1.0] controller_2 = ROSCO_controller.Controller(controller_params) controller_2.tune_controller(turbine) # Linear increasing power - controller_params['FBP_speed_mode'] = 0 - controller_params['FBP_P'] = [1.0, 2.0] + controller_params['VS_FBP_speed_mode'] = 0 + controller_params['VS_FBP_P'] = [1.0, 2.0] controller_3 = ROSCO_controller.Controller(controller_params) controller_3.tune_controller(turbine) # Linear increasing power, leveling out - controller_params['FBP_U'] = [2.0, 3.0] - controller_params['FBP_P'] = [1.0, 2.0] + controller_params['VS_FBP_U'] = [2.0, 3.0] + controller_params['VS_FBP_P'] = [1.0, 2.0] controller_4 = ROSCO_controller.Controller(controller_params) controller_4.tune_controller(turbine) - + fig, axs = plt.subplots(3,1) axs[0].plot(controller_1.v, controller_1.power_op, label='Constant Power Underspeed') diff --git a/Examples/Tune_Cases/RM1_MHK_FBP.yaml b/Examples/Tune_Cases/RM1_MHK_FBP.yaml index 752e23d8..725f6631 100644 --- a/Examples/Tune_Cases/RM1_MHK_FBP.yaml +++ b/Examples/Tune_Cases/RM1_MHK_FBP.yaml @@ -55,10 +55,10 @@ controller_params: sd_maxpit: 0.4363 # Maximum blade pitch angle to initiate shutdown [rad], {default = bld pitch at v_max} Kp_float: -0.3897 max_torque_factor: 5 - FBP_ref_mode: 1 - FBP_P_mode: 0 - FBP_U: [2.0, 4.0] - FBP_P: [1.0, 1.0] + VS_FBP_ref_mode: 1 + VS_FBP_P_mode: 0 + VS_FBP_U: [2.0, 4.0] + VS_FBP_P: [1.0, 1.0] DISCON: F_NumNotchFilts: 0 F_NotchFreqs: [1.0, 2.4200] # 2P @@ -70,4 +70,4 @@ controller_params: F_TwrTopNotch_Ind: [1,2] F_NotchCornerFreq_GS: [2.42] F_FlHighPassFreq: 1.5 - VS_PwrFiltF: 0.05 + F_VSRefSpdCornerFreq: 0.05 diff --git a/rosco/controller/rosco_registry/rosco_types.yaml b/rosco/controller/rosco_registry/rosco_types.yaml index b0caa136..68d1661a 100644 --- a/rosco/controller/rosco_registry/rosco_types.yaml +++ b/rosco/controller/rosco_registry/rosco_types.yaml @@ -270,7 +270,7 @@ ControlParameters: # Generator Torque Controller VS_ControlMode: <<: *integer - description: Generator torque control mode in above rated conditions {0 - no torque control, 1 - komega^2 with PI trans, 2 - WSE TSR Tracking, 3 - Power TSR Tracking} + description: Generator torque control mode in below rated conditions {0 - no torque control, 1 - komega^2 with PI trans, 2 - WSE TSR Tracking, 3 - Power TSR Tracking, 4 - Fixed pitch, generic operating schedule for torque controller in Regions 2 and 3} VS_ConstPower: <<: *integer description: Constant power torque control @@ -318,7 +318,25 @@ ControlParameters: VS_TSRopt: <<: *real description: Power-maximizing region 2 tip-speed ratio [rad] - + VS_FBP_RefMode: + <<: *integer + description: Reference interpolation control mode for fixed blade pitch in above rated conditions {0 - no torque control, 1 - komega^2 with PI trans, 2 - WSE TSR Tracking, 3 - Power TSR Tracking} + VS_FBP_n: + <<: *integer + description: Number of operating schedule entries for fixed blade pitch control + VS_FBP_U: + <<: *real + description: Operating schedule for fixed blade pitch control - Wind speed + allocatable: True + VS_FBP_Omega: + <<: *real + description: Operating schedule for fixed blade pitch control - Generator speed + allocatable: True + VS_FBP_Tau: + <<: *real + description: Operating schedule for fixed blade pitch control - Generator torque + allocatable: True + # Setpoint Smoother SS_Mode: <<: *integer @@ -1018,7 +1036,7 @@ LocalVariables: description: Torque control generator speed set point [rad/s] VS_RefSpd_TSR: <<: *real - description: Torque control generator speed set point based on optimal TSR [rad/s] + description: Torque control generator speed set point based on optimal TSR (unfiltered) [rad/s] VS_RefSpd_TRA: <<: *real description: Torque control generator speed set point after freq avoidance [rad/s] @@ -1037,9 +1055,6 @@ LocalVariables: RotSpeedF: <<: *real description: Filtered LSS (generator) speed [rad/s]. - VS_RefSpd: - <<: *real - description: Generator speed set point of torque controller [rad/s] PC_RefSpd: <<: *real description: Generator speed set point of pitch controller [rad/s] diff --git a/rosco/controller/rosco_registry/write_registry.py b/rosco/controller/rosco_registry/write_registry.py index 1c07fc98..c41ccbd0 100644 --- a/rosco/controller/rosco_registry/write_registry.py +++ b/rosco/controller/rosco_registry/write_registry.py @@ -44,7 +44,7 @@ def write_types(yfile): file.write(' {:<25s} :: {:<25s} ! {}\n'.format(f90type, atstr, reg[toptype][attype]['description'])) file.write('END TYPE {}\n'.format(toptype)) file.write('\n') - file.write('END MODULE ROSCO_Types') + file.write('END MODULE ROSCO_Types\n') file.close() def write_roscoio(yfile): @@ -388,7 +388,7 @@ def write_roscoio(yfile): file.write("END SUBROUTINE Debug\n") file.write("\n") - file.write("END MODULE ROSCO_IO") + file.write("END MODULE ROSCO_IO\n") file.close() def check_size(main_attribute, sub_attribute): diff --git a/rosco/controller/src/ControllerBlocks.f90 b/rosco/controller/src/ControllerBlocks.f90 index e53ccb40..67da4306 100644 --- a/rosco/controller/src/ControllerBlocks.f90 +++ b/rosco/controller/src/ControllerBlocks.f90 @@ -69,10 +69,10 @@ SUBROUTINE ComputeVariablesSetpoints(CntrPar, LocalVar, objInst, DebugVar, ErrVa LocalVar%VS_RefSpd_TSR = (LocalVar%VS_GenPwr/CntrPar%VS_Rgn2K)**(1./3.) ELSEIF (CntrPar%VS_ControlMode == 4) THEN ! Generic lookup table for genspeed reference - IF (CntrPar%FBP_RefMode == 0) THEN ! Use WSE to look up speed reference - VS_RefSpdRaw = interp1d(CntrPar%FBP_U, CntrPar%FBP_Omega, LocalVar%WE_Vw, ErrVar) - ELSEIF (CntrPar%FBP_RefMode == 1) THEN ! Use LocalVar%GenTq or LocalVar%GenTqMeas, Omega must be expressed as a function of Tau - VS_RefSpdRaw = interp1d(CntrPar%FBP_Tau, CntrPar%FBP_Omega, LocalVar%GenTq, ErrVar) + IF (CntrPar%VS_FBP_RefMode == 0) THEN ! Use WSE to look up speed reference + VS_RefSpdRaw = interp1d(CntrPar%VS_FBP_U, CntrPar%VS_FBP_Omega, LocalVar%WE_Vw, ErrVar) + ELSEIF (CntrPar%VS_FBP_RefMode == 1) THEN ! Use LocalVar%GenTq or LocalVar%GenTqMeas, Omega must be expressed as a function of Tau + VS_RefSpdRaw = interp1d(CntrPar%VS_FBP_Tau, CntrPar%VS_FBP_Omega, LocalVar%GenTq, ErrVar) ENDIF ELSE ! Generate constant reference @@ -80,7 +80,7 @@ SUBROUTINE ComputeVariablesSetpoints(CntrPar, LocalVar, objInst, DebugVar, ErrVa ENDIF ! Filter reference signal - LocalVar%VS_RefSpd = LPFilter(LocalVar%VS_RefSpd_TSR, LocalVar%DT, CntrPar%VS_RefSpdFiltF, LocalVar%FP, LocalVar%iStatus, LocalVar%restart, objInst%instLPF) + LocalVar%VS_RefSpd = LPFilter(LocalVar%VS_RefSpd_TSR, LocalVar%DT, CntrPar%F_VSRefSpdCornerFreq, LocalVar%FP, LocalVar%iStatus, LocalVar%restart, objInst%instLPF) ! Exclude reference speeds specified by user IF (CntrPar%TRA_Mode > 0) THEN diff --git a/rosco/controller/src/ROSCO_Types.f90 b/rosco/controller/src/ROSCO_Types.f90 index fbf73281..e2f9a5fb 100644 --- a/rosco/controller/src/ROSCO_Types.f90 +++ b/rosco/controller/src/ROSCO_Types.f90 @@ -32,6 +32,7 @@ MODULE ROSCO_Types REAL(DbKi) :: F_FlHighPassFreq ! Natural frequency of first-roder high-pass filter for nacelle fore-aft motion [rad/s]. REAL(DbKi) :: F_YawErr ! Corner low pass filter corner frequency for yaw controller [rad/s]. REAL(DbKi), DIMENSION(:), ALLOCATABLE :: F_FlpCornerFreq ! Corner frequency (-3dB point) in the second order low pass filter of the blade root bending moment for flap control [rad/s]. + REAL(DbKi) :: F_VSRefSpdCornerFreq ! Corner frequency (-3dB point) in the first order low pass filter of the generator speed reference used for TSR tracking torque control [rad/s]. INTEGER(IntKi) :: TRA_Mode ! Tower Fore-Aft control mode {0 - no fore-aft control, 1 - Tower fore-aft damping, 2 -Frequency exclusion zone, 3- Options 1 and 2} REAL(DbKi) :: TRA_ExclSpeed ! Rotor speed for exclusion [LSS] [rad/s] REAL(DbKi) :: TRA_ExclBand ! One-half of the total frequency exclusion band. Torque controller reference will be TRA_ExclFreq +/- TRA_ExlBand [rad/s] @@ -62,7 +63,7 @@ MODULE ROSCO_Types REAL(DbKi) :: PC_RefSpd ! Desired (reference) HSS speed for pitch controller, [rad/s]. REAL(DbKi) :: PC_FinePit ! Record 5 - Below-rated pitch angle set-point (deg) [used only with Bladed Interface] REAL(DbKi) :: PC_Switch ! Angle above lowest minimum pitch angle for switch [rad] - INTEGER(IntKi) :: VS_ControlMode ! Generator torque control mode in above rated conditions {0 - no torque control, 1 - komega^2 with PI trans, 2 - WSE TSR Tracking, 3 - Power TSR Tracking} + INTEGER(IntKi) :: VS_ControlMode ! Generator torque control mode in below rated conditions {0 - no torque control, 1 - komega^2 with PI trans, 2 - WSE TSR Tracking, 3 - Power TSR Tracking, 4 - Fixed pitch, generic operating schedule for torque controller in Regions 2 and 3} INTEGER(IntKi) :: VS_ConstPower ! Constant power torque control REAL(DbKi) :: VS_GenEff ! Generator efficiency mechanical power -> electrical power [-] REAL(DbKi) :: VS_ArSatTq ! Above rated generator torque PI control saturation, [Nm] -- 212900 @@ -78,12 +79,11 @@ MODULE ROSCO_Types REAL(DbKi), DIMENSION(:), ALLOCATABLE :: VS_KP ! Proportional gain for generator PI torque controller, used in the transitional 2.5 region REAL(DbKi), DIMENSION(:), ALLOCATABLE :: VS_KI ! Integral gain for generator PI torque controller, used in the transitional 2.5 region REAL(DbKi) :: VS_TSRopt ! Power-maximizing region 2 tip-speed ratio [rad] - REAL(DbKi) :: VS_PwrFiltF ! Cut-off frequency of filter on generator power for power-based tsr tracking control - INTEGER(IntKi) :: FBP_RefMode ! Fixed blade pitch reference interpolation mode (0 for WSE, 1 for torque feedback) - INTEGER(IntKi) :: FBP_n ! Amount of fixed blade pitch operating schedule table entries - REAL(DbKi), DIMENSION(:), ALLOCATABLE :: FBP_U ! FBP Operating-schedule table - Wind speeds - REAL(DbKi), DIMENSION(:), ALLOCATABLE :: FBP_Omega ! FBP Operating-schedule table - Generator speeds - REAL(DbKi), DIMENSION(:), ALLOCATABLE :: FBP_Tau ! FBP Operating-schedule table - Generator torques + INTEGER(IntKi) :: VS_FBP_RefMode ! Reference interpolation control mode for fixed blade pitch in above rated conditions {0 - no torque control, 1 - komega^2 with PI trans, 2 - WSE TSR Tracking, 3 - Power TSR Tracking} + INTEGER(IntKi) :: VS_FBP_n ! Number of operating schedule entries for fixed blade pitch control + REAL(DbKi), DIMENSION(:), ALLOCATABLE :: VS_FBP_U ! Operating schedule for fixed blade pitch control - Wind speed + REAL(DbKi), DIMENSION(:), ALLOCATABLE :: VS_FBP_Omega ! Operating schedule for fixed blade pitch control - Generator speed + REAL(DbKi), DIMENSION(:), ALLOCATABLE :: VS_FBP_Tau ! Operating schedule for fixed blade pitch control - Generator torque INTEGER(IntKi) :: SS_Mode ! Setpoint Smoother mode {0 - no setpoint smoothing, 1 - introduce setpoint smoothing} REAL(DbKi) :: SS_VSGain ! Variable speed torque controller setpoint smoother gain, [-]. REAL(DbKi) :: SS_PCGain ! Collective pitch controller setpoint smoother gain, [-]. @@ -282,7 +282,7 @@ MODULE ROSCO_Types REAL(DbKi) :: FA_AccHPFI ! Tower velocity, high-pass filtered and integrated fore-aft acceleration [m/s] REAL(DbKi) :: FA_PitCom(3) ! Tower fore-aft vibration damping pitch contribution [rad] REAL(DbKi) :: VS_RefSpd ! Torque control generator speed set point [rad/s] - REAL(DbKi) :: VS_RefSpd_TSR ! Torque control generator speed set point based on optimal TSR [rad/s] + REAL(DbKi) :: VS_RefSpd_TSR ! Torque control generator speed set point based on optimal TSR (unfiltered) [rad/s] REAL(DbKi) :: VS_RefSpd_TRA ! Torque control generator speed set point after freq avoidance [rad/s] REAL(DbKi) :: VS_RefSpd_RL ! Torque control generator speed set point after rate limit [rad/s] REAL(DbKi) :: PC_RefSpd ! Generator speed set point of pitch controller [rad/s] diff --git a/rosco/controller/src/ReadSetParameters.f90 b/rosco/controller/src/ReadSetParameters.f90 index 5f1fb073..6542141a 100644 --- a/rosco/controller/src/ReadSetParameters.f90 +++ b/rosco/controller/src/ReadSetParameters.f90 @@ -230,7 +230,7 @@ SUBROUTINE SetParameters(avrSWAP, accINFILE, size_avcMSG, CntrPar, LocalVar, obj ENDIF ELSE ! Set torque initial condition based on operating schedule at current wind speed - LocalVar%GenTq = interp1d(CntrPar%FBP_U, CntrPar%FBP_Tau, LocalVar%HorWindV, ErrVar) + LocalVar%GenTq = interp1d(CntrPar%VS_FBP_U, CntrPar%VS_FBP_Tau, LocalVar%HorWindV, ErrVar) ENDIF LocalVar%VS_LastGenTrq = LocalVar%GenTq LocalVar%VS_MaxTq = CntrPar%VS_MaxTq @@ -384,6 +384,7 @@ SUBROUTINE ReadControlParameterFileSub(CntrPar, LocalVar, accINFILE, accINFILE_s CALL ParseAry( FileLines, 'F_FlCornerFreq', CntrPar%F_FlCornerFreq, 2, accINFILE(1), ErrVar, CntrPar%FL_Mode == 0, UnEc) CALL ParseInput(FileLines, 'F_FlHighPassFreq', CntrPar%F_FlHighPassFreq, accINFILE(1), ErrVar, CntrPar%FL_Mode == 0, UnEc) CALL ParseAry( FileLines, 'F_FlpCornerFreq', CntrPar%F_FlpCornerFreq, 2, accINFILE(1), ErrVar, CntrPar%Flp_Mode == 0, UnEc) + CALL ParseInput(FileLines, 'F_VSRefSpdCornerFreq', CntrPar%F_VSRefSpdCornerFreq, accINFILE(1), ErrVar, CntrPar%VS_ControlMode < 2, UnEc) ! Optional filter inds IF (CntrPar%F_GenSpdNotch_N > 0) THEN @@ -436,15 +437,14 @@ SUBROUTINE ReadControlParameterFileSub(CntrPar, LocalVar, accINFILE, accINFILE_s CALL ParseAry( FileLines, 'VS_KP', CntrPar%VS_KP, CntrPar%VS_n, accINFILE(1), ErrVar, .FALSE., UnEc) CALL ParseAry( FileLines, 'VS_KI', CntrPar%VS_KI, CntrPar%VS_n, accINFILE(1), ErrVar, .FALSE., UnEc) CALL ParseInput(FileLines, 'VS_TSRopt', CntrPar%VS_TSRopt, accINFILE(1), ErrVar, CntrPar%VS_ControlMode < 2, UnEc) - CALL ParseInput(FileLines, 'VS_PwrFiltF', CntrPar%VS_PwrFiltF, accINFILE(1), ErrVar, CntrPar%VS_ControlMode < 3, UnEc) IF (ErrVar%aviFAIL < 0) RETURN !------------ Fixed-Pitch Region 3 Control ------------ - CALL ParseInput(FileLines, 'FBP_RefMode', CntrPar%FBP_RefMode, accINFILE(1), ErrVar, CntrPar%VS_ControlMode < 4, UnEc) - CALL ParseInput(FileLines, 'FBP_n', CntrPar%FBP_n, accINFILE(1), ErrVar, CntrPar%VS_ControlMode < 4, UnEc) - CALL ParseAry( FileLines, 'FBP_U', CntrPar%FBP_U, CntrPar%FBP_n, accINFILE(1), ErrVar, CntrPar%VS_ControlMode < 4, UnEc) - CALL ParseAry( FileLines, 'FBP_Omega', CntrPar%FBP_Omega, CntrPar%FBP_n, accINFILE(1), ErrVar, CntrPar%VS_ControlMode < 4, UnEc) - CALL ParseAry( FileLines, 'FBP_Tau', CntrPar%FBP_Tau, CntrPar%FBP_n, accINFILE(1), ErrVar, CntrPar%VS_ControlMode < 4, UnEc) + CALL ParseInput(FileLines, 'VS_FBP_RefMode', CntrPar%VS_FBP_RefMode, accINFILE(1), ErrVar, CntrPar%VS_ControlMode < 4, UnEc) + CALL ParseInput(FileLines, 'VS_FBP_n', CntrPar%VS_FBP_n, accINFILE(1), ErrVar, CntrPar%VS_ControlMode < 4, UnEc) + CALL ParseAry( FileLines, 'VS_FBP_U', CntrPar%VS_FBP_U, CntrPar%VS_FBP_n, accINFILE(1), ErrVar, CntrPar%VS_ControlMode < 4, UnEc) + CALL ParseAry( FileLines, 'VS_FBP_Omega', CntrPar%VS_FBP_Omega, CntrPar%VS_FBP_n, accINFILE(1), ErrVar, CntrPar%VS_ControlMode < 4, UnEc) + CALL ParseAry( FileLines, 'VS_FBP_Tau', CntrPar%VS_FBP_Tau, CntrPar%VS_FBP_n, accINFILE(1), ErrVar, CntrPar%VS_ControlMode < 4, UnEc) IF (ErrVar%aviFAIL < 0) RETURN !------- Setpoint Smoother -------------------------------- diff --git a/rosco/toolbox/controller.py b/rosco/toolbox/controller.py index 8bbafcba..dca0c369 100644 --- a/rosco/toolbox/controller.py +++ b/rosco/toolbox/controller.py @@ -107,17 +107,17 @@ def __init__(self, controller_params): raise Exception( 'rosco.toolbox:controller: PC_ControlMode must be 0 if VS_ControlMode == 4') - if 'FBP_ref_mode' in controller_params: - self.fbp_ref_mode = controller_params['FBP_ref_mode'] + if 'VS_FBP_ref_mode' in controller_params: + self.fbp_ref_mode = controller_params['VS_FBP_ref_mode'] else: raise Exception( - 'rosco.toolbox:controller: FBP options (FBP_ref_mode) must be set if VS_ControlMode == 4') + 'rosco.toolbox:controller: FBP options (VS_FBP_ref_mode) must be set if VS_ControlMode == 4') # Defaults to constant power, underspeed - self.fbp_power_mode = controller_params['FBP_power_mode'] - self.fbp_speed_mode = controller_params['FBP_speed_mode'] - self.fbp_U = controller_params['FBP_U'] # Should we set this default based on rated speed? - self.fbp_P = controller_params['FBP_P'] + self.fbp_power_mode = controller_params['VS_FBP_power_mode'] + self.fbp_speed_mode = controller_params['VS_FBP_speed_mode'] + self.fbp_U = controller_params['VS_FBP_U'] # Should we set this default based on rated speed? + self.fbp_P = controller_params['VS_FBP_P'] else: self.fbp_ref_mode = 0 @@ -161,6 +161,7 @@ def __init__(self, controller_params): self.f_ss_cornerfreq = controller_params['filter_params']['f_ss_cornerfreq'] self.f_yawerr = controller_params['filter_params']['f_yawerr'] self.f_sd_cornerfreq = controller_params['filter_params']['f_sd_cornerfreq'] + self.f_vs_refspd_cornerfreq = controller_params['filter_params']['f_vs_refspd_cornerfreq'] # Open loop parameters: set up and error catching @@ -356,6 +357,12 @@ def tune_controller(self, turbine): print('WARNING: Torque operating schedule is above maximum generator torque and may not be realizable within saturation limits.') # DBS: Do we want to saturate maximum torque and recompute equilibrium points? + # Check if options allow a nonmonotonic torque schedule + if self.fbp_ref_mode == 1: + # The simulation will crash if we have a nonmonotonic schedule, so fail to generate the config and alert the user + if np.any(np.diff(tau_op) <= 0): + raise Exception("VS controller reference torque interpolation is selected (VS_FBP_ref_mode == 1), but computed generator torque schedule is not monotonically increasing. Reconfigure power curve, ensure VS_FBP_speed_mode == 0, or switch VS_FBP_ref_mode to 0.") + # Full Cx surface gradients dCp_dbeta = dCp_beta/np.diff(pitch_initial_rad)[0] diff --git a/rosco/toolbox/inputs/toolbox_schema.yaml b/rosco/toolbox/inputs/toolbox_schema.yaml index 35c78ae0..86557e35 100644 --- a/rosco/toolbox/inputs/toolbox_schema.yaml +++ b/rosco/toolbox/inputs/toolbox_schema.yaml @@ -434,24 +434,24 @@ properties: description: Factor on VS_Rgn2K to increase/decrease optimal torque control gain, default is 1. Sometimes environmental conditions or differences in BEM solvers necessitate this change. default: 1 minimum: 0 - FBP_ref_mode: + VS_FBP_ref_mode: type: number description: Method of identifying operating point reference during operation (0- Use WSE, 1- Use filtered torque signal) minimum: 0 maximum: 1 - FBP_power_mode: + VS_FBP_power_mode: type: number - description: Interpretation mode for FBP_P (0- scale relative to rated power, 1- absolute power) + description: Interpretation mode for VS_FBP_P (0- scale relative to rated power, 1- absolute power) default: 0 minimum: 0 maximum: 1 - FBP_speed_mode: + VS_FBP_speed_mode: type: number description: Overspeed or underspeed operating schedule (0- underspeed, 1- overspeed) default: 0 minimum: 0 maximum: 1 - FBP_U: + VS_FBP_U: type: array description: List of wind speeds to schedule user-defined power curve for fixed blade pitch (FBP) control in Region 3 unit: m/s @@ -459,15 +459,15 @@ properties: type: number minimum: 0 uniqueItems: True - default: [12] - FBP_P: + default: [1.0, 2.0] + VS_FBP_P: type: [array,number] - description: List of points defining power curve for fixed blade pitch (FBP) control in Region 3, relative or absolute based on FBP_mode + description: List of points defining power curve for fixed blade pitch (FBP) control in Region 3, relative or absolute based on VS_FBP_power_mode unit: none items: type: number minimum: 0 - default: [1.0] + default: [1.0, 1.0] filter_params: type: object @@ -514,6 +514,12 @@ properties: type: number default: 0.41888 unit: rad + f_vs_refspd_cornerfreq: + type: number + description: Corner frequency (-3dB point) in the first order low pass filter for TSR tracking torque control [rad/s] + minimum: 0 + unit: rad/s + default: 0.05 open_loop: type: object default: {} @@ -710,6 +716,10 @@ properties: type: number description: Corner frequency and damping in the second order low pass filter of the blade root bending moment for flap control units: rad/s + F_VSRefSpdCornerFreq: + type: number + description: Corner frequency (-3dB point) in the first order low pass filter of the generator speed reference used for TSR tracking torque control [rad/s]. + units: rad PC_GS_n: type: number description: Amount of gain-scheduling table entries @@ -849,11 +859,6 @@ properties: type: number description: Power-maximizing region 2 tip-speed-ratio. Only used in VS_ControlMode = 2. units: rad - VS_PwrFiltF: - type: number - description: Low pass filter on power used to determine generator speed set point. Only used in VS_ControlMode = 3. - units: rad - default: 0.314 SS_VSGain: type: number description: Variable speed torque controller setpoint smoother gain diff --git a/rosco/toolbox/utilities.py b/rosco/toolbox/utilities.py index 78b8f0e6..5aee6b50 100644 --- a/rosco/toolbox/utilities.py +++ b/rosco/toolbox/utilities.py @@ -139,6 +139,7 @@ def write_DISCON(turbine, controller, param_file='DISCON.IN', txt_filename='Cp_C file.write('{}! F_FlCornerFreq - Natural frequency and damping in the second order low pass filter of the tower-top fore-aft motion for floating feedback control [rad/s, -].\n'.format(''.join('{:<4.6f} '.format(rosco_vt['F_FlCornerFreq'][i]) for i in range(len(rosco_vt['F_FlCornerFreq']))))) file.write('{:<13.5f} ! F_FlHighPassFreq - Natural frequency of first-order high-pass filter for nacelle fore-aft motion [rad/s].\n'.format(rosco_vt['F_FlHighPassFreq'])) file.write('{} ! F_FlpCornerFreq - {}\n'.format(write_array(rosco_vt["F_FlpCornerFreq"]), input_descriptions["F_FlpCornerFreq"])) + file.write('{:<013.5f} ! F_VSRefSpdCornerFreq - {}\n'.format(float(rosco_vt['F_VSRefSpdCornerFreq']),input_descriptions['F_VSRefSpdCornerFreq'])) file.write('\n') file.write('!------- BLADE PITCH CONTROL ----------------------------------------------\n') @@ -180,14 +181,13 @@ def write_DISCON(turbine, controller, param_file='DISCON.IN', txt_filename='Cp_C file.write('{:<014.5f} ! VS_KP - Proportional gain for generator PI torque controller [-]. (Only used in the transitional 2.5 region if VS_ControlMode =/ 2)\n'.format(rosco_vt['VS_KP'])) file.write('{:<014.5f} ! VS_KI - Integral gain for generator PI torque controller [s]. (Only used in the transitional 2.5 region if VS_ControlMode =/ 2)\n'.format(rosco_vt['VS_KI'])) file.write('{:<13.2f} ! VS_TSRopt - {}\n'.format(float(rosco_vt['VS_TSRopt']),input_descriptions['VS_TSRopt'])) - file.write('{:<014.5f} ! VS_PwrFiltF - {}\n'.format(float(rosco_vt['VS_PwrFiltF']),input_descriptions['VS_PwrFiltF'])) file.write('\n') file.write('!------- FIXED PITCH REGION 3 TORQUE CONTROL ------------------------------------------------\n') - file.write('{:<11d} ! FBP_RefMode - Reference control mode (0 - Use wind speed estimator, 1 - Use torque feedback)\n'.format(int(rosco_vt['FBP_RefMode']))) - file.write('{:<11d} ! FBP_n - Number of gain-scheduling table entries\n'.format(int(rosco_vt['FBP_n']))) - file.write('{} ! FBP_U - Operating schedule table: Wind speeds [m/s].\n'.format(''.join('{:<4.6f} '.format(rosco_vt['FBP_U'][i]) for i in range(len(rosco_vt['FBP_U']))))) - file.write('{} ! FBP_Omega - Operating schedule table: Generator speeds [rad/s].\n'.format(''.join('{:<4.6f} '.format(rosco_vt['FBP_Omega'][i]) for i in range(len(rosco_vt['FBP_Omega']))))) - file.write('{} ! FBP_Tau - Operating schedule table: Generator torques [N m].\n'.format(''.join('{:<4.6f} '.format(rosco_vt['FBP_Tau'][i]) for i in range(len(rosco_vt['FBP_Tau']))))) + file.write('{:<11d} ! VS_FBP_RefMode - Reference control mode (0 - Use wind speed estimator, 1 - Use torque feedback)\n'.format(int(rosco_vt['VS_FBP_RefMode']))) + file.write('{:<11d} ! VS_FBP_n - Number of gain-scheduling table entries\n'.format(int(rosco_vt['VS_FBP_n']))) + file.write('{} ! VS_FBP_U - Operating schedule table: Wind speeds [m/s].\n'.format(''.join('{:<4.6f} '.format(rosco_vt['VS_FBP_U'][i]) for i in range(len(rosco_vt['VS_FBP_U']))))) + file.write('{} ! VS_FBP_Omega - Operating schedule table: Generator speeds [rad/s].\n'.format(''.join('{:<4.6f} '.format(rosco_vt['VS_FBP_Omega'][i]) for i in range(len(rosco_vt['VS_FBP_Omega']))))) + file.write('{} ! VS_FBP_Tau - Operating schedule table: Generator torques [N m].\n'.format(''.join('{:<4.6f} '.format(rosco_vt['VS_FBP_Tau'][i]) for i in range(len(rosco_vt['VS_FBP_Tau']))))) file.write('\n') file.write('!------- SETPOINT SMOOTHER ---------------------------------------------\n') file.write('{:<13.5f} ! SS_VSGain - Variable speed torque controller setpoint smoother gain, [-].\n'.format(rosco_vt['SS_VSGain'])) @@ -523,6 +523,7 @@ def DISCON_dict(turbine, controller, txt_filename=None): DISCON_dict['F_YawErr'] = controller.f_yawerr DISCON_dict['F_FlHighPassFreq'] = controller.f_fl_highpassfreq DISCON_dict['F_FlCornerFreq'] = [controller.ptfm_freq, 1.0] + DISCON_dict['F_VSRefSpdCornerFreq'] = controller.f_vs_refspd_cornerfreq # ------- BLADE PITCH CONTROL ------- DISCON_dict['PC_GS_n'] = len(controller.pitch_op_pc) DISCON_dict['PC_GS_angles'] = controller.pitch_op_pc @@ -563,11 +564,11 @@ def DISCON_dict(turbine, controller, txt_filename=None): DISCON_dict['VS_KI'] = controller.vs_gain_schedule.Ki[-1] DISCON_dict['VS_TSRopt'] = turbine.TSR_operational # ------- FIXED BLADE PITCH TORQUE CONTROL ------- - DISCON_dict['FBP_RefMode'] = controller.fbp_ref_mode - DISCON_dict['FBP_n'] = len(controller.v) - DISCON_dict['FBP_U'] = controller.v - DISCON_dict['FBP_Omega'] = controller.omega_gen_op - DISCON_dict['FBP_Tau'] = controller.tau_op + DISCON_dict['VS_FBP_RefMode'] = controller.fbp_ref_mode + DISCON_dict['VS_FBP_n'] = len(controller.v) + DISCON_dict['VS_FBP_U'] = controller.v + DISCON_dict['VS_FBP_Omega'] = controller.omega_gen_op + DISCON_dict['VS_FBP_Tau'] = controller.tau_op # ------- SETPOINT SMOOTHER ------- DISCON_dict['SS_VSGain'] = controller.ss_vsgain DISCON_dict['SS_PCGain'] = controller.ss_pcgain From 822b731fa835a7f047ab9c9e38abd37d6f03a76c Mon Sep 17 00:00:00 2001 From: David Stockhouse Date: Mon, 13 May 2024 13:42:13 -0600 Subject: [PATCH 149/224] Regenerated DISCONs --- Examples/Test_Cases/BAR_10/BAR_10_DISCON.IN | 16 +++++++------- .../DISCON-UMaineSemi.IN | 16 +++++++------- Examples/Test_Cases/MHK_RM1/MHK_RM1_DISCON.IN | 22 +++++++++---------- Examples/Test_Cases/NREL-5MW/DISCON.IN | 16 +++++++------- .../NREL_2p8_127/NREL-2p8-127_DISCON.IN | 16 +++++++------- rosco/controller/src/ReadSetParameters.f90 | 2 +- 6 files changed, 44 insertions(+), 44 deletions(-) diff --git a/Examples/Test_Cases/BAR_10/BAR_10_DISCON.IN b/Examples/Test_Cases/BAR_10/BAR_10_DISCON.IN index c353edb6..7de75abf 100644 --- a/Examples/Test_Cases/BAR_10/BAR_10_DISCON.IN +++ b/Examples/Test_Cases/BAR_10/BAR_10_DISCON.IN @@ -1,5 +1,5 @@ ! Controller parameter input file for the BAR_10 wind turbine -! - File written using ROSCO version 2.9.0 controller tuning logic on 05/10/24 +! - File written using ROSCO version 2.9.0 controller tuning logic on 05/13/24 !------- SIMULATION CONTROL ------------------------------------------------------------ 1 ! LoggingLevel - {0: write no debug files, 1: write standard output .dbg-file, 2: LoggingLevel 1 + ROSCO LocalVars (.dbg2) 3: LoggingLevel 2 + complete avrSWAP-array (.dbg3)} @@ -49,6 +49,7 @@ 0.000000 1.000000 ! F_FlCornerFreq - Natural frequency and damping in the second order low pass filter of the tower-top fore-aft motion for floating feedback control [rad/s, -]. 0.01042 ! F_FlHighPassFreq - Natural frequency of first-order high-pass filter for nacelle fore-aft motion [rad/s]. 7.8480 1.0000 ! F_FlpCornerFreq - Corner frequency and damping in the second order low pass filter of the blade root bending moment for flap control +0.05000000000 ! F_VSRefSpdCornerFreq - Corner frequency (-3dB point) in the first order low pass filter of the generator speed reference used for TSR tracking torque control [rad/s]. !------- BLADE PITCH CONTROL ---------------------------------------------- 30 ! PC_GS_n - Amount of gain-scheduling table entries @@ -81,7 +82,7 @@ 70282.09458000 ! VS_MaxTq - Maximum generator torque in Region 3 (HSS side), [Nm]. 0.000000000000 ! VS_MinTq - Minimum generator torque (HSS side), [Nm]. 27.49717000000 ! VS_MinOMSpd - Minimum generator speed [rad/s] -11.20801000000 ! VS_Rgn2K - Generator torque constant in Region 2 (HSS side). Only used in VS_ControlMode = 1,3 +12.03868000000 ! VS_Rgn2K - Generator torque constant in Region 2 (HSS side). Only used in VS_ControlMode = 1,3 5000000.000000 ! VS_RtPwr - Wind turbine rated power [W] 63892.81326000 ! VS_RtTq - Rated torque, [Nm]. 75.83317000000 ! VS_RefSpd - Rated generator speed [rad/s] @@ -89,14 +90,13 @@ -2452.07948000 ! VS_KP - Proportional gain for generator PI torque controller [-]. (Only used in the transitional 2.5 region if VS_ControlMode =/ 2) -332.357190000 ! VS_KI - Integral gain for generator PI torque controller [s]. (Only used in the transitional 2.5 region if VS_ControlMode =/ 2) 9.76 ! VS_TSRopt - Power-maximizing region 2 tip-speed-ratio. Only used in VS_ControlMode = 2. -0.314000000000 ! VS_PwrFiltF - Low pass filter on power used to determine generator speed set point. Only used in VS_ControlMode = 3. !------- FIXED PITCH REGION 3 TORQUE CONTROL ------------------------------------------------ -0 ! FBP_RefMode - Reference control mode (0 - Use wind speed estimator, 1 - Use torque feedback) -60 ! FBP_n - Number of gain-scheduling table entries -3.000000 3.181847 3.363694 3.545541 3.727388 3.909234 4.091081 4.272928 4.454775 4.636622 4.818469 5.000316 5.182163 5.364010 5.545857 5.727703 5.909550 6.091397 6.273244 6.455091 6.636938 6.818785 7.000632 7.182479 7.364326 7.546172 7.728019 7.909866 8.091713 8.273560 8.831108 9.388656 9.946204 10.503752 11.061300 11.618848 12.176396 12.733944 13.291492 13.849040 14.406588 14.964136 15.521684 16.079232 16.636780 17.194328 17.751876 18.309424 18.866972 19.424520 19.982068 20.539616 21.097164 21.654712 22.212260 22.769808 23.327356 23.884904 24.442452 25.000000 ! FBP_U - Operating schedule table: Wind speeds [m/s]. -27.497174 29.163932 30.830691 32.497450 34.164208 35.830967 37.497725 39.164484 40.831243 42.498001 44.164760 45.831518 47.498277 49.165035 50.831794 52.498553 54.165311 55.832070 57.498828 59.165587 60.832346 62.499104 64.165863 65.832621 67.499380 69.166138 70.832897 72.499656 74.166414 79.853125 79.853125 79.853125 79.853125 79.853125 79.853125 79.853125 79.853125 79.853125 79.853125 79.853125 79.853125 79.853125 79.853125 79.853125 79.853125 79.853125 79.853125 79.853125 79.853125 79.853125 79.853125 79.853125 79.853125 79.853125 79.853125 79.853125 79.853125 79.853125 79.853125 79.853125 ! FBP_Omega - Operating schedule table: Generator speeds [rad/s]. -9102.377387 10239.314561 11443.140643 12713.855635 14051.459535 15455.952344 16927.334062 18465.604688 20070.764223 21742.812668 23481.750020 25287.576282 27160.291453 29099.895532 31106.388520 33179.770417 35320.041223 37527.200937 39801.249560 42142.187093 44550.013533 47024.728883 49566.333142 52174.826309 54850.208385 57592.479370 60401.639263 63277.688066 66220.625777 65712.002182 65712.002182 65712.002182 65712.002182 65712.002182 65712.002182 65712.002182 65712.002182 65712.002182 65712.002182 65712.002182 65712.002182 65712.002182 65712.002182 65712.002182 65712.002182 65712.002182 65712.002182 65712.002182 65712.002182 65712.002182 65712.002182 65712.002182 65712.002182 65712.002182 65712.002182 65712.002182 65712.002182 65712.002182 65712.002182 65712.002182 ! FBP_Tau - Operating schedule table: Generator torques [N m]. +0 ! VS_FBP_RefMode - Reference control mode (0 - Use wind speed estimator, 1 - Use torque feedback) +60 ! VS_FBP_n - Number of gain-scheduling table entries +3.000000 3.181847 3.363694 3.545541 3.727388 3.909234 4.091081 4.272928 4.454775 4.636622 4.818469 5.000316 5.182163 5.364010 5.545857 5.727703 5.909550 6.091397 6.273244 6.455091 6.636938 6.818785 7.000632 7.182479 7.364326 7.546172 7.728019 7.909866 8.091713 8.273560 8.831108 9.388656 9.946204 10.503752 11.061300 11.618848 12.176396 12.733944 13.291492 13.849040 14.406588 14.964136 15.521684 16.079232 16.636780 17.194328 17.751876 18.309424 18.866972 19.424520 19.982068 20.539616 21.097164 21.654712 22.212260 22.769808 23.327356 23.884904 24.442452 25.000000 ! VS_FBP_U - Operating schedule table: Wind speeds [m/s]. +27.497174 29.163932 30.830691 32.497450 34.164208 35.830967 37.497725 39.164484 40.831243 42.498001 44.164760 45.831518 47.498277 49.165035 50.831794 52.498553 54.165311 55.832070 57.498828 59.165587 60.832346 62.499104 64.165863 65.832621 67.499380 69.166138 70.832897 72.499656 74.166414 79.853125 79.853125 79.853125 79.853125 79.853125 79.853125 79.853125 79.853125 79.853125 79.853125 79.853125 79.853125 79.853125 79.853125 79.853125 79.853125 79.853125 79.853125 79.853125 79.853125 79.853125 79.853125 79.853125 79.853125 79.853125 79.853125 79.853125 79.853125 79.853125 79.853125 79.853125 ! VS_FBP_Omega - Operating schedule table: Generator speeds [rad/s]. +9102.377387 10239.314561 11443.140643 12713.855635 14051.459535 15455.952344 16927.334062 18465.604688 20070.764223 21742.812668 23481.750020 25287.576282 27160.291453 29099.895532 31106.388520 33179.770417 35320.041223 37527.200937 39801.249560 42142.187093 44550.013533 47024.728883 49566.333142 52174.826309 54850.208385 57592.479370 60401.639263 63277.688066 66220.625777 65712.002182 65712.002182 65712.002182 65712.002182 65712.002182 65712.002182 65712.002182 65712.002182 65712.002182 65712.002182 65712.002182 65712.002182 65712.002182 65712.002182 65712.002182 65712.002182 65712.002182 65712.002182 65712.002182 65712.002182 65712.002182 65712.002182 65712.002182 65712.002182 65712.002182 65712.002182 65712.002182 65712.002182 65712.002182 65712.002182 65712.002182 ! VS_FBP_Tau - Operating schedule table: Generator torques [N m]. !------- SETPOINT SMOOTHER --------------------------------------------- 1.00000 ! SS_VSGain - Variable speed torque controller setpoint smoother gain, [-]. diff --git a/Examples/Test_Cases/IEA-15-240-RWT-UMaineSemi/DISCON-UMaineSemi.IN b/Examples/Test_Cases/IEA-15-240-RWT-UMaineSemi/DISCON-UMaineSemi.IN index d347385c..546191da 100644 --- a/Examples/Test_Cases/IEA-15-240-RWT-UMaineSemi/DISCON-UMaineSemi.IN +++ b/Examples/Test_Cases/IEA-15-240-RWT-UMaineSemi/DISCON-UMaineSemi.IN @@ -1,5 +1,5 @@ ! Controller parameter input file for the IEA-15-240-RWT-UMaineSemi wind turbine -! - File written using ROSCO version 2.9.0 controller tuning logic on 05/10/24 +! - File written using ROSCO version 2.9.0 controller tuning logic on 05/13/24 !------- SIMULATION CONTROL ------------------------------------------------------------ 2 ! LoggingLevel - {0: write no debug files, 1: write standard output .dbg-file, 2: LoggingLevel 1 + ROSCO LocalVars (.dbg2) 3: LoggingLevel 2 + complete avrSWAP-array (.dbg3)} @@ -49,6 +49,7 @@ 0.213000 1.000000 ! F_FlCornerFreq - Natural frequency and damping in the second order low pass filter of the tower-top fore-aft motion for floating feedback control [rad/s, -]. 0.01042 ! F_FlHighPassFreq - Natural frequency of first-order high-pass filter for nacelle fore-aft motion [rad/s]. 10.4616 1.0000 ! F_FlpCornerFreq - Corner frequency and damping in the second order low pass filter of the blade root bending moment for flap control +0.05000000000 ! F_VSRefSpdCornerFreq - Corner frequency (-3dB point) in the first order low pass filter of the generator speed reference used for TSR tracking torque control [rad/s]. !------- BLADE PITCH CONTROL ---------------------------------------------- 30 ! PC_GS_n - Amount of gain-scheduling table entries @@ -81,7 +82,7 @@ 21586451.33303 ! VS_MaxTq - Maximum generator torque in Region 3 (HSS side), [Nm]. 0.000000000000 ! VS_MinTq - Minimum generator torque (HSS side), [Nm]. 0.523600000000 ! VS_MinOMSpd - Minimum generator speed [rad/s] -31393135.82403 ! VS_Rgn2K - Generator torque constant in Region 2 (HSS side). Only used in VS_ControlMode = 1,3 +32514899.86953 ! VS_Rgn2K - Generator torque constant in Region 2 (HSS side). Only used in VS_ControlMode = 1,3 15000000.00000 ! VS_RtPwr - Wind turbine rated power [W] 19624046.66639 ! VS_RtTq - Rated torque, [Nm]. 0.791680000000 ! VS_RefSpd - Rated generator speed [rad/s] @@ -89,14 +90,13 @@ -37877315.85935 ! VS_KP - Proportional gain for generator PI torque controller [-]. (Only used in the transitional 2.5 region if VS_ControlMode =/ 2) -4588245.18720 ! VS_KI - Integral gain for generator PI torque controller [s]. (Only used in the transitional 2.5 region if VS_ControlMode =/ 2) 9.00 ! VS_TSRopt - Power-maximizing region 2 tip-speed-ratio. Only used in VS_ControlMode = 2. -0.314000000000 ! VS_PwrFiltF - Low pass filter on power used to determine generator speed set point. Only used in VS_ControlMode = 3. !------- FIXED PITCH REGION 3 TORQUE CONTROL ------------------------------------------------ -0 ! FBP_RefMode - Reference control mode (0 - Use wind speed estimator, 1 - Use torque feedback) -60 ! FBP_n - Number of gain-scheduling table entries -3.000000 3.266897 3.533793 3.800690 4.067586 4.334483 4.601379 4.868276 5.135172 5.402069 5.668966 5.935862 6.202759 6.469655 6.736552 7.003448 7.270345 7.537241 7.804138 8.071034 8.337931 8.604828 8.871724 9.138621 9.405517 9.672414 9.939310 10.206207 10.473103 10.740000 11.215333 11.690667 12.166000 12.641333 13.116667 13.592000 14.067333 14.542667 15.018000 15.493333 15.968667 16.444000 16.919333 17.394667 17.870000 18.345333 18.820667 19.296000 19.771333 20.246667 20.722000 21.197333 21.672667 22.148000 22.623333 23.098667 23.574000 24.049333 24.524667 25.000000 ! FBP_U - Operating schedule table: Wind speeds [m/s]. -0.523599 0.523599 0.523599 0.523599 0.523599 0.523599 0.523599 0.523599 0.523599 0.523599 0.523599 0.523599 0.523599 0.523599 0.523599 0.525259 0.545276 0.565293 0.585310 0.605328 0.625345 0.645362 0.665379 0.685397 0.705414 0.725431 0.745448 0.765466 0.785483 0.791681 0.791681 0.791681 0.791681 0.791681 0.791681 0.791681 0.791681 0.791681 0.791681 0.791681 0.791681 0.791681 0.791681 0.791681 0.791681 0.791681 0.791681 0.791681 0.791681 0.791681 0.791681 0.791681 0.791681 0.791681 0.791681 0.791681 0.791681 0.791681 0.791681 0.791681 ! FBP_Omega - Operating schedule table: Generator speeds [rad/s]. -670491.743806 865836.356288 1095854.831758 1363379.930396 1671244.412384 2022281.037902 2419322.567131 2865201.760252 3362751.377446 3914804.178893 4524192.924774 5193750.375270 5926309.290562 6724702.430830 7591762.556256 8503366.146143 9163830.508856 9848994.075161 10558856.845058 11293418.818547 12052679.995627 12836640.376300 13645299.960564 14478658.748420 15336716.739867 16219473.934907 17126930.333538 18059085.935762 19015940.741577 20378439.244242 20378439.244242 20378439.244242 20378439.244242 20378439.244242 20378439.244242 20378439.244242 20378439.244242 20378439.244242 20378439.244242 20378439.244242 20378439.244242 20378439.244242 20378439.244242 20378439.244242 20378439.244242 20378439.244242 20378439.244242 20378439.244242 20378439.244242 20378439.244242 20378439.244242 20378439.244242 20378439.244242 20378439.244242 20378439.244242 20378439.244242 20378439.244242 20378439.244242 20378439.244242 20378439.244242 ! FBP_Tau - Operating schedule table: Generator torques [N m]. +0 ! VS_FBP_RefMode - Reference control mode (0 - Use wind speed estimator, 1 - Use torque feedback) +60 ! VS_FBP_n - Number of gain-scheduling table entries +3.000000 3.266897 3.533793 3.800690 4.067586 4.334483 4.601379 4.868276 5.135172 5.402069 5.668966 5.935862 6.202759 6.469655 6.736552 7.003448 7.270345 7.537241 7.804138 8.071034 8.337931 8.604828 8.871724 9.138621 9.405517 9.672414 9.939310 10.206207 10.473103 10.740000 11.215333 11.690667 12.166000 12.641333 13.116667 13.592000 14.067333 14.542667 15.018000 15.493333 15.968667 16.444000 16.919333 17.394667 17.870000 18.345333 18.820667 19.296000 19.771333 20.246667 20.722000 21.197333 21.672667 22.148000 22.623333 23.098667 23.574000 24.049333 24.524667 25.000000 ! VS_FBP_U - Operating schedule table: Wind speeds [m/s]. +0.523599 0.523599 0.523599 0.523599 0.523599 0.523599 0.523599 0.523599 0.523599 0.523599 0.523599 0.523599 0.523599 0.523599 0.523599 0.525259 0.545276 0.565293 0.585310 0.605328 0.625345 0.645362 0.665379 0.685397 0.705414 0.725431 0.745448 0.765466 0.785483 0.791681 0.791681 0.791681 0.791681 0.791681 0.791681 0.791681 0.791681 0.791681 0.791681 0.791681 0.791681 0.791681 0.791681 0.791681 0.791681 0.791681 0.791681 0.791681 0.791681 0.791681 0.791681 0.791681 0.791681 0.791681 0.791681 0.791681 0.791681 0.791681 0.791681 0.791681 ! VS_FBP_Omega - Operating schedule table: Generator speeds [rad/s]. +670491.743806 865836.356288 1095854.831758 1363379.930396 1671244.412384 2022281.037902 2419322.567131 2865201.760252 3362751.377446 3914804.178893 4524192.924774 5193750.375270 5926309.290562 6724702.430830 7591762.556256 8503366.146143 9163830.508856 9848994.075161 10558856.845058 11293418.818547 12052679.995627 12836640.376300 13645299.960564 14478658.748420 15336716.739867 16219473.934907 17126930.333538 18059085.935762 19015940.741577 20378439.244242 20378439.244242 20378439.244242 20378439.244242 20378439.244242 20378439.244242 20378439.244242 20378439.244242 20378439.244242 20378439.244242 20378439.244242 20378439.244242 20378439.244242 20378439.244242 20378439.244242 20378439.244242 20378439.244242 20378439.244242 20378439.244242 20378439.244242 20378439.244242 20378439.244242 20378439.244242 20378439.244242 20378439.244242 20378439.244242 20378439.244242 20378439.244242 20378439.244242 20378439.244242 20378439.244242 ! VS_FBP_Tau - Operating schedule table: Generator torques [N m]. !------- SETPOINT SMOOTHER --------------------------------------------- 1.00000 ! SS_VSGain - Variable speed torque controller setpoint smoother gain, [-]. diff --git a/Examples/Test_Cases/MHK_RM1/MHK_RM1_DISCON.IN b/Examples/Test_Cases/MHK_RM1/MHK_RM1_DISCON.IN index a11607be..5f0e722f 100644 --- a/Examples/Test_Cases/MHK_RM1/MHK_RM1_DISCON.IN +++ b/Examples/Test_Cases/MHK_RM1/MHK_RM1_DISCON.IN @@ -1,5 +1,5 @@ ! Controller parameter input file for the MHK_RM1_Floating wind turbine -! - File written using ROSCO version 2.9.0 controller tuning logic on 05/10/24 +! - File written using ROSCO version 2.9.0 controller tuning logic on 05/13/24 !------- SIMULATION CONTROL ------------------------------------------------------------ 2 ! LoggingLevel - {0: write no debug files, 1: write standard output .dbg-file, 2: LoggingLevel 1 + ROSCO LocalVars (.dbg2) 3: LoggingLevel 2 + complete avrSWAP-array (.dbg3)} @@ -49,6 +49,7 @@ 0.661300 1.000000 ! F_FlCornerFreq - Natural frequency and damping in the second order low pass filter of the tower-top fore-aft motion for floating feedback control [rad/s, -]. 1.50000 ! F_FlHighPassFreq - Natural frequency of first-order high-pass filter for nacelle fore-aft motion [rad/s]. 0.0000 1.0000 ! F_FlpCornerFreq - Corner frequency and damping in the second order low pass filter of the blade root bending moment for flap control +0.05000000000 ! F_VSRefSpdCornerFreq - Corner frequency (-3dB point) in the first order low pass filter of the generator speed reference used for TSR tracking torque control [rad/s]. !------- BLADE PITCH CONTROL ---------------------------------------------- 30 ! PC_GS_n - Amount of gain-scheduling table entries @@ -80,8 +81,8 @@ 1500000.000000 ! VS_MaxRat - Maximum torque rate (in absolute value) in torque controller, [Nm/s]. 12450.50344000 ! VS_MaxTq - Maximum generator torque in Region 3 (HSS side), [Nm]. 0.000000000000 ! VS_MinTq - Minimum generator torque (HSS side), [Nm]. -19.01313000000 ! VS_MinOMSpd - Minimum generator speed [rad/s] -1.137080000000 ! VS_Rgn2K - Generator torque constant in Region 2 (HSS side). Only used in VS_ControlMode = 1,3 +19.00787000000 ! VS_MinOMSpd - Minimum generator speed [rad/s] +1.310360000000 ! VS_Rgn2K - Generator torque constant in Region 2 (HSS side). Only used in VS_ControlMode = 1,3 500000.0000000 ! VS_RtPwr - Wind turbine rated power [W] 8300.335630000 ! VS_RtTq - Rated torque, [Nm]. 63.81200000000 ! VS_RefSpd - Rated generator speed [rad/s] @@ -89,14 +90,13 @@ -64.2578900000 ! VS_KP - Proportional gain for generator PI torque controller [-]. (Only used in the transitional 2.5 region if VS_ControlMode =/ 2) -84.4329000000 ! VS_KI - Integral gain for generator PI torque controller [s]. (Only used in the transitional 2.5 region if VS_ControlMode =/ 2) 7.17 ! VS_TSRopt - Power-maximizing region 2 tip-speed-ratio. Only used in VS_ControlMode = 2. -0.314000000000 ! VS_PwrFiltF - Low pass filter on power used to determine generator speed set point. Only used in VS_ControlMode = 3. !------- FIXED PITCH REGION 3 TORQUE CONTROL ------------------------------------------------ -0 ! FBP_RefMode - Reference control mode (0 - Use wind speed estimator, 1 - Use torque feedback) -60 ! FBP_n - Number of gain-scheduling table entries -0.500000 0.551724 0.603448 0.655172 0.706897 0.758621 0.810345 0.862069 0.913793 0.965517 1.017241 1.068966 1.120690 1.172414 1.224138 1.275862 1.327586 1.379310 1.431034 1.482759 1.534483 1.586207 1.637931 1.689655 1.741379 1.793103 1.844828 1.896552 1.948276 2.000000 2.033333 2.066667 2.100000 2.133333 2.166667 2.200000 2.233333 2.266667 2.300000 2.333333 2.366667 2.400000 2.433333 2.466667 2.500000 2.533333 2.566667 2.600000 2.633333 2.666667 2.700000 2.733333 2.766667 2.800000 2.833333 2.866667 2.900000 2.933333 2.966667 3.000000 ! FBP_U - Operating schedule table: Wind speeds [m/s]. -19.013134 20.980010 22.946886 24.913762 26.880638 28.847514 30.814390 32.781266 34.748142 36.715018 38.681894 40.648770 42.615646 44.582522 46.549398 48.516274 50.483150 52.450026 54.416902 56.383778 58.350654 60.317530 62.284406 63.812000 63.812000 63.812000 63.812000 63.812000 63.812000 63.812000 63.812000 63.812000 63.812000 63.812000 63.812000 63.812000 63.812000 63.812000 63.812000 63.812000 63.812000 63.812000 63.812000 63.812000 63.812000 63.812000 63.812000 63.812000 63.812000 63.812000 63.812000 63.812000 63.812000 63.812000 63.812000 63.812000 63.812000 63.812000 63.812000 63.812000 ! FBP_Omega - Operating schedule table: Generator speeds [rad/s]. -473.300280 576.289520 689.408850 812.658269 946.037777 1089.547374 1243.187061 1406.956837 1580.856702 1764.886656 1959.046699 2163.336832 2377.757054 2602.307365 2836.987765 3081.798255 3336.738834 3601.809502 3877.010259 4162.341105 4457.802041 4763.393066 5079.114180 5442.173156 5953.593744 6483.496857 7051.903239 7643.209401 8252.348857 8797.474880 8797.474880 8797.474880 8797.474880 8797.474880 8797.474880 8797.474880 8797.474880 8797.474880 8797.474880 8797.474880 8797.474880 8797.474880 8797.474880 8797.474880 8797.474880 8797.474880 8797.474880 8797.474880 8797.474880 8797.474880 8797.474880 8797.474880 8797.474880 8797.474880 8797.474880 8797.474880 8797.474880 8797.474880 8797.474880 8797.474880 ! FBP_Tau - Operating schedule table: Generator torques [N m]. +0 ! VS_FBP_RefMode - Reference control mode (0 - Use wind speed estimator, 1 - Use torque feedback) +60 ! VS_FBP_n - Number of gain-scheduling table entries +0.500000 0.551724 0.603448 0.655172 0.706897 0.758621 0.810345 0.862069 0.913793 0.965517 1.017241 1.068966 1.120690 1.172414 1.224138 1.275862 1.327586 1.379310 1.431034 1.482759 1.534483 1.586207 1.637931 1.689655 1.741379 1.793103 1.844828 1.896552 1.948276 2.000000 2.033333 2.066667 2.100000 2.133333 2.166667 2.200000 2.233333 2.266667 2.300000 2.333333 2.366667 2.400000 2.433333 2.466667 2.500000 2.533333 2.566667 2.600000 2.633333 2.666667 2.700000 2.733333 2.766667 2.800000 2.833333 2.866667 2.900000 2.933333 2.966667 3.000000 ! VS_FBP_U - Operating schedule table: Wind speeds [m/s]. +19.007868 20.974199 22.940530 24.906861 26.873192 28.839524 30.805855 32.772186 34.738517 36.704848 38.671179 40.637511 42.603842 44.570173 46.536504 48.502835 50.469166 52.435498 54.401829 56.368160 58.334491 60.300822 62.267153 63.812000 63.812000 63.812000 63.812000 63.812000 63.812000 63.812000 63.812000 63.812000 63.812000 63.812000 63.812000 63.812000 63.812000 63.812000 63.812000 63.812000 63.812000 63.812000 63.812000 63.812000 63.812000 63.812000 63.812000 63.812000 63.812000 63.812000 63.812000 63.812000 63.812000 63.812000 63.812000 63.812000 63.812000 63.812000 63.812000 63.812000 ! VS_FBP_Omega - Operating schedule table: Generator speeds [rad/s]. +473.431417 576.449193 689.599865 812.883432 946.299896 1089.849256 1243.531511 1407.346663 1581.294710 1765.375654 1959.589493 2163.936229 2378.415860 2603.028388 2837.773811 3082.652130 3337.663346 3602.807457 3878.084464 4163.494367 4459.037166 4764.712862 5080.521453 5442.173156 5953.593744 6483.496857 7051.903239 7643.209401 8252.348857 8797.474880 8797.474880 8797.474880 8797.474880 8797.474880 8797.474880 8797.474880 8797.474880 8797.474880 8797.474880 8797.474880 8797.474880 8797.474880 8797.474880 8797.474880 8797.474880 8797.474880 8797.474880 8797.474880 8797.474880 8797.474880 8797.474880 8797.474880 8797.474880 8797.474880 8797.474880 8797.474880 8797.474880 8797.474880 8797.474880 8797.474880 ! VS_FBP_Tau - Operating schedule table: Generator torques [N m]. !------- SETPOINT SMOOTHER --------------------------------------------- 1.00000 ! SS_VSGain - Variable speed torque controller setpoint smoother gain, [-]. @@ -117,10 +117,10 @@ 484024.50000 ! WE_Jtot - Total drivetrain inertia, including blades, hub and casted generator inertia to LSS, [kg m^2] 1025.000 ! WE_RhoAir - Air density, [kg m^-3] "MHK_RM1_Cp_Ct_Cq.txt" ! PerfFileName - File containing rotor performance tables (Cp,Ct,Cq) (absolute path or relative to this file) -36 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 +36 49 ! PerfTableSize - Size of rotor performance tables, first number refers to number of blade pitch angles, second number referse to number of tip-speed ratios 60 ! WE_FOPoles_N - Number of first-order system poles used in EKF 0.5000 0.5517 0.6034 0.6552 0.7069 0.7586 0.8103 0.8621 0.9138 0.9655 1.0172 1.0690 1.1207 1.1724 1.2241 1.2759 1.3276 1.3793 1.4310 1.4828 1.5345 1.5862 1.6379 1.6897 1.7414 1.7931 1.8448 1.8966 1.9483 2.0000 2.0333 2.0667 2.1000 2.1333 2.1667 2.2000 2.2333 2.2667 2.3000 2.3333 2.3667 2.4000 2.4333 2.4667 2.5000 2.5333 2.5667 2.6000 2.6333 2.6667 2.7000 2.7333 2.7667 2.8000 2.8333 2.8667 2.9000 2.9333 2.9667 3.0000 ! WE_FOPoles_v - Wind speeds corresponding to first-order system poles [m/s] --0.14308393 -0.15788571 -0.17268750 -0.18748928 -0.20229107 -0.21709285 -0.23189464 -0.24669643 -0.26149821 -0.27630000 -0.29110178 -0.30590357 -0.32070535 -0.33550714 -0.35030892 -0.36511071 -0.37991250 -0.39471428 -0.40951607 -0.42431785 -0.43911964 -0.45392142 -0.46872321 -0.48487459 -0.50420905 -0.51897473 -0.60027681 -0.60489437 -0.60708415 -0.55452329 0.18039231 0.15353375 0.11034116 0.05930222 0.00360074 -0.05616070 -0.11594248 -0.17921755 -0.24424769 -0.31180903 -0.38057365 -0.45117734 -0.52158847 -0.59317066 -0.66628530 -0.74082760 -0.81629342 -0.89295334 -0.97099163 -1.04925592 -1.12788429 -1.20781665 -1.28757103 -1.36845961 -1.45107295 -1.53364806 -1.61655483 -1.70142184 -1.78767141 -1.87248964 ! WE_FOPoles - First order system poles [1/s] +-0.14309872 -0.15790204 -0.17270536 -0.18750867 -0.20231199 -0.21711530 -0.23191862 -0.24672194 -0.26152525 -0.27632857 -0.29113188 -0.30593520 -0.32073852 -0.33554183 -0.35034515 -0.36514847 -0.37995178 -0.39475510 -0.40955841 -0.42436173 -0.43916505 -0.45396836 -0.46877168 -0.48487459 -0.50420905 -0.51897473 -0.60027681 -0.60489437 -0.60708415 -0.55452329 0.18039231 0.15353375 0.11034116 0.05930222 0.00360074 -0.05616070 -0.11594248 -0.17921755 -0.24424769 -0.31180903 -0.38057365 -0.45117734 -0.52158847 -0.59317066 -0.66628530 -0.74082760 -0.81629342 -0.89295334 -0.97099163 -1.04925592 -1.12788429 -1.20781665 -1.28757103 -1.36845961 -1.45107295 -1.53364806 -1.61655483 -1.70142184 -1.78767141 -1.87248964 ! WE_FOPoles - First order system poles [1/s] !------- YAW CONTROL ------------------------------------------------------ 0.00000 ! Y_uSwitch - Wind speed to switch between Y_ErrThresh. If zero, only the second value of Y_ErrThresh is used [m/s] diff --git a/Examples/Test_Cases/NREL-5MW/DISCON.IN b/Examples/Test_Cases/NREL-5MW/DISCON.IN index bb6d8c4e..f49dafb4 100644 --- a/Examples/Test_Cases/NREL-5MW/DISCON.IN +++ b/Examples/Test_Cases/NREL-5MW/DISCON.IN @@ -1,5 +1,5 @@ ! Controller parameter input file for the NREL-5MW wind turbine -! - File written using ROSCO version 2.9.0 controller tuning logic on 05/10/24 +! - File written using ROSCO version 2.9.0 controller tuning logic on 05/13/24 !------- SIMULATION CONTROL ------------------------------------------------------------ 1 ! LoggingLevel - {0: write no debug files, 1: write standard output .dbg-file, 2: LoggingLevel 1 + ROSCO LocalVars (.dbg2) 3: LoggingLevel 2 + complete avrSWAP-array (.dbg3)} @@ -49,6 +49,7 @@ 0.000000 1.000000 ! F_FlCornerFreq - Natural frequency and damping in the second order low pass filter of the tower-top fore-aft motion for floating feedback control [rad/s, -]. 0.01042 ! F_FlHighPassFreq - Natural frequency of first-order high-pass filter for nacelle fore-aft motion [rad/s]. 0.0000 1.0000 ! F_FlpCornerFreq - Corner frequency and damping in the second order low pass filter of the blade root bending moment for flap control +0.05000000000 ! F_VSRefSpdCornerFreq - Corner frequency (-3dB point) in the first order low pass filter of the generator speed reference used for TSR tracking torque control [rad/s]. !------- BLADE PITCH CONTROL ---------------------------------------------- 30 ! PC_GS_n - Amount of gain-scheduling table entries @@ -81,7 +82,7 @@ 47402.87063000 ! VS_MaxTq - Maximum generator torque in Region 3 (HSS side), [Nm]. 0.000000000000 ! VS_MinTq - Minimum generator torque (HSS side), [Nm]. 35.29006000000 ! VS_MinOMSpd - Minimum generator speed [rad/s] -2.063350000000 ! VS_Rgn2K - Generator torque constant in Region 2 (HSS side). Only used in VS_ControlMode = 1,3 +2.185750000000 ! VS_Rgn2K - Generator torque constant in Region 2 (HSS side). Only used in VS_ControlMode = 1,3 5000000.000000 ! VS_RtPwr - Wind turbine rated power [W] 43093.51876000 ! VS_RtTq - Rated torque, [Nm]. 122.9096700000 ! VS_RefSpd - Rated generator speed [rad/s] @@ -89,14 +90,13 @@ -657.442080000 ! VS_KP - Proportional gain for generator PI torque controller [-]. (Only used in the transitional 2.5 region if VS_ControlMode =/ 2) -104.507080000 ! VS_KI - Integral gain for generator PI torque controller [s]. (Only used in the transitional 2.5 region if VS_ControlMode =/ 2) 7.64 ! VS_TSRopt - Power-maximizing region 2 tip-speed-ratio. Only used in VS_ControlMode = 2. -0.314000000000 ! VS_PwrFiltF - Low pass filter on power used to determine generator speed set point. Only used in VS_ControlMode = 3. !------- FIXED PITCH REGION 3 TORQUE CONTROL ------------------------------------------------ -0 ! FBP_RefMode - Reference control mode (0 - Use wind speed estimator, 1 - Use torque feedback) -60 ! FBP_n - Number of gain-scheduling table entries -3.000000 3.289655 3.579310 3.868966 4.158621 4.448276 4.737931 5.027586 5.317241 5.606897 5.896552 6.186207 6.475862 6.765517 7.055172 7.344828 7.634483 7.924138 8.213793 8.503448 8.793103 9.082759 9.372414 9.662069 9.951724 10.241379 10.531034 10.820690 11.110345 11.400000 11.853333 12.306667 12.760000 13.213333 13.666667 14.120000 14.573333 15.026667 15.480000 15.933333 16.386667 16.840000 17.293333 17.746667 18.200000 18.653333 19.106667 19.560000 20.013333 20.466667 20.920000 21.373333 21.826667 22.280000 22.733333 23.186667 23.640000 24.093333 24.546667 25.000000 ! FBP_U - Operating schedule table: Wind speeds [m/s]. -35.290063 38.697380 42.104696 45.512012 48.919329 52.326645 55.733962 59.141278 62.548595 65.955911 69.363228 72.770544 76.177860 79.585177 82.992493 86.399810 89.807126 93.214443 96.621759 100.029076 103.436392 106.843708 110.251025 113.658341 117.065658 120.472974 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 ! FBP_Omega - Operating schedule table: Generator speeds [rad/s]. -2722.104214 3273.128021 3874.904020 4527.432212 5230.712597 5984.745175 6789.529945 7645.066908 8551.356064 9508.397412 10516.190954 11574.736688 12684.034614 13844.084733 15054.887046 16316.441550 17628.748248 18991.807138 20405.618221 21870.181497 23385.496965 24951.564626 26568.384480 28235.956527 29954.280766 31723.357198 33808.077172 36640.947188 39612.510839 42557.267110 42557.267110 42557.267110 42557.267110 42557.267110 42557.267110 42557.267110 42557.267110 42557.267110 42557.267110 42557.267110 42557.267110 42557.267110 42557.267110 42557.267110 42557.267110 42557.267110 42557.267110 42557.267110 42557.267110 42557.267110 42557.267110 42557.267110 42557.267110 42557.267110 42557.267110 42557.267110 42557.267110 42557.267110 42557.267110 42557.267110 ! FBP_Tau - Operating schedule table: Generator torques [N m]. +0 ! VS_FBP_RefMode - Reference control mode (0 - Use wind speed estimator, 1 - Use torque feedback) +60 ! VS_FBP_n - Number of gain-scheduling table entries +3.000000 3.289655 3.579310 3.868966 4.158621 4.448276 4.737931 5.027586 5.317241 5.606897 5.896552 6.186207 6.475862 6.765517 7.055172 7.344828 7.634483 7.924138 8.213793 8.503448 8.793103 9.082759 9.372414 9.662069 9.951724 10.241379 10.531034 10.820690 11.110345 11.400000 11.853333 12.306667 12.760000 13.213333 13.666667 14.120000 14.573333 15.026667 15.480000 15.933333 16.386667 16.840000 17.293333 17.746667 18.200000 18.653333 19.106667 19.560000 20.013333 20.466667 20.920000 21.373333 21.826667 22.280000 22.733333 23.186667 23.640000 24.093333 24.546667 25.000000 ! VS_FBP_U - Operating schedule table: Wind speeds [m/s]. +35.290063 38.697380 42.104696 45.512012 48.919329 52.326645 55.733962 59.141278 62.548595 65.955911 69.363228 72.770544 76.177860 79.585177 82.992493 86.399810 89.807126 93.214443 96.621759 100.029076 103.436392 106.843708 110.251025 113.658341 117.065658 120.472974 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 ! VS_FBP_Omega - Operating schedule table: Generator speeds [rad/s]. +2722.104214 3273.128021 3874.904020 4527.432212 5230.712597 5984.745175 6789.529945 7645.066908 8551.356064 9508.397412 10516.190954 11574.736688 12684.034614 13844.084733 15054.887046 16316.441550 17628.748248 18991.807138 20405.618221 21870.181497 23385.496965 24951.564626 26568.384480 28235.956527 29954.280766 31723.357198 33808.077172 36640.947188 39612.510839 42557.267110 42557.267110 42557.267110 42557.267110 42557.267110 42557.267110 42557.267110 42557.267110 42557.267110 42557.267110 42557.267110 42557.267110 42557.267110 42557.267110 42557.267110 42557.267110 42557.267110 42557.267110 42557.267110 42557.267110 42557.267110 42557.267110 42557.267110 42557.267110 42557.267110 42557.267110 42557.267110 42557.267110 42557.267110 42557.267110 42557.267110 ! VS_FBP_Tau - Operating schedule table: Generator torques [N m]. !------- SETPOINT SMOOTHER --------------------------------------------- 1.00000 ! SS_VSGain - Variable speed torque controller setpoint smoother gain, [-]. diff --git a/Examples/Test_Cases/NREL_2p8_127/NREL-2p8-127_DISCON.IN b/Examples/Test_Cases/NREL_2p8_127/NREL-2p8-127_DISCON.IN index 5d9ae259..663e4334 100644 --- a/Examples/Test_Cases/NREL_2p8_127/NREL-2p8-127_DISCON.IN +++ b/Examples/Test_Cases/NREL_2p8_127/NREL-2p8-127_DISCON.IN @@ -1,5 +1,5 @@ ! Controller parameter input file for the NREL-2p8-127 wind turbine -! - File written using ROSCO version 2.9.0 controller tuning logic on 05/10/24 +! - File written using ROSCO version 2.9.0 controller tuning logic on 05/13/24 !------- SIMULATION CONTROL ------------------------------------------------------------ 2 ! LoggingLevel - {0: write no debug files, 1: write standard output .dbg-file, 2: LoggingLevel 1 + ROSCO LocalVars (.dbg2) 3: LoggingLevel 2 + complete avrSWAP-array (.dbg3)} @@ -49,6 +49,7 @@ 0.000000 1.000000 ! F_FlCornerFreq - Natural frequency and damping in the second order low pass filter of the tower-top fore-aft motion for floating feedback control [rad/s, -]. 0.01042 ! F_FlHighPassFreq - Natural frequency of first-order high-pass filter for nacelle fore-aft motion [rad/s]. 0.0000 1.0000 ! F_FlpCornerFreq - Corner frequency and damping in the second order low pass filter of the blade root bending moment for flap control +0.05000000000 ! F_VSRefSpdCornerFreq - Corner frequency (-3dB point) in the first order low pass filter of the generator speed reference used for TSR tracking torque control [rad/s]. !------- BLADE PITCH CONTROL ---------------------------------------------- 30 ! PC_GS_n - Amount of gain-scheduling table entries @@ -81,7 +82,7 @@ 26673.40024000 ! VS_MaxTq - Maximum generator torque in Region 3 (HSS side), [Nm]. 0.000000000000 ! VS_MinTq - Minimum generator torque (HSS side), [Nm]. 37.81562000000 ! VS_MinOMSpd - Minimum generator speed [rad/s] -1.654680000000 ! VS_Rgn2K - Generator torque constant in Region 2 (HSS side). Only used in VS_ControlMode = 1,3 +1.844270000000 ! VS_Rgn2K - Generator torque constant in Region 2 (HSS side). Only used in VS_ControlMode = 1,3 2800000.000000 ! VS_RtPwr - Wind turbine rated power [W] 24248.54567000 ! VS_RtTq - Rated torque, [Nm]. 122.9096700000 ! VS_RefSpd - Rated generator speed [rad/s] @@ -89,14 +90,13 @@ -600.450450000 ! VS_KP - Proportional gain for generator PI torque controller [-]. (Only used in the transitional 2.5 region if VS_ControlMode =/ 2) -85.3230300000 ! VS_KI - Integral gain for generator PI torque controller [s]. (Only used in the transitional 2.5 region if VS_ControlMode =/ 2) 8.25 ! VS_TSRopt - Power-maximizing region 2 tip-speed-ratio. Only used in VS_ControlMode = 2. -0.314000000000 ! VS_PwrFiltF - Low pass filter on power used to determine generator speed set point. Only used in VS_ControlMode = 3. !------- FIXED PITCH REGION 3 TORQUE CONTROL ------------------------------------------------ -0 ! FBP_RefMode - Reference control mode (0 - Use wind speed estimator, 1 - Use torque feedback) -60 ! FBP_n - Number of gain-scheduling table entries -3.000000 3.289655 3.579310 3.868966 4.158621 4.448276 4.737931 5.027586 5.317241 5.606897 5.896552 6.186207 6.475862 6.765517 7.055172 7.344828 7.634483 7.924138 8.213793 8.503448 8.793103 9.082759 9.372414 9.662069 9.951724 10.241379 10.531034 10.820690 11.110345 11.400000 11.853333 12.306667 12.760000 13.213333 13.666667 14.120000 14.573333 15.026667 15.480000 15.933333 16.386667 16.840000 17.293333 17.746667 18.200000 18.653333 19.106667 19.560000 20.013333 20.466667 20.920000 21.373333 21.826667 22.280000 22.733333 23.186667 23.640000 24.093333 24.546667 25.000000 ! FBP_U - Operating schedule table: Wind speeds [m/s]. -37.815619 41.466782 45.117946 48.769109 52.420272 56.071435 59.722599 63.373762 67.024925 70.676088 74.327252 77.978415 81.629578 85.280741 88.931905 92.583068 96.234231 99.885394 103.536557 107.187721 110.838884 114.490047 118.141210 121.792374 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 ! FBP_Omega - Operating schedule table: Generator speeds [rad/s]. -2637.346056 3171.212635 3754.251136 4386.461558 5067.843901 5798.398167 6578.124354 7407.022463 8285.092494 9212.334446 10188.748320 11214.334116 12289.091834 13413.021473 14586.123034 15808.396517 17079.841921 18400.459247 19770.248495 21189.209665 22657.342756 24174.647769 25741.124704 27356.773561 29584.316737 32095.342171 34687.873109 37276.821338 39798.060940 42179.037757 42179.037757 42179.037757 42179.037757 42179.037757 42179.037757 42179.037757 42179.037757 42179.037757 42179.037757 42179.037757 42179.037757 42179.037757 42179.037757 42179.037757 42179.037757 42179.037757 42179.037757 42179.037757 42179.037757 42179.037757 42179.037757 42179.037757 42179.037757 42179.037757 42179.037757 42179.037757 42179.037757 42179.037757 42179.037757 42179.037757 ! FBP_Tau - Operating schedule table: Generator torques [N m]. +0 ! VS_FBP_RefMode - Reference control mode (0 - Use wind speed estimator, 1 - Use torque feedback) +60 ! VS_FBP_n - Number of gain-scheduling table entries +3.000000 3.289655 3.579310 3.868966 4.158621 4.448276 4.737931 5.027586 5.317241 5.606897 5.896552 6.186207 6.475862 6.765517 7.055172 7.344828 7.634483 7.924138 8.213793 8.503448 8.793103 9.082759 9.372414 9.662069 9.951724 10.241379 10.531034 10.820690 11.110345 11.400000 11.853333 12.306667 12.760000 13.213333 13.666667 14.120000 14.573333 15.026667 15.480000 15.933333 16.386667 16.840000 17.293333 17.746667 18.200000 18.653333 19.106667 19.560000 20.013333 20.466667 20.920000 21.373333 21.826667 22.280000 22.733333 23.186667 23.640000 24.093333 24.546667 25.000000 ! VS_FBP_U - Operating schedule table: Wind speeds [m/s]. +37.815619 41.466782 45.117946 48.769109 52.420272 56.071435 59.722599 63.373762 67.024925 70.676088 74.327252 77.978415 81.629578 85.280741 88.931905 92.583068 96.234231 99.885394 103.536557 107.187721 110.838884 114.490047 118.141210 121.792374 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 ! VS_FBP_Omega - Operating schedule table: Generator speeds [rad/s]. +2637.346056 3171.212635 3754.251136 4386.461558 5067.843901 5798.398167 6578.124354 7407.022463 8285.092494 9212.334446 10188.748320 11214.334116 12289.091834 13413.021473 14586.123034 15808.396517 17079.841921 18400.459247 19770.248495 21189.209665 22657.342756 24174.647769 25741.124704 27356.773561 29584.316737 32095.342171 34687.873109 37276.821338 39798.060940 42179.037757 42179.037757 42179.037757 42179.037757 42179.037757 42179.037757 42179.037757 42179.037757 42179.037757 42179.037757 42179.037757 42179.037757 42179.037757 42179.037757 42179.037757 42179.037757 42179.037757 42179.037757 42179.037757 42179.037757 42179.037757 42179.037757 42179.037757 42179.037757 42179.037757 42179.037757 42179.037757 42179.037757 42179.037757 42179.037757 42179.037757 ! VS_FBP_Tau - Operating schedule table: Generator torques [N m]. !------- SETPOINT SMOOTHER --------------------------------------------- 1.00000 ! SS_VSGain - Variable speed torque controller setpoint smoother gain, [-]. diff --git a/rosco/controller/src/ReadSetParameters.f90 b/rosco/controller/src/ReadSetParameters.f90 index 6542141a..4acbfb00 100644 --- a/rosco/controller/src/ReadSetParameters.f90 +++ b/rosco/controller/src/ReadSetParameters.f90 @@ -385,7 +385,7 @@ SUBROUTINE ReadControlParameterFileSub(CntrPar, LocalVar, accINFILE, accINFILE_s CALL ParseInput(FileLines, 'F_FlHighPassFreq', CntrPar%F_FlHighPassFreq, accINFILE(1), ErrVar, CntrPar%FL_Mode == 0, UnEc) CALL ParseAry( FileLines, 'F_FlpCornerFreq', CntrPar%F_FlpCornerFreq, 2, accINFILE(1), ErrVar, CntrPar%Flp_Mode == 0, UnEc) CALL ParseInput(FileLines, 'F_VSRefSpdCornerFreq', CntrPar%F_VSRefSpdCornerFreq, accINFILE(1), ErrVar, CntrPar%VS_ControlMode < 2, UnEc) - + ! Optional filter inds IF (CntrPar%F_GenSpdNotch_N > 0) THEN CALL ParseAry(FileLines, 'F_GenSpdNotch_Ind', CntrPar%F_GenSpdNotch_Ind, CntrPar%F_GenSpdNotch_N, accINFILE(1), ErrVar, CntrPar%F_GenSpdNotch_N == 0, UnEc) From 7726f0d47f706a209f1b1cae5f70a388857f445e Mon Sep 17 00:00:00 2001 From: dzalkind Date: Wed, 15 May 2024 09:49:39 -0600 Subject: [PATCH 150/224] Disable the pitch controller at the DISCON level --- rosco/controller/src/Controllers.f90 | 29 +++++++++------------------- rosco/controller/src/DISCON.F90 | 4 +++- 2 files changed, 12 insertions(+), 21 deletions(-) diff --git a/rosco/controller/src/Controllers.f90 b/rosco/controller/src/Controllers.f90 index 36c09c64..63a7fd48 100644 --- a/rosco/controller/src/Controllers.f90 +++ b/rosco/controller/src/Controllers.f90 @@ -50,26 +50,15 @@ SUBROUTINE PitchControl(avrSWAP, CntrPar, LocalVar, objInst, DebugVar, ErrVar) LocalVar%PC_MaxPit = CntrPar%PC_FinePit END IF - IF (CntrPar%VS_ControlMode .NE. VS_Mode_FBP) THEN - ! Compute (interpolate) the gains based on previously commanded blade pitch angles and lookup table: - LocalVar%PC_KP = interp1d(CntrPar%PC_GS_angles, CntrPar%PC_GS_KP, LocalVar%PC_PitComTF, ErrVar) ! Proportional gain - LocalVar%PC_KI = interp1d(CntrPar%PC_GS_angles, CntrPar%PC_GS_KI, LocalVar%PC_PitComTF, ErrVar) ! Integral gain - LocalVar%PC_KD = interp1d(CntrPar%PC_GS_angles, CntrPar%PC_GS_KD, LocalVar%PC_PitComTF, ErrVar) ! Derivative gain - LocalVar%PC_TF = interp1d(CntrPar%PC_GS_angles, CntrPar%PC_GS_TF, LocalVar%PC_PitComTF, ErrVar) ! TF gains (derivative filter) !NJA - need to clarify - - ! Compute the collective pitch command associated with the proportional and integral gains: - LocalVar%PC_PitComT = PIController(LocalVar%PC_SpdErr, LocalVar%PC_KP, LocalVar%PC_KI, LocalVar%PC_MinPit, LocalVar%PC_MaxPit, LocalVar%DT, LocalVar%BlPitch(1), LocalVar%piP, LocalVar%restart, objInst%instPI) - DebugVar%PC_PICommand = LocalVar%PC_PitComT - ELSE - ! Avoid the need to interpolate and compute gains for fixed-pitch control - LocalVar%PC_KP = 0.0 - LocalVar%PC_KI = 0.0 - LocalVar%PC_KD = 0.0 - LocalVar%PC_TF = 0.0 - - LocalVar%PC_PitComT = CntrPar%PC_FinePit - DebugVar%PC_PICommand = LocalVar%PC_PitComT - ENDIF + ! Compute (interpolate) the gains based on previously commanded blade pitch angles and lookup table: + LocalVar%PC_KP = interp1d(CntrPar%PC_GS_angles, CntrPar%PC_GS_KP, LocalVar%PC_PitComTF, ErrVar) ! Proportional gain + LocalVar%PC_KI = interp1d(CntrPar%PC_GS_angles, CntrPar%PC_GS_KI, LocalVar%PC_PitComTF, ErrVar) ! Integral gain + LocalVar%PC_KD = interp1d(CntrPar%PC_GS_angles, CntrPar%PC_GS_KD, LocalVar%PC_PitComTF, ErrVar) ! Derivative gain + LocalVar%PC_TF = interp1d(CntrPar%PC_GS_angles, CntrPar%PC_GS_TF, LocalVar%PC_PitComTF, ErrVar) ! TF gains (derivative filter) !NJA - need to clarify + + ! Compute the collective pitch command associated with the proportional and integral gains: + LocalVar%PC_PitComT = PIController(LocalVar%PC_SpdErr, LocalVar%PC_KP, LocalVar%PC_KI, LocalVar%PC_MinPit, LocalVar%PC_MaxPit, LocalVar%DT, LocalVar%BlPitch(1), LocalVar%piP, LocalVar%restart, objInst%instPI) + DebugVar%PC_PICommand = LocalVar%PC_PitComT ! Find individual pitch control contribution IF ((CntrPar%IPC_ControlMode >= 1) .OR. (CntrPar%Y_ControlMode == 2)) THEN diff --git a/rosco/controller/src/DISCON.F90 b/rosco/controller/src/DISCON.F90 index 4787e19f..39334b6b 100644 --- a/rosco/controller/src/DISCON.F90 +++ b/rosco/controller/src/DISCON.F90 @@ -105,7 +105,9 @@ SUBROUTINE DISCON(avrSWAP, aviFAIL, accINFILE, avcOUTNAME, avcMSG) BIND (C, NAME CALL StateMachine(CntrPar, LocalVar) CALL SetpointSmoother(LocalVar, CntrPar, objInst) CALL VariableSpeedControl(avrSWAP, CntrPar, LocalVar, objInst, ErrVar) - CALL PitchControl(avrSWAP, CntrPar, LocalVar, objInst, DebugVar, ErrVar) + IF (CntrPar%PC_ControlMode > 0) THEN + CALL PitchControl(avrSWAP, CntrPar, LocalVar, objInst, DebugVar, ErrVar) + END IF IF (CntrPar%Y_ControlMode > 0) THEN CALL YawRateControl(avrSWAP, CntrPar, LocalVar, objInst, DebugVar, ErrVar) From 01121e2ea03c098731809b03b5d9442661adef17 Mon Sep 17 00:00:00 2001 From: David Stockhouse Date: Wed, 15 May 2024 17:46:53 -0600 Subject: [PATCH 151/224] Working on overspeed operating schedule, still not yet giving stable results --- Examples/29_marine_hydro_fbp.py | 46 +++++++++++++++-------- Examples/Tune_Cases/RM1_MHK_FBP.yaml | 9 +++-- rosco/controller/src/ControllerBlocks.f90 | 9 ++--- 3 files changed, 40 insertions(+), 24 deletions(-) diff --git a/Examples/29_marine_hydro_fbp.py b/Examples/29_marine_hydro_fbp.py index f53ec301..62bb46cb 100644 --- a/Examples/29_marine_hydro_fbp.py +++ b/Examples/29_marine_hydro_fbp.py @@ -59,46 +59,62 @@ def main(): ### Tune controller cases # Constant power underspeed (should be the default) - controller_params['VS_FBP_speed_mode'] = 0 - controller_params['VS_FBP_P'] = [1.0, 1.0] - controller_1 = ROSCO_controller.Controller(controller_params) + controller_params_1 = controller_params.copy() + controller_params_1['VS_FBP_ref_mode'] = 0 # Switch to WSE reference + controller_params_1['VS_FBP_speed_mode'] = 0 + controller_params_1['VS_FBP_P'] = [1.0, 1.0] + controller_1 = ROSCO_controller.Controller(controller_params_1) controller_1.tune_controller(turbine) # Constant power overspeed - controller_params['VS_FBP_ref_mode'] = 0 # Switch to WSE reference - controller_params['VS_FBP_speed_mode'] = 1 - controller_params['VS_FBP_P'] = [1.0, 1.0] - controller_2 = ROSCO_controller.Controller(controller_params) + controller_params_2 = controller_params.copy() + controller_params_2['VS_FBP_ref_mode'] = 0 # Switch to WSE reference + controller_params_2['VS_FBP_speed_mode'] = 1 + controller_params_2['VS_FBP_P'] = [1.0, 1.0] + controller_2 = ROSCO_controller.Controller(controller_params_2) controller_2.tune_controller(turbine) # Linear increasing power - controller_params['VS_FBP_speed_mode'] = 0 - controller_params['VS_FBP_P'] = [1.0, 2.0] - controller_3 = ROSCO_controller.Controller(controller_params) + controller_params_3 = controller_params.copy() + controller_params_3['VS_FBP_speed_mode'] = 0 + controller_params_3['VS_FBP_P'] = [1.0, 2.0] + controller_3 = ROSCO_controller.Controller(controller_params_3) controller_3.tune_controller(turbine) # Linear increasing power, leveling out - controller_params['VS_FBP_U'] = [2.0, 3.0] - controller_params['VS_FBP_P'] = [1.0, 2.0] - controller_4 = ROSCO_controller.Controller(controller_params) + controller_params_4 = controller_params.copy() + controller_params_4['VS_FBP_U'] = [2.0, 3.0] + controller_params_4['VS_FBP_P'] = [1.0, 2.0] + controller_4 = ROSCO_controller.Controller(controller_params_4) controller_4.tune_controller(turbine) + # Generic numeric function + controller_params_5 = controller_params.copy() + controller_params_5['VS_FBP_ref_mode'] = 0 # Switch to WSE reference + controller_params_5['VS_FBP_U'] = [2.0, 2.2, 2.4, 2.6, 2.8, 3.0, 3.2, 3.4, 3.6, 3.8, 4.0] + controller_params_5['VS_FBP_P'] = [1.0, 1.3, 1.6, 1.8, 1.9, 2.0, 1.9, 1.8, 1.7, 1.6, 1.5] + controller_5 = ROSCO_controller.Controller(controller_params_5) + controller_5.tune_controller(turbine) + fig, axs = plt.subplots(3,1) axs[0].plot(controller_1.v, controller_1.power_op, label='Constant Power Underspeed') axs[0].plot(controller_2.v, controller_2.power_op, linestyle='--', label='Constant Power Overspeed') axs[0].plot(controller_3.v, controller_3.power_op, label='Linear Increasing Power') axs[0].plot(controller_4.v, controller_4.power_op, label='Increasing Leveled Power') + axs[0].plot(controller_5.v, controller_5.power_op, label='Generic') axs[0].set_ylabel('Gen Power [W]') axs[1].plot(controller_1.v, controller_1.omega_gen_op, label='Constant Power Underspeed') axs[1].plot(controller_2.v, controller_2.omega_gen_op, linestyle='--', label='Constant Power Overspeed') axs[1].plot(controller_3.v, controller_3.omega_gen_op, label='Linear Increasing Power') axs[1].plot(controller_4.v, controller_4.omega_gen_op, label='Increasing Leveled Power') + axs[1].plot(controller_5.v, controller_5.omega_gen_op, label='Generic') axs[1].set_ylabel('Gen Speed [rad/s]') axs[2].plot(controller_1.v, controller_1.tau_op, label='Constant Power Underspeed') axs[2].plot(controller_2.v, controller_2.tau_op, linestyle='--', label='Constant Power Overspeed') axs[2].plot(controller_3.v, controller_3.tau_op, label='Linear Increasing Power') axs[2].plot(controller_4.v, controller_4.tau_op, label='Increasing Leveled Power') + axs[2].plot(controller_5.v, controller_5.tau_op, label='Generic') axs[2].set_ylabel('Gen Torque [N m]') axs[2].set_xlabel('Flow Speed [m/s]') axs[0].legend(loc='upper left') @@ -113,7 +129,7 @@ def main(): # Write parameter input file for constant power underspeed controller param_file = os.path.join(run_dir,'DISCON.IN') write_DISCON(turbine, - controller_1, + controller_2, param_file=param_file, txt_filename=cp_filename ) @@ -131,7 +147,7 @@ def main(): } r.case_inputs = {} # r.fst_vt = reader.fst_vt - # r.controller_params = controller_params + r.controller_params = controller_params_2 r.save_dir = run_dir r.rosco_dir = rosco_dir diff --git a/Examples/Tune_Cases/RM1_MHK_FBP.yaml b/Examples/Tune_Cases/RM1_MHK_FBP.yaml index 725f6631..a3862f77 100644 --- a/Examples/Tune_Cases/RM1_MHK_FBP.yaml +++ b/Examples/Tune_Cases/RM1_MHK_FBP.yaml @@ -55,10 +55,11 @@ controller_params: sd_maxpit: 0.4363 # Maximum blade pitch angle to initiate shutdown [rad], {default = bld pitch at v_max} Kp_float: -0.3897 max_torque_factor: 5 - VS_FBP_ref_mode: 1 - VS_FBP_P_mode: 0 - VS_FBP_U: [2.0, 4.0] - VS_FBP_P: [1.0, 1.0] + VS_FBP_ref_mode: 1 + VS_FBP_power_mode: 0 + VS_FBP_speed_mode: 0 + VS_FBP_U: [2.0, 4.0] + VS_FBP_P: [1.0, 1.0] DISCON: F_NumNotchFilts: 0 F_NotchFreqs: [1.0, 2.4200] # 2P diff --git a/rosco/controller/src/ControllerBlocks.f90 b/rosco/controller/src/ControllerBlocks.f90 index 67da4306..425bf18f 100644 --- a/rosco/controller/src/ControllerBlocks.f90 +++ b/rosco/controller/src/ControllerBlocks.f90 @@ -34,8 +34,6 @@ SUBROUTINE ComputeVariablesSetpoints(CntrPar, LocalVar, objInst, DebugVar, ErrVa TYPE(DebugVariables), INTENT(INOUT) :: DebugVar TYPE(ErrorVariables), INTENT(INOUT) :: ErrVar - REAL(DbKi) :: VS_RefSpdRaw ! Temporary variable for applying LPF to the reference speed after it is generated - ! ----- Pitch controller speed and power error ----- ! Power reference tracking generator speed @@ -70,9 +68,9 @@ SUBROUTINE ComputeVariablesSetpoints(CntrPar, LocalVar, objInst, DebugVar, ErrVa ELSEIF (CntrPar%VS_ControlMode == 4) THEN ! Generic lookup table for genspeed reference IF (CntrPar%VS_FBP_RefMode == 0) THEN ! Use WSE to look up speed reference - VS_RefSpdRaw = interp1d(CntrPar%VS_FBP_U, CntrPar%VS_FBP_Omega, LocalVar%WE_Vw, ErrVar) + LocalVar%VS_RefSpd_TSR = interp1d(CntrPar%VS_FBP_U, CntrPar%VS_FBP_Omega, LocalVar%WE_Vw, ErrVar) ELSEIF (CntrPar%VS_FBP_RefMode == 1) THEN ! Use LocalVar%GenTq or LocalVar%GenTqMeas, Omega must be expressed as a function of Tau - VS_RefSpdRaw = interp1d(CntrPar%VS_FBP_Tau, CntrPar%VS_FBP_Omega, LocalVar%GenTq, ErrVar) + LocalVar%VS_RefSpd_TSR = interp1d(CntrPar%VS_FBP_Tau, CntrPar%VS_FBP_Omega, LocalVar%GenTq, ErrVar) ENDIF ELSE ! Generate constant reference @@ -88,7 +86,8 @@ SUBROUTINE ComputeVariablesSetpoints(CntrPar, LocalVar, objInst, DebugVar, ErrVa END IF ! Saturate torque reference speed between min speed and rated speed - LocalVar%VS_RefSpd = saturate(LocalVar%VS_RefSpd,CntrPar%VS_MinOMSpd, CntrPar%VS_RefSpd) + ! LocalVar%VS_RefSpd = saturate(LocalVar%VS_RefSpd, CntrPar%VS_MinOMSpd, CntrPar%VS_RefSpd) + ! Saturate torque reference speed above lower bound (below) ! Implement power reference rotor speed (overwrites above), convert to generator speed IF (CntrPar%PRC_Mode == 1) THEN From ab7a1f86ad7661c86750eec564b8ab52015fa8b5 Mon Sep 17 00:00:00 2001 From: dzalkind <65573423+dzalkind@users.noreply.github.com> Date: Fri, 14 Jun 2024 11:41:23 -0600 Subject: [PATCH 152/224] Update .readthedocs.yaml --- .readthedocs.yaml | 5 +++++ 1 file changed, 5 insertions(+) diff --git a/.readthedocs.yaml b/.readthedocs.yaml index 061090c2..2ed53743 100644 --- a/.readthedocs.yaml +++ b/.readthedocs.yaml @@ -10,6 +10,11 @@ build: os: ubuntu-22.04 tools: python: "mambaforge-22.9" + jobs: + # Read the docs needs a couple packages not in the environment file + pre_install: + - conda install -y cmake compilers sphinx sphinxcontrib-bibtex + - conda install sphinx_rtd_theme>=1.3 conda: environment: environment.yml From 7870a01f31e8990eb13073c4707d2e92cf6ef0ac Mon Sep 17 00:00:00 2001 From: dzalkind Date: Fri, 14 Jun 2024 14:20:30 -0600 Subject: [PATCH 153/224] Implement open loop PRC inputs --- .../rosco_registry/rosco_types.yaml | 21 ++++++++++ rosco/controller/src/ControllerBlocks.f90 | 20 ++++++++- rosco/controller/src/ROSCO_Types.f90 | 6 +++ rosco/controller/src/ReadSetParameters.f90 | 42 ++++++++++++++++++- rosco/toolbox/controller.py | 39 ++++++++++++++++- rosco/toolbox/inputs/toolbox_schema.yaml | 27 ++++++++++++ rosco/toolbox/utilities.py | 8 +++- 7 files changed, 158 insertions(+), 5 deletions(-) diff --git a/rosco/controller/rosco_registry/rosco_types.yaml b/rosco/controller/rosco_registry/rosco_types.yaml index eb31f067..506bc093 100644 --- a/rosco/controller/rosco_registry/rosco_types.yaml +++ b/rosco/controller/rosco_registry/rosco_types.yaml @@ -527,6 +527,15 @@ ControlParameters: Ind_YawRate: <<: *integer description: The column in OL_Filename that contains the generator torque in Nm + Ind_R_Speed: + <<: *integer + description: The column in OL_Filename that contains the generator torque in Nm + Ind_R_Torque: + <<: *integer + description: The column in OL_Filename that contains the generator torque in Nm + Ind_R_Pitch: + <<: *integer + description: The column in OL_Filename that contains the generator torque in Nm Ind_Azimuth: <<: *integer description: The column in OL_Filename that contains the desired azimuth position in rad (used if OL_Mode = 2) @@ -578,6 +587,18 @@ ControlParameters: <<: *real allocatable: True description: Open loop azimuth timeseries + OL_R_Speed: + <<: *real + allocatable: True + description: Open loop R_Speed timeseries + OL_R_Torque: + <<: *real + allocatable: True + description: Open loop R_Torque timeseries + OL_R_Pitch: + <<: *real + allocatable: True + description: Open loop R_Pitch timeseries OL_Channels: <<: *real allocatable: True diff --git a/rosco/controller/src/ControllerBlocks.f90 b/rosco/controller/src/ControllerBlocks.f90 index a3555422..05a70b7e 100644 --- a/rosco/controller/src/ControllerBlocks.f90 +++ b/rosco/controller/src/ControllerBlocks.f90 @@ -43,7 +43,25 @@ SUBROUTINE ComputeVariablesSetpoints(CntrPar, LocalVar, objInst, DebugVar, ErrVa LocalVar%PRC_R_Pitch = CntrPar%PRC_R_Pitch ELSEIF (CntrPar%PRC_Comm == 1) THEN ! Open loop - ! TODO + + IF (CntrPar%Ind_R_Speed > 0) THEN + LocalVar%PRC_R_Speed = interp1d(CntrPar%OL_Breakpoints,CntrPar%OL_R_Speed,LocalVar%Time,ErrVar) + WRITE(401,*) LocalVar%PRC_R_Speed + ELSE + LocalVar%PRC_R_Speed = 1.0_DbKi + ENDIF + + IF (CntrPar%Ind_R_Torque > 0) THEN + LocalVar%PRC_R_Torque = interp1d(CntrPar%OL_Breakpoints,CntrPar%OL_R_Torque,LocalVar%Time,ErrVar) + ELSE + LocalVar%PRC_R_Torque = 1.0_DbKi + ENDIF + + IF (CntrPar%Ind_R_Pitch > 0) THEN + LocalVar%PRC_R_Pitch = interp1d(CntrPar%OL_Breakpoints,CntrPar%OL_R_Pitch,LocalVar%Time,ErrVar) + ELSE + LocalVar%PRC_R_Pitch = 1.0_DbKi + ENDIF ELSEIF (CntrPar%PRC_Comm == 2) THEN ! ZeroMQ ! TODO diff --git a/rosco/controller/src/ROSCO_Types.f90 b/rosco/controller/src/ROSCO_Types.f90 index 66ca3506..eb23aabc 100644 --- a/rosco/controller/src/ROSCO_Types.f90 +++ b/rosco/controller/src/ROSCO_Types.f90 @@ -137,6 +137,9 @@ MODULE ROSCO_Types INTEGER(IntKi), DIMENSION(:), ALLOCATABLE :: Ind_BldPitch ! The columns in OL_Filename that contains the blade pitch inputs (1,2,3) in rad INTEGER(IntKi) :: Ind_GenTq ! The column in OL_Filename that contains the generator torque in Nm INTEGER(IntKi) :: Ind_YawRate ! The column in OL_Filename that contains the generator torque in Nm + INTEGER(IntKi) :: Ind_R_Speed ! The column in OL_Filename that contains the generator torque in Nm + INTEGER(IntKi) :: Ind_R_Torque ! The column in OL_Filename that contains the generator torque in Nm + INTEGER(IntKi) :: Ind_R_Pitch ! The column in OL_Filename that contains the generator torque in Nm INTEGER(IntKi) :: Ind_Azimuth ! The column in OL_Filename that contains the desired azimuth position in rad (used if OL_Mode = 2) REAL(DbKi), DIMENSION(:), ALLOCATABLE :: RP_Gains ! PID gains and Tf on derivative term for rotor position control (used if OL_Mode = 2) INTEGER(IntKi), DIMENSION(:), ALLOCATABLE :: Ind_CableControl ! The column in OL_Filename that contains the cable control inputs in m @@ -150,6 +153,9 @@ MODULE ROSCO_Types REAL(DbKi), DIMENSION(:), ALLOCATABLE :: OL_GenTq ! Open loop generator torque timeseries REAL(DbKi), DIMENSION(:), ALLOCATABLE :: OL_YawRate ! Open loop yaw rate timeseries REAL(DbKi), DIMENSION(:), ALLOCATABLE :: OL_Azimuth ! Open loop azimuth timeseries + REAL(DbKi), DIMENSION(:), ALLOCATABLE :: OL_R_Speed ! Open loop R_Speed timeseries + REAL(DbKi), DIMENSION(:), ALLOCATABLE :: OL_R_Torque ! Open loop R_Torque timeseries + REAL(DbKi), DIMENSION(:), ALLOCATABLE :: OL_R_Pitch ! Open loop R_Pitch timeseries REAL(DbKi), DIMENSION(:,:), ALLOCATABLE :: OL_Channels ! Open loop channels in timeseries INTEGER(IntKi) :: PA_Mode ! Pitch actuator mode {0 - not used, 1 - first order filter, 2 - second order filter} REAL(DbKi) :: PA_CornerFreq ! Pitch actuator bandwidth/cut-off frequency [rad/s] diff --git a/rosco/controller/src/ReadSetParameters.f90 b/rosco/controller/src/ReadSetParameters.f90 index 60a61110..a7456807 100644 --- a/rosco/controller/src/ReadSetParameters.f90 +++ b/rosco/controller/src/ReadSetParameters.f90 @@ -523,6 +523,9 @@ SUBROUTINE ReadControlParameterFileSub(CntrPar, LocalVar, accINFILE, accINFILE_s CALL ParseInput(FileLines, 'Ind_GenTq', CntrPar%Ind_GenTq, accINFILE(1), ErrVar, UnEc=UnEc) CALL ParseInput(FileLines, 'Ind_YawRate', CntrPar%Ind_YawRate, accINFILE(1), ErrVar, UnEc=UnEc) CALL ParseInput(FileLines, 'Ind_Azimuth', CntrPar%Ind_Azimuth, accINFILE(1), ErrVar, CntrPar%OL_Mode .NE. 2, UnEc=UnEc) + CALL ParseInput(FileLines, 'Ind_R_Speed', CntrPar%Ind_R_Speed, accINFILE(1), ErrVar, CntrPar%OL_Mode .NE. 2, UnEc=UnEc) + CALL ParseInput(FileLines, 'Ind_R_Torque', CntrPar%Ind_R_Torque, accINFILE(1), ErrVar, CntrPar%OL_Mode .NE. 2, UnEc=UnEc) + CALL ParseInput(FileLines, 'Ind_R_Pitch', CntrPar%Ind_R_Pitch, accINFILE(1), ErrVar, CntrPar%OL_Mode .NE. 2, UnEc=UnEc) CALL ParseAry( FileLines, 'RP_Gains', CntrPar%RP_Gains, 4, accINFILE(1), ErrVar, CntrPar%OL_Mode .NE. 2, UnEc=UnEc) IF (ErrVar%aviFAIL < 0) RETURN @@ -644,6 +647,27 @@ SUBROUTINE ReadControlParameterFileSub(CntrPar, LocalVar, accINFILE, accINFILE_s END IF ENDIF + IF (CntrPar%Ind_R_Speed > 0) THEN + IF (CntrPar%OL_Mode == 1) THEN + OL_String = TRIM(OL_String)//' R_Speed ' + OL_Count = OL_Count + 1 + END IF + ENDIF + + IF (CntrPar%Ind_R_Torque > 0) THEN + IF (CntrPar%OL_Mode == 1) THEN + OL_String = TRIM(OL_String)//' R_Torque ' + OL_Count = OL_Count + 1 + END IF + ENDIF + + IF (CntrPar%Ind_R_Pitch > 0) THEN + IF (CntrPar%OL_Mode == 1) THEN + OL_String = TRIM(OL_String)//' R_Pitch ' + OL_Count = OL_Count + 1 + END IF + ENDIF + N_OL_Cables = 0 IF (ANY(CntrPar%Ind_CableControl > 0)) THEN DO I = 1,SIZE(CntrPar%Ind_CableControl) @@ -704,6 +728,19 @@ SUBROUTINE ReadControlParameterFileSub(CntrPar, LocalVar, accINFILE, accINFILE_s IF (CntrPar%Ind_Azimuth > 0) THEN CntrPar%OL_Azimuth = Unwrap(CntrPar%OL_Channels(:,CntrPar%Ind_Azimuth),ErrVar) ENDIF + + IF (CntrPar%Ind_R_Speed > 0) THEN + CntrPar%OL_R_Speed = CntrPar%OL_Channels(:,CntrPar%Ind_R_Speed) + ENDIF + WRITE(400,*) CntrPar%OL_R_Speed + + IF (CntrPar%Ind_R_Torque > 0) THEN + CntrPar%OL_R_Torque = CntrPar%OL_Channels(:,CntrPar%Ind_R_Torque) + ENDIF + + IF (CntrPar%Ind_R_Pitch > 0) THEN + CntrPar%OL_R_Pitch = CntrPar%OL_Channels(:,CntrPar%Ind_R_Pitch) + ENDIF IF (ANY(CntrPar%Ind_CableControl > 0)) THEN ALLOCATE(CntrPar%OL_CableControl(N_OL_Cables,SIZE(CntrPar%OL_Channels,DIM=1))) @@ -1314,7 +1351,10 @@ SUBROUTINE CheckInputs(LocalVar, CntrPar, avrSWAP, ErrVar, size_avcMSG) ALLOCATE(All_OL_Indices(5)) ! Will need to increase to 5 when IPC All_OL_Indices = (/CntrPar%Ind_BldPitch, & CntrPar%Ind_GenTq, & - CntrPar%Ind_YawRate/) + CntrPar%Ind_YawRate, & + CntrPar%Ind_R_Speed, & + CntrPar%Ind_R_Torque, & + CntrPar%Ind_R_Pitch/) DO I = 1,SIZE(CntrPar%Ind_CableControl) Call AddToList(All_OL_Indices, CntrPar%Ind_CableControl(I)) diff --git a/rosco/toolbox/controller.py b/rosco/toolbox/controller.py index bffe3259..e43f6069 100644 --- a/rosco/toolbox/controller.py +++ b/rosco/toolbox/controller.py @@ -146,6 +146,7 @@ def __init__(self, controller_params): self.OL_Mode = controller_params['OL_Mode'] self.OL_Filename = controller_params['open_loop']['filename'] self.OL_Ind_Breakpoint = self.OL_Ind_GenTq = self.OL_Ind_YawRate = self.OL_Ind_Azimuth = 0 + self.OL_Ind_R_Speed = self.OL_Ind_R_Torque = self.OL_Ind_R_Pitch = 0 self.OL_Ind_BldPitch = [0,0,0] self.OL_Ind_CableControl = [0] self.OL_Ind_StructControl = [0] @@ -157,6 +158,9 @@ def __init__(self, controller_params): self.OL_Ind_GenTq = ol_params['OL_Ind_GenTq'] self.OL_Ind_YawRate = ol_params['OL_Ind_YawRate'] self.OL_Ind_Azimuth = ol_params['OL_Ind_Azimuth'] + self.OL_Ind_R_Speed = ol_params['OL_Ind_R_Speed'] + self.OL_Ind_R_Torque = ol_params['OL_Ind_R_Torque'] + self.OL_Ind_R_Pitch = ol_params['OL_Ind_R_Pitch'] self.OL_Ind_CableControl = ol_params['OL_Ind_CableControl'] self.OL_Ind_StructControl = ol_params['OL_Ind_StructControl'] @@ -752,7 +756,17 @@ def __init__(self, **kwargs): self.ol_timeseries = {} self.ol_timeseries['time'] = np.arange(0,self.t_max,self.dt) - self.allowed_controls = ['blade_pitch','generator_torque','nacelle_yaw','nacelle_yaw_rate','cable_control','struct_control'] + self.allowed_controls = [ + 'blade_pitch', + 'generator_torque', + 'nacelle_yaw', + 'nacelle_yaw_rate', + 'cable_control', + 'struct_control', + 'R_speed', + 'R_torque', + 'R_pitch', + ] def const_timeseries(self,control,value): @@ -839,7 +853,7 @@ def write_input(self,ol_filename): # Init indices OL_Ind_Breakpoint = 1 - OL_Ind_Azimuth = OL_Ind_GenTq = OL_Ind_YawRate = 0 + OL_Ind_Azimuth = OL_Ind_GenTq = OL_Ind_YawRate = OL_Ind_R_Speed = OL_Ind_R_Torque = OL_Ind_R_Pitch = 0 OL_Ind_BldPitch = 3*[0] OL_Ind_CableControl = [] OL_Ind_StructControl = [] @@ -882,6 +896,12 @@ def write_input(self,ol_filename): OL_Ind_BldPitch[2] = ol_index_counter elif channel == 'azimuth': OL_Ind_Azimuth = ol_index_counter + elif channel == 'R_speed': + OL_Ind_R_Speed = ol_index_counter + elif channel == 'R_torque': + OL_Ind_R_Torque = ol_index_counter + elif channel == 'R_pitch': + OL_Ind_R_Pitch = ol_index_counter elif 'cable_control' in channel or 'struct_control' in channel: skip_write = True ol_index_counter -= 1 # don't increment counter @@ -972,6 +992,18 @@ def write_input(self,ol_filename): else: OL_Ind_StructControl = [0] + if OL_Ind_R_Speed: + headers[OL_Ind_R_Speed-1] = 'R_speed' + units[OL_Ind_R_Speed-1] = '(-)' + + if OL_Ind_R_Torque: + headers[OL_Ind_R_Torque-1] = 'R_Torque' + units[OL_Ind_R_Torque-1] = '(-)' + + if OL_Ind_R_Pitch: + headers[OL_Ind_R_Pitch-1] = 'R_Pitch' + units[OL_Ind_R_Pitch-1] = '(-)' + # Join headers and units header_line = '!' + '\t\t'.join(headers) + '\n' unit_line = '!' + '\t\t'.join(units) + '\n' @@ -994,6 +1026,9 @@ def write_input(self,ol_filename): open_loop['OL_Ind_Azimuth'] = OL_Ind_Azimuth open_loop['OL_Ind_CableControl'] = OL_Ind_CableControl open_loop['OL_Ind_StructControl'] = OL_Ind_StructControl + open_loop['OL_Ind_R_Speed'] = OL_Ind_R_Speed + open_loop['OL_Ind_R_Torque'] = OL_Ind_R_Torque + open_loop['OL_Ind_R_Pitch'] = OL_Ind_R_Pitch return open_loop diff --git a/rosco/toolbox/inputs/toolbox_schema.yaml b/rosco/toolbox/inputs/toolbox_schema.yaml index 0b29464f..084b7f4a 100644 --- a/rosco/toolbox/inputs/toolbox_schema.yaml +++ b/rosco/toolbox/inputs/toolbox_schema.yaml @@ -518,6 +518,21 @@ properties: type: number default: 0 description: The column in OL_Filename that contains the desired azimuth position in rad (used if OL_Mode = 2) + Ind_R_Speed: + description: Index (column, 1-indexed) of power rating via speed offset + type: number + default: 0 + minimum: 0 + Ind_R_Torque: + description: Index (column, 1-indexed) of power rating via torque offset + type: number + default: 0 + minimum: 0 + Ind_R_Pitch: + description: Index (column, 1-indexed) of power rating via pitch offset + type: number + default: 0 + minimum: 0 Ind_CableControl: type: array items: @@ -1071,6 +1086,18 @@ properties: default: [0,0,0,0] items: type: number + Ind_R_Speed: + description: Index (column, 1-indexed) of power rating via speed offset + type: number + minimum: 0 + Ind_R_Torque: + description: Index (column, 1-indexed) of power rating via torque offset + type: number + minimum: 0 + Ind_R_Pitch: + description: Index (column, 1-indexed) of power rating via pitch offset + type: number + minimum: 0 Ind_CableControl: type: array items: diff --git a/rosco/toolbox/utilities.py b/rosco/toolbox/utilities.py index 65a4ba58..c62ee896 100644 --- a/rosco/toolbox/utilities.py +++ b/rosco/toolbox/utilities.py @@ -261,6 +261,9 @@ def write_DISCON(turbine, controller, param_file='DISCON.IN', txt_filename='Cp_C file.write('{} ! {} - {}\n'.format(' '.join([f'{g:02.4f}' for g in rosco_vt["RP_Gains"]]),"RP_Gains",input_descriptions["RP_Gains"])) file.write('{} ! Ind_CableControl - The column(s) in OL_Filename that contains the cable control inputs in m [Used with CC_Mode = 2, must be the same size as CC_Group_N]\n'.format(write_array(rosco_vt['Ind_CableControl'],'<4d'))) file.write('{} ! Ind_StructControl - The column(s) in OL_Filename that contains the structural control inputs [Used with StC_Mode = 2, must be the same size as StC_Group_N]\n'.format(write_array(rosco_vt['Ind_StructControl'],'<4d'))) + file.write('{:<12d} ! Ind_R_Speed - {}\n'.format(int(rosco_vt["Ind_R_Speed"]), input_descriptions["Ind_R_Speed"])) + file.write('{:<12d} ! Ind_R_Torque - {}\n'.format(int(rosco_vt["Ind_R_Torque"]), input_descriptions["Ind_R_Torque"])) + file.write('{:<12d} ! Ind_R_Pitch - {}\n'.format(int(rosco_vt["Ind_R_Pitch"]), input_descriptions["Ind_R_Pitch"])) file.write('\n') file.write('!------- Pitch Actuator Model -----------------------------------------------------\n') file.write('{:<014.5f} ! PA_CornerFreq - Pitch actuator bandwidth/cut-off frequency [rad/s]\n'.format(rosco_vt['PA_CornerFreq'])) @@ -616,7 +619,10 @@ def DISCON_dict(turbine, controller, txt_filename=None): DISCON_dict['Ind_YawRate'] = controller.OL_Ind_YawRate DISCON_dict['Ind_CableControl'] = controller.OL_Ind_CableControl DISCON_dict['Ind_StructControl'] = controller.OL_Ind_StructControl - DISCON_dict['Ind_Azimuth'] = controller.OL_Ind_Azimuth + DISCON_dict['Ind_Azimuth'] = controller.OL_Ind_Azimuth + DISCON_dict['Ind_R_Speed'] = controller.OL_Ind_R_Speed + DISCON_dict['Ind_R_Torque'] = controller.OL_Ind_R_Torque + DISCON_dict['Ind_R_Pitch'] = controller.OL_Ind_R_Pitch # ------- Pitch Actuator ------- DISCON_dict['PA_Mode'] = controller.PA_Mode From b8559fad8539d70a4c14f2376b30a2afd15be9db Mon Sep 17 00:00:00 2001 From: dzalkind Date: Fri, 14 Jun 2024 16:14:34 -0600 Subject: [PATCH 154/224] Add ZMQ PRC inputs, defaults in wfc setpoints --- Examples/17b_zeromq_multi_openfast.py | 24 +++++++++++++++---- .../rosco_registry/rosco_types.yaml | 9 +++++++ .../rosco_registry/wfc_interface.yaml | 16 ++++++++++++- .../rosco_registry/write_wfc_interface.py | 3 +++ rosco/controller/src/Constants.f90 | 6 +++++ rosco/controller/src/ControllerBlocks.f90 | 11 +++++---- rosco/controller/src/ROSCO_IO.f90 | 21 +++++++++++----- rosco/controller/src/ROSCO_Types.f90 | 3 +++ rosco/controller/src/ReadSetParameters.f90 | 15 ++++++++---- rosco/controller/src/ZeroMQInterface.f90 | 7 ++++-- rosco/controller/src/zmq_client.c | 19 ++++++++------- rosco/toolbox/control_interface.py | 4 ++-- 12 files changed, 105 insertions(+), 33 deletions(-) diff --git a/Examples/17b_zeromq_multi_openfast.py b/Examples/17b_zeromq_multi_openfast.py index 0de4d9a7..5c7bdeef 100644 --- a/Examples/17b_zeromq_multi_openfast.py +++ b/Examples/17b_zeromq_multi_openfast.py @@ -13,6 +13,7 @@ os.makedirs(example_out_dir, exist_ok=True) TIME_CHECK = 20 DESIRED_YAW_OFFSET = [-10, 10] +DESIRED_R_PITCH = 0.9 def run_zmq(logfile=None): @@ -40,6 +41,7 @@ def wfc_controller(id, current_time, measurements): should be overwriten with this fuction, otherwise, an exception is raised and the simulation stops. """ + R_Pitch = 1.0 if current_time <= 10.0: YawOffset = 0.0 col_pitch_command = 0.0 @@ -47,6 +49,7 @@ def wfc_controller(id, current_time, measurements): col_pitch_command = np.deg2rad(2) * np.sin(0.1 * current_time) + np.deg2rad(2) # Implement dynamic induction control if id == 1: YawOffset = DESIRED_YAW_OFFSET[0] + R_Pitch = DESIRED_R_PITCH else: YawOffset = DESIRED_YAW_OFFSET[1] @@ -56,6 +59,7 @@ def wfc_controller(id, current_time, measurements): setpoints['ZMQ_PitOffset(1)'] = col_pitch_command setpoints['ZMQ_PitOffset(2)'] = col_pitch_command setpoints['ZMQ_PitOffset(3)'] = col_pitch_command + setpoints['ZMQ_R_Pitch'] = R_Pitch return setpoints @@ -74,6 +78,8 @@ def sim_openfast_1(): r.controller_params["DISCON"] = {} r.controller_params["DISCON"]["ZMQ_Mode"] = 1 r.controller_params["DISCON"]["ZMQ_ID"] = 1 + r.controller_params['DISCON']['PRC_Mode'] = 1 + r.controller_params['DISCON']['PRC_Comm'] = 2 r.save_dir = run_dir r.run_FAST() @@ -94,6 +100,8 @@ def sim_openfast_2(): r.controller_params["LoggingLevel"] = 2 r.controller_params["DISCON"]["ZMQ_Mode"] = 1 r.controller_params["DISCON"]["ZMQ_ID"] = 2 + r.controller_params['DISCON']['PRC_Mode'] = 1 + r.controller_params['DISCON']['PRC_Comm'] = 2 r.run_FAST() @@ -148,13 +156,19 @@ def sim_openfast_2(): else: plt.savefig(os.path.join(example_out_dir, "17b_NREL5MW_ZMQ_Setpoints.png")) - # Spot check input at time = 30 sec. - ind1_30 = local_vars1[0]["Time"] == TIME_CHECK - ind2_30 = local_vars2[0]["Time"] == TIME_CHECK + # Spot check input at time = TIME_CHECK + ind1_TC = local_vars1[0]["Time"] == TIME_CHECK + ind2_TC = local_vars2[0]["Time"] == TIME_CHECK np.testing.assert_almost_equal( - local_vars1[0]["ZMQ_YawOffset"][ind1_30], DESIRED_YAW_OFFSET[0] + local_vars1[0]["ZMQ_YawOffset"][ind1_TC], DESIRED_YAW_OFFSET[0] ) np.testing.assert_almost_equal( - local_vars2[0]["ZMQ_YawOffset"][ind2_30], DESIRED_YAW_OFFSET[1] + local_vars2[0]["ZMQ_YawOffset"][ind2_TC], DESIRED_YAW_OFFSET[1] ) + + np.testing.assert_almost_equal( + local_vars1[0]["ZMQ_R_Pitch"][ind1_TC], DESIRED_R_PITCH + ) + + diff --git a/rosco/controller/rosco_registry/rosco_types.yaml b/rosco/controller/rosco_registry/rosco_types.yaml index 506bc093..371a7aac 100644 --- a/rosco/controller/rosco_registry/rosco_types.yaml +++ b/rosco/controller/rosco_registry/rosco_types.yaml @@ -1384,6 +1384,15 @@ LocalVariables: <<: *real size: 3 description: Pitch command offset provided by ZeroMQ + ZMQ_R_Speed: + <<: *real + description: R_Speed command provided by ZeroMQ + ZMQ_R_Torque: + <<: *real + description: R_Torque command provided by ZeroMQ + ZMQ_R_Pitch: + <<: *real + description: R_Pitch command provided by ZeroMQ WE: <<: *derived_type id: WE diff --git a/rosco/controller/rosco_registry/wfc_interface.yaml b/rosco/controller/rosco_registry/wfc_interface.yaml index 63b6e895..00d26051 100644 --- a/rosco/controller/rosco_registry/wfc_interface.yaml +++ b/rosco/controller/rosco_registry/wfc_interface.yaml @@ -24,4 +24,18 @@ setpoints: [ ZMQ_PitOffset(1), ZMQ_PitOffset(2), ZMQ_PitOffset(3), - ] \ No newline at end of file + ZMQ_R_Speed, + ZMQ_R_Torque, + ZMQ_R_Pitch, + ] + +setpoints_default: [ # order should match setpoints + 0, + 0, + 0, + 0, + 0, + 1, + 1, + 1, +] \ No newline at end of file diff --git a/rosco/controller/rosco_registry/write_wfc_interface.py b/rosco/controller/rosco_registry/write_wfc_interface.py index 06895db8..fb26a493 100644 --- a/rosco/controller/rosco_registry/write_wfc_interface.py +++ b/rosco/controller/rosco_registry/write_wfc_interface.py @@ -40,6 +40,9 @@ def main(): if local_vars[ms]['size'] < ind_int: raise Exception(f'Requested index ({ind_int}) of WFC variable {ms} is greater than LocalVars version.') + # Check that length of defaults is the same as setpoints + if len(wfc_int['setpoints']) != len(wfc_int['setpoints_default']): + raise Exception(f'The lengths of setpoints and setpoints_default in the wfc_interface.yaml are not equal') write_zmq_f90(wfc_int) write_client_c(wfc_int) diff --git a/rosco/controller/src/Constants.f90 b/rosco/controller/src/Constants.f90 index 56298879..dd3be0a5 100644 --- a/rosco/controller/src/Constants.f90 +++ b/rosco/controller/src/Constants.f90 @@ -37,4 +37,10 @@ MODULE Constants CHARACTER(1), PARAMETER :: Tab = CHAR( 9 ) + ! PRC Mode constants + REAL(IntKi), PARAMETER :: PRC_Comm_Constant = 0 ! Constant based on discon input + REAL(IntKi), PARAMETER :: PRC_Comm_OpenLoop = 1 ! Based on open loop input + REAL(IntKi), PARAMETER :: PRC_Comm_ZMQ = 2 ! Determined using ZMQ input + + END MODULE Constants diff --git a/rosco/controller/src/ControllerBlocks.f90 b/rosco/controller/src/ControllerBlocks.f90 index 05a70b7e..945cb007 100644 --- a/rosco/controller/src/ControllerBlocks.f90 +++ b/rosco/controller/src/ControllerBlocks.f90 @@ -37,12 +37,12 @@ SUBROUTINE ComputeVariablesSetpoints(CntrPar, LocalVar, objInst, DebugVar, ErrVa ! Set up power reference IF (CntrPar%PRC_Mode == 1) THEN ! Using power reference control - IF (CntrPar%PRC_Comm == 0) THEN ! Constant, from DISCON + IF (CntrPar%PRC_Comm == PRC_Comm_Constant) THEN ! Constant, from DISCON LocalVar%PRC_R_Speed = CntrPar%PRC_R_Speed LocalVar%PRC_R_Torque = CntrPar%PRC_R_Torque LocalVar%PRC_R_Pitch = CntrPar%PRC_R_Pitch - ELSEIF (CntrPar%PRC_Comm == 1) THEN ! Open loop + ELSEIF (CntrPar%PRC_Comm == PRC_Comm_OpenLoop) THEN ! Open loop IF (CntrPar%Ind_R_Speed > 0) THEN LocalVar%PRC_R_Speed = interp1d(CntrPar%OL_Breakpoints,CntrPar%OL_R_Speed,LocalVar%Time,ErrVar) @@ -63,9 +63,10 @@ SUBROUTINE ComputeVariablesSetpoints(CntrPar, LocalVar, objInst, DebugVar, ErrVa LocalVar%PRC_R_Pitch = 1.0_DbKi ENDIF - ELSEIF (CntrPar%PRC_Comm == 2) THEN ! ZeroMQ - ! TODO - ! Check when ZMQ is called, should be before this! + ELSEIF (CntrPar%PRC_Comm == PRC_Comm_ZMQ) THEN ! ZeroMQ + LocalVar%PRC_R_Speed = LocalVar%ZMQ_R_Speed + LocalVar%PRC_R_Torque = LocalVar%ZMQ_R_Torque + LocalVar%PRC_R_Pitch = LocalVar%ZMQ_R_Pitch ENDIF diff --git a/rosco/controller/src/ROSCO_IO.f90 b/rosco/controller/src/ROSCO_IO.f90 index 8706e34b..e40d977f 100644 --- a/rosco/controller/src/ROSCO_IO.f90 +++ b/rosco/controller/src/ROSCO_IO.f90 @@ -241,6 +241,9 @@ SUBROUTINE WriteRestartFile(LocalVar, CntrPar, ErrVar, objInst, RootName, size_a WRITE( Un, IOSTAT=ErrStat) LocalVar%ZMQ_PitOffset(1) WRITE( Un, IOSTAT=ErrStat) LocalVar%ZMQ_PitOffset(2) WRITE( Un, IOSTAT=ErrStat) LocalVar%ZMQ_PitOffset(3) + WRITE( Un, IOSTAT=ErrStat) LocalVar%ZMQ_R_Speed + WRITE( Un, IOSTAT=ErrStat) LocalVar%ZMQ_R_Torque + WRITE( Un, IOSTAT=ErrStat) LocalVar%ZMQ_R_Pitch WRITE( Un, IOSTAT=ErrStat) LocalVar%WE%om_r WRITE( Un, IOSTAT=ErrStat) LocalVar%WE%v_t WRITE( Un, IOSTAT=ErrStat) LocalVar%WE%v_m @@ -550,6 +553,9 @@ SUBROUTINE ReadRestartFile(avrSWAP, LocalVar, CntrPar, objInst, PerfData, RootNa READ( Un, IOSTAT=ErrStat) LocalVar%ZMQ_PitOffset(1) READ( Un, IOSTAT=ErrStat) LocalVar%ZMQ_PitOffset(2) READ( Un, IOSTAT=ErrStat) LocalVar%ZMQ_PitOffset(3) + READ( Un, IOSTAT=ErrStat) LocalVar%ZMQ_R_Speed + READ( Un, IOSTAT=ErrStat) LocalVar%ZMQ_R_Torque + READ( Un, IOSTAT=ErrStat) LocalVar%ZMQ_R_Pitch READ( Un, IOSTAT=ErrStat) LocalVar%WE%om_r READ( Un, IOSTAT=ErrStat) LocalVar%WE%v_t READ( Un, IOSTAT=ErrStat) LocalVar%WE%v_m @@ -704,7 +710,7 @@ SUBROUTINE Debug(LocalVar, CntrPar, DebugVar, ErrVar, avrSWAP, RootName, size_av '[N/A]', '[N/A]', '[N/A]', '[N/A]', '[rad/s]', & '[deg]', '[deg]', '[deg]', '[N/A]', '[rad/s]', & '[rad/s]'] - nLocalVars = 130 + nLocalVars = 133 Allocate(LocalVarOutData(nLocalVars)) Allocate(LocalVarOutStrings(nLocalVars)) LocalVarOutData(1) = LocalVar%iStatus @@ -837,6 +843,9 @@ SUBROUTINE Debug(LocalVar, CntrPar, DebugVar, ErrVar, avrSWAP, RootName, size_av LocalVarOutData(128) = LocalVar%ZMQ_YawOffset LocalVarOutData(129) = LocalVar%ZMQ_TorqueOffset LocalVarOutData(130) = LocalVar%ZMQ_PitOffset(1) + LocalVarOutData(131) = LocalVar%ZMQ_R_Speed + LocalVarOutData(132) = LocalVar%ZMQ_R_Torque + LocalVarOutData(133) = LocalVar%ZMQ_R_Pitch LocalVarOutStrings = [CHARACTER(15) :: 'iStatus', 'Time', 'DT', 'n_DT', 'Time_Last', & 'VS_GenPwr', 'VS_GenPwrF', 'GenSpeed', 'RotSpeed', 'NacHeading', & 'NacVane', 'HorWindV', 'rootMOOP', 'rootMOOPF', 'BlPitch', & @@ -862,8 +871,8 @@ SUBROUTINE Debug(LocalVar, CntrPar, DebugVar, ErrVar, avrSWAP, RootName, size_av 'PtfmRVY', 'PtfmRVZ', 'PtfmTAX', 'PtfmTAY', 'PtfmTAZ', & 'PtfmRAX', 'PtfmRAY', 'PtfmRAZ', 'CC_DesiredL', 'CC_ActuatedL', & 'CC_ActuatedDL', 'StC_Input', 'Flp_Angle', 'RootMyb_Last', 'ACC_INFILE_SIZE', & - 'AWC_complexangle', 'ZMQ_ID', 'ZMQ_YawOffset', 'ZMQ_TorqueOffset', 'ZMQ_PitOffset' & - ] + 'AWC_complexangle', 'ZMQ_ID', 'ZMQ_YawOffset', 'ZMQ_TorqueOffset', 'ZMQ_PitOffset', & + 'ZMQ_R_Speed', 'ZMQ_R_Torque', 'ZMQ_R_Pitch'] ! Initialize debug file IF ((LocalVar%iStatus == 0) .OR. (LocalVar%iStatus == -9)) THEN ! .TRUE. if we're on the first call to the DLL IF (CntrPar%LoggingLevel > 0) THEN @@ -878,8 +887,8 @@ SUBROUTINE Debug(LocalVar, CntrPar, DebugVar, ErrVar, avrSWAP, RootName, size_av CALL GetNewUnit(UnDb2, ErrVar) OPEN(unit=UnDb2, FILE=TRIM(RootName)//'.RO.dbg2') WRITE(UnDb2, *) 'Generated on '//CurDate()//' at '//CurTime()//' using ROSCO-'//TRIM(rosco_version) - WRITE(UnDb2, '(131(a20,TR5:))') 'Time', LocalVarOutStrings - WRITE(UnDb2, '(131(a20,TR5:))') + WRITE(UnDb2, '(134(a20,TR5:))') 'Time', LocalVarOutStrings + WRITE(UnDb2, '(134(a20,TR5:))') END IF IF (CntrPar%LoggingLevel > 2) THEN @@ -942,7 +951,7 @@ SUBROUTINE Debug(LocalVar, CntrPar, DebugVar, ErrVar, avrSWAP, RootName, size_av END DO ! Write debug files - FmtDat = "(F20.5,TR5,130(ES20.5E2,TR5:))" ! The format of the debugging data + FmtDat = "(F20.5,TR5,133(ES20.5E2,TR5:))" ! The format of the debugging data IF ( MOD(LocalVar%n_DT, CntrPar%n_DT_Out) == 0) THEN IF(CntrPar%LoggingLevel > 0) THEN WRITE (UnDb, TRIM(FmtDat)) LocalVar%Time, DebugOutData diff --git a/rosco/controller/src/ROSCO_Types.f90 b/rosco/controller/src/ROSCO_Types.f90 index eb23aabc..e3aebc42 100644 --- a/rosco/controller/src/ROSCO_Types.f90 +++ b/rosco/controller/src/ROSCO_Types.f90 @@ -394,6 +394,9 @@ MODULE ROSCO_Types REAL(DbKi) :: ZMQ_YawOffset ! Yaw offset command, [rad] REAL(DbKi) :: ZMQ_TorqueOffset ! Torque offset command, [Nm] REAL(DbKi) :: ZMQ_PitOffset(3) ! Pitch command offset provided by ZeroMQ + REAL(DbKi) :: ZMQ_R_Speed ! R_Speed command provided by ZeroMQ + REAL(DbKi) :: ZMQ_R_Torque ! R_Torque command provided by ZeroMQ + REAL(DbKi) :: ZMQ_R_Pitch ! R_Pitch command provided by ZeroMQ TYPE(WE) :: WE ! Wind speed estimator parameters derived type TYPE(FilterParameters) :: FP ! Filter parameters derived type TYPE(piParams) :: piP ! PI parameters derived type diff --git a/rosco/controller/src/ReadSetParameters.f90 b/rosco/controller/src/ReadSetParameters.f90 index a7456807..b225cc2c 100644 --- a/rosco/controller/src/ReadSetParameters.f90 +++ b/rosco/controller/src/ReadSetParameters.f90 @@ -441,9 +441,9 @@ SUBROUTINE ReadControlParameterFileSub(CntrPar, LocalVar, accINFILE, accINFILE_s !------------ POWER REFERENCE TRACKING SETPOINTS -------------- CALL ParseInput(FileLines, 'PRC_Comm', CntrPar%PRC_Comm, accINFILE(1), ErrVar, CntrPar%PRC_Mode .NE. 1, UnEc) - CALL ParseInput(FileLines, 'PRC_R_Torque', CntrPar%PRC_R_Torque, accINFILE(1), ErrVar, (CntrPar%PRC_Mode .NE. 1) .OR. (CntrPar%PRC_Comm .NE. 0), UnEc) - CALL ParseInput(FileLines, 'PRC_R_Speed', CntrPar%PRC_R_Speed, accINFILE(1), ErrVar, (CntrPar%PRC_Mode .NE. 1) .OR. (CntrPar%PRC_Comm .NE. 0), UnEc) - CALL ParseInput(FileLines, 'PRC_R_Pitch', CntrPar%PRC_R_Pitch, accINFILE(1), ErrVar, (CntrPar%PRC_Mode .NE. 1) .OR. (CntrPar%PRC_Comm .NE. 0), UnEc) + CALL ParseInput(FileLines, 'PRC_R_Torque', CntrPar%PRC_R_Torque, accINFILE(1), ErrVar, (CntrPar%PRC_Mode .NE. 1) .OR. (CntrPar%PRC_Comm .NE. PRC_Comm_Constant), UnEc) + CALL ParseInput(FileLines, 'PRC_R_Speed', CntrPar%PRC_R_Speed, accINFILE(1), ErrVar, (CntrPar%PRC_Mode .NE. 1) .OR. (CntrPar%PRC_Comm .NE. PRC_Comm_Constant), UnEc) + CALL ParseInput(FileLines, 'PRC_R_Pitch', CntrPar%PRC_R_Pitch, accINFILE(1), ErrVar, (CntrPar%PRC_Mode .NE. 1) .OR. (CntrPar%PRC_Comm .NE. PRC_Comm_Constant), UnEc) CALL ParseInput(FileLines, 'PRC_Table_n', CntrPar%PRC_Table_n, accINFILE(1), ErrVar, (CntrPar%PRC_Mode .NE. 1) .OR. (CntrPar%PRC_R_Pitch == 1.0), UnEc) CALL ParseAry(FileLines, 'PRC_R_Table', CntrPar%PRC_R_Table, CntrPar%PRC_Table_n, accINFILE(1), ErrVar, (CntrPar%PRC_Mode .NE. 1) .OR. (CntrPar%PRC_R_Pitch == 1.0), UnEc) CALL ParseAry(FileLines, 'PRC_Pitch_Table', CntrPar%PRC_Pitch_Table, CntrPar%PRC_Table_n, accINFILE(1), ErrVar, (CntrPar%PRC_Mode .NE. 1) .OR. (CntrPar%PRC_R_Pitch == 1.0), UnEc) @@ -1220,7 +1220,14 @@ SUBROUTINE CheckInputs(LocalVar, CntrPar, avrSWAP, ErrVar, size_avcMSG) ENDIF IF (CntrPar%PRC_Mode > 0) THEN - PRINT *, "Note: PRC Mode = ", CntrPar%PRC_Mode, ", which will ignore VS_RefSpeed, VS_TSRopt, and PC_RefSpeed" + PRINT *, "Note: PRC Mode = ", CntrPar%PRC_Mode, ", which will affect VS_RefSpeed, VS_TSRopt, and PC_RefSpeed" + + ! TODO: All PRC checks + ! ZMQ_Mode and PRC_Comm + ! OL_Mode and PRC_Comm + + + ENDIF !------- WIND SPEED ESTIMATOR --------------------------------------------- diff --git a/rosco/controller/src/ZeroMQInterface.f90 b/rosco/controller/src/ZeroMQInterface.f90 index 9a3c1d19..e08aa7e1 100644 --- a/rosco/controller/src/ZeroMQInterface.f90 +++ b/rosco/controller/src/ZeroMQInterface.f90 @@ -12,7 +12,7 @@ SUBROUTINE UpdateZeroMQ(LocalVar, CntrPar, ErrVar) TYPE(ErrorVariables), INTENT(INOUT) :: ErrVar character(256) :: zmq_address - real(C_DOUBLE) :: setpoints(5) + real(C_DOUBLE) :: setpoints(8) real(C_DOUBLE) :: turbine_measurements(17) CHARACTER(*), PARAMETER :: RoutineName = 'UpdateZeroMQ' @@ -24,7 +24,7 @@ subroutine zmq_client(zmq_address, measurements, setpoints) bind(C, name='zmq_cl implicit none character(C_CHAR), intent(out) :: zmq_address(*) real(C_DOUBLE) :: measurements(17) - real(C_DOUBLE) :: setpoints(5) + real(C_DOUBLE) :: setpoints(8) end subroutine zmq_client end interface #endif @@ -73,6 +73,9 @@ end subroutine zmq_client LocalVar%ZMQ_PitOffset(1) = setpoints(3) LocalVar%ZMQ_PitOffset(2) = setpoints(4) LocalVar%ZMQ_PitOffset(3) = setpoints(5) + LocalVar%ZMQ_R_Speed = setpoints(6) + LocalVar%ZMQ_R_Torque = setpoints(7) + LocalVar%ZMQ_R_Pitch = setpoints(8) ENDIF diff --git a/rosco/controller/src/zmq_client.c b/rosco/controller/src/zmq_client.c index d0aed4a5..76b76287 100644 --- a/rosco/controller/src/zmq_client.c +++ b/rosco/controller/src/zmq_client.c @@ -5,14 +5,16 @@ #include -void delete_blank_spaces_in_string(char *s) { - +void delete_blank_spaces_in_string(char *s) +{ int i,k=0; - for(i=0;s[i];i++) { + for(i=0;s[i];i++) + { s[i]=s[i+k]; - if(s[i]==" "|| s[i]=="\t") { - k++; - i--; + if(s[i]==" "|| s[i]=="\t") + { + k++; + i--; } } } @@ -21,8 +23,9 @@ void delete_blank_spaces_in_string(char *s) { int zmq_client ( char *zmq_address, double measurements[17], - double setpoints[5] -) { + double setpoints[8] +) +{ int num_measurements = 17; // Number of setpoints and measurements, respectively, and float precision (character length) int char_buffer_size_single = 20; // Char buffer for a single measurement int char_buffer_size_array = (num_measurements * (char_buffer_size_single + 1)); // Char buffer for full messages to and from ROSCO diff --git a/rosco/toolbox/control_interface.py b/rosco/toolbox/control_interface.py index 1a92decf..fea282b4 100644 --- a/rosco/toolbox/control_interface.py +++ b/rosco/toolbox/control_interface.py @@ -421,8 +421,8 @@ def _get_setpoints(self, id, measurements): setpoints = self.wfc_controller(id, current_time, measurements) logger.info(f"Received setpoints {setpoints} from wfc_controller for time = {current_time} and id = {id}") - for s in self.wfc_interface["setpoints"]: - self.connections.setpoints[id][s] = setpoints.get(s, 0) + for i, s in enumerate(self.wfc_interface["setpoints"]): + self.connections.setpoints[id][s] = setpoints.get(s, self.wfc_interface['setpoints_default'][i]) logger.debug(f'Set setpoint {s} in the connections list to {setpoints.get(s,0)} for id = {id}') def wfc_controller(self, id, current_time, measurements): From 754687958a1424c3662f5cc479a0a94af6a7fec7 Mon Sep 17 00:00:00 2001 From: dzalkind Date: Mon, 1 Jul 2024 16:13:18 -0600 Subject: [PATCH 155/224] Update to latest scipy functions --- Examples/Test_Cases/BAR_10/BAR_10_DISCON.IN | 12 +++---- .../DISCON-UMaineSemi.IN | 34 +++++++++---------- Examples/Test_Cases/MHK_RM1/MHK_RM1_DISCON.IN | 14 ++++---- Examples/Test_Cases/NREL-5MW/DISCON.IN | 12 +++---- .../NREL_2p8_127/NREL-2p8-127_DISCON.IN | 12 +++---- pyproject.toml | 2 +- rosco/toolbox/__init__.py | 2 +- rosco/toolbox/controller.py | 4 +-- rosco/toolbox/turbine.py | 12 +++---- 9 files changed, 52 insertions(+), 52 deletions(-) diff --git a/Examples/Test_Cases/BAR_10/BAR_10_DISCON.IN b/Examples/Test_Cases/BAR_10/BAR_10_DISCON.IN index ebbc56f5..49d1d8be 100644 --- a/Examples/Test_Cases/BAR_10/BAR_10_DISCON.IN +++ b/Examples/Test_Cases/BAR_10/BAR_10_DISCON.IN @@ -1,10 +1,10 @@ ! Controller parameter input file for the BAR_10 wind turbine -! - File written using ROSCO version 2.8.0 controller tuning logic on 01/05/24 +! - File written using ROSCO version 2.9.4 controller tuning logic on 07/01/24 !------- SIMULATION CONTROL ------------------------------------------------------------ 1 ! LoggingLevel - {0: write no debug files, 1: write standard output .dbg-file, 2: LoggingLevel 1 + ROSCO LocalVars (.dbg2) 3: LoggingLevel 2 + complete avrSWAP-array (.dbg3)} 0 ! DT_Out - {Time step to output .dbg* files, or 0 to match sampling period of OpenFAST} -1 ! Ext_Interface - (0 - use standard bladed interface, 1 - Use the extened DLL interface introduced in OpenFAST 3.5.0.) +1 ! Ext_Interface - (0 - use standard bladed interface, 1 - Use the extened DLL interface introduced in OpenFAST 3.5.0.) 0 ! Echo - (0 - no Echo, 1 - Echo input data to .echo) !------- CONTROLLER FLAGS ------------------------------------------------- @@ -53,8 +53,8 @@ !------- BLADE PITCH CONTROL ---------------------------------------------- 30 ! PC_GS_n - Amount of gain-scheduling table entries 0.057899 0.086034 0.108220 0.127602 0.145231 0.161628 0.177110 0.191882 0.205973 0.219605 0.232854 0.245775 0.258317 0.270576 0.282622 0.294421 0.305965 0.317359 0.328547 0.339534 0.350412 0.361066 0.371600 0.382012 0.392231 0.402383 0.412328 0.422200 0.431927 0.441532 ! PC_GS_angles - Gain-schedule table: pitch angles [rad]. --0.017460 -0.014512 -0.012235 -0.010423 -0.008947 -0.007722 -0.006689 -0.005805 -0.005042 -0.004374 -0.003787 -0.003265 -0.002799 -0.002380 -0.002002 -0.001658 -0.001344 -0.001057 -0.000793 -0.000549 -0.000324 -0.000115 0.000080 0.000261 0.000431 0.000590 0.000740 0.000880 0.001013 0.001138 ! PC_GS_KP - Gain-schedule table: pitch controller kp gains [s]. --0.000715 -0.000623 -0.000552 -0.000496 -0.000450 -0.000412 -0.000380 -0.000352 -0.000328 -0.000307 -0.000289 -0.000273 -0.000258 -0.000245 -0.000233 -0.000223 -0.000213 -0.000204 -0.000196 -0.000188 -0.000181 -0.000175 -0.000169 -0.000163 -0.000158 -0.000153 -0.000148 -0.000144 -0.000140 -0.000136 ! PC_GS_KI - Gain-schedule table: pitch controller ki gains [-]. +-0.017426 -0.014498 -0.012232 -0.010428 -0.008956 -0.007733 -0.006701 -0.005818 -0.005054 -0.004387 -0.003799 -0.003276 -0.002810 -0.002390 -0.002011 -0.001666 -0.001352 -0.001064 -0.000799 -0.000554 -0.000328 -0.000118 0.000077 0.000259 0.000430 0.000589 0.000739 0.000881 0.001014 0.001139 ! PC_GS_KP - Gain-schedule table: pitch controller kp gains [s]. +-0.000714 -0.000623 -0.000552 -0.000496 -0.000450 -0.000412 -0.000380 -0.000353 -0.000329 -0.000308 -0.000290 -0.000274 -0.000259 -0.000246 -0.000234 -0.000223 -0.000214 -0.000205 -0.000196 -0.000189 -0.000182 -0.000175 -0.000169 -0.000164 -0.000158 -0.000153 -0.000149 -0.000144 -0.000140 -0.000136 ! PC_GS_KI - Gain-schedule table: pitch controller ki gains [-]. 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 ! PC_GS_KD - Gain-schedule table: pitch controller kd gains 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 ! PC_GS_TF - Gain-schedule table: pitch controller tf gains (derivative filter) 1.570000000000 ! PC_MaxPit - Maximum physical pitch limit, [rad]. @@ -86,7 +86,7 @@ 63892.81326000 ! VS_RtTq - Rated torque, [Nm]. 75.83317000000 ! VS_RefSpd - Rated generator speed [rad/s] 1 ! VS_n - Number of generator PI torque controller gains --2452.07948000 ! VS_KP - Proportional gain for generator PI torque controller [-]. (Only used in the transitional 2.5 region if VS_ControlMode =/ 2) +-2454.67747000 ! VS_KP - Proportional gain for generator PI torque controller [-]. (Only used in the transitional 2.5 region if VS_ControlMode =/ 2) -332.357190000 ! VS_KI - Integral gain for generator PI torque controller [s]. (Only used in the transitional 2.5 region if VS_ControlMode =/ 2) 9.76 ! VS_TSRopt - Power-maximizing region 2 tip-speed-ratio. Only used in VS_ControlMode = 2. 0.314000000000 ! VS_PwrFiltF - Low pass filter on power used to determine generator speed set point. Only used in VS_ControlMode = 3. @@ -113,7 +113,7 @@ 36 26 ! PerfTableSize - Size of rotor performance tables, first number refers to number of blade pitch angles, second number referse to number of tip-speed ratios 60 ! WE_FOPoles_N - Number of first-order system poles used in EKF 3.0000 3.1818 3.3637 3.5455 3.7274 3.9092 4.0911 4.2729 4.4548 4.6366 4.8185 5.0003 5.1822 5.3640 5.5459 5.7277 5.9096 6.0914 6.2732 6.4551 6.6369 6.8188 7.0006 7.1825 7.3643 7.5462 7.7280 7.9099 8.0917 8.2736 8.8311 9.3887 9.9462 10.5038 11.0613 11.6188 12.1764 12.7339 13.2915 13.8490 14.4066 14.9641 15.5217 16.0792 16.6368 17.1943 17.7519 18.3094 18.8670 19.4245 19.9821 20.5396 21.0972 21.6547 22.2123 22.7698 23.3274 23.8849 24.4425 25.0000 ! WE_FOPoles_v - Wind speeds corresponding to first-order system poles [m/s] --0.00972164 -0.01031092 -0.01090020 -0.01148948 -0.01207877 -0.01266805 -0.01325733 -0.01384662 -0.01443590 -0.01502518 -0.01561447 -0.01620375 -0.01679303 -0.01738232 -0.01797160 -0.01856088 -0.01915016 -0.01973945 -0.02032873 -0.02091801 -0.02150730 -0.02209658 -0.02268586 -0.02327515 -0.02386443 -0.02445371 -0.02504300 -0.02563228 -0.02622156 -0.02378670 -0.02062296 -0.02541485 -0.03159105 -0.03849962 -0.04595997 -0.05389417 -0.06225884 -0.07101431 -0.08016995 -0.08970426 -0.09955610 -0.10976762 -0.12028100 -0.13120419 -0.14238799 -0.15383228 -0.16572504 -0.17783697 -0.19011487 -0.20289651 -0.21593424 -0.22919262 -0.24255457 -0.25635133 -0.27049546 -0.28482651 -0.29923376 -0.31380076 -0.32862514 -0.34372726 ! WE_FOPoles - First order system poles [1/s] +-0.00969265 -0.01028018 -0.01086771 -0.01145523 -0.01204276 -0.01263029 -0.01321781 -0.01380534 -0.01439287 -0.01498039 -0.01556792 -0.01615544 -0.01674297 -0.01733050 -0.01791802 -0.01850555 -0.01909308 -0.01968060 -0.02026813 -0.02085566 -0.02144318 -0.02203071 -0.02261823 -0.02320576 -0.02379329 -0.02438081 -0.02496834 -0.02555587 -0.02614339 -0.02379613 -0.02047291 -0.02537932 -0.03151563 -0.03840840 -0.04587537 -0.05382394 -0.06221064 -0.07100937 -0.08011138 -0.08959645 -0.09946249 -0.10970584 -0.12021535 -0.13105665 -0.14226361 -0.15376640 -0.16552312 -0.17764204 -0.19004300 -0.20272586 -0.21577830 -0.22897091 -0.24242644 -0.25613739 -0.27000365 -0.28425482 -0.29866687 -0.31351260 -0.32866968 -0.34414305 ! WE_FOPoles - First order system poles [1/s] !------- YAW CONTROL ------------------------------------------------------ 0.00000 ! Y_uSwitch - Wind speed to switch between Y_ErrThresh. If zero, only the second value of Y_ErrThresh is used [m/s] diff --git a/Examples/Test_Cases/IEA-15-240-RWT-UMaineSemi/DISCON-UMaineSemi.IN b/Examples/Test_Cases/IEA-15-240-RWT-UMaineSemi/DISCON-UMaineSemi.IN index cd58ccf8..a55a49d0 100644 --- a/Examples/Test_Cases/IEA-15-240-RWT-UMaineSemi/DISCON-UMaineSemi.IN +++ b/Examples/Test_Cases/IEA-15-240-RWT-UMaineSemi/DISCON-UMaineSemi.IN @@ -1,10 +1,10 @@ ! Controller parameter input file for the IEA-15-240-RWT-UMaineSemi wind turbine -! - File written using ROSCO version 2.8.0 controller tuning logic on 01/05/24 +! - File written using ROSCO version 2.9.4 controller tuning logic on 07/01/24 !------- SIMULATION CONTROL ------------------------------------------------------------ 2 ! LoggingLevel - {0: write no debug files, 1: write standard output .dbg-file, 2: LoggingLevel 1 + ROSCO LocalVars (.dbg2) 3: LoggingLevel 2 + complete avrSWAP-array (.dbg3)} 0 ! DT_Out - {Time step to output .dbg* files, or 0 to match sampling period of OpenFAST} -1 ! Ext_Interface - (0 - use standard bladed interface, 1 - Use the extened DLL interface introduced in OpenFAST 3.5.0.) +1 ! Ext_Interface - (0 - use standard bladed interface, 1 - Use the extened DLL interface introduced in OpenFAST 3.5.0.) 0 ! Echo - (0 - no Echo, 1 - Echo input data to .echo) !------- CONTROLLER FLAGS ------------------------------------------------- @@ -52,9 +52,9 @@ !------- BLADE PITCH CONTROL ---------------------------------------------- 30 ! PC_GS_n - Amount of gain-scheduling table entries -0.061311 0.088116 0.108942 0.126990 0.143219 0.158161 0.172040 0.185119 0.197612 0.209635 0.221066 0.232181 0.242992 0.253405 0.263647 0.273567 0.283313 0.292848 0.302185 0.311386 0.320385 0.329291 0.338004 0.346643 0.355108 0.363504 0.371761 0.379937 0.388011 0.395981 ! PC_GS_angles - Gain-schedule table: pitch angles [rad]. --1.206456 -1.044724 -0.911403 -0.799610 -0.704521 -0.622652 -0.551426 -0.488893 -0.433554 -0.384235 -0.340004 -0.300113 -0.263952 -0.231022 -0.200909 -0.173265 -0.147799 -0.124263 -0.102447 -0.082167 -0.063268 -0.045612 -0.029082 -0.013573 0.001008 0.014740 0.027696 0.039940 0.051529 0.062514 ! PC_GS_KP - Gain-schedule table: pitch controller kp gains [s]. --0.125868 -0.113748 -0.103758 -0.095380 -0.088255 -0.082120 -0.076782 -0.072096 -0.067949 -0.064253 -0.060939 -0.057949 -0.055240 -0.052772 -0.050515 -0.048444 -0.046536 -0.044772 -0.043137 -0.041617 -0.040201 -0.038878 -0.037639 -0.036477 -0.035384 -0.034355 -0.033384 -0.032467 -0.031599 -0.030775 ! PC_GS_KI - Gain-schedule table: pitch controller ki gains [-]. +0.062094 0.088628 0.109270 0.127148 0.143223 0.158025 0.171764 0.184722 0.197105 0.209011 0.220338 0.231364 0.242063 0.252399 0.262569 0.272384 0.282068 0.291504 0.300785 0.309890 0.318839 0.327654 0.336324 0.344874 0.353301 0.361612 0.369834 0.377928 0.385970 0.393863 ! PC_GS_angles - Gain-schedule table: pitch angles [rad]. +-1.142777 -0.987724 -0.859824 -0.752519 -0.661205 -0.582556 -0.514107 -0.453995 -0.400785 -0.353352 -0.310803 -0.272422 -0.237625 -0.205931 -0.176944 -0.150331 -0.125812 -0.103149 -0.082139 -0.062607 -0.044403 -0.027396 -0.011472 0.003470 0.017518 0.030750 0.043234 0.055033 0.066202 0.076789 ! PC_GS_KP - Gain-schedule table: pitch controller kp gains [s]. +-0.119556 -0.108083 -0.098619 -0.090679 -0.083922 -0.078102 -0.073038 -0.068590 -0.064652 -0.061143 -0.057994 -0.055154 -0.052579 -0.050234 -0.048089 -0.046120 -0.044306 -0.042629 -0.041074 -0.039629 -0.038282 -0.037024 -0.035845 -0.034740 -0.033700 -0.032721 -0.031797 -0.030924 -0.030098 -0.029315 ! PC_GS_KI - Gain-schedule table: pitch controller ki gains [-]. 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 ! PC_GS_KD - Gain-schedule table: pitch controller kd gains 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 ! PC_GS_TF - Gain-schedule table: pitch controller tf gains (derivative filter) 1.570000000000 ! PC_MaxPit - Maximum physical pitch limit, [rad]. @@ -75,19 +75,19 @@ 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 ------------------------------------------------ -96.55000000000 ! VS_GenEff - Generator efficiency mechanical power -> electrical power, [should match the efficiency defined in the generator properties!], [%] -19624046.66639 ! VS_ArSatTq - Above rated generator torque PI control saturation, [Nm] +95.75600000000 ! VS_GenEff - Generator efficiency mechanical power -> electrical power, [should match the efficiency defined in the generator properties!], [%] +19786767.46773 ! VS_ArSatTq - Above rated generator torque PI control saturation, [Nm] 4500000.000000 ! VS_MaxRat - Maximum torque rate (in absolute value) in torque controller, [Nm/s]. -21586451.33303 ! VS_MaxTq - Maximum generator torque in Region 3 (HSS side), [Nm]. +21765444.21450 ! VS_MaxTq - Maximum generator torque in Region 3 (HSS side), [Nm]. 0.000000000000 ! VS_MinTq - Minimum generator torque (HSS side), [Nm]. 0.523600000000 ! VS_MinOMSpd - Minimum generator speed [rad/s] -31393135.82403 ! VS_Rgn2K - Generator torque constant in Region 2 (HSS side). Only used in VS_ControlMode = 1,3 +32413847.90763 ! VS_Rgn2K - Generator torque constant in Region 2 (HSS side). Only used in VS_ControlMode = 1,3 15000000.00000 ! VS_RtPwr - Wind turbine rated power [W] -19624046.66639 ! VS_RtTq - Rated torque, [Nm]. +19786767.46773 ! VS_RtTq - Rated torque, [Nm]. 0.791680000000 ! VS_RefSpd - Rated generator speed [rad/s] 1 ! VS_n - Number of generator PI torque controller gains --37877315.85935 ! VS_KP - Proportional gain for generator PI torque controller [-]. (Only used in the transitional 2.5 region if VS_ControlMode =/ 2) --4588245.18720 ! VS_KI - Integral gain for generator PI torque controller [s]. (Only used in the transitional 2.5 region if VS_ControlMode =/ 2) +-35730593.18196 ! VS_KP - Proportional gain for generator PI torque controller [-]. (Only used in the transitional 2.5 region if VS_ControlMode =/ 2) +-4499370.31680 ! VS_KI - Integral gain for generator PI torque controller [s]. (Only used in the transitional 2.5 region if VS_ControlMode =/ 2) 9.00 ! VS_TSRopt - Power-maximizing region 2 tip-speed-ratio. Only used in VS_ControlMode = 2. 0.314000000000 ! VS_PwrFiltF - Low pass filter on power used to determine generator speed set point. Only used in VS_ControlMode = 3. @@ -102,18 +102,18 @@ 0.7917 0.7917 ! PRC_GenSpeeds - Array of generator speeds corresponding to PRC_WindSpeeds [rad/s] !------- WIND SPEED ESTIMATOR --------------------------------------------- -120.000 ! WE_BladeRadius - Blade length (distance from hub center to blade tip), [m] +120.970 ! WE_BladeRadius - Blade length (distance from hub center to blade tip), [m] 1 ! WE_CP_n - Amount of parameters in the Cp array 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] 1.0 ! WE_GearboxRatio - Gearbox ratio [>=1], [-] -318628138.00000 ! WE_Jtot - Total drivetrain inertia, including blades, hub and casted generator inertia to LSS, [kg m^2] +312456272.00000 ! 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.IEA15MW.txt" ! PerfFileName - File containing rotor performance tables (Cp,Ct,Cq) (absolute path or relative to this file) 36 26 ! PerfTableSize - Size of rotor performance tables, first number refers to number of blade pitch angles, second number referse to number of tip-speed ratios 60 ! WE_FOPoles_N - Number of first-order system poles used in EKF 3.0000 3.2669 3.5338 3.8007 4.0676 4.3345 4.6014 4.8683 5.1352 5.4021 5.6690 5.9359 6.2028 6.4697 6.7366 7.0034 7.2703 7.5372 7.8041 8.0710 8.3379 8.6048 8.8717 9.1386 9.4055 9.6724 9.9393 10.2062 10.4731 10.7400 11.2153 11.6907 12.1660 12.6413 13.1167 13.5920 14.0673 14.5427 15.0180 15.4933 15.9687 16.4440 16.9193 17.3947 17.8700 18.3453 18.8207 19.2960 19.7713 20.2467 20.7220 21.1973 21.6727 22.1480 22.6233 23.0987 23.5740 24.0493 24.5247 25.0000 ! WE_FOPoles_v - Wind speeds corresponding to first-order system poles [m/s] --0.02438353 -0.02655283 -0.02872212 -0.03089141 -0.03306071 -0.03523000 -0.03739930 -0.03956859 -0.04173788 -0.04390718 -0.04607647 -0.04824576 -0.05041506 -0.05258435 -0.05475365 -0.05692294 -0.05909223 -0.06126153 -0.06343082 -0.06560011 -0.06776941 -0.06993870 -0.07210800 -0.07427729 -0.07644658 -0.07861588 -0.08078517 -0.08295446 -0.08512376 -0.08490640 -0.05739531 -0.05967534 -0.06643664 -0.07537721 -0.08537869 -0.09664144 -0.10851650 -0.12137925 -0.13453168 -0.14834459 -0.16280188 -0.17753158 -0.19283401 -0.20862160 -0.22461456 -0.24120058 -0.25817445 -0.27538476 -0.29299882 -0.31103587 -0.32941546 -0.34807902 -0.36693717 -0.38625237 -0.40583167 -0.42579305 -0.44596365 -0.46626113 -0.48675074 -0.50756940 ! WE_FOPoles - First order system poles [1/s] +-0.02567895 -0.02796349 -0.03024803 -0.03253257 -0.03481711 -0.03710166 -0.03938620 -0.04167074 -0.04395528 -0.04623982 -0.04852436 -0.05080890 -0.05309344 -0.05537798 -0.05766253 -0.05994707 -0.06223161 -0.06451615 -0.06680069 -0.06908523 -0.07136977 -0.07365431 -0.07593885 -0.07822339 -0.08050794 -0.08279248 -0.08507702 -0.08736156 -0.08964610 -0.09072643 -0.06009903 -0.06290457 -0.06990800 -0.07913876 -0.08983236 -0.10162611 -0.11417145 -0.12741619 -0.14137334 -0.15599691 -0.17090894 -0.18647049 -0.20252854 -0.21889218 -0.23592237 -0.25309367 -0.27087557 -0.28892640 -0.30743285 -0.32627475 -0.34546793 -0.36504435 -0.38494782 -0.40520553 -0.42575368 -0.44656633 -0.46770980 -0.48900537 -0.51069324 -0.53238692 ! WE_FOPoles - First order system poles [1/s] !------- YAW CONTROL ------------------------------------------------------ 0.00000 ! Y_uSwitch - Wind speed to switch between Y_ErrThresh. If zero, only the second value of Y_ErrThresh is used [m/s] @@ -135,7 +135,7 @@ !------- MINIMUM PITCH SATURATION ------------------------------------------- 60 ! PS_BldPitchMin_N - Number of values in minimum blade pitch lookup table (should equal number of values in PS_WindSpeeds and PS_BldPitchMin) 3.000 3.267 3.534 3.801 4.068 4.334 4.601 4.868 5.135 5.402 5.669 5.936 6.203 6.470 6.737 7.003 7.270 7.537 7.804 8.071 8.338 8.605 8.872 9.139 9.406 9.672 9.939 10.206 10.473 10.740 11.215 11.691 12.166 12.641 13.117 13.592 14.067 14.543 15.018 15.493 15.969 16.444 16.919 17.395 17.870 18.345 18.821 19.296 19.771 20.247 20.722 21.197 21.673 22.148 22.623 23.099 23.574 24.049 24.525 25.000 ! PS_WindSpeeds - Wind speeds corresponding to minimum blade pitch angles [m/s] -0.060 0.060 0.060 0.060 0.060 0.060 0.056 0.051 0.046 0.041 0.034 0.028 0.021 0.014 0.007 0.000 0.000 0.000 0.000 0.000 0.000 0.000 0.000 0.000 0.000 0.008 0.022 0.035 0.046 0.053 0.064 0.074 0.084 0.094 0.103 0.112 0.121 0.130 0.139 0.147 0.156 0.164 0.172 0.180 0.189 0.197 0.205 0.212 0.220 0.228 0.236 0.243 0.251 0.259 0.266 0.273 0.281 0.288 0.296 0.303 ! PS_BldPitchMin - Minimum blade pitch angles [rad] +0.060 0.060 0.060 0.060 0.060 0.060 0.056 0.052 0.047 0.041 0.036 0.029 0.022 0.015 0.008 0.001 0.000 0.000 0.000 0.000 0.000 0.000 0.000 0.000 0.000 0.006 0.021 0.033 0.044 0.053 0.064 0.074 0.084 0.093 0.103 0.112 0.121 0.130 0.138 0.147 0.155 0.163 0.172 0.180 0.188 0.196 0.203 0.211 0.219 0.227 0.234 0.242 0.250 0.257 0.265 0.272 0.279 0.287 0.294 0.301 ! PS_BldPitchMin - Minimum blade pitch angles [rad] !------- SHUTDOWN ----------------------------------------------------------- 0.698100000000 ! SD_MaxPit - Maximum blade pitch angle to initiate shutdown, [rad] @@ -143,7 +143,7 @@ !------- Floating ----------------------------------------------------------- 1 ! Fl_n - Number of Fl_Kp gains in gain scheduling, optional with default of 1 --9.3465 ! Fl_Kp - Nacelle pitching proportional feedback gain [s] +-9.1984 ! Fl_Kp - Nacelle pitching proportional feedback gain [s] 11.2770 ! Fl_U - Wind speeds for scheduling Fl_Kp, optional if Fl_Kp is single value [m/s] !------- FLAP ACTUATION ----------------------------------------------------- diff --git a/Examples/Test_Cases/MHK_RM1/MHK_RM1_DISCON.IN b/Examples/Test_Cases/MHK_RM1/MHK_RM1_DISCON.IN index 322213ff..e23b75b5 100644 --- a/Examples/Test_Cases/MHK_RM1/MHK_RM1_DISCON.IN +++ b/Examples/Test_Cases/MHK_RM1/MHK_RM1_DISCON.IN @@ -1,10 +1,10 @@ ! Controller parameter input file for the MHK_RM1_Floating wind turbine -! - File written using ROSCO version 2.8.0 controller tuning logic on 01/05/24 +! - File written using ROSCO version 2.9.4 controller tuning logic on 07/01/24 !------- SIMULATION CONTROL ------------------------------------------------------------ 2 ! LoggingLevel - {0: write no debug files, 1: write standard output .dbg-file, 2: LoggingLevel 1 + ROSCO LocalVars (.dbg2) 3: LoggingLevel 2 + complete avrSWAP-array (.dbg3)} 0 ! DT_Out - {Time step to output .dbg* files, or 0 to match sampling period of OpenFAST} -1 ! Ext_Interface - (0 - use standard bladed interface, 1 - Use the extened DLL interface introduced in OpenFAST 3.5.0.) +1 ! Ext_Interface - (0 - use standard bladed interface, 1 - Use the extened DLL interface introduced in OpenFAST 3.5.0.) 0 ! Echo - (0 - no Echo, 1 - Echo input data to .echo) !------- CONTROLLER FLAGS ------------------------------------------------- @@ -53,8 +53,8 @@ !------- BLADE PITCH CONTROL ---------------------------------------------- 30 ! PC_GS_n - Amount of gain-scheduling table entries 0.030335 0.049075 0.063610 0.076093 0.087460 0.097196 0.106672 0.115225 0.123634 0.131302 0.139019 0.146056 0.153083 0.159873 0.166338 0.172854 0.178999 0.185046 0.191143 0.196863 0.202559 0.208301 0.213742 0.219137 0.224575 0.229836 0.234972 0.240145 0.245291 0.250200 ! PC_GS_angles - Gain-schedule table: pitch angles [rad]. --0.010178 -0.008780 -0.007625 -0.006655 -0.005829 -0.005116 -0.004495 -0.003950 -0.003467 -0.003036 -0.002650 -0.002301 -0.001984 -0.001696 -0.001432 -0.001190 -0.000966 -0.000760 -0.000568 -0.000390 -0.000225 -0.000069 0.000076 0.000212 0.000340 0.000461 0.000575 0.000682 0.000784 0.000881 ! PC_GS_KP - Gain-schedule table: pitch controller kp gains [s]. --0.005272 -0.004770 -0.004355 -0.004007 -0.003710 -0.003454 -0.003232 -0.003036 -0.002862 -0.002708 -0.002569 -0.002443 -0.002330 -0.002226 -0.002132 -0.002045 -0.001964 -0.001890 -0.001822 -0.001758 -0.001698 -0.001642 -0.001590 -0.001541 -0.001495 -0.001452 -0.001411 -0.001372 -0.001336 -0.001301 ! PC_GS_KI - Gain-schedule table: pitch controller ki gains [-]. +-0.010207 -0.008807 -0.007650 -0.006678 -0.005849 -0.005135 -0.004512 -0.003965 -0.003481 -0.003048 -0.002661 -0.002310 -0.001993 -0.001703 -0.001438 -0.001195 -0.000971 -0.000764 -0.000572 -0.000393 -0.000226 -0.000071 0.000075 0.000212 0.000341 0.000462 0.000576 0.000685 0.000787 0.000884 ! PC_GS_KP - Gain-schedule table: pitch controller kp gains [s]. +-0.005283 -0.004781 -0.004366 -0.004017 -0.003720 -0.003464 -0.003241 -0.003045 -0.002871 -0.002716 -0.002577 -0.002451 -0.002337 -0.002234 -0.002139 -0.002051 -0.001971 -0.001897 -0.001828 -0.001764 -0.001704 -0.001648 -0.001596 -0.001547 -0.001501 -0.001457 -0.001416 -0.001377 -0.001341 -0.001306 ! PC_GS_KI - Gain-schedule table: pitch controller ki gains [-]. 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 ! PC_GS_KD - Gain-schedule table: pitch controller kd gains 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 ! PC_GS_TF - Gain-schedule table: pitch controller tf gains (derivative filter) 1.570000000000 ! PC_MaxPit - Maximum physical pitch limit, [rad]. @@ -86,7 +86,7 @@ 8300.335630000 ! VS_RtTq - Rated torque, [Nm]. 63.81200000000 ! VS_RefSpd - Rated generator speed [rad/s] 1 ! VS_n - Number of generator PI torque controller gains --63.8796200000 ! VS_KP - Proportional gain for generator PI torque controller [-]. (Only used in the transitional 2.5 region if VS_ControlMode =/ 2) +-63.3401400000 ! VS_KP - Proportional gain for generator PI torque controller [-]. (Only used in the transitional 2.5 region if VS_ControlMode =/ 2) -84.4329000000 ! VS_KI - Integral gain for generator PI torque controller [s]. (Only used in the transitional 2.5 region if VS_ControlMode =/ 2) 7.17 ! VS_TSRopt - Power-maximizing region 2 tip-speed-ratio. Only used in VS_ControlMode = 2. 0.314000000000 ! VS_PwrFiltF - Low pass filter on power used to determine generator speed set point. Only used in VS_ControlMode = 3. @@ -113,7 +113,7 @@ 36 26 ! PerfTableSize - Size of rotor performance tables, first number refers to number of blade pitch angles, second number referse to number of tip-speed ratios 60 ! WE_FOPoles_N - Number of first-order system poles used in EKF 0.5000 0.5517 0.6034 0.6552 0.7069 0.7586 0.8103 0.8621 0.9138 0.9655 1.0172 1.0690 1.1207 1.1724 1.2241 1.2759 1.3276 1.3793 1.4310 1.4828 1.5345 1.5862 1.6379 1.6897 1.7414 1.7931 1.8448 1.8966 1.9483 2.0000 2.0333 2.0667 2.1000 2.1333 2.1667 2.2000 2.2333 2.2667 2.3000 2.3333 2.3667 2.4000 2.4333 2.4667 2.5000 2.5333 2.5667 2.6000 2.6333 2.6667 2.7000 2.7333 2.7667 2.8000 2.8333 2.8667 2.9000 2.9333 2.9667 3.0000 ! WE_FOPoles_v - Wind speeds corresponding to first-order system poles [m/s] --0.14364445 -0.15850422 -0.17336400 -0.18822377 -0.20308354 -0.21794331 -0.23280308 -0.24766285 -0.26252262 -0.27738239 -0.29224216 -0.30710193 -0.32196171 -0.33682148 -0.35168125 -0.36654102 -0.38140079 -0.39626056 -0.41112033 -0.42598010 -0.44083987 -0.45569965 -0.47055942 -0.48666545 -0.50602877 -0.52082936 -0.60274133 -0.60720589 -0.60927938 -0.55668516 0.17844923 0.15174296 0.10860051 0.05753679 0.00176535 -0.05812003 -0.11803585 -0.18146508 -0.24666701 -0.31440662 -0.38335107 -0.45418067 -0.52480063 -0.59662243 -0.67000720 -0.74481113 -0.82056059 -0.89753628 -0.97589183 -1.05446405 -1.13345094 -1.21374047 -1.29379323 -1.37507241 -1.45808464 -1.54093580 -1.62426617 -1.70957888 -1.79610923 -1.88140848 ! WE_FOPoles - First order system poles [1/s] +-0.14373366 -0.15860266 -0.17347166 -0.18834066 -0.20320966 -0.21807866 -0.23294766 -0.24781666 -0.26268566 -0.27755466 -0.29242365 -0.30729265 -0.32216165 -0.33703065 -0.35189965 -0.36676865 -0.38163765 -0.39650665 -0.41137565 -0.42624465 -0.44111365 -0.45598265 -0.47085165 -0.48688530 -0.50710708 -0.52286299 -0.60338450 -0.60991074 -0.61241025 -0.55721025 0.17998191 0.15135742 0.10945592 0.05908027 0.00104043 -0.05507169 -0.11824557 -0.18009670 -0.24756868 -0.31240541 -0.38377494 -0.45106439 -0.52304487 -0.59605008 -0.66806086 -0.74501532 -0.81929468 -0.89533886 -0.97582430 -1.05220290 -1.13115451 -1.21410608 -1.29344979 -1.37444765 -1.45900848 -1.54200828 -1.62439937 -1.70996742 -1.79715535 -1.88045193 ! WE_FOPoles - First order system poles [1/s] !------- YAW CONTROL ------------------------------------------------------ 0.00000 ! Y_uSwitch - Wind speed to switch between Y_ErrThresh. If zero, only the second value of Y_ErrThresh is used [m/s] @@ -143,7 +143,7 @@ !------- Floating ----------------------------------------------------------- 1 ! Fl_n - Number of Fl_Kp gains in gain scheduling, optional with default of 1 --0.3999 ! Fl_Kp - Nacelle velocity proportional feedback gain [s] +-0.4009 ! Fl_Kp - Nacelle velocity proportional feedback gain [s] 2.1000 ! Fl_U - Wind speeds for scheduling Fl_Kp, optional if Fl_Kp is single value [m/s] !------- FLAP ACTUATION ----------------------------------------------------- diff --git a/Examples/Test_Cases/NREL-5MW/DISCON.IN b/Examples/Test_Cases/NREL-5MW/DISCON.IN index 0d8024d1..bf86cf78 100644 --- a/Examples/Test_Cases/NREL-5MW/DISCON.IN +++ b/Examples/Test_Cases/NREL-5MW/DISCON.IN @@ -1,10 +1,10 @@ ! Controller parameter input file for the NREL-5MW wind turbine -! - File written using ROSCO version 2.8.0 controller tuning logic on 01/05/24 +! - File written using ROSCO version 2.9.4 controller tuning logic on 07/01/24 !------- SIMULATION CONTROL ------------------------------------------------------------ 1 ! LoggingLevel - {0: write no debug files, 1: write standard output .dbg-file, 2: LoggingLevel 1 + ROSCO LocalVars (.dbg2) 3: LoggingLevel 2 + complete avrSWAP-array (.dbg3)} 0 ! DT_Out - {Time step to output .dbg* files, or 0 to match sampling period of OpenFAST} -1 ! Ext_Interface - (0 - use standard bladed interface, 1 - Use the extened DLL interface introduced in OpenFAST 3.5.0.) +1 ! Ext_Interface - (0 - use standard bladed interface, 1 - Use the extened DLL interface introduced in OpenFAST 3.5.0.) 0 ! Echo - (0 - no Echo, 1 - Echo input data to .echo) !------- CONTROLLER FLAGS ------------------------------------------------- @@ -53,8 +53,8 @@ !------- BLADE PITCH CONTROL ---------------------------------------------- 30 ! PC_GS_n - Amount of gain-scheduling table entries 0.056789 0.084492 0.106018 0.124332 0.140807 0.155903 0.169931 0.183270 0.196062 0.208354 0.220050 0.231503 0.242646 0.253377 0.263967 0.274233 0.284343 0.294292 0.303997 0.313626 0.322957 0.332260 0.341319 0.350368 0.359221 0.368059 0.376700 0.385301 0.393691 0.402050 ! PC_GS_angles - Gain-schedule table: pitch angles [rad]. --0.018995 -0.016672 -0.014787 -0.013228 -0.011916 -0.010797 -0.009831 -0.008989 -0.008248 -0.007592 -0.007006 -0.006480 -0.006005 -0.005574 -0.005182 -0.004822 -0.004492 -0.004187 -0.003906 -0.003644 -0.003402 -0.003175 -0.002963 -0.002765 -0.002579 -0.002404 -0.002239 -0.002083 -0.001936 -0.001797 ! PC_GS_KP - Gain-schedule table: pitch controller kp gains [s]. --0.008388 -0.007514 -0.006805 -0.006218 -0.005725 -0.005304 -0.004940 -0.004624 -0.004345 -0.004098 -0.003878 -0.003680 -0.003501 -0.003339 -0.003192 -0.003056 -0.002932 -0.002817 -0.002712 -0.002613 -0.002522 -0.002437 -0.002357 -0.002283 -0.002212 -0.002147 -0.002085 -0.002026 -0.001971 -0.001918 ! PC_GS_KI - Gain-schedule table: pitch controller ki gains [-]. +-0.019085 -0.016739 -0.014837 -0.013265 -0.011943 -0.010816 -0.009844 -0.008997 -0.008252 -0.007593 -0.007004 -0.006475 -0.005998 -0.005565 -0.005171 -0.004810 -0.004479 -0.004173 -0.003890 -0.003628 -0.003385 -0.003157 -0.002945 -0.002746 -0.002559 -0.002384 -0.002219 -0.002062 -0.001915 -0.001775 ! PC_GS_KP - Gain-schedule table: pitch controller kp gains [s]. +-0.008417 -0.007536 -0.006822 -0.006232 -0.005735 -0.005312 -0.004947 -0.004629 -0.004350 -0.004102 -0.003881 -0.003682 -0.003503 -0.003341 -0.003192 -0.003057 -0.002932 -0.002818 -0.002712 -0.002613 -0.002522 -0.002436 -0.002357 -0.002282 -0.002212 -0.002146 -0.002084 -0.002025 -0.001970 -0.001917 ! PC_GS_KI - Gain-schedule table: pitch controller ki gains [-]. 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 ! PC_GS_KD - Gain-schedule table: pitch controller kd gains 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 ! PC_GS_TF - Gain-schedule table: pitch controller tf gains (derivative filter) 1.570000000000 ! PC_MaxPit - Maximum physical pitch limit, [rad]. @@ -86,7 +86,7 @@ 43093.51876000 ! VS_RtTq - Rated torque, [Nm]. 122.9096700000 ! VS_RefSpd - Rated generator speed [rad/s] 1 ! VS_n - Number of generator PI torque controller gains --657.442080000 ! VS_KP - Proportional gain for generator PI torque controller [-]. (Only used in the transitional 2.5 region if VS_ControlMode =/ 2) +-654.312360000 ! VS_KP - Proportional gain for generator PI torque controller [-]. (Only used in the transitional 2.5 region if VS_ControlMode =/ 2) -104.507080000 ! VS_KI - Integral gain for generator PI torque controller [s]. (Only used in the transitional 2.5 region if VS_ControlMode =/ 2) 7.64 ! VS_TSRopt - Power-maximizing region 2 tip-speed-ratio. Only used in VS_ControlMode = 2. 0.314000000000 ! VS_PwrFiltF - Low pass filter on power used to determine generator speed set point. Only used in VS_ControlMode = 3. @@ -113,7 +113,7 @@ 36 26 ! PerfTableSize - Size of rotor performance tables, first number refers to number of blade pitch angles, second number referse to number of tip-speed ratios 60 ! WE_FOPoles_N - Number of first-order system poles used in EKF 3.0000 3.2897 3.5793 3.8690 4.1586 4.4483 4.7379 5.0276 5.3172 5.6069 5.8966 6.1862 6.4759 6.7655 7.0552 7.3448 7.6345 7.9241 8.2138 8.5034 8.7931 9.0828 9.3724 9.6621 9.9517 10.2414 10.5310 10.8207 11.1103 11.4000 11.8533 12.3067 12.7600 13.2133 13.6667 14.1200 14.5733 15.0267 15.4800 15.9333 16.3867 16.8400 17.2933 17.7467 18.2000 18.6533 19.1067 19.5600 20.0133 20.4667 20.9200 21.3733 21.8267 22.2800 22.7333 23.1867 23.6400 24.0933 24.5467 25.0000 ! WE_FOPoles_v - Wind speeds corresponding to first-order system poles [m/s] --0.01638154 -0.01796321 -0.01954487 -0.02112654 -0.02270820 -0.02428987 -0.02587154 -0.02745320 -0.02903487 -0.03061653 -0.03219820 -0.03377987 -0.03536153 -0.03694320 -0.03852486 -0.04010653 -0.04168820 -0.04326986 -0.04485153 -0.04643319 -0.04801486 -0.04959652 -0.05117819 -0.05275986 -0.05434152 -0.05592319 -0.05758373 -0.05882656 -0.06845507 -0.05992890 -0.05031134 -0.05798636 -0.06840333 -0.08061549 -0.09336590 -0.10698855 -0.12116040 -0.13530722 -0.15025447 -0.16589008 -0.18080009 -0.19651023 -0.21294470 -0.22969213 -0.24540879 -0.26178304 -0.27905964 -0.29706835 -0.31499595 -0.33136688 -0.34832584 -0.36677525 -0.38556416 -0.40554370 -0.42546670 -0.44309547 -0.46062268 -0.47954729 -0.49884696 -0.51943992 ! WE_FOPoles - First order system poles [1/s] +-0.01640352 -0.01798730 -0.01957109 -0.02115488 -0.02273867 -0.02432245 -0.02590624 -0.02749003 -0.02907382 -0.03065761 -0.03224139 -0.03382518 -0.03540897 -0.03699276 -0.03857654 -0.04016033 -0.04174412 -0.04332791 -0.04491170 -0.04649548 -0.04807927 -0.04966306 -0.05124685 -0.05283063 -0.05441442 -0.05599821 -0.05763347 -0.05907205 -0.06912889 -0.05993737 -0.05021616 -0.05780794 -0.06849544 -0.08052122 -0.09351145 -0.10710432 -0.12106730 -0.13547025 -0.15041833 -0.16588021 -0.18135551 -0.19724989 -0.21342206 -0.22970423 -0.24663982 -0.26354532 -0.28064419 -0.29794214 -0.31532544 -0.33332004 -0.35128130 -0.36985759 -0.38827549 -0.40713466 -0.42584061 -0.44509747 -0.46449375 -0.48460700 -0.50475242 -0.52537402 ! WE_FOPoles - First order system poles [1/s] !------- YAW CONTROL ------------------------------------------------------ 0.00000 ! Y_uSwitch - Wind speed to switch between Y_ErrThresh. If zero, only the second value of Y_ErrThresh is used [m/s] diff --git a/Examples/Test_Cases/NREL_2p8_127/NREL-2p8-127_DISCON.IN b/Examples/Test_Cases/NREL_2p8_127/NREL-2p8-127_DISCON.IN index 31d0ed79..46be3ce2 100644 --- a/Examples/Test_Cases/NREL_2p8_127/NREL-2p8-127_DISCON.IN +++ b/Examples/Test_Cases/NREL_2p8_127/NREL-2p8-127_DISCON.IN @@ -1,10 +1,10 @@ ! Controller parameter input file for the NREL-2p8-127 wind turbine -! - File written using ROSCO version 2.8.0 controller tuning logic on 01/05/24 +! - File written using ROSCO version 2.9.4 controller tuning logic on 07/01/24 !------- SIMULATION CONTROL ------------------------------------------------------------ 2 ! LoggingLevel - {0: write no debug files, 1: write standard output .dbg-file, 2: LoggingLevel 1 + ROSCO LocalVars (.dbg2) 3: LoggingLevel 2 + complete avrSWAP-array (.dbg3)} 0 ! DT_Out - {Time step to output .dbg* files, or 0 to match sampling period of OpenFAST} -1 ! Ext_Interface - (0 - use standard bladed interface, 1 - Use the extened DLL interface introduced in OpenFAST 3.5.0.) +1 ! Ext_Interface - (0 - use standard bladed interface, 1 - Use the extened DLL interface introduced in OpenFAST 3.5.0.) 0 ! Echo - (0 - no Echo, 1 - Echo input data to .echo) !------- CONTROLLER FLAGS ------------------------------------------------- @@ -53,8 +53,8 @@ !------- BLADE PITCH CONTROL ---------------------------------------------- 30 ! PC_GS_n - Amount of gain-scheduling table entries 0.075990 0.104503 0.127446 0.147544 0.164940 0.181678 0.197073 0.211624 0.225753 0.238993 0.252021 0.264458 0.276515 0.288229 0.299596 0.310932 0.321646 0.332112 0.342584 0.353105 0.363012 0.373072 0.382733 0.392195 0.401619 0.411107 0.420504 0.429096 0.437752 0.446357 ! PC_GS_angles - Gain-schedule table: pitch angles [rad]. --0.023307 -0.020910 -0.018908 -0.017210 -0.015752 -0.014487 -0.013378 -0.012398 -0.011527 -0.010746 -0.010043 -0.009406 -0.008827 -0.008298 -0.007813 -0.007366 -0.006953 -0.006571 -0.006216 -0.005885 -0.005577 -0.005288 -0.005017 -0.004762 -0.004522 -0.004296 -0.004083 -0.003881 -0.003689 -0.003508 ! PC_GS_KP - Gain-schedule table: pitch controller kp gains [s]. --0.000804 -0.000732 -0.000672 -0.000621 -0.000577 -0.000539 -0.000505 -0.000476 -0.000450 -0.000426 -0.000405 -0.000386 -0.000369 -0.000353 -0.000338 -0.000325 -0.000312 -0.000301 -0.000290 -0.000280 -0.000271 -0.000262 -0.000254 -0.000246 -0.000239 -0.000232 -0.000226 -0.000220 -0.000214 -0.000209 ! PC_GS_KI - Gain-schedule table: pitch controller ki gains [-]. +-0.023241 -0.020868 -0.018883 -0.017197 -0.015748 -0.014490 -0.013386 -0.012410 -0.011542 -0.010763 -0.010062 -0.009426 -0.008848 -0.008320 -0.007835 -0.007388 -0.006976 -0.006594 -0.006238 -0.005908 -0.005599 -0.005310 -0.005038 -0.004783 -0.004543 -0.004317 -0.004103 -0.003901 -0.003709 -0.003527 ! PC_GS_KP - Gain-schedule table: pitch controller kp gains [s]. +-0.000802 -0.000731 -0.000671 -0.000620 -0.000577 -0.000539 -0.000506 -0.000476 -0.000450 -0.000427 -0.000406 -0.000387 -0.000369 -0.000353 -0.000339 -0.000325 -0.000313 -0.000302 -0.000291 -0.000281 -0.000272 -0.000263 -0.000255 -0.000247 -0.000240 -0.000233 -0.000227 -0.000221 -0.000215 -0.000209 ! PC_GS_KI - Gain-schedule table: pitch controller ki gains [-]. 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 ! PC_GS_KD - Gain-schedule table: pitch controller kd gains 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 ! PC_GS_TF - Gain-schedule table: pitch controller tf gains (derivative filter) 1.570000000000 ! PC_MaxPit - Maximum physical pitch limit, [rad]. @@ -86,7 +86,7 @@ 24248.54567000 ! VS_RtTq - Rated torque, [Nm]. 122.9096700000 ! VS_RefSpd - Rated generator speed [rad/s] 1 ! VS_n - Number of generator PI torque controller gains --600.450450000 ! VS_KP - Proportional gain for generator PI torque controller [-]. (Only used in the transitional 2.5 region if VS_ControlMode =/ 2) +-599.338770000 ! VS_KP - Proportional gain for generator PI torque controller [-]. (Only used in the transitional 2.5 region if VS_ControlMode =/ 2) -85.3230300000 ! VS_KI - Integral gain for generator PI torque controller [s]. (Only used in the transitional 2.5 region if VS_ControlMode =/ 2) 8.25 ! VS_TSRopt - Power-maximizing region 2 tip-speed-ratio. Only used in VS_ControlMode = 2. 0.314000000000 ! VS_PwrFiltF - Low pass filter on power used to determine generator speed set point. Only used in VS_ControlMode = 3. @@ -113,7 +113,7 @@ 30 30 ! PerfTableSize - Size of rotor performance tables, first number refers to number of blade pitch angles, second number referse to number of tip-speed ratios 60 ! WE_FOPoles_N - Number of first-order system poles used in EKF 3.0000 3.2897 3.5793 3.8690 4.1586 4.4483 4.7379 5.0276 5.3172 5.6069 5.8966 6.1862 6.4759 6.7655 7.0552 7.3448 7.6345 7.9241 8.2138 8.5034 8.7931 9.0828 9.3724 9.6621 9.9517 10.2414 10.5310 10.8207 11.1103 11.4000 11.8533 12.3067 12.7600 13.2133 13.6667 14.1200 14.5733 15.0267 15.4800 15.9333 16.3867 16.8400 17.2933 17.7467 18.2000 18.6533 19.1067 19.5600 20.0133 20.4667 20.9200 21.3733 21.8267 22.2800 22.7333 23.1867 23.6400 24.0933 24.5467 25.0000 ! WE_FOPoles_v - Wind speeds corresponding to first-order system poles [m/s] --0.01246409 -0.01366752 -0.01487095 -0.01607438 -0.01727781 -0.01848123 -0.01968466 -0.02088809 -0.02209152 -0.02329495 -0.02449838 -0.02570181 -0.02690524 -0.02810867 -0.02931210 -0.03051553 -0.03171896 -0.03292239 -0.03412582 -0.03532924 -0.03653267 -0.03773610 -0.03893953 -0.04014296 -0.03876534 -0.03527029 -0.03014051 -0.02417865 -0.01714772 -0.00815401 -0.02209033 -0.02677213 -0.03094759 -0.03700125 -0.04188805 -0.04820630 -0.05390840 -0.06043728 -0.06624359 -0.07295380 -0.07986166 -0.08646363 -0.09412176 -0.10174417 -0.10913837 -0.11728247 -0.12497467 -0.13271621 -0.14189107 -0.15083268 -0.15981675 -0.16948290 -0.17870908 -0.18789884 -0.19750668 -0.20786563 -0.21788705 -0.22660607 -0.23612135 -0.24537696 ! WE_FOPoles - First order system poles [1/s] +-0.01260186 -0.01381859 -0.01503532 -0.01625205 -0.01746878 -0.01868551 -0.01990224 -0.02111897 -0.02233570 -0.02355243 -0.02476916 -0.02598590 -0.02720263 -0.02841936 -0.02963609 -0.03085282 -0.03206955 -0.03328628 -0.03450301 -0.03571974 -0.03693647 -0.03815320 -0.03936993 -0.04058667 -0.03922608 -0.03508867 -0.03003198 -0.02417528 -0.01730537 -0.00898539 -0.02245032 -0.02706065 -0.03108854 -0.03712828 -0.04209566 -0.04857003 -0.05395978 -0.06079111 -0.06630809 -0.07261058 -0.07985034 -0.08612180 -0.09374691 -0.10151803 -0.10895439 -0.11680833 -0.12401154 -0.13232357 -0.14130955 -0.14979812 -0.15867841 -0.16925534 -0.17835395 -0.18685622 -0.19682022 -0.20777561 -0.21797608 -0.22670834 -0.23616033 -0.24519119 ! WE_FOPoles - First order system poles [1/s] !------- YAW CONTROL ------------------------------------------------------ 0.00000 ! Y_uSwitch - Wind speed to switch between Y_ErrThresh. If zero, only the second value of Y_ErrThresh is used [m/s] diff --git a/pyproject.toml b/pyproject.toml index 6eba66b4..8b51ab87 100644 --- a/pyproject.toml +++ b/pyproject.toml @@ -4,7 +4,7 @@ build-backend = "setuptools.build_meta" [project] name = "rosco" -version = "2.9.3" +version = "2.9.4" description = "A reference open source controller toolset for wind turbine applications." readme = "README.md" requires-python = ">=3.9" diff --git a/rosco/toolbox/__init__.py b/rosco/toolbox/__init__.py index 3aa708bc..6a29f156 100644 --- a/rosco/toolbox/__init__.py +++ b/rosco/toolbox/__init__.py @@ -3,4 +3,4 @@ __author__ = """Nikhar J. Abbas and Daniel S. Zalkind""" __email__ = 'daniel.zalkind@nrel.gov' -__version__ = '2.9.0' +__version__ = '2.9.4' diff --git a/rosco/toolbox/controller.py b/rosco/toolbox/controller.py index 9b78cce5..f26c67d0 100644 --- a/rosco/toolbox/controller.py +++ b/rosco/toolbox/controller.py @@ -542,8 +542,8 @@ def tune_flap_controller(self,turbine): C1 = np.zeros(len(v_rel)) C2 = np.zeros(len(v_rel)) for i, (v_sec,phi) in enumerate(zip(v_rel, phi_vec)): - C1[i] = integrate.trapz(0.5 * turbine.rho * turbine.chord * v_sec[0]**2 * turbine.span * Kcl * np.cos(phi)) - C2[i] = integrate.trapz(0.5 * turbine.rho * turbine.chord * v_sec[0]**2 * turbine.span * Kcd * np.sin(phi)) + C1[i] = integrate.trapezoid(0.5 * turbine.rho * turbine.chord * v_sec[0]**2 * turbine.span * Kcl * np.cos(phi)) + C2[i] = integrate.trapezoid(0.5 * turbine.rho * turbine.chord * v_sec[0]**2 * turbine.span * Kcd * np.sin(phi)) self.kappa[i]=C1[i]+C2[i] # PI Gains diff --git a/rosco/toolbox/turbine.py b/rosco/toolbox/turbine.py index f7cbb727..ddf42a04 100644 --- a/rosco/toolbox/turbine.py +++ b/rosco/toolbox/turbine.py @@ -670,9 +670,9 @@ def interp_surface(self,pitch,TSR): ''' # Form the interpolant functions which can look up any arbitrary location on rotor performance surface - interp_fun = interpolate.interp2d( - self.pitch_initial_rad, self.TSR_initial, self.performance_table, kind='cubic') - return interp_fun(pitch,TSR) + interp_fun = interpolate.RectBivariateSpline( + self.pitch_initial_rad, self.TSR_initial, self.performance_table.T) + return np.squeeze(interp_fun(pitch,TSR).T) def interp_gradient(self,pitch,TSR): ''' @@ -691,11 +691,11 @@ def interp_gradient(self,pitch,TSR): [1 x 2] array coresponding to gradient in pitch and TSR directions, respectively ''' # Form the interpolant functions to find gradient at any arbitrary location on rotor performance surface - dCP_beta_interp = interpolate.interp2d(self.pitch_initial_rad, self.TSR_initial, self.gradient_pitch, kind='linear') - dCP_TSR_interp = interpolate.interp2d(self.pitch_initial_rad, self.TSR_initial, self.gradient_TSR, kind='linear') + dCP_beta_interp = interpolate.RectBivariateSpline(self.pitch_initial_rad, self.TSR_initial, self.gradient_pitch.T) + dCP_TSR_interp = interpolate.RectBivariateSpline(self.pitch_initial_rad, self.TSR_initial, self.gradient_TSR.T) # grad.shape output as (2,) numpy array, equivalent to (pitch-direction,TSR-direction) - grad = np.array([dCP_beta_interp(pitch,TSR), dCP_TSR_interp(pitch,TSR)]) + grad = np.array([dCP_beta_interp(pitch,TSR).T, dCP_TSR_interp(pitch,TSR).T]) return np.ndarray.flatten(grad) def plot_performance(self): From 86cf9f6c03535bc1eac65b54eb665a867487146a Mon Sep 17 00:00:00 2001 From: dzalkind Date: Mon, 1 Jul 2024 16:20:58 -0600 Subject: [PATCH 156/224] Update max_torque_rates --- Examples/Tune_Cases/NREL2p8.yaml | 2 +- Examples/Tune_Cases/NREL5MW.yaml | 2 +- Examples/Tune_Cases/NREL5MW_PassThrough.yaml | 2 +- Examples/Tune_Cases/RM1_MHK.yaml | 2 +- 4 files changed, 4 insertions(+), 4 deletions(-) diff --git a/Examples/Tune_Cases/NREL2p8.yaml b/Examples/Tune_Cases/NREL2p8.yaml index c1562a83..154d7b08 100644 --- a/Examples/Tune_Cases/NREL2p8.yaml +++ b/Examples/Tune_Cases/NREL2p8.yaml @@ -63,4 +63,4 @@ controller_params: n_U: 1 omega_flp: 0.0 zeta_flp: 0.0 -turbine_params: {rotor_inertia: 19858184.0, rated_rotor_speed: 1.26711, v_min: 3.0, v_rated: 11.4, v_max: 25.0, max_pitch_rate: 0.1745, max_torque_rate: 1500000.0, rated_power: 2800000.0, bld_edgewise_freq: 8.2831853, bld_flapwise_freq: 0.0, TSR_operational: 0} +turbine_params: {rotor_inertia: 19858184.0, rated_rotor_speed: 1.26711, v_min: 3.0, v_rated: 11.4, v_max: 25.0, max_pitch_rate: 0.1745, max_torque_rate: 550000.0, rated_power: 2800000.0, bld_edgewise_freq: 8.2831853, bld_flapwise_freq: 0.0, TSR_operational: 0} diff --git a/Examples/Tune_Cases/NREL5MW.yaml b/Examples/Tune_Cases/NREL5MW.yaml index 21f5acab..9d3ff2a5 100644 --- a/Examples/Tune_Cases/NREL5MW.yaml +++ b/Examples/Tune_Cases/NREL5MW.yaml @@ -16,7 +16,7 @@ turbine_params: v_rated: 11.4 # Rated wind speed [m/s] v_max: 25.0 # Cut-out wind speed [m/s], -- Does not need to be exact (JUST ASSUME FOR NOW) max_pitch_rate: 0.1745 # Maximum blade pitch rate [rad/s] - max_torque_rate: 1500000. # Maximum torque rate [Nm/s], {~1/4 VS_RtTq/s} + max_torque_rate: 1000000. # Maximum torque rate [Nm/s], {~1/4 VS_RtTq/s} rated_power: 5000000. # Rated Power [W] bld_edgewise_freq: 6.2831853 # Blade edgewise first natural frequency [rad/s] bld_flapwise_freq: 0.0 # Blade flapwise first natural frequency [rad/s] diff --git a/Examples/Tune_Cases/NREL5MW_PassThrough.yaml b/Examples/Tune_Cases/NREL5MW_PassThrough.yaml index 7f126785..d1f158a7 100644 --- a/Examples/Tune_Cases/NREL5MW_PassThrough.yaml +++ b/Examples/Tune_Cases/NREL5MW_PassThrough.yaml @@ -16,7 +16,7 @@ turbine_params: v_rated: 11.4 # Rated wind speed [m/s] v_max: 25.0 # Cut-out wind speed [m/s], -- Does not need to be exact (JUST ASSUME FOR NOW) max_pitch_rate: 0.1745 # Maximum blade pitch rate [rad/s] - max_torque_rate: 1500000. # Maximum torque rate [Nm/s], {~1/4 VS_RtTq/s} + max_torque_rate: 1000000. # Maximum torque rate [Nm/s], {~1/4 VS_RtTq/s} rated_power: 5000000. # Rated Power [W] bld_edgewise_freq: 6.2831853 # Blade edgewise first natural frequency [rad/s] bld_flapwise_freq: 0.0 # Blade flapwise first natural frequency [rad/s] diff --git a/Examples/Tune_Cases/RM1_MHK.yaml b/Examples/Tune_Cases/RM1_MHK.yaml index 12b294c2..c81d1b8f 100644 --- a/Examples/Tune_Cases/RM1_MHK.yaml +++ b/Examples/Tune_Cases/RM1_MHK.yaml @@ -16,7 +16,7 @@ turbine_params: v_rated: 2.0 # Rated wind speed [m/s] v_max: 3.0 # Cut-out wind speed [m/s], -- Does not need to be exact (JUST ASSUME FOR NOW) max_pitch_rate: 0.1745 # Maximum blade pitch rate [rad/s] - max_torque_rate: 1500000. # Maximum torque rate [Nm/s], {~1/4 VS_RtTq/s} + max_torque_rate: 100000. # Maximum torque rate [Nm/s], {~1/4 VS_RtTq/s} rated_power: 500000 # Rated Power [W] bld_edgewise_freq: 60.2831853 # Blade edgewise first natural frequency [rad/s] bld_flapwise_freq: 0.0 # Blade flapwise first natural frequency [rad/s] From 105dc45d11a5a5ffa445bd4ea4097966f664b08b Mon Sep 17 00:00:00 2001 From: dzalkind Date: Tue, 2 Jul 2024 16:21:59 -0600 Subject: [PATCH 157/224] Switch constants to integers --- rosco/controller/src/Constants.f90 | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/rosco/controller/src/Constants.f90 b/rosco/controller/src/Constants.f90 index dd3be0a5..3a1ee0c2 100644 --- a/rosco/controller/src/Constants.f90 +++ b/rosco/controller/src/Constants.f90 @@ -38,9 +38,9 @@ MODULE Constants CHARACTER(1), PARAMETER :: Tab = CHAR( 9 ) ! PRC Mode constants - REAL(IntKi), PARAMETER :: PRC_Comm_Constant = 0 ! Constant based on discon input - REAL(IntKi), PARAMETER :: PRC_Comm_OpenLoop = 1 ! Based on open loop input - REAL(IntKi), PARAMETER :: PRC_Comm_ZMQ = 2 ! Determined using ZMQ input + INTEGER(IntKi), PARAMETER :: PRC_Comm_Constant = 0 ! Constant based on discon input + INTEGER(IntKi), PARAMETER :: PRC_Comm_OpenLoop = 1 ! Based on open loop input + INTEGER(IntKi), PARAMETER :: PRC_Comm_ZMQ = 2 ! Determined using ZMQ input END MODULE Constants From 8b62b8542da9afb39c450b0cde1dadb2479404d0 Mon Sep 17 00:00:00 2001 From: dzalkind Date: Tue, 2 Jul 2024 16:29:08 -0600 Subject: [PATCH 158/224] Let R_Speed affect below rated ref speed (based on TSR) --- rosco/controller/src/ControllerBlocks.f90 | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/rosco/controller/src/ControllerBlocks.f90 b/rosco/controller/src/ControllerBlocks.f90 index 945cb007..d1544adf 100644 --- a/rosco/controller/src/ControllerBlocks.f90 +++ b/rosco/controller/src/ControllerBlocks.f90 @@ -114,7 +114,8 @@ SUBROUTINE ComputeVariablesSetpoints(CntrPar, LocalVar, objInst, DebugVar, ErrVa LocalVar%VS_RefSpd_TSR = CntrPar%VS_RefSpd ENDIF - LocalVar%VS_RefSpd = LocalVar%VS_RefSpd_TSR + ! Change VS Ref speed based on R_Speed + LocalVar%VS_RefSpd = LocalVar%VS_RefSpd_TSR * LocalVar%PRC_R_Speed ! Exclude reference speeds specified by user IF (CntrPar%TRA_Mode > 0) THEN From a83e4bbc0875929d36bf1f16717064e915fe0850 Mon Sep 17 00:00:00 2001 From: AbhineetGupta Date: Fri, 12 Jul 2024 13:34:09 -0600 Subject: [PATCH 159/224] Docs: Fix small bug in docs that caused errors with links --- docs/source/how_to_contribute_code.rst | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/docs/source/how_to_contribute_code.rst b/docs/source/how_to_contribute_code.rst index b9c6bed1..970f5d39 100644 --- a/docs/source/how_to_contribute_code.rst +++ b/docs/source/how_to_contribute_code.rst @@ -47,9 +47,9 @@ Updating the ROSCO API (Changing Input Files) --------------------------------------------- Any API changes should result in the following changes: -1. Update to the `rosco schema`_. -2. Update to `DISCON writer`_. You can use the `input_descriptions` dictionary to streamline the process. -3. `Document API changes here`_ -4. Update to the `rosco registry`_, which `regenerates the ROSCO_IO using this script`_. +1. Update to the `rosco schema `_. +2. Update to `DISCON writer `_. You can use the `input_descriptions` dictionary to streamline the process. +3. `Document API changes here `_ +4. Update to the `rosco registry `_, which `regenerates the ROSCO_IO using this script `_. From 3cc17b3e20765a9216cf0c630dedfc5fc276245c Mon Sep 17 00:00:00 2001 From: dzalkind Date: Fri, 12 Jul 2024 16:20:12 -0600 Subject: [PATCH 160/224] Add open loop control with wind speed breakpoints --- Examples/14_open_loop_control.py | 4 +- Examples/22_cable_control.py | 6 +- Examples/23_structural_control.py | 6 +- .../rosco_registry/rosco_types.yaml | 9 ++ rosco/controller/src/ControllerBlocks.f90 | 6 +- rosco/controller/src/Controllers.f90 | 10 +- rosco/controller/src/ROSCO_IO.f90 | 123 ++++++++-------- rosco/controller/src/ROSCO_Types.f90 | 5 +- rosco/controller/src/ReadSetParameters.f90 | 18 +++ rosco/toolbox/controller.py | 135 +++++++++++------- rosco/toolbox/inputs/toolbox_schema.yaml | 13 ++ rosco/toolbox/utilities.py | 3 + 12 files changed, 211 insertions(+), 127 deletions(-) diff --git a/Examples/14_open_loop_control.py b/Examples/14_open_loop_control.py index 862b6306..ada5cdb8 100644 --- a/Examples/14_open_loop_control.py +++ b/Examples/14_open_loop_control.py @@ -47,7 +47,7 @@ # Set up open loop input olc = ROSCO_controller.OpenLoopControl(t_max=20) -olc.interp_timeseries( +olc.interp_series( 'blade_pitch', [0,20], [0,0.0873] , @@ -60,7 +60,7 @@ olc.sine_timeseries('nacelle_yaw', 0.0524, 60) # Plot open loop timeseries -fig,ax = olc.plot_timeseries() +fig,ax = olc.plot_series() if False: plt.show() else: diff --git a/Examples/22_cable_control.py b/Examples/22_cable_control.py index ce9a85b2..72d76418 100644 --- a/Examples/22_cable_control.py +++ b/Examples/22_cable_control.py @@ -78,21 +78,21 @@ def main(): line_ends = [-14.51, 1.58, 10.33] olc = OpenLoopControl(t_max=t_max) - olc.interp_timeseries( + olc.interp_series( 'cable_control_1', [0,t_trans,t_trans+t_sigma], [0,0,line_ends[0]] , 'sigma' ) - olc.interp_timeseries( + olc.interp_series( 'cable_control_2', [0,t_trans,t_trans+t_sigma], [0,0,line_ends[1]] , 'sigma' ) - olc.interp_timeseries( + olc.interp_series( 'cable_control_3', [0,t_trans,t_trans+t_sigma], [0,0,line_ends[2]] , diff --git a/Examples/23_structural_control.py b/Examples/23_structural_control.py index 63022907..f39a6ffa 100644 --- a/Examples/23_structural_control.py +++ b/Examples/23_structural_control.py @@ -68,21 +68,21 @@ def main(): applied_force = [-2e6, 1e6, 1e6] olc = OpenLoopControl(t_max=t_max) - olc.interp_timeseries( + olc.interp_series( 'struct_control_1', [0,t_trans,t_trans+t_sigma], [0,0,applied_force[0]] , 'sigma' ) - olc.interp_timeseries( + olc.interp_series( 'struct_control_2', [0,t_trans,t_trans+t_sigma], [0,0,applied_force[1]] , 'sigma' ) - olc.interp_timeseries( + olc.interp_series( 'struct_control_3', [0,t_trans,t_trans+t_sigma], [0,0,applied_force[2]] , diff --git a/rosco/controller/rosco_registry/rosco_types.yaml b/rosco/controller/rosco_registry/rosco_types.yaml index 371a7aac..c807516d 100644 --- a/rosco/controller/rosco_registry/rosco_types.yaml +++ b/rosco/controller/rosco_registry/rosco_types.yaml @@ -514,6 +514,12 @@ ControlParameters: OL_Mode: <<: *integer description: Open loop control mode {0 - no open loop control, 1 - open loop control vs. time, 2 - open loop control vs. wind speed} + OL_BP_Mode: + <<: *integer + description: Open loop control mode {0 - no open loop control, 1 - open loop control vs. time, 2 - open loop control vs. wind speed} + OL_BP_FiltFreq: + <<: *real + description: Open loop control mode {0 - no open loop control, 1 - open loop control vs. time, 2 - open loop control vs. wind speed} Ind_Breakpoint: <<: *integer description: The column in OL_Filename that contains the breakpoint (time if OL_Mode = 1) @@ -1263,6 +1269,9 @@ LocalVariables: PS_Min_Pitch: <<: *real description: Instantaneous peak shaving + OL_Index: + <<: *real + description: Open loop indexing variable (time or wind speed) SD: <<: *logical description: Shutdown, .FALSE. if inactive, .TRUE. if active diff --git a/rosco/controller/src/ControllerBlocks.f90 b/rosco/controller/src/ControllerBlocks.f90 index d1544adf..93837fed 100644 --- a/rosco/controller/src/ControllerBlocks.f90 +++ b/rosco/controller/src/ControllerBlocks.f90 @@ -45,20 +45,20 @@ SUBROUTINE ComputeVariablesSetpoints(CntrPar, LocalVar, objInst, DebugVar, ErrVa ELSEIF (CntrPar%PRC_Comm == PRC_Comm_OpenLoop) THEN ! Open loop IF (CntrPar%Ind_R_Speed > 0) THEN - LocalVar%PRC_R_Speed = interp1d(CntrPar%OL_Breakpoints,CntrPar%OL_R_Speed,LocalVar%Time,ErrVar) + LocalVar%PRC_R_Speed = interp1d(CntrPar%OL_Breakpoints,CntrPar%OL_R_Speed,LocalVar%OL_Index,ErrVar) WRITE(401,*) LocalVar%PRC_R_Speed ELSE LocalVar%PRC_R_Speed = 1.0_DbKi ENDIF IF (CntrPar%Ind_R_Torque > 0) THEN - LocalVar%PRC_R_Torque = interp1d(CntrPar%OL_Breakpoints,CntrPar%OL_R_Torque,LocalVar%Time,ErrVar) + LocalVar%PRC_R_Torque = interp1d(CntrPar%OL_Breakpoints,CntrPar%OL_R_Torque,LocalVar%OL_Index,ErrVar) ELSE LocalVar%PRC_R_Torque = 1.0_DbKi ENDIF IF (CntrPar%Ind_R_Pitch > 0) THEN - LocalVar%PRC_R_Pitch = interp1d(CntrPar%OL_Breakpoints,CntrPar%OL_R_Pitch,LocalVar%Time,ErrVar) + LocalVar%PRC_R_Pitch = interp1d(CntrPar%OL_Breakpoints,CntrPar%OL_R_Pitch,LocalVar%OL_Index,ErrVar) ELSE LocalVar%PRC_R_Pitch = 1.0_DbKi ENDIF diff --git a/rosco/controller/src/Controllers.f90 b/rosco/controller/src/Controllers.f90 index 189ddd3c..d4bce27b 100644 --- a/rosco/controller/src/Controllers.f90 +++ b/rosco/controller/src/Controllers.f90 @@ -122,15 +122,15 @@ SUBROUTINE PitchControl(avrSWAP, CntrPar, LocalVar, objInst, DebugVar, ErrVar) IF (CntrPar%OL_Mode > 0) THEN IF (LocalVar%Time >= CntrPar%OL_Breakpoints(1)) THEN ! Time > first open loop breakpoint IF (CntrPar%Ind_BldPitch(1) > 0) THEN - LocalVar%PitCom(1) = interp1d(CntrPar%OL_Breakpoints,CntrPar%OL_BldPitch1,LocalVar%Time, ErrVar) + LocalVar%PitCom(1) = interp1d(CntrPar%OL_Breakpoints,CntrPar%OL_BldPitch1,LocalVar%OL_Index, ErrVar) ENDIF IF (CntrPar%Ind_BldPitch(2) > 0) THEN - LocalVar%PitCom(2) = interp1d(CntrPar%OL_Breakpoints,CntrPar%OL_BldPitch2,LocalVar%Time, ErrVar) + LocalVar%PitCom(2) = interp1d(CntrPar%OL_Breakpoints,CntrPar%OL_BldPitch2,LocalVar%OL_Index, ErrVar) ENDIF IF (CntrPar%Ind_BldPitch(3) > 0) THEN - LocalVar%PitCom(3) = interp1d(CntrPar%OL_Breakpoints,CntrPar%OL_BldPitch3,LocalVar%Time, ErrVar) + LocalVar%PitCom(3) = interp1d(CntrPar%OL_Breakpoints,CntrPar%OL_BldPitch3,LocalVar%OL_Index, ErrVar) ENDIF ENDIF ENDIF @@ -264,7 +264,7 @@ SUBROUTINE VariableSpeedControl(avrSWAP, CntrPar, LocalVar, objInst, ErrVar) IF ((CntrPar%OL_Mode > 0) .AND. (CntrPar%Ind_GenTq > 0)) THEN ! Get current OL GenTq, applies for OL_Mode 1 and 2 IF (LocalVar%Time >= CntrPar%OL_Breakpoints(1)) THEN - LocalVar%GenTq = interp1d(CntrPar%OL_Breakpoints,CntrPar%OL_GenTq,LocalVar%Time,ErrVar) + LocalVar%GenTq = interp1d(CntrPar%OL_Breakpoints,CntrPar%OL_GenTq,LocalVar%OL_Index,ErrVar) ENDIF ! Azimuth tracking control @@ -416,7 +416,7 @@ SUBROUTINE YawRateControl(avrSWAP, CntrPar, LocalVar, objInst, DebugVar, ErrVar) ! Open loop yaw rate control - control input in rad/s IF ((CntrPar%OL_Mode > 0) .AND. (CntrPar%Ind_YawRate > 0)) THEN IF (LocalVar%Time >= CntrPar%OL_Breakpoints(1)) THEN - avrSWAP(48) = interp1d(CntrPar%OL_Breakpoints,CntrPar%OL_YawRate,LocalVar%Time, ErrVar) + avrSWAP(48) = interp1d(CntrPar%OL_Breakpoints,CntrPar%OL_YawRate,LocalVar%OL_Index, ErrVar) ENDIF ENDIF diff --git a/rosco/controller/src/ROSCO_IO.f90 b/rosco/controller/src/ROSCO_IO.f90 index 0c101db9..a6d42209 100644 --- a/rosco/controller/src/ROSCO_IO.f90 +++ b/rosco/controller/src/ROSCO_IO.f90 @@ -1,5 +1,5 @@ ! ROSCO IO -! This file is automatically generated by write_registry.py using ROSCO v2.9.0 +! This file is automatically generated by write_registry.py using ROSCO v2.9.4 ! For any modification to the registry, please edit the rosco_types.yaml accordingly MODULE ROSCO_IO @@ -150,6 +150,7 @@ SUBROUTINE WriteRestartFile(LocalVar, CntrPar, ErrVar, objInst, RootName, size_a WRITE( Un, IOSTAT=ErrStat) LocalVar%PRC_R_Total WRITE( Un, IOSTAT=ErrStat) LocalVar%PRC_Min_Pitch WRITE( Un, IOSTAT=ErrStat) LocalVar%PS_Min_Pitch + WRITE( Un, IOSTAT=ErrStat) LocalVar%OL_Index WRITE( Un, IOSTAT=ErrStat) LocalVar%SD WRITE( Un, IOSTAT=ErrStat) LocalVar%Fl_PitCom WRITE( Un, IOSTAT=ErrStat) LocalVar%NACIMU_FA_AccF @@ -461,6 +462,7 @@ SUBROUTINE ReadRestartFile(avrSWAP, LocalVar, CntrPar, objInst, PerfData, RootNa READ( Un, IOSTAT=ErrStat) LocalVar%PRC_R_Total READ( Un, IOSTAT=ErrStat) LocalVar%PRC_Min_Pitch READ( Un, IOSTAT=ErrStat) LocalVar%PS_Min_Pitch + READ( Un, IOSTAT=ErrStat) LocalVar%OL_Index READ( Un, IOSTAT=ErrStat) LocalVar%SD READ( Un, IOSTAT=ErrStat) LocalVar%Fl_PitCom READ( Un, IOSTAT=ErrStat) LocalVar%NACIMU_FA_AccF @@ -710,7 +712,7 @@ SUBROUTINE Debug(LocalVar, CntrPar, DebugVar, ErrVar, avrSWAP, RootName, size_av '[N/A]', '[N/A]', '[N/A]', '[N/A]', '[rad/s]', & '[deg]', '[deg]', '[deg]', '[N/A]', '[rad/s]', & '[rad/s]'] - nLocalVars = 133 + nLocalVars = 134 Allocate(LocalVarOutData(nLocalVars)) Allocate(LocalVarOutStrings(nLocalVars)) LocalVarOutData(1) = LocalVar%iStatus @@ -807,45 +809,46 @@ SUBROUTINE Debug(LocalVar, CntrPar, DebugVar, ErrVar, avrSWAP, RootName, size_av LocalVarOutData(92) = LocalVar%PRC_R_Total LocalVarOutData(93) = LocalVar%PRC_Min_Pitch LocalVarOutData(94) = LocalVar%PS_Min_Pitch - LocalVarOutData(95) = LocalVar%Fl_PitCom - LocalVarOutData(96) = LocalVar%NACIMU_FA_AccF - LocalVarOutData(97) = LocalVar%FA_AccF - LocalVarOutData(98) = LocalVar%FA_Hist - LocalVarOutData(99) = LocalVar%TRA_LastRefSpd - LocalVarOutData(100) = LocalVar%VS_RefSpeed - LocalVarOutData(101) = LocalVar%PtfmTDX - LocalVarOutData(102) = LocalVar%PtfmTDY - LocalVarOutData(103) = LocalVar%PtfmTDZ - LocalVarOutData(104) = LocalVar%PtfmRDX - LocalVarOutData(105) = LocalVar%PtfmRDY - LocalVarOutData(106) = LocalVar%PtfmRDZ - LocalVarOutData(107) = LocalVar%PtfmTVX - LocalVarOutData(108) = LocalVar%PtfmTVY - LocalVarOutData(109) = LocalVar%PtfmTVZ - LocalVarOutData(110) = LocalVar%PtfmRVX - LocalVarOutData(111) = LocalVar%PtfmRVY - LocalVarOutData(112) = LocalVar%PtfmRVZ - LocalVarOutData(113) = LocalVar%PtfmTAX - LocalVarOutData(114) = LocalVar%PtfmTAY - LocalVarOutData(115) = LocalVar%PtfmTAZ - LocalVarOutData(116) = LocalVar%PtfmRAX - LocalVarOutData(117) = LocalVar%PtfmRAY - LocalVarOutData(118) = LocalVar%PtfmRAZ - LocalVarOutData(119) = LocalVar%CC_DesiredL(1) - LocalVarOutData(120) = LocalVar%CC_ActuatedL(1) - LocalVarOutData(121) = LocalVar%CC_ActuatedDL(1) - LocalVarOutData(122) = LocalVar%StC_Input(1) - LocalVarOutData(123) = LocalVar%Flp_Angle(1) - LocalVarOutData(124) = LocalVar%RootMyb_Last(1) - LocalVarOutData(125) = LocalVar%ACC_INFILE_SIZE - LocalVarOutData(126) = LocalVar%AWC_complexangle(1) - LocalVarOutData(127) = LocalVar%ZMQ_ID - LocalVarOutData(128) = LocalVar%ZMQ_YawOffset - LocalVarOutData(129) = LocalVar%ZMQ_TorqueOffset - LocalVarOutData(130) = LocalVar%ZMQ_PitOffset(1) - LocalVarOutData(131) = LocalVar%ZMQ_R_Speed - LocalVarOutData(132) = LocalVar%ZMQ_R_Torque - LocalVarOutData(133) = LocalVar%ZMQ_R_Pitch + LocalVarOutData(95) = LocalVar%OL_Index + LocalVarOutData(96) = LocalVar%Fl_PitCom + LocalVarOutData(97) = LocalVar%NACIMU_FA_AccF + LocalVarOutData(98) = LocalVar%FA_AccF + LocalVarOutData(99) = LocalVar%FA_Hist + LocalVarOutData(100) = LocalVar%TRA_LastRefSpd + LocalVarOutData(101) = LocalVar%VS_RefSpeed + LocalVarOutData(102) = LocalVar%PtfmTDX + LocalVarOutData(103) = LocalVar%PtfmTDY + LocalVarOutData(104) = LocalVar%PtfmTDZ + LocalVarOutData(105) = LocalVar%PtfmRDX + LocalVarOutData(106) = LocalVar%PtfmRDY + LocalVarOutData(107) = LocalVar%PtfmRDZ + LocalVarOutData(108) = LocalVar%PtfmTVX + LocalVarOutData(109) = LocalVar%PtfmTVY + LocalVarOutData(110) = LocalVar%PtfmTVZ + LocalVarOutData(111) = LocalVar%PtfmRVX + LocalVarOutData(112) = LocalVar%PtfmRVY + LocalVarOutData(113) = LocalVar%PtfmRVZ + LocalVarOutData(114) = LocalVar%PtfmTAX + LocalVarOutData(115) = LocalVar%PtfmTAY + LocalVarOutData(116) = LocalVar%PtfmTAZ + LocalVarOutData(117) = LocalVar%PtfmRAX + LocalVarOutData(118) = LocalVar%PtfmRAY + LocalVarOutData(119) = LocalVar%PtfmRAZ + LocalVarOutData(120) = LocalVar%CC_DesiredL(1) + LocalVarOutData(121) = LocalVar%CC_ActuatedL(1) + LocalVarOutData(122) = LocalVar%CC_ActuatedDL(1) + LocalVarOutData(123) = LocalVar%StC_Input(1) + LocalVarOutData(124) = LocalVar%Flp_Angle(1) + LocalVarOutData(125) = LocalVar%RootMyb_Last(1) + LocalVarOutData(126) = LocalVar%ACC_INFILE_SIZE + LocalVarOutData(127) = LocalVar%AWC_complexangle(1) + LocalVarOutData(128) = LocalVar%ZMQ_ID + LocalVarOutData(129) = LocalVar%ZMQ_YawOffset + LocalVarOutData(130) = LocalVar%ZMQ_TorqueOffset + LocalVarOutData(131) = LocalVar%ZMQ_PitOffset(1) + LocalVarOutData(132) = LocalVar%ZMQ_R_Speed + LocalVarOutData(133) = LocalVar%ZMQ_R_Torque + LocalVarOutData(134) = LocalVar%ZMQ_R_Pitch LocalVarOutStrings = [CHARACTER(15) :: 'iStatus', 'Time', 'DT', 'n_DT', 'Time_Last', & 'VS_GenPwr', 'VS_GenPwrF', 'GenSpeed', 'RotSpeed', 'NacHeading', & 'NacVane', 'HorWindV', 'rootMOOP', 'rootMOOPF', 'BlPitch', & @@ -864,15 +867,15 @@ SUBROUTINE Debug(LocalVar, CntrPar, DebugVar, ErrVar, avrSWAP, RootName, size_av 'VS_LastGenPwr', 'VS_MechGenPwr', 'VS_SpdErrAr', 'VS_SpdErrBr', 'VS_SpdErr', & 'VS_State', 'VS_Rgn3Pitch', 'WE_Vw', 'WE_Vw_F', 'WE_VwI', & 'WE_VwIdot', 'VS_LastGenTrqF', 'PRC_WSE_F', 'PRC_R_Speed', 'PRC_R_Torque', & - 'PRC_R_Pitch', 'PRC_R_Total', 'PRC_Min_Pitch', 'PS_Min_Pitch', 'Fl_PitCom', & - 'NACIMU_FA_AccF', 'FA_AccF', 'FA_Hist', 'TRA_LastRefSpd', 'VS_RefSpeed', & - 'PtfmTDX', 'PtfmTDY', 'PtfmTDZ', 'PtfmRDX', 'PtfmRDY', & - 'PtfmRDZ', 'PtfmTVX', 'PtfmTVY', 'PtfmTVZ', 'PtfmRVX', & - 'PtfmRVY', 'PtfmRVZ', 'PtfmTAX', 'PtfmTAY', 'PtfmTAZ', & - 'PtfmRAX', 'PtfmRAY', 'PtfmRAZ', 'CC_DesiredL', 'CC_ActuatedL', & - 'CC_ActuatedDL', 'StC_Input', 'Flp_Angle', 'RootMyb_Last', 'ACC_INFILE_SIZE', & - 'AWC_complexangle', 'ZMQ_ID', 'ZMQ_YawOffset', 'ZMQ_TorqueOffset', 'ZMQ_PitOffset', & - 'ZMQ_R_Speed', 'ZMQ_R_Torque', 'ZMQ_R_Pitch'] + 'PRC_R_Pitch', 'PRC_R_Total', 'PRC_Min_Pitch', 'PS_Min_Pitch', 'OL_Index', & + 'Fl_PitCom', 'NACIMU_FA_AccF', 'FA_AccF', 'FA_Hist', 'TRA_LastRefSpd', & + 'VS_RefSpeed', 'PtfmTDX', 'PtfmTDY', 'PtfmTDZ', 'PtfmRDX', & + 'PtfmRDY', 'PtfmRDZ', 'PtfmTVX', 'PtfmTVY', 'PtfmTVZ', & + 'PtfmRVX', 'PtfmRVY', 'PtfmRVZ', 'PtfmTAX', 'PtfmTAY', & + 'PtfmTAZ', 'PtfmRAX', 'PtfmRAY', 'PtfmRAZ', 'CC_DesiredL', & + 'CC_ActuatedL', 'CC_ActuatedDL', 'StC_Input', 'Flp_Angle', 'RootMyb_Last', & + 'ACC_INFILE_SIZE', 'AWC_complexangle', 'ZMQ_ID', 'ZMQ_YawOffset', 'ZMQ_TorqueOffset', & + 'ZMQ_PitOffset', 'ZMQ_R_Speed', 'ZMQ_R_Torque', 'ZMQ_R_Pitch'] ! Initialize debug file IF ((LocalVar%iStatus == 0) .OR. (LocalVar%iStatus == -9)) THEN ! .TRUE. if we're on the first call to the DLL IF (CntrPar%LoggingLevel > 0) THEN @@ -887,8 +890,8 @@ SUBROUTINE Debug(LocalVar, CntrPar, DebugVar, ErrVar, avrSWAP, RootName, size_av CALL GetNewUnit(UnDb2, ErrVar) OPEN(unit=UnDb2, FILE=TRIM(RootName)//'.RO.dbg2') WRITE(UnDb2, *) 'Generated on '//CurDate()//' at '//CurTime()//' using ROSCO-'//TRIM(rosco_version) - WRITE(UnDb2, '(134(a20,TR5:))') 'Time', LocalVarOutStrings - WRITE(UnDb2, '(134(a20,TR5:))') + WRITE(UnDb2, '(135(a20,TR5:))') 'Time', LocalVarOutStrings + WRITE(UnDb2, '(135(a20,TR5:))') END IF IF (CntrPar%LoggingLevel > 2) THEN @@ -933,25 +936,25 @@ SUBROUTINE Debug(LocalVar, CntrPar, DebugVar, ErrVar, avrSWAP, RootName, size_av ! Process DebugOutData, LocalVarOutData ! Remove very small numbers that cause ******** outputs DO I = 1,SIZE(DebugOutData) - IF (ABS(DebugOutData(I)) < 1D-99) THEN + IF (ABS(DebugOutData(I)) < 1E-99) THEN DebugOutData(I) = 0 END IF - IF (ABS(DebugOutData(I)) > 1D+99) THEN - DebugOutData(I) = 1D+99 + IF (ABS(DebugOutData(I)) > 1E+99) THEN + DebugOutData(I) = 1E+99 END IF END DO DO I = 1,SIZE(LocalVarOutData) - IF (ABS(LocalVarOutData(I)) < 1D-99) THEN + IF (ABS(LocalVarOutData(I)) < 1E-99) THEN LocalVarOutData(I) = 0 END IF - IF (ABS(LocalVarOutData(I)) > 1D+99) THEN - LocalVarOutData(I) = 1D+99 + IF (ABS(LocalVarOutData(I)) > 1E+99) THEN + LocalVarOutData(I) = 1E+99 END IF END DO ! Write debug files - FmtDat = "(F20.5,TR5,133(ES20.5E2,TR5:))" ! The format of the debugging data + FmtDat = "(F20.5,TR5,134(ES20.5E2,TR5:))" ! The format of the debugging data IF ( MOD(LocalVar%n_DT, CntrPar%n_DT_Out) == 0) THEN IF(CntrPar%LoggingLevel > 0) THEN WRITE (UnDb, TRIM(FmtDat)) LocalVar%Time, DebugOutData @@ -974,4 +977,4 @@ SUBROUTINE Debug(LocalVar, CntrPar, DebugVar, ErrVar, avrSWAP, RootName, size_av ENDIF END SUBROUTINE Debug -END MODULE ROSCO_IO +END MODULE ROSCO_IO \ No newline at end of file diff --git a/rosco/controller/src/ROSCO_Types.f90 b/rosco/controller/src/ROSCO_Types.f90 index e3aebc42..16d4ada2 100644 --- a/rosco/controller/src/ROSCO_Types.f90 +++ b/rosco/controller/src/ROSCO_Types.f90 @@ -1,5 +1,5 @@ ! ROSCO Registry -! This file is automatically generated by write_registry.py using ROSCO v2.9.0 +! This file is automatically generated by write_registry.py using ROSCO v2.9.4 ! For any modification to the registry, please edit the rosco_types.yaml accordingly MODULE ROSCO_Types @@ -133,6 +133,8 @@ MODULE ROSCO_Types REAL(DbKi) :: Flp_MaxPit ! Maximum (and minimum) flap pitch angle [rad] CHARACTER(1024) :: OL_Filename ! Input file with open loop timeseries INTEGER(IntKi) :: OL_Mode ! Open loop control mode {0 - no open loop control, 1 - open loop control vs. time, 2 - open loop control vs. wind speed} + INTEGER(IntKi) :: OL_BP_Mode ! Open loop control mode {0 - no open loop control, 1 - open loop control vs. time, 2 - open loop control vs. wind speed} + REAL(DbKi) :: OL_BP_FiltFreq ! Open loop control mode {0 - no open loop control, 1 - open loop control vs. time, 2 - open loop control vs. wind speed} INTEGER(IntKi) :: Ind_Breakpoint ! The column in OL_Filename that contains the breakpoint (time if OL_Mode = 1) INTEGER(IntKi), DIMENSION(:), ALLOCATABLE :: Ind_BldPitch ! The columns in OL_Filename that contains the blade pitch inputs (1,2,3) in rad INTEGER(IntKi) :: Ind_GenTq ! The column in OL_Filename that contains the generator torque in Nm @@ -355,6 +357,7 @@ MODULE ROSCO_Types REAL(DbKi) :: PRC_R_Total ! Instantaneous PRC_R_Total REAL(DbKi) :: PRC_Min_Pitch ! Instantaneous PRC_Min_Pitch REAL(DbKi) :: PS_Min_Pitch ! Instantaneous peak shaving + REAL(DbKi) :: OL_Index ! Open loop indexing variable (time or wind speed) LOGICAL :: SD ! Shutdown, .FALSE. if inactive, .TRUE. if active REAL(DbKi) :: Fl_PitCom ! Shutdown, .FALSE. if inactive, .TRUE. if active REAL(DbKi) :: NACIMU_FA_AccF ! None diff --git a/rosco/controller/src/ReadSetParameters.f90 b/rosco/controller/src/ReadSetParameters.f90 index b225cc2c..a4bbfd0e 100644 --- a/rosco/controller/src/ReadSetParameters.f90 +++ b/rosco/controller/src/ReadSetParameters.f90 @@ -251,6 +251,22 @@ SUBROUTINE SetParameters(avrSWAP, accINFILE, size_avcMSG, CntrPar, LocalVar, obj ENDIF + + ! Initialize other values on each timestep + + ! Open Loop index + IF (CntrPar%OL_BP_Mode == 0) THEN + LocalVar%OL_Index = LocalVar%Time + + ELSE + ! Wind speed, OL_BP_Mode = 1 + LocalVar%OL_Index = LocalVar%WE_Vw + IF (CntrPar%OL_BP_FiltFreq > 0) THEN + LocalVar%OL_Index = LPFilter(LocalVar%WE_Vw, LocalVar%DT,CntrPar%OL_BP_FiltFreq, LocalVar%FP, LocalVar%iStatus, LocalVar%restart, objInst%instLPF) + ENDIF + + ENDIF + END SUBROUTINE SetParameters ! ----------------------------------------------------------------------------------- @@ -518,6 +534,8 @@ SUBROUTINE ReadControlParameterFileSub(CntrPar, LocalVar, accINFILE, accINFILE_s !------------ Open loop input ------------ ! Indices can be left 0 by default, checked later CALL ParseInput(FileLines, 'OL_Filename', CntrPar%OL_Filename, accINFILE(1), ErrVar, CntrPar%OL_Mode == 0, UnEc) + CALL ParseInput(FileLines, 'OL_BP_Mode', CntrPar%OL_BP_Mode, accINFILE(1), ErrVar, CntrPar%OL_Mode == 0, UnEc) + CALL ParseInput(FileLines, 'OL_BP_FiltFreq', CntrPar%OL_BP_FiltFreq, accINFILE(1), ErrVar, CntrPar%OL_Mode == 0, UnEc) CALL ParseInput(FileLines, 'Ind_Breakpoint', CntrPar%Ind_Breakpoint, accINFILE(1), ErrVar, UnEc=UnEc) CALL ParseAry( FileLines, 'Ind_BldPitch', CntrPar%Ind_BldPitch, 3, accINFILE(1), ErrVar, UnEc=UnEc) CALL ParseInput(FileLines, 'Ind_GenTq', CntrPar%Ind_GenTq, accINFILE(1), ErrVar, UnEc=UnEc) diff --git a/rosco/toolbox/controller.py b/rosco/toolbox/controller.py index 1dd19f30..50fccbc0 100644 --- a/rosco/toolbox/controller.py +++ b/rosco/toolbox/controller.py @@ -147,12 +147,14 @@ def __init__(self, controller_params): self.OL_Filename = controller_params['open_loop']['filename'] self.OL_Ind_Breakpoint = self.OL_Ind_GenTq = self.OL_Ind_YawRate = self.OL_Ind_Azimuth = 0 self.OL_Ind_R_Speed = self.OL_Ind_R_Torque = self.OL_Ind_R_Pitch = 0 - self.OL_Ind_BldPitch = [0,0,0] - self.OL_Ind_CableControl = [0] - self.OL_Ind_StructControl = [0] + self.OL_Ind_BldPitch = [0,0,0] + self.OL_Ind_CableControl = [0] + self.OL_Ind_StructControl = [0] + self.OL_BP_Mode = 0 if self.OL_Mode: ol_params = controller_params['open_loop'] + self.OL_BP_Mode = ol_params['OL_BP_Mode'] self.OL_Ind_Breakpoint = ol_params['OL_Ind_Breakpoint'] self.OL_Ind_BldPitch = ol_params['OL_Ind_BldPitch'] self.OL_Ind_GenTq = ol_params['OL_Ind_GenTq'] @@ -743,18 +745,12 @@ class OpenLoopControl(object): ''' def __init__(self, **kwargs): - self.dt = 0.05 - self.t_max = 200 - - # Optional population class attributes from key word arguments - for (k, w) in kwargs.items(): - try: - setattr(self, k, w) - except: - pass - - self.ol_timeseries = {} - self.ol_timeseries['time'] = np.arange(0,self.t_max,self.dt) + self.dt = 0.05 # sec + self.t_max = 200 # sec + self.breakpoint = 'time' # or wind_speed + self.du = 0.5 # m/s + self.u_min = 5 # m/s + self.u_max = 30 # m/s self.allowed_controls = [ 'blade_pitch', @@ -767,13 +763,29 @@ def __init__(self, **kwargs): 'R_torque', 'R_pitch', ] + self.allowed_breakpoints = ['time','wind_speed'] + + # Optional population class attributes from key word arguments + for (k, w) in kwargs.items(): + try: + setattr(self, k, w) + except: + pass + + self.ol_series = {} + if self.breakpoint == 'time': + self.ol_series[self.breakpoint] = np.arange(0,self.t_max+self.dt,self.dt) + elif self.breakpoint == 'wind_speed': + self.ol_series[self.breakpoint] = np.arange(self.u_min,self.u_max+self.du,self.du) + else: + raise Exception(f'Breakpoint of {self.breakpoint} is not allowed. Available options are {self.allowed_breakpoints}.') def const_timeseries(self,control,value): - self.ol_timeseries[control] = value * np.ones(len(self.ol_timeseries['time'])) + self.ol_series[control] = value * np.ones(len(self.ol_series[self.breakpoint])) - def interp_timeseries(self,control,breakpoints,values,method='sigma'): + def interp_series(self,control,breakpoints,values,method='sigma'): # Error checking if not list_check(breakpoints) or len(breakpoints) == 1: @@ -792,15 +804,14 @@ def interp_timeseries(self,control,breakpoints,values,method='sigma'): else: # Finally interpolate if method == 'sigma': - self.ol_timeseries[control] = multi_sigma(self.ol_timeseries['time'],breakpoints,values) + self.ol_series[control] = multi_sigma(self.ol_series[self.breakpoint],breakpoints,values) elif method == 'linear': - interp_fcn = interpolate.interp1d(breakpoints,values,fill_value=values[-1],bounds_error=False) - self.ol_timeseries[control] = interp_fcn(self.ol_timeseries['time']) + self.ol_series[control] = np.interp(self.ol_series[self.breakpoint],breakpoints,values,left=values[0],right=values[-1]) elif method == 'cubic': - interp_fcn = interpolate.interp1d(breakpoints,values,kind='cubic',fill_value=values[-1],bounds_error=False) - self.ol_timeseries[control] = interp_fcn(self.ol_timeseries['time']) + interp_fcn = interpolate.Akima1DInterpolator(breakpoints,values,method='akima',extrapolate=True) #,kind='cubic',fill_value=values[-1],bounds_error=False) + self.ol_series[control] = interp_fcn(self.ol_series[self.breakpoint]) else: raise Exception(f'Open loop interpolation method {method} not supported') @@ -813,33 +824,36 @@ def sine_timeseries(self,control,amplitude,period): if period <= 0: raise Exception('Open loop sine input period is <= 0') + + if self.breakpoint != 'time': + raise Exception(f'Only time breakpoints are allowed for sine timeseries') if control not in self.allowed_controls: raise Exception(f'Open loop control of {control} is not allowed') else: - self.ol_timeseries[control] = amplitude * np.sin(2 * np.pi * self.ol_timeseries['time'] / period) + self.ol_series[control] = amplitude * np.sin(2 * np.pi * self.ol_series['time'] / period) if control == 'nacelle_yaw': self.compute_yaw_rate() def compute_yaw_rate(self): - self.ol_timeseries['nacelle_yaw_rate'] = np.concatenate(([0],np.diff(self.ol_timeseries['nacelle_yaw'])))/self.dt + self.ol_series['nacelle_yaw_rate'] = np.concatenate(([0],np.diff(self.ol_series['nacelle_yaw'])))/self.dt - def plot_timeseries(self): + def plot_series(self): ''' Debugging script for showing open loop timeseries ''' import matplotlib.pyplot as plt - fig, ax = plt.subplots(len(self.ol_timeseries)-1,1) + fig, ax = plt.subplots(len(self.ol_series)-1,1) i_ax = -1 - for ol_input in self.ol_timeseries: - if ol_input != 'time': + for ol_input in self.ol_series: + if ol_input not in ['time','wind_speed']: i_ax += 1 - if len(self.ol_timeseries)-1 == 1: - ax.plot(self.ol_timeseries['time'],self.ol_timeseries[ol_input]) + if len(self.ol_series)-1 == 1: + ax.plot(self.ol_series[self.breakpoint],self.ol_series[ol_input]) ax.set_ylabel(ol_input) else: - ax[i_ax].plot(self.ol_timeseries['time'],self.ol_timeseries[ol_input]) + ax[i_ax].plot(self.ol_series[self.breakpoint],self.ol_series[ol_input]) ax[i_ax].set_ylabel(ol_input) return fig, ax @@ -849,7 +863,7 @@ def write_input(self,ol_filename): Return open_loop dict for control params ''' - ol_timeseries = self.ol_timeseries + ol_series = self.ol_series # Init indices OL_Ind_Breakpoint = 1 @@ -860,25 +874,32 @@ def write_input(self,ol_filename): ol_index_counter = 0 # start input index at 2 - # Write time first, initialize OL matrix - if 'time' in ol_timeseries: - ol_control_array = ol_timeseries['time'] - Ind_Breakpoint = 1 + # Write breakpoint first, initialize OL matrix + if 'time' in ol_series: + ol_input_matrix = ol_series['time'] + elif 'wind_speed' in ol_series: + ol_input_matrix = ol_series['wind_speed'] else: - raise Exception('WARNING: no time index for open loop control. This is only index currently supported') + raise Exception('WARNING: no time or wind-speed index for open loop control. These are the only indices currently supported') + + if 'time' in ol_series and 'wind_speed' in ol_series: + raise Exception('WARNING: both time and wind_speed are in the OL input setup. Please check.') - for channel in ol_timeseries: + for channel in ol_series: # increment index counter first for 1-indexing in input file ol_index_counter += 1 - # skip writing for certain channels + # skip writing for certain channels, if already in ol_input_matrix skip_write = False # Set open loop index based on name if channel == 'time': OL_Ind_Breakpoint = ol_index_counter skip_write = True + elif channel == 'wind_speed': + OL_Ind_Breakpoint = ol_index_counter + skip_write = True elif channel == 'blade_pitch': # collective blade pitch OL_Ind_BldPitch = 3 * [ol_index_counter] elif channel == 'generator_torque': @@ -910,32 +931,32 @@ def write_input(self,ol_filename): # append open loop input array for non-ptfm channels if not skip_write: - ol_control_array = np.c_[ol_control_array,ol_timeseries[channel]] + ol_input_matrix = np.c_[ol_input_matrix,ol_series[channel]] ol_index_counter += 1 # Increment counter so it's 1 more than time, just like above in each iteration # Cable control - is_cable_chan = np.array(['cable_control' in ol_chan for ol_chan in ol_timeseries.keys()]) + is_cable_chan = np.array(['cable_control' in ol_chan for ol_chan in ol_series.keys()]) if any(is_cable_chan): # if any channels are cable_control_* n_cable_chan = np.sum(is_cable_chan) - cable_chan_names = np.array(list(ol_timeseries.keys()))[is_cable_chan] + cable_chan_names = np.array(list(ol_series.keys()))[is_cable_chan] # Let's assume they are 1-indexed and all there, otherwise a key error will be thrown for cable_chan in cable_chan_names: - ol_control_array = np.c_[ol_control_array,ol_timeseries[cable_chan]] + ol_input_matrix = np.c_[ol_input_matrix,ol_series[cable_chan]] OL_Ind_CableControl.append(ol_index_counter) ol_index_counter += 1 # Struct control - is_struct_chan = ['struct_control' in ol_chan for ol_chan in ol_timeseries.keys()] + is_struct_chan = ['struct_control' in ol_chan for ol_chan in ol_series.keys()] if any(is_struct_chan): # if any channels are struct_control_* n_struct_chan = np.sum(np.array(is_struct_chan)) # Let's assume they are 1-indexed and all there, otherwise a key error will be thrown for i_chan in range(1,n_struct_chan+1): - ol_control_array = np.c_[ol_control_array,ol_timeseries[f'struct_control_{i_chan}']] + ol_input_matrix = np.c_[ol_input_matrix,ol_series[f'struct_control_{i_chan}']] OL_Ind_StructControl.append(ol_index_counter) ol_index_counter += 1 @@ -948,11 +969,20 @@ def write_input(self,ol_filename): # Write header headers = [''] * ol_index_counter units = [''] * ol_index_counter - header_line = '!\tTime' - unit_line = '!\t(sec.)' - headers[0] = 'Time' - units[0] = 'sec.' + if self.breakpoint == 'time': + header_line = '!\tTime' # TODO: not sure if we need header_line and headers, check struct control + unit_line = '!\t(sec.)' + + headers[0] = 'Time' + units[0] = 'sec.' + elif self.breakpoint == 'wind_speed': + header_line = '!\tWindSpeed' # TODO: not sure if we need header_line and headers, check struct control + unit_line = '!\t(m/s)' + + headers[0] = 'WindSpeed' + units[0] = 'm/s' + if OL_Ind_GenTq: headers[OL_Ind_GenTq-1] = 'GenTq' @@ -1012,7 +1042,7 @@ def write_input(self,ol_filename): f.write(unit_line) # Write lines - for ol_line in ol_control_array: + for ol_line in ol_input_matrix: line = ''.join(['{:<10.8f}\t'.format(val) for val in ol_line]) + '\n' f.write(line) @@ -1029,6 +1059,11 @@ def write_input(self,ol_filename): open_loop['OL_Ind_R_Speed'] = OL_Ind_R_Speed open_loop['OL_Ind_R_Torque'] = OL_Ind_R_Torque open_loop['OL_Ind_R_Pitch'] = OL_Ind_R_Pitch + if self.breakpoint == 'time': + open_loop['OL_BP_Mode'] = 0 + elif self.breakpoint == 'wind_speed': + open_loop['OL_BP_Mode'] = 1 + return open_loop diff --git a/rosco/toolbox/inputs/toolbox_schema.yaml b/rosco/toolbox/inputs/toolbox_schema.yaml index 084b7f4a..ba74184b 100644 --- a/rosco/toolbox/inputs/toolbox_schema.yaml +++ b/rosco/toolbox/inputs/toolbox_schema.yaml @@ -492,6 +492,12 @@ properties: description: Filename of open loop input that ROSCO reads type: string default: unused + OL_BP_Mode: + description: Breakpoint mode for open loop control, 0 - indexed by time (default), 1 - indexed by wind speed + type: number + default: 0 + minimum: 0 + maximum: 1 Ind_Breakpoint: description: Index (column, 1-indexed) of breakpoint (time) in open loop index type: number @@ -1065,6 +1071,13 @@ properties: OL_Filename: type: string description: Input file with open loop timeseries (absolute path or relative to this file) + OL_BP_Mode: + description: Breakpoint mode for open loop control, 0 - indexed by time (default), 1 - indexed by wind speed + type: number + OL_BP_FiltFreq: + description: Natural frequency of 1st order filter on breakpoint for open loop control. 0 will skip filter. + type: number + default: 0 Ind_Breakpoint: type: number description: The column in OL_Filename that contains the breakpoint (time if OL_Mode > 0) diff --git a/rosco/toolbox/utilities.py b/rosco/toolbox/utilities.py index c62ee896..1ebc277e 100644 --- a/rosco/toolbox/utilities.py +++ b/rosco/toolbox/utilities.py @@ -253,6 +253,8 @@ def write_DISCON(turbine, controller, param_file='DISCON.IN', txt_filename='Cp_C file.write('\n') file.write('!------- Open Loop Control -----------------------------------------------------\n') file.write('"{}" ! OL_Filename - Input file with open loop timeseries (absolute path or relative to this file)\n'.format(rosco_vt['OL_Filename'])) + file.write('{:<12d} ! OL_BP_Mode - {}]\n'.format(int(rosco_vt['OL_BP_Mode']),input_descriptions['OL_BP_Mode'])) + file.write('{:<12f} ! OL_BP_FiltFreq - {}\n'.format(int(rosco_vt['OL_BP_FiltFreq']),input_descriptions['OL_BP_FiltFreq'])) file.write('{0:<12d} ! Ind_Breakpoint - The column in OL_Filename that contains the breakpoint (time if OL_Mode = 1)\n'.format(int(rosco_vt['Ind_Breakpoint']))) file.write('{} ! Ind_BldPitch - The columns in OL_Filename that contains the blade pitch (1,2,3) inputs in rad [array]\n'.format(' '.join([f'{int(ipb):3d}' for ipb in rosco_vt['Ind_BldPitch']]))) file.write('{0:<12d} ! Ind_GenTq - The column in OL_Filename that contains the generator torque in Nm\n'.format(int(rosco_vt['Ind_GenTq']))) @@ -613,6 +615,7 @@ def DISCON_dict(turbine, controller, txt_filename=None): DISCON_dict['Flp_MaxPit'] = controller.flp_maxpit # ------- Open Loop Control ------- DISCON_dict['OL_Filename'] = controller.OL_Filename + DISCON_dict['OL_BP_Mode'] = controller.OL_BP_Mode DISCON_dict['Ind_Breakpoint'] = controller.OL_Ind_Breakpoint DISCON_dict['Ind_BldPitch'] = controller.OL_Ind_BldPitch DISCON_dict['Ind_GenTq'] = controller.OL_Ind_GenTq From a2255a127844985f6cd0cc85e9a700b2e9eb5412 Mon Sep 17 00:00:00 2001 From: dzalkind Date: Fri, 12 Jul 2024 16:41:34 -0600 Subject: [PATCH 161/224] Add checks for power control --- rosco/controller/src/ReadSetParameters.f90 | 44 ++++++++++++++++++++-- 1 file changed, 40 insertions(+), 4 deletions(-) diff --git a/rosco/controller/src/ReadSetParameters.f90 b/rosco/controller/src/ReadSetParameters.f90 index a4bbfd0e..ef8bda94 100644 --- a/rosco/controller/src/ReadSetParameters.f90 +++ b/rosco/controller/src/ReadSetParameters.f90 @@ -1240,11 +1240,33 @@ SUBROUTINE CheckInputs(LocalVar, CntrPar, avrSWAP, ErrVar, size_avcMSG) IF (CntrPar%PRC_Mode > 0) THEN PRINT *, "Note: PRC Mode = ", CntrPar%PRC_Mode, ", which will affect VS_RefSpeed, VS_TSRopt, and PC_RefSpeed" - ! TODO: All PRC checks - ! ZMQ_Mode and PRC_Comm - ! OL_Mode and PRC_Comm - + IF (CntrPar%PRC_Comm == 0) THEN + IF (CntrPar%PRC_R_Pitch < 0) THEN + ErrVar%aviFAIL = -1 + ErrVar%ErrMsg = 'PRC_R_Pitch must be greater than or equal to zero.' + ENDIF + + IF (CntrPar%PRC_R_Speed < 0) THEN + ErrVar%aviFAIL = -1 + ErrVar%ErrMsg = 'PRC_R_Speed must be greater than or equal to zero.' + ENDIF + + IF (CntrPar%PRC_R_Torque < 0) THEN + ErrVar%aviFAIL = -1 + ErrVar%ErrMsg = 'PRC_R_Torque must be greater than or equal to zero.' + ENDIF + + ENDIF + + IF ((CntrPar%PRC_Comm == 1) .AND. (CntrPar%OL_Mode .NE. 1)) THEN + ErrVar%aviFAIL = -1 + ErrVar%ErrMsg = 'OL_Mode must be 1 to use open loop inputs for power control (PRC_Comm = 1).' + ENDIF + IF ((CntrPar%PRC_Comm == 2) .AND. (CntrPar%ZMQ_Mode .NE. 1)) THEN + ErrVar%aviFAIL = -1 + ErrVar%ErrMsg = 'ZMQ_Mode must be 1 to use ZeroMQ inputs for power control (PRC_Comm = 2).' + ENDIF ENDIF @@ -1425,6 +1447,20 @@ SUBROUTINE CheckInputs(LocalVar, CntrPar, avrSWAP, ErrVar, size_avcMSG) ErrVar%ErrMsg = 'CC_Mode must be 2 if using open loop struct control via Ind_StructControl' ENDIF + IF ((CntrPar%OL_BP_Mode < 0) .OR. (CntrPar%OL_BP_Mode > 1)) THEN + ErrVar%aviFAIL = -1 + ErrVar%ErrMsg = 'OL_BP_Mode must be 0 or 1.' + ENDIF + + IF (CntrPar%OL_BP_FiltFreq < 0) THEN + ErrVar%aviFAIL = -1 + ErrVar%ErrMsg = 'OL_BP_FiltFreq must be greater than or equal to 0.' + ENDIF + + IF ((CntrPar%OL_BP_Mode == 1) .AND. (CntrPar%OL_Mode == 2)) THEN + ErrVar%aviFAIL = -1 + ErrVar%ErrMsg = 'Rotor position control (OL_Mode = 2) is not compatible with wind speed breakpoints (OL_BP_Mode = 1)' + ENDIF ENDIF From 102286d97d4d93695fd45f89d4168b149b14fef2 Mon Sep 17 00:00:00 2001 From: David Stockhouse Date: Thu, 25 Jul 2024 01:14:24 -0600 Subject: [PATCH 162/224] Considerable cahnges to fixed-blade-pitch (FBP) operation for marine turbines. FBP modes changed so that any VS Region 2 mode can be paired with any FBP Region 3 mode, and the logic for controller switching has been restructured and (hopefully) made more readable. Still undergoing testing. --- Examples/29_marine_hydro_fbp.py | 50 ++++++---- Examples/Test_Cases/BAR_10/BAR_10_DISCON.IN | 6 +- .../DISCON-UMaineSemi.IN | 6 +- Examples/Test_Cases/MHK_RM1/MHK_RM1_DISCON.IN | 6 +- Examples/Test_Cases/NREL-5MW/DISCON.IN | 6 +- .../NREL_2p8_127/NREL-2p8-127_DISCON.IN | 6 +- Examples/Tune_Cases/RM1_MHK_FBP.yaml | 6 +- .../rosco_registry/rosco_types.yaml | 8 +- rosco/controller/src/Constants.f90 | 34 ++++++- rosco/controller/src/ControllerBlocks.f90 | 98 ++++++++++--------- rosco/controller/src/Controllers.f90 | 61 +++++++----- rosco/controller/src/ROSCO_IO.f90 | 2 +- rosco/controller/src/ROSCO_Types.f90 | 4 +- rosco/controller/src/ReadSetParameters.f90 | 26 +++-- rosco/toolbox/controller.py | 41 ++++---- rosco/toolbox/inputs/toolbox_schema.yaml | 22 +++-- rosco/toolbox/utilities.py | 12 +-- 17 files changed, 231 insertions(+), 163 deletions(-) diff --git a/Examples/29_marine_hydro_fbp.py b/Examples/29_marine_hydro_fbp.py index 62bb46cb..67a8475e 100644 --- a/Examples/29_marine_hydro_fbp.py +++ b/Examples/29_marine_hydro_fbp.py @@ -60,7 +60,7 @@ def main(): ### Tune controller cases # Constant power underspeed (should be the default) controller_params_1 = controller_params.copy() - controller_params_1['VS_FBP_ref_mode'] = 0 # Switch to WSE reference + controller_params_1['VS_FBP'] = 3 # Power reference controller_params_1['VS_FBP_speed_mode'] = 0 controller_params_1['VS_FBP_P'] = [1.0, 1.0] controller_1 = ROSCO_controller.Controller(controller_params_1) @@ -68,7 +68,7 @@ def main(): # Constant power overspeed controller_params_2 = controller_params.copy() - controller_params_2['VS_FBP_ref_mode'] = 0 # Switch to WSE reference + controller_params_2['VS_FBP'] = 2 # Switch to WSE reference controller_params_2['VS_FBP_speed_mode'] = 1 controller_params_2['VS_FBP_P'] = [1.0, 1.0] controller_2 = ROSCO_controller.Controller(controller_params_2) @@ -90,31 +90,41 @@ def main(): # Generic numeric function controller_params_5 = controller_params.copy() - controller_params_5['VS_FBP_ref_mode'] = 0 # Switch to WSE reference + controller_params_5['VS_FBP'] = 2 # WSE reference controller_params_5['VS_FBP_U'] = [2.0, 2.2, 2.4, 2.6, 2.8, 3.0, 3.2, 3.4, 3.6, 3.8, 4.0] controller_params_5['VS_FBP_P'] = [1.0, 1.3, 1.6, 1.8, 1.9, 2.0, 1.9, 1.8, 1.7, 1.6, 1.5] controller_5 = ROSCO_controller.Controller(controller_params_5) controller_5.tune_controller(turbine) + # Constant power overspeed, nonlinear lookup table control + controller_params_6 = controller_params.copy() + controller_params_6['VS_FBP'] = 0 # Constant power overspeed + controller_params_6['VS_FBP_speed_mode'] = 1 + controller_params_6['VS_FBP_P'] = [1.0, 1.0] + controller_params_6['VS_ControlMode'] = 1 + controller_6 = ROSCO_controller.Controller(controller_params_6) + controller_6.tune_controller(turbine) + + plot_labels = ['Constant Power Underspeed', 'Constant Power Overspeed', 'Linear Increasing Power', 'Increasing Leveled Power', 'Generic User-Defined'] fig, axs = plt.subplots(3,1) - axs[0].plot(controller_1.v, controller_1.power_op, label='Constant Power Underspeed') - axs[0].plot(controller_2.v, controller_2.power_op, linestyle='--', label='Constant Power Overspeed') - axs[0].plot(controller_3.v, controller_3.power_op, label='Linear Increasing Power') - axs[0].plot(controller_4.v, controller_4.power_op, label='Increasing Leveled Power') - axs[0].plot(controller_5.v, controller_5.power_op, label='Generic') + axs[0].plot(controller_1.v, controller_1.power_op, label=plot_labels[0]) + axs[0].plot(controller_2.v, controller_2.power_op, label=plot_labels[1], linestyle='--') + axs[0].plot(controller_3.v, controller_3.power_op, label=plot_labels[2]) + axs[0].plot(controller_4.v, controller_4.power_op, label=plot_labels[3]) + axs[0].plot(controller_5.v, controller_5.power_op, label=plot_labels[4]) axs[0].set_ylabel('Gen Power [W]') - axs[1].plot(controller_1.v, controller_1.omega_gen_op, label='Constant Power Underspeed') - axs[1].plot(controller_2.v, controller_2.omega_gen_op, linestyle='--', label='Constant Power Overspeed') - axs[1].plot(controller_3.v, controller_3.omega_gen_op, label='Linear Increasing Power') - axs[1].plot(controller_4.v, controller_4.omega_gen_op, label='Increasing Leveled Power') - axs[1].plot(controller_5.v, controller_5.omega_gen_op, label='Generic') + axs[1].plot(controller_1.v, controller_1.omega_gen_op, label=plot_labels[0]) + axs[1].plot(controller_2.v, controller_2.omega_gen_op, label=plot_labels[1], linestyle='--') + axs[1].plot(controller_3.v, controller_3.omega_gen_op, label=plot_labels[2]) + axs[1].plot(controller_4.v, controller_4.omega_gen_op, label=plot_labels[3]) + axs[1].plot(controller_5.v, controller_5.omega_gen_op, label=plot_labels[4]) axs[1].set_ylabel('Gen Speed [rad/s]') - axs[2].plot(controller_1.v, controller_1.tau_op, label='Constant Power Underspeed') - axs[2].plot(controller_2.v, controller_2.tau_op, linestyle='--', label='Constant Power Overspeed') - axs[2].plot(controller_3.v, controller_3.tau_op, label='Linear Increasing Power') - axs[2].plot(controller_4.v, controller_4.tau_op, label='Increasing Leveled Power') - axs[2].plot(controller_5.v, controller_5.tau_op, label='Generic') + axs[2].plot(controller_1.v, controller_1.tau_op, label=plot_labels[0]) + axs[2].plot(controller_2.v, controller_2.tau_op, label=plot_labels[1], linestyle='--') + axs[2].plot(controller_3.v, controller_3.tau_op, label=plot_labels[2]) + axs[2].plot(controller_4.v, controller_4.tau_op, label=plot_labels[3]) + axs[2].plot(controller_5.v, controller_5.tau_op, label=plot_labels[4]) axs[2].set_ylabel('Gen Torque [N m]') axs[2].set_xlabel('Flow Speed [m/s]') axs[0].legend(loc='upper left') @@ -129,7 +139,7 @@ def main(): # Write parameter input file for constant power underspeed controller param_file = os.path.join(run_dir,'DISCON.IN') write_DISCON(turbine, - controller_2, + controller_1, param_file=param_file, txt_filename=cp_filename ) @@ -147,7 +157,7 @@ def main(): } r.case_inputs = {} # r.fst_vt = reader.fst_vt - r.controller_params = controller_params_2 + r.controller_params = controller_params_1 r.save_dir = run_dir r.rosco_dir = rosco_dir diff --git a/Examples/Test_Cases/BAR_10/BAR_10_DISCON.IN b/Examples/Test_Cases/BAR_10/BAR_10_DISCON.IN index 7de75abf..d766e497 100644 --- a/Examples/Test_Cases/BAR_10/BAR_10_DISCON.IN +++ b/Examples/Test_Cases/BAR_10/BAR_10_DISCON.IN @@ -1,5 +1,5 @@ ! Controller parameter input file for the BAR_10 wind turbine -! - File written using ROSCO version 2.9.0 controller tuning logic on 05/13/24 +! - File written using ROSCO version 2.9.0 controller tuning logic on 07/24/24 !------- SIMULATION CONTROL ------------------------------------------------------------ 1 ! LoggingLevel - {0: write no debug files, 1: write standard output .dbg-file, 2: LoggingLevel 1 + ROSCO LocalVars (.dbg2) 3: LoggingLevel 2 + complete avrSWAP-array (.dbg3)} @@ -12,6 +12,7 @@ 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- no torque control, 1- k*omega^2 with PI transitions, 2- WSE TSR Tracking, 3- Power-based TSR Tracking)} 0 ! VS_ConstPower - Do constant power torque control, where above rated torque varies, 0 for constant torque} +0 ! VS_FBP - Fixed blade pitch configuration mode 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} @@ -82,7 +83,7 @@ 70282.09458000 ! VS_MaxTq - Maximum generator torque in Region 3 (HSS side), [Nm]. 0.000000000000 ! VS_MinTq - Minimum generator torque (HSS side), [Nm]. 27.49717000000 ! VS_MinOMSpd - Minimum generator speed [rad/s] -12.03868000000 ! VS_Rgn2K - Generator torque constant in Region 2 (HSS side). Only used in VS_ControlMode = 1,3 +12.03868000000 ! VS_Rgn2K - Generator torque constant in Region 2 (HSS side). Only used in VS_ControlMode = 1,3,4 5000000.000000 ! VS_RtPwr - Wind turbine rated power [W] 63892.81326000 ! VS_RtTq - Rated torque, [Nm]. 75.83317000000 ! VS_RefSpd - Rated generator speed [rad/s] @@ -92,7 +93,6 @@ 9.76 ! VS_TSRopt - Power-maximizing region 2 tip-speed-ratio. Only used in VS_ControlMode = 2. !------- FIXED PITCH REGION 3 TORQUE CONTROL ------------------------------------------------ -0 ! VS_FBP_RefMode - Reference control mode (0 - Use wind speed estimator, 1 - Use torque feedback) 60 ! VS_FBP_n - Number of gain-scheduling table entries 3.000000 3.181847 3.363694 3.545541 3.727388 3.909234 4.091081 4.272928 4.454775 4.636622 4.818469 5.000316 5.182163 5.364010 5.545857 5.727703 5.909550 6.091397 6.273244 6.455091 6.636938 6.818785 7.000632 7.182479 7.364326 7.546172 7.728019 7.909866 8.091713 8.273560 8.831108 9.388656 9.946204 10.503752 11.061300 11.618848 12.176396 12.733944 13.291492 13.849040 14.406588 14.964136 15.521684 16.079232 16.636780 17.194328 17.751876 18.309424 18.866972 19.424520 19.982068 20.539616 21.097164 21.654712 22.212260 22.769808 23.327356 23.884904 24.442452 25.000000 ! VS_FBP_U - Operating schedule table: Wind speeds [m/s]. 27.497174 29.163932 30.830691 32.497450 34.164208 35.830967 37.497725 39.164484 40.831243 42.498001 44.164760 45.831518 47.498277 49.165035 50.831794 52.498553 54.165311 55.832070 57.498828 59.165587 60.832346 62.499104 64.165863 65.832621 67.499380 69.166138 70.832897 72.499656 74.166414 79.853125 79.853125 79.853125 79.853125 79.853125 79.853125 79.853125 79.853125 79.853125 79.853125 79.853125 79.853125 79.853125 79.853125 79.853125 79.853125 79.853125 79.853125 79.853125 79.853125 79.853125 79.853125 79.853125 79.853125 79.853125 79.853125 79.853125 79.853125 79.853125 79.853125 79.853125 ! VS_FBP_Omega - Operating schedule table: Generator speeds [rad/s]. diff --git a/Examples/Test_Cases/IEA-15-240-RWT-UMaineSemi/DISCON-UMaineSemi.IN b/Examples/Test_Cases/IEA-15-240-RWT-UMaineSemi/DISCON-UMaineSemi.IN index 546191da..bde8064f 100644 --- a/Examples/Test_Cases/IEA-15-240-RWT-UMaineSemi/DISCON-UMaineSemi.IN +++ b/Examples/Test_Cases/IEA-15-240-RWT-UMaineSemi/DISCON-UMaineSemi.IN @@ -1,5 +1,5 @@ ! Controller parameter input file for the IEA-15-240-RWT-UMaineSemi wind turbine -! - File written using ROSCO version 2.9.0 controller tuning logic on 05/13/24 +! - File written using ROSCO version 2.9.0 controller tuning logic on 07/24/24 !------- SIMULATION CONTROL ------------------------------------------------------------ 2 ! LoggingLevel - {0: write no debug files, 1: write standard output .dbg-file, 2: LoggingLevel 1 + ROSCO LocalVars (.dbg2) 3: LoggingLevel 2 + complete avrSWAP-array (.dbg3)} @@ -12,6 +12,7 @@ 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- no torque control, 1- k*omega^2 with PI transitions, 2- WSE TSR Tracking, 3- Power-based TSR Tracking)} 0 ! VS_ConstPower - Do constant power torque control, where above rated torque varies, 0 for constant torque} +0 ! VS_FBP - Fixed blade pitch configuration mode 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} @@ -82,7 +83,7 @@ 21586451.33303 ! VS_MaxTq - Maximum generator torque in Region 3 (HSS side), [Nm]. 0.000000000000 ! VS_MinTq - Minimum generator torque (HSS side), [Nm]. 0.523600000000 ! VS_MinOMSpd - Minimum generator speed [rad/s] -32514899.86953 ! VS_Rgn2K - Generator torque constant in Region 2 (HSS side). Only used in VS_ControlMode = 1,3 +32514899.86953 ! VS_Rgn2K - Generator torque constant in Region 2 (HSS side). Only used in VS_ControlMode = 1,3,4 15000000.00000 ! VS_RtPwr - Wind turbine rated power [W] 19624046.66639 ! VS_RtTq - Rated torque, [Nm]. 0.791680000000 ! VS_RefSpd - Rated generator speed [rad/s] @@ -92,7 +93,6 @@ 9.00 ! VS_TSRopt - Power-maximizing region 2 tip-speed-ratio. Only used in VS_ControlMode = 2. !------- FIXED PITCH REGION 3 TORQUE CONTROL ------------------------------------------------ -0 ! VS_FBP_RefMode - Reference control mode (0 - Use wind speed estimator, 1 - Use torque feedback) 60 ! VS_FBP_n - Number of gain-scheduling table entries 3.000000 3.266897 3.533793 3.800690 4.067586 4.334483 4.601379 4.868276 5.135172 5.402069 5.668966 5.935862 6.202759 6.469655 6.736552 7.003448 7.270345 7.537241 7.804138 8.071034 8.337931 8.604828 8.871724 9.138621 9.405517 9.672414 9.939310 10.206207 10.473103 10.740000 11.215333 11.690667 12.166000 12.641333 13.116667 13.592000 14.067333 14.542667 15.018000 15.493333 15.968667 16.444000 16.919333 17.394667 17.870000 18.345333 18.820667 19.296000 19.771333 20.246667 20.722000 21.197333 21.672667 22.148000 22.623333 23.098667 23.574000 24.049333 24.524667 25.000000 ! VS_FBP_U - Operating schedule table: Wind speeds [m/s]. 0.523599 0.523599 0.523599 0.523599 0.523599 0.523599 0.523599 0.523599 0.523599 0.523599 0.523599 0.523599 0.523599 0.523599 0.523599 0.525259 0.545276 0.565293 0.585310 0.605328 0.625345 0.645362 0.665379 0.685397 0.705414 0.725431 0.745448 0.765466 0.785483 0.791681 0.791681 0.791681 0.791681 0.791681 0.791681 0.791681 0.791681 0.791681 0.791681 0.791681 0.791681 0.791681 0.791681 0.791681 0.791681 0.791681 0.791681 0.791681 0.791681 0.791681 0.791681 0.791681 0.791681 0.791681 0.791681 0.791681 0.791681 0.791681 0.791681 0.791681 ! VS_FBP_Omega - Operating schedule table: Generator speeds [rad/s]. diff --git a/Examples/Test_Cases/MHK_RM1/MHK_RM1_DISCON.IN b/Examples/Test_Cases/MHK_RM1/MHK_RM1_DISCON.IN index 5f0e722f..09e915ea 100644 --- a/Examples/Test_Cases/MHK_RM1/MHK_RM1_DISCON.IN +++ b/Examples/Test_Cases/MHK_RM1/MHK_RM1_DISCON.IN @@ -1,5 +1,5 @@ ! Controller parameter input file for the MHK_RM1_Floating wind turbine -! - File written using ROSCO version 2.9.0 controller tuning logic on 05/13/24 +! - File written using ROSCO version 2.9.0 controller tuning logic on 07/24/24 !------- SIMULATION CONTROL ------------------------------------------------------------ 2 ! LoggingLevel - {0: write no debug files, 1: write standard output .dbg-file, 2: LoggingLevel 1 + ROSCO LocalVars (.dbg2) 3: LoggingLevel 2 + complete avrSWAP-array (.dbg3)} @@ -12,6 +12,7 @@ 0 ! IPC_ControlMode - Turn Individual Pitch Control (IPC) for fatigue load reductions (pitch contribution) {0: off, 1: 1P reductions, 2: 1P+2P reductions} 3 ! VS_ControlMode - Generator torque control mode in above rated conditions (0- no torque control, 1- k*omega^2 with PI transitions, 2- WSE TSR Tracking, 3- Power-based TSR Tracking)} 1 ! VS_ConstPower - Do constant power torque control, where above rated torque varies, 0 for constant torque} +0 ! VS_FBP - Fixed blade pitch configuration mode 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} @@ -82,7 +83,7 @@ 12450.50344000 ! VS_MaxTq - Maximum generator torque in Region 3 (HSS side), [Nm]. 0.000000000000 ! VS_MinTq - Minimum generator torque (HSS side), [Nm]. 19.00787000000 ! VS_MinOMSpd - Minimum generator speed [rad/s] -1.310360000000 ! VS_Rgn2K - Generator torque constant in Region 2 (HSS side). Only used in VS_ControlMode = 1,3 +1.310360000000 ! VS_Rgn2K - Generator torque constant in Region 2 (HSS side). Only used in VS_ControlMode = 1,3,4 500000.0000000 ! VS_RtPwr - Wind turbine rated power [W] 8300.335630000 ! VS_RtTq - Rated torque, [Nm]. 63.81200000000 ! VS_RefSpd - Rated generator speed [rad/s] @@ -92,7 +93,6 @@ 7.17 ! VS_TSRopt - Power-maximizing region 2 tip-speed-ratio. Only used in VS_ControlMode = 2. !------- FIXED PITCH REGION 3 TORQUE CONTROL ------------------------------------------------ -0 ! VS_FBP_RefMode - Reference control mode (0 - Use wind speed estimator, 1 - Use torque feedback) 60 ! VS_FBP_n - Number of gain-scheduling table entries 0.500000 0.551724 0.603448 0.655172 0.706897 0.758621 0.810345 0.862069 0.913793 0.965517 1.017241 1.068966 1.120690 1.172414 1.224138 1.275862 1.327586 1.379310 1.431034 1.482759 1.534483 1.586207 1.637931 1.689655 1.741379 1.793103 1.844828 1.896552 1.948276 2.000000 2.033333 2.066667 2.100000 2.133333 2.166667 2.200000 2.233333 2.266667 2.300000 2.333333 2.366667 2.400000 2.433333 2.466667 2.500000 2.533333 2.566667 2.600000 2.633333 2.666667 2.700000 2.733333 2.766667 2.800000 2.833333 2.866667 2.900000 2.933333 2.966667 3.000000 ! VS_FBP_U - Operating schedule table: Wind speeds [m/s]. 19.007868 20.974199 22.940530 24.906861 26.873192 28.839524 30.805855 32.772186 34.738517 36.704848 38.671179 40.637511 42.603842 44.570173 46.536504 48.502835 50.469166 52.435498 54.401829 56.368160 58.334491 60.300822 62.267153 63.812000 63.812000 63.812000 63.812000 63.812000 63.812000 63.812000 63.812000 63.812000 63.812000 63.812000 63.812000 63.812000 63.812000 63.812000 63.812000 63.812000 63.812000 63.812000 63.812000 63.812000 63.812000 63.812000 63.812000 63.812000 63.812000 63.812000 63.812000 63.812000 63.812000 63.812000 63.812000 63.812000 63.812000 63.812000 63.812000 63.812000 ! VS_FBP_Omega - Operating schedule table: Generator speeds [rad/s]. diff --git a/Examples/Test_Cases/NREL-5MW/DISCON.IN b/Examples/Test_Cases/NREL-5MW/DISCON.IN index f49dafb4..0e8ec064 100644 --- a/Examples/Test_Cases/NREL-5MW/DISCON.IN +++ b/Examples/Test_Cases/NREL-5MW/DISCON.IN @@ -1,5 +1,5 @@ ! Controller parameter input file for the NREL-5MW wind turbine -! - File written using ROSCO version 2.9.0 controller tuning logic on 05/13/24 +! - File written using ROSCO version 2.9.0 controller tuning logic on 07/24/24 !------- SIMULATION CONTROL ------------------------------------------------------------ 1 ! LoggingLevel - {0: write no debug files, 1: write standard output .dbg-file, 2: LoggingLevel 1 + ROSCO LocalVars (.dbg2) 3: LoggingLevel 2 + complete avrSWAP-array (.dbg3)} @@ -12,6 +12,7 @@ 0 ! IPC_ControlMode - Turn Individual Pitch Control (IPC) for fatigue load reductions (pitch contribution) {0: off, 1: 1P reductions, 2: 1P+2P reductions} 3 ! VS_ControlMode - Generator torque control mode in above rated conditions (0- no torque control, 1- k*omega^2 with PI transitions, 2- WSE TSR Tracking, 3- Power-based TSR Tracking)} 0 ! VS_ConstPower - Do constant power torque control, where above rated torque varies, 0 for constant torque} +0 ! VS_FBP - Fixed blade pitch configuration mode 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} @@ -82,7 +83,7 @@ 47402.87063000 ! VS_MaxTq - Maximum generator torque in Region 3 (HSS side), [Nm]. 0.000000000000 ! VS_MinTq - Minimum generator torque (HSS side), [Nm]. 35.29006000000 ! VS_MinOMSpd - Minimum generator speed [rad/s] -2.185750000000 ! VS_Rgn2K - Generator torque constant in Region 2 (HSS side). Only used in VS_ControlMode = 1,3 +2.185750000000 ! VS_Rgn2K - Generator torque constant in Region 2 (HSS side). Only used in VS_ControlMode = 1,3,4 5000000.000000 ! VS_RtPwr - Wind turbine rated power [W] 43093.51876000 ! VS_RtTq - Rated torque, [Nm]. 122.9096700000 ! VS_RefSpd - Rated generator speed [rad/s] @@ -92,7 +93,6 @@ 7.64 ! VS_TSRopt - Power-maximizing region 2 tip-speed-ratio. Only used in VS_ControlMode = 2. !------- FIXED PITCH REGION 3 TORQUE CONTROL ------------------------------------------------ -0 ! VS_FBP_RefMode - Reference control mode (0 - Use wind speed estimator, 1 - Use torque feedback) 60 ! VS_FBP_n - Number of gain-scheduling table entries 3.000000 3.289655 3.579310 3.868966 4.158621 4.448276 4.737931 5.027586 5.317241 5.606897 5.896552 6.186207 6.475862 6.765517 7.055172 7.344828 7.634483 7.924138 8.213793 8.503448 8.793103 9.082759 9.372414 9.662069 9.951724 10.241379 10.531034 10.820690 11.110345 11.400000 11.853333 12.306667 12.760000 13.213333 13.666667 14.120000 14.573333 15.026667 15.480000 15.933333 16.386667 16.840000 17.293333 17.746667 18.200000 18.653333 19.106667 19.560000 20.013333 20.466667 20.920000 21.373333 21.826667 22.280000 22.733333 23.186667 23.640000 24.093333 24.546667 25.000000 ! VS_FBP_U - Operating schedule table: Wind speeds [m/s]. 35.290063 38.697380 42.104696 45.512012 48.919329 52.326645 55.733962 59.141278 62.548595 65.955911 69.363228 72.770544 76.177860 79.585177 82.992493 86.399810 89.807126 93.214443 96.621759 100.029076 103.436392 106.843708 110.251025 113.658341 117.065658 120.472974 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 ! VS_FBP_Omega - Operating schedule table: Generator speeds [rad/s]. diff --git a/Examples/Test_Cases/NREL_2p8_127/NREL-2p8-127_DISCON.IN b/Examples/Test_Cases/NREL_2p8_127/NREL-2p8-127_DISCON.IN index 663e4334..76038f25 100644 --- a/Examples/Test_Cases/NREL_2p8_127/NREL-2p8-127_DISCON.IN +++ b/Examples/Test_Cases/NREL_2p8_127/NREL-2p8-127_DISCON.IN @@ -1,5 +1,5 @@ ! Controller parameter input file for the NREL-2p8-127 wind turbine -! - File written using ROSCO version 2.9.0 controller tuning logic on 05/13/24 +! - File written using ROSCO version 2.9.0 controller tuning logic on 07/24/24 !------- SIMULATION CONTROL ------------------------------------------------------------ 2 ! LoggingLevel - {0: write no debug files, 1: write standard output .dbg-file, 2: LoggingLevel 1 + ROSCO LocalVars (.dbg2) 3: LoggingLevel 2 + complete avrSWAP-array (.dbg3)} @@ -12,6 +12,7 @@ 1 ! IPC_ControlMode - Turn Individual Pitch Control (IPC) for fatigue load reductions (pitch contribution) {0: off, 1: 1P reductions, 2: 1P+2P reductions} 3 ! VS_ControlMode - Generator torque control mode in above rated conditions (0- no torque control, 1- k*omega^2 with PI transitions, 2- WSE TSR Tracking, 3- Power-based TSR Tracking)} 0 ! VS_ConstPower - Do constant power torque control, where above rated torque varies, 0 for constant torque} +0 ! VS_FBP - Fixed blade pitch configuration mode 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} @@ -82,7 +83,7 @@ 26673.40024000 ! VS_MaxTq - Maximum generator torque in Region 3 (HSS side), [Nm]. 0.000000000000 ! VS_MinTq - Minimum generator torque (HSS side), [Nm]. 37.81562000000 ! VS_MinOMSpd - Minimum generator speed [rad/s] -1.844270000000 ! VS_Rgn2K - Generator torque constant in Region 2 (HSS side). Only used in VS_ControlMode = 1,3 +1.844270000000 ! VS_Rgn2K - Generator torque constant in Region 2 (HSS side). Only used in VS_ControlMode = 1,3,4 2800000.000000 ! VS_RtPwr - Wind turbine rated power [W] 24248.54567000 ! VS_RtTq - Rated torque, [Nm]. 122.9096700000 ! VS_RefSpd - Rated generator speed [rad/s] @@ -92,7 +93,6 @@ 8.25 ! VS_TSRopt - Power-maximizing region 2 tip-speed-ratio. Only used in VS_ControlMode = 2. !------- FIXED PITCH REGION 3 TORQUE CONTROL ------------------------------------------------ -0 ! VS_FBP_RefMode - Reference control mode (0 - Use wind speed estimator, 1 - Use torque feedback) 60 ! VS_FBP_n - Number of gain-scheduling table entries 3.000000 3.289655 3.579310 3.868966 4.158621 4.448276 4.737931 5.027586 5.317241 5.606897 5.896552 6.186207 6.475862 6.765517 7.055172 7.344828 7.634483 7.924138 8.213793 8.503448 8.793103 9.082759 9.372414 9.662069 9.951724 10.241379 10.531034 10.820690 11.110345 11.400000 11.853333 12.306667 12.760000 13.213333 13.666667 14.120000 14.573333 15.026667 15.480000 15.933333 16.386667 16.840000 17.293333 17.746667 18.200000 18.653333 19.106667 19.560000 20.013333 20.466667 20.920000 21.373333 21.826667 22.280000 22.733333 23.186667 23.640000 24.093333 24.546667 25.000000 ! VS_FBP_U - Operating schedule table: Wind speeds [m/s]. 37.815619 41.466782 45.117946 48.769109 52.420272 56.071435 59.722599 63.373762 67.024925 70.676088 74.327252 77.978415 81.629578 85.280741 88.931905 92.583068 96.234231 99.885394 103.536557 107.187721 110.838884 114.490047 118.141210 121.792374 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 ! VS_FBP_Omega - Operating schedule table: Generator speeds [rad/s]. diff --git a/Examples/Tune_Cases/RM1_MHK_FBP.yaml b/Examples/Tune_Cases/RM1_MHK_FBP.yaml index a3862f77..9ac1d933 100644 --- a/Examples/Tune_Cases/RM1_MHK_FBP.yaml +++ b/Examples/Tune_Cases/RM1_MHK_FBP.yaml @@ -30,8 +30,8 @@ controller_params: F_LPFType: 1 # {1: first-order low-pass filter, 2: second-order low-pass filter}, [rad/s] (currently filters generator speed and pitch control signals) F_NotchType: 1 # Notch filter on generator speed and/or tower fore-aft motion (for floating) {0: disable, 1: generator speed, 2: tower-top fore-aft motion, 3: generator speed and tower-top fore-aft motion} IPC_ControlMode: 0 # Turn Individual Pitch Control (IPC) for fatigue load reductions (pitch contribution) {0: off, 1: 1P reductions, 2: 1P+2P reductions} - VS_ControlMode: 4 # Generator torque control mode in above rated conditions {0: constant torque, 1: constant power, 2: TSR tracking PI control} - VS_ConstPower: 0 # Generator torque control mode in above rated conditions {0: constant torque, 1: constant power, 2: TSR tracking PI control} + VS_ControlMode: 2 # Generator torque control mode in below rated conditions {0: torque control disabled, 1: K*Omega^2, 2: WSE TSR-tracking PI control, 3: power TSR-tracking PI control, 4: Torque TSR-tracking PI control} + VS_ConstPower: 0 # Generator torque control mode in above rated conditions with variable blade pitch {0: constant torque, 1: constant power} PC_ControlMode: 0 # Blade pitch control mode {0: No pitch, fix to fine pitch, 1: active PI blade pitch control} Y_ControlMode: 0 # Yaw control mode {0: no yaw control, 1: yaw rate control, 2: yaw-by-IPC} SS_Mode: 1 # Setpoint Smoother mode {0: no setpoint smoothing, 1: introduce setpoint smoothing} @@ -55,7 +55,7 @@ controller_params: sd_maxpit: 0.4363 # Maximum blade pitch angle to initiate shutdown [rad], {default = bld pitch at v_max} Kp_float: -0.3897 max_torque_factor: 5 - VS_FBP_ref_mode: 1 + VS_FBP: 3 VS_FBP_power_mode: 0 VS_FBP_speed_mode: 0 VS_FBP_U: [2.0, 4.0] diff --git a/rosco/controller/rosco_registry/rosco_types.yaml b/rosco/controller/rosco_registry/rosco_types.yaml index d8c488ea..71871bfc 100644 --- a/rosco/controller/rosco_registry/rosco_types.yaml +++ b/rosco/controller/rosco_registry/rosco_types.yaml @@ -270,10 +270,13 @@ ControlParameters: # Generator Torque Controller VS_ControlMode: <<: *integer - description: Generator torque control mode in below rated conditions {0 - no torque control, 1 - komega^2 with PI trans, 2 - WSE TSR Tracking, 3 - Power TSR Tracking, 4 - Fixed pitch, generic operating schedule for torque controller in Regions 2 and 3} + description: Generator torque control mode in below rated conditions {0 - no torque control, 1 - komega^2 with PI trans, 2 - WSE TSR Tracking, 3 - Power TSR Tracking, 4 - Torque TSR Tracking} VS_ConstPower: <<: *integer description: Constant power torque control + VS_FBP: + <<: *integer + description: Fixed blade pitch control mode in above rated conditions {0 - variable pitch (defer to PC_ControlMode and VS_ConstPower), 1 - P/omega overspeed control law, 2 - PI reference tracking based on WSE lookup table, 3 - PI reference tracking based on torque lookup table (must have VS_FBP_Tau be a monotonic function)} VS_GenEff: <<: *real description: Generator efficiency mechanical power -> electrical power [-] @@ -318,9 +321,6 @@ ControlParameters: VS_TSRopt: <<: *real description: Power-maximizing region 2 tip-speed ratio [rad] - VS_FBP_RefMode: - <<: *integer - description: Reference interpolation control mode for fixed blade pitch in above rated conditions {0 - no torque control, 1 - komega^2 with PI trans, 2 - WSE TSR Tracking, 3 - Power TSR Tracking} VS_FBP_n: <<: *integer description: Number of operating schedule entries for fixed blade pitch control diff --git a/rosco/controller/src/Constants.f90 b/rosco/controller/src/Constants.f90 index 2f9b7258..243ced9c 100644 --- a/rosco/controller/src/Constants.f90 +++ b/rosco/controller/src/Constants.f90 @@ -40,10 +40,34 @@ MODULE Constants ! Control Modes ! VS_ControlMode - INTEGER(IntKi), PARAMETER :: VS_Mode_Disabled = 0 - INTEGER(IntKi), PARAMETER :: VS_Mode_KOmega = 1 - INTEGER(IntKi), PARAMETER :: VS_Mode_WSE_TSR = 2 - INTEGER(IntKi), PARAMETER :: VS_Mode_Power_TSR = 3 - INTEGER(IntKi), PARAMETER :: VS_Mode_FBP = 4 + INTEGER(IntKi), PARAMETER :: VS_Mode_Disabled = 0 + INTEGER(IntKi), PARAMETER :: VS_Mode_KOmega = 1 + INTEGER(IntKi), PARAMETER :: VS_Mode_WSE_TSR = 2 + INTEGER(IntKi), PARAMETER :: VS_Mode_Power_TSR = 3 + INTEGER(IntKi), PARAMETER :: VS_Mode_Torque_TSR = 4 + + ! VS_ConstPower + INTEGER(IntKi), PARAMETER :: VS_Mode_ConstTrq = 0 + INTEGER(IntKi), PARAMETER :: VS_Mode_ConstPwr = 1 + + ! VS_FBP + INTEGER(IntKi), PARAMETER :: VS_FBP_Variable_Pitch = 0 + INTEGER(IntKi), PARAMETER :: VS_FBP_Power_Overspeed = 1 + INTEGER(IntKi), PARAMETER :: VS_FBP_WSE_Ref = 2 + INTEGER(IntKi), PARAMETER :: VS_FBP_Torque_Ref = 3 + + ! VS_State + INTEGER(IntKi), PARAMETER :: VS_State_Error = 0 + INTEGER(IntKi), PARAMETER :: VS_State_Region_1_5 = 1 + INTEGER(IntKi), PARAMETER :: VS_State_Region_2 = 2 + INTEGER(IntKi), PARAMETER :: VS_State_Region_2_5 = 3 + INTEGER(IntKi), PARAMETER :: VS_State_Region_3_ConstTrq = 4 + INTEGER(IntKi), PARAMETER :: VS_State_Region_3_ConstPwr = 5 + INTEGER(IntKi), PARAMETER :: VS_State_Region_3_FBP = 6 + INTEGER(IntKi), PARAMETER :: VS_State_PI = 7 + + ! PC_State + INTEGER(IntKi), PARAMETER :: PC_State_Disabled = 0 + INTEGER(IntKi), PARAMETER :: PC_State_Enabled = 1 END MODULE Constants diff --git a/rosco/controller/src/ControllerBlocks.f90 b/rosco/controller/src/ControllerBlocks.f90 index 02e61923..9c7eac85 100644 --- a/rosco/controller/src/ControllerBlocks.f90 +++ b/rosco/controller/src/ControllerBlocks.f90 @@ -35,7 +35,7 @@ SUBROUTINE ComputeVariablesSetpoints(CntrPar, LocalVar, objInst, DebugVar, ErrVa TYPE(ErrorVariables), INTENT(INOUT) :: ErrVar ! ----- Pitch controller speed and power error ----- - + ! Power reference tracking generator speed IF (CntrPar%PRC_Mode == 1) THEN LocalVar%PRC_WSE_F = LPFilter(LocalVar%WE_Vw, LocalVar%DT,CntrPar%PRC_LPF_Freq, LocalVar%FP, LocalVar%iStatus, LocalVar%restart, objInst%instLPF) @@ -43,7 +43,7 @@ SUBROUTINE ComputeVariablesSetpoints(CntrPar, LocalVar, objInst, DebugVar, ErrVa ELSE LocalVar%PC_RefSpd_PRC = CntrPar%PC_RefSpd ENDIF - + ! Implement setpoint smoothing IF (LocalVar%SS_DelOmegaF < 0) THEN LocalVar%PC_RefSpd_SS = LocalVar%PC_RefSpd_PRC - LocalVar%SS_DelOmegaF @@ -55,28 +55,36 @@ SUBROUTINE ComputeVariablesSetpoints(CntrPar, LocalVar, objInst, DebugVar, ErrVa LocalVar%PC_RefSpd = LocalVar%PC_RefSpd_SS LocalVar%PC_SpdErr = LocalVar%PC_RefSpd - LocalVar%GenSpeedF ! Speed error LocalVar%PC_PwrErr = CntrPar%VS_RtPwr - LocalVar%VS_GenPwr ! Power error, unused - + ! ----- Torque controller reference errors ----- ! Define VS reference generator speed [rad/s] IF (CntrPar%VS_ControlMode == VS_Mode_WSE_TSR) THEN - ! LocalVar%VS_RefSpd_TSR = (CntrPar%VS_TSRopt * LocalVar%We_Vw_F / CntrPar%WE_BladeRadius) * CntrPar%WE_GearboxRatio ! Use unfiltered wind speed estimate, then filter below LocalVar%VS_RefSpd_TSR = (CntrPar%VS_TSRopt * LocalVar%WE_Vw / CntrPar%WE_BladeRadius) * CntrPar%WE_GearboxRatio ELSEIF (CntrPar%VS_ControlMode == VS_Mode_Power_TSR) THEN ! Genspeed reference that doesn't depend on wind speed estimate (https://doi.org/10.2172/1259805) - LocalVar%VS_RefSpd_TSR = (LocalVar%VS_GenPwr/CntrPar%VS_Rgn2K)**(1./3.) + LocalVar%VS_RefSpd_TSR = (LocalVar%VS_GenPwr/(CntrPar%VS_GenEff/100.0)/CntrPar%VS_Rgn2K)**(1./3.) - ELSEIF (CntrPar%VS_ControlMode == VS_Mode_FBP) THEN ! Generic lookup table for genspeed reference - IF (CntrPar%VS_FBP_RefMode == 0) THEN ! Use WSE to look up speed reference - LocalVar%VS_RefSpd_TSR = interp1d(CntrPar%VS_FBP_U, CntrPar%VS_FBP_Omega, LocalVar%WE_Vw, ErrVar) - ELSEIF (CntrPar%VS_FBP_RefMode == 1) THEN ! Use LocalVar%GenTq or LocalVar%GenTqMeas, Omega must be expressed as a function of Tau - LocalVar%VS_RefSpd_TSR = interp1d(CntrPar%VS_FBP_Tau, CntrPar%VS_FBP_Omega, LocalVar%GenTq, ErrVar) - ENDIF + ELSEIF (CntrPar%VS_ControlMode == VS_Mode_Torque_TSR) THEN ! Non-WSE TSR tracking based on square-root of torque + LocalVar%VS_RefSpd_TSR = (LocalVar%GenTq/CntrPar%VS_Rgn2K)**(1./2.) ELSE ! Generate constant reference LocalVar%VS_RefSpd_TSR = CntrPar%VS_RefSpd ENDIF + ! Region 3 FBP reference logic, triggers if Region-2 reference speed is higher than rated + ! DBS: Alternatively, each of these alternative reference modes could identify Region 3 using their reference-deriving signal, e.g. if WE_Vw > rated speed (accessible in ROSCO?) or GenTq > VS_RtTq + IF (LocalVar%VS_RefSpd_TSR > CntrPar%VS_RefSpd) THEN + IF (CntrPar%VS_FBP == VS_FBP_WSE_Ref) THEN ! Use WSE to look up speed reference in Region 3 + LocalVar%VS_RefSpd_TSR = interp1d(CntrPar%VS_FBP_U, CntrPar%VS_FBP_Omega, LocalVar%WE_Vw, ErrVar) + + ELSEIF (CntrPar%VS_FBP == VS_FBP_Torque_Ref) THEN ! Use torque to look up speed reference in Region 3 + LocalVar%VS_RefSpd_TSR = interp1d(CntrPar%VS_FBP_Tau, CntrPar%VS_FBP_Omega, LocalVar%GenTq, ErrVar) + + ENDIF + ENDIF + + ! Filter reference signal LocalVar%VS_RefSpd = LPFilter(LocalVar%VS_RefSpd_TSR, LocalVar%DT, CntrPar%F_VSRefSpdCornerFreq, LocalVar%FP, LocalVar%iStatus, LocalVar%restart, objInst%instLPF) @@ -93,7 +101,7 @@ SUBROUTINE ComputeVariablesSetpoints(CntrPar, LocalVar, objInst, DebugVar, ErrVa IF (CntrPar%PRC_Mode == 1) THEN LocalVar%VS_RefSpd = interp1d(CntrPar%PRC_WindSpeeds,CntrPar%PRC_GenSpeeds,LocalVar%WE_Vw_F,ErrVar) ENDIF - + ! Implement setpoint smoothing IF (LocalVar%SS_DelOmegaF > 0) THEN LocalVar%VS_RefSpd = LocalVar%VS_RefSpd - LocalVar%SS_DelOmegaF @@ -108,11 +116,7 @@ SUBROUTINE ComputeVariablesSetpoints(CntrPar, LocalVar, objInst, DebugVar, ErrVa LocalVar%VS_RefSpd = max(LocalVar%VS_RefSpd, CntrPar%VS_MinOmSpd) ! Compute speed error from reference - IF ((CntrPar%VS_ControlMode == VS_Mode_WSE_TSR) .OR. \ - (CntrPar%VS_ControlMode == VS_Mode_Power_TSR) .OR. \ - (CntrPar%VS_ControlMode == VS_Mode_FBP)) THEN - LocalVar%VS_SpdErr = LocalVar%VS_RefSpd - LocalVar%GenSpeedF - ENDIF + LocalVar%VS_SpdErr = LocalVar%VS_RefSpd - LocalVar%GenSpeedF ! Define transition region setpoint errors LocalVar%VS_SpdErrAr = LocalVar%VS_RefSpd - LocalVar%GenSpeedF ! Current speed error - Region 2.5 PI-control (Above Rated) @@ -131,16 +135,17 @@ END SUBROUTINE ComputeVariablesSetpoints SUBROUTINE StateMachine(CntrPar, LocalVar) ! State machine, determines the state of the wind turbine to specify the corresponding control actions ! PC States: - ! PC_State = 0, No pitch control active, BldPitch = PC_MinPit - ! PC_State = 1, Active PI blade pitch control enabled + ! PC_State = PC_State_Disabled (0), No pitch control active, BldPitch = PC_MinPit + ! PC_State = PC_State_Enabled (1), Active PI blade pitch control enabled ! VS States - ! VS_State = 0, Error state, for debugging purposes, GenTq = VS_RtTq - ! VS_State = 1, Region 1(.5) operation, torque control to keep the rotor at cut-in speed towards the Cp-max operational curve - ! VS_State = 2, Region 2 operation, maximum rotor power efficiency (Cp-max) tracking using K*omega^2 law, fixed fine-pitch angle in BldPitch controller - ! VS_State = 3, Region 2.5, transition between below and above-rated operating conditions (near-rated region) using PI torque control - ! VS_State = 4, above-rated operation using pitch control (constant torque mode) - ! VS_State = 5, above-rated operation using pitch and torque control (constant power mode) - ! VS_State = 6, Tip-Speed-Ratio tracking PI controller + ! VS_State = VS_State_Error (0), Error state, for debugging purposes, GenTq = VS_RtTq + ! VS_State = VS_State_Region_1_5 (1), Region 1(.5) operation, torque control to keep the rotor at cut-in speed towards the Cp-max operational curve + ! VS_State = VS_State_Region_2 (2), Region 2 operation, maximum rotor power efficiency (Cp-max) tracking using K*omega^2 law, fixed fine-pitch angle in BldPitch controller + ! VS_State = VS_State_Region_2_5 (3), Region 2.5, transition between below and above-rated operating conditions (near-rated region) using PI torque control + ! VS_State = VS_State_Region_3_ConstTrq (4), above-rated operation using pitch control (constant torque mode) + ! VS_State = VS_State_Region_3_ConstPwr (5), above-rated operation using pitch and torque control (constant power mode) + ! VS_State = VS_State_Region_3_FBP (6), above-rated operation using fixed-pitch torque control + ! VS_State = VS_State_PI (7), Tip-Speed-Ratio tracking PI controller USE ROSCO_Types, ONLY : LocalVariables, ControlParameters IMPLICIT NONE @@ -152,46 +157,49 @@ SUBROUTINE StateMachine(CntrPar, LocalVar) IF (LocalVar%iStatus == 0) THEN ! .TRUE. if we're on the first call to the DLL IF (LocalVar%PitCom(1) >= LocalVar%VS_Rgn3Pitch) THEN ! We are in region 3 - IF (CntrPar%VS_ConstPower == 1) THEN ! Constant power tracking - LocalVar%VS_State = 5 - LocalVar%PC_State = 1 + IF (CntrPar%VS_ConstPower == VS_Mode_ConstPwr) THEN ! Constant power tracking + LocalVar%VS_State = VS_State_Region_3_ConstPwr + LocalVar%PC_State = PC_State_Enabled ELSE ! Constant torque tracking - LocalVar%VS_State = 4 - LocalVar%PC_State = 1 + LocalVar%VS_State = VS_State_Region_3_ConstTrq + LocalVar%PC_State = PC_State_Enabled END IF ELSE ! We are in Region 2 - LocalVar%VS_State = 2 - LocalVar%PC_State = 0 + LocalVar%VS_State = VS_State_Region_2 + LocalVar%PC_State = PC_State_Disabled END IF ! Operational States ELSE ! --- Pitch controller state machine --- IF (CntrPar%PC_ControlMode == 1) THEN - LocalVar%PC_State = 1 + LocalVar%PC_State = PC_State_Enabled ELSE - LocalVar%PC_State = 0 + LocalVar%PC_State = PC_State_Disabled END IF ! --- Torque control state machine --- IF (LocalVar%PC_PitComT >= LocalVar%VS_Rgn3Pitch) THEN - - IF (CntrPar%VS_ConstPower == 1) THEN ! Region 3 - LocalVar%VS_State = 5 ! Constant power tracking + IF (CntrPar%VS_ConstPower == VS_Mode_ConstPwr) THEN ! Region 3 + LocalVar%VS_State = VS_State_Region_3_ConstPwr ! Constant power tracking ELSE - LocalVar%VS_State = 4 ! Constant torque tracking + LocalVar%VS_State = VS_State_Region_3_ConstTrq ! Constant torque tracking END IF ELSE IF (LocalVar%GenArTq >= CntrPar%VS_MaxOMTq*1.01) THEN ! Region 2 1/2 - active PI torque control - LocalVar%VS_State = 3 + IF (CntrPar%VS_FBP == VS_FBP_Variable_Pitch) THEN + LocalVar%VS_State = VS_State_Region_2_5 + ELSE + LocalVar%VS_State = VS_State_Region_3_FBP ! Region 3 - fixed blade pitch torque control + END IF ELSEIF ((LocalVar%GenSpeedF < CntrPar%VS_RefSpd) .AND. & - (LocalVar%GenBrTq >= CntrPar%VS_MinOMTq)) THEN ! Region 2 - optimal torque is proportional to the square of the generator speed - LocalVar%VS_State = 2 - ELSEIF (LocalVar%GenBrTq < CntrPar%VS_MinOMTq) THEN ! Region 1 1/2 + (LocalVar%GenBrTq >= CntrPar%VS_MinOMTq)) THEN ! Region 2 - optimal torque is proportional to the square of the generator speed + LocalVar%VS_State = VS_State_Region_2 + ELSEIF (LocalVar%GenBrTq < CntrPar%VS_MinOMTq) THEN ! Region 1 1/2 - LocalVar%VS_State = 1 + LocalVar%VS_State = VS_State_Region_1_5 ELSE ! Error state, Debug - LocalVar%VS_State = 0 + LocalVar%VS_State = VS_State_Error END IF END IF END IF diff --git a/rosco/controller/src/Controllers.f90 b/rosco/controller/src/Controllers.f90 index 63a7fd48..a979c2e7 100644 --- a/rosco/controller/src/Controllers.f90 +++ b/rosco/controller/src/Controllers.f90 @@ -25,8 +25,8 @@ MODULE Controllers !------------------------------------------------------------------------------------------------------------------------------- SUBROUTINE PitchControl(avrSWAP, CntrPar, LocalVar, objInst, DebugVar, ErrVar) ! Blade pitch controller, generally maximizes rotor speed below rated (region 2) and regulates rotor speed above rated (region 3) - ! PC_State = 0, fix blade pitch to fine pitch angle (PC_FinePit) - ! PC_State = 1, is gain scheduled PI controller + ! PC_State = PC_State_Disabled (0), fix blade pitch to fine pitch angle (PC_FinePit) + ! PC_State = PC_State_Disabled (1), is gain scheduled PI controller USE ROSCO_Types, ONLY : ControlParameters, LocalVariables, ObjectInstances, DebugVariables, ErrorVariables ! Inputs @@ -44,7 +44,7 @@ SUBROUTINE PitchControl(avrSWAP, CntrPar, LocalVar, objInst, DebugVar, ErrVar) ! ------- Blade Pitch Controller -------- ! Load PC State - IF (LocalVar%PC_State == 1) THEN ! PI BldPitch control + IF (LocalVar%PC_State == PC_State_Enabled) THEN ! PI BldPitch control LocalVar%PC_MaxPit = CntrPar%PC_MaxPit ELSE ! debug mode, fix at fine pitch LocalVar%PC_MaxPit = CntrPar%PC_FinePit @@ -186,13 +186,13 @@ END SUBROUTINE PitchControl !------------------------------------------------------------------------------------------------------------------------------- SUBROUTINE VariableSpeedControl(avrSWAP, CntrPar, LocalVar, objInst, ErrVar) ! Generator torque controller - ! VS_State = 0, Error state, for debugging purposes, GenTq = VS_RtTq - ! VS_State = 1, Region 1(.5) operation, torque control to keep the rotor at cut-in speed towards the Cp-max operational curve - ! VS_State = 2, Region 2 operation, maximum rotor power efficiency (Cp-max) tracking using K*omega^2 law, fixed fine-pitch angle in BldPitch controller - ! VS_State = 3, Region 2.5, transition between below and above-rated operating conditions (near-rated region) using PI torque control - ! VS_State = 4, above-rated operation using pitch control (constant torque mode) - ! VS_State = 5, above-rated operation using pitch and torque control (constant power mode) - ! VS_State = 6, Tip-Speed-Ratio tracking PI controller + ! VS_State = VS_State_Error (0), Error state, for debugging purposes, GenTq = VS_RtTq + ! VS_State = VS_State_Region_1_5 (1), Region 1(.5) operation, torque control to keep the rotor at cut-in speed towards the Cp-max operational curve + ! VS_State = VS_State_Region_2 (2), Region 2 operation, maximum rotor power efficiency (Cp-max) tracking using K*omega^2 law, fixed fine-pitch angle in BldPitch controller + ! VS_State = VS_State_Region_2_5 (3), Region 2.5, transition between below and above-rated operating conditions (near-rated region) using PI torque control + ! VS_State = VS_State_Region_3_ConstTrq (4), above-rated operation using pitch control (constant torque mode) + ! VS_State = VS_State_Region_3_ConstPwr (5), above-rated operation using pitch and torque control (constant power mode) + ! VS_State = VS_State_PI (6), Tip-Speed-Ratio tracking PI controller (ignore state machine) USE ROSCO_Types, ONLY : ControlParameters, LocalVariables, ObjectInstances, ErrorVariables ! Inputs REAL(ReKi), INTENT(INOUT) :: avrSWAP(*) ! The swap array, used to pass data to, and receive data from, the DLL controller. @@ -207,24 +207,25 @@ SUBROUTINE VariableSpeedControl(avrSWAP, CntrPar, LocalVar, objInst, ErrVar) ! -------- Variable-Speed Torque Controller -------- ! Define max torque - IF (LocalVar%VS_State == 4) THEN + IF (LocalVar%VS_State == VS_State_Region_3_ConstTrq) THEN LocalVar%VS_MaxTq = CntrPar%VS_RtTq ELSE ! VS_MaxTq = CntrPar%VS_MaxTq ! NJA: May want to boost max torque LocalVar%VS_MaxTq = CntrPar%VS_RtTq ENDIF - ! Optimal Tip-Speed-Ratio tracking controller + ! Optimal Tip-Speed-Ratio tracking controller (reference generated in subroutine ComputeVariablesSetpoints) IF ((CntrPar%VS_ControlMode == VS_Mode_WSE_TSR) .OR. \ (CntrPar%VS_ControlMode == VS_Mode_Power_TSR) .OR. \ - (CntrPar%VS_ControlMode == VS_Mode_FBP)) THEN + (CntrPar%VS_ControlMode == VS_Mode_Torque_TSR)) THEN + ! Constant Power, update VS_MaxTq - IF (CntrPar%VS_ConstPower == 1) THEN + IF (CntrPar%VS_ConstPower == VS_Mode_ConstPwr) THEN LocalVar%VS_MaxTq = min((CntrPar%VS_RtPwr/(CntrPar%VS_GenEff/100.0))/LocalVar%GenSpeedF, CntrPar%VS_MaxTq) END IF - IF (CntrPar%VS_ControlMode == VS_Mode_FBP) THEN - ! DBS: In the future, look into combining FBP with constant power + IF (CntrPar%VS_FBP > 0) THEN + ! Increase torque limit from rated if torque control also used in Region 3 LocalVar%VS_MaxTq = CntrPar%VS_MaxTq END IF @@ -236,23 +237,39 @@ SUBROUTINE VariableSpeedControl(avrSWAP, CntrPar, LocalVar, objInst, ErrVar) CntrPar%VS_MinTq, LocalVar%VS_MaxTq, & LocalVar%DT, LocalVar%VS_LastGenTrq, LocalVar%piP, LocalVar%restart, objInst%instPI) + IF (CntrPar%VS_FBP == VS_FBP_Power_Overspeed) THEN + ! Saturate input if FBP mode is set to constant power overspeed + LocalVar%GenTq = MIN((CntrPar%VS_RtPwr/(CntrPar%VS_GenEff/100.0))/LocalVar%GenSpeedF, LocalVar%GenTq) + ENDIF + ! K*Omega^2 control law with PI torque control in transition regions ELSEIF (CntrPar%VS_ControlMode == VS_Mode_KOmega) THEN ! 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_MaxOMTq, LocalVar%piP, LocalVar%restart, objInst%instPI) LocalVar%GenBrTq = PIController(LocalVar%VS_SpdErrBr, CntrPar%VS_KP(1), CntrPar%VS_KI(1), CntrPar%VS_MinTq, CntrPar%VS_MinOMTq, LocalVar%DT, CntrPar%VS_MinOMTq, LocalVar%piP, LocalVar%restart, objInst%instPI) - ! The action - IF (LocalVar%VS_State == 1) THEN ! Region 1.5 + ! State machine if switching to blade pitch control + IF (LocalVar%VS_State == VS_State_Region_1_5) THEN ! Region 1.5 LocalVar%GenTq = LocalVar%GenBrTq - ELSEIF (LocalVar%VS_State == 2) THEN ! Region 2 + ELSEIF (LocalVar%VS_State == VS_State_Region_2) THEN ! Region 2 LocalVar%GenTq = CntrPar%VS_Rgn2K*LocalVar%GenSpeedF*LocalVar%GenSpeedF - ELSEIF (LocalVar%VS_State == 3) THEN ! Region 2.5 + ELSEIF (LocalVar%VS_State == VS_State_Region_2_5) THEN ! Region 2.5 LocalVar%GenTq = LocalVar%GenArTq - ELSEIF (LocalVar%VS_State == 4) THEN ! Region 3, constant torque + ELSEIF (LocalVar%VS_State == VS_State_Region_3_ConstTrq) THEN ! Region 3, constant torque LocalVar%GenTq = CntrPar%VS_RtTq - ELSEIF (LocalVar%VS_State == 5) THEN ! Region 3, constant power + ELSEIF (LocalVar%VS_State == VS_State_Region_3_ConstPwr) THEN ! Region 3, constant power LocalVar%GenTq = (CntrPar%VS_RtPwr/(CntrPar%VS_GenEff/100.0))/LocalVar%GenSpeedF + ELSEIF (LocalVar%VS_State == VS_State_Region_3_FBP) THEN ! Region 3, fixed blade pitch + ! Constant power overspeed + IF (CntrPar%VS_FBP == VS_FBP_Power_Overspeed) THEN + ! Nonlinear lookup table from gen speed to gen torque + ! LocalVar%GenTq = interp1d(CntrPar%VS_FBP_Omega, CntrPar%VS_FBP_Tau, LocalVar%GenSpeedF, ErrVar) ! (must express LUTs for torque as a function of speed) + ! Either K*Omega^2 or constant power overspeed + LocalVar%GenTq = MIN((CntrPar%VS_RtPwr/(CntrPar%VS_GenEff/100.0))/LocalVar%GenSpeedF, CntrPar%VS_Rgn2K*LocalVar%GenSpeedF*LocalVar%GenSpeedF) + ! Reference-tracking in Region 3 + ELSEIF ((CntrPar%VS_FBP == VS_FBP_WSE_Ref) .OR. (CntrPar%VS_FBP == VS_FBP_Torque_Ref)) THEN + LocalVar%GenTq = LocalVar%GenArTq + ENDIF END IF ELSE ! VS_ControlMode of 0 diff --git a/rosco/controller/src/ROSCO_IO.f90 b/rosco/controller/src/ROSCO_IO.f90 index a4f44283..ab1ec3ea 100644 --- a/rosco/controller/src/ROSCO_IO.f90 +++ b/rosco/controller/src/ROSCO_IO.f90 @@ -945,4 +945,4 @@ SUBROUTINE Debug(LocalVar, CntrPar, DebugVar, ErrVar, avrSWAP, RootName, size_av ENDIF END SUBROUTINE Debug -END MODULE ROSCO_IO \ No newline at end of file +END MODULE ROSCO_IO diff --git a/rosco/controller/src/ROSCO_Types.f90 b/rosco/controller/src/ROSCO_Types.f90 index e2f9a5fb..8074a268 100644 --- a/rosco/controller/src/ROSCO_Types.f90 +++ b/rosco/controller/src/ROSCO_Types.f90 @@ -63,8 +63,9 @@ MODULE ROSCO_Types REAL(DbKi) :: PC_RefSpd ! Desired (reference) HSS speed for pitch controller, [rad/s]. REAL(DbKi) :: PC_FinePit ! Record 5 - Below-rated pitch angle set-point (deg) [used only with Bladed Interface] REAL(DbKi) :: PC_Switch ! Angle above lowest minimum pitch angle for switch [rad] - INTEGER(IntKi) :: VS_ControlMode ! Generator torque control mode in below rated conditions {0 - no torque control, 1 - komega^2 with PI trans, 2 - WSE TSR Tracking, 3 - Power TSR Tracking, 4 - Fixed pitch, generic operating schedule for torque controller in Regions 2 and 3} + INTEGER(IntKi) :: VS_ControlMode ! Generator torque control mode in below rated conditions {0 - no torque control, 1 - komega^2 with PI trans, 2 - WSE TSR Tracking, 3 - Power TSR Tracking, 4 - Torque TSR Tracking} INTEGER(IntKi) :: VS_ConstPower ! Constant power torque control + INTEGER(IntKi) :: VS_FBP ! Fixed blade pitch control mode in above rated conditions {0 - variable pitch (defer to PC_ControlMode and VS_ConstPower), 1 - P/omega overspeed control law, 2 - PI reference tracking based on WSE lookup table, 3 - PI reference tracking based on torque lookup table (must have VS_FBP_Tau be a monotonic function)} REAL(DbKi) :: VS_GenEff ! Generator efficiency mechanical power -> electrical power [-] REAL(DbKi) :: VS_ArSatTq ! Above rated generator torque PI control saturation, [Nm] -- 212900 REAL(DbKi) :: VS_MaxRat ! Maximum torque rate (in absolute value) in torque controller, [Nm/s]. @@ -79,7 +80,6 @@ MODULE ROSCO_Types REAL(DbKi), DIMENSION(:), ALLOCATABLE :: VS_KP ! Proportional gain for generator PI torque controller, used in the transitional 2.5 region REAL(DbKi), DIMENSION(:), ALLOCATABLE :: VS_KI ! Integral gain for generator PI torque controller, used in the transitional 2.5 region REAL(DbKi) :: VS_TSRopt ! Power-maximizing region 2 tip-speed ratio [rad] - INTEGER(IntKi) :: VS_FBP_RefMode ! Reference interpolation control mode for fixed blade pitch in above rated conditions {0 - no torque control, 1 - komega^2 with PI trans, 2 - WSE TSR Tracking, 3 - Power TSR Tracking} INTEGER(IntKi) :: VS_FBP_n ! Number of operating schedule entries for fixed blade pitch control REAL(DbKi), DIMENSION(:), ALLOCATABLE :: VS_FBP_U ! Operating schedule for fixed blade pitch control - Wind speed REAL(DbKi), DIMENSION(:), ALLOCATABLE :: VS_FBP_Omega ! Operating schedule for fixed blade pitch control - Generator speed diff --git a/rosco/controller/src/ReadSetParameters.f90 b/rosco/controller/src/ReadSetParameters.f90 index 6ae465df..8bcb393e 100644 --- a/rosco/controller/src/ReadSetParameters.f90 +++ b/rosco/controller/src/ReadSetParameters.f90 @@ -221,7 +221,7 @@ SUBROUTINE SetParameters(avrSWAP, accINFILE, size_avcMSG, CntrPar, LocalVar, obj ! Setpoint Smoother initialization to zero LocalVar%SS_DelOmegaF = 0 - IF (CntrPar%VS_ControlMode < VS_Mode_FBP) THEN + IF (CntrPar%VS_FBP == VS_FBP_Variable_Pitch) THEN ! Generator Torque at K omega^2 or rated IF (LocalVar%GenSpeed > 0.98 * CntrPar%PC_RefSpd) THEN LocalVar%GenTq = CntrPar%VS_RtTq @@ -347,7 +347,8 @@ SUBROUTINE ReadControlParameterFileSub(CntrPar, LocalVar, accINFILE, accINFILE_s CALL ParseInput(FileLines,'F_LPFType', CntrPar%F_LPFType, accINFILE(1), ErrVar, UnEc=UnEc) CALL ParseInput(FileLines,'IPC_ControlMode', CntrPar%IPC_ControlMode, accINFILE(1), ErrVar, UnEc=UnEc) CALL ParseInput(FileLines,'VS_ControlMode', CntrPar%VS_ControlMode, accINFILE(1), ErrVar, UnEc=UnEc) - CALL ParseInput(FileLines,'VS_ConstPower', CntrPar%VS_ConstPower, accINFILE(1), ErrVar, .TRUE., UnEc=UnEc) ! Default is 0 + CALL ParseInput(FileLines,'VS_ConstPower', CntrPar%VS_ConstPower, accINFILE(1), ErrVar, .TRUE., UnEc=UnEc) ! Default is 0 + CALL ParseInput(FileLines,'VS_FBP', CntrPar%VS_FBP, accINFILE(1), ErrVar, .TRUE., UnEc=UnEc) ! Default is 0 CALL ParseInput(FileLines,'PC_ControlMode', CntrPar%PC_ControlMode, accINFILE(1), ErrVar, UnEc=UnEc) CALL ParseInput(FileLines,'Y_ControlMode', CntrPar%Y_ControlMode, accINFILE(1), ErrVar, UnEc=UnEc) CALL ParseInput(FileLines,'SS_Mode', CntrPar%SS_Mode, accINFILE(1), ErrVar, UnEc=UnEc) @@ -440,11 +441,10 @@ SUBROUTINE ReadControlParameterFileSub(CntrPar, LocalVar, accINFILE, accINFILE_s IF (ErrVar%aviFAIL < 0) RETURN !------------ Fixed-Pitch Region 3 Control ------------ - CALL ParseInput(FileLines, 'VS_FBP_RefMode', CntrPar%VS_FBP_RefMode, accINFILE(1), ErrVar, CntrPar%VS_ControlMode < 4, UnEc) - CALL ParseInput(FileLines, 'VS_FBP_n', CntrPar%VS_FBP_n, accINFILE(1), ErrVar, CntrPar%VS_ControlMode < 4, UnEc) - CALL ParseAry( FileLines, 'VS_FBP_U', CntrPar%VS_FBP_U, CntrPar%VS_FBP_n, accINFILE(1), ErrVar, CntrPar%VS_ControlMode < 4, UnEc) - CALL ParseAry( FileLines, 'VS_FBP_Omega', CntrPar%VS_FBP_Omega, CntrPar%VS_FBP_n, accINFILE(1), ErrVar, CntrPar%VS_ControlMode < 4, UnEc) - CALL ParseAry( FileLines, 'VS_FBP_Tau', CntrPar%VS_FBP_Tau, CntrPar%VS_FBP_n, accINFILE(1), ErrVar, CntrPar%VS_ControlMode < 4, UnEc) + CALL ParseInput(FileLines, 'VS_FBP_n', CntrPar%VS_FBP_n, accINFILE(1), ErrVar, CntrPar%VS_FBP == VS_FBP_Variable_Pitch, UnEc) + CALL ParseAry( FileLines, 'VS_FBP_U', CntrPar%VS_FBP_U, CntrPar%VS_FBP_n, accINFILE(1), ErrVar, CntrPar%VS_FBP == VS_FBP_Variable_Pitch, UnEc) + CALL ParseAry( FileLines, 'VS_FBP_Omega', CntrPar%VS_FBP_Omega, CntrPar%VS_FBP_n, accINFILE(1), ErrVar, CntrPar%VS_FBP == VS_FBP_Variable_Pitch, UnEc) + CALL ParseAry( FileLines, 'VS_FBP_Tau', CntrPar%VS_FBP_Tau, CntrPar%VS_FBP_n, accINFILE(1), ErrVar, CntrPar%VS_FBP == VS_FBP_Variable_Pitch, UnEc) IF (ErrVar%aviFAIL < 0) RETURN !------- Setpoint Smoother -------------------------------- @@ -903,7 +903,7 @@ SUBROUTINE CheckInputs(LocalVar, CntrPar, avrSWAP, ErrVar, size_avcMSG) ! VS_ControlMode IF ((CntrPar%VS_ControlMode < 0) .OR. (CntrPar%VS_ControlMode > 4)) THEN ErrVar%aviFAIL = -1 - ErrVar%ErrMsg = 'VS_ControlMode must be 0, 1, 2, or 3.' + ErrVar%ErrMsg = 'VS_ControlMode must be between 0 and 4.' ENDIF ! VS_ConstPower @@ -912,6 +912,16 @@ SUBROUTINE CheckInputs(LocalVar, CntrPar, avrSWAP, ErrVar, size_avcMSG) ErrVar%ErrMsg = 'VS_ConstPower must be 0 or 1.' ENDIF + ! VS_FBP + IF ((CntrPar%VS_FBP < 0) .OR. (CntrPar%VS_FBP > 3)) THEN + ErrVar%aviFAIL = -1 + ErrVar%ErrMsg = 'VS_FBP must be between 0 and 3.' + ENDIF + IF ((CntrPar%VS_FBP > 0) .AND. (CntrPar%PC_ControlMode > 0)) THEN + ErrVar%aviFAIL = -1 + ErrVar%ErrMsg = 'VS_FBP and PC_ControlMode cannot both be greater than 0.' + ENDIF + ! PC_ControlMode IF ((CntrPar%PC_ControlMode < 0) .OR. (CntrPar%PC_ControlMode > 1)) THEN ErrVar%aviFAIL = -1 diff --git a/rosco/toolbox/controller.py b/rosco/toolbox/controller.py index dca0c369..c983ae4a 100644 --- a/rosco/toolbox/controller.py +++ b/rosco/toolbox/controller.py @@ -55,6 +55,7 @@ def __init__(self, controller_params): self.IPC_ControlMode = controller_params['IPC_ControlMode'] self.VS_ControlMode = controller_params['VS_ControlMode'] self.VS_ConstPower = controller_params['VS_ConstPower'] + self.VS_FBP = controller_params['VS_FBP'] self.PC_ControlMode = controller_params['PC_ControlMode'] self.Y_ControlMode = controller_params['Y_ControlMode'] self.SS_Mode = controller_params['SS_Mode'] @@ -99,27 +100,19 @@ def __init__(self, controller_params): self.IPC_Vramp = controller_params['IPC_Vramp'] self.ZMQ_UpdatePeriod = controller_params['ZMQ_UpdatePeriod'] + # FBP config defaults to constant power, underspeed + self.fbp_power_mode = controller_params['VS_FBP_power_mode'] + self.fbp_speed_mode = controller_params['VS_FBP_speed_mode'] + self.fbp_U = controller_params['VS_FBP_U'] # DBS: Should we set this default based on rated speed? + self.fbp_P = controller_params['VS_FBP_P'] + # Optional parameters without defaults - if self.VS_ControlMode == 4: + if self.VS_FBP > 0: # Fail if generator torque enabled in Region 3 but pitch control not disabled (may enable these modes to operate together in the future) if self.PC_ControlMode != 0: raise Exception( - 'rosco.toolbox:controller: PC_ControlMode must be 0 if VS_ControlMode == 4') - - if 'VS_FBP_ref_mode' in controller_params: - self.fbp_ref_mode = controller_params['VS_FBP_ref_mode'] - else: - raise Exception( - 'rosco.toolbox:controller: FBP options (VS_FBP_ref_mode) must be set if VS_ControlMode == 4') - - # Defaults to constant power, underspeed - self.fbp_power_mode = controller_params['VS_FBP_power_mode'] - self.fbp_speed_mode = controller_params['VS_FBP_speed_mode'] - self.fbp_U = controller_params['VS_FBP_U'] # Should we set this default based on rated speed? - self.fbp_P = controller_params['VS_FBP_P'] - else: - self.fbp_ref_mode = 0 + 'rosco.toolbox:controller: PC_ControlMode must be 0 if VS_FBP > 0') if self.Flp_Mode > 0: if 'flp_kp_norm' in controller_params and 'flp_tau' in controller_params: @@ -238,11 +231,11 @@ def tune_controller(self, turbine): v = np.concatenate((v_below_rated, v_above_rated)) # Construct power schedule differently based on pitch control configuration - if self.VS_ControlMode == 4: # If using torque control in Region 3 + if self.VS_FBP > 0: # If using torque control in Region 3 # Check if constant power control disabled (may be implemented to work concurrently in the future) if self.VS_ConstPower != 0: - raise Exception("VS_ConstPower must be 0 when VS_ControlMode == 4") + raise Exception("VS_ConstPower must be 0 when VS_FBP > 0") # Begin with user-defined power curve from input yaml (default constant rated power) f_P_user_defined = interpolate.interp1d(self.fbp_U, self.fbp_P, fill_value=(self.fbp_P[0], self.fbp_P[-1]), bounds_error=False) @@ -276,7 +269,7 @@ def tune_controller(self, turbine): TSR_above_rated = TSR_op[len(v_below_rated):] # elif self.PC_ControlMode > 0: # If using pitch control in Region 3 - else: # Default here even if pitch control disabled + else: # Default here even if pitch control disabled to maintain backwards compatibility # separate TSRs by operations regions TSR_below_rated = [min(turbine.TSR_operational, rated_rotor_speed*R/v) for v in v_below_rated] # below rated @@ -304,7 +297,7 @@ def tune_controller(self, turbine): # At each operating point for i in range(len(TSR_op)): - if self.VS_ControlMode == 4: # Fixed pitch control in Region 3 + if self.VS_FBP > 0: # Fixed blade pitch control in Region 3 if isinstance(self.min_pitch, float): pitch_op[i] = self.min_pitch @@ -344,7 +337,7 @@ def tune_controller(self, turbine): # Compute generator speed and torque operating schedule P_op = 0.5 * turbine.rho * np.pi*turbine.rotor_radius**2 * Cp_op * v**3 * turbine.GBoxEff/100 * turbine.GenEff/100 - if self.VS_ControlMode < 4: # Saturate between min speed and rated if variable pitch in Region 3 + if self.VS_FBP == 0: # Saturate between min speed and rated if variable pitch in Region 3 omega_op = np.maximum(np.minimum(turbine.rated_rotor_speed, TSR_op*v/R), self.vs_minspd) else: # Only saturate min pitch if torque control in Region 3 omega_op = np.maximum(TSR_op*v/R, self.vs_minspd) @@ -358,10 +351,10 @@ def tune_controller(self, turbine): # DBS: Do we want to saturate maximum torque and recompute equilibrium points? # Check if options allow a nonmonotonic torque schedule - if self.fbp_ref_mode == 1: + if self.VS_FBP == 3: # The simulation will crash if we have a nonmonotonic schedule, so fail to generate the config and alert the user if np.any(np.diff(tau_op) <= 0): - raise Exception("VS controller reference torque interpolation is selected (VS_FBP_ref_mode == 1), but computed generator torque schedule is not monotonically increasing. Reconfigure power curve, ensure VS_FBP_speed_mode == 0, or switch VS_FBP_ref_mode to 0.") + raise Exception("VS controller reference torque interpolation is selected (VS_FBP_ref_mode == 1), but computed generator torque schedule is not monotonically increasing. Reconfigure power curve, ensure VS_FBP_speed_mode == 0, or switch VS_FBP to 2.") # Full Cx surface gradients @@ -418,7 +411,7 @@ def tune_controller(self, turbine): self.pc_gain_schedule = ControllerTypes() self.pc_gain_schedule.second_order_PI(self.zeta_pc_U, self.omega_pc_U,A_pc,B_beta[-len(v_above_rated)+1:],linearize=True,v=v_above_rated[1:]) self.vs_gain_schedule = ControllerTypes() - if self.VS_ControlMode < 4: + if self.VS_FBP == 0: self.vs_gain_schedule.second_order_PI(self.zeta_vs, self.omega_vs,A_vs,B_tau[0:len(v_below_rated)],linearize=False,v=v_below_rated) else: self.vs_gain_schedule.second_order_PI(self.zeta_vs, self.omega_vs,A,B_tau,linearize=False,v=v) diff --git a/rosco/toolbox/inputs/toolbox_schema.yaml b/rosco/toolbox/inputs/toolbox_schema.yaml index 86557e35..179c91a3 100644 --- a/rosco/toolbox/inputs/toolbox_schema.yaml +++ b/rosco/toolbox/inputs/toolbox_schema.yaml @@ -130,13 +130,19 @@ properties: minimum: 0 maximum: 4 default: 2 - description: Generator torque control mode in above rated conditions (0- no torque control, 1- k*omega^2 with PI transitions, 2- WSE TSR Tracking, 3- Power-based TSR Tracking) + description: Generator torque control mode in above rated conditions (0- no torque control, 1- k*omega^2 with PI transitions, 2- WSE TSR Tracking, 3- Power-based TSR Tracking, 4- Torque-based TSR Tracking) VS_ConstPower: type: number minimum: 0 maximum: 1 default: 0 description: Do constant power torque control, where above rated torque varies, 0 for constant torque + VS_FBP: + type: number + minimum: 0 + maximum: 3 + default: 0 + description: Configuration for FBP mode (0- variable pitch (disabled), 1- constant power overspeed, 2- WSE-lookup reference tracking, 3- torque-lookup reference tracking) PC_ControlMode: type: number minimum: 0 @@ -434,11 +440,6 @@ properties: description: Factor on VS_Rgn2K to increase/decrease optimal torque control gain, default is 1. Sometimes environmental conditions or differences in BEM solvers necessitate this change. default: 1 minimum: 0 - VS_FBP_ref_mode: - type: number - description: Method of identifying operating point reference during operation (0- Use WSE, 1- Use filtered torque signal) - minimum: 0 - maximum: 1 VS_FBP_power_mode: type: number description: Interpretation mode for VS_FBP_P (0- scale relative to rated power, 1- absolute power) @@ -611,12 +612,17 @@ properties: type: number minimum: 0 maximum: 4 - description: Generator torque control mode in above rated conditions (0- no torque control, 1- k*omega^2 with PI transitions, 2- WSE TSR Tracking, 3- Power-based TSR Tracking, 4- Torque-based TSR tracking in Region 2 + torque control with user-defined power curve in Region 3) + description: Generator torque control mode in above rated conditions (0- no torque control, 1- k*omega^2 with PI transitions, 2- WSE TSR Tracking, 3- Power-based TSR Tracking, 4- Torque-based TSR Tracking) VS_ConstPower: type: number minimum: 0 maximum: 1 description: Do constant power torque control, where above rated torque varies + VS_FBP: + type: number + minimum: 0 + maximum: 3 + description: Configuration for FBP mode (0- variable pitch (disabled), 1- constant power overspeed, 2- WSE-lookup reference tracking, 3- torque-lookup reference tracking) F_NotchType: type: number description: Notch on the measured generator speed and/or tower fore-aft motion (for floating) (0- disable, 1- generator speed, 2- tower-top fore-aft motion, 3- generator speed and tower-top fore-aft motion) @@ -831,7 +837,7 @@ properties: units: rad/s VS_Rgn2K: type: number - description: Generator torque constant in Region 2 (HSS side). Only used in VS_ControlMode = 1,3 + description: Generator torque constant in Region 2 (HSS side). Only used in VS_ControlMode = 1,3,4 units: Nm/(rad/s)^2 VS_RtPwr: type: number diff --git a/rosco/toolbox/utilities.py b/rosco/toolbox/utilities.py index 5aee6b50..98263328 100644 --- a/rosco/toolbox/utilities.py +++ b/rosco/toolbox/utilities.py @@ -97,10 +97,11 @@ def write_DISCON(turbine, controller, param_file='DISCON.IN', txt_filename='Cp_C file.write('{:<11d} ! Echo - ({})\n'.format(int(rosco_vt['Echo']), input_descriptions['Echo'])) file.write('\n') file.write('!------- CONTROLLER FLAGS -------------------------------------------------\n') - file.write('{0:<12d} ! F_LPFType - (1: first-order low-pass filter, 2: second-order low-pass filter), [rad/s] (currently filters generator speed and pitch control signals\n'.format(int(rosco_vt['F_LPFType']))) - file.write('{0:<12d} ! IPC_ControlMode - Turn Individual Pitch Control (IPC) for fatigue load reductions (pitch contribution) {{0: off, 1: 1P reductions, 2: 1P+2P reductions}}\n'.format(int(rosco_vt['IPC_ControlMode']))) - file.write('{0:<12d} ! VS_ControlMode - Generator torque control mode in above rated conditions (0- no torque control, 1- k*omega^2 with PI transitions, 2- WSE TSR Tracking, 3- Power-based TSR Tracking)}}\n'.format(int(rosco_vt['VS_ControlMode']))) - file.write('{0:<12d} ! VS_ConstPower - Do constant power torque control, where above rated torque varies, 0 for constant torque}}\n'.format(int(rosco_vt['VS_ConstPower']))) + file.write('{0:<12d} ! F_LPFType - (1: first-order low-pass filter, 2: second-order low-pass filter), [rad/s] (currently filters generator speed and pitch control signals\n'.format(int(rosco_vt['F_LPFType']))) + file.write('{0:<12d} ! IPC_ControlMode - Turn Individual Pitch Control (IPC) for fatigue load reductions (pitch contribution) {{0: off, 1: 1P reductions, 2: 1P+2P reductions}}\n'.format(int(rosco_vt['IPC_ControlMode']))) + file.write('{0:<12d} ! VS_ControlMode - Generator torque control mode in above rated conditions (0- no torque control, 1- k*omega^2 with PI transitions, 2- WSE TSR Tracking, 3- Power-based TSR Tracking, 4- Torque-based TSR Tracking)}}\n'.format(int(rosco_vt['VS_ControlMode']))) + file.write('{0:<12d} ! VS_ConstPower - Do constant power torque control, where above rated torque varies, 0 for constant torque}}\n'.format(int(rosco_vt['VS_ConstPower']))) + file.write('{0:<12d} ! VS_FBP - Fixed blade pitch configuration mode (0- variable pitch (disabled), 1- constant power overspeed, 2- WSE-lookup reference tracking, 3- torque-lookup reference tracking)\n'.format(int(rosco_vt['VS_FBP']))) file.write('{0:<12d} ! PC_ControlMode - Blade pitch control mode {{0: No pitch, fix to fine pitch, 1: active PI blade pitch control}}\n'.format(int(rosco_vt['PC_ControlMode']))) file.write('{0:<12d} ! Y_ControlMode - Yaw control mode {{0: no yaw control, 1: yaw rate control, 2: yaw-by-IPC}}\n'.format(int(rosco_vt['Y_ControlMode']))) file.write('{0:<12d} ! SS_Mode - Setpoint Smoother mode {{0: no setpoint smoothing, 1: introduce setpoint smoothing}}\n'.format(int(rosco_vt['SS_Mode']))) @@ -183,7 +184,6 @@ def write_DISCON(turbine, controller, param_file='DISCON.IN', txt_filename='Cp_C file.write('{:<13.2f} ! VS_TSRopt - {}\n'.format(float(rosco_vt['VS_TSRopt']),input_descriptions['VS_TSRopt'])) file.write('\n') file.write('!------- FIXED PITCH REGION 3 TORQUE CONTROL ------------------------------------------------\n') - file.write('{:<11d} ! VS_FBP_RefMode - Reference control mode (0 - Use wind speed estimator, 1 - Use torque feedback)\n'.format(int(rosco_vt['VS_FBP_RefMode']))) file.write('{:<11d} ! VS_FBP_n - Number of gain-scheduling table entries\n'.format(int(rosco_vt['VS_FBP_n']))) file.write('{} ! VS_FBP_U - Operating schedule table: Wind speeds [m/s].\n'.format(''.join('{:<4.6f} '.format(rosco_vt['VS_FBP_U'][i]) for i in range(len(rosco_vt['VS_FBP_U']))))) file.write('{} ! VS_FBP_Omega - Operating schedule table: Generator speeds [rad/s].\n'.format(''.join('{:<4.6f} '.format(rosco_vt['VS_FBP_Omega'][i]) for i in range(len(rosco_vt['VS_FBP_Omega']))))) @@ -483,6 +483,7 @@ def DISCON_dict(turbine, controller, txt_filename=None): DISCON_dict['IPC_ControlMode'] = int(controller.IPC_ControlMode) DISCON_dict['VS_ControlMode'] = int(controller.VS_ControlMode) DISCON_dict['VS_ConstPower'] = int(controller.VS_ConstPower) + DISCON_dict['VS_FBP'] = int(controller.VS_FBP) DISCON_dict['PC_ControlMode'] = int(controller.PC_ControlMode) DISCON_dict['Y_ControlMode'] = int(controller.Y_ControlMode) DISCON_dict['SS_Mode'] = int(controller.SS_Mode) @@ -564,7 +565,6 @@ def DISCON_dict(turbine, controller, txt_filename=None): DISCON_dict['VS_KI'] = controller.vs_gain_schedule.Ki[-1] DISCON_dict['VS_TSRopt'] = turbine.TSR_operational # ------- FIXED BLADE PITCH TORQUE CONTROL ------- - DISCON_dict['VS_FBP_RefMode'] = controller.fbp_ref_mode DISCON_dict['VS_FBP_n'] = len(controller.v) DISCON_dict['VS_FBP_U'] = controller.v DISCON_dict['VS_FBP_Omega'] = controller.omega_gen_op From 541fe813bbaac024c0dc11a26229cfe51ed3c903 Mon Sep 17 00:00:00 2001 From: Abhineet Gupta Date: Fri, 9 Aug 2024 10:50:49 -0600 Subject: [PATCH 163/224] Start using automatic documentation for examples (#371) --- Examples/01_turbine_model.py | 88 +++++++++++++++++++----------------- docs/conf.py | 5 ++ docs/source/examples.rst | 6 +++ 3 files changed, 57 insertions(+), 42 deletions(-) diff --git a/Examples/01_turbine_model.py b/Examples/01_turbine_model.py index ab1870d7..27bbf7ca 100644 --- a/Examples/01_turbine_model.py +++ b/Examples/01_turbine_model.py @@ -1,16 +1,16 @@ -''' ------------ 01_turbine_model -------------- -Load and save a turbine model -------------------------------------- -In this example: -- Read .yaml input file -- Load an openfast turbine model -- Read text file with rotor performance properties -- Print some basic turbine properties -- Save the turbine as a picklle +""" +01_turbine_model +---------------- +Load and save a turbine model. + +* Read .yaml input file +* Load an openfast turbine model +* Read text file with rotor performance properties +* Print some basic turbine properties +* Save the turbine as a picklle Note: Uses the NREL 5MW included in the Test Cases and is a part of the OpenFAST distribution -''' +""" # Python Modules import os @@ -19,44 +19,48 @@ from rosco.toolbox.inputs.validation import load_rosco_yaml import matplotlib.pyplot as plt +def main(): + # Load yaml file + this_dir = os.path.dirname(os.path.abspath(__file__)) + tune_dir = os.path.join(this_dir,'Tune_Cases') + parameter_filename = os.path.join(tune_dir,'NREL5MW.yaml') + inps = load_rosco_yaml(parameter_filename) + path_params = inps['path_params'] + turbine_params = inps['turbine_params'] + + # Load turbine data from openfast model + turbine = ROSCO_turbine.Turbine(turbine_params) -# Load yaml file -this_dir = os.path.dirname(os.path.abspath(__file__)) -tune_dir = os.path.join(this_dir,'Tune_Cases') -parameter_filename = os.path.join(tune_dir,'NREL5MW.yaml') -inps = load_rosco_yaml(parameter_filename) -path_params = inps['path_params'] -turbine_params = inps['turbine_params'] + turbine.load_from_fast( + path_params['FAST_InputFile'], + os.path.join(tune_dir,path_params['FAST_directory']), + rot_source='txt',txt_filename=os.path.join(tune_dir,path_params['rotor_performance_filename']) + ) -# Load turbine data from openfast model -turbine = ROSCO_turbine.Turbine(turbine_params) + # Print some basic turbine info + print(turbine) -turbine.load_from_fast( - path_params['FAST_InputFile'], - os.path.join(tune_dir,path_params['FAST_directory']), - rot_source='txt',txt_filename=os.path.join(tune_dir,path_params['rotor_performance_filename']) - ) + # Save the turbine model + example_out_dir = os.path.join(this_dir,'examples_out') + if not os.path.isdir(example_out_dir): + os.makedirs(example_out_dir) -# Print some basic turbine info -print(turbine) + turbine.save(os.path.join(example_out_dir,'01_NREL5MW_saved.p')) -# Save the turbine model -example_out_dir = os.path.join(this_dir,'examples_out') -if not os.path.isdir(example_out_dir): - os.makedirs(example_out_dir) + # Now load the turbine and plot the Cp surface -turbine.save(os.path.join(example_out_dir,'01_NREL5MW_saved.p')) + # Load quick from python pickle + turbine = turbine.load(os.path.join(example_out_dir,'01_NREL5MW_saved.p')) -# Now load the turbine and plot the Cp surface + # plot rotor performance + print('Plotting Cp data') + turbine.Cp.plot_performance() -# Load quick from python pickle -turbine = turbine.load(os.path.join(example_out_dir,'01_NREL5MW_saved.p')) + if False: + plt.show() + else: + plt.savefig(os.path.join(example_out_dir,'01_NREL5MW_Cp.png')) -# plot rotor performance -print('Plotting Cp data') -turbine.Cp.plot_performance() -if False: - plt.show() -else: - plt.savefig(os.path.join(example_out_dir,'01_NREL5MW_Cp.png')) \ No newline at end of file +if __name__=='__main__': + main() \ No newline at end of file diff --git a/docs/conf.py b/docs/conf.py index 952f6936..d83fe85c 100644 --- a/docs/conf.py +++ b/docs/conf.py @@ -15,6 +15,7 @@ from datetime import date root_path = os.path.abspath(os.path.join(os.path.dirname(__file__), "..")) sys.path.insert(0, root_path) +sys.path.insert(0, os.path.join(root_path,'Examples')) # -- Project information ----------------------------------------------------- @@ -53,6 +54,7 @@ def __getattr__(cls, name): "sphinx.ext.graphviz", "sphinx.ext.autosectionlabel", "sphinx_rtd_theme", + "sphinx.ext.autodoc", # "sphinxcontrib.bibtex", ] @@ -91,3 +93,6 @@ def __getattr__(cls, name): # relative to this directory. They are copied after the builtin static files, # so a file named "default.css" will overwrite the builtin "default.css". # html_static_path = ['_static'] + +# Options for AutoDoc: +add_module_names = False diff --git a/docs/source/examples.rst b/docs/source/examples.rst index 5302c1c0..9bb5f04c 100644 --- a/docs/source/examples.rst +++ b/docs/source/examples.rst @@ -98,3 +98,9 @@ By setting :code:`testtype`, the user can run a variety of tests: Setting the :code:`turbine2test` allows the user to test either the IEA-15MW with the UMaine floating semisubmersible or the NREL-5MW reference onshore turbine. + +List of Examples +---------------- +A complete list of examples is given below: + +.. automodule:: 01_turbine_model From df133ee6317f99eae9490509434cc9e1b8d80a73 Mon Sep 17 00:00:00 2001 From: AbhineetGupta Date: Fri, 9 Aug 2024 19:10:55 -0600 Subject: [PATCH 164/224] Added autodocumentation template for all examples --- Examples/02_ccblade.py | 85 ++++---- Examples/03_tune_controller.py | 118 ++++++----- Examples/04_simple_sim.py | 159 +++++++------- Examples/05_openfast_sim.py | 96 ++++----- Examples/06_peak_shaving.py | 105 +++++----- Examples/07_openfast_outputs.py | 70 ++++--- Examples/08_run_turbsim.py | 30 +-- Examples/09_distributed_aero.py | 79 +++---- Examples/10_linear_params.py | 115 ++++++----- Examples/11_robust_tuning.py | 24 ++- Examples/12_tune_ipc.py | 16 +- Examples/14_open_loop_control.py | 287 +++++++++++++------------- Examples/15_pass_through.py | 27 ++- Examples/16_external_dll.py | 22 +- Examples/17a_zeromq_simple.py | 83 ++++---- Examples/17b_zeromq_multi_openfast.py | 138 +++++++------ Examples/18_pitch_offsets.py | 22 +- Examples/19_update_discon_version.py | 15 +- Examples/20_active_wake_control.py | 269 ++++++++++++------------ Examples/21_optional_inputs.py | 22 +- Examples/22_cable_control.py | 40 ++-- Examples/23_structural_control.py | 44 ++-- Examples/24_floating_feedback.py | 30 ++- Examples/25_rotor_position_control.py | 22 +- Examples/26_marine_hydro.py | 30 +-- Examples/27_power_ref_control.py | 34 ++- Examples/28_tower_resonance.py | 27 +-- docs/source/examples.rst | 27 +++ 28 files changed, 1022 insertions(+), 1014 deletions(-) diff --git a/Examples/02_ccblade.py b/Examples/02_ccblade.py index 581603d7..366d973d 100644 --- a/Examples/02_ccblade.py +++ b/Examples/02_ccblade.py @@ -1,46 +1,53 @@ -''' ------------ 02_ccblade -------------- -Run CCblade, save a rotor performance text file -------------------------------------- - +""" +02_ccblade +-------------- +Run CCblade, save a rotor performance text file. In this example: -- Read .yaml input file -- Load an openfast turbine model -- Run ccblade to get rotor performance properties -- Write a text file with rotor performance properties -''' + +* Read .yaml input file +* Load an openfast turbine model +* Run ccblade to get rotor performance properties +* Write a text file with rotor performance properties +""" + # Python modules import os # ROSCO toolbox modules from rosco.toolbox import turbine as ROSCO_turbine from rosco.toolbox.utilities import write_rotor_performance from rosco.toolbox.inputs.validation import load_rosco_yaml -# Initialize parameter dictionaries -turbine_params = {} -control_params = {} - -this_dir = os.path.dirname(os.path.abspath(__file__)) -example_out_dir = os.path.join(this_dir,'examples_out') -if not os.path.isdir(example_out_dir): - os.makedirs(example_out_dir) - -# Load yaml file -this_dir = os.path.dirname(os.path.abspath(__file__)) -tune_dir = os.path.join(this_dir,'Tune_Cases') -parameter_filename = os.path.join(tune_dir,'NREL5MW.yaml') -inps = load_rosco_yaml(parameter_filename) -path_params = inps['path_params'] -turbine_params = inps['turbine_params'] -controller_params = inps['controller_params'] - -# Load turbine data from openfast model -turbine = ROSCO_turbine.Turbine(turbine_params) -turbine.load_from_fast( - path_params['FAST_InputFile'], - os.path.join(tune_dir,path_params['FAST_directory']), - rot_source='cc-blade', - txt_filename=None) - -# Write rotor performance text file -txt_filename = os.path.join(example_out_dir,'02_Cp_Ct_Cq.Ex03.txt') -write_rotor_performance(turbine,txt_filename=txt_filename) + +def main(): + # Initialize parameter dictionaries + turbine_params = {} + control_params = {} + + this_dir = os.path.dirname(os.path.abspath(__file__)) + example_out_dir = os.path.join(this_dir,'examples_out') + if not os.path.isdir(example_out_dir): + os.makedirs(example_out_dir) + + # Load yaml file + this_dir = os.path.dirname(os.path.abspath(__file__)) + tune_dir = os.path.join(this_dir,'Tune_Cases') + parameter_filename = os.path.join(tune_dir,'NREL5MW.yaml') + inps = load_rosco_yaml(parameter_filename) + path_params = inps['path_params'] + turbine_params = inps['turbine_params'] + controller_params = inps['controller_params'] + + # Load turbine data from openfast model + turbine = ROSCO_turbine.Turbine(turbine_params) + turbine.load_from_fast( + path_params['FAST_InputFile'], + os.path.join(tune_dir,path_params['FAST_directory']), + rot_source='cc-blade', + txt_filename=None) + + # Write rotor performance text file + txt_filename = os.path.join(example_out_dir,'02_Cp_Ct_Cq.Ex03.txt') + write_rotor_performance(turbine,txt_filename=txt_filename) + +if __name__ == "__main__": + main() + diff --git a/Examples/03_tune_controller.py b/Examples/03_tune_controller.py index 9d426e50..e4f0e1b8 100644 --- a/Examples/03_tune_controller.py +++ b/Examples/03_tune_controller.py @@ -1,15 +1,16 @@ -''' ------------ 03_tune_controller -------------- +""" +03_tune_controller +------------------ Load a turbine model and tune the controller -------------------------------------- - In this example: - - Read a .yaml file - - Load a turbine model from OpenFAST - - Tune a controller - - Write a controller input file - - Plot gain schedule -''' + +* Read a .yaml file +* Load a turbine model from OpenFAST +* Tune a controller +* Write a controller input file +* Plot gain schedule +""" + # Python modules import matplotlib.pyplot as plt import os @@ -19,62 +20,65 @@ from rosco.toolbox.utilities import write_DISCON from rosco.toolbox.inputs.validation import load_rosco_yaml +def main(): + # Load yaml file + this_dir = os.path.dirname(os.path.abspath(__file__)) + tune_dir = os.path.join(this_dir,'Tune_Cases') + parameter_filename = os.path.join(tune_dir,'NREL5MW.yaml') + inps = load_rosco_yaml(parameter_filename) + path_params = inps['path_params'] + turbine_params = inps['turbine_params'] + controller_params = inps['controller_params'] -# Load yaml file -this_dir = os.path.dirname(os.path.abspath(__file__)) -tune_dir = os.path.join(this_dir,'Tune_Cases') -parameter_filename = os.path.join(tune_dir,'NREL5MW.yaml') -inps = load_rosco_yaml(parameter_filename) -path_params = inps['path_params'] -turbine_params = inps['turbine_params'] -controller_params = inps['controller_params'] + # Instantiate turbine, controller, and file processing classes + turbine = ROSCO_turbine.Turbine(turbine_params) + controller = ROSCO_controller.Controller(controller_params) -# Instantiate turbine, controller, and file processing classes -turbine = ROSCO_turbine.Turbine(turbine_params) -controller = ROSCO_controller.Controller(controller_params) + # Load turbine data from OpenFAST and rotor performance text file + cp_filename = os.path.join(tune_dir,path_params['rotor_performance_filename']) + turbine.load_from_fast( + path_params['FAST_InputFile'], + os.path.join(tune_dir,path_params['FAST_directory']), + rot_source='txt',txt_filename= cp_filename + ) -# Load turbine data from OpenFAST and rotor performance text file -cp_filename = os.path.join(tune_dir,path_params['rotor_performance_filename']) -turbine.load_from_fast( - path_params['FAST_InputFile'], - os.path.join(tune_dir,path_params['FAST_directory']), - rot_source='txt',txt_filename= cp_filename - ) + # Tune controller + controller.tune_controller(turbine) -# Tune controller -controller.tune_controller(turbine) + # Write parameter input file + param_file = os.path.join(this_dir,'DISCON.IN') + write_DISCON(turbine,controller, + param_file=param_file, + txt_filename=cp_filename + ) -# Write parameter input file -param_file = os.path.join(this_dir,'DISCON.IN') -write_DISCON(turbine,controller, -param_file=param_file, -txt_filename=cp_filename -) + # Plot gain schedule + fig, ax = plt.subplots(2,2,constrained_layout=True,sharex=True) + ax = ax.flatten() + ax[0].plot(controller.v[len(controller.v_below_rated)+1:], controller.omega_pc_U) + ax[0].set_ylabel('omega_pc') -# Plot gain schedule -fig, ax = plt.subplots(2,2,constrained_layout=True,sharex=True) -ax = ax.flatten() -ax[0].plot(controller.v[len(controller.v_below_rated)+1:], controller.omega_pc_U) -ax[0].set_ylabel('omega_pc') + ax[1].plot(controller.v[len(controller.v_below_rated)+1:], controller.zeta_pc_U) + ax[1].set_ylabel('zeta_pc') -ax[1].plot(controller.v[len(controller.v_below_rated)+1:], controller.zeta_pc_U) -ax[1].set_ylabel('zeta_pc') + ax[2].plot(controller.v[len(controller.v_below_rated)+1:], controller.pc_gain_schedule.Kp) + ax[2].set_xlabel('Wind Speed') + ax[2].set_ylabel('Proportional Gain') -ax[2].plot(controller.v[len(controller.v_below_rated)+1:], controller.pc_gain_schedule.Kp) -ax[2].set_xlabel('Wind Speed') -ax[2].set_ylabel('Proportional Gain') + ax[3].plot(controller.v[len(controller.v_below_rated)+1:], controller.pc_gain_schedule.Ki) + ax[3].set_xlabel('Wind Speed') + ax[3].set_ylabel('Integral Gain') -ax[3].plot(controller.v[len(controller.v_below_rated)+1:], controller.pc_gain_schedule.Ki) -ax[3].set_xlabel('Wind Speed') -ax[3].set_ylabel('Integral Gain') + plt.suptitle('Pitch Controller Gains') -plt.suptitle('Pitch Controller Gains') + example_out_dir = os.path.join(this_dir,'examples_out') + if not os.path.isdir(example_out_dir): + os.makedirs(example_out_dir) -example_out_dir = os.path.join(this_dir,'examples_out') -if not os.path.isdir(example_out_dir): - os.makedirs(example_out_dir) + if False: + plt.show() + else: + plt.savefig(os.path.join(example_out_dir,'03_GainSched.png')) -if False: - plt.show() -else: - plt.savefig(os.path.join(example_out_dir,'03_GainSched.png')) \ No newline at end of file +if __name__ == "__main__": + main() \ No newline at end of file diff --git a/Examples/04_simple_sim.py b/Examples/04_simple_sim.py index a19a2ccb..acd0848e 100644 --- a/Examples/04_simple_sim.py +++ b/Examples/04_simple_sim.py @@ -1,19 +1,18 @@ -''' ------------ 04_simple_sim -------------- +""" +04_simple_sim +------------- Run and plot a simple simple step wind simulation -------------------------------------- - In this example: - - Load turbine from saved pickle - - Tune a controller - - Run and plot a simple step wind simulation - -Notes - You will need to have a compiled controller in ROSCO, and - properly point to it in the `lib_name` variable. - - Using wind speed estimators in this simple simulation is - known to cause problems. We suggesting using WE_Mode = 0 in DISCON.IN - or increasing sampling rate of simulation -''' + +* Load turbine from saved pickle +* Tune a controller +* Run and plot a simple step wind simulation + +Notes: + +* You will need to have a compiled controller in ROSCO, and properly point to it in the `lib_name` variable. +* Using wind speed estimators in this simple simulation is known to cause problems. We suggesting using WE_Mode = 0 in DISCON.IN or increasing sampling rate of simulation +""" # Python modules import matplotlib.pyplot as plt import numpy as np @@ -27,80 +26,80 @@ from rosco.toolbox.utilities import write_DISCON from rosco.toolbox.inputs.validation import load_rosco_yaml - -# Load yaml file -this_dir = os.path.dirname(os.path.abspath(__file__)) -tune_dir = os.path.join(this_dir,'Tune_Cases') -parameter_filename = os.path.join(tune_dir,'NREL5MW.yaml') -inps = load_rosco_yaml(parameter_filename) -path_params = inps['path_params'] -turbine_params = inps['turbine_params'] -controller_params = inps['controller_params'] - -# Specify controller dynamic library path and name - -#directories -rosco_dir = os.path.dirname(this_dir) -example_out_dir = os.path.join(this_dir,'examples_out') -os.makedirs(example_out_dir,exist_ok=True) - -# # Load turbine model from saved pickle -turbine = ROSCO_turbine.Turbine -turbine = turbine.load(os.path.join(example_out_dir,'01_NREL5MW_saved.p')) -# controller = ROSCO_controller.Controller(controller_params) - -# Load turbine data from OpenFAST and rotor performance text file -cp_filename = os.path.join(tune_dir,path_params['rotor_performance_filename']) -turbine.load_from_fast( - path_params['FAST_InputFile'], - os.path.join(tune_dir,path_params['FAST_directory']), - rot_source='txt',txt_filename=cp_filename +def main(): + # Load yaml file + this_dir = os.path.dirname(os.path.abspath(__file__)) + tune_dir = os.path.join(this_dir,'Tune_Cases') + parameter_filename = os.path.join(tune_dir,'NREL5MW.yaml') + inps = load_rosco_yaml(parameter_filename) + path_params = inps['path_params'] + turbine_params = inps['turbine_params'] + controller_params = inps['controller_params'] + + # Specify controller dynamic library path and name + + #directories + rosco_dir = os.path.dirname(this_dir) + example_out_dir = os.path.join(this_dir,'examples_out') + os.makedirs(example_out_dir,exist_ok=True) + + # # Load turbine model from saved pickle + turbine = ROSCO_turbine.Turbine + turbine = turbine.load(os.path.join(example_out_dir,'01_NREL5MW_saved.p')) + # controller = ROSCO_controller.Controller(controller_params) + + # Load turbine data from OpenFAST and rotor performance text file + cp_filename = os.path.join(tune_dir,path_params['rotor_performance_filename']) + turbine.load_from_fast( + path_params['FAST_InputFile'], + os.path.join(tune_dir,path_params['FAST_directory']), + rot_source='txt',txt_filename=cp_filename + ) + + # Tune controller + controller = ROSCO_controller.Controller(controller_params) + controller.tune_controller(turbine) + + # Write parameter input file + param_filename = os.path.join(this_dir,'DISCON.IN') + write_DISCON( + turbine,controller, + param_file=param_filename, + txt_filename=cp_filename ) -# Tune controller -controller = ROSCO_controller.Controller(controller_params) -controller.tune_controller(turbine) - -# Write parameter input file -param_filename = os.path.join(this_dir,'DISCON.IN') -write_DISCON( - turbine,controller, - param_file=param_filename, - txt_filename=cp_filename - ) - -# Load controller library -controller_int = ROSCO_ci.ControllerInterface(lib_name,param_filename=param_filename,sim_name='sim1') + # Load controller library + controller_int = ROSCO_ci.ControllerInterface(lib_name,param_filename=param_filename,sim_name='sim1') -# Load the simulator -sim_1 = ROSCO_sim.Sim(turbine,controller_int) + # Load the simulator + sim_1 = ROSCO_sim.Sim(turbine,controller_int) -# Define a wind speed history -dt = 0.025 -tlen = 1000 # length of time to simulate (s) -ws0 = 7 # 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 + # Define a wind speed history + dt = 0.025 + tlen = 1000 # length of time to simulate (s) + ws0 = 7 # 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 and plot results -sim_1.sim_ws_series(t,ws,rotor_rpm_init=4) + # Run simulator and plot results + sim_1.sim_ws_series(t,ws,rotor_rpm_init=4) -# Load controller library again to see if we deallocated properly -controller_int = ROSCO_ci.ControllerInterface(lib_name,param_filename=param_filename,sim_name='sim_2') + # Load controller library again to see if we deallocated properly + controller_int = ROSCO_ci.ControllerInterface(lib_name,param_filename=param_filename,sim_name='sim_2') -# Run simulator again and plot results -sim_2 = ROSCO_sim.Sim(turbine,controller_int) -sim_2.sim_ws_series(t,ws,rotor_rpm_init=4) + # Run simulator again and plot results + sim_2 = ROSCO_sim.Sim(turbine,controller_int) + sim_2.sim_ws_series(t,ws,rotor_rpm_init=4) -# Check if simulations are equal -np.testing.assert_almost_equal(sim_1.gen_speed,sim_2.gen_speed) + # Check if simulations are equal + np.testing.assert_almost_equal(sim_1.gen_speed,sim_2.gen_speed) -if False: - plt.show() -else: - plt.savefig(os.path.join(example_out_dir,'04_NREL5MW_SimpSim.png')) + if False: + plt.show() + else: + plt.savefig(os.path.join(example_out_dir,'04_NREL5MW_SimpSim.png')) diff --git a/Examples/05_openfast_sim.py b/Examples/05_openfast_sim.py index 3a45d40d..c552f6d7 100644 --- a/Examples/05_openfast_sim.py +++ b/Examples/05_openfast_sim.py @@ -1,15 +1,18 @@ -''' ------------ 05_openfast_sim -------------- +""" +05_openfast_sim +--------------- Load a turbine, tune a controller, run OpenFAST simulation -------------------------------------- - In this example: - - Load a turbine from OpenFAST - - Tune a controller - - Run an OpenFAST simulation -Note - you will need to have a compiled controller in ROSCO/build/ -''' +* Load a turbine from OpenFAST +* Tune a controller +* Run an OpenFAST simulation + +Note + +* you will need to have a compiled controller in ROSCO/build/ +""" + # Python Modules #import yaml import os @@ -21,48 +24,47 @@ from rosco.toolbox.utilities import write_DISCON, run_openfast from rosco.toolbox.inputs.validation import load_rosco_yaml +def main(): + this_dir = os.path.dirname(os.path.abspath(__file__)) + tune_dir = os.path.join(this_dir,'Tune_Cases') + example_out_dir = os.path.join(this_dir,'examples_out') -this_dir = os.path.dirname(os.path.abspath(__file__)) -tune_dir = os.path.join(this_dir,'Tune_Cases') -example_out_dir = os.path.join(this_dir,'examples_out') - -# Load yaml file -parameter_filename = os.path.join(tune_dir, 'IEA15MW_MultiOmega.yaml') -inps = load_rosco_yaml(parameter_filename) -path_params = inps['path_params'] -turbine_params = inps['turbine_params'] -controller_params = inps['controller_params'] - -# Instantiate turbine, controller, and file processing classes -turbine = ROSCO_turbine.Turbine(turbine_params) -controller = ROSCO_controller.Controller(controller_params) + # Load yaml file + parameter_filename = os.path.join(tune_dir, 'IEA15MW_MultiOmega.yaml') + inps = load_rosco_yaml(parameter_filename) + path_params = inps['path_params'] + turbine_params = inps['turbine_params'] + controller_params = inps['controller_params'] -# Load turbine data from OpenFAST and rotor performance text file -turbine.load_from_fast( - path_params['FAST_InputFile'], - os.path.join(tune_dir,path_params['FAST_directory']), - rot_source='txt', - txt_filename=os.path.join(tune_dir,path_params['rotor_performance_filename']) - ) - -# Tune controller -controller.tune_controller(turbine) + # Instantiate turbine, controller, and file processing classes + turbine = ROSCO_turbine.Turbine(turbine_params) + controller = ROSCO_controller.Controller(controller_params) -# Write parameter input file -param_file = os.path.join(this_dir,'DISCON.IN') # This must be named DISCON.IN to be seen by the compiled controller binary. -write_DISCON(turbine,controller,param_file=param_file, txt_filename=path_params['rotor_performance_filename']) - -# Run OpenFAST -# --- May need to change fastcall if you use a non-standard, conda-installed command to call openfast -# If you run the `fastcall` from the command line where you run this script, it should run OpenFAST -fastcall = 'openfast' -run_openfast( - os.path.join(tune_dir,path_params['FAST_directory']), - fastcall=fastcall, - fastfile=path_params['FAST_InputFile'], - chdir=True - ) + # Load turbine data from OpenFAST and rotor performance text file + turbine.load_from_fast( + path_params['FAST_InputFile'], + os.path.join(tune_dir,path_params['FAST_directory']), + rot_source='txt', + txt_filename=os.path.join(tune_dir,path_params['rotor_performance_filename']) + ) + # Tune controller + controller.tune_controller(turbine) + # Write parameter input file + param_file = os.path.join(this_dir,'DISCON.IN') # This must be named DISCON.IN to be seen by the compiled controller binary. + write_DISCON(turbine,controller,param_file=param_file, txt_filename=path_params['rotor_performance_filename']) + # Run OpenFAST + # --- May need to change fastcall if you use a non-standard, conda-installed command to call openfast + # If you run the `fastcall` from the command line where you run this script, it should run OpenFAST + fastcall = 'openfast' + run_openfast( + os.path.join(tune_dir,path_params['FAST_directory']), + fastcall=fastcall, + fastfile=path_params['FAST_InputFile'], + chdir=True + ) +if __name__ == "__main__": + main() \ No newline at end of file diff --git a/Examples/06_peak_shaving.py b/Examples/06_peak_shaving.py index 9bfa5228..2edfb3e5 100644 --- a/Examples/06_peak_shaving.py +++ b/Examples/06_peak_shaving.py @@ -1,14 +1,14 @@ -''' ------------ 06_peak_shavings -------------- +""" +06_peak_shavings +---------------- Load saved turbine, tune controller, plot minimum pitch schedule -------------------------------------- - In this example: - - Load a yaml file - - Load a turbine from openfast - - Tune a controller - - Plot minimum pitch schedule -''' + +* Load a yaml file +* Load a turbine from openfast +* Tune a controller +* Plot minimum pitch schedule +""" # Python modules import matplotlib.pyplot as plt @@ -18,46 +18,49 @@ from rosco.toolbox import turbine as ROSCO_turbine from rosco.toolbox.inputs.validation import load_rosco_yaml +def main(): + this_dir = os.path.dirname(__file__) + tune_dir = os.path.join(this_dir,'Tune_Cases') + example_out_dir = os.path.join(this_dir,'examples_out') + if not os.path.isdir(example_out_dir): + os.makedirs(example_out_dir) + + # Load yaml file + parameter_filename = os.path.join(tune_dir,'NREL5MW.yaml') + inps = load_rosco_yaml(parameter_filename) + path_params = inps['path_params'] + turbine_params = inps['turbine_params'] + controller_params = inps['controller_params'] + + # Ensure minimum generator speed at 50 rpm (for example's sake), turn on peak shaving and cp-maximizing min pitch + controller_params['vs_minspd'] = 50/97 + controller_params['PS_Mode'] = 3 + + # Instantiate turbine, controller, and file processing classes + turbine = ROSCO_turbine.Turbine(turbine_params) + controller = ROSCO_controller.Controller(controller_params) + + # Load turbine data from OpenFAST and rotor performance text file + turbine.load_from_fast( + path_params['FAST_InputFile'], + os.path.join(tune_dir,path_params['FAST_directory']), + rot_source='txt',txt_filename=os.path.join(tune_dir,path_params['rotor_performance_filename']) + ) + # Tune controller + controller.tune_controller(turbine) + + # Plot minimum pitch schedule + fig, ax = plt.subplots(1,1) + ax.plot(controller.v, controller.pitch_op,label='Steady State Operation') + ax.plot(controller.v, controller.ps_min_bld_pitch, label='Minimum Pitch Schedule') + ax.legend() + ax.set_xlabel('Wind speed (m/s)') + ax.set_ylabel('Blade pitch (rad)') + + if False: + plt.show() + else: + plt.savefig(os.path.join(example_out_dir,'06_MinPitch.png')) -this_dir = os.path.dirname(__file__) -tune_dir = os.path.join(this_dir,'Tune_Cases') -example_out_dir = os.path.join(this_dir,'examples_out') -if not os.path.isdir(example_out_dir): - os.makedirs(example_out_dir) - -# Load yaml file -parameter_filename = os.path.join(tune_dir,'NREL5MW.yaml') -inps = load_rosco_yaml(parameter_filename) -path_params = inps['path_params'] -turbine_params = inps['turbine_params'] -controller_params = inps['controller_params'] - -# Ensure minimum generator speed at 50 rpm (for example's sake), turn on peak shaving and cp-maximizing min pitch -controller_params['vs_minspd'] = 50/97 -controller_params['PS_Mode'] = 3 - -# Instantiate turbine, controller, and file processing classes -turbine = ROSCO_turbine.Turbine(turbine_params) -controller = ROSCO_controller.Controller(controller_params) - -# Load turbine data from OpenFAST and rotor performance text file -turbine.load_from_fast( - path_params['FAST_InputFile'], - os.path.join(tune_dir,path_params['FAST_directory']), - rot_source='txt',txt_filename=os.path.join(tune_dir,path_params['rotor_performance_filename']) - ) -# Tune controller -controller.tune_controller(turbine) - -# Plot minimum pitch schedule -fig, ax = plt.subplots(1,1) -ax.plot(controller.v, controller.pitch_op,label='Steady State Operation') -ax.plot(controller.v, controller.ps_min_bld_pitch, label='Minimum Pitch Schedule') -ax.legend() -ax.set_xlabel('Wind speed (m/s)') -ax.set_ylabel('Blade pitch (rad)') - -if False: - plt.show() -else: - plt.savefig(os.path.join(example_out_dir,'06_MinPitch.png')) +if __name__ == "__main__": + main() diff --git a/Examples/07_openfast_outputs.py b/Examples/07_openfast_outputs.py index ed19bc63..f92f7125 100644 --- a/Examples/07_openfast_outputs.py +++ b/Examples/07_openfast_outputs.py @@ -1,15 +1,15 @@ -''' ------------ 07_openfast_outputss -------------- +""" +07_openfast_outputs +------------------- Plot some OpenFAST output data -------------------------------------- - In this example: - - Load openfast output data - - Trim the time series - - Plot some available channels + +* Load openfast output data +* Trim the time series +* Plot some available channels Note: need to run openfast model in 'Test_Cases/5MW_Land_DLL_WTurb/' to plot -''' +""" # Python Modules #import numpy as np @@ -18,37 +18,39 @@ from rosco.toolbox.ofTools.fast_io import output_processing import os -this_dir = os.path.dirname(os.path.abspath(__file__)) -example_out_dir = os.path.join(this_dir,'examples_out') -if not os.path.isdir(example_out_dir): - os.makedirs(example_out_dir) - -# Define openfast output filenames -filenames = ["Test_Cases/IEA-15-240-RWT-UMaineSemi/IEA-15-240-RWT-UMaineSemi.outb"] -# ---- Note: Could load and plot multiple cases, textfiles, and binaries... -# filenames = ["../Test_Cases/NREL-5MW/NREL-5MW.outb", -# "../Test_Cases/NREL-5MW/NREL-5MW_ex8.outb"] +def main(): + this_dir = os.path.dirname(os.path.abspath(__file__)) + example_out_dir = os.path.join(this_dir,'examples_out') + if not os.path.isdir(example_out_dir): + os.makedirs(example_out_dir) -filenames = [os.path.join(this_dir,file) for file in filenames] + # Define openfast output filenames + filenames = ["Test_Cases/IEA-15-240-RWT-UMaineSemi/IEA-15-240-RWT-UMaineSemi.outb"] + # ---- Note: Could load and plot multiple cases, textfiles, and binaries... + # filenames = ["../Test_Cases/NREL-5MW/NREL-5MW.outb", + # "../Test_Cases/NREL-5MW/NREL-5MW_ex8.outb"] -# Define Plot cases -# --- Comment,uncomment, create, and change these as desired... -cases = {} -cases['Baseline'] = ['Wind1VelX', 'BldPitch1', 'GenTq', 'RotSpeed'] -# cases['Rotor'] = ['BldPitch1', 'GenTq', 'GenPwr'] -# cases['Platform Motion'] = ['PtfmSurge', 'PtfmSway', 'PtfmHeave', 'PtfmPitch','PtfmRoll','PtfmYaw'] + filenames = [os.path.join(this_dir,file) for file in filenames] + # Define Plot cases + # --- Comment,uncomment, create, and change these as desired... + cases = {} + cases['Baseline'] = ['Wind1VelX', 'BldPitch1', 'GenTq', 'RotSpeed'] + # cases['Rotor'] = ['BldPitch1', 'GenTq', 'GenPwr'] + # cases['Platform Motion'] = ['PtfmSurge', 'PtfmSway', 'PtfmHeave', 'PtfmPitch','PtfmRoll','PtfmYaw'] -# Instantiate fast_IO -fast_out = output_processing.output_processing() -# Can also do: -# fast_out = output_processing.output_processing(filenames=filenames, cases=cases) -# fast_out.plot_fast_out() -# Load and plot -fastout = fast_out.load_fast_out(filenames) -fast_out.plot_fast_out(cases=cases,showplot=False) + # Instantiate fast_IO + fast_out = output_processing.output_processing() + # Can also do: + # fast_out = output_processing.output_processing(filenames=filenames, cases=cases) + # fast_out.plot_fast_out() -plt.savefig(os.path.join(example_out_dir,'07_IEA-15MW_Semi_Out.png')) + # Load and plot + fastout = fast_out.load_fast_out(filenames) + fast_out.plot_fast_out(cases=cases,showplot=False) + plt.savefig(os.path.join(example_out_dir,'07_IEA-15MW_Semi_Out.png')) +if __name__ == "__main__": + main() diff --git a/Examples/08_run_turbsim.py b/Examples/08_run_turbsim.py index bbacb93e..321b3776 100644 --- a/Examples/08_run_turbsim.py +++ b/Examples/08_run_turbsim.py @@ -1,23 +1,27 @@ -''' ------------ 08_run_turbsim -------------- +""" +08_run_turbsim +-------------- Run TurbSim to create wind field binary -------------------------------------- - In this example: - - Leverage the run_openfast functionality to compile a turbsim binary -''' + +* Leverage the run_openfast functionality to compile a turbsim binary +""" # ROSCO toolbox modules from rosco.toolbox.utilities import run_openfast import os -this_dir = os.path.dirname(os.path.abspath(__file__)) +def main(): + this_dir = os.path.dirname(os.path.abspath(__file__)) + + # Define openfast output filenames + wind_directory = os.path.join(this_dir,'Test_Cases/Wind/') + turbsim_infile = '90m_12mps_twr.inp' -# Define openfast output filenames -wind_directory = os.path.join(this_dir,'Test_Cases/Wind/') -turbsim_infile = '90m_12mps_twr.inp' + run_openfast(wind_directory, fastcall='turbsim', + fastfile=os.path.join(wind_directory, turbsim_infile), chdir=False) -run_openfast(wind_directory, fastcall='turbsim', - fastfile=os.path.join(wind_directory, turbsim_infile), chdir=False) + print('test') -print('test') +if __name__ == "__main__": + main() diff --git a/Examples/09_distributed_aero.py b/Examples/09_distributed_aero.py index 810de3f2..322e909b 100644 --- a/Examples/09_distributed_aero.py +++ b/Examples/09_distributed_aero.py @@ -1,19 +1,19 @@ -''' ------------ 09_distributed_aero -------------- +""" +09_distributed_aero +------------------- Tune a controller for distributed aerodynamic control -------------------------------------- - In this example: -- Read .yaml input file -- Load an openfast turbine model -- Read text file with rotor performance properties -- Load blade information -- Tune controller with flap actuator -Note: You will need a turbine model with DAC capabilites in order to run this. - The curious user can contact Nikhar Abbas (nikhar.abbas@nrel.gov) for available - models, if they do not have any themselves. -''' +* Read .yaml input file +* Load an openfast turbine model +* Read text file with rotor performance properties +* Load blade information +* Tune controller with flap actuator + +Note + +* You will need a turbine model with DAC capabilites in order to run this. The curious user can contact Nikhar Abbas (nikhar.abbas@nrel.gov) for available models, if they do not have any themselves. +""" # Python Modules import os @@ -22,28 +22,31 @@ from rosco.toolbox import controller as ROSCO_controller from rosco.toolbox.inputs.validation import load_rosco_yaml - -this_dir = os.path.dirname(os.path.abspath(__file__)) -tune_dir = os.path.join(this_dir,'Tune_Cases') - -# Load yaml file -parameter_filename = os.path.join(tune_dir,'BAR.yaml') -inps = load_rosco_yaml(parameter_filename) -path_params = inps['path_params'] -turbine_params = inps['turbine_params'] -controller_params = inps['controller_params'] - -# Load turbine data from openfast model -turbine = ROSCO_turbine.Turbine(turbine_params) -turbine.load_from_fast( - path_params['FAST_InputFile'], - os.path.join(tune_dir,path_params['FAST_directory']) - ) - -# Tune controller -controller = ROSCO_controller.Controller(controller_params) -controller.tune_controller(turbine) - -print('Flap PI gains:') -print('Kp_flap = {}'.format(controller.Kp_flap[-1])) -print('Ki_flap = {}'.format(controller.Ki_flap[-1])) +def main(): + this_dir = os.path.dirname(os.path.abspath(__file__)) + tune_dir = os.path.join(this_dir,'Tune_Cases') + + # Load yaml file + parameter_filename = os.path.join(tune_dir,'BAR.yaml') + inps = load_rosco_yaml(parameter_filename) + path_params = inps['path_params'] + turbine_params = inps['turbine_params'] + controller_params = inps['controller_params'] + + # Load turbine data from openfast model + turbine = ROSCO_turbine.Turbine(turbine_params) + turbine.load_from_fast( + path_params['FAST_InputFile'], + os.path.join(tune_dir,path_params['FAST_directory']) + ) + + # Tune controller + controller = ROSCO_controller.Controller(controller_params) + controller.tune_controller(turbine) + + print('Flap PI gains:') + print('Kp_flap = {}'.format(controller.Kp_flap[-1])) + print('Ki_flap = {}'.format(controller.Ki_flap[-1])) + +if __name__ == "__main__": + main() \ No newline at end of file diff --git a/Examples/10_linear_params.py b/Examples/10_linear_params.py index dc09aba6..95f9ff8a 100644 --- a/Examples/10_linear_params.py +++ b/Examples/10_linear_params.py @@ -1,14 +1,15 @@ -''' ------------ 10_linear_params -------------- -Load a turbine, tune a controller, export linear model -------------------------------------- +""" +10_linear_params +---------------- +Load a turbine, tune a controller, export linear model In this example: - - Load a turbine from OpenFAST - - Tune a controller - - Use tuning parameters to export linear model -''' +* Load a turbine from OpenFAST +* Tune a controller +* Use tuning parameters to export linear model +""" + # Python Modules import os # ROSCO toolbox modules @@ -16,69 +17,73 @@ from rosco.toolbox import turbine as ROSCO_turbine from rosco.toolbox.inputs.validation import load_rosco_yaml - import numpy as np -this_dir = os.path.dirname(os.path.abspath(__file__)) -tune_dir = os.path.join(this_dir,'Tune_Cases') +def main(): + + this_dir = os.path.dirname(os.path.abspath(__file__)) + tune_dir = os.path.join(this_dir,'Tune_Cases') + + # Load yaml file + parameter_filename = os.path.join( tune_dir, 'IEA15MW.yaml') + inps = load_rosco_yaml(parameter_filename) + path_params = inps['path_params'] + turbine_params = inps['turbine_params'] + controller_params = inps['controller_params'] -# Load yaml file -parameter_filename = os.path.join( tune_dir, 'IEA15MW.yaml') -inps = load_rosco_yaml(parameter_filename) -path_params = inps['path_params'] -turbine_params = inps['turbine_params'] -controller_params = inps['controller_params'] + # Linear file output -# Linear file output + os.path.join(this_dir,path_params['FAST_directory']) + example_out_dir = os.path.join(this_dir,'examples_out') + if not os.path.isdir(example_out_dir): + os.makedirs(example_out_dir) -os.path.join(this_dir,path_params['FAST_directory']) -example_out_dir = os.path.join(this_dir,'examples_out') -if not os.path.isdir(example_out_dir): - os.makedirs(example_out_dir) + linmod_filename = os.path.join(example_out_dir,'10_IEA15MW_LinMod.dat') -linmod_filename = os.path.join(example_out_dir,'10_IEA15MW_LinMod.dat') + # Instantiate turbine, controller, and file processing classes + turbine = ROSCO_turbine.Turbine(turbine_params) + controller = ROSCO_controller.Controller(controller_params) -# Instantiate turbine, controller, and file processing classes -turbine = ROSCO_turbine.Turbine(turbine_params) -controller = ROSCO_controller.Controller(controller_params) + # Load turbine data from OpenFAST and rotor performance text file + turbine.load_from_fast( + path_params['FAST_InputFile'], + os.path.join(tune_dir,path_params['FAST_directory']), + rot_source='txt', + txt_filename=os.path.join(tune_dir,path_params['rotor_performance_filename']) + ) -# Load turbine data from OpenFAST and rotor performance text file -turbine.load_from_fast( - path_params['FAST_InputFile'], - os.path.join(tune_dir,path_params['FAST_directory']), - rot_source='txt', - txt_filename=os.path.join(tune_dir,path_params['rotor_performance_filename']) - ) + # Tune controller + controller.tune_controller(turbine) -# Tune controller -controller.tune_controller(turbine) + # Write Linear model parameters to text file for matlab processing + # Add to ROSCO_utilities.FileProcessing() when finished -# Write Linear model parameters to text file for matlab processing -# Add to ROSCO_utilities.FileProcessing() when finished + print('Writing linear models to text file: ' + linmod_filename) -print('Writing linear models to text file: ' + linmod_filename) + # extend gain schedule -# extend gain schedule + pc_br = np.zeros(len(controller.v_below_rated)) + pc_Kp = np.concatenate((pc_br,controller.pc_gain_schedule.Kp)) + pc_Ki = np.concatenate((pc_br,controller.pc_gain_schedule.Ki)) -pc_br = np.zeros(len(controller.v_below_rated)) -pc_Kp = np.concatenate((pc_br,controller.pc_gain_schedule.Kp)) -pc_Ki = np.concatenate((pc_br,controller.pc_gain_schedule.Ki)) + vs_ar = np.zeros(len(controller.pc_gain_schedule.Kp)) + vs_Kp = np.concatenate((controller.vs_gain_schedule.Kp,vs_ar)) + vs_Ki = np.concatenate((controller.vs_gain_schedule.Ki,vs_ar)) -vs_ar = np.zeros(len(controller.pc_gain_schedule.Kp)) -vs_Kp = np.concatenate((controller.vs_gain_schedule.Kp,vs_ar)) -vs_Ki = np.concatenate((controller.vs_gain_schedule.Ki,vs_ar)) + with open(linmod_filename,'w') as f: + f.write('{:12}\t{:12}\t{:12}\t{:12}\t{:12}\t{:12}\t{:12}\t{:12}\t{:12}\t{:12}\t{:12}\t{:12}\n'.\ + format('WindSpeed','A_om','b_theta','b_tau','b_wind','pc_Kp','pc_Ki','vs_Kp','vs_Ki','Pi_omega','Pi_theta','Pi_wind')) -with open(linmod_filename,'w') as f: - f.write('{:12}\t{:12}\t{:12}\t{:12}\t{:12}\t{:12}\t{:12}\t{:12}\t{:12}\t{:12}\t{:12}\t{:12}\n'.\ - format('WindSpeed','A_om','b_theta','b_tau','b_wind','pc_Kp','pc_Ki','vs_Kp','vs_Ki','Pi_omega','Pi_theta','Pi_wind')) + for v,A,B_beta,B_tau,B_wind,pc_Kp,pc_Ki,vs_Kp,vs_Ki,Pi_omega,Pi_beta,Pi_wind in zip(controller.v,controller.A,controller.B_beta,controller.B_tau, controller.B_wind, \ + pc_Kp, pc_Ki, vs_Kp, vs_Ki, \ + controller.Pi_omega, controller.Pi_beta, controller.Pi_wind): + f.write('{:12.4e}\t{:12.4e}\t{:12.4e}\t{:12.4e}\t{:12.4e}\t{:12.4e}\t{:12.4e}\t{:12.4e}\t{:12.4e}\t{:12.4e}\t{:12.4e}\t{:12.4e}\n'\ + .format(v,A,B_beta,B_tau,B_wind,pc_Kp,pc_Ki,vs_Kp,vs_Ki,Pi_omega,Pi_beta,Pi_wind)) - for v,A,B_beta,B_tau,B_wind,pc_Kp,pc_Ki,vs_Kp,vs_Ki,Pi_omega,Pi_beta,Pi_wind in zip(controller.v,controller.A,controller.B_beta,controller.B_tau, controller.B_wind, \ - pc_Kp, pc_Ki, vs_Kp, vs_Ki, \ - controller.Pi_omega, controller.Pi_beta, controller.Pi_wind): - f.write('{:12.4e}\t{:12.4e}\t{:12.4e}\t{:12.4e}\t{:12.4e}\t{:12.4e}\t{:12.4e}\t{:12.4e}\t{:12.4e}\t{:12.4e}\t{:12.4e}\t{:12.4e}\n'\ - .format(v,A,B_beta,B_tau,B_wind,pc_Kp,pc_Ki,vs_Kp,vs_Ki,Pi_omega,Pi_beta,Pi_wind)) + print('Tower Height = {} m'.format(turbine.hubHt)) + print('Platform Freq. = {} rad/s'.format(controller.ptfm_freq)) -print('Tower Height = {} m'.format(turbine.hubHt)) -print('Platform Freq. = {} rad/s'.format(controller.ptfm_freq)) +if __name__ == "__main__": + main() diff --git a/Examples/11_robust_tuning.py b/Examples/11_robust_tuning.py index 171968ae..d5c31fda 100644 --- a/Examples/11_robust_tuning.py +++ b/Examples/11_robust_tuning.py @@ -1,20 +1,22 @@ -''' ------------ 11_robust_tuning -------------- +""" +11_robust_tuning +---------------- Controller tuning to satisfy a robustness criteria -------------------------------------- -NOTE: This example necessitates the mbc3 through either pyFAST or WEIS + +Note that this example necessitates the mbc3 through either pyFAST or WEIS pyFAST is the easiest to install by cloning https://github.com/OpenFAST/openfast_toolbox and -running `python setup.py develop` from your conda environment +running ``python setup.py develop`` from your conda environment In this example: - - setup ROSCO's robust tuning methods for the IEA15MW on the UMaine Semi-sub - - run a the standard tuning method to find k_float - - run robust tuning to find omega_pc schedule satisfy a prescribed stability margin - - Tune ROSCO's pitch controller using omega_pc schedule - - Plot gain schedule + +* setup ROSCO's robust tuning methods for the IEA15MW on the UMaine Semi-sub +* run a the standard tuning method to find k_float +* run robust tuning to find omega_pc schedule satisfy a prescribed stability margin +* Tune ROSCO's pitch controller using omega_pc schedule +* Plot gain schedule The example is put in a function call to show the ability to load linear models in parallel -''' +""" import os import numpy as np import matplotlib.pyplot as plt diff --git a/Examples/12_tune_ipc.py b/Examples/12_tune_ipc.py index 6bb5b9e8..028407c8 100644 --- a/Examples/12_tune_ipc.py +++ b/Examples/12_tune_ipc.py @@ -1,14 +1,14 @@ -''' ------------ 12_tune_ipc -------------- +""" +12_tune_ipc +-------------- Load a turbine, tune a controller with IPC -------------------------------------- - In this example: - - Load a turbine from OpenFAST - - Tune a controller with IPC - - Run simple simulation with open loop control -''' +* Load a turbine from OpenFAST +* Tune a controller with IPC +* Run simple simulation with open loop control +""" + # Python Modules import os import matplotlib.pyplot as plt diff --git a/Examples/14_open_loop_control.py b/Examples/14_open_loop_control.py index 862b6306..2b895940 100644 --- a/Examples/14_open_loop_control.py +++ b/Examples/14_open_loop_control.py @@ -1,15 +1,15 @@ -''' ------------ 14_open_loop_control -------------- +""" +14_open_loop_control +-------------------- Load a turbine, tune a controller with open loop control commands -------------------------------------- - In this example: - - Load a turbine from OpenFAST - - Tune a controller - - Write open loop inputs - - Run simple simulation with open loop control -''' +* Load a turbine from OpenFAST +* Tune a controller +* Write open loop inputs +* Run simple simulation with open loop control +""" + # Python Modules import os import numpy as np @@ -26,138 +26,139 @@ from rosco.toolbox.ofTools.case_gen.runFAST_pywrapper import runFAST_pywrapper, runFAST_pywrapper_batch from rosco.toolbox.ofTools.case_gen.CaseGen_General import CaseGen_General - - -this_dir = os.path.dirname(os.path.abspath(__file__)) -tune_dir = os.path.join(this_dir,'Tune_Cases') - -rosco_dir = os.path.dirname(this_dir) -example_out_dir = os.path.join(this_dir,'examples_out') -example_out_dir = os.path.join(this_dir,'examples_out') -if not os.path.isdir(example_out_dir): - os.makedirs(example_out_dir) - -# Load yaml file (Open Loop Case) -parameter_filename = os.path.join(tune_dir, 'IEA15MW_OL.yaml') - -inps = load_rosco_yaml(parameter_filename) -path_params = inps['path_params'] -turbine_params = inps['turbine_params'] -controller_params = inps['controller_params'] - -# Set up open loop input -olc = ROSCO_controller.OpenLoopControl(t_max=20) -olc.interp_timeseries( - 'blade_pitch', - [0,20], - [0,0.0873] , - 'sigma' - ) -olc.const_timeseries( - 'generator_torque', - 19624046*.5 - ) -olc.sine_timeseries('nacelle_yaw', 0.0524, 60) - -# Plot open loop timeseries -fig,ax = olc.plot_timeseries() -if False: - plt.show() -else: - fig.savefig(os.path.join(example_out_dir,'14_OL_Inputs.png')) - -# Write open loop input, get OL indices -ol_filename = os.path.join(example_out_dir,'14_OL_Input.dat') -ol_dict = olc.write_input(ol_filename) -controller_params['open_loop'] = ol_dict - - -# Instantiate turbine, controller, and file processing classes -turbine = ROSCO_turbine.Turbine(turbine_params) -controller = ROSCO_controller.Controller(controller_params) - -# Load turbine data from OpenFAST and rotor performance text file -turbine.load_from_fast(path_params['FAST_InputFile'], \ - os.path.join(tune_dir,path_params['FAST_directory']), \ - rot_source='txt',\ - txt_filename=os.path.join(tune_dir,path_params['rotor_performance_filename'])) - -# Tune controller -controller.tune_controller(turbine) - -# Write parameter input file -param_file = os.path.join(this_dir,'DISCON.IN') # This must be named DISCON.IN to be seen by the compiled controller binary. -ROSCO_utilities.write_DISCON(turbine,controller,param_file=param_file, txt_filename=path_params['rotor_performance_filename']) - -### Run OpenFAST using aeroelasticse tools -case_inputs = {} -case_inputs[('ServoDyn','DLL_FileName')] = {'vals': [discon_lib_path], 'group': 0} - -# Apply all discon variables as case inputs -discon_vt = ROSCO_utilities.DISCON_dict( - turbine, -controller, -txt_filename=os.path.join(tune_dir,path_params['FAST_directory'],path_params['rotor_performance_filename']) -) -for discon_input in discon_vt: - case_inputs[('DISCON_in',discon_input)] = {'vals': [discon_vt[discon_input]], 'group': 0} - -case_inputs[('Fst','TMax')] = {'vals': [20], 'group': 0} -case_inputs[('InflowWind','HWindSpeed')] = {'vals': [10], 'group': 0} -case_inputs[('ElastoDyn','HWindSpeed')] = {'vals': [5.], 'group': 0} -case_inputs[('DISCON_in','LoggingLevel')] = {'vals': [3], 'group': 0} - -# Generate cases -run_dir = os.path.join(example_out_dir,'14_OL_Sim') -if not os.path.exists(run_dir): - os.makedirs(run_dir) - -case_list, case_name_list = CaseGen_General(case_inputs, dir_matrix=run_dir, namebase='OL_Example') -channels = set_channels() - -# Run FAST cases -fastBatch = runFAST_pywrapper_batch() - -fastBatch.FAST_directory = os.path.realpath(os.path.join(tune_dir,path_params['FAST_directory'])) -fastBatch.FAST_InputFile = path_params['FAST_InputFile'] -fastBatch.channels = channels -fastBatch.FAST_runDirectory = run_dir -fastBatch.case_list = case_list -fastBatch.case_name_list = case_name_list -fastBatch.debug_level = 2 -fastBatch.FAST_exe = 'openfast' - -fastBatch.run_serial() - - -# # Define Plot cases -cases = {} -cases['Baseline'] = ['Wind1VelX', 'BldPitch1', 'GenTq', 'RotSpeed','NacYaw'] - -out_file = os.path.join(example_out_dir,'14_OL_Sim/OL_Example_0.outb') -op = output_processing.output_processing() -fastout = op.load_fast_out(out_file, tmin=0) -fig, ax = op.plot_fast_out(cases=cases,showplot=False) - -# Check that open loop commands are close to control outputs from OpenFAST -fo = fastout[0] -tt = fo['Time'] -valid_ind = tt > 2 # first few timesteps can differ, depending on OpenFAST solve config - -# Compute errors -nacelle_yaw_diff = fo['NacYaw'][valid_ind] - np.degrees(np.interp(tt[valid_ind],olc.ol_timeseries['time'],olc.ol_timeseries['nacelle_yaw'])) -bld_pitch_diff = fo['BldPitch1'][valid_ind] - np.degrees(np.interp(tt[valid_ind],olc.ol_timeseries['time'],olc.ol_timeseries['blade_pitch'])) -gen_tq_diff = fo['GenTq'][valid_ind] - np.interp(tt[valid_ind],olc.ol_timeseries['time'],olc.ol_timeseries['generator_torque'])/1e3 - -# Check diff timeseries -np.testing.assert_allclose(nacelle_yaw_diff, 0, atol = 1e-1) # yaw has dynamics and integration error, tolerance higher -np.testing.assert_allclose(bld_pitch_diff, 0, atol = 1e-3) -np.testing.assert_allclose(gen_tq_diff, 0, atol = 1e-3) - - -if False: - plt.show() -else: - fig[0].savefig(os.path.join(example_out_dir,'14_OL_FAST_Out.png')) - +def main(): + this_dir = os.path.dirname(os.path.abspath(__file__)) + tune_dir = os.path.join(this_dir,'Tune_Cases') + + rosco_dir = os.path.dirname(this_dir) + example_out_dir = os.path.join(this_dir,'examples_out') + example_out_dir = os.path.join(this_dir,'examples_out') + if not os.path.isdir(example_out_dir): + os.makedirs(example_out_dir) + + # Load yaml file (Open Loop Case) + parameter_filename = os.path.join(tune_dir, 'IEA15MW_OL.yaml') + + inps = load_rosco_yaml(parameter_filename) + path_params = inps['path_params'] + turbine_params = inps['turbine_params'] + controller_params = inps['controller_params'] + + # Set up open loop input + olc = ROSCO_controller.OpenLoopControl(t_max=20) + olc.interp_timeseries( + 'blade_pitch', + [0,20], + [0,0.0873] , + 'sigma' + ) + olc.const_timeseries( + 'generator_torque', + 19624046*.5 + ) + olc.sine_timeseries('nacelle_yaw', 0.0524, 60) + + # Plot open loop timeseries + fig,ax = olc.plot_timeseries() + if False: + plt.show() + else: + fig.savefig(os.path.join(example_out_dir,'14_OL_Inputs.png')) + + # Write open loop input, get OL indices + ol_filename = os.path.join(example_out_dir,'14_OL_Input.dat') + ol_dict = olc.write_input(ol_filename) + controller_params['open_loop'] = ol_dict + + + # Instantiate turbine, controller, and file processing classes + turbine = ROSCO_turbine.Turbine(turbine_params) + controller = ROSCO_controller.Controller(controller_params) + + # Load turbine data from OpenFAST and rotor performance text file + turbine.load_from_fast(path_params['FAST_InputFile'], \ + os.path.join(tune_dir,path_params['FAST_directory']), \ + rot_source='txt',\ + txt_filename=os.path.join(tune_dir,path_params['rotor_performance_filename'])) + + # Tune controller + controller.tune_controller(turbine) + + # Write parameter input file + param_file = os.path.join(this_dir,'DISCON.IN') # This must be named DISCON.IN to be seen by the compiled controller binary. + ROSCO_utilities.write_DISCON(turbine,controller,param_file=param_file, txt_filename=path_params['rotor_performance_filename']) + + ### Run OpenFAST using aeroelasticse tools + case_inputs = {} + case_inputs[('ServoDyn','DLL_FileName')] = {'vals': [discon_lib_path], 'group': 0} + + # Apply all discon variables as case inputs + discon_vt = ROSCO_utilities.DISCON_dict( + turbine, + controller, + txt_filename=os.path.join(tune_dir,path_params['FAST_directory'],path_params['rotor_performance_filename']) + ) + for discon_input in discon_vt: + case_inputs[('DISCON_in',discon_input)] = {'vals': [discon_vt[discon_input]], 'group': 0} + + case_inputs[('Fst','TMax')] = {'vals': [20], 'group': 0} + case_inputs[('InflowWind','HWindSpeed')] = {'vals': [10], 'group': 0} + case_inputs[('ElastoDyn','HWindSpeed')] = {'vals': [5.], 'group': 0} + case_inputs[('DISCON_in','LoggingLevel')] = {'vals': [3], 'group': 0} + + # Generate cases + run_dir = os.path.join(example_out_dir,'14_OL_Sim') + if not os.path.exists(run_dir): + os.makedirs(run_dir) + + case_list, case_name_list = CaseGen_General(case_inputs, dir_matrix=run_dir, namebase='OL_Example') + channels = set_channels() + + # Run FAST cases + fastBatch = runFAST_pywrapper_batch() + + fastBatch.FAST_directory = os.path.realpath(os.path.join(tune_dir,path_params['FAST_directory'])) + fastBatch.FAST_InputFile = path_params['FAST_InputFile'] + fastBatch.channels = channels + fastBatch.FAST_runDirectory = run_dir + fastBatch.case_list = case_list + fastBatch.case_name_list = case_name_list + fastBatch.debug_level = 2 + fastBatch.FAST_exe = 'openfast' + + fastBatch.run_serial() + + + # # Define Plot cases + cases = {} + cases['Baseline'] = ['Wind1VelX', 'BldPitch1', 'GenTq', 'RotSpeed','NacYaw'] + + out_file = os.path.join(example_out_dir,'14_OL_Sim/OL_Example_0.outb') + op = output_processing.output_processing() + fastout = op.load_fast_out(out_file, tmin=0) + fig, ax = op.plot_fast_out(cases=cases,showplot=False) + + # Check that open loop commands are close to control outputs from OpenFAST + fo = fastout[0] + tt = fo['Time'] + valid_ind = tt > 2 # first few timesteps can differ, depending on OpenFAST solve config + + # Compute errors + nacelle_yaw_diff = fo['NacYaw'][valid_ind] - np.degrees(np.interp(tt[valid_ind],olc.ol_timeseries['time'],olc.ol_timeseries['nacelle_yaw'])) + bld_pitch_diff = fo['BldPitch1'][valid_ind] - np.degrees(np.interp(tt[valid_ind],olc.ol_timeseries['time'],olc.ol_timeseries['blade_pitch'])) + gen_tq_diff = fo['GenTq'][valid_ind] - np.interp(tt[valid_ind],olc.ol_timeseries['time'],olc.ol_timeseries['generator_torque'])/1e3 + + # Check diff timeseries + np.testing.assert_allclose(nacelle_yaw_diff, 0, atol = 1e-1) # yaw has dynamics and integration error, tolerance higher + np.testing.assert_allclose(bld_pitch_diff, 0, atol = 1e-3) + np.testing.assert_allclose(gen_tq_diff, 0, atol = 1e-3) + + + if False: + plt.show() + else: + fig[0].savefig(os.path.join(example_out_dir,'14_OL_FAST_Out.png')) + +if __name__ == "__main__": + main() diff --git a/Examples/15_pass_through.py b/Examples/15_pass_through.py index c0b7916d..c8e2e4c5 100644 --- a/Examples/15_pass_through.py +++ b/Examples/15_pass_through.py @@ -1,27 +1,24 @@ -''' ------------ 15_pass_through -------------- +""" +15_pass_through +--------------- Use the runFAST scripts to set up an example, use pass through in yaml -------------------------------------- - In this example: - - use run_FAST_ROSCO class to set up a test case -''' +* use run_FAST_ROSCO class to set up a test case +""" import os from rosco.toolbox.ofTools.case_gen.run_FAST import run_FAST_ROSCO from rosco.toolbox.ofTools.case_gen import CaseLibrary as cl - -#directories -this_dir = os.path.dirname(os.path.abspath(__file__)) -rosco_dir = os.path.dirname(this_dir) -example_out_dir = os.path.join(this_dir,'examples_out') -os.makedirs(example_out_dir,exist_ok=True) - - def main(): - # Simulation config + #directories + this_dir = os.path.dirname(os.path.abspath(__file__)) + rosco_dir = os.path.dirname(this_dir) + example_out_dir = os.path.join(this_dir,'examples_out') + os.makedirs(example_out_dir,exist_ok=True) + + # Simulation config r = run_FAST_ROSCO() parameter_filename = os.path.join(this_dir,'Tune_Cases/NREL5MW_PassThrough.yaml') diff --git a/Examples/16_external_dll.py b/Examples/16_external_dll.py index cb79ab07..381f2623 100644 --- a/Examples/16_external_dll.py +++ b/Examples/16_external_dll.py @@ -1,11 +1,9 @@ -''' ------------ 16_external_dll -------------- +""" +16_external_dll +--------------- Run openfast with ROSCO and external control interface -------------------------------------- - IEA-15MW will call NREL-5MW controller and read control inputs - -''' +""" import os, platform from rosco import discon_lib_path as lib_name @@ -14,14 +12,12 @@ import shutil -#directories -this_dir = os.path.dirname(os.path.abspath(__file__)) -rosco_dir = os.path.dirname(this_dir) -example_out_dir = os.path.join(this_dir,'examples_out') -os.makedirs(example_out_dir,exist_ok=True) - - def main(): + #directories + this_dir = os.path.dirname(os.path.abspath(__file__)) + rosco_dir = os.path.dirname(this_dir) + example_out_dir = os.path.join(this_dir,'examples_out') + os.makedirs(example_out_dir,exist_ok=True) # Make copy of libdiscon ext = lib_name.split('.')[-1] diff --git a/Examples/17a_zeromq_simple.py b/Examples/17a_zeromq_simple.py index 2ccae2be..e881964c 100644 --- a/Examples/17a_zeromq_simple.py +++ b/Examples/17a_zeromq_simple.py @@ -1,11 +1,11 @@ -''' ------------ 17_zeromq_interface -------------- -Run ROSCO using the ROSCO toolbox control interface and execute communication with ZeroMQ -------------------------------------- +""" +17a_zeromq_simple +-------------------- +Run ROSCO using the ROSCO toolbox control interface and execute communication with ZeroMQ. A demonstrator for ZeroMQ communication. Instead of using ROSCO with with control interface, one could call ROSCO from OpenFAST, and communicate with ZeroMQ through that. -''' +""" import os @@ -22,15 +22,22 @@ import numpy as np import multiprocessing as mp -TIME_CHECK = 30 -DESIRED_YAW_OFFSET = 20 -DESIRED_PITCH_OFFSET = np.deg2rad(2) * np.sin(0.1 * TIME_CHECK) + np.deg2rad(2) -#directories -this_dir = os.path.dirname(os.path.abspath(__file__)) -rosco_dir = os.path.dirname(this_dir) -example_out_dir = os.path.join(this_dir,'examples_out') -os.makedirs(example_out_dir,exist_ok=True) +def main(): + #directories + this_dir = os.path.dirname(os.path.abspath(__file__)) + rosco_dir = os.path.dirname(this_dir) + example_out_dir = os.path.join(this_dir,'examples_out') + os.makedirs(example_out_dir,exist_ok=True) + + logfile = os.path.join(example_out_dir,os.path.splitext(os.path.basename(__file__))[0]+'.log') + p1 = mp.Process(target=run_zmq,args=(logfile,)) + p1.start() + p2 = mp.Process(target=sim_rosco) + p2.start() + p1.join() + p2.join() + def run_zmq(logfile=None): # Start the server at the following address @@ -44,25 +51,29 @@ def run_zmq(logfile=None): server.runserver() def wfc_controller(id,current_time,measurements): - if current_time <= 10.0: - yaw_setpoint = 0.0 - else: - yaw_setpoint = DESIRED_YAW_OFFSET - - # Pitch offset - if current_time >= 10.0: - col_pitch_command = np.deg2rad(2) * np.sin(0.1 * current_time) + np.deg2rad(2) # Implement dynamic induction control - else: - col_pitch_command = 0.0 - - # Send new setpoints back to ROSCO - setpoints = {} - setpoints['ZMQ_TorqueOffset'] = 0.0 - setpoints['ZMQ_YawOffset'] = yaw_setpoint - setpoints['ZMQ_PitOffset(1)'] = col_pitch_command - setpoints['ZMQ_PitOffset(2)'] = col_pitch_command - setpoints['ZMQ_PitOffset(3)'] = col_pitch_command - return setpoints + time_check = 30 + desired_yaw_offset = 20 + desired_pitch_offset = np.deg2rad(2) * np.sin(0.1 * time_check) + np.deg2rad(2) + + if current_time <= 10.0: + yaw_setpoint = 0.0 + else: + yaw_setpoint = desired_yaw_offset + + # Pitch offset + if current_time >= 10.0: + col_pitch_command = np.deg2rad(2) * np.sin(0.1 * current_time) + np.deg2rad(2) # Implement dynamic induction control + else: + col_pitch_command = 0.0 + + # Send new setpoints back to ROSCO + setpoints = {} + setpoints['ZMQ_TorqueOffset'] = 0.0 + setpoints['ZMQ_YawOffset'] = yaw_setpoint + setpoints['ZMQ_PitOffset(1)'] = col_pitch_command + setpoints['ZMQ_PitOffset(2)'] = col_pitch_command + setpoints['ZMQ_PitOffset(3)'] = col_pitch_command + return setpoints def sim_rosco(): # Load yaml file @@ -157,10 +168,4 @@ def sim_rosco(): np.testing.assert_almost_equal(local_vars[0]['ZMQ_PitOffset'][ind_30], DESIRED_PITCH_OFFSET, decimal=3) if __name__ == "__main__": - logfile = os.path.join(example_out_dir,os.path.splitext(os.path.basename(__file__))[0]+'.log') - p1 = mp.Process(target=run_zmq,args=(logfile,)) - p1.start() - p2 = mp.Process(target=sim_rosco) - p2.start() - p1.join() - p2.join() + main() diff --git a/Examples/17b_zeromq_multi_openfast.py b/Examples/17b_zeromq_multi_openfast.py index 0de4d9a7..d3749696 100644 --- a/Examples/17b_zeromq_multi_openfast.py +++ b/Examples/17b_zeromq_multi_openfast.py @@ -1,3 +1,9 @@ +""" +17b_zeromq_multi_openfast +------------------------- +Run multiple openfast simulations and execute communication with ZeroMQ. +""" + import os import numpy as np import multiprocessing as mp @@ -7,13 +13,76 @@ from rosco.toolbox.ofTools.case_gen.run_FAST import run_FAST_ROSCO from rosco.toolbox.ofTools.fast_io import output_processing - -this_dir = os.path.dirname(os.path.abspath(__file__)) -example_out_dir = os.path.join(this_dir, "examples_out") -os.makedirs(example_out_dir, exist_ok=True) TIME_CHECK = 20 DESIRED_YAW_OFFSET = [-10, 10] +def main(): + this_dir = os.path.dirname(os.path.abspath(__file__)) + example_out_dir = os.path.join(this_dir, "examples_out") + os.makedirs(example_out_dir, exist_ok=True) + + + # Start wind farm control server and two openfast simulation + # as separate processes + logfile = os.path.join(example_out_dir,os.path.splitext(os.path.basename(__file__))[0]+'.log') + p0 = mp.Process(target=run_zmq,args=(logfile,)) + p1 = mp.Process(target=sim_openfast_1) + p2 = mp.Process(target=sim_openfast_2) + + p0.start() + p1.start() + p2.start() + + p0.join() + p1.join() + p2.join() + + ## Run tests + # Check that info is passed to ROSCO for first simulation + op1 = output_processing.output_processing() + debug_file1 = os.path.join( + example_out_dir, + "17b_zeromq_OF1", + "NREL5MW", + "power_curve", + "base", + "NREL5MW_0.RO.dbg2", + ) + local_vars1 = op1.load_fast_out(debug_file1, tmin=0) + + # Check that info is passed to ROSCO for first simulation + op2 = output_processing.output_processing() + debug_file2 = os.path.join( + example_out_dir, + "17b_zeromq_OF2", + "NREL5MW", + "power_curve", + "base", + "NREL5MW_0.RO.dbg2", + ) + local_vars2 = op2.load_fast_out(debug_file2, tmin=0) + + # Generate plots + _, axs = plt.subplots(2, 1) + axs[0].plot(local_vars1[0]["Time"], local_vars1[0]["ZMQ_YawOffset"]) + axs[1].plot(local_vars2[0]["Time"], local_vars2[0]["ZMQ_YawOffset"]) + + if False: + plt.show() + else: + plt.savefig(os.path.join(example_out_dir, "17b_NREL5MW_ZMQ_Setpoints.png")) + + # Spot check input at time = 30 sec. + ind1_30 = local_vars1[0]["Time"] == TIME_CHECK + ind2_30 = local_vars2[0]["Time"] == TIME_CHECK + + np.testing.assert_almost_equal( + local_vars1[0]["ZMQ_YawOffset"][ind1_30], DESIRED_YAW_OFFSET[0] + ) + np.testing.assert_almost_equal( + local_vars2[0]["ZMQ_YawOffset"][ind2_30], DESIRED_YAW_OFFSET[1] + ) + def run_zmq(logfile=None): """Start the ZeroMQ server for wind farm control""" @@ -98,63 +167,4 @@ def sim_openfast_2(): if __name__ == "__main__": - # Start wind farm control server and two openfast simulation - # as separate processes - logfile = os.path.join(example_out_dir,os.path.splitext(os.path.basename(__file__))[0]+'.log') - p0 = mp.Process(target=run_zmq,args=(logfile,)) - p1 = mp.Process(target=sim_openfast_1) - p2 = mp.Process(target=sim_openfast_2) - - p0.start() - p1.start() - p2.start() - - p0.join() - p1.join() - p2.join() - - ## Run tests - # Check that info is passed to ROSCO for first simulation - op1 = output_processing.output_processing() - debug_file1 = os.path.join( - example_out_dir, - "17b_zeromq_OF1", - "NREL5MW", - "power_curve", - "base", - "NREL5MW_0.RO.dbg2", - ) - local_vars1 = op1.load_fast_out(debug_file1, tmin=0) - - # Check that info is passed to ROSCO for first simulation - op2 = output_processing.output_processing() - debug_file2 = os.path.join( - example_out_dir, - "17b_zeromq_OF2", - "NREL5MW", - "power_curve", - "base", - "NREL5MW_0.RO.dbg2", - ) - local_vars2 = op2.load_fast_out(debug_file2, tmin=0) - - # Generate plots - _, axs = plt.subplots(2, 1) - axs[0].plot(local_vars1[0]["Time"], local_vars1[0]["ZMQ_YawOffset"]) - axs[1].plot(local_vars2[0]["Time"], local_vars2[0]["ZMQ_YawOffset"]) - - if False: - plt.show() - else: - plt.savefig(os.path.join(example_out_dir, "17b_NREL5MW_ZMQ_Setpoints.png")) - - # Spot check input at time = 30 sec. - ind1_30 = local_vars1[0]["Time"] == TIME_CHECK - ind2_30 = local_vars2[0]["Time"] == TIME_CHECK - - np.testing.assert_almost_equal( - local_vars1[0]["ZMQ_YawOffset"][ind1_30], DESIRED_YAW_OFFSET[0] - ) - np.testing.assert_almost_equal( - local_vars2[0]["ZMQ_YawOffset"][ind2_30], DESIRED_YAW_OFFSET[1] - ) + main() \ No newline at end of file diff --git a/Examples/18_pitch_offsets.py b/Examples/18_pitch_offsets.py index 74f42201..baaf8ab2 100644 --- a/Examples/18_pitch_offsets.py +++ b/Examples/18_pitch_offsets.py @@ -1,11 +1,9 @@ -''' ------------ 18_pitch_offsets ------------------------ +""" +18_pitch_offsets +---------------- Run openfast with ROSCO and pitch offset faults ------------------------------------------------ - Set up and run simulation with pitch offsets, check outputs - -''' +""" import os from rosco.toolbox.ofTools.case_gen.run_FAST import run_FAST_ROSCO @@ -14,14 +12,12 @@ import numpy as np -#directories -this_dir = os.path.dirname(os.path.abspath(__file__)) -rosco_dir = os.path.dirname(this_dir) -example_out_dir = os.path.join(this_dir,'examples_out') -os.makedirs(example_out_dir,exist_ok=True) - - def main(): + #directories + this_dir = os.path.dirname(os.path.abspath(__file__)) + rosco_dir = os.path.dirname(this_dir) + example_out_dir = os.path.join(this_dir,'examples_out') + os.makedirs(example_out_dir,exist_ok=True) # Input yaml and output directory parameter_filename = os.path.join(this_dir,'Tune_Cases/IEA15MW.yaml') diff --git a/Examples/19_update_discon_version.py b/Examples/19_update_discon_version.py index e4cd2960..78feb5d0 100644 --- a/Examples/19_update_discon_version.py +++ b/Examples/19_update_discon_version.py @@ -1,17 +1,16 @@ -''' ------------ 19_update_discon_version ----------------- +""" +19_update_discon_version +------------------------ Test and demonstrate update_discon_version() function for converting an old ROSCO input to the current version -''' +""" import os from rosco.toolbox.tune import update_discon_version -this_dir = os.path.dirname(os.path.abspath(__file__)) -rosco_dir = os.path.dirname(this_dir) - - def main(): + this_dir = os.path.dirname(os.path.abspath(__file__)) + rosco_dir = os.path.dirname(this_dir) old_discon_filename = os.path.join(this_dir,'example_inputs','DISCON_v2.2.0.IN') # An IEA-15MW input @@ -23,7 +22,5 @@ def main(): os.path.join(this_dir,'examples_out','18_UPDATED_DISCON.IN') ) - - if __name__ == "__main__": main() \ No newline at end of file diff --git a/Examples/20_active_wake_control.py b/Examples/20_active_wake_control.py index aa936a9f..85fca9d8 100644 --- a/Examples/20_active_wake_control.py +++ b/Examples/20_active_wake_control.py @@ -1,157 +1,157 @@ -''' ------------ 20_active_wake_control ------------ +""" +20_active_wake_control +---------------------- Run openfast with ROSCO and active wake control ------------------------------------------------ Set up and run simulation with AWC, check outputs Active wake control (AWC) with blade pitching is implemented in this example with two approaches as detailed below: - ------------------------------------------------ -AWC_Mode = 1: Normal mode method: ------------------------------------------------ -The normal mode method is an adaptation into the rotating frame of the mathematical framework from the classical theory for stability of axisymmetric jets [1], which offers flexibility in specifying the forcing strategy. - -The inputs to the controller are: - Name Unit Type Range Description - AWC_NumModes - Integer [0,inf] number of forcing modes - AWC_n - Integer [-inf,inf] azimuthal mode number(s) (i.e., the azimuthal mode number relates to the number and direction of the lobes of the wake structure according to the classical spatio-temporal Fourier decomposition of an arbitrary quantity q, sigma{sigma{q*exp(i*n*theta)*exp(i*omega*time)}}. For the case of a non-time-varying flow (i.e., where omega = 0), the azimuthal mode number specifies the number of cycles of blade pitch oscillation per one rotation around the rotor azimuth.) - AWC_clockangle deg Float [0,360] clocking angle(s) of forcing mode(s) - AWC_freq Hz Float [0,inf] frequency(s) of forcing mode(s) - AWC_amp deg Float [0,inf] pitch amplitude(s) of forcing mode(s) (note that AWC_amp specifies the amplitude of each individual mode so that the total amplitude of pitching will be the sum of AWC_amp) - -The latter two inputs may be specified based on the expected inflow while the former three inputs determine the type of active wake control to be used. - -Readers may be familiar with several forcing strategies from literature on active wake control that can be represented as follows: - -collective dynamic induction control: AWC_NumModes = 1, AWC_n = 0, AWC_clockangle = 0 - -helix clockwise [2]: AWC_NumModes = 1, AWC_n = 1, AWC_clockangle = 0 - -helix counter-clockwise [2]: AWC_NumModes = 1, AWC_n = -1, AWC_clockangle = 0 - -up-and-down: AWC_NumModes = 2, AWC_n = -1 1, AWC_clockangle = 0 0 - -side-to-side: AWC_NumModes = 2, AWC_n = -1 1, AWC_clockangle = 90 90 - -other: Higher-order modes or different combinations of the above can also be specified +""" +# ----------------------------------------------- +# AWC_Mode = 1: Normal mode method: +# ----------------------------------------------- +# The normal mode method is an adaptation into the rotating frame of the mathematical framework from the classical theory for stability of axisymmetric jets [1], which offers flexibility in specifying the forcing strategy. + +# The inputs to the controller are: +# Name Unit Type Range Description +# AWC_NumModes - Integer [0,inf] number of forcing modes +# AWC_n - Integer [-inf,inf] azimuthal mode number(s) (i.e., the azimuthal mode number relates to the number and direction of the lobes of the wake structure according to the classical spatio-temporal Fourier decomposition of an arbitrary quantity q, sigma{sigma{q*exp(i*n*theta)*exp(i*omega*time)}}. For the case of a non-time-varying flow (i.e., where omega = 0), the azimuthal mode number specifies the number of cycles of blade pitch oscillation per one rotation around the rotor azimuth.) +# AWC_clockangle deg Float [0,360] clocking angle(s) of forcing mode(s) +# AWC_freq Hz Float [0,inf] frequency(s) of forcing mode(s) +# AWC_amp deg Float [0,inf] pitch amplitude(s) of forcing mode(s) (note that AWC_amp specifies the amplitude of each individual mode so that the total amplitude of pitching will be the sum of AWC_amp) + +# The latter two inputs may be specified based on the expected inflow while the former three inputs determine the type of active wake control to be used. + +# Readers may be familiar with several forcing strategies from literature on active wake control that can be represented as follows: +# -collective dynamic induction control: AWC_NumModes = 1, AWC_n = 0, AWC_clockangle = 0 +# -helix clockwise [2]: AWC_NumModes = 1, AWC_n = 1, AWC_clockangle = 0 +# -helix counter-clockwise [2]: AWC_NumModes = 1, AWC_n = -1, AWC_clockangle = 0 +# -up-and-down: AWC_NumModes = 2, AWC_n = -1 1, AWC_clockangle = 0 0 +# -side-to-side: AWC_NumModes = 2, AWC_n = -1 1, AWC_clockangle = 90 90 +# -other: Higher-order modes or different combinations of the above can also be specified - These strategies are implemented using the following calculation methodology: - For each blade, we compute the total phase angle of blade pitch excursion according to: - AWC_angle(t) = 2*Pi*AWC_freq * t - AWC_n * (psi(t) + phi + AWC_clockangle*PI/180) (eq 1) - where t is time - phi(t) is the angular offset of the given blade in the rotor plane relative to blade 1 - psi is the angle of blade 1 in the rotor plane from top-dead center +# These strategies are implemented using the following calculation methodology: +# For each blade, we compute the total phase angle of blade pitch excursion according to: +# AWC_angle(t) = 2*Pi*AWC_freq * t - AWC_n * (psi(t) + phi + AWC_clockangle*PI/180) (eq 1) +# where t is time +# phi(t) is the angular offset of the given blade in the rotor plane relative to blade 1 +# psi is the angle of blade 1 in the rotor plane from top-dead center - Next, the phase angle is converted into the complex pitch amplitude: - AWC_complexangle(t) = AWC_amp*PI/180 * EXP(i * AWC_angle(t)) (eq 2) - where i is the square root of -1 +# Next, the phase angle is converted into the complex pitch amplitude: +# AWC_complexangle(t) = AWC_amp*PI/180 * EXP(i * AWC_angle(t)) (eq 2) +# where i is the square root of -1 - Note that if AWC_NumModes>1, then eq 1 and 2 are computed for each additional mode, and AWC_complexangle becomes a summation over all modes for each blade. +# Note that if AWC_NumModes>1, then eq 1 and 2 are computed for each additional mode, and AWC_complexangle becomes a summation over all modes for each blade. - Finally, the real pitch amplitude, theta(t), to be passed to the next step of the controller is calculated: - theta(t) = theta_0(t) + REAL(AWC_complexangle(t)) (eq 3) - where theta_0(t) is the controller's nominal pitch command +# Finally, the real pitch amplitude, theta(t), to be passed to the next step of the controller is calculated: +# theta(t) = theta_0(t) + REAL(AWC_complexangle(t)) (eq 3) +# where theta_0(t) is the controller's nominal pitch command - Rearranging for ease of viewing: - Inserting eq 1 into eq 2, and then putting that result into eq 3 gives: - theta(t) = theta_0(t) + REAL(AWC_amp*PI/180 * EXP(i * (2*Pi*AWC_freq * t - AWC_n * (psi(t) + phi + AWC_clockangle*PI/180)))) (eq 4) +# Rearranging for ease of viewing: +# Inserting eq 1 into eq 2, and then putting that result into eq 3 gives: +# theta(t) = theta_0(t) + REAL(AWC_amp*PI/180 * EXP(i * (2*Pi*AWC_freq * t - AWC_n * (psi(t) + phi + AWC_clockangle*PI/180)))) (eq 4) - Applying Euler's formula and carrying out the REAL operator: - theta(t) = theta_0(t) + AWC_amp*PI/180 * cos(2*Pi*AWC_freq * t - AWC_n * (psi(t) + phi + AWC_clockangle*PI/180)) (eq 5) +# Applying Euler's formula and carrying out the REAL operator: +# theta(t) = theta_0(t) + AWC_amp*PI/180 * cos(2*Pi*AWC_freq * t - AWC_n * (psi(t) + phi + AWC_clockangle*PI/180)) (eq 5) - As an example, we can set parameters to produce the counter-clockwise helix pattern from [2] using AWC_NumModes = 1, AWC_n = -1, and AWC_clockangle = 0: - For blade 1, eq 5 becomes: - theta(t) = theta_0(t) + AWC_amp*PI/180 * cos(2*Pi*AWC_freq * t + psi(t)) (eq 6) +# As an example, we can set parameters to produce the counter-clockwise helix pattern from [2] using AWC_NumModes = 1, AWC_n = -1, and AWC_clockangle = 0: +# For blade 1, eq 5 becomes: +# theta(t) = theta_0(t) + AWC_amp*PI/180 * cos(2*Pi*AWC_freq * t + psi(t)) (eq 6) -Note that the inverse multi-blade coordinate (MBC) transformation can also be used to obtain the same result as eq 6. - Beginning with Eq. 3 from [2], we have +# Note that the inverse multi-blade coordinate (MBC) transformation can also be used to obtain the same result as eq 6. +# Beginning with Eq. 3 from [2], we have - / \ / \ - | theta_1(t) | | theta_0(t) | - | theta_2(t) | = T^-1(psi(t)) * | theta_tilt(t) | (eq 7) - | theta_3(t) | | theta_yaw(t) | - \ / \ / +# / \ / \ +# | theta_1(t) | | theta_0(t) | +# | theta_2(t) | = T^-1(psi(t)) * | theta_tilt(t) | (eq 7) +# | theta_3(t) | | theta_yaw(t) | +# \ / \ / - where +# where - / \ - | 1 cos(psi_1(t)) sin(psi_1(t)) | - T^-1(psi(t)) = | 1 cos(psi_2(t)) sin(psi_2(t)) | - | 1 cos(psi_3(t)) sin(psi_3(t)) | - \ / +# / \ +# | 1 cos(psi_1(t)) sin(psi_1(t)) | +# T^-1(psi(t)) = | 1 cos(psi_2(t)) sin(psi_2(t)) | +# | 1 cos(psi_3(t)) sin(psi_3(t)) | +# \ / - Multiplying the first row of the top matrix (and dropping the subscript of blade 1) yields: - theta(t) = theta_0(t) + theta_tilt(t)*cos(psi(t)) + theta_yaw(t)*sin(psi(t)) (eq 8) +# Multiplying the first row of the top matrix (and dropping the subscript of blade 1) yields: +# theta(t) = theta_0(t) + theta_tilt(t)*cos(psi(t)) + theta_yaw(t)*sin(psi(t)) (eq 8) - Setting theta_tilt(t) = AWC_amp*PI/180 * cos(2*Pi*AWC_freq * t) and theta_yaw(t) = -AWC_amp*PI/180 * sin(2*Pi*AWC_freq * t) gives: - theta(t) = theta_0(t) + (AWC_amp*PI/180 * cos(2*Pi*AWC_freq * t))*cos(psi(t)) - (AWC_amp*PI/180 * sin(2*Pi*AWC_freq * t))*sin(psi(t)) (eq 9) +# Setting theta_tilt(t) = AWC_amp*PI/180 * cos(2*Pi*AWC_freq * t) and theta_yaw(t) = -AWC_amp*PI/180 * sin(2*Pi*AWC_freq * t) gives: +# theta(t) = theta_0(t) + (AWC_amp*PI/180 * cos(2*Pi*AWC_freq * t))*cos(psi(t)) - (AWC_amp*PI/180 * sin(2*Pi*AWC_freq * t))*sin(psi(t)) (eq 9) - Applying a Ptolemy identity gives: - theta(t) = theta_0(t) + AWC_amp*PI/180 * cos(2*Pi*AWC_freq * t + psi(t)) (eq 10) - which is equivlanet to eq 6 above. - ------------------------------------------------ -AWC_Mode = 2: Coleman transform method: ------------------------------------------------ -A second method is the Coleman transform method. - -The inputs to the controller are: - Name Unit Type Range Description - AWC_NumModes - Integer [1,2] number of modes for tilt and yaw (1: identical settings for tilt and yaw pitch angles, 2: seperate settings for tilt and yaw moments) - AWC_harmonic - Integer [0,inf] harmonic(s) to apply in the inverse Coleman transform (size = AWC_NumModes. 0: collective pitch AWC, 1: 1P IPC-AWC, 2: 2P IPC-AWC, etc.) - AWC_clockangle deg Array of Floats [-360,360] clocking angle(s) of tilt and yaw pitch angles (size = AWC_NumModes. If size = 1, yaw clockangle = 2*clockangle) - AWC_freq Hz Array of Floats [0,inf] frequency(s) of the tilt and yaw ptich angles, respectively (size = AWC_NumModes. If size = 1, both frequencies are assumed identical) - AWC_amp deg Array of Floats [0,inf] pitch amplitude(s) of tilt and yaw pitch angles (size = AWC_NumModes. If size = 1, both amplitudes are assumed identical) +# Applying a Ptolemy identity gives: +# theta(t) = theta_0(t) + AWC_amp*PI/180 * cos(2*Pi*AWC_freq * t + psi(t)) (eq 10) +# which is equivlanet to eq 6 above. + +# ----------------------------------------------- +# AWC_Mode = 2: Coleman transform method: +# ----------------------------------------------- +# A second method is the Coleman transform method. + +# The inputs to the controller are: +# Name Unit Type Range Description +# AWC_NumModes - Integer [1,2] number of modes for tilt and yaw (1: identical settings for tilt and yaw pitch angles, 2: seperate settings for tilt and yaw moments) +# AWC_harmonic - Integer [0,inf] harmonic(s) to apply in the inverse Coleman transform (size = AWC_NumModes. 0: collective pitch AWC, 1: 1P IPC-AWC, 2: 2P IPC-AWC, etc.) +# AWC_clockangle deg Array of Floats [-360,360] clocking angle(s) of tilt and yaw pitch angles (size = AWC_NumModes. If size = 1, yaw clockangle = 2*clockangle) +# AWC_freq Hz Array of Floats [0,inf] frequency(s) of the tilt and yaw ptich angles, respectively (size = AWC_NumModes. If size = 1, both frequencies are assumed identical) +# AWC_amp deg Array of Floats [0,inf] pitch amplitude(s) of tilt and yaw pitch angles (size = AWC_NumModes. If size = 1, both amplitudes are assumed identical) -Using the inputs mentioned above, the user is able to specify any desired combination of sinusoidal tilt and yaw modes to be tracked by the turbine. -When a single mode is defined in the inputs, the prescribed tilt and yaw angles are assumed to be identical, except for the phase. The phase difference -between the tilt and yaw angles is taken from the input AWC_clockangle. - -Readers may be familiar with several forcing strategies from literature on active wake control that can be represented as follows: - -collective dynamic induction control: AWC_NumModes = 1, AWC_harmonic = 0 - -helix clockwise [2]: AWC_NumModes = 1, AWC_harmonic = 1, AWC_clockangle = -90 OR AWC_NumModes = 2, AWC_n = [1 1], AWC_clockangle = [0 -90] - -helix counter-clockwise [2]: AWC_NumModes = 1, AWC_harmonic = 1, AWC_clockangle = 90 OR AWC_NumModes = 2, AWC_n = [1 1], AWC_clockangle = [0 90] - -up-and-down: AWC_NumModes = 2, AWC_harmonic = [1 1], AWC_amp = [# 0] (where "#" represents the desired amplitude) - -side-to-side: AWC_NumModes = 2, AWC_harmonic = [1 1], AWC_amp = [0 #] (where "#" represents the desired amplitude) - -other: different combinations of the above can also be specified +# Using the inputs mentioned above, the user is able to specify any desired combination of sinusoidal tilt and yaw modes to be tracked by the turbine. +# When a single mode is defined in the inputs, the prescribed tilt and yaw angles are assumed to be identical, except for the phase. The phase difference +# between the tilt and yaw angles is taken from the input AWC_clockangle. + +# Readers may be familiar with several forcing strategies from literature on active wake control that can be represented as follows: +# -collective dynamic induction control: AWC_NumModes = 1, AWC_harmonic = 0 +# -helix clockwise [2]: AWC_NumModes = 1, AWC_harmonic = 1, AWC_clockangle = -90 OR AWC_NumModes = 2, AWC_n = [1 1], AWC_clockangle = [0 -90] +# -helix counter-clockwise [2]: AWC_NumModes = 1, AWC_harmonic = 1, AWC_clockangle = 90 OR AWC_NumModes = 2, AWC_n = [1 1], AWC_clockangle = [0 90] +# -up-and-down: AWC_NumModes = 2, AWC_harmonic = [1 1], AWC_amp = [# 0] (where "#" represents the desired amplitude) +# -side-to-side: AWC_NumModes = 2, AWC_harmonic = [1 1], AWC_amp = [0 #] (where "#" represents the desired amplitude) +# -other: different combinations of the above can also be specified - These strategies are implemented using the following calculation methodology: - The inputs described above enable the user to specify a desired sinusoidal signal for either the collective pitch (AWC_n = 0) or tilt and yaw pitch - angles (AWC_n = 1). These AWC pitch angles are defined as: - AWC_angle(t) = AWC_amp * sin(2*pi*AWC_freq*t + AWC_clockangle) (eq 1) +# These strategies are implemented using the following calculation methodology: +# The inputs described above enable the user to specify a desired sinusoidal signal for either the collective pitch (AWC_n = 0) or tilt and yaw pitch +# angles (AWC_n = 1). These AWC pitch angles are defined as: +# AWC_angle(t) = AWC_amp * sin(2*pi*AWC_freq*t + AWC_clockangle) (eq 1) - In case of collective pitch AWC, this signal is directly superimposed on the regular pitch control signal. +# In case of collective pitch AWC, this signal is directly superimposed on the regular pitch control signal. - In case of IPC-based AWC, the reference tilt and yaw pitch angles theta are transformed to the rotating frame (i.e., pitch angles theta_k(t) for all - individual blades) using the inverse MBC transformation: +# In case of IPC-based AWC, the reference tilt and yaw pitch angles theta are transformed to the rotating frame (i.e., pitch angles theta_k(t) for all +# individual blades) using the inverse MBC transformation: - / \ / \ - | theta_1(t) | | theta_0(t) | - | theta_2(t) | = T^-1(psi(t)) * | theta_tilt(t) | (eq 2) - | theta_3(t) | | theta_yaw(t) | - \ / \ / +# / \ / \ +# | theta_1(t) | | theta_0(t) | +# | theta_2(t) | = T^-1(psi(t)) * | theta_tilt(t) | (eq 2) +# | theta_3(t) | | theta_yaw(t) | +# \ / \ / - where +# where - theta_tilt(t) = AWC_amp(1) * sin(2*pi*AWC_freq(1)*t + AWC_clockangle(1)) (eq 3) - theta_yaw(t) = AWC_amp(2) * sin(2*pi*AWC_freq(2)*t + AWC_clockangle(2)) (eq 4) +# theta_tilt(t) = AWC_amp(1) * sin(2*pi*AWC_freq(1)*t + AWC_clockangle(1)) (eq 3) +# theta_yaw(t) = AWC_amp(2) * sin(2*pi*AWC_freq(2)*t + AWC_clockangle(2)) (eq 4) - and - / \ - | 1 cos(psi_1(t)) sin(psi_1(t)) | - T^-1(psi(t)) = | 1 cos(psi_2(t)) sin(psi_2(t)) | (eq 5) - | 1 cos(psi_3(t)) sin(psi_3(t)) | - \ / +# and +# / \ +# | 1 cos(psi_1(t)) sin(psi_1(t)) | +# T^-1(psi(t)) = | 1 cos(psi_2(t)) sin(psi_2(t)) | (eq 5) +# | 1 cos(psi_3(t)) sin(psi_3(t)) | +# \ / - with psi_k(t) the azimuthal position of blade k at time instant t. Note that if AWC_NumModes = 1, it is assumed that: - AWC_amp(2) = AWC_amp(1) - AWC_freq(2) = AWC_freq(1) - AWC_clockangle(2) = 2*AWC_clockangle(1) +# with psi_k(t) the azimuthal position of blade k at time instant t. Note that if AWC_NumModes = 1, it is assumed that: +# AWC_amp(2) = AWC_amp(1) +# AWC_freq(2) = AWC_freq(1) +# AWC_clockangle(2) = 2*AWC_clockangle(1) - For more information on this control strategy, the user is referred to [2]. +# For more information on this control strategy, the user is referred to [2]. ------------------------------------------------ +# ----------------------------------------------- + +# General Implementation note: AWC strategies will be compromised if the AWC pitch command attempts to lower the blade pitch below value PC_MinPit as specified +# in the DISCON file, so PC_MinPit may need to be reduced by the user. -General Implementation note: AWC strategies will be compromised if the AWC pitch command attempts to lower the blade pitch below value PC_MinPit as specified -in the DISCON file, so PC_MinPit may need to be reduced by the user. +# References: +# [1] - Batchelor, G. K., and A. E. Gill. "Analysis of the stability of axisymmetric jets." Journal of fluid mechanics 14.4 (1962): 529-551. +# [2] - Frederik, Joeri A., et al. "The helix approach: Using dynamic individual pitch control to enhance wake mixing in wind farms." Wind Energy 23.8 (2020): 1739-1751. -References: -[1] - Batchelor, G. K., and A. E. Gill. "Analysis of the stability of axisymmetric jets." Journal of fluid mechanics 14.4 (1962): 529-551. -[2] - Frederik, Joeri A., et al. "The helix approach: Using dynamic individual pitch control to enhance wake mixing in wind farms." Wind Energy 23.8 (2020): 1739-1751. -''' import os from rosco.toolbox.ofTools.case_gen.run_FAST import run_FAST_ROSCO @@ -160,20 +160,17 @@ from rosco.toolbox.utilities import read_DISCON #, DISCON_dict #import numpy as np -# Choose your implementation method -AWC_Mode = 1 # 1 for SNL implementation, 2 for Coleman Transformation implementation - - -#directories -this_dir = os.path.dirname(os.path.abspath(__file__)) -rosco_dir = os.path.dirname(this_dir) -example_out_dir = os.path.join(this_dir,'examples_out') -os.makedirs(example_out_dir,exist_ok=True) - - - def main(): + # Choose your implementation method + AWC_Mode = 1 # 1 for SNL implementation, 2 for Coleman Transformation implementation + + #directories + this_dir = os.path.dirname(os.path.abspath(__file__)) + rosco_dir = os.path.dirname(this_dir) + example_out_dir = os.path.join(this_dir,'examples_out') + os.makedirs(example_out_dir,exist_ok=True) + # Input yaml and output directory parameter_filename = os.path.join(this_dir,'Tune_Cases/NREL2p8.yaml') # will be dummy and overwritten with SNL DISCON params run_dir = os.path.join(example_out_dir,'20_active_wake_control/all_cases') diff --git a/Examples/21_optional_inputs.py b/Examples/21_optional_inputs.py index 17b4f90b..59292fc1 100644 --- a/Examples/21_optional_inputs.py +++ b/Examples/21_optional_inputs.py @@ -1,8 +1,9 @@ -''' ------------ 21_optional_inputse_discon_version ----------------- +""" +21_optional_inputse_discon_version +---------------------------------- Test and demonstrate update_discon_version() function for converting an old ROSCO input to the current version -''' +""" import os from rosco import discon_lib_path @@ -11,15 +12,12 @@ from rosco.toolbox import turbine as ROSCO_turbine #import numpy as np -#directories -this_dir = os.path.dirname(os.path.abspath(__file__)) -rosco_dir = os.path.dirname(this_dir) -example_out_dir = os.path.join(this_dir,'examples_out') -example_in_dir = os.path.join(this_dir,'example_inputs') -os.makedirs(example_out_dir,exist_ok=True) - - -def main(): +def main():#directories + this_dir = os.path.dirname(os.path.abspath(__file__)) + rosco_dir = os.path.dirname(this_dir) + example_out_dir = os.path.join(this_dir,'examples_out') + example_in_dir = os.path.join(this_dir,'example_inputs') + os.makedirs(example_out_dir,exist_ok=True) # Load turbine model from saved pickle turbine = ROSCO_turbine.Turbine diff --git a/Examples/22_cable_control.py b/Examples/22_cable_control.py index ce9a85b2..e5e23885 100644 --- a/Examples/22_cable_control.py +++ b/Examples/22_cable_control.py @@ -1,11 +1,18 @@ -''' ------------ 22_cable_control ------------------------ +""" +22_cable_control +---------------- Run openfast with ROSCO and cable control ------------------------------------------------ - Set up and run simulation with pitch offsets, check outputs -''' +ROSCO currently supports user-defined hooks for cable control actuation, if CC_Mode = 1. +The control logic can be determined in Controllers.f90 with the CableControl subroutine. +The CableControl subroutine takes an array of CC_DesiredL (length) equal to the ChannelIDs set in MoorDyn and +determines the length and change in length needed for MoorDyn using a 2nd order actuator model (CC\_ActTau). +In the DISCON input, users must specify CC\_GroupIndex relating to the deltaL of each control ChannelID. +These indices can be found in the ServoDyn summary file (\*SrvD.sum) + +In the example below (and hard-coded in ROSCO) a step change of -10 m on line 1 is applied at 50 sec. +""" import os from rosco.toolbox.ofTools.case_gen.run_FAST import run_FAST_ROSCO @@ -17,25 +24,12 @@ import matplotlib.pyplot as plt from rosco.toolbox.controller import OpenLoopControl -''' -ROSCO currently supports user-defined hooks for cable control actuation, if CC_Mode = 1. -The control logic can be determined in Controllers.f90 with the CableControl subroutine. -The CableControl subroutine takes an array of CC_DesiredL (length) equal to the ChannelIDs set in MoorDyn and -determines the length and change in length needed for MoorDyn using a 2nd order actuator model (CC_ActTau). -In the DISCON input, users must specify CC_GroupIndex relating to the deltaL of each control ChannelID. -These indices can be found in the ServoDyn summary file (*SrvD.sum) - -In the example below (and hard-coded in ROSCO) a step change of -10 m on line 1 is applied at 50 sec. -''' - - -#directories -this_dir = os.path.dirname(os.path.abspath(__file__)) -rosco_dir = os.path.dirname(this_dir) -example_out_dir = os.path.join(this_dir,'examples_out') -os.makedirs(example_out_dir,exist_ok=True) - def main(): + #directories + this_dir = os.path.dirname(os.path.abspath(__file__)) + rosco_dir = os.path.dirname(this_dir) + example_out_dir = os.path.join(this_dir,'examples_out') + os.makedirs(example_out_dir,exist_ok=True) # Input yaml and output directory parameter_filename = os.path.join(this_dir,'Tune_Cases/IEA15MW_cable.yaml') diff --git a/Examples/23_structural_control.py b/Examples/23_structural_control.py index 63022907..96569c93 100644 --- a/Examples/23_structural_control.py +++ b/Examples/23_structural_control.py @@ -1,11 +1,19 @@ -''' ------------ 23_structural_control ------------------------ +""" +23_structural_control +--------------------- Run openfast with ROSCO and structural control ------------------------------------------------ - Set up and run simulation with pitch offsets, check outputs -''' +ROSCO currently supports user-defined hooks for structural control control actuation, if StC\_Mode = 1. +The control logic can be determined in Controllers.f90 with the StructrualControl subroutine. +In the DISCON input, users must specify StC\_GroupIndex relating to the control ChannelID. +These indices can be found in the ServoDyn summary file (\*SrvD.sum) + +In the example below, we implement a smooth step change mimicing the exchange of ballast from the +upwind column to the down wind columns + +OpenFAST v3.5.0 is required to run this example +""" import os from rosco.toolbox.ofTools.case_gen.run_FAST import run_FAST_ROSCO @@ -15,28 +23,12 @@ from rosco.toolbox.inputs.validation import load_rosco_yaml from rosco.toolbox.controller import OpenLoopControl - -''' -ROSCO currently supports user-defined hooks for structural control control actuation, if StC_Mode = 1. -The control logic can be determined in Controllers.f90 with the StructrualControl subroutine. -In the DISCON input, users must specify StC_GroupIndex relating to the control ChannelID. -These indices can be found in the ServoDyn summary file (*SrvD.sum) - -In the example below, we implement a smooth step change mimicing the exchange of ballast from the -upwind column to the down wind columns - -OpenFAST v3.5.0 is required to run this example -''' - - -#directories -this_dir = os.path.dirname(os.path.abspath(__file__)) -rosco_dir = os.path.dirname(this_dir) -example_out_dir = os.path.join(this_dir,'examples_out') -os.makedirs(example_out_dir,exist_ok=True) - - def main(): + #directories + this_dir = os.path.dirname(os.path.abspath(__file__)) + rosco_dir = os.path.dirname(this_dir) + example_out_dir = os.path.join(this_dir,'examples_out') + os.makedirs(example_out_dir,exist_ok=True) # Input yaml and output directory parameter_filename = os.path.join(this_dir,'Tune_Cases/IEA15MW_ballast.yaml') diff --git a/Examples/24_floating_feedback.py b/Examples/24_floating_feedback.py index 7da30c70..db895c18 100644 --- a/Examples/24_floating_feedback.py +++ b/Examples/24_floating_feedback.py @@ -1,16 +1,14 @@ -''' ------------ 23_structural_control ------------------------ +""" +24_floating_feedback +--------------------- Run openfast with ROSCO and all the floating feedback methods ------------------------------------------------ - Floating feedback methods available in ROSCO/ROSCO_Toolbox -1. Automated tuning, constant for all wind speeds -2. Automated tuning, varies with wind speed -3. Direct tuning, constant for all wind speeds -4. Direct tuning, varies with wind speeds - -''' +#. Automated tuning, constant for all wind speeds +#. Automated tuning, varies with wind speed +#. Direct tuning, constant for all wind speeds +#. Direct tuning, varies with wind speeds +""" import os from rosco.toolbox.ofTools.case_gen.run_FAST import run_FAST_ROSCO @@ -26,14 +24,12 @@ import matplotlib.pyplot as plt - -#directories -this_dir = os.path.dirname(os.path.abspath(__file__)) -rosco_dir = os.path.dirname(this_dir) -example_out_dir = os.path.join(this_dir,'examples_out') -os.makedirs(example_out_dir,exist_ok=True) - def main(): + #directories + this_dir = os.path.dirname(os.path.abspath(__file__)) + rosco_dir = os.path.dirname(this_dir) + example_out_dir = os.path.join(this_dir,'examples_out') + os.makedirs(example_out_dir,exist_ok=True) # Input yaml and output directory parameter_filename = os.path.join(this_dir,'Tune_Cases/IEA15MW.yaml') diff --git a/Examples/25_rotor_position_control.py b/Examples/25_rotor_position_control.py index fe1abef8..d1449d59 100644 --- a/Examples/25_rotor_position_control.py +++ b/Examples/25_rotor_position_control.py @@ -1,11 +1,9 @@ -''' ------------ 25_rotor_position_control -------------- +""" +25_rotor_position_control +------------------------- Run ROSCO with rotor position control -------------------------------------- - Run a steady simulation, use the azimuth output as an input to the next steady simulation, with different ICs - -''' +""" import os from rosco.toolbox.ofTools.case_gen.run_FAST import run_FAST_ROSCO @@ -17,14 +15,12 @@ import matplotlib.pyplot as plt -#directories -this_dir = os.path.dirname(os.path.abspath(__file__)) -rosco_dir = os.path.dirname(this_dir) -example_out_dir = os.path.join(this_dir,'examples_out') -os.makedirs(example_out_dir,exist_ok=True) - - def main(): + #directories + this_dir = os.path.dirname(os.path.abspath(__file__)) + rosco_dir = os.path.dirname(this_dir) + example_out_dir = os.path.join(this_dir,'examples_out') + os.makedirs(example_out_dir,exist_ok=True) # Set up paths diff --git a/Examples/26_marine_hydro.py b/Examples/26_marine_hydro.py index 6773482b..24abfc3f 100644 --- a/Examples/26_marine_hydro.py +++ b/Examples/26_marine_hydro.py @@ -1,10 +1,8 @@ -''' ------------ 26_marine_hydro ------------------------ -Run openfast with ROSCO and a MHK turbine ------------------------------------------------ - - -''' +""" +26_marine_hydro +--------------- +Run MHK turbine in OpenFAST with ROSCO torque controller +""" import os from rosco.toolbox.ofTools.case_gen.run_FAST import run_FAST_ROSCO @@ -15,20 +13,12 @@ #import matplotlib.pyplot as plt #from rosco.toolbox.controller import OpenLoopControl -''' -Run MHK turbine in OpenFAST with ROSCO torque controller - - -''' - - -#directories -this_dir = os.path.dirname(os.path.abspath(__file__)) -rosco_dir = os.path.dirname(this_dir) -example_out_dir = os.path.join(this_dir,'examples_out') -os.makedirs(example_out_dir,exist_ok=True) - def main(): + #directories + this_dir = os.path.dirname(os.path.abspath(__file__)) + rosco_dir = os.path.dirname(this_dir) + example_out_dir = os.path.join(this_dir,'examples_out') + os.makedirs(example_out_dir,exist_ok=True) # Input yaml and output directory parameter_filename = os.path.join(this_dir,'Tune_Cases/RM1_MHK.yaml') diff --git a/Examples/27_power_ref_control.py b/Examples/27_power_ref_control.py index ebeba3b6..d6164234 100644 --- a/Examples/27_power_ref_control.py +++ b/Examples/27_power_ref_control.py @@ -1,12 +1,10 @@ -''' ------------ 27_power_ref_control ------------------------ +""" +27_power_ref_control +-------------------- Run openfast with ROSCO and cable control ------------------------------------------------ - Demonstrate a simulation with a generator reference speed that changes with estimated wind speed - - -''' +Set reference rotor speed as a function of wind speed (estimate in ROSCO) +""" import os from rosco import discon_lib_path @@ -17,24 +15,16 @@ #from rosco.toolbox.inputs.validation import load_rosco_yaml import matplotlib.pyplot as plt -''' -Set reference rotor speed as a function of wind speed (estimate in ROSCO) - -''' - FULL_TEST = False - -#directories -this_dir = os.path.dirname(os.path.abspath(__file__)) -rosco_dir = os.path.dirname(this_dir) -example_out_dir = os.path.join(this_dir,'examples_out') -os.makedirs(example_out_dir,exist_ok=True) -lib_name = discon_lib_path - - def main(): - + #directories + this_dir = os.path.dirname(os.path.abspath(__file__)) + rosco_dir = os.path.dirname(this_dir) + example_out_dir = os.path.join(this_dir,'examples_out') + os.makedirs(example_out_dir,exist_ok=True) + lib_name = discon_lib_path + # Input yaml and output directory parameter_filename = os.path.join(this_dir,'Tune_Cases/IEA15MW.yaml') run_dir = os.path.join(example_out_dir,'27_PRC_0') diff --git a/Examples/28_tower_resonance.py b/Examples/28_tower_resonance.py index 912e4081..209a928e 100644 --- a/Examples/28_tower_resonance.py +++ b/Examples/28_tower_resonance.py @@ -1,11 +1,9 @@ -''' ------------ 28_tower_resonance ------------------------ +""" +28_tower_resonance +------------------ Demonstrate tower resonance avoidance controller ------------------------------------------------ - Set up and run simulation with tower resonance avoidance - -''' +""" import os from rosco.toolbox.ofTools.case_gen.run_FAST import run_FAST_ROSCO @@ -16,17 +14,14 @@ import numpy as np -rpm2RadSec = 2.0*(np.pi)/60.0 - - -#directories -this_dir = os.path.dirname(os.path.abspath(__file__)) -rosco_dir = os.path.dirname(this_dir) -example_out_dir = os.path.join(this_dir,'examples_out') -os.makedirs(example_out_dir,exist_ok=True) - - def main(): + rpm2RadSec = 2.0*(np.pi)/60.0 + + #directories + this_dir = os.path.dirname(os.path.abspath(__file__)) + rosco_dir = os.path.dirname(this_dir) + example_out_dir = os.path.join(this_dir,'examples_out') + os.makedirs(example_out_dir,exist_ok=True) # Input yaml and output directory parameter_filename = os.path.join(this_dir,'Tune_Cases/IEA15MW.yaml') diff --git a/docs/source/examples.rst b/docs/source/examples.rst index 9bb5f04c..ce1b73f1 100644 --- a/docs/source/examples.rst +++ b/docs/source/examples.rst @@ -104,3 +104,30 @@ List of Examples A complete list of examples is given below: .. automodule:: 01_turbine_model +.. automodule:: 02_ccblade +.. automodule:: 03_tune_controller +.. automodule:: 04_simple_sim +.. automodule:: 05_openfast_sim +.. automodule:: 06_peak_shaving +.. automodule:: 07_openfast_outputs +.. automodule:: 08_run_turbsim +.. automodule:: 09_distributed_aero +.. automodule:: 10_linear_params +.. automodule:: 11_robust_tuning +.. automodule:: 12_tune_ipc +.. automodule:: 14_open_loop_control +.. automodule:: 15_pass_through +.. automodule:: 16_external_dll +.. automodule:: 17a_zeromq_simple +.. automodule:: 17b_zeromq_multi_openfast +.. automodule:: 18_pitch_offsets +.. automodule:: 19_update_discon_version +.. automodule:: 20_active_wake_control +.. automodule:: 21_optional_inputs +.. automodule:: 22_cable_control +.. automodule:: 23_structural_control +.. automodule:: 24_floating_feedback +.. automodule:: 25_rotor_position_control +.. automodule:: 26_marine_hydro +.. automodule:: 27_power_ref_control +.. automodule:: 28_tower_resonance From 62169723bcc3ccdd19e8f9613f9b7954cf878a9e Mon Sep 17 00:00:00 2001 From: David Stockhouse Date: Tue, 20 Aug 2024 21:58:34 -0600 Subject: [PATCH 165/224] Fixed bug in FBP control with VS_RefSpd turning to NaN if GenTq ever drops below 0 --- rosco/controller/src/ControllerBlocks.f90 | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/rosco/controller/src/ControllerBlocks.f90 b/rosco/controller/src/ControllerBlocks.f90 index 9c7eac85..677ce9c0 100644 --- a/rosco/controller/src/ControllerBlocks.f90 +++ b/rosco/controller/src/ControllerBlocks.f90 @@ -63,10 +63,10 @@ SUBROUTINE ComputeVariablesSetpoints(CntrPar, LocalVar, objInst, DebugVar, ErrVa LocalVar%VS_RefSpd_TSR = (CntrPar%VS_TSRopt * LocalVar%WE_Vw / CntrPar%WE_BladeRadius) * CntrPar%WE_GearboxRatio ELSEIF (CntrPar%VS_ControlMode == VS_Mode_Power_TSR) THEN ! Genspeed reference that doesn't depend on wind speed estimate (https://doi.org/10.2172/1259805) - LocalVar%VS_RefSpd_TSR = (LocalVar%VS_GenPwr/(CntrPar%VS_GenEff/100.0)/CntrPar%VS_Rgn2K)**(1./3.) + LocalVar%VS_RefSpd_TSR = (MAX(LocalVar%VS_GenPwr, 0.0)/(CntrPar%VS_GenEff/100.0)/CntrPar%VS_Rgn2K)**(1./3.) ELSEIF (CntrPar%VS_ControlMode == VS_Mode_Torque_TSR) THEN ! Non-WSE TSR tracking based on square-root of torque - LocalVar%VS_RefSpd_TSR = (LocalVar%GenTq/CntrPar%VS_Rgn2K)**(1./2.) + LocalVar%VS_RefSpd_TSR = (MAX(LocalVar%GenTq, 0.0)/CntrPar%VS_Rgn2K)**(1./2.) ELSE ! Generate constant reference LocalVar%VS_RefSpd_TSR = CntrPar%VS_RefSpd From ce1b0eb73e699a10942da2562d2ab31e7b92981d Mon Sep 17 00:00:00 2001 From: David Stockhouse Date: Thu, 22 Aug 2024 16:33:23 -0600 Subject: [PATCH 166/224] Revised usage of generator and gearbox efficiencies in toolbox controller tuning --- rosco/toolbox/controller.py | 14 +++++++++----- 1 file changed, 9 insertions(+), 5 deletions(-) diff --git a/rosco/toolbox/controller.py b/rosco/toolbox/controller.py index 5e545376..d7739fff 100644 --- a/rosco/toolbox/controller.py +++ b/rosco/toolbox/controller.py @@ -343,12 +343,11 @@ def tune_controller(self, turbine): omega_op = np.maximum(TSR_op*v/R, self.vs_minspd) omega_gen_op = omega_op * Ng - tau_op = P_op / omega_gen_op \ - / (turbine.GBoxEff/100 * turbine.GenEff/100) # Includes increase to counteract generator efficiency loss + tau_op = P_op / omega_gen_op / (turbine.GenEff/100) # Includes increase to counteract generator efficiency loss, but not gearbox efficiency loss # Check if maximum torque leaves enough leeway to control the system if np.max(tau_op) > turbine.max_torque: # turbine.max_torque * 1.2 # DBS: Should we include additional margin? print('WARNING: Torque operating schedule is above maximum generator torque and may not be realizable within saturation limits.') - # DBS: Do we want to saturate maximum torque and recompute equilibrium points? + # DBS: Future - add input constraints to satisfy maximum torque, speed, and thrust (peak shaving) in addition to power # Check if options allow a nonmonotonic torque schedule if self.VS_FBP == 3: @@ -417,8 +416,13 @@ def tune_controller(self, turbine): self.vs_gain_schedule.second_order_PI(self.zeta_vs, self.omega_vs,A,B_tau,linearize=False,v=v) # -- Find K for Komega_g^2 -- - self.vs_rgn2K = (pi*rho*R**5.0 * turbine.Cp.max) / \ - (2.0 * turbine.Cp.TSR_opt**3 * Ng**3) * self.controller_params['rgn2k_factor'] + # P_aero = 1/2 * Cp * rho * pi * R^5 / (TSR^3 * Ng^3) + # P_rot = GBoxEff * P_aero = tau_gen * omega_gen = K * omega_gen^3 + # P_gen = GenEff * P_rot + # Generator efficiency is not included in K here, but gearbox efficiency is + self.vs_rgn2K = (pi*rho*R**5.0 * turbine.Cp.max * turbine.GBoxEff/100) \ + / (2.0 * turbine.Cp.TSR_opt**3 * Ng**3) \ + * self.controller_params['rgn2k_factor'] self.vs_refspd = min(turbine.TSR_operational * turbine.v_rated/R, turbine.rated_rotor_speed) * Ng # -- Define some setpoints -- From b12e4997266519e33e5f86697f3ce4cbd27d0c5d Mon Sep 17 00:00:00 2001 From: dzalkind Date: Tue, 3 Sep 2024 14:39:30 -0600 Subject: [PATCH 167/224] Re-enable previous PRC_Mode --- rosco/controller/src/ControllerBlocks.f90 | 24 +++++++++++----------- rosco/controller/src/ReadSetParameters.f90 | 21 +++++++++++-------- rosco/toolbox/inputs/toolbox_schema.yaml | 14 ++++++------- rosco/toolbox/utilities.py | 2 +- 4 files changed, 32 insertions(+), 29 deletions(-) diff --git a/rosco/controller/src/ControllerBlocks.f90 b/rosco/controller/src/ControllerBlocks.f90 index 93837fed..d41081d8 100644 --- a/rosco/controller/src/ControllerBlocks.f90 +++ b/rosco/controller/src/ControllerBlocks.f90 @@ -36,7 +36,7 @@ SUBROUTINE ComputeVariablesSetpoints(CntrPar, LocalVar, objInst, DebugVar, ErrVa ! Set up power reference - IF (CntrPar%PRC_Mode == 1) THEN ! Using power reference control + IF (CntrPar%PRC_Mode == 2) THEN ! Using power reference control IF (CntrPar%PRC_Comm == PRC_Comm_Constant) THEN ! Constant, from DISCON LocalVar%PRC_R_Speed = CntrPar%PRC_R_Speed LocalVar%PRC_R_Torque = CntrPar%PRC_R_Torque @@ -83,13 +83,13 @@ SUBROUTINE ComputeVariablesSetpoints(CntrPar, LocalVar, objInst, DebugVar, ErrVa ! Change pitch reference speed LocalVar%PC_RefSpd_PRC = CntrPar%PC_RefSpd * LocalVar%PRC_R_Speed - ! Power reference tracking generator speed - ! IF (CntrPar%PRC_Mode == 1) THEN - ! LocalVar%PRC_WSE_F = LPFilter(LocalVar%WE_Vw, LocalVar%DT,CntrPar%PRC_LPF_Freq, LocalVar%FP, LocalVar%iStatus, LocalVar%restart, objInst%instLPF) - ! LocalVar%PC_RefSpd_PRC = interp1d(CntrPar%PRC_WindSpeeds,CntrPar%PRC_GenSpeeds,LocalVar%PRC_WSE_F,ErrVar) - ! ELSE - ! LocalVar%PC_RefSpd_PRC = CntrPar%PC_RefSpd - ! ENDIF + ! Lookup table for speed setpoint (PRC_Mode 1) + IF (CntrPar%PRC_Mode == 1) THEN + LocalVar%PRC_WSE_F = LPFilter(LocalVar%WE_Vw, LocalVar%DT,CntrPar%PRC_LPF_Freq, LocalVar%FP, LocalVar%iStatus, LocalVar%restart, objInst%instLPF) + LocalVar%PC_RefSpd_PRC = interp1d(CntrPar%PRC_WindSpeeds,CntrPar%PRC_GenSpeeds,LocalVar%PRC_WSE_F,ErrVar) + ELSE + LocalVar%PC_RefSpd_PRC = CntrPar%PC_RefSpd + ENDIF ! Implement setpoint smoothing IF (LocalVar%SS_DelOmegaF < 0) THEN @@ -125,10 +125,10 @@ SUBROUTINE ComputeVariablesSetpoints(CntrPar, LocalVar, objInst, DebugVar, ErrVa ! Saturate torque reference speed between min speed and rated speed LocalVar%VS_RefSpd = saturate(LocalVar%VS_RefSpd,CntrPar%VS_MinOMSpd, CntrPar%VS_RefSpd * LocalVar%PRC_R_Speed) - ! ! Implement power reference rotor speed (overwrites above), convert to generator speed - ! IF (CntrPar%PRC_Mode == 1) THEN - ! LocalVar%VS_RefSpd = interp1d(CntrPar%PRC_WindSpeeds,CntrPar%PRC_GenSpeeds,LocalVar%WE_Vw_F,ErrVar) - ! ENDIF + ! Simple lookup table for generator speed (PRC_Mode 1) + IF (CntrPar%PRC_Mode == 1) THEN + LocalVar%VS_RefSpd = interp1d(CntrPar%PRC_WindSpeeds,CntrPar%PRC_GenSpeeds,LocalVar%PRC_WSE_F,ErrVar) + ENDIF ! Implement setpoint smoothing IF (LocalVar%SS_DelOmegaF > 0) THEN diff --git a/rosco/controller/src/ReadSetParameters.f90 b/rosco/controller/src/ReadSetParameters.f90 index ef8bda94..0a124895 100644 --- a/rosco/controller/src/ReadSetParameters.f90 +++ b/rosco/controller/src/ReadSetParameters.f90 @@ -457,14 +457,12 @@ SUBROUTINE ReadControlParameterFileSub(CntrPar, LocalVar, accINFILE, accINFILE_s !------------ POWER REFERENCE TRACKING SETPOINTS -------------- CALL ParseInput(FileLines, 'PRC_Comm', CntrPar%PRC_Comm, accINFILE(1), ErrVar, CntrPar%PRC_Mode .NE. 1, UnEc) - CALL ParseInput(FileLines, 'PRC_R_Torque', CntrPar%PRC_R_Torque, accINFILE(1), ErrVar, (CntrPar%PRC_Mode .NE. 1) .OR. (CntrPar%PRC_Comm .NE. PRC_Comm_Constant), UnEc) - CALL ParseInput(FileLines, 'PRC_R_Speed', CntrPar%PRC_R_Speed, accINFILE(1), ErrVar, (CntrPar%PRC_Mode .NE. 1) .OR. (CntrPar%PRC_Comm .NE. PRC_Comm_Constant), UnEc) - CALL ParseInput(FileLines, 'PRC_R_Pitch', CntrPar%PRC_R_Pitch, accINFILE(1), ErrVar, (CntrPar%PRC_Mode .NE. 1) .OR. (CntrPar%PRC_Comm .NE. PRC_Comm_Constant), UnEc) - CALL ParseInput(FileLines, 'PRC_Table_n', CntrPar%PRC_Table_n, accINFILE(1), ErrVar, (CntrPar%PRC_Mode .NE. 1) .OR. (CntrPar%PRC_R_Pitch == 1.0), UnEc) - CALL ParseAry(FileLines, 'PRC_R_Table', CntrPar%PRC_R_Table, CntrPar%PRC_Table_n, accINFILE(1), ErrVar, (CntrPar%PRC_Mode .NE. 1) .OR. (CntrPar%PRC_R_Pitch == 1.0), UnEc) - CALL ParseAry(FileLines, 'PRC_Pitch_Table', CntrPar%PRC_Pitch_Table, CntrPar%PRC_Table_n, accINFILE(1), ErrVar, (CntrPar%PRC_Mode .NE. 1) .OR. (CntrPar%PRC_R_Pitch == 1.0), UnEc) - - ! These need to be adapted + CALL ParseInput(FileLines, 'PRC_R_Torque', CntrPar%PRC_R_Torque, accINFILE(1), ErrVar, (CntrPar%PRC_Mode .NE. 2) .OR. (CntrPar%PRC_Comm .NE. PRC_Comm_Constant), UnEc) + CALL ParseInput(FileLines, 'PRC_R_Speed', CntrPar%PRC_R_Speed, accINFILE(1), ErrVar, (CntrPar%PRC_Mode .NE. 2) .OR. (CntrPar%PRC_Comm .NE. PRC_Comm_Constant), UnEc) + CALL ParseInput(FileLines, 'PRC_R_Pitch', CntrPar%PRC_R_Pitch, accINFILE(1), ErrVar, (CntrPar%PRC_Mode .NE. 2) .OR. (CntrPar%PRC_Comm .NE. PRC_Comm_Constant), UnEc) + CALL ParseInput(FileLines, 'PRC_Table_n', CntrPar%PRC_Table_n, accINFILE(1), ErrVar, (CntrPar%PRC_Mode .NE. 2) .OR. (CntrPar%PRC_R_Pitch == 1.0), UnEc) + CALL ParseAry(FileLines, 'PRC_R_Table', CntrPar%PRC_R_Table, CntrPar%PRC_Table_n, accINFILE(1), ErrVar, (CntrPar%PRC_Mode .NE. 2) .OR. (CntrPar%PRC_R_Pitch == 1.0), UnEc) + CALL ParseAry(FileLines, 'PRC_Pitch_Table', CntrPar%PRC_Pitch_Table, CntrPar%PRC_Table_n, accINFILE(1), ErrVar, (CntrPar%PRC_Mode .NE. 2) .OR. (CntrPar%PRC_R_Pitch == 1.0), UnEc) CALL ParseInput(FileLines, 'PRC_n', CntrPar%PRC_n, accINFILE(1), ErrVar, CntrPar%PRC_Mode == 0) CALL ParseInput(FileLines, 'PRC_LPF_Freq', CntrPar%PRC_LPF_Freq, accINFILE(1), ErrVar, CntrPar%PRC_Mode == 0) CALL ParseAry( FileLines, 'PRC_WindSpeeds', CntrPar%PRC_WindSpeeds, CntrPar%PRC_n, accINFILE(1), ErrVar, CntrPar%PRC_Mode == 0) @@ -1237,7 +1235,12 @@ SUBROUTINE CheckInputs(LocalVar, CntrPar, avrSWAP, ErrVar, size_avcMSG) ErrVar%ErrMsg = 'SS_PCGain must be greater than zero.' ENDIF - IF (CntrPar%PRC_Mode > 0) THEN + IF ((CntrPar%PRC_Mode < 0) .OR. (CntrPar%PRC_Mode > 2)) THEN + ErrVar%aviFAIL = -1 + ErrVar%ErrMsg = 'PRC_Mode must be 0, 1, or 2.' + ENDIF + + IF (CntrPar%PRC_Mode == 2) THEN PRINT *, "Note: PRC Mode = ", CntrPar%PRC_Mode, ", which will affect VS_RefSpeed, VS_TSRopt, and PC_RefSpeed" IF (CntrPar%PRC_Comm == 0) THEN diff --git a/rosco/toolbox/inputs/toolbox_schema.yaml b/rosco/toolbox/inputs/toolbox_schema.yaml index ba74184b..3131f8bf 100644 --- a/rosco/toolbox/inputs/toolbox_schema.yaml +++ b/rosco/toolbox/inputs/toolbox_schema.yaml @@ -869,35 +869,35 @@ properties: description: Number of elements in PRC_WindSpeeds and PRC_GenSpeeds array PRC_Comm: type: number - description: Power reference communication mode, 0- use constant DISCON inputs, 1- use open loop inputs, 2- use ZMQ inputs + description: Power reference communication mode when PRC_Mode = 2, 0- use constant DISCON inputs, 1- use open loop inputs, 2- use ZMQ inputs default: 0 PRC_R_Torque: type: number - description: Constant power rating through changing the rated torque, used if PRC_Comm = 0, default is 1, effective above rated [-] + description: Constant power rating through changing the rated torque, used if PRC_Mode = 2, PRC_Comm = 0, default is 1, effective above rated [-] default: 1 PRC_R_Speed: type: number - description: Constant power rating through changing the rated generator speed, used if PRC_Comm = 0, default is 1, effective above rated [-] + description: Constant power rating through changing the rated generator speed, used if PRC_Mode = 2, PRC_Comm = 0, default is 1, effective above rated [-] default: 1 PRC_R_Pitch: type: number - description: Constant power rating through changing the fine pitch angle, used if PRC_Comm = 0, default is 1, effective below rated [-] + description: Constant power rating through changing the fine pitch angle, used if PRC_Mode = 2, PRC_Comm = 0, default is 1, effective below rated [-] default: 1 PRC_Table_n: type: number - description: Number of elements in PRC_R to _Pitch table + description: Number of elements in PRC_R to _Pitch table. Used if PRC_Mode = 1. default: 20 PRC_Pitch_Table: type: array items: type: number - description: Table of fine pitch versus PRC_R_Table, length should be PRC_Table_n [rad] + description: Table of fine pitch versus PRC_R_Table, length should be PRC_Table_n [rad]. Used if PRC_Mode = 1. default: [0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0] PRC_R_Table: type: array items: type: number - description: Table of turbine rating versus fine pitch (PRC_Pitch_Table), length should be PRC_Table_n, default is 1 [-] + description: Table of turbine rating versus fine pitch (PRC_Pitch_Table), length should be PRC_Table_n, default is 1 [-]. Used if PRC_Mode = 1. default: [1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1] TRA_ExclSpeed: type: number diff --git a/rosco/toolbox/utilities.py b/rosco/toolbox/utilities.py index 1ebc277e..4f35c433 100644 --- a/rosco/toolbox/utilities.py +++ b/rosco/toolbox/utilities.py @@ -101,7 +101,7 @@ def write_DISCON(turbine, controller, param_file='DISCON.IN', txt_filename='Cp_C file.write('{0:<12d} ! PC_ControlMode - Blade pitch control mode {{0: No pitch, fix to fine pitch, 1: active PI blade pitch control}}\n'.format(int(rosco_vt['PC_ControlMode']))) file.write('{0:<12d} ! Y_ControlMode - Yaw control mode {{0: no yaw control, 1: yaw rate control, 2: yaw-by-IPC}}\n'.format(int(rosco_vt['Y_ControlMode']))) file.write('{0:<12d} ! SS_Mode - Setpoint Smoother mode {{0: no setpoint smoothing, 1: introduce setpoint smoothing}}\n'.format(int(rosco_vt['SS_Mode']))) - file.write('{0:<12d} ! PRC_Mode - Power reference tracking mode{{0: use standard rotor speed set points, 1: use PRC rotor speed setpoints}}\n'.format(int(rosco_vt['PRC_Mode']))) + file.write('{0:<12d} ! PRC_Mode - Power reference tracking mode{{0: power control disabled, 1: lookup table from wind speed to generator speed setpoints, 2: change speed, torque, pitch to control power}}\n'.format(int(rosco_vt['PRC_Mode']))) file.write('{0:<12d} ! WE_Mode - Wind speed estimator mode {{0: One-second low pass filtered hub height wind speed, 1: Immersion and Invariance Estimator, 2: Extended Kalman Filter}}\n'.format(int(rosco_vt['WE_Mode']))) file.write('{0:<12d} ! PS_Mode - Pitch saturation mode {{0: no pitch saturation, 1: implement pitch saturation}}\n'.format(int(rosco_vt['PS_Mode']))) file.write('{0:<12d} ! SD_Mode - Shutdown mode {{0: no shutdown procedure, 1: pitch to max pitch at shutdown}}\n'.format(int(rosco_vt['SD_Mode']))) From 0b569e4017916375dab9f0b88a53471712c105f0 Mon Sep 17 00:00:00 2001 From: dzalkind Date: Tue, 3 Sep 2024 14:39:48 -0600 Subject: [PATCH 168/224] Update 5MW yamls for constant power --- Examples/Tune_Cases/NREL5MW.yaml | 3 ++- Examples/Tune_Cases/NREL5MW_PassThrough.yaml | 4 ++-- 2 files changed, 4 insertions(+), 3 deletions(-) diff --git a/Examples/Tune_Cases/NREL5MW.yaml b/Examples/Tune_Cases/NREL5MW.yaml index 9d3ff2a5..b6d74bcc 100644 --- a/Examples/Tune_Cases/NREL5MW.yaml +++ b/Examples/Tune_Cases/NREL5MW.yaml @@ -29,7 +29,8 @@ controller_params: F_LPFType: 1 # {1: first-order low-pass filter, 2: second-order low-pass filter}, [rad/s] (currently filters generator speed and pitch control signals) F_NotchType: 0 # Notch filter on generator speed and/or tower fore-aft motion (for floating) {0: disable, 1: generator speed, 2: tower-top fore-aft motion, 3: generator speed and tower-top fore-aft motion} IPC_ControlMode: 0 # Turn Individual Pitch Control (IPC) for fatigue load reductions (pitch contribution) {0: off, 1: 1P reductions, 2: 1P+2P reductions} - VS_ControlMode: 3 # Generator torque control mode in above rated conditions {0: constant torque, 1: constant power, 2: TSR tracking PI control} + VS_ControlMode: 2 # Generator torque control mode in above rated conditions {0: constant torque, 1: constant power, 2: TSR tracking PI control} + VS_ConstPower: 1 # Use constant power PC_ControlMode: 1 # Blade pitch control mode {0: No pitch, fix to fine pitch, 1: active PI blade pitch control} Y_ControlMode: 0 # Yaw control mode {0: no yaw control, 1: yaw rate control, 2: yaw-by-IPC} SS_Mode: 1 # Setpoint Smoother mode {0: no setpoint smoothing, 1: introduce setpoint smoothing} diff --git a/Examples/Tune_Cases/NREL5MW_PassThrough.yaml b/Examples/Tune_Cases/NREL5MW_PassThrough.yaml index d1f158a7..ab363634 100644 --- a/Examples/Tune_Cases/NREL5MW_PassThrough.yaml +++ b/Examples/Tune_Cases/NREL5MW_PassThrough.yaml @@ -29,8 +29,8 @@ controller_params: F_LPFType: 1 # {1: first-order low-pass filter, 2: second-order low-pass filter}, [rad/s] (currently filters generator speed and pitch control signals) F_NotchType: 0 # Notch filter on generator speed and/or tower fore-aft motion (for floating) {0: disable, 1: generator speed, 2: tower-top fore-aft motion, 3: generator speed and tower-top fore-aft motion} IPC_ControlMode: 0 # Turn Individual Pitch Control (IPC) for fatigue load reductions (pitch contribution) {0: off, 1: 1P reductions, 2: 1P+2P reductions} - VS_ControlMode: 3 # Generator torque control mode in above rated conditions {0: constant torque, 1: constant power, 2: TSR tracking PI control} - PC_ControlMode: 1 # Blade pitch control mode {0: No pitch, fix to fine pitch, 1: active PI blade pitch control} + VS_ControlMode: 2 # Generator torque control mode in above rated conditions {0: constant torque, 1: constant power, 2: TSR tracking PI control} + VS_ConstPower: 1 # Use constant power PC_ControlMode: 1 # Blade pitch control mode {0: No pitch, fix to fine pitch, 1: active PI blade pitch control} Y_ControlMode: 0 # Yaw control mode {0: no yaw control, 1: yaw rate control, 2: yaw-by-IPC} SS_Mode: 1 # Setpoint Smoother mode {0: no setpoint smoothing, 1: introduce setpoint smoothing} WE_Mode: 2 # Wind speed estimator mode {0: One-second low pass filtered hub height wind speed, 1: Immersion and Invariance Estimator (Ortega et al.)} From a24f1579593e069a252ce5cdc0bd74102eaec476 Mon Sep 17 00:00:00 2001 From: dzalkind Date: Tue, 3 Sep 2024 14:48:50 -0600 Subject: [PATCH 169/224] Edit comments --- Examples/{27_power_ref_control.py => 27_soft_cut_out.py} | 0 rosco/controller/src/ControllerBlocks.f90 | 4 +++- 2 files changed, 3 insertions(+), 1 deletion(-) rename Examples/{27_power_ref_control.py => 27_soft_cut_out.py} (100%) diff --git a/Examples/27_power_ref_control.py b/Examples/27_soft_cut_out.py similarity index 100% rename from Examples/27_power_ref_control.py rename to Examples/27_soft_cut_out.py diff --git a/rosco/controller/src/ControllerBlocks.f90 b/rosco/controller/src/ControllerBlocks.f90 index d41081d8..797d2545 100644 --- a/rosco/controller/src/ControllerBlocks.f90 +++ b/rosco/controller/src/ControllerBlocks.f90 @@ -35,7 +35,7 @@ SUBROUTINE ComputeVariablesSetpoints(CntrPar, LocalVar, objInst, DebugVar, ErrVa TYPE(ErrorVariables), INTENT(INOUT) :: ErrVar - ! Set up power reference + ! Set up power control IF (CntrPar%PRC_Mode == 2) THEN ! Using power reference control IF (CntrPar%PRC_Comm == PRC_Comm_Constant) THEN ! Constant, from DISCON LocalVar%PRC_R_Speed = CntrPar%PRC_R_Speed @@ -80,6 +80,8 @@ SUBROUTINE ComputeVariablesSetpoints(CntrPar, LocalVar, objInst, DebugVar, ErrVa LocalVar%PRC_Min_Pitch = CntrPar%PC_FinePit ENDIF + ! End any power control before this point + ! Change pitch reference speed LocalVar%PC_RefSpd_PRC = CntrPar%PC_RefSpd * LocalVar%PRC_R_Speed From 9456ef21edfc4b9b0b5b8657fbe9ad0e7bc1573b Mon Sep 17 00:00:00 2001 From: dzalkind Date: Tue, 3 Sep 2024 16:02:47 -0600 Subject: [PATCH 170/224] Check for IPC openfast flag when using AWC --- rosco/controller/src/ReadSetParameters.f90 | 5 +++++ 1 file changed, 5 insertions(+) diff --git a/rosco/controller/src/ReadSetParameters.f90 b/rosco/controller/src/ReadSetParameters.f90 index 131b6581..f9a90a7d 100644 --- a/rosco/controller/src/ReadSetParameters.f90 +++ b/rosco/controller/src/ReadSetParameters.f90 @@ -1499,6 +1499,11 @@ SUBROUTINE CheckInputs(LocalVar, CntrPar, avrSWAP, ErrVar, size_avcMSG) ErrVar%ErrMsg = 'Pitch offset fault enabled (PF_Mode = 1), but Ptch_Cntrl in ServoDyn has a value of 0. Set it to 1 for individual pitch control.' ENDIF + IF (NINT(avrSWAP(28)) == 0 .AND. (CntrPar%AWC_Mode > 1)) THEN + ErrVar%aviFAIL = -1 + ErrVar%ErrMsg = 'AWC enabled, but Ptch_Cntrl in ServoDyn has a value of 0. Set it to 1 for individual pitch control.' + ENDIF + ! DT IF (LocalVar%DT <= 0.0) THEN ErrVar%aviFAIL = -1 From 9124f93b7abac5204b70eb97b72ab4ac54a6d454 Mon Sep 17 00:00:00 2001 From: dzalkind Date: Tue, 3 Sep 2024 16:31:46 -0600 Subject: [PATCH 171/224] Update discons --- Examples/Test_Cases/BAR_10/BAR_10_DISCON.IN | 18 ++++++++++--- .../DISCON-UMaineSemi.IN | 16 ++++++++++-- Examples/Test_Cases/MHK_RM1/MHK_RM1_DISCON.IN | 18 ++++++++++--- Examples/Test_Cases/NREL-5MW/DISCON.IN | 26 ++++++++++++++----- .../NREL_2p8_127/NREL-2p8-127_DISCON.IN | 18 ++++++++++--- 5 files changed, 78 insertions(+), 18 deletions(-) diff --git a/Examples/Test_Cases/BAR_10/BAR_10_DISCON.IN b/Examples/Test_Cases/BAR_10/BAR_10_DISCON.IN index 49d1d8be..d79e7b4e 100644 --- a/Examples/Test_Cases/BAR_10/BAR_10_DISCON.IN +++ b/Examples/Test_Cases/BAR_10/BAR_10_DISCON.IN @@ -1,5 +1,5 @@ ! Controller parameter input file for the BAR_10 wind turbine -! - File written using ROSCO version 2.9.4 controller tuning logic on 07/01/24 +! - File written using ROSCO version 2.9.4 controller tuning logic on 09/03/24 !------- SIMULATION CONTROL ------------------------------------------------------------ 1 ! LoggingLevel - {0: write no debug files, 1: write standard output .dbg-file, 2: LoggingLevel 1 + ROSCO LocalVars (.dbg2) 3: LoggingLevel 2 + complete avrSWAP-array (.dbg3)} @@ -15,7 +15,7 @@ 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} -0 ! PRC_Mode - Power reference tracking mode{0: use standard rotor speed set points, 1: use PRC rotor speed setpoints} +0 ! PRC_Mode - Power reference tracking mode{0: power control disabled, 1: lookup table from wind speed to generator speed setpoints, 2: change speed, torque, pitch to control power} 2 ! WE_Mode - Wind speed estimator mode {0: One-second low pass filtered hub height wind speed, 1: Immersion and Invariance Estimator, 2: Extended Kalman Filter} 1 ! PS_Mode - Pitch saturation mode {0: no pitch saturation, 1: implement pitch saturation} 0 ! SD_Mode - Shutdown mode {0: no shutdown procedure, 1: pitch to max pitch at shutdown} @@ -77,7 +77,7 @@ !------- VS TORQUE CONTROL ------------------------------------------------ 98.00000000000 ! VS_GenEff - Generator efficiency mechanical power -> electrical power, [should match the efficiency defined in the generator properties!], [%] 63892.81326000 ! VS_ArSatTq - Above rated generator torque PI control saturation, [Nm] -4500000.000000 ! VS_MaxRat - Maximum torque rate (in absolute value) in torque controller, [Nm/s]. +62000.00000000 ! VS_MaxRat - Maximum torque rate (in absolute value) in torque controller, [Nm/s]. 70282.09458000 ! VS_MaxTq - Maximum generator torque in Region 3 (HSS side), [Nm]. 0.000000000000 ! VS_MinTq - Minimum generator torque (HSS side), [Nm]. 27.49717000000 ! VS_MinOMSpd - Minimum generator speed [rad/s] @@ -96,6 +96,13 @@ 0.00100 ! SS_PCGain - Collective pitch controller setpoint smoother gain, [-]. !------- POWER REFERENCE TRACKING -------------------------------------- +0 ! PRC_Comm - Power reference communication mode when PRC_Mode = 2, 0- use constant DISCON inputs, 1- use open loop inputs, 2- use ZMQ inputs +1.00000 ! PRC_R_Torque - Constant power rating through changing the rated torque, used if PRC_Mode = 2, PRC_Comm = 0, default is 1, effective above rated [-] +1.00000 ! PRC_R_Speed - Constant power rating through changing the rated generator speed, used if PRC_Mode = 2, PRC_Comm = 0, default is 1, effective above rated [-] +1.00000 ! PRC_R_Pitch - Constant power rating through changing the fine pitch angle, used if PRC_Mode = 2, PRC_Comm = 0, default is 1, effective below rated [-] +20 ! PRC_Table_n - Number of elements in PRC_R to _Pitch table. Used if PRC_Mode = 1. +0.0000 0.0526 0.1053 0.1579 0.2105 0.2632 0.3158 0.3684 0.4211 0.4737 0.5263 0.5789 0.6316 0.6842 0.7368 0.7895 0.8421 0.8947 0.9474 1.0000 ! PRC_R_Table - Table of turbine rating versus fine pitch (PRC_Pitch_Table), length should be PRC_Table_n, default is 1 [-]. Used if PRC_Mode = 1. +0.1766 0.1707 0.1647 0.1586 0.1522 0.1458 0.1391 0.1323 0.1252 0.1178 0.1102 0.1022 0.0939 0.0850 0.0755 0.0655 0.0538 0.0405 0.0238 -0.0123 ! PRC_Pitch_Table - Table of fine pitch versus PRC_R_Table, length should be PRC_Table_n [rad]. Used if PRC_Mode = 1. 2 ! PRC_n - Number of elements in PRC_WindSpeeds and PRC_GenSpeeds array 0.07854 ! PRC_LPF_Freq - Frequency of the low pass filter on the wind speed estimate used to set PRC_GenSpeeds [rad/s] 3.0000 25.0000 ! PRC_WindSpeeds - Array of wind speeds used in rotor speed vs. wind speed lookup table [m/s] @@ -154,6 +161,8 @@ !------- Open Loop Control ----------------------------------------------------- "unused" ! OL_Filename - Input file with open loop timeseries (absolute path or relative to this file) +0 ! OL_BP_Mode - Breakpoint mode for open loop control, 0 - indexed by time (default), 1 - indexed by wind speed] +0.000000 ! OL_BP_FiltFreq - Natural frequency of 1st order filter on breakpoint for open loop control. 0 will skip filter. 0 ! Ind_Breakpoint - The column in OL_Filename that contains the breakpoint (time if OL_Mode = 1) 0 0 0 ! Ind_BldPitch - The columns in OL_Filename that contains the blade pitch (1,2,3) inputs in rad [array] 0 ! Ind_GenTq - The column in OL_Filename that contains the generator torque in Nm @@ -162,6 +171,9 @@ 0.0000 0.0000 0.0000 0.0000 ! RP_Gains - PID gains and Tf of derivative for rotor position control (used if OL_Mode = 2) 0 ! Ind_CableControl - The column(s) in OL_Filename that contains the cable control inputs in m [Used with CC_Mode = 2, must be the same size as CC_Group_N] 0 ! Ind_StructControl - The column(s) in OL_Filename that contains the structural control inputs [Used with StC_Mode = 2, must be the same size as StC_Group_N] +0 ! Ind_R_Speed - Index (column, 1-indexed) of power rating via speed offset +0 ! Ind_R_Torque - Index (column, 1-indexed) of power rating via torque offset +0 ! Ind_R_Pitch - Index (column, 1-indexed) of power rating via pitch offset !------- Pitch Actuator Model ----------------------------------------------------- 3.140000000000 ! PA_CornerFreq - Pitch actuator bandwidth/cut-off frequency [rad/s] diff --git a/Examples/Test_Cases/IEA-15-240-RWT-UMaineSemi/DISCON-UMaineSemi.IN b/Examples/Test_Cases/IEA-15-240-RWT-UMaineSemi/DISCON-UMaineSemi.IN index a55a49d0..ed348ab9 100644 --- a/Examples/Test_Cases/IEA-15-240-RWT-UMaineSemi/DISCON-UMaineSemi.IN +++ b/Examples/Test_Cases/IEA-15-240-RWT-UMaineSemi/DISCON-UMaineSemi.IN @@ -1,5 +1,5 @@ ! Controller parameter input file for the IEA-15-240-RWT-UMaineSemi wind turbine -! - File written using ROSCO version 2.9.4 controller tuning logic on 07/01/24 +! - File written using ROSCO version 2.9.4 controller tuning logic on 09/03/24 !------- SIMULATION CONTROL ------------------------------------------------------------ 2 ! LoggingLevel - {0: write no debug files, 1: write standard output .dbg-file, 2: LoggingLevel 1 + ROSCO LocalVars (.dbg2) 3: LoggingLevel 2 + complete avrSWAP-array (.dbg3)} @@ -15,7 +15,7 @@ 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} -0 ! PRC_Mode - Power reference tracking mode{0: use standard rotor speed set points, 1: use PRC rotor speed setpoints} +0 ! PRC_Mode - Power reference tracking mode{0: power control disabled, 1: lookup table from wind speed to generator speed setpoints, 2: change speed, torque, pitch to control power} 2 ! WE_Mode - Wind speed estimator mode {0: One-second low pass filtered hub height wind speed, 1: Immersion and Invariance Estimator, 2: Extended Kalman Filter} 1 ! PS_Mode - Pitch saturation mode {0: no pitch saturation, 1: implement pitch saturation} 0 ! SD_Mode - Shutdown mode {0: no shutdown procedure, 1: pitch to max pitch at shutdown} @@ -96,6 +96,13 @@ 0.00100 ! SS_PCGain - Collective pitch controller setpoint smoother gain, [-]. !------- POWER REFERENCE TRACKING -------------------------------------- +0 ! PRC_Comm - Power reference communication mode when PRC_Mode = 2, 0- use constant DISCON inputs, 1- use open loop inputs, 2- use ZMQ inputs +1.00000 ! PRC_R_Torque - Constant power rating through changing the rated torque, used if PRC_Mode = 2, PRC_Comm = 0, default is 1, effective above rated [-] +1.00000 ! PRC_R_Speed - Constant power rating through changing the rated generator speed, used if PRC_Mode = 2, PRC_Comm = 0, default is 1, effective above rated [-] +1.00000 ! PRC_R_Pitch - Constant power rating through changing the fine pitch angle, used if PRC_Mode = 2, PRC_Comm = 0, default is 1, effective below rated [-] +20 ! PRC_Table_n - Number of elements in PRC_R to _Pitch table. Used if PRC_Mode = 1. +0.0000 0.0526 0.1053 0.1579 0.2105 0.2632 0.3158 0.3684 0.4211 0.4737 0.5263 0.5789 0.6316 0.6842 0.7368 0.7895 0.8421 0.8947 0.9474 1.0000 ! PRC_R_Table - Table of turbine rating versus fine pitch (PRC_Pitch_Table), length should be PRC_Table_n, default is 1 [-]. Used if PRC_Mode = 1. +0.2296 0.2222 0.2144 0.2066 0.1984 0.1902 0.1814 0.1726 0.1633 0.1538 0.1439 0.1334 0.1226 0.1112 0.0989 0.0858 0.0715 0.0552 0.0351 0.0000 ! PRC_Pitch_Table - Table of fine pitch versus PRC_R_Table, length should be PRC_Table_n [rad]. Used if PRC_Mode = 1. 2 ! PRC_n - Number of elements in PRC_WindSpeeds and PRC_GenSpeeds array 0.07854 ! PRC_LPF_Freq - Frequency of the low pass filter on the wind speed estimate used to set PRC_GenSpeeds [rad/s] 3.0000 25.0000 ! PRC_WindSpeeds - Array of wind speeds used in rotor speed vs. wind speed lookup table [m/s] @@ -154,6 +161,8 @@ !------- Open Loop Control ----------------------------------------------------- "unused" ! OL_Filename - Input file with open loop timeseries (absolute path or relative to this file) +0 ! OL_BP_Mode - Breakpoint mode for open loop control, 0 - indexed by time (default), 1 - indexed by wind speed] +0.000000 ! OL_BP_FiltFreq - Natural frequency of 1st order filter on breakpoint for open loop control. 0 will skip filter. 0 ! Ind_Breakpoint - The column in OL_Filename that contains the breakpoint (time if OL_Mode = 1) 0 0 0 ! Ind_BldPitch - The columns in OL_Filename that contains the blade pitch (1,2,3) inputs in rad [array] 0 ! Ind_GenTq - The column in OL_Filename that contains the generator torque in Nm @@ -162,6 +171,9 @@ 0.0000 0.0000 0.0000 0.0000 ! RP_Gains - PID gains and Tf of derivative for rotor position control (used if OL_Mode = 2) 0 ! Ind_CableControl - The column(s) in OL_Filename that contains the cable control inputs in m [Used with CC_Mode = 2, must be the same size as CC_Group_N] 0 ! Ind_StructControl - The column(s) in OL_Filename that contains the structural control inputs [Used with StC_Mode = 2, must be the same size as StC_Group_N] +0 ! Ind_R_Speed - Index (column, 1-indexed) of power rating via speed offset +0 ! Ind_R_Torque - Index (column, 1-indexed) of power rating via torque offset +0 ! Ind_R_Pitch - Index (column, 1-indexed) of power rating via pitch offset !------- Pitch Actuator Model ----------------------------------------------------- 1.570800000000 ! PA_CornerFreq - Pitch actuator bandwidth/cut-off frequency [rad/s] diff --git a/Examples/Test_Cases/MHK_RM1/MHK_RM1_DISCON.IN b/Examples/Test_Cases/MHK_RM1/MHK_RM1_DISCON.IN index e23b75b5..89395380 100644 --- a/Examples/Test_Cases/MHK_RM1/MHK_RM1_DISCON.IN +++ b/Examples/Test_Cases/MHK_RM1/MHK_RM1_DISCON.IN @@ -1,5 +1,5 @@ ! Controller parameter input file for the MHK_RM1_Floating wind turbine -! - File written using ROSCO version 2.9.4 controller tuning logic on 07/01/24 +! - File written using ROSCO version 2.9.4 controller tuning logic on 09/03/24 !------- SIMULATION CONTROL ------------------------------------------------------------ 2 ! LoggingLevel - {0: write no debug files, 1: write standard output .dbg-file, 2: LoggingLevel 1 + ROSCO LocalVars (.dbg2) 3: LoggingLevel 2 + complete avrSWAP-array (.dbg3)} @@ -15,7 +15,7 @@ 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} -0 ! PRC_Mode - Power reference tracking mode{0: use standard rotor speed set points, 1: use PRC rotor speed setpoints} +0 ! PRC_Mode - Power reference tracking mode{0: power control disabled, 1: lookup table from wind speed to generator speed setpoints, 2: change speed, torque, pitch to control power} 0 ! WE_Mode - Wind speed estimator mode {0: One-second low pass filtered hub height wind speed, 1: Immersion and Invariance Estimator, 2: Extended Kalman Filter} 0 ! PS_Mode - Pitch saturation mode {0: no pitch saturation, 1: implement pitch saturation} 0 ! SD_Mode - Shutdown mode {0: no shutdown procedure, 1: pitch to max pitch at shutdown} @@ -77,7 +77,7 @@ !------- VS TORQUE CONTROL ------------------------------------------------ 94.40000000000 ! VS_GenEff - Generator efficiency mechanical power -> electrical power, [should match the efficiency defined in the generator properties!], [%] 8300.335630000 ! VS_ArSatTq - Above rated generator torque PI control saturation, [Nm] -1500000.000000 ! VS_MaxRat - Maximum torque rate (in absolute value) in torque controller, [Nm/s]. +7800.000000000 ! VS_MaxRat - Maximum torque rate (in absolute value) in torque controller, [Nm/s]. 12450.50344000 ! VS_MaxTq - Maximum generator torque in Region 3 (HSS side), [Nm]. 0.000000000000 ! VS_MinTq - Minimum generator torque (HSS side), [Nm]. 19.00309000000 ! VS_MinOMSpd - Minimum generator speed [rad/s] @@ -96,6 +96,13 @@ 0.00100 ! SS_PCGain - Collective pitch controller setpoint smoother gain, [-]. !------- POWER REFERENCE TRACKING -------------------------------------- +0 ! PRC_Comm - Power reference communication mode when PRC_Mode = 2, 0- use constant DISCON inputs, 1- use open loop inputs, 2- use ZMQ inputs +1.00000 ! PRC_R_Torque - Constant power rating through changing the rated torque, used if PRC_Mode = 2, PRC_Comm = 0, default is 1, effective above rated [-] +1.00000 ! PRC_R_Speed - Constant power rating through changing the rated generator speed, used if PRC_Mode = 2, PRC_Comm = 0, default is 1, effective above rated [-] +1.00000 ! PRC_R_Pitch - Constant power rating through changing the fine pitch angle, used if PRC_Mode = 2, PRC_Comm = 0, default is 1, effective below rated [-] +20 ! PRC_Table_n - Number of elements in PRC_R to _Pitch table. Used if PRC_Mode = 1. +0.0000 0.0526 0.1053 0.1579 0.2105 0.2632 0.3158 0.3684 0.4211 0.4737 0.5263 0.5789 0.6316 0.6842 0.7368 0.7895 0.8421 0.8947 0.9474 1.0000 ! PRC_R_Table - Table of turbine rating versus fine pitch (PRC_Pitch_Table), length should be PRC_Table_n, default is 1 [-]. Used if PRC_Mode = 1. +0.1702 0.1654 0.1607 0.1556 0.1505 0.1453 0.1398 0.1341 0.1284 0.1221 0.1157 0.1089 0.1016 0.0939 0.0853 0.0760 0.0656 0.0528 0.0364 0.0013 ! PRC_Pitch_Table - Table of fine pitch versus PRC_R_Table, length should be PRC_Table_n [rad]. Used if PRC_Mode = 1. 2 ! PRC_n - Number of elements in PRC_WindSpeeds and PRC_GenSpeeds array 0.07854 ! PRC_LPF_Freq - Frequency of the low pass filter on the wind speed estimate used to set PRC_GenSpeeds [rad/s] 3.0000 25.0000 ! PRC_WindSpeeds - Array of wind speeds used in rotor speed vs. wind speed lookup table [m/s] @@ -154,6 +161,8 @@ !------- Open Loop Control ----------------------------------------------------- "unused" ! OL_Filename - Input file with open loop timeseries (absolute path or relative to this file) +0 ! OL_BP_Mode - Breakpoint mode for open loop control, 0 - indexed by time (default), 1 - indexed by wind speed] +0.000000 ! OL_BP_FiltFreq - Natural frequency of 1st order filter on breakpoint for open loop control. 0 will skip filter. 0 ! Ind_Breakpoint - The column in OL_Filename that contains the breakpoint (time if OL_Mode = 1) 0 0 0 ! Ind_BldPitch - The columns in OL_Filename that contains the blade pitch (1,2,3) inputs in rad [array] 0 ! Ind_GenTq - The column in OL_Filename that contains the generator torque in Nm @@ -162,6 +171,9 @@ 0.0000 0.0000 0.0000 0.0000 ! RP_Gains - PID gains and Tf of derivative for rotor position control (used if OL_Mode = 2) 0 ! Ind_CableControl - The column(s) in OL_Filename that contains the cable control inputs in m [Used with CC_Mode = 2, must be the same size as CC_Group_N] 0 ! Ind_StructControl - The column(s) in OL_Filename that contains the structural control inputs [Used with StC_Mode = 2, must be the same size as StC_Group_N] +0 ! Ind_R_Speed - Index (column, 1-indexed) of power rating via speed offset +0 ! Ind_R_Torque - Index (column, 1-indexed) of power rating via torque offset +0 ! Ind_R_Pitch - Index (column, 1-indexed) of power rating via pitch offset !------- Pitch Actuator Model ----------------------------------------------------- 3.140000000000 ! PA_CornerFreq - Pitch actuator bandwidth/cut-off frequency [rad/s] diff --git a/Examples/Test_Cases/NREL-5MW/DISCON.IN b/Examples/Test_Cases/NREL-5MW/DISCON.IN index bf86cf78..185c4126 100644 --- a/Examples/Test_Cases/NREL-5MW/DISCON.IN +++ b/Examples/Test_Cases/NREL-5MW/DISCON.IN @@ -1,5 +1,5 @@ ! Controller parameter input file for the NREL-5MW wind turbine -! - File written using ROSCO version 2.9.4 controller tuning logic on 07/01/24 +! - File written using ROSCO version 2.9.4 controller tuning logic on 09/03/24 !------- SIMULATION CONTROL ------------------------------------------------------------ 1 ! LoggingLevel - {0: write no debug files, 1: write standard output .dbg-file, 2: LoggingLevel 1 + ROSCO LocalVars (.dbg2) 3: LoggingLevel 2 + complete avrSWAP-array (.dbg3)} @@ -10,12 +10,12 @@ !------- 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 ! IPC_ControlMode - Turn Individual Pitch Control (IPC) for fatigue load reductions (pitch contribution) {0: off, 1: 1P reductions, 2: 1P+2P reductions} -3 ! VS_ControlMode - Generator torque control mode in above rated conditions (0- no torque control, 1- k*omega^2 with PI transitions, 2- WSE TSR Tracking, 3- Power-based TSR Tracking)} -0 ! VS_ConstPower - Do constant power torque control, where above rated torque varies, 0 for constant torque} +2 ! VS_ControlMode - Generator torque control mode in above rated conditions (0- no torque control, 1- k*omega^2 with PI transitions, 2- WSE TSR Tracking, 3- Power-based TSR Tracking)} +1 ! VS_ConstPower - Do constant power torque control, where above rated torque varies, 0 for constant torque} 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} -0 ! PRC_Mode - Power reference tracking mode{0: use standard rotor speed set points, 1: use PRC rotor speed setpoints} +0 ! PRC_Mode - Power reference tracking mode{0: power control disabled, 1: lookup table from wind speed to generator speed setpoints, 2: change speed, torque, pitch to control power} 2 ! WE_Mode - Wind speed estimator mode {0: One-second low pass filtered hub height wind speed, 1: Immersion and Invariance Estimator, 2: Extended Kalman Filter} 1 ! PS_Mode - Pitch saturation mode {0: no pitch saturation, 1: implement pitch saturation} 0 ! SD_Mode - Shutdown mode {0: no shutdown procedure, 1: pitch to max pitch at shutdown} @@ -53,7 +53,7 @@ !------- BLADE PITCH CONTROL ---------------------------------------------- 30 ! PC_GS_n - Amount of gain-scheduling table entries 0.056789 0.084492 0.106018 0.124332 0.140807 0.155903 0.169931 0.183270 0.196062 0.208354 0.220050 0.231503 0.242646 0.253377 0.263967 0.274233 0.284343 0.294292 0.303997 0.313626 0.322957 0.332260 0.341319 0.350368 0.359221 0.368059 0.376700 0.385301 0.393691 0.402050 ! PC_GS_angles - Gain-schedule table: pitch angles [rad]. --0.019085 -0.016739 -0.014837 -0.013265 -0.011943 -0.010816 -0.009844 -0.008997 -0.008252 -0.007593 -0.007004 -0.006475 -0.005998 -0.005565 -0.005171 -0.004810 -0.004479 -0.004173 -0.003890 -0.003628 -0.003385 -0.003157 -0.002945 -0.002746 -0.002559 -0.002384 -0.002219 -0.002062 -0.001915 -0.001775 ! PC_GS_KP - Gain-schedule table: pitch controller kp gains [s]. +-0.020751 -0.018231 -0.016188 -0.014498 -0.013078 -0.011868 -0.010823 -0.009913 -0.009113 -0.008404 -0.007772 -0.007204 -0.006692 -0.006227 -0.005803 -0.005415 -0.005059 -0.004731 -0.004427 -0.004146 -0.003884 -0.003640 -0.003411 -0.003198 -0.002997 -0.002809 -0.002631 -0.002463 -0.002305 -0.002155 ! PC_GS_KP - Gain-schedule table: pitch controller kp gains [s]. -0.008417 -0.007536 -0.006822 -0.006232 -0.005735 -0.005312 -0.004947 -0.004629 -0.004350 -0.004102 -0.003881 -0.003682 -0.003503 -0.003341 -0.003192 -0.003057 -0.002932 -0.002818 -0.002712 -0.002613 -0.002522 -0.002436 -0.002357 -0.002282 -0.002212 -0.002146 -0.002084 -0.002025 -0.001970 -0.001917 ! PC_GS_KI - Gain-schedule table: pitch controller ki gains [-]. 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 ! PC_GS_KD - Gain-schedule table: pitch controller kd gains 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 ! PC_GS_TF - Gain-schedule table: pitch controller tf gains (derivative filter) @@ -77,7 +77,7 @@ !------- VS TORQUE CONTROL ------------------------------------------------ 94.40000000000 ! VS_GenEff - Generator efficiency mechanical power -> electrical power, [should match the efficiency defined in the generator properties!], [%] 43093.51876000 ! VS_ArSatTq - Above rated generator torque PI control saturation, [Nm] -1500000.000000 ! VS_MaxRat - Maximum torque rate (in absolute value) in torque controller, [Nm/s]. +40000.00000000 ! VS_MaxRat - Maximum torque rate (in absolute value) in torque controller, [Nm/s]. 47402.87063000 ! VS_MaxTq - Maximum generator torque in Region 3 (HSS side), [Nm]. 0.000000000000 ! VS_MinTq - Minimum generator torque (HSS side), [Nm]. 35.29006000000 ! VS_MinOMSpd - Minimum generator speed [rad/s] @@ -96,6 +96,13 @@ 0.00100 ! SS_PCGain - Collective pitch controller setpoint smoother gain, [-]. !------- POWER REFERENCE TRACKING -------------------------------------- +0 ! PRC_Comm - Power reference communication mode when PRC_Mode = 2, 0- use constant DISCON inputs, 1- use open loop inputs, 2- use ZMQ inputs +1.00000 ! PRC_R_Torque - Constant power rating through changing the rated torque, used if PRC_Mode = 2, PRC_Comm = 0, default is 1, effective above rated [-] +1.00000 ! PRC_R_Speed - Constant power rating through changing the rated generator speed, used if PRC_Mode = 2, PRC_Comm = 0, default is 1, effective above rated [-] +1.00000 ! PRC_R_Pitch - Constant power rating through changing the fine pitch angle, used if PRC_Mode = 2, PRC_Comm = 0, default is 1, effective below rated [-] +20 ! PRC_Table_n - Number of elements in PRC_R to _Pitch table. Used if PRC_Mode = 1. +0.0000 0.0526 0.1053 0.1579 0.2105 0.2632 0.3158 0.3684 0.4211 0.4737 0.5263 0.5789 0.6316 0.6842 0.7368 0.7895 0.8421 0.8947 0.9474 1.0000 ! PRC_R_Table - Table of turbine rating versus fine pitch (PRC_Pitch_Table), length should be PRC_Table_n, default is 1 [-]. Used if PRC_Mode = 1. +0.1933 0.1876 0.1819 0.1761 0.1701 0.1640 0.1577 0.1511 0.1446 0.1375 0.1303 0.1227 0.1147 0.1060 0.0969 0.0865 0.0750 0.0615 0.0436 0.0018 ! PRC_Pitch_Table - Table of fine pitch versus PRC_R_Table, length should be PRC_Table_n [rad]. Used if PRC_Mode = 1. 2 ! PRC_n - Number of elements in PRC_WindSpeeds and PRC_GenSpeeds array 0.07854 ! PRC_LPF_Freq - Frequency of the low pass filter on the wind speed estimate used to set PRC_GenSpeeds [rad/s] 3.0000 25.0000 ! PRC_WindSpeeds - Array of wind speeds used in rotor speed vs. wind speed lookup table [m/s] @@ -113,7 +120,7 @@ 36 26 ! PerfTableSize - Size of rotor performance tables, first number refers to number of blade pitch angles, second number referse to number of tip-speed ratios 60 ! WE_FOPoles_N - Number of first-order system poles used in EKF 3.0000 3.2897 3.5793 3.8690 4.1586 4.4483 4.7379 5.0276 5.3172 5.6069 5.8966 6.1862 6.4759 6.7655 7.0552 7.3448 7.6345 7.9241 8.2138 8.5034 8.7931 9.0828 9.3724 9.6621 9.9517 10.2414 10.5310 10.8207 11.1103 11.4000 11.8533 12.3067 12.7600 13.2133 13.6667 14.1200 14.5733 15.0267 15.4800 15.9333 16.3867 16.8400 17.2933 17.7467 18.2000 18.6533 19.1067 19.5600 20.0133 20.4667 20.9200 21.3733 21.8267 22.2800 22.7333 23.1867 23.6400 24.0933 24.5467 25.0000 ! WE_FOPoles_v - Wind speeds corresponding to first-order system poles [m/s] --0.01640352 -0.01798730 -0.01957109 -0.02115488 -0.02273867 -0.02432245 -0.02590624 -0.02749003 -0.02907382 -0.03065761 -0.03224139 -0.03382518 -0.03540897 -0.03699276 -0.03857654 -0.04016033 -0.04174412 -0.04332791 -0.04491170 -0.04649548 -0.04807927 -0.04966306 -0.05124685 -0.05283063 -0.05441442 -0.05599821 -0.05763347 -0.05907205 -0.06912889 -0.05993737 -0.05021616 -0.05780794 -0.06849544 -0.08052122 -0.09351145 -0.10710432 -0.12106730 -0.13547025 -0.15041833 -0.16588021 -0.18135551 -0.19724989 -0.21342206 -0.22970423 -0.24663982 -0.26354532 -0.28064419 -0.29794214 -0.31532544 -0.33332004 -0.35128130 -0.36985759 -0.38827549 -0.40713466 -0.42584061 -0.44509747 -0.46449375 -0.48460700 -0.50475242 -0.52537402 ! WE_FOPoles - First order system poles [1/s] +-0.01640352 -0.01798730 -0.01957109 -0.02115488 -0.02273867 -0.02432245 -0.02590624 -0.02749003 -0.02907382 -0.03065761 -0.03224139 -0.03382518 -0.03540897 -0.03699276 -0.03857654 -0.04016033 -0.04174412 -0.04332791 -0.04491170 -0.04649548 -0.04807927 -0.04966306 -0.05124685 -0.05283063 -0.05441442 -0.05599821 -0.05763347 -0.05907205 -0.06912889 -0.05993737 0.02104202 0.01345023 0.00276274 -0.00926304 -0.02225327 -0.03584614 -0.04980912 -0.06421207 -0.07916015 -0.09462203 -0.11009734 -0.12599172 -0.14216388 -0.15844606 -0.17538164 -0.19228714 -0.20938601 -0.22668396 -0.24406726 -0.26206186 -0.28002312 -0.29859942 -0.31701731 -0.33587649 -0.35458243 -0.37383930 -0.39323557 -0.41334882 -0.43349424 -0.45411584 ! WE_FOPoles - First order system poles [1/s] !------- YAW CONTROL ------------------------------------------------------ 0.00000 ! Y_uSwitch - Wind speed to switch between Y_ErrThresh. If zero, only the second value of Y_ErrThresh is used [m/s] @@ -154,6 +161,8 @@ !------- Open Loop Control ----------------------------------------------------- "unused" ! OL_Filename - Input file with open loop timeseries (absolute path or relative to this file) +0 ! OL_BP_Mode - Breakpoint mode for open loop control, 0 - indexed by time (default), 1 - indexed by wind speed] +0.000000 ! OL_BP_FiltFreq - Natural frequency of 1st order filter on breakpoint for open loop control. 0 will skip filter. 0 ! Ind_Breakpoint - The column in OL_Filename that contains the breakpoint (time if OL_Mode = 1) 0 0 0 ! Ind_BldPitch - The columns in OL_Filename that contains the blade pitch (1,2,3) inputs in rad [array] 0 ! Ind_GenTq - The column in OL_Filename that contains the generator torque in Nm @@ -162,6 +171,9 @@ 0.0000 0.0000 0.0000 0.0000 ! RP_Gains - PID gains and Tf of derivative for rotor position control (used if OL_Mode = 2) 0 ! Ind_CableControl - The column(s) in OL_Filename that contains the cable control inputs in m [Used with CC_Mode = 2, must be the same size as CC_Group_N] 0 ! Ind_StructControl - The column(s) in OL_Filename that contains the structural control inputs [Used with StC_Mode = 2, must be the same size as StC_Group_N] +0 ! Ind_R_Speed - Index (column, 1-indexed) of power rating via speed offset +0 ! Ind_R_Torque - Index (column, 1-indexed) of power rating via torque offset +0 ! Ind_R_Pitch - Index (column, 1-indexed) of power rating via pitch offset !------- Pitch Actuator Model ----------------------------------------------------- 3.140000000000 ! PA_CornerFreq - Pitch actuator bandwidth/cut-off frequency [rad/s] diff --git a/Examples/Test_Cases/NREL_2p8_127/NREL-2p8-127_DISCON.IN b/Examples/Test_Cases/NREL_2p8_127/NREL-2p8-127_DISCON.IN index 46be3ce2..a73c2829 100644 --- a/Examples/Test_Cases/NREL_2p8_127/NREL-2p8-127_DISCON.IN +++ b/Examples/Test_Cases/NREL_2p8_127/NREL-2p8-127_DISCON.IN @@ -1,5 +1,5 @@ ! Controller parameter input file for the NREL-2p8-127 wind turbine -! - File written using ROSCO version 2.9.4 controller tuning logic on 07/01/24 +! - File written using ROSCO version 2.9.4 controller tuning logic on 09/03/24 !------- SIMULATION CONTROL ------------------------------------------------------------ 2 ! LoggingLevel - {0: write no debug files, 1: write standard output .dbg-file, 2: LoggingLevel 1 + ROSCO LocalVars (.dbg2) 3: LoggingLevel 2 + complete avrSWAP-array (.dbg3)} @@ -15,7 +15,7 @@ 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} -0 ! PRC_Mode - Power reference tracking mode{0: use standard rotor speed set points, 1: use PRC rotor speed setpoints} +0 ! PRC_Mode - Power reference tracking mode{0: power control disabled, 1: lookup table from wind speed to generator speed setpoints, 2: change speed, torque, pitch to control power} 2 ! WE_Mode - Wind speed estimator mode {0: One-second low pass filtered hub height wind speed, 1: Immersion and Invariance Estimator, 2: Extended Kalman Filter} 1 ! PS_Mode - Pitch saturation mode {0: no pitch saturation, 1: implement pitch saturation} 0 ! SD_Mode - Shutdown mode {0: no shutdown procedure, 1: pitch to max pitch at shutdown} @@ -77,7 +77,7 @@ !------- VS TORQUE CONTROL ------------------------------------------------ 93.94773000000 ! VS_GenEff - Generator efficiency mechanical power -> electrical power, [should match the efficiency defined in the generator properties!], [%] 24248.54567000 ! VS_ArSatTq - Above rated generator torque PI control saturation, [Nm] -1500000.000000 ! VS_MaxRat - Maximum torque rate (in absolute value) in torque controller, [Nm/s]. +22000.00000000 ! VS_MaxRat - Maximum torque rate (in absolute value) in torque controller, [Nm/s]. 26673.40024000 ! VS_MaxTq - Maximum generator torque in Region 3 (HSS side), [Nm]. 0.000000000000 ! VS_MinTq - Minimum generator torque (HSS side), [Nm]. 37.81562000000 ! VS_MinOMSpd - Minimum generator speed [rad/s] @@ -96,6 +96,13 @@ 0.00100 ! SS_PCGain - Collective pitch controller setpoint smoother gain, [-]. !------- POWER REFERENCE TRACKING -------------------------------------- +0 ! PRC_Comm - Power reference communication mode when PRC_Mode = 2, 0- use constant DISCON inputs, 1- use open loop inputs, 2- use ZMQ inputs +1.00000 ! PRC_R_Torque - Constant power rating through changing the rated torque, used if PRC_Mode = 2, PRC_Comm = 0, default is 1, effective above rated [-] +1.00000 ! PRC_R_Speed - Constant power rating through changing the rated generator speed, used if PRC_Mode = 2, PRC_Comm = 0, default is 1, effective above rated [-] +1.00000 ! PRC_R_Pitch - Constant power rating through changing the fine pitch angle, used if PRC_Mode = 2, PRC_Comm = 0, default is 1, effective below rated [-] +20 ! PRC_Table_n - Number of elements in PRC_R to _Pitch table. Used if PRC_Mode = 1. +0.0000 0.0526 0.1053 0.1579 0.2105 0.2632 0.3158 0.3684 0.4211 0.4737 0.5263 0.5789 0.6316 0.6842 0.7368 0.7895 0.8421 0.8947 0.9474 1.0000 ! PRC_R_Table - Table of turbine rating versus fine pitch (PRC_Pitch_Table), length should be PRC_Table_n, default is 1 [-]. Used if PRC_Mode = 1. +0.2300 0.2236 0.2170 0.2102 0.2032 0.1960 0.1886 0.1808 0.1729 0.1646 0.1561 0.1471 0.1378 0.1280 0.1174 0.1060 0.0936 0.0791 0.0606 0.0000 ! PRC_Pitch_Table - Table of fine pitch versus PRC_R_Table, length should be PRC_Table_n [rad]. Used if PRC_Mode = 1. 2 ! PRC_n - Number of elements in PRC_WindSpeeds and PRC_GenSpeeds array 0.07854 ! PRC_LPF_Freq - Frequency of the low pass filter on the wind speed estimate used to set PRC_GenSpeeds [rad/s] 3.0000 25.0000 ! PRC_WindSpeeds - Array of wind speeds used in rotor speed vs. wind speed lookup table [m/s] @@ -154,6 +161,8 @@ !------- Open Loop Control ----------------------------------------------------- "unused" ! OL_Filename - Input file with open loop timeseries (absolute path or relative to this file) +0 ! OL_BP_Mode - Breakpoint mode for open loop control, 0 - indexed by time (default), 1 - indexed by wind speed] +0.000000 ! OL_BP_FiltFreq - Natural frequency of 1st order filter on breakpoint for open loop control. 0 will skip filter. 0 ! Ind_Breakpoint - The column in OL_Filename that contains the breakpoint (time if OL_Mode = 1) 0 0 0 ! Ind_BldPitch - The columns in OL_Filename that contains the blade pitch (1,2,3) inputs in rad [array] 0 ! Ind_GenTq - The column in OL_Filename that contains the generator torque in Nm @@ -162,6 +171,9 @@ 0.0000 0.0000 0.0000 0.0000 ! RP_Gains - PID gains and Tf of derivative for rotor position control (used if OL_Mode = 2) 0 ! Ind_CableControl - The column(s) in OL_Filename that contains the cable control inputs in m [Used with CC_Mode = 2, must be the same size as CC_Group_N] 0 ! Ind_StructControl - The column(s) in OL_Filename that contains the structural control inputs [Used with StC_Mode = 2, must be the same size as StC_Group_N] +0 ! Ind_R_Speed - Index (column, 1-indexed) of power rating via speed offset +0 ! Ind_R_Torque - Index (column, 1-indexed) of power rating via torque offset +0 ! Ind_R_Pitch - Index (column, 1-indexed) of power rating via pitch offset !------- Pitch Actuator Model ----------------------------------------------------- 3.140000000000 ! PA_CornerFreq - Pitch actuator bandwidth/cut-off frequency [rad/s] From 44703b6c74f0073b7a7214abb45d352cce48ff30 Mon Sep 17 00:00:00 2001 From: David Stockhouse Date: Thu, 5 Sep 2024 10:39:40 -0600 Subject: [PATCH 172/224] Modified comments related to GBoxEff in rng2K calculation --- rosco/toolbox/controller.py | 7 ++++--- 1 file changed, 4 insertions(+), 3 deletions(-) diff --git a/rosco/toolbox/controller.py b/rosco/toolbox/controller.py index d7739fff..e07f5b39 100644 --- a/rosco/toolbox/controller.py +++ b/rosco/toolbox/controller.py @@ -416,9 +416,10 @@ def tune_controller(self, turbine): self.vs_gain_schedule.second_order_PI(self.zeta_vs, self.omega_vs,A,B_tau,linearize=False,v=v) # -- Find K for Komega_g^2 -- - # P_aero = 1/2 * Cp * rho * pi * R^5 / (TSR^3 * Ng^3) - # P_rot = GBoxEff * P_aero = tau_gen * omega_gen = K * omega_gen^3 - # P_gen = GenEff * P_rot + # Careful handling of different efficiencies + # P_lss = 1/2 * Cp * rho * pi * R^5 / (TSR^3 * Ng^3) + # P_hss = GBoxEff * P_lss = tau_gen * omega_gen = K * omega_gen^3 + # P_gen = GenEff * P_hss # Generator efficiency is not included in K here, but gearbox efficiency is self.vs_rgn2K = (pi*rho*R**5.0 * turbine.Cp.max * turbine.GBoxEff/100) \ / (2.0 * turbine.Cp.TSR_opt**3 * Ng**3) \ From 33272258d872dca09979127ee5947b701d19c00b Mon Sep 17 00:00:00 2001 From: dzalkind Date: Thu, 5 Sep 2024 11:34:50 -0600 Subject: [PATCH 173/224] Fix GB and gen efficiencies GB efficiency reduces LSS to HSS GEN reduces HSS to generator electrical output We apply the GenTq at the HSS --- rosco/controller/src/ReadSetParameters.f90 | 2 +- rosco/toolbox/controller.py | 10 ++++++++-- rosco/toolbox/sim.py | 3 +-- 3 files changed, 10 insertions(+), 5 deletions(-) diff --git a/rosco/controller/src/ReadSetParameters.f90 b/rosco/controller/src/ReadSetParameters.f90 index f9a90a7d..b76ef5f5 100644 --- a/rosco/controller/src/ReadSetParameters.f90 +++ b/rosco/controller/src/ReadSetParameters.f90 @@ -229,7 +229,7 @@ SUBROUTINE SetParameters(avrSWAP, accINFILE, size_avcMSG, CntrPar, LocalVar, obj ENDIF LocalVar%VS_LastGenTrq = LocalVar%GenTq LocalVar%VS_MaxTq = CntrPar%VS_MaxTq - LocalVar%VS_GenPwr = LocalVar%GenTq * LocalVar%GenSpeed + LocalVar%VS_GenPwr = LocalVar%GenTq * LocalVar%GenSpeed * CntrPar%VS_GenEff/100.0 ! Initialize variables LocalVar%CC_DesiredL = 0 diff --git a/rosco/toolbox/controller.py b/rosco/toolbox/controller.py index f26c67d0..bce35b2e 100644 --- a/rosco/toolbox/controller.py +++ b/rosco/toolbox/controller.py @@ -325,8 +325,14 @@ def tune_controller(self, turbine): self.vs_gain_schedule.second_order_PI(self.zeta_vs, self.omega_vs,A_vs,B_tau[0:len(v_below_rated)],linearize=False,v=v_below_rated) # -- Find K for Komega_g^2 -- - self.vs_rgn2K = (pi*rho*R**5.0 * turbine.Cp.max * turbine.GBoxEff/100 * turbine.GenEff/100) / \ - (2.0 * turbine.Cp.TSR_opt**3 * Ng**3) * self.controller_params['rgn2k_factor'] + # Careful handling of different efficiencies + # P_lss = 1/2 * Cp * rho * pi * R^5 / (TSR^3 * Ng^3) + # P_hss = GBoxEff * P_lss = tau_gen * omega_gen = K * omega_gen^3 + # P_gen = GenEff * P_hss + # Generator efficiency is not included in K here, but gearbox efficiency is + # Note that this differs from the + self.vs_rgn2K = (pi*rho*R**5.0 * turbine.Cp.max * turbine.GBoxEff/100) / (2.0 * turbine.Cp.TSR_opt**3 * Ng**3) * self.controller_params['rgn2k_factor'] + self.vs_refspd = min(turbine.TSR_operational * turbine.v_rated/R, turbine.rated_rotor_speed) * Ng # -- Define some setpoints -- diff --git a/rosco/toolbox/sim.py b/rosco/toolbox/sim.py index 2c845ca7..1846af21 100644 --- a/rosco/toolbox/sim.py +++ b/rosco/toolbox/sim.py @@ -113,8 +113,7 @@ def sim_ws_series(self, t_array, ws_array, rotor_rpm_init=10, init_pitch=0.0, # Update the turbine state # -- 1DOF model: rotor speed and generator speed (scaled by Ng) aero_torque[i] = 0.5 * self.turbine.rho * (np.pi * R**3) * (cp/tsr) * ws**2 - rot_speed[i] = rot_speed[i-1] + (dt/self.turbine.J)*(aero_torque[i] - * self.turbine.GenEff/100 - self.turbine.Ng * gen_torque[i-1]) + rot_speed[i] = rot_speed[i-1] + (dt/self.turbine.J)*(aero_torque[i] - self.turbine.Ng * gen_torque[i-1] / (self.turbine.GBoxEff/100)) gen_speed[i] = rot_speed[i] * self.turbine.Ng # -- Simple nacelle model nac_yawerr[i] = wd - nac_yaw[i-1] From 27476f9392cf81cbfea77e59594484e5efce9137 Mon Sep 17 00:00:00 2001 From: dzalkind Date: Mon, 9 Sep 2024 14:59:09 -0600 Subject: [PATCH 174/224] Allow updating of Ind_BldPitch from int to array --- rosco/toolbox/tune.py | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/rosco/toolbox/tune.py b/rosco/toolbox/tune.py index fa121247..a48dbc8b 100644 --- a/rosco/toolbox/tune.py +++ b/rosco/toolbox/tune.py @@ -112,6 +112,10 @@ def update_discon_version(file,tuning_yaml,new_discon_filename): if original_vt['F_NotchType'] == 2 or original_vt['F_NotchType'] == 3: new_discon['F_TwrTopNotch_N'] = 1 new_discon['F_TwrTopNotch_Ind'] = [1] + + # OL blade pitch changed to array + if not hasattr(original_vt['Ind_BldPitch'],'__len__'): + new_discon['Ind_BldPitch'] = [original_vt['Ind_BldPitch']] * 3 # Make the DISCON From ac73ddeb31fbf628e37ac474daa39576838338dc Mon Sep 17 00:00:00 2001 From: dzalkind Date: Tue, 10 Sep 2024 15:34:45 -0600 Subject: [PATCH 175/224] Remove print statement --- rosco/controller/src/ReadSetParameters.f90 | 1 - 1 file changed, 1 deletion(-) diff --git a/rosco/controller/src/ReadSetParameters.f90 b/rosco/controller/src/ReadSetParameters.f90 index 0a124895..cff32f3f 100644 --- a/rosco/controller/src/ReadSetParameters.f90 +++ b/rosco/controller/src/ReadSetParameters.f90 @@ -748,7 +748,6 @@ SUBROUTINE ReadControlParameterFileSub(CntrPar, LocalVar, accINFILE, accINFILE_s IF (CntrPar%Ind_R_Speed > 0) THEN CntrPar%OL_R_Speed = CntrPar%OL_Channels(:,CntrPar%Ind_R_Speed) ENDIF - WRITE(400,*) CntrPar%OL_R_Speed IF (CntrPar%Ind_R_Torque > 0) THEN CntrPar%OL_R_Torque = CntrPar%OL_Channels(:,CntrPar%Ind_R_Torque) From bdc1c3e611324de1884ef5efe3f29815f0b98be3 Mon Sep 17 00:00:00 2001 From: dzalkind Date: Tue, 10 Sep 2024 15:35:50 -0600 Subject: [PATCH 176/224] Add power control example --- Examples/29_power_control.py | 173 +++++++++++++++++++++++++++++++++++ rosco/test/test_examples.py | 1 + 2 files changed, 174 insertions(+) create mode 100644 Examples/29_power_control.py diff --git a/Examples/29_power_control.py b/Examples/29_power_control.py new file mode 100644 index 00000000..c0102f91 --- /dev/null +++ b/Examples/29_power_control.py @@ -0,0 +1,173 @@ +''' +29_power_control +---------------- +This example demonstrates an advanced method for controlling the power output of a turbine. +Users may want to reduce the power output, or de-rate the turbine to reduce loads, increase wind speeds deeper in the farm, or for grid support functions. +Users might also want to increase the power output when it's safe to do so. +Future advanced control methods can make use of these inputs to directly account for the trade off between power and loads. + +There are a few ways to control the turbine power output + +The power rating (``R``) is the controlled power relative to the rated power (or available power below rated). +For example R = 0.9, will produce 90% of the rated power (or available power below rated). + +* Speed (``R_Speed``) will change the rated speed, or the speed relative to the optimal tip speed ratio (below rated). +* Torque (``R_Torque``): will change the rated torque. In constant power operation (`VS_ConstPower` of 1), the torque is non-constant, but the rated power used to calcualte the torque is adapted accordingly. +* Pitch (``R_Pitch``): will change the minimum pitch angle of the turbine. When using peak shaving, the min pitch is the maximum of the minimum pitch for peak shaving (``PS_Min_Pitch``) and the minimum pitch for power control (``PRC_Min_Pitch``). The ROSCO toolbox can generate a lookup table from ``R_Pitch`` to ``PRC_Min_Pitch`` using the Cp surface. + +The three methods are compared in the following figure: + +.. image:: ../images/29_PRC_Methods.png + +The power rating can be controlled with three different "communication" methods (``PRC_Comm``), via: + +#. Constant settings in the DISCON: ``R_Speed``, ``R_Torque``, and ``R_Pitch``. +#. Open-loop control inputs with time or wind speed breakpoints. Two applications will be shown in the example below. +#. The ZeroMQ interface. A simple example is provided in ``17b_zeromq_multi_openfast.py``. + +This example shows users how to set up + +#. A constant input with R_Speed of 0.85. +#. A soft start up routine that slowly ramps the rating from 0 to 1 over 60 seconds. +#. A soft cut-out routine for high wind speeds. + + + +''' + +import os +from rosco.toolbox.ofTools.case_gen.run_FAST import run_FAST_ROSCO +from rosco.toolbox.ofTools.case_gen import CaseLibrary as cl +#from rosco.toolbox.ofTools.fast_io import output_processing +from rosco.toolbox.ofTools.fast_io.FAST_reader import InputReader_OpenFAST +from rosco.toolbox.inputs.validation import load_rosco_yaml +from rosco.toolbox import controller as ROSCO_controller + + +import numpy as np + +rpm2RadSec = 2.0*(np.pi)/60.0 + + +#directories +this_dir = os.path.dirname(os.path.abspath(__file__)) +rosco_dir = os.path.dirname(this_dir) +example_out_dir = os.path.join(this_dir,'examples_out') +os.makedirs(example_out_dir,exist_ok=True) + + +def main(): + + # Input yaml and output directory + parameter_filename = os.path.join(this_dir,'Tune_Cases/IEA15MW.yaml') + run_dir = os.path.join(example_out_dir,'29_PRC_Test/12_AWC_Speed') + os.makedirs(run_dir,exist_ok=True) + + + # Set DISCON input dynamically through yaml/dict + controller_params = {} + controller_params['DISCON'] = {} + controller_params['DISCON']['Echo'] = 1 + controller_params['DISCON']['PRC_Mode'] = 1 + controller_params['DISCON']['PRC_Comm'] = 1 + controller_params['DISCON']['PRC_R_Torque'] = 1.0 + controller_params['DISCON']['PRC_R_Speed'] = 1.0 + controller_params['DISCON']['PRC_R_Pitch'] = 1.0 + controller_params['DISCON']['OL_BP_FitFreq'] = 2 * np.pi / 30 + + + # Soft start up + if False: + olc = ROSCO_controller.OpenLoopControl(t_max=100) + olc.interp_series( + 'R_speed', + [50,70], + [1,1.1] , + 'sigma' + ) + + # Soft cut out + if False: + olc = ROSCO_controller.OpenLoopControl( + breakpoint='wind_speed', + u_min = 20, + u_max = 30 + ) + olc.interp_series( + 'R_speed', + [20,30], + [1,0.5] , + 'cubic' + ) + + # AWC above rated via R_Speed/Torque + if True: + controller_params['OL_Mode'] = 1 + olc = ROSCO_controller.OpenLoopControl(t_max=600) + olc.sine_timeseries( + 'R_speed', + 0.104719, # amplitude, 1 rpm + 100, # period, sec + ) + + + fig,ax = olc.plot_series() + fig.savefig(os.path.join(example_out_dir,'29_OL_Inputs.png')) + # import matplotlib.pyplot as plt + # plt.show() + + + # Write open loop input, get OL indices + ol_filename = os.path.join(example_out_dir,'29_OL_Input.dat') + ol_dict = olc.write_input(ol_filename) + controller_params['open_loop'] = ol_dict + controller_params['OL_Mode'] = 1 + + + # simulation set up + r = run_FAST_ROSCO() + r.tuning_yaml = parameter_filename + + # Wind case + # A few different cases highlight TRA + + # Ramp: good demo of functionality, short for CI + r.wind_case_fcn = cl.power_curve + r.wind_case_opts = { + 'U': [14], # from 10 to 15 m/s + 'TMax': 600, + } + + # # steady + # r.wind_case_fcn = cl.power_curve + # r.wind_case_opts = { + # 'U': 6.5, # from 10 to 15 m/s + # 'TMax': 400, + # } + + # # turbulence + # r.wind_case_fcn = cl.turb_bts + # r.wind_case_opts = { + # 'TMax': 400, # from 10 to 15 m/s + # 'wind_filenames': ['/Users/dzalkind/Downloads/heavy_test_1ETM_U6.000000_Seed603.0.bts'], + # } + + # # Do a run with both tower modes + # r.control_sweep_fcn = cl.sweep_yaml_input + # r.control_sweep_opts = { + # 'control_param': 'TRA_Mode', + # 'param_values': [0,1] + # } + + r.controller_params = controller_params + r.save_dir = run_dir + r.rosco_dll = '/Users/dzalkind/Tools/ROSCO-PRC/rosco/controller/build/libdiscon.dylib' + # r.rosco_dir = rosco_dir + # r.case_inputs = {} + # r.n_cores = 2 + r.run_FAST() + + + +if __name__=="__main__": + main() diff --git a/rosco/test/test_examples.py b/rosco/test/test_examples.py index 2aa44cc0..a760b1df 100644 --- a/rosco/test/test_examples.py +++ b/rosco/test/test_examples.py @@ -32,6 +32,7 @@ '26_marine_hydro', '27_power_ref_control', '28_tower_resonance', + '29_power_control', 'update_rosco_discons', ] From 5eb81deee7ea547a4b982609168f58b3805156b1 Mon Sep 17 00:00:00 2001 From: dzalkind Date: Tue, 10 Sep 2024 15:57:11 -0600 Subject: [PATCH 177/224] Fix issue where PRC_Mode 2 was not setting PC_RefSpeed_PRC --- rosco/controller/src/ControllerBlocks.f90 | 2 -- 1 file changed, 2 deletions(-) diff --git a/rosco/controller/src/ControllerBlocks.f90 b/rosco/controller/src/ControllerBlocks.f90 index 797d2545..fc7df9d9 100644 --- a/rosco/controller/src/ControllerBlocks.f90 +++ b/rosco/controller/src/ControllerBlocks.f90 @@ -89,8 +89,6 @@ SUBROUTINE ComputeVariablesSetpoints(CntrPar, LocalVar, objInst, DebugVar, ErrVa IF (CntrPar%PRC_Mode == 1) THEN LocalVar%PRC_WSE_F = LPFilter(LocalVar%WE_Vw, LocalVar%DT,CntrPar%PRC_LPF_Freq, LocalVar%FP, LocalVar%iStatus, LocalVar%restart, objInst%instLPF) LocalVar%PC_RefSpd_PRC = interp1d(CntrPar%PRC_WindSpeeds,CntrPar%PRC_GenSpeeds,LocalVar%PRC_WSE_F,ErrVar) - ELSE - LocalVar%PC_RefSpd_PRC = CntrPar%PC_RefSpd ENDIF ! Implement setpoint smoothing From 008c15401dde0108153c921af5d6c61822a28389 Mon Sep 17 00:00:00 2001 From: dzalkind Date: Tue, 10 Sep 2024 15:57:20 -0600 Subject: [PATCH 178/224] Add offset to sine_timeseries --- rosco/toolbox/controller.py | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/rosco/toolbox/controller.py b/rosco/toolbox/controller.py index 50fccbc0..1b560268 100644 --- a/rosco/toolbox/controller.py +++ b/rosco/toolbox/controller.py @@ -820,7 +820,7 @@ def interp_series(self,control,breakpoints,values,method='sigma'): self.compute_yaw_rate() - def sine_timeseries(self,control,amplitude,period): + def sine_timeseries(self,control,amplitude,period,offset=0): if period <= 0: raise Exception('Open loop sine input period is <= 0') @@ -831,7 +831,7 @@ def sine_timeseries(self,control,amplitude,period): if control not in self.allowed_controls: raise Exception(f'Open loop control of {control} is not allowed') else: - self.ol_series[control] = amplitude * np.sin(2 * np.pi * self.ol_series['time'] / period) + self.ol_series[control] = amplitude * np.sin(2 * np.pi * self.ol_series['time'] / period) + offset if control == 'nacelle_yaw': self.compute_yaw_rate() From 5c942076f0abab34230a979b1bec7a49bd174697 Mon Sep 17 00:00:00 2001 From: dzalkind Date: Tue, 10 Sep 2024 16:47:29 -0600 Subject: [PATCH 179/224] Clean up power control example --- Examples/29_power_control.py | 33 +++++---------------------------- 1 file changed, 5 insertions(+), 28 deletions(-) diff --git a/Examples/29_power_control.py b/Examples/29_power_control.py index c0102f91..230a4514 100644 --- a/Examples/29_power_control.py +++ b/Examples/29_power_control.py @@ -60,7 +60,7 @@ def main(): # Input yaml and output directory parameter_filename = os.path.join(this_dir,'Tune_Cases/IEA15MW.yaml') - run_dir = os.path.join(example_out_dir,'29_PRC_Test/12_AWC_Speed') + run_dir = os.path.join(example_out_dir,'29_PRC_Test/14_AWC_Torque') os.makedirs(run_dir,exist_ok=True) @@ -68,7 +68,7 @@ def main(): controller_params = {} controller_params['DISCON'] = {} controller_params['DISCON']['Echo'] = 1 - controller_params['DISCON']['PRC_Mode'] = 1 + controller_params['DISCON']['PRC_Mode'] = 2 controller_params['DISCON']['PRC_Comm'] = 1 controller_params['DISCON']['PRC_R_Torque'] = 1.0 controller_params['DISCON']['PRC_R_Speed'] = 1.0 @@ -105,16 +105,15 @@ def main(): controller_params['OL_Mode'] = 1 olc = ROSCO_controller.OpenLoopControl(t_max=600) olc.sine_timeseries( - 'R_speed', - 0.104719, # amplitude, 1 rpm + 'R_torque', # could use R_speed or R_torque + 0.05, # amplitude, fraction of rated power 100, # period, sec + 1, # offset, (-) ) fig,ax = olc.plot_series() fig.savefig(os.path.join(example_out_dir,'29_OL_Inputs.png')) - # import matplotlib.pyplot as plt - # plt.show() # Write open loop input, get OL indices @@ -130,34 +129,12 @@ def main(): # Wind case # A few different cases highlight TRA - - # Ramp: good demo of functionality, short for CI r.wind_case_fcn = cl.power_curve r.wind_case_opts = { 'U': [14], # from 10 to 15 m/s 'TMax': 600, } - - # # steady - # r.wind_case_fcn = cl.power_curve - # r.wind_case_opts = { - # 'U': 6.5, # from 10 to 15 m/s - # 'TMax': 400, - # } - # # turbulence - # r.wind_case_fcn = cl.turb_bts - # r.wind_case_opts = { - # 'TMax': 400, # from 10 to 15 m/s - # 'wind_filenames': ['/Users/dzalkind/Downloads/heavy_test_1ETM_U6.000000_Seed603.0.bts'], - # } - - # # Do a run with both tower modes - # r.control_sweep_fcn = cl.sweep_yaml_input - # r.control_sweep_opts = { - # 'control_param': 'TRA_Mode', - # 'param_values': [0,1] - # } r.controller_params = controller_params r.save_dir = run_dir From d77ba20f231fe7e0664bfdcaed504a2d106f66de Mon Sep 17 00:00:00 2001 From: David Stockhouse Date: Wed, 18 Sep 2024 11:56:41 -0600 Subject: [PATCH 180/224] Restructured some controller code related to saturation, attempted to remove some redundant saturations and restored some that had been previously removed --- .../rosco_registry/rosco_types.yaml | 17 +- rosco/controller/src/ControllerBlocks.f90 | 11 +- rosco/controller/src/Controllers.f90 | 30 +- rosco/controller/src/ROSCO_IO.f90 | 314 +++++++++--------- rosco/controller/src/ROSCO_Types.f90 | 13 +- 5 files changed, 195 insertions(+), 190 deletions(-) diff --git a/rosco/controller/rosco_registry/rosco_types.yaml b/rosco/controller/rosco_registry/rosco_types.yaml index 71871bfc..6ee3b2ba 100644 --- a/rosco/controller/rosco_registry/rosco_types.yaml +++ b/rosco/controller/rosco_registry/rosco_types.yaml @@ -282,16 +282,16 @@ ControlParameters: description: Generator efficiency mechanical power -> electrical power [-] VS_ArSatTq: <<: *real - description: Above rated generator torque PI control saturation, [Nm] -- 212900 + description: Above rated generator torque PI control saturation, [Nm] VS_MaxRat: <<: *real description: Maximum torque rate (in absolute value) in torque controller, [Nm/s]. VS_MaxTq: <<: *real - description: Maximum generator torque in Region 3 (HSS side), [Nm]. -- chosen to be 10% above VS_RtTq + description: Maximum generator torque in Region 3 (HSS side), [Nm]. VS_MinTq: <<: *real - description: Minimum generator (HSS side), [Nm]. + description: Minimum generator torque (HSS side), [Nm]. VS_MinOMSpd: <<: *real description: Optimal mode minimum speed, [rad/s] @@ -960,9 +960,6 @@ LocalVariables: VS_GenPwr: <<: *real description: Generator power [W] - VS_GenPwrF: - <<: *real - description: Generator power [W] GenSpeed: <<: *real description: Generator speed (HSS) [rad/s] @@ -1054,7 +1051,7 @@ LocalVariables: description: Generator speed set point of pitch controller after power ref control [rad/s] RotSpeedF: <<: *real - description: Filtered LSS (generator) speed [rad/s]. + description: Filtered LSS (rotor) speed [rad/s]. GenSpeedF: <<: *real description: Filtered HSS (generator) speed [rad/s]. @@ -1070,6 +1067,12 @@ LocalVariables: GenBrTq: <<: *real description: Electrical generator torque, for below-rated PI-control [Nm]. + VS_KOmega2_GenTq: + <<: *real + description: Calculation of torque signal used by K*Omega^2 controller + VS_ConstPwr_GenTq: + <<: *real + description: Calculation of constant-power torque signal IPC_PitComF: <<: *real description: Commanded pitch of each blade as calculated by the individual pitch controller, F stands for low-pass filtered [rad]. diff --git a/rosco/controller/src/ControllerBlocks.f90 b/rosco/controller/src/ControllerBlocks.f90 index 677ce9c0..222b616b 100644 --- a/rosco/controller/src/ControllerBlocks.f90 +++ b/rosco/controller/src/ControllerBlocks.f90 @@ -68,7 +68,7 @@ SUBROUTINE ComputeVariablesSetpoints(CntrPar, LocalVar, objInst, DebugVar, ErrVa ELSEIF (CntrPar%VS_ControlMode == VS_Mode_Torque_TSR) THEN ! Non-WSE TSR tracking based on square-root of torque LocalVar%VS_RefSpd_TSR = (MAX(LocalVar%GenTq, 0.0)/CntrPar%VS_Rgn2K)**(1./2.) - ELSE ! Generate constant reference + ELSE ! Generate constant speed reference if K*Omega^2 in use or torque control disabled LocalVar%VS_RefSpd_TSR = CntrPar%VS_RefSpd ENDIF @@ -93,9 +93,10 @@ SUBROUTINE ComputeVariablesSetpoints(CntrPar, LocalVar, objInst, DebugVar, ErrVa CALL RefSpeedExclusion(LocalVar, CntrPar, objInst, DebugVar) END IF - ! Saturate torque reference speed between min speed and rated speed - ! LocalVar%VS_RefSpd = saturate(LocalVar%VS_RefSpd, CntrPar%VS_MinOMSpd, CntrPar%VS_RefSpd) - ! Saturate torque reference speed above lower bound (below) + ! Saturate torque reference speed below rated speed if using pitch control in Region 3 + IF (CntrPar%VS_FBP == VS_FBP_Variable_Pitch) THEN + LocalVar%VS_RefSpd = saturate(LocalVar%VS_RefSpd, CntrPar%VS_MinOMSpd, CntrPar%VS_RefSpd) + END IF ! Implement power reference rotor speed (overwrites above), convert to generator speed IF (CntrPar%PRC_Mode == 1) THEN @@ -112,7 +113,7 @@ SUBROUTINE ComputeVariablesSetpoints(CntrPar, LocalVar, objInst, DebugVar, ErrVa LocalVar%VS_RefSpd = CntrPar%VS_MinOMSpd ENDIF - ! Force minimum rotor speed + ! Force minimum rotor speed reference LocalVar%VS_RefSpd = max(LocalVar%VS_RefSpd, CntrPar%VS_MinOmSpd) ! Compute speed error from reference diff --git a/rosco/controller/src/Controllers.f90 b/rosco/controller/src/Controllers.f90 index a979c2e7..4a877513 100644 --- a/rosco/controller/src/Controllers.f90 +++ b/rosco/controller/src/Controllers.f90 @@ -208,12 +208,15 @@ SUBROUTINE VariableSpeedControl(avrSWAP, CntrPar, LocalVar, objInst, ErrVar) ! -------- Variable-Speed Torque Controller -------- ! Define max torque IF (LocalVar%VS_State == VS_State_Region_3_ConstTrq) THEN - LocalVar%VS_MaxTq = CntrPar%VS_RtTq - ELSE - ! VS_MaxTq = CntrPar%VS_MaxTq ! NJA: May want to boost max torque LocalVar%VS_MaxTq = CntrPar%VS_RtTq + ELSE + LocalVar%VS_MaxTq = CntrPar%VS_MaxTq ENDIF + ! Pre-compute generatoer torque values for K*Omega^2 and constant power + LocalVar%VS_KOmega2_GenTq = CntrPar%VS_Rgn2K*LocalVar%GenSpeedF*LocalVar%GenSpeedF + LocalVar%VS_ConstPwr_GenTq = (CntrPar%VS_RtPwr/(CntrPar%VS_GenEff/100.0))/LocalVar%GenSpeedF + ! Optimal Tip-Speed-Ratio tracking controller (reference generated in subroutine ComputeVariablesSetpoints) IF ((CntrPar%VS_ControlMode == VS_Mode_WSE_TSR) .OR. \ (CntrPar%VS_ControlMode == VS_Mode_Power_TSR) .OR. \ @@ -221,12 +224,7 @@ SUBROUTINE VariableSpeedControl(avrSWAP, CntrPar, LocalVar, objInst, ErrVar) ! Constant Power, update VS_MaxTq IF (CntrPar%VS_ConstPower == VS_Mode_ConstPwr) THEN - LocalVar%VS_MaxTq = min((CntrPar%VS_RtPwr/(CntrPar%VS_GenEff/100.0))/LocalVar%GenSpeedF, CntrPar%VS_MaxTq) - END IF - - IF (CntrPar%VS_FBP > 0) THEN - ! Increase torque limit from rated if torque control also used in Region 3 - LocalVar%VS_MaxTq = CntrPar%VS_MaxTq + LocalVar%VS_MaxTq = min(LocalVar%VS_ConstPwr_GenTq, CntrPar%VS_MaxTq) END IF ! PI controller @@ -237,9 +235,9 @@ SUBROUTINE VariableSpeedControl(avrSWAP, CntrPar, LocalVar, objInst, ErrVar) CntrPar%VS_MinTq, LocalVar%VS_MaxTq, & LocalVar%DT, LocalVar%VS_LastGenTrq, LocalVar%piP, LocalVar%restart, objInst%instPI) + ! Saturate control input to Region 3 constant-power value if FBP mode is set to constant-power overspeed (no need for explicit transition region) IF (CntrPar%VS_FBP == VS_FBP_Power_Overspeed) THEN - ! Saturate input if FBP mode is set to constant power overspeed - LocalVar%GenTq = MIN((CntrPar%VS_RtPwr/(CntrPar%VS_GenEff/100.0))/LocalVar%GenSpeedF, LocalVar%GenTq) + LocalVar%GenTq = MIN(LocalVar%VS_ConstPwr_GenTq, LocalVar%GenTq) ENDIF ! K*Omega^2 control law with PI torque control in transition regions @@ -252,20 +250,18 @@ SUBROUTINE VariableSpeedControl(avrSWAP, CntrPar, LocalVar, objInst, ErrVar) IF (LocalVar%VS_State == VS_State_Region_1_5) THEN ! Region 1.5 LocalVar%GenTq = LocalVar%GenBrTq ELSEIF (LocalVar%VS_State == VS_State_Region_2) THEN ! Region 2 - LocalVar%GenTq = CntrPar%VS_Rgn2K*LocalVar%GenSpeedF*LocalVar%GenSpeedF + LocalVar%GenTq = LocalVar%VS_KOmega2_GenTq ELSEIF (LocalVar%VS_State == VS_State_Region_2_5) THEN ! Region 2.5 LocalVar%GenTq = LocalVar%GenArTq ELSEIF (LocalVar%VS_State == VS_State_Region_3_ConstTrq) THEN ! Region 3, constant torque LocalVar%GenTq = CntrPar%VS_RtTq ELSEIF (LocalVar%VS_State == VS_State_Region_3_ConstPwr) THEN ! Region 3, constant power - LocalVar%GenTq = (CntrPar%VS_RtPwr/(CntrPar%VS_GenEff/100.0))/LocalVar%GenSpeedF + LocalVar%GenTq = LocalVar%VS_ConstPwr_GenTq ELSEIF (LocalVar%VS_State == VS_State_Region_3_FBP) THEN ! Region 3, fixed blade pitch ! Constant power overspeed IF (CntrPar%VS_FBP == VS_FBP_Power_Overspeed) THEN - ! Nonlinear lookup table from gen speed to gen torque - ! LocalVar%GenTq = interp1d(CntrPar%VS_FBP_Omega, CntrPar%VS_FBP_Tau, LocalVar%GenSpeedF, ErrVar) ! (must express LUTs for torque as a function of speed) - ! Either K*Omega^2 or constant power overspeed - LocalVar%GenTq = MIN((CntrPar%VS_RtPwr/(CntrPar%VS_GenEff/100.0))/LocalVar%GenSpeedF, CntrPar%VS_Rgn2K*LocalVar%GenSpeedF*LocalVar%GenSpeedF) + ! K*Omega^2 in Region 2 or constant power overspeed in Region 3 + LocalVar%GenTq = MIN(LocalVar%VS_ConstPwr_GenTq, LocalVar%VS_KOmega2_GenTq) ! Reference-tracking in Region 3 ELSEIF ((CntrPar%VS_FBP == VS_FBP_WSE_Ref) .OR. (CntrPar%VS_FBP == VS_FBP_Torque_Ref)) THEN LocalVar%GenTq = LocalVar%GenArTq diff --git a/rosco/controller/src/ROSCO_IO.f90 b/rosco/controller/src/ROSCO_IO.f90 index c537f9b4..b2570988 100644 --- a/rosco/controller/src/ROSCO_IO.f90 +++ b/rosco/controller/src/ROSCO_IO.f90 @@ -1,5 +1,5 @@ ! ROSCO IO -! This file is automatically generated by write_registry.py using ROSCO v2.9.0 +! This file is automatically generated by write_registry.py using ROSCO v2.9.4 ! For any modification to the registry, please edit the rosco_types.yaml accordingly MODULE ROSCO_IO @@ -43,7 +43,6 @@ SUBROUTINE WriteRestartFile(LocalVar, CntrPar, ErrVar, objInst, RootName, size_a WRITE( Un, IOSTAT=ErrStat) LocalVar%n_DT WRITE( Un, IOSTAT=ErrStat) LocalVar%Time_Last WRITE( Un, IOSTAT=ErrStat) LocalVar%VS_GenPwr - WRITE( Un, IOSTAT=ErrStat) LocalVar%VS_GenPwrF WRITE( Un, IOSTAT=ErrStat) LocalVar%GenSpeed WRITE( Un, IOSTAT=ErrStat) LocalVar%RotSpeed WRITE( Un, IOSTAT=ErrStat) LocalVar%NacHeading @@ -87,6 +86,8 @@ SUBROUTINE WriteRestartFile(LocalVar, CntrPar, ErrVar, objInst, RootName, size_a WRITE( Un, IOSTAT=ErrStat) LocalVar%GenTqMeas WRITE( Un, IOSTAT=ErrStat) LocalVar%GenArTq WRITE( Un, IOSTAT=ErrStat) LocalVar%GenBrTq + WRITE( Un, IOSTAT=ErrStat) LocalVar%VS_KOmega2_GenTq + WRITE( Un, IOSTAT=ErrStat) LocalVar%VS_ConstPwr_GenTq WRITE( Un, IOSTAT=ErrStat) LocalVar%IPC_PitComF(1) WRITE( Un, IOSTAT=ErrStat) LocalVar%IPC_PitComF(2) WRITE( Un, IOSTAT=ErrStat) LocalVar%IPC_PitComF(3) @@ -345,7 +346,6 @@ SUBROUTINE ReadRestartFile(avrSWAP, LocalVar, CntrPar, objInst, PerfData, RootNa READ( Un, IOSTAT=ErrStat) LocalVar%n_DT READ( Un, IOSTAT=ErrStat) LocalVar%Time_Last READ( Un, IOSTAT=ErrStat) LocalVar%VS_GenPwr - READ( Un, IOSTAT=ErrStat) LocalVar%VS_GenPwrF READ( Un, IOSTAT=ErrStat) LocalVar%GenSpeed READ( Un, IOSTAT=ErrStat) LocalVar%RotSpeed READ( Un, IOSTAT=ErrStat) LocalVar%NacHeading @@ -389,6 +389,8 @@ SUBROUTINE ReadRestartFile(avrSWAP, LocalVar, CntrPar, objInst, PerfData, RootNa READ( Un, IOSTAT=ErrStat) LocalVar%GenTqMeas READ( Un, IOSTAT=ErrStat) LocalVar%GenArTq READ( Un, IOSTAT=ErrStat) LocalVar%GenBrTq + READ( Un, IOSTAT=ErrStat) LocalVar%VS_KOmega2_GenTq + READ( Un, IOSTAT=ErrStat) LocalVar%VS_ConstPwr_GenTq READ( Un, IOSTAT=ErrStat) LocalVar%IPC_PitComF(1) READ( Un, IOSTAT=ErrStat) LocalVar%IPC_PitComF(2) READ( Un, IOSTAT=ErrStat) LocalVar%IPC_PitComF(3) @@ -692,7 +694,7 @@ SUBROUTINE Debug(LocalVar, CntrPar, DebugVar, ErrVar, avrSWAP, RootName, size_av '[N/A]', '[N/A]', '[N/A]', '[N/A]', '[rad/s]', & '[deg]', '[deg]', '[deg]', '[N/A]', '[rad/s]', & '[rad/s]'] - nLocalVars = 124 + nLocalVars = 125 Allocate(LocalVarOutData(nLocalVars)) Allocate(LocalVarOutStrings(nLocalVars)) LocalVarOutData(1) = LocalVar%iStatus @@ -701,149 +703,151 @@ SUBROUTINE Debug(LocalVar, CntrPar, DebugVar, ErrVar, avrSWAP, RootName, size_av LocalVarOutData(4) = LocalVar%n_DT LocalVarOutData(5) = LocalVar%Time_Last LocalVarOutData(6) = LocalVar%VS_GenPwr - LocalVarOutData(7) = LocalVar%VS_GenPwrF - LocalVarOutData(8) = LocalVar%GenSpeed - LocalVarOutData(9) = LocalVar%RotSpeed - LocalVarOutData(10) = LocalVar%NacHeading - LocalVarOutData(11) = LocalVar%NacVane - LocalVarOutData(12) = LocalVar%HorWindV - LocalVarOutData(13) = LocalVar%rootMOOP(1) - LocalVarOutData(14) = LocalVar%rootMOOPF(1) - LocalVarOutData(15) = LocalVar%BlPitch(1) - LocalVarOutData(16) = LocalVar%BlPitchCMeas - LocalVarOutData(17) = LocalVar%Azimuth - LocalVarOutData(18) = LocalVar%OL_Azimuth - LocalVarOutData(19) = LocalVar%AzUnwrapped - LocalVarOutData(20) = LocalVar%AzError - LocalVarOutData(21) = LocalVar%GenTqAz - LocalVarOutData(22) = LocalVar%AzBuffer(1) - LocalVarOutData(23) = LocalVar%NumBl - LocalVarOutData(24) = LocalVar%FA_Acc - LocalVarOutData(25) = LocalVar%NacIMU_FA_Acc - LocalVarOutData(26) = LocalVar%FA_AccHPF - LocalVarOutData(27) = LocalVar%FA_AccHPFI - LocalVarOutData(28) = LocalVar%FA_PitCom(1) - LocalVarOutData(29) = LocalVar%VS_RefSpd - LocalVarOutData(30) = LocalVar%VS_RefSpd_TSR - LocalVarOutData(31) = LocalVar%VS_RefSpd_TRA - LocalVarOutData(32) = LocalVar%VS_RefSpd_RL - LocalVarOutData(33) = LocalVar%PC_RefSpd - LocalVarOutData(34) = LocalVar%PC_RefSpd_SS - LocalVarOutData(35) = LocalVar%PC_RefSpd_PRC - LocalVarOutData(36) = LocalVar%RotSpeedF - LocalVarOutData(37) = LocalVar%GenSpeedF - LocalVarOutData(38) = LocalVar%GenTq - LocalVarOutData(39) = LocalVar%GenTqMeas - LocalVarOutData(40) = LocalVar%GenArTq - LocalVarOutData(41) = LocalVar%GenBrTq - LocalVarOutData(42) = LocalVar%IPC_PitComF(1) - LocalVarOutData(43) = LocalVar%PC_KP - LocalVarOutData(44) = LocalVar%PC_KI - LocalVarOutData(45) = LocalVar%PC_KD - LocalVarOutData(46) = LocalVar%PC_TF - LocalVarOutData(47) = LocalVar%PC_MaxPit - LocalVarOutData(48) = LocalVar%PC_MinPit - LocalVarOutData(49) = LocalVar%PC_PitComT - LocalVarOutData(50) = LocalVar%PC_PitComT_Last - LocalVarOutData(51) = LocalVar%PC_PitComTF - LocalVarOutData(52) = LocalVar%PC_PitComT_IPC(1) - LocalVarOutData(53) = LocalVar%PC_PwrErr - LocalVarOutData(54) = LocalVar%PC_SpdErr - LocalVarOutData(55) = LocalVar%IPC_AxisTilt_1P - LocalVarOutData(56) = LocalVar%IPC_AxisYaw_1P - LocalVarOutData(57) = LocalVar%IPC_AxisTilt_2P - LocalVarOutData(58) = LocalVar%IPC_AxisYaw_2P - LocalVarOutData(59) = LocalVar%axisTilt_1P - LocalVarOutData(60) = LocalVar%axisYaw_1P - LocalVarOutData(61) = LocalVar%axisYawF_1P - LocalVarOutData(62) = LocalVar%axisTilt_2P - LocalVarOutData(63) = LocalVar%axisYaw_2P - LocalVarOutData(64) = LocalVar%axisYawF_2P - LocalVarOutData(65) = LocalVar%IPC_KI(1) - LocalVarOutData(66) = LocalVar%IPC_KP(1) - LocalVarOutData(67) = LocalVar%IPC_IntSat - LocalVarOutData(68) = LocalVar%PC_State - LocalVarOutData(69) = LocalVar%PitCom(1) - LocalVarOutData(70) = LocalVar%PitComAct(1) - LocalVarOutData(71) = LocalVar%SS_DelOmegaF - LocalVarOutData(72) = LocalVar%TestType - LocalVarOutData(73) = LocalVar%Kp_Float - LocalVarOutData(74) = LocalVar%VS_MaxTq - LocalVarOutData(75) = LocalVar%VS_LastGenTrq - LocalVarOutData(76) = LocalVar%VS_LastGenPwr - LocalVarOutData(77) = LocalVar%VS_MechGenPwr - LocalVarOutData(78) = LocalVar%VS_SpdErrAr - LocalVarOutData(79) = LocalVar%VS_SpdErrBr - LocalVarOutData(80) = LocalVar%VS_SpdErr - LocalVarOutData(81) = LocalVar%VS_State - LocalVarOutData(82) = LocalVar%VS_Rgn3Pitch - LocalVarOutData(83) = LocalVar%WE_Vw - LocalVarOutData(84) = LocalVar%WE_Vw_F - LocalVarOutData(85) = LocalVar%WE_VwI - LocalVarOutData(86) = LocalVar%WE_VwIdot - LocalVarOutData(87) = LocalVar%VS_LastGenTrqF - LocalVarOutData(88) = LocalVar%PRC_WSE_F - LocalVarOutData(89) = LocalVar%Fl_PitCom - LocalVarOutData(90) = LocalVar%NACIMU_FA_AccF - LocalVarOutData(91) = LocalVar%FA_AccF - LocalVarOutData(92) = LocalVar%FA_Hist - LocalVarOutData(93) = LocalVar%TRA_LastRefSpd - LocalVarOutData(94) = LocalVar%VS_RefSpeed - LocalVarOutData(95) = LocalVar%PtfmTDX - LocalVarOutData(96) = LocalVar%PtfmTDY - LocalVarOutData(97) = LocalVar%PtfmTDZ - LocalVarOutData(98) = LocalVar%PtfmRDX - LocalVarOutData(99) = LocalVar%PtfmRDY - LocalVarOutData(100) = LocalVar%PtfmRDZ - LocalVarOutData(101) = LocalVar%PtfmTVX - LocalVarOutData(102) = LocalVar%PtfmTVY - LocalVarOutData(103) = LocalVar%PtfmTVZ - LocalVarOutData(104) = LocalVar%PtfmRVX - LocalVarOutData(105) = LocalVar%PtfmRVY - LocalVarOutData(106) = LocalVar%PtfmRVZ - LocalVarOutData(107) = LocalVar%PtfmTAX - LocalVarOutData(108) = LocalVar%PtfmTAY - LocalVarOutData(109) = LocalVar%PtfmTAZ - LocalVarOutData(110) = LocalVar%PtfmRAX - LocalVarOutData(111) = LocalVar%PtfmRAY - LocalVarOutData(112) = LocalVar%PtfmRAZ - LocalVarOutData(113) = LocalVar%CC_DesiredL(1) - LocalVarOutData(114) = LocalVar%CC_ActuatedL(1) - LocalVarOutData(115) = LocalVar%CC_ActuatedDL(1) - LocalVarOutData(116) = LocalVar%StC_Input(1) - LocalVarOutData(117) = LocalVar%Flp_Angle(1) - LocalVarOutData(118) = LocalVar%RootMyb_Last(1) - LocalVarOutData(119) = LocalVar%ACC_INFILE_SIZE - LocalVarOutData(120) = LocalVar%AWC_complexangle(1) - LocalVarOutData(121) = LocalVar%ZMQ_ID - LocalVarOutData(122) = LocalVar%ZMQ_YawOffset - LocalVarOutData(123) = LocalVar%ZMQ_TorqueOffset - LocalVarOutData(124) = LocalVar%ZMQ_PitOffset(1) + LocalVarOutData(7) = LocalVar%GenSpeed + LocalVarOutData(8) = LocalVar%RotSpeed + LocalVarOutData(9) = LocalVar%NacHeading + LocalVarOutData(10) = LocalVar%NacVane + LocalVarOutData(11) = LocalVar%HorWindV + LocalVarOutData(12) = LocalVar%rootMOOP(1) + LocalVarOutData(13) = LocalVar%rootMOOPF(1) + LocalVarOutData(14) = LocalVar%BlPitch(1) + LocalVarOutData(15) = LocalVar%BlPitchCMeas + LocalVarOutData(16) = LocalVar%Azimuth + LocalVarOutData(17) = LocalVar%OL_Azimuth + LocalVarOutData(18) = LocalVar%AzUnwrapped + LocalVarOutData(19) = LocalVar%AzError + LocalVarOutData(20) = LocalVar%GenTqAz + LocalVarOutData(21) = LocalVar%AzBuffer(1) + LocalVarOutData(22) = LocalVar%NumBl + LocalVarOutData(23) = LocalVar%FA_Acc + LocalVarOutData(24) = LocalVar%NacIMU_FA_Acc + LocalVarOutData(25) = LocalVar%FA_AccHPF + LocalVarOutData(26) = LocalVar%FA_AccHPFI + LocalVarOutData(27) = LocalVar%FA_PitCom(1) + LocalVarOutData(28) = LocalVar%VS_RefSpd + LocalVarOutData(29) = LocalVar%VS_RefSpd_TSR + LocalVarOutData(30) = LocalVar%VS_RefSpd_TRA + LocalVarOutData(31) = LocalVar%VS_RefSpd_RL + LocalVarOutData(32) = LocalVar%PC_RefSpd + LocalVarOutData(33) = LocalVar%PC_RefSpd_SS + LocalVarOutData(34) = LocalVar%PC_RefSpd_PRC + LocalVarOutData(35) = LocalVar%RotSpeedF + LocalVarOutData(36) = LocalVar%GenSpeedF + LocalVarOutData(37) = LocalVar%GenTq + LocalVarOutData(38) = LocalVar%GenTqMeas + LocalVarOutData(39) = LocalVar%GenArTq + LocalVarOutData(40) = LocalVar%GenBrTq + LocalVarOutData(41) = LocalVar%VS_KOmega2_GenTq + LocalVarOutData(42) = LocalVar%VS_ConstPwr_GenTq + LocalVarOutData(43) = LocalVar%IPC_PitComF(1) + LocalVarOutData(44) = LocalVar%PC_KP + LocalVarOutData(45) = LocalVar%PC_KI + LocalVarOutData(46) = LocalVar%PC_KD + LocalVarOutData(47) = LocalVar%PC_TF + LocalVarOutData(48) = LocalVar%PC_MaxPit + LocalVarOutData(49) = LocalVar%PC_MinPit + LocalVarOutData(50) = LocalVar%PC_PitComT + LocalVarOutData(51) = LocalVar%PC_PitComT_Last + LocalVarOutData(52) = LocalVar%PC_PitComTF + LocalVarOutData(53) = LocalVar%PC_PitComT_IPC(1) + LocalVarOutData(54) = LocalVar%PC_PwrErr + LocalVarOutData(55) = LocalVar%PC_SpdErr + LocalVarOutData(56) = LocalVar%IPC_AxisTilt_1P + LocalVarOutData(57) = LocalVar%IPC_AxisYaw_1P + LocalVarOutData(58) = LocalVar%IPC_AxisTilt_2P + LocalVarOutData(59) = LocalVar%IPC_AxisYaw_2P + LocalVarOutData(60) = LocalVar%axisTilt_1P + LocalVarOutData(61) = LocalVar%axisYaw_1P + LocalVarOutData(62) = LocalVar%axisYawF_1P + LocalVarOutData(63) = LocalVar%axisTilt_2P + LocalVarOutData(64) = LocalVar%axisYaw_2P + LocalVarOutData(65) = LocalVar%axisYawF_2P + LocalVarOutData(66) = LocalVar%IPC_KI(1) + LocalVarOutData(67) = LocalVar%IPC_KP(1) + LocalVarOutData(68) = LocalVar%IPC_IntSat + LocalVarOutData(69) = LocalVar%PC_State + LocalVarOutData(70) = LocalVar%PitCom(1) + LocalVarOutData(71) = LocalVar%PitComAct(1) + LocalVarOutData(72) = LocalVar%SS_DelOmegaF + LocalVarOutData(73) = LocalVar%TestType + LocalVarOutData(74) = LocalVar%Kp_Float + LocalVarOutData(75) = LocalVar%VS_MaxTq + LocalVarOutData(76) = LocalVar%VS_LastGenTrq + LocalVarOutData(77) = LocalVar%VS_LastGenPwr + LocalVarOutData(78) = LocalVar%VS_MechGenPwr + LocalVarOutData(79) = LocalVar%VS_SpdErrAr + LocalVarOutData(80) = LocalVar%VS_SpdErrBr + LocalVarOutData(81) = LocalVar%VS_SpdErr + LocalVarOutData(82) = LocalVar%VS_State + LocalVarOutData(83) = LocalVar%VS_Rgn3Pitch + LocalVarOutData(84) = LocalVar%WE_Vw + LocalVarOutData(85) = LocalVar%WE_Vw_F + LocalVarOutData(86) = LocalVar%WE_VwI + LocalVarOutData(87) = LocalVar%WE_VwIdot + LocalVarOutData(88) = LocalVar%VS_LastGenTrqF + LocalVarOutData(89) = LocalVar%PRC_WSE_F + LocalVarOutData(90) = LocalVar%Fl_PitCom + LocalVarOutData(91) = LocalVar%NACIMU_FA_AccF + LocalVarOutData(92) = LocalVar%FA_AccF + LocalVarOutData(93) = LocalVar%FA_Hist + LocalVarOutData(94) = LocalVar%TRA_LastRefSpd + LocalVarOutData(95) = LocalVar%VS_RefSpeed + LocalVarOutData(96) = LocalVar%PtfmTDX + LocalVarOutData(97) = LocalVar%PtfmTDY + LocalVarOutData(98) = LocalVar%PtfmTDZ + LocalVarOutData(99) = LocalVar%PtfmRDX + LocalVarOutData(100) = LocalVar%PtfmRDY + LocalVarOutData(101) = LocalVar%PtfmRDZ + LocalVarOutData(102) = LocalVar%PtfmTVX + LocalVarOutData(103) = LocalVar%PtfmTVY + LocalVarOutData(104) = LocalVar%PtfmTVZ + LocalVarOutData(105) = LocalVar%PtfmRVX + LocalVarOutData(106) = LocalVar%PtfmRVY + LocalVarOutData(107) = LocalVar%PtfmRVZ + LocalVarOutData(108) = LocalVar%PtfmTAX + LocalVarOutData(109) = LocalVar%PtfmTAY + LocalVarOutData(110) = LocalVar%PtfmTAZ + LocalVarOutData(111) = LocalVar%PtfmRAX + LocalVarOutData(112) = LocalVar%PtfmRAY + LocalVarOutData(113) = LocalVar%PtfmRAZ + LocalVarOutData(114) = LocalVar%CC_DesiredL(1) + LocalVarOutData(115) = LocalVar%CC_ActuatedL(1) + LocalVarOutData(116) = LocalVar%CC_ActuatedDL(1) + LocalVarOutData(117) = LocalVar%StC_Input(1) + LocalVarOutData(118) = LocalVar%Flp_Angle(1) + LocalVarOutData(119) = LocalVar%RootMyb_Last(1) + LocalVarOutData(120) = LocalVar%ACC_INFILE_SIZE + LocalVarOutData(121) = LocalVar%AWC_complexangle(1) + LocalVarOutData(122) = LocalVar%ZMQ_ID + LocalVarOutData(123) = LocalVar%ZMQ_YawOffset + LocalVarOutData(124) = LocalVar%ZMQ_TorqueOffset + LocalVarOutData(125) = LocalVar%ZMQ_PitOffset(1) LocalVarOutStrings = [CHARACTER(15) :: 'iStatus', 'Time', 'DT', 'n_DT', 'Time_Last', & - 'VS_GenPwr', 'VS_GenPwrF', 'GenSpeed', 'RotSpeed', 'NacHeading', & - 'NacVane', 'HorWindV', 'rootMOOP', 'rootMOOPF', 'BlPitch', & - 'BlPitchCMeas', 'Azimuth', 'OL_Azimuth', 'AzUnwrapped', 'AzError', & - 'GenTqAz', 'AzBuffer', 'NumBl', 'FA_Acc', 'NacIMU_FA_Acc', & - 'FA_AccHPF', 'FA_AccHPFI', 'FA_PitCom', 'VS_RefSpd', 'VS_RefSpd_TSR', & - 'VS_RefSpd_TRA', 'VS_RefSpd_RL', 'PC_RefSpd', 'PC_RefSpd_SS', 'PC_RefSpd_PRC', & - 'RotSpeedF', 'GenSpeedF', 'GenTq', 'GenTqMeas', 'GenArTq', & - 'GenBrTq', 'IPC_PitComF', 'PC_KP', 'PC_KI', 'PC_KD', & - 'PC_TF', 'PC_MaxPit', 'PC_MinPit', 'PC_PitComT', 'PC_PitComT_Last', & - 'PC_PitComTF', 'PC_PitComT_IPC', 'PC_PwrErr', 'PC_SpdErr', 'IPC_AxisTilt_1P', & - 'IPC_AxisYaw_1P', 'IPC_AxisTilt_2P', 'IPC_AxisYaw_2P', 'axisTilt_1P', 'axisYaw_1P', & - 'axisYawF_1P', 'axisTilt_2P', 'axisYaw_2P', 'axisYawF_2P', 'IPC_KI', & - 'IPC_KP', 'IPC_IntSat', 'PC_State', 'PitCom', 'PitComAct', & - 'SS_DelOmegaF', 'TestType', 'Kp_Float', 'VS_MaxTq', 'VS_LastGenTrq', & - 'VS_LastGenPwr', 'VS_MechGenPwr', 'VS_SpdErrAr', 'VS_SpdErrBr', 'VS_SpdErr', & - 'VS_State', 'VS_Rgn3Pitch', 'WE_Vw', 'WE_Vw_F', 'WE_VwI', & - 'WE_VwIdot', 'VS_LastGenTrqF', 'PRC_WSE_F', 'Fl_PitCom', 'NACIMU_FA_AccF', & - 'FA_AccF', 'FA_Hist', 'TRA_LastRefSpd', 'VS_RefSpeed', 'PtfmTDX', & - 'PtfmTDY', 'PtfmTDZ', 'PtfmRDX', 'PtfmRDY', 'PtfmRDZ', & - 'PtfmTVX', 'PtfmTVY', 'PtfmTVZ', 'PtfmRVX', 'PtfmRVY', & - 'PtfmRVZ', 'PtfmTAX', 'PtfmTAY', 'PtfmTAZ', 'PtfmRAX', & - 'PtfmRAY', 'PtfmRAZ', 'CC_DesiredL', 'CC_ActuatedL', 'CC_ActuatedDL', & - 'StC_Input', 'Flp_Angle', 'RootMyb_Last', 'ACC_INFILE_SIZE', 'AWC_complexangle', & - 'ZMQ_ID', 'ZMQ_YawOffset', 'ZMQ_TorqueOffset', 'ZMQ_PitOffset'] + 'VS_GenPwr', 'GenSpeed', 'RotSpeed', 'NacHeading', 'NacVane', & + 'HorWindV', 'rootMOOP', 'rootMOOPF', 'BlPitch', 'BlPitchCMeas', & + 'Azimuth', 'OL_Azimuth', 'AzUnwrapped', 'AzError', 'GenTqAz', & + 'AzBuffer', 'NumBl', 'FA_Acc', 'NacIMU_FA_Acc', 'FA_AccHPF', & + 'FA_AccHPFI', 'FA_PitCom', 'VS_RefSpd', 'VS_RefSpd_TSR', 'VS_RefSpd_TRA', & + 'VS_RefSpd_RL', 'PC_RefSpd', 'PC_RefSpd_SS', 'PC_RefSpd_PRC', 'RotSpeedF', & + 'GenSpeedF', 'GenTq', 'GenTqMeas', 'GenArTq', 'GenBrTq', & + 'VS_KOmega2_GenTq', 'VS_ConstPwr_GenTq', 'IPC_PitComF', 'PC_KP', 'PC_KI', & + 'PC_KD', 'PC_TF', 'PC_MaxPit', 'PC_MinPit', 'PC_PitComT', & + 'PC_PitComT_Last', 'PC_PitComTF', 'PC_PitComT_IPC', 'PC_PwrErr', 'PC_SpdErr', & + 'IPC_AxisTilt_1P', 'IPC_AxisYaw_1P', 'IPC_AxisTilt_2P', 'IPC_AxisYaw_2P', 'axisTilt_1P', & + 'axisYaw_1P', 'axisYawF_1P', 'axisTilt_2P', 'axisYaw_2P', 'axisYawF_2P', & + 'IPC_KI', 'IPC_KP', 'IPC_IntSat', 'PC_State', 'PitCom', & + 'PitComAct', 'SS_DelOmegaF', 'TestType', 'Kp_Float', 'VS_MaxTq', & + 'VS_LastGenTrq', 'VS_LastGenPwr', 'VS_MechGenPwr', 'VS_SpdErrAr', 'VS_SpdErrBr', & + 'VS_SpdErr', 'VS_State', 'VS_Rgn3Pitch', 'WE_Vw', 'WE_Vw_F', & + 'WE_VwI', 'WE_VwIdot', 'VS_LastGenTrqF', 'PRC_WSE_F', 'Fl_PitCom', & + 'NACIMU_FA_AccF', 'FA_AccF', 'FA_Hist', 'TRA_LastRefSpd', 'VS_RefSpeed', & + 'PtfmTDX', 'PtfmTDY', 'PtfmTDZ', 'PtfmRDX', 'PtfmRDY', & + 'PtfmRDZ', 'PtfmTVX', 'PtfmTVY', 'PtfmTVZ', 'PtfmRVX', & + 'PtfmRVY', 'PtfmRVZ', 'PtfmTAX', 'PtfmTAY', 'PtfmTAZ', & + 'PtfmRAX', 'PtfmRAY', 'PtfmRAZ', 'CC_DesiredL', 'CC_ActuatedL', & + 'CC_ActuatedDL', 'StC_Input', 'Flp_Angle', 'RootMyb_Last', 'ACC_INFILE_SIZE', & + 'AWC_complexangle', 'ZMQ_ID', 'ZMQ_YawOffset', 'ZMQ_TorqueOffset', 'ZMQ_PitOffset' & + ] ! Initialize debug file IF ((LocalVar%iStatus == 0) .OR. (LocalVar%iStatus == -9)) THEN ! .TRUE. if we're on the first call to the DLL IF (CntrPar%LoggingLevel > 0) THEN @@ -858,8 +862,8 @@ SUBROUTINE Debug(LocalVar, CntrPar, DebugVar, ErrVar, avrSWAP, RootName, size_av CALL GetNewUnit(UnDb2, ErrVar) OPEN(unit=UnDb2, FILE=TRIM(RootName)//'.RO.dbg2') WRITE(UnDb2, *) 'Generated on '//CurDate()//' at '//CurTime()//' using ROSCO-'//TRIM(rosco_version) - WRITE(UnDb2, '(125(a20,TR5:))') 'Time', LocalVarOutStrings - WRITE(UnDb2, '(125(a20,TR5:))') + WRITE(UnDb2, '(126(a20,TR5:))') 'Time', LocalVarOutStrings + WRITE(UnDb2, '(126(a20,TR5:))') END IF IF (CntrPar%LoggingLevel > 2) THEN @@ -904,25 +908,25 @@ SUBROUTINE Debug(LocalVar, CntrPar, DebugVar, ErrVar, avrSWAP, RootName, size_av ! Process DebugOutData, LocalVarOutData ! Remove very small numbers that cause ******** outputs DO I = 1,SIZE(DebugOutData) - IF (ABS(DebugOutData(I)) < 1D-99) THEN + IF (ABS(DebugOutData(I)) < 1E-99) THEN DebugOutData(I) = 0 END IF - IF (ABS(DebugOutData(I)) > 1D+99) THEN - DebugOutData(I) = 1D+99 + IF (ABS(DebugOutData(I)) > 1E+99) THEN + DebugOutData(I) = 1E+99 END IF END DO DO I = 1,SIZE(LocalVarOutData) - IF (ABS(LocalVarOutData(I)) < 1D-99) THEN + IF (ABS(LocalVarOutData(I)) < 1E-99) THEN LocalVarOutData(I) = 0 END IF - IF (ABS(LocalVarOutData(I)) > 1D+99) THEN - LocalVarOutData(I) = 1D+99 + IF (ABS(LocalVarOutData(I)) > 1E+99) THEN + LocalVarOutData(I) = 1E+99 END IF END DO ! Write debug files - FmtDat = "(F20.5,TR5,124(ES20.5E2,TR5:))" ! The format of the debugging data + FmtDat = "(F20.5,TR5,125(ES20.5E2,TR5:))" ! The format of the debugging data IF ( MOD(LocalVar%n_DT, CntrPar%n_DT_Out) == 0) THEN IF(CntrPar%LoggingLevel > 0) THEN WRITE (UnDb, TRIM(FmtDat)) LocalVar%Time, DebugOutData diff --git a/rosco/controller/src/ROSCO_Types.f90 b/rosco/controller/src/ROSCO_Types.f90 index 8074a268..a073b531 100644 --- a/rosco/controller/src/ROSCO_Types.f90 +++ b/rosco/controller/src/ROSCO_Types.f90 @@ -1,5 +1,5 @@ ! ROSCO Registry -! This file is automatically generated by write_registry.py using ROSCO v2.9.0 +! This file is automatically generated by write_registry.py using ROSCO v2.9.4 ! For any modification to the registry, please edit the rosco_types.yaml accordingly MODULE ROSCO_Types @@ -67,10 +67,10 @@ MODULE ROSCO_Types INTEGER(IntKi) :: VS_ConstPower ! Constant power torque control INTEGER(IntKi) :: VS_FBP ! Fixed blade pitch control mode in above rated conditions {0 - variable pitch (defer to PC_ControlMode and VS_ConstPower), 1 - P/omega overspeed control law, 2 - PI reference tracking based on WSE lookup table, 3 - PI reference tracking based on torque lookup table (must have VS_FBP_Tau be a monotonic function)} REAL(DbKi) :: VS_GenEff ! Generator efficiency mechanical power -> electrical power [-] - REAL(DbKi) :: VS_ArSatTq ! Above rated generator torque PI control saturation, [Nm] -- 212900 + REAL(DbKi) :: VS_ArSatTq ! Above rated generator torque PI control saturation, [Nm] REAL(DbKi) :: VS_MaxRat ! Maximum torque rate (in absolute value) in torque controller, [Nm/s]. - REAL(DbKi) :: VS_MaxTq ! Maximum generator torque in Region 3 (HSS side), [Nm]. -- chosen to be 10% above VS_RtTq - REAL(DbKi) :: VS_MinTq ! Minimum generator (HSS side), [Nm]. + REAL(DbKi) :: VS_MaxTq ! Maximum generator torque in Region 3 (HSS side), [Nm]. + REAL(DbKi) :: VS_MinTq ! Minimum generator torque (HSS side), [Nm]. REAL(DbKi) :: VS_MinOMSpd ! Optimal mode minimum speed, [rad/s] REAL(DbKi) :: VS_Rgn2K ! Generator torque constant in Region 2 (HSS side), N-m/(rad/s)^2 REAL(DbKi) :: VS_RtPwr ! Wind turbine rated power [W] @@ -259,7 +259,6 @@ MODULE ROSCO_Types INTEGER(IntKi) :: n_DT ! number of timesteps since start REAL(DbKi) :: Time_Last ! Last time [s] REAL(DbKi) :: VS_GenPwr ! Generator power [W] - REAL(DbKi) :: VS_GenPwrF ! Generator power [W] REAL(DbKi) :: GenSpeed ! Generator speed (HSS) [rad/s] REAL(DbKi) :: RotSpeed ! Rotor speed (LSS) [rad/s] REAL(DbKi) :: NacHeading ! Nacelle heading of the turbine w.r.t. north [deg] @@ -288,12 +287,14 @@ MODULE ROSCO_Types REAL(DbKi) :: PC_RefSpd ! Generator speed set point of pitch controller [rad/s] REAL(DbKi) :: PC_RefSpd_SS ! Generator speed set point of pitch controller after setpoint smoothing [rad/s] REAL(DbKi) :: PC_RefSpd_PRC ! Generator speed set point of pitch controller after power ref control [rad/s] - REAL(DbKi) :: RotSpeedF ! Filtered LSS (generator) speed [rad/s]. + REAL(DbKi) :: RotSpeedF ! Filtered LSS (rotor) speed [rad/s]. REAL(DbKi) :: GenSpeedF ! Filtered HSS (generator) speed [rad/s]. REAL(DbKi) :: GenTq ! Electrical generator torque, [Nm]. REAL(DbKi) :: GenTqMeas ! Measured generator torque [Nm] REAL(DbKi) :: GenArTq ! Electrical generator torque, for above-rated PI-control [Nm]. REAL(DbKi) :: GenBrTq ! Electrical generator torque, for below-rated PI-control [Nm]. + REAL(DbKi) :: VS_KOmega2_GenTq ! Calculation of torque signal used by K*Omega^2 controller + REAL(DbKi) :: VS_ConstPwr_GenTq ! Calculation of constant-power torque signal REAL(DbKi) :: IPC_PitComF(3) ! Commanded pitch of each blade as calculated by the individual pitch controller, F stands for low-pass filtered [rad]. REAL(DbKi) :: PC_KP ! Proportional gain for pitch controller at rated pitch (zero) [s]. REAL(DbKi) :: PC_KI ! Integral gain for pitch controller at rated pitch (zero) [-]. From 6d79062d95244ec811621b69306f7367fb4139c3 Mon Sep 17 00:00:00 2001 From: David Stockhouse Date: Wed, 18 Sep 2024 12:01:32 -0600 Subject: [PATCH 181/224] Added more precise calculation of Cp-optimizing pitch and updated the FBP and VBP tuning procedure to compute everything based on min_pitch rather than assuming fine pitch to be zero --- rosco/toolbox/controller.py | 52 ++++++++++++----------- rosco/toolbox/inputs/toolbox_schema.yaml | 1 - rosco/toolbox/turbine.py | 53 ++++++++++++++---------- 3 files changed, 59 insertions(+), 47 deletions(-) diff --git a/rosco/toolbox/controller.py b/rosco/toolbox/controller.py index e07f5b39..0d3ce2b0 100644 --- a/rosco/toolbox/controller.py +++ b/rosco/toolbox/controller.py @@ -83,7 +83,6 @@ def __init__(self, controller_params): self.interp_type = controller_params['interp_type'] # Optional parameters with defaults - self.min_pitch = controller_params['min_pitch'] self.max_pitch = controller_params['max_pitch'] self.vs_minspd = controller_params['vs_minspd'] self.ss_vsgain = controller_params['ss_vsgain'] @@ -106,7 +105,11 @@ def __init__(self, controller_params): self.fbp_U = controller_params['VS_FBP_U'] # DBS: Should we set this default based on rated speed? self.fbp_P = controller_params['VS_FBP_P'] - # Optional parameters without defaults + # Optional parameters without defaults + if 'min_pitch' in controller_params: + # Set below if no user input + self.min_pitch = controller_params['min_pitch'] + if self.VS_FBP > 0: # Fail if generator torque enabled in Region 3 but pitch control not disabled (may enable these modes to operate together in the future) @@ -198,7 +201,7 @@ def __init__(self, controller_params): not len(self.U_pc) == len(self.omega_pc) == len(self.zeta_pc): raise Exception( 'U_pc, omega_pc, and zeta_pc are all list-like and are not of equal length') - + def tune_controller(self, turbine): """ @@ -220,6 +223,9 @@ def tune_controller(self, turbine): # ------------- Saturation Limits --------------- # turbine.max_torque = turbine.rated_torque * self.controller_params['max_torque_factor'] + if not hasattr(self, 'min_pitch') or not isinstance(self.min_pitch, float): # Set min pitch to optimal if no user input + self.min_pitch = turbine.Cp.pitch_opt + turbine.min_pitch = self.min_pitch # -------------Define Operation Points ------------- # TSR_rated = rated_rotor_speed*R/turbine.v_rated # TSR at rated @@ -243,17 +249,18 @@ def tune_controller(self, turbine): if self.fbp_power_mode == 0: P_user_defined *= turbine.rated_power # Maximum potential power from MPPT (extending Region 2 power curve to cut-out) - P_max = 0.5 * turbine.rho * np.pi*turbine.rotor_radius**2 * turbine.Cp.max * v**3 \ + Cp_operational = turbine.Cp.interp_surface(self.min_pitch, turbine.TSR_operational) # Compute TSR at controller pitch saturation and operational TSR (may not be optimal) + P_max = 0.5 * turbine.rho * np.pi*turbine.rotor_radius**2 * Cp_operational * v**3 \ * turbine.GBoxEff/100 * turbine.GenEff/100 # Includes generator efficiency reduction from available inflow power - # Take minimum + # Take minimum between user input and max possible P_op = np.min([P_user_defined, P_max], axis=0) # Operation along Cp surface (with fixed pitch) - Cp_op = (P_op / P_max) * turbine.Cp.max + Cp_op = (P_op / P_max) * Cp_operational Cp_op_br = Cp_op[:len(v_below_rated)] Cp_op_ar = Cp_op[len(v_below_rated):] # Identify TSR matching the Cp values (similar to variable pitch angle interpolation below) - Cp_FBP = np.ndarray.flatten(turbine.Cp.interp_surface(0, turbine.TSR_initial)) # all Cp values for fine blade pitch (assumed 0) + Cp_FBP = np.ndarray.flatten(turbine.Cp.interp_surface(self.min_pitch, turbine.TSR_initial)) # all Cp values for fine blade pitch Cp_maxidx = Cp_FBP.argmax() # When we depart from Cp_max, our TSR has to fall to either above or below TSR_opt, leading to overspeed and underspeed configurations if self.fbp_speed_mode: # Overspeed @@ -265,21 +272,23 @@ def tune_controller(self, turbine): Cp_op = np.clip(Cp_op, np.min(Cp_FBP[:Cp_maxidx+1]), np.max(Cp_FBP[:Cp_maxidx+1])) # saturate Cp values to be on Cp surface # Find maximum Cp value for this TSR f_cp_TSR = interpolate.interp1d(Cp_FBP[:Cp_maxidx+1], turbine.TSR_initial[:Cp_maxidx+1]) # interpolate function for Cp(tsr) values TSR_op = f_cp_TSR(Cp_op) - TSR_below_rated = TSR_op[:len(v_below_rated)] + # Defer to operational TSR for below rated, even if other optimum (should keep Cp the same, but may lead to discontinuities in operating schedule if min_pitch is not optimal) + TSR_op[v < turbine.v_rated] = turbine.TSR_operational + TSR_below_rated = TSR_op[:len(v_below_rated)] # Should be constant at TSR_operational TSR_above_rated = TSR_op[len(v_below_rated):] # elif self.PC_ControlMode > 0: # If using pitch control in Region 3 else: # Default here even if pitch control disabled to maintain backwards compatibility - # separate TSRs by operations regions - TSR_below_rated = [min(turbine.TSR_operational, rated_rotor_speed*R/v) for v in v_below_rated] # below rated + # TSR setpoints + TSR_below_rated = [min(turbine.TSR_operational, rated_rotor_speed*R/v) for v in v_below_rated] # below rated, saturated to not exceed rated rotor speed TSR_above_rated = rated_rotor_speed*R/v_above_rated # above rated TSR_op = np.concatenate((TSR_below_rated, TSR_above_rated)) # operational TSRs # Find expected operational Cp values - Cp_above_rated = turbine.Cp.interp_surface(0,TSR_above_rated[0]) # Cp during rated operation (not optimal). Assumes cut-in bld pitch to be 0 - Cp_op_br = np.ones(len(v_below_rated)) * turbine.Cp.max # below rated + Cp_above_rated = turbine.Cp.interp_surface(self.min_pitch,TSR_above_rated[0]) # Cp during rated operation (not optimal) Cp_op_ar = Cp_above_rated * (TSR_above_rated/TSR_rated)**3 # above rated + Cp_op_br = [turbine.Cp.interp_surface(self.min_pitch, TSR) for TSR in TSR_below_rated] # Below rated, reinterpolated for accurate operational Cp based on controller pitch Cp_op = np.concatenate((Cp_op_br, Cp_op_ar)) # operational CPs to linearize around @@ -299,11 +308,8 @@ def tune_controller(self, turbine): if self.VS_FBP > 0: # Fixed blade pitch control in Region 3 - if isinstance(self.min_pitch, float): - pitch_op[i] = self.min_pitch - else: - # pitch_op[i] = 0 # Assume zero pitch - pitch_op[i] = turbine.pitch_initial_rad[turbine.Cp.max_ind[1]] # Take optimal pitch from Cp surface + # Constant pitch, either user input or optimal pitch from Cp surface + pitch_op[i] = self.min_pitch else: # Variable pitch control in Region 3 (default) @@ -314,12 +320,10 @@ def tune_controller(self, turbine): f_cp_pitch = interpolate.interp1d(Cp_TSR[Cp_maxidx:],pitch_initial_rad[Cp_maxidx:]) # interpolate function for Cp(tsr) values # expected operational blade pitch values. Saturates by min_pitch if it exists - if v[i] <= turbine.v_rated and isinstance(self.min_pitch, float): # Below rated & defined min_pitch + if v[i] <= turbine.v_rated: # Below rated, keep lowest pitch pitch_op[i] = min(self.min_pitch, f_cp_pitch(Cp_op[i])) - elif isinstance(self.min_pitch, float): # above rated & defined min_pitch + else: # above rated, keep highest pitch pitch_op[i] = max(self.min_pitch, f_cp_pitch(Cp_op[i])) - else: # no defined minimum pitch schedule - pitch_op[i] = f_cp_pitch(Cp_op[i]) # Calculate Cp Surface gradients dCp_beta[i], dCp_TSR[i] = turbine.Cp.interp_gradient(pitch_op[i],TSR_op[i]) @@ -331,10 +335,6 @@ def tune_controller(self, turbine): Ct_op[i] = f_ct(pitch_op[i]) Ct_op[i] = np.clip(Ct_op[i], np.min(Ct_TSR), np.max(Ct_TSR)) # saturate Ct values to be on Ct surface - # Define minimum pitch saturation to be at Cp-maximizing pitch angle if not specifically defined - if not isinstance(self.min_pitch, float): - self.min_pitch = pitch_op[0] - # Compute generator speed and torque operating schedule P_op = 0.5 * turbine.rho * np.pi*turbine.rotor_radius**2 * Cp_op * v**3 * turbine.GBoxEff/100 * turbine.GenEff/100 if self.VS_FBP == 0: # Saturate between min speed and rated if variable pitch in Region 3 @@ -411,8 +411,10 @@ def tune_controller(self, turbine): self.pc_gain_schedule.second_order_PI(self.zeta_pc_U, self.omega_pc_U,A_pc,B_beta[-len(v_above_rated)+1:],linearize=True,v=v_above_rated[1:]) self.vs_gain_schedule = ControllerTypes() if self.VS_FBP == 0: + # Using variable pitch control in Region 3, so generate torque gain schedule only for Region 2 self.vs_gain_schedule.second_order_PI(self.zeta_vs, self.omega_vs,A_vs,B_tau[0:len(v_below_rated)],linearize=False,v=v_below_rated) else: + # Using fixed pitch torque control in Region 3, so generate torque gain schedule for Regions 2 and 3 self.vs_gain_schedule.second_order_PI(self.zeta_vs, self.omega_vs,A,B_tau,linearize=False,v=v) # -- Find K for Komega_g^2 -- diff --git a/rosco/toolbox/inputs/toolbox_schema.yaml b/rosco/toolbox/inputs/toolbox_schema.yaml index 179c91a3..c1a1a6f9 100644 --- a/rosco/toolbox/inputs/toolbox_schema.yaml +++ b/rosco/toolbox/inputs/toolbox_schema.yaml @@ -312,7 +312,6 @@ properties: min_pitch: description: Minimum pitch angle [rad], {default = 0 degrees} type: number - default: 0 unit: rad vs_minspd: description: Minimum rotor speed [rad/s], {default = 0 rad/s} diff --git a/rosco/toolbox/turbine.py b/rosco/toolbox/turbine.py index b4a3e9c5..5fbf6842 100644 --- a/rosco/toolbox/turbine.py +++ b/rosco/toolbox/turbine.py @@ -57,7 +57,6 @@ class Turbine(): load_from_ccblade load_from_txt generate_rotperf_fast - write_rotor_performance Parameters: ----------- @@ -272,6 +271,8 @@ def load_from_fast( # Define operational TSR if not self.TSR_operational: self.TSR_operational = self.Cp.TSR_opt + # Compute operational Cp (may not be optimal if TSR_operational set by user) + self.Cp_operational = self.Cp.interp_surface(self.Cp.pitch_opt, self.TSR_operational) # Pull out some floating-related data try: @@ -291,7 +292,6 @@ def load_from_ccblade(self): Dictionary containing fast model details - defined using from InputReader_OpenFAST (distributed as a part of AeroelasticSE) ''' - from wisdem.ccblade.ccblade import CCAirfoil, CCBlade print('Loading rotor performance data from CC-Blade.') @@ -334,7 +334,6 @@ def load_from_ccblade(self): self.Ct_table = Ct self.Cq_table = Cq - def generate_rotperf_fast(self, openfast_path, FAST_runDirectory=None, run_BeamDyn=False, debug_level=1, run_type='multi'): ''' @@ -622,7 +621,7 @@ class RotorPerformance(): TSR_initial : array_like (rad) An [n x 1] or [1 x n] array containing tip-speed ratios corresponding to performance_table ''' - def __init__(self,performance_table, pitch_initial_rad, TSR_initial): + def __init__(self, performance_table, pitch_initial_rad, TSR_initial): # Store performance data tables self.performance_table = performance_table # Table containing rotor performance data, i.e. Cp, Ct, Cq @@ -635,27 +634,39 @@ def __init__(self,performance_table, pitch_initial_rad, TSR_initial): # "Optimal" below rated TSR and blade pitch (for Cp) - note this may be limited by resolution of Cp-surface self.max = np.amax(performance_table) self.max_ind = np.where(performance_table == np.amax(performance_table)) - self.pitch_opt = pitch_initial_rad[self.max_ind[1]] - # --- Find TSR --- - # Make finer mesh for Tip speed ratios at "optimal" blade pitch angle, do a simple lookup. - # -- nja: this seems to work a little better than interpolating - # Find the 1D performance table when pitch is at the maximum part of the Cx surface: - performance_beta_max = np.ndarray.flatten(performance_table[:,self.max_ind[1][-1]]) # performance metric at the last maximizing pitch angle - - # If there is more than one max pitch angle: + # Throw a warning if there is more than one max pitch angle if len(self.max_ind[1]) > 1: print('rosco.toolbox Warning: repeated maximum values in a performance table and the last one @ pitch = {} rad. was taken...'.format(self.pitch_opt[-1])) - # Find TSR that maximizes Cx at fine pitch - # - TSR to satisfy: max( Cx(TSR, \beta_fine) ) = TSR_opt - TSR_fine_ind = np.linspace(TSR_initial[0],TSR_initial[-1],int(TSR_initial[-1] - TSR_initial[0])*100) # Range of TSRs to interpolate accross - f_TSR = interpolate.interp1d(TSR_initial,TSR_initial,bounds_error='False',kind='quadratic') # interpolate function for Cp(tsr) values - TSR_fine = f_TSR(TSR_fine_ind) # TSRs at fine pitch - f_performance = interpolate.interp1d(TSR_initial,performance_beta_max,bounds_error='False',kind='quadratic') # interpolate function for Cx(tsr) values - performance_fine = f_performance(TSR_fine_ind) # Cx values at fine pitch - performance_max_ind = np.where(performance_fine == np.max(performance_fine)) # Find max performance at fine pitch - self.TSR_opt = float(TSR_fine[performance_max_ind[0]][0]) # TSR to maximize Cx at fine pitch + # Refine optimal point using smooth interpolation -- gives more precise estimates than coarse grid + # Select region around maximizing TSR and blade pitch + TSR_max_ind = self.max_ind[0][-1] + pitch_max_ind = self.max_ind[1][-1] + ind_search_num = 3 + TSR_search_ind = [np.max([0, TSR_max_ind - ind_search_num]), np.min([TSR_max_ind + ind_search_num, len(self.TSR_initial)-1])] + pitch_search_ind = [np.max([0, pitch_max_ind - ind_search_num]), np.min([pitch_max_ind + ind_search_num, len(self.pitch_initial_rad)-1])] + TSR_search_range = range(TSR_search_ind[0], TSR_search_ind[1]+1) + pitch_search_range = range(pitch_search_ind[0], pitch_search_ind[1]+1) + + print('rosco.toolbox: Refining maximum performance estimate...') + + # Generate finer mesh in the proximity of maximizer + fine_mesh_scale = 20 + TSR_fine = np.linspace(self.TSR_initial[TSR_search_ind[0]], self.TSR_initial[TSR_search_ind[1]], np.diff(TSR_search_ind)[0] * fine_mesh_scale) + pitch_fine = np.linspace(self.pitch_initial_rad[pitch_search_ind[0]], self.pitch_initial_rad[pitch_search_ind[1]], np.diff(pitch_search_ind)[0] * fine_mesh_scale) + pitch_fine_mesh, TSR_fine_mesh = np.meshgrid(pitch_fine, TSR_fine) # Construct mesh grids of fine data to interpolate performance surface + performance_fine = interpolate.interpn([TSR_initial[TSR_search_range], pitch_initial_rad[pitch_search_range]], \ + self.performance_table[TSR_search_range, :][:, pitch_search_range], \ + np.array([TSR_fine_mesh, pitch_fine_mesh]).T, \ + bounds_error='False', method='cubic') # Cubic spline interpolation over finer mesh data + + # Save optimal performance, TSR, and pitch + self.performance_opt = np.max(performance_fine) # Maximal Cx on fine grid + performance_max_ind = np.where(performance_fine == self.performance_opt) # Find maximizer + self.TSR_opt = float(TSR_fine[performance_max_ind[0][0]]) # If multiple maximizers, pick lowest TSR + self.pitch_opt = float(pitch_fine[performance_max_ind[1][-1]]) # If multiple maximizers, pick highest pitch + def interp_surface(self,pitch,TSR): ''' From 2ec41dd0c98744a38a54e0ee0243a15cc09d2523 Mon Sep 17 00:00:00 2001 From: dzalkind Date: Fri, 27 Sep 2024 16:04:09 -0600 Subject: [PATCH 182/224] Disable WSE automatically outside normal operation --- .../rosco_registry/rosco_types.yaml | 9 + rosco/controller/src/ControllerBlocks.f90 | 49 ++- rosco/controller/src/ROSCO_IO.f90 | 312 +++++++++--------- rosco/controller/src/ROSCO_Types.f90 | 3 + rosco/controller/src/ReadSetParameters.f90 | 2 + 5 files changed, 214 insertions(+), 161 deletions(-) diff --git a/rosco/controller/rosco_registry/rosco_types.yaml b/rosco/controller/rosco_registry/rosco_types.yaml index c807516d..ad9fdcfb 100644 --- a/rosco/controller/rosco_registry/rosco_types.yaml +++ b/rosco/controller/rosco_registry/rosco_types.yaml @@ -1012,6 +1012,9 @@ LocalVariables: HorWindV: <<: *real description: Hub height wind speed m/s + HorWindV_F: + <<: *real + description: Filtered hub height wind speed m/s rootMOOP: <<: *real description: Blade root bending moment [Nm] @@ -1245,6 +1248,12 @@ LocalVariables: WE_VwIdot: <<: *real description: Differentiated integrated wind speed quantity for estimation [m/s] + WE_Op: + <<: *integer + description: WSE Operational state (0- not operating, 1-operating) + WE_Op_Last: + <<: *integer + description: WSE Operational state (0- not operating, 1-operating) VS_LastGenTrqF: <<: *real description: Differentiated integrated wind speed quantity for estimation [m/s] diff --git a/rosco/controller/src/ControllerBlocks.f90 b/rosco/controller/src/ControllerBlocks.f90 index fc7df9d9..8a95a1cb 100644 --- a/rosco/controller/src/ControllerBlocks.f90 +++ b/rosco/controller/src/ControllerBlocks.f90 @@ -18,6 +18,7 @@ MODULE ControllerBlocks USE Constants USE Filters USE Functions +USE SysSubs IMPLICIT NONE @@ -273,30 +274,58 @@ SUBROUTINE WindSpeedEstimator(LocalVar, CntrPar, objInst, PerfData, DebugVar, Er REAL(DbKi) :: WE_Inp_Pitch REAL(DbKi) :: WE_Inp_Torque REAL(DbKi) :: WE_Inp_Speed + REAL(DbKi) :: Max_Op_Pitch CHARACTER(*), PARAMETER :: RoutineName = 'WindSpeedEstimator' + CHARACTER(1024) :: WarningMessage - ! Saturate inputs to WSE + ! Saturate inputs to WSE: + ! Rotor speed IF (LocalVar%RotSpeedF < 0.25 * CntrPar%VS_MinOMSpd / CntrPar%WE_GearboxRatio) THEN WE_Inp_Speed = 0.25 * CntrPar%VS_MinOMSpd / CntrPar%WE_GearboxRatio + EPSILON(1.0_DbKi) ! If this is 0, could cause problems... ELSE WE_Inp_Speed = LocalVar%RotSpeedF END IF - IF (LocalVar%BlPitchCMeas < CntrPar%PC_MinPit) THEN - WE_Inp_Pitch = CntrPar%PC_MinPit - ELSE - WE_Inp_Pitch = LocalVar%BlPitchCMeas - END IF + + ! Blade pitch + Max_Op_Pitch = PerfData%Beta_vec(SIZE(PerfData%Beta_vec)) * D2R ! The Cp surface is only valid up to the end of Beta_vec + WE_Inp_Pitch = saturate(LocalVar%BlPitchCMeas, CntrPar%PC_MinPit,Max_Op_Pitch) + ! Gen torque IF (LocalVar%VS_LastGenTrqF < 0.0001 * CntrPar%VS_RtTq) THEN WE_Inp_Torque = 0.0001 * CntrPar%VS_RtTq ELSE WE_Inp_Torque = LocalVar%VS_LastGenTrqF END IF + ! Check to see if in operational range + LocalVar%WE_Op_Last = LocalVar%WE_Op + IF (ABS(WE_Inp_Pitch - LocalVar%BlPitchCMeas) > 0) THEN + LocalVar%WE_Op = 0 + ELSEIF (ABS(WE_Inp_Torque - LocalVar%VS_LastGenTrqF) > 0) THEN + LocalVar%WE_Op = 0 + ELSEIF (ABS(WE_Inp_Speed - LocalVar%RotSpeedF) > 0) THEN + LocalVar%WE_Op = 0 + ELSE + LocalVar%WE_Op = 1 + ENDIF + + IF (CntrPar%WE_Mode > 0) THEN + IF (LocalVar%WE_Op < 1 .AND. LocalVar%WE_Op_Last == 1) THEN + WarningMessage = NewLine//'***************************************************************************************************************************************'//NewLine// & + 'ROSCO Warning: The wind speed estimator is used, but an input (pitch, rotor speed, or torque) has left the bounds of normal operation.'//NewLine// & + 'The filtered hub-height wind speed will be used instead. This warning will not persist even though the condition may.'//NewLine// & + '***************************************************************************************************************************************' + PRINT *, TRIM(WarningMessage) + ENDIF + ENDIF + + ! Filter the wind speed at hub height regardless, only use if WE_Mode = 0 or WE_Op = 0 + LocalVar%HorWindV_F = LPFilter(LocalVar%HorWindV, LocalVar%DT, CntrPar%F_WECornerFreq, LocalVar%FP, LocalVar%iStatus, LocalVar%restart, objInst%instLPF) + ! ---- Debug Inputs ------ DebugVar%WE_b = WE_Inp_Pitch DebugVar%WE_w = WE_Inp_Speed @@ -305,7 +334,7 @@ SUBROUTINE WindSpeedEstimator(LocalVar, CntrPar, objInst, PerfData, DebugVar, Er ! ---- Define wind speed estimate ---- ! Inversion and Invariance Filter implementation - IF (CntrPar%WE_Mode == 1) THEN + IF (CntrPar%WE_Mode == 1 .AND. LocalVar%WE_Op > 0) THEN ! Compute AeroDynTorque Tau_r = AeroDynTorque(LocalVar%RotSpeedF, LocalVar%BlPitchCMeas, LocalVar, CntrPar, PerfData, ErrVar) @@ -314,7 +343,7 @@ SUBROUTINE WindSpeedEstimator(LocalVar, CntrPar, objInst, PerfData, DebugVar, Er LocalVar%WE_Vw = LocalVar%WE_VwI + CntrPar%WE_Gamma*LocalVar%RotSpeedF ! Extended Kalman Filter (EKF) implementation - ELSEIF (CntrPar%WE_Mode == 2) THEN + ELSEIF (CntrPar%WE_Mode == 2 .AND. LocalVar%WE_Op > 0) THEN ! Define contant values L = 6.0 * CntrPar%WE_BladeRadius Ti = 0.18 @@ -396,8 +425,8 @@ SUBROUTINE WindSpeedEstimator(LocalVar, CntrPar, objInst, PerfData, DebugVar, Er DebugVar%WE_Vt = LocalVar%WE%v_t DebugVar%WE_lambda = lambda ELSE - ! Filter wind speed at hub height as directly passed from OpenFAST - LocalVar%WE_Vw = LPFilter(LocalVar%HorWindV, LocalVar%DT, CntrPar%F_WECornerFreq, LocalVar%FP, LocalVar%iStatus, LocalVar%restart, objInst%instLPF) + ! Use filtered hub-height + LocalVar%WE_Vw = LocalVar%HorWindV_F ENDIF DebugVar%WE_Vw = LocalVar%WE_Vw ! Add RoutineName to error message diff --git a/rosco/controller/src/ROSCO_IO.f90 b/rosco/controller/src/ROSCO_IO.f90 index a6d42209..f1fbe979 100644 --- a/rosco/controller/src/ROSCO_IO.f90 +++ b/rosco/controller/src/ROSCO_IO.f90 @@ -49,6 +49,7 @@ SUBROUTINE WriteRestartFile(LocalVar, CntrPar, ErrVar, objInst, RootName, size_a WRITE( Un, IOSTAT=ErrStat) LocalVar%NacHeading WRITE( Un, IOSTAT=ErrStat) LocalVar%NacVane WRITE( Un, IOSTAT=ErrStat) LocalVar%HorWindV + WRITE( Un, IOSTAT=ErrStat) LocalVar%HorWindV_F WRITE( Un, IOSTAT=ErrStat) LocalVar%rootMOOP(1) WRITE( Un, IOSTAT=ErrStat) LocalVar%rootMOOP(2) WRITE( Un, IOSTAT=ErrStat) LocalVar%rootMOOP(3) @@ -142,6 +143,8 @@ SUBROUTINE WriteRestartFile(LocalVar, CntrPar, ErrVar, objInst, RootName, size_a WRITE( Un, IOSTAT=ErrStat) LocalVar%WE_Vw_F WRITE( Un, IOSTAT=ErrStat) LocalVar%WE_VwI WRITE( Un, IOSTAT=ErrStat) LocalVar%WE_VwIdot + WRITE( Un, IOSTAT=ErrStat) LocalVar%WE_Op + WRITE( Un, IOSTAT=ErrStat) LocalVar%WE_Op_Last WRITE( Un, IOSTAT=ErrStat) LocalVar%VS_LastGenTrqF WRITE( Un, IOSTAT=ErrStat) LocalVar%PRC_WSE_F WRITE( Un, IOSTAT=ErrStat) LocalVar%PRC_R_Speed @@ -361,6 +364,7 @@ SUBROUTINE ReadRestartFile(avrSWAP, LocalVar, CntrPar, objInst, PerfData, RootNa READ( Un, IOSTAT=ErrStat) LocalVar%NacHeading READ( Un, IOSTAT=ErrStat) LocalVar%NacVane READ( Un, IOSTAT=ErrStat) LocalVar%HorWindV + READ( Un, IOSTAT=ErrStat) LocalVar%HorWindV_F READ( Un, IOSTAT=ErrStat) LocalVar%rootMOOP(1) READ( Un, IOSTAT=ErrStat) LocalVar%rootMOOP(2) READ( Un, IOSTAT=ErrStat) LocalVar%rootMOOP(3) @@ -454,6 +458,8 @@ SUBROUTINE ReadRestartFile(avrSWAP, LocalVar, CntrPar, objInst, PerfData, RootNa READ( Un, IOSTAT=ErrStat) LocalVar%WE_Vw_F READ( Un, IOSTAT=ErrStat) LocalVar%WE_VwI READ( Un, IOSTAT=ErrStat) LocalVar%WE_VwIdot + READ( Un, IOSTAT=ErrStat) LocalVar%WE_Op + READ( Un, IOSTAT=ErrStat) LocalVar%WE_Op_Last READ( Un, IOSTAT=ErrStat) LocalVar%VS_LastGenTrqF READ( Un, IOSTAT=ErrStat) LocalVar%PRC_WSE_F READ( Un, IOSTAT=ErrStat) LocalVar%PRC_R_Speed @@ -712,7 +718,7 @@ SUBROUTINE Debug(LocalVar, CntrPar, DebugVar, ErrVar, avrSWAP, RootName, size_av '[N/A]', '[N/A]', '[N/A]', '[N/A]', '[rad/s]', & '[deg]', '[deg]', '[deg]', '[N/A]', '[rad/s]', & '[rad/s]'] - nLocalVars = 134 + nLocalVars = 137 Allocate(LocalVarOutData(nLocalVars)) Allocate(LocalVarOutStrings(nLocalVars)) LocalVarOutData(1) = LocalVar%iStatus @@ -727,155 +733,159 @@ SUBROUTINE Debug(LocalVar, CntrPar, DebugVar, ErrVar, avrSWAP, RootName, size_av LocalVarOutData(10) = LocalVar%NacHeading LocalVarOutData(11) = LocalVar%NacVane LocalVarOutData(12) = LocalVar%HorWindV - LocalVarOutData(13) = LocalVar%rootMOOP(1) - LocalVarOutData(14) = LocalVar%rootMOOPF(1) - LocalVarOutData(15) = LocalVar%BlPitch(1) - LocalVarOutData(16) = LocalVar%BlPitchCMeas - LocalVarOutData(17) = LocalVar%Azimuth - LocalVarOutData(18) = LocalVar%OL_Azimuth - LocalVarOutData(19) = LocalVar%AzUnwrapped - LocalVarOutData(20) = LocalVar%AzError - LocalVarOutData(21) = LocalVar%GenTqAz - LocalVarOutData(22) = LocalVar%AzBuffer(1) - LocalVarOutData(23) = LocalVar%NumBl - LocalVarOutData(24) = LocalVar%FA_Acc - LocalVarOutData(25) = LocalVar%NacIMU_FA_Acc - LocalVarOutData(26) = LocalVar%FA_AccHPF - LocalVarOutData(27) = LocalVar%FA_AccHPFI - LocalVarOutData(28) = LocalVar%FA_PitCom(1) - LocalVarOutData(29) = LocalVar%VS_RefSpd - LocalVarOutData(30) = LocalVar%VS_RefSpd_TSR - LocalVarOutData(31) = LocalVar%VS_RefSpd_TRA - LocalVarOutData(32) = LocalVar%VS_RefSpd_RL - LocalVarOutData(33) = LocalVar%PC_RefSpd - LocalVarOutData(34) = LocalVar%PC_RefSpd_SS - LocalVarOutData(35) = LocalVar%PC_RefSpd_PRC - LocalVarOutData(36) = LocalVar%RotSpeedF - LocalVarOutData(37) = LocalVar%GenSpeedF - LocalVarOutData(38) = LocalVar%GenTq - LocalVarOutData(39) = LocalVar%GenTqMeas - LocalVarOutData(40) = LocalVar%GenArTq - LocalVarOutData(41) = LocalVar%GenBrTq - LocalVarOutData(42) = LocalVar%IPC_PitComF(1) - LocalVarOutData(43) = LocalVar%PC_KP - LocalVarOutData(44) = LocalVar%PC_KI - LocalVarOutData(45) = LocalVar%PC_KD - LocalVarOutData(46) = LocalVar%PC_TF - LocalVarOutData(47) = LocalVar%PC_MaxPit - LocalVarOutData(48) = LocalVar%PC_MinPit - LocalVarOutData(49) = LocalVar%PC_PitComT - LocalVarOutData(50) = LocalVar%PC_PitComT_Last - LocalVarOutData(51) = LocalVar%PC_PitComTF - LocalVarOutData(52) = LocalVar%PC_PitComT_IPC(1) - LocalVarOutData(53) = LocalVar%PC_PwrErr - LocalVarOutData(54) = LocalVar%PC_SpdErr - LocalVarOutData(55) = LocalVar%IPC_AxisTilt_1P - LocalVarOutData(56) = LocalVar%IPC_AxisYaw_1P - LocalVarOutData(57) = LocalVar%IPC_AxisTilt_2P - LocalVarOutData(58) = LocalVar%IPC_AxisYaw_2P - LocalVarOutData(59) = LocalVar%axisTilt_1P - LocalVarOutData(60) = LocalVar%axisYaw_1P - LocalVarOutData(61) = LocalVar%axisYawF_1P - LocalVarOutData(62) = LocalVar%axisTilt_2P - LocalVarOutData(63) = LocalVar%axisYaw_2P - LocalVarOutData(64) = LocalVar%axisYawF_2P - LocalVarOutData(65) = LocalVar%IPC_KI(1) - LocalVarOutData(66) = LocalVar%IPC_KP(1) - LocalVarOutData(67) = LocalVar%IPC_IntSat - LocalVarOutData(68) = LocalVar%PC_State - LocalVarOutData(69) = LocalVar%PitCom(1) - LocalVarOutData(70) = LocalVar%PitComAct(1) - LocalVarOutData(71) = LocalVar%SS_DelOmegaF - LocalVarOutData(72) = LocalVar%TestType - LocalVarOutData(73) = LocalVar%Kp_Float - LocalVarOutData(74) = LocalVar%VS_MaxTq - LocalVarOutData(75) = LocalVar%VS_LastGenTrq - LocalVarOutData(76) = LocalVar%VS_LastGenPwr - LocalVarOutData(77) = LocalVar%VS_MechGenPwr - LocalVarOutData(78) = LocalVar%VS_SpdErrAr - LocalVarOutData(79) = LocalVar%VS_SpdErrBr - LocalVarOutData(80) = LocalVar%VS_SpdErr - LocalVarOutData(81) = LocalVar%VS_State - LocalVarOutData(82) = LocalVar%VS_Rgn3Pitch - LocalVarOutData(83) = LocalVar%WE_Vw - LocalVarOutData(84) = LocalVar%WE_Vw_F - LocalVarOutData(85) = LocalVar%WE_VwI - LocalVarOutData(86) = LocalVar%WE_VwIdot - LocalVarOutData(87) = LocalVar%VS_LastGenTrqF - LocalVarOutData(88) = LocalVar%PRC_WSE_F - LocalVarOutData(89) = LocalVar%PRC_R_Speed - LocalVarOutData(90) = LocalVar%PRC_R_Torque - LocalVarOutData(91) = LocalVar%PRC_R_Pitch - LocalVarOutData(92) = LocalVar%PRC_R_Total - LocalVarOutData(93) = LocalVar%PRC_Min_Pitch - LocalVarOutData(94) = LocalVar%PS_Min_Pitch - LocalVarOutData(95) = LocalVar%OL_Index - LocalVarOutData(96) = LocalVar%Fl_PitCom - LocalVarOutData(97) = LocalVar%NACIMU_FA_AccF - LocalVarOutData(98) = LocalVar%FA_AccF - LocalVarOutData(99) = LocalVar%FA_Hist - LocalVarOutData(100) = LocalVar%TRA_LastRefSpd - LocalVarOutData(101) = LocalVar%VS_RefSpeed - LocalVarOutData(102) = LocalVar%PtfmTDX - LocalVarOutData(103) = LocalVar%PtfmTDY - LocalVarOutData(104) = LocalVar%PtfmTDZ - LocalVarOutData(105) = LocalVar%PtfmRDX - LocalVarOutData(106) = LocalVar%PtfmRDY - LocalVarOutData(107) = LocalVar%PtfmRDZ - LocalVarOutData(108) = LocalVar%PtfmTVX - LocalVarOutData(109) = LocalVar%PtfmTVY - LocalVarOutData(110) = LocalVar%PtfmTVZ - LocalVarOutData(111) = LocalVar%PtfmRVX - LocalVarOutData(112) = LocalVar%PtfmRVY - LocalVarOutData(113) = LocalVar%PtfmRVZ - LocalVarOutData(114) = LocalVar%PtfmTAX - LocalVarOutData(115) = LocalVar%PtfmTAY - LocalVarOutData(116) = LocalVar%PtfmTAZ - LocalVarOutData(117) = LocalVar%PtfmRAX - LocalVarOutData(118) = LocalVar%PtfmRAY - LocalVarOutData(119) = LocalVar%PtfmRAZ - LocalVarOutData(120) = LocalVar%CC_DesiredL(1) - LocalVarOutData(121) = LocalVar%CC_ActuatedL(1) - LocalVarOutData(122) = LocalVar%CC_ActuatedDL(1) - LocalVarOutData(123) = LocalVar%StC_Input(1) - LocalVarOutData(124) = LocalVar%Flp_Angle(1) - LocalVarOutData(125) = LocalVar%RootMyb_Last(1) - LocalVarOutData(126) = LocalVar%ACC_INFILE_SIZE - LocalVarOutData(127) = LocalVar%AWC_complexangle(1) - LocalVarOutData(128) = LocalVar%ZMQ_ID - LocalVarOutData(129) = LocalVar%ZMQ_YawOffset - LocalVarOutData(130) = LocalVar%ZMQ_TorqueOffset - LocalVarOutData(131) = LocalVar%ZMQ_PitOffset(1) - LocalVarOutData(132) = LocalVar%ZMQ_R_Speed - LocalVarOutData(133) = LocalVar%ZMQ_R_Torque - LocalVarOutData(134) = LocalVar%ZMQ_R_Pitch + LocalVarOutData(13) = LocalVar%HorWindV_F + LocalVarOutData(14) = LocalVar%rootMOOP(1) + LocalVarOutData(15) = LocalVar%rootMOOPF(1) + LocalVarOutData(16) = LocalVar%BlPitch(1) + LocalVarOutData(17) = LocalVar%BlPitchCMeas + LocalVarOutData(18) = LocalVar%Azimuth + LocalVarOutData(19) = LocalVar%OL_Azimuth + LocalVarOutData(20) = LocalVar%AzUnwrapped + LocalVarOutData(21) = LocalVar%AzError + LocalVarOutData(22) = LocalVar%GenTqAz + LocalVarOutData(23) = LocalVar%AzBuffer(1) + LocalVarOutData(24) = LocalVar%NumBl + LocalVarOutData(25) = LocalVar%FA_Acc + LocalVarOutData(26) = LocalVar%NacIMU_FA_Acc + LocalVarOutData(27) = LocalVar%FA_AccHPF + LocalVarOutData(28) = LocalVar%FA_AccHPFI + LocalVarOutData(29) = LocalVar%FA_PitCom(1) + LocalVarOutData(30) = LocalVar%VS_RefSpd + LocalVarOutData(31) = LocalVar%VS_RefSpd_TSR + LocalVarOutData(32) = LocalVar%VS_RefSpd_TRA + LocalVarOutData(33) = LocalVar%VS_RefSpd_RL + LocalVarOutData(34) = LocalVar%PC_RefSpd + LocalVarOutData(35) = LocalVar%PC_RefSpd_SS + LocalVarOutData(36) = LocalVar%PC_RefSpd_PRC + LocalVarOutData(37) = LocalVar%RotSpeedF + LocalVarOutData(38) = LocalVar%GenSpeedF + LocalVarOutData(39) = LocalVar%GenTq + LocalVarOutData(40) = LocalVar%GenTqMeas + LocalVarOutData(41) = LocalVar%GenArTq + LocalVarOutData(42) = LocalVar%GenBrTq + LocalVarOutData(43) = LocalVar%IPC_PitComF(1) + LocalVarOutData(44) = LocalVar%PC_KP + LocalVarOutData(45) = LocalVar%PC_KI + LocalVarOutData(46) = LocalVar%PC_KD + LocalVarOutData(47) = LocalVar%PC_TF + LocalVarOutData(48) = LocalVar%PC_MaxPit + LocalVarOutData(49) = LocalVar%PC_MinPit + LocalVarOutData(50) = LocalVar%PC_PitComT + LocalVarOutData(51) = LocalVar%PC_PitComT_Last + LocalVarOutData(52) = LocalVar%PC_PitComTF + LocalVarOutData(53) = LocalVar%PC_PitComT_IPC(1) + LocalVarOutData(54) = LocalVar%PC_PwrErr + LocalVarOutData(55) = LocalVar%PC_SpdErr + LocalVarOutData(56) = LocalVar%IPC_AxisTilt_1P + LocalVarOutData(57) = LocalVar%IPC_AxisYaw_1P + LocalVarOutData(58) = LocalVar%IPC_AxisTilt_2P + LocalVarOutData(59) = LocalVar%IPC_AxisYaw_2P + LocalVarOutData(60) = LocalVar%axisTilt_1P + LocalVarOutData(61) = LocalVar%axisYaw_1P + LocalVarOutData(62) = LocalVar%axisYawF_1P + LocalVarOutData(63) = LocalVar%axisTilt_2P + LocalVarOutData(64) = LocalVar%axisYaw_2P + LocalVarOutData(65) = LocalVar%axisYawF_2P + LocalVarOutData(66) = LocalVar%IPC_KI(1) + LocalVarOutData(67) = LocalVar%IPC_KP(1) + LocalVarOutData(68) = LocalVar%IPC_IntSat + LocalVarOutData(69) = LocalVar%PC_State + LocalVarOutData(70) = LocalVar%PitCom(1) + LocalVarOutData(71) = LocalVar%PitComAct(1) + LocalVarOutData(72) = LocalVar%SS_DelOmegaF + LocalVarOutData(73) = LocalVar%TestType + LocalVarOutData(74) = LocalVar%Kp_Float + LocalVarOutData(75) = LocalVar%VS_MaxTq + LocalVarOutData(76) = LocalVar%VS_LastGenTrq + LocalVarOutData(77) = LocalVar%VS_LastGenPwr + LocalVarOutData(78) = LocalVar%VS_MechGenPwr + LocalVarOutData(79) = LocalVar%VS_SpdErrAr + LocalVarOutData(80) = LocalVar%VS_SpdErrBr + LocalVarOutData(81) = LocalVar%VS_SpdErr + LocalVarOutData(82) = LocalVar%VS_State + LocalVarOutData(83) = LocalVar%VS_Rgn3Pitch + LocalVarOutData(84) = LocalVar%WE_Vw + LocalVarOutData(85) = LocalVar%WE_Vw_F + LocalVarOutData(86) = LocalVar%WE_VwI + LocalVarOutData(87) = LocalVar%WE_VwIdot + LocalVarOutData(88) = LocalVar%WE_Op + LocalVarOutData(89) = LocalVar%WE_Op_Last + LocalVarOutData(90) = LocalVar%VS_LastGenTrqF + LocalVarOutData(91) = LocalVar%PRC_WSE_F + LocalVarOutData(92) = LocalVar%PRC_R_Speed + LocalVarOutData(93) = LocalVar%PRC_R_Torque + LocalVarOutData(94) = LocalVar%PRC_R_Pitch + LocalVarOutData(95) = LocalVar%PRC_R_Total + LocalVarOutData(96) = LocalVar%PRC_Min_Pitch + LocalVarOutData(97) = LocalVar%PS_Min_Pitch + LocalVarOutData(98) = LocalVar%OL_Index + LocalVarOutData(99) = LocalVar%Fl_PitCom + LocalVarOutData(100) = LocalVar%NACIMU_FA_AccF + LocalVarOutData(101) = LocalVar%FA_AccF + LocalVarOutData(102) = LocalVar%FA_Hist + LocalVarOutData(103) = LocalVar%TRA_LastRefSpd + LocalVarOutData(104) = LocalVar%VS_RefSpeed + LocalVarOutData(105) = LocalVar%PtfmTDX + LocalVarOutData(106) = LocalVar%PtfmTDY + LocalVarOutData(107) = LocalVar%PtfmTDZ + LocalVarOutData(108) = LocalVar%PtfmRDX + LocalVarOutData(109) = LocalVar%PtfmRDY + LocalVarOutData(110) = LocalVar%PtfmRDZ + LocalVarOutData(111) = LocalVar%PtfmTVX + LocalVarOutData(112) = LocalVar%PtfmTVY + LocalVarOutData(113) = LocalVar%PtfmTVZ + LocalVarOutData(114) = LocalVar%PtfmRVX + LocalVarOutData(115) = LocalVar%PtfmRVY + LocalVarOutData(116) = LocalVar%PtfmRVZ + LocalVarOutData(117) = LocalVar%PtfmTAX + LocalVarOutData(118) = LocalVar%PtfmTAY + LocalVarOutData(119) = LocalVar%PtfmTAZ + LocalVarOutData(120) = LocalVar%PtfmRAX + LocalVarOutData(121) = LocalVar%PtfmRAY + LocalVarOutData(122) = LocalVar%PtfmRAZ + LocalVarOutData(123) = LocalVar%CC_DesiredL(1) + LocalVarOutData(124) = LocalVar%CC_ActuatedL(1) + LocalVarOutData(125) = LocalVar%CC_ActuatedDL(1) + LocalVarOutData(126) = LocalVar%StC_Input(1) + LocalVarOutData(127) = LocalVar%Flp_Angle(1) + LocalVarOutData(128) = LocalVar%RootMyb_Last(1) + LocalVarOutData(129) = LocalVar%ACC_INFILE_SIZE + LocalVarOutData(130) = LocalVar%AWC_complexangle(1) + LocalVarOutData(131) = LocalVar%ZMQ_ID + LocalVarOutData(132) = LocalVar%ZMQ_YawOffset + LocalVarOutData(133) = LocalVar%ZMQ_TorqueOffset + LocalVarOutData(134) = LocalVar%ZMQ_PitOffset(1) + LocalVarOutData(135) = LocalVar%ZMQ_R_Speed + LocalVarOutData(136) = LocalVar%ZMQ_R_Torque + LocalVarOutData(137) = LocalVar%ZMQ_R_Pitch LocalVarOutStrings = [CHARACTER(15) :: 'iStatus', 'Time', 'DT', 'n_DT', 'Time_Last', & 'VS_GenPwr', 'VS_GenPwrF', 'GenSpeed', 'RotSpeed', 'NacHeading', & - 'NacVane', 'HorWindV', 'rootMOOP', 'rootMOOPF', 'BlPitch', & - 'BlPitchCMeas', 'Azimuth', 'OL_Azimuth', 'AzUnwrapped', 'AzError', & - 'GenTqAz', 'AzBuffer', 'NumBl', 'FA_Acc', 'NacIMU_FA_Acc', & - 'FA_AccHPF', 'FA_AccHPFI', 'FA_PitCom', 'VS_RefSpd', 'VS_RefSpd_TSR', & - 'VS_RefSpd_TRA', 'VS_RefSpd_RL', 'PC_RefSpd', 'PC_RefSpd_SS', 'PC_RefSpd_PRC', & - 'RotSpeedF', 'GenSpeedF', 'GenTq', 'GenTqMeas', 'GenArTq', & - 'GenBrTq', 'IPC_PitComF', 'PC_KP', 'PC_KI', 'PC_KD', & - 'PC_TF', 'PC_MaxPit', 'PC_MinPit', 'PC_PitComT', 'PC_PitComT_Last', & - 'PC_PitComTF', 'PC_PitComT_IPC', 'PC_PwrErr', 'PC_SpdErr', 'IPC_AxisTilt_1P', & - 'IPC_AxisYaw_1P', 'IPC_AxisTilt_2P', 'IPC_AxisYaw_2P', 'axisTilt_1P', 'axisYaw_1P', & - 'axisYawF_1P', 'axisTilt_2P', 'axisYaw_2P', 'axisYawF_2P', 'IPC_KI', & - 'IPC_KP', 'IPC_IntSat', 'PC_State', 'PitCom', 'PitComAct', & - 'SS_DelOmegaF', 'TestType', 'Kp_Float', 'VS_MaxTq', 'VS_LastGenTrq', & - 'VS_LastGenPwr', 'VS_MechGenPwr', 'VS_SpdErrAr', 'VS_SpdErrBr', 'VS_SpdErr', & - 'VS_State', 'VS_Rgn3Pitch', 'WE_Vw', 'WE_Vw_F', 'WE_VwI', & - 'WE_VwIdot', 'VS_LastGenTrqF', 'PRC_WSE_F', 'PRC_R_Speed', 'PRC_R_Torque', & - 'PRC_R_Pitch', 'PRC_R_Total', 'PRC_Min_Pitch', 'PS_Min_Pitch', 'OL_Index', & - 'Fl_PitCom', 'NACIMU_FA_AccF', 'FA_AccF', 'FA_Hist', 'TRA_LastRefSpd', & - 'VS_RefSpeed', 'PtfmTDX', 'PtfmTDY', 'PtfmTDZ', 'PtfmRDX', & - 'PtfmRDY', 'PtfmRDZ', 'PtfmTVX', 'PtfmTVY', 'PtfmTVZ', & - 'PtfmRVX', 'PtfmRVY', 'PtfmRVZ', 'PtfmTAX', 'PtfmTAY', & - 'PtfmTAZ', 'PtfmRAX', 'PtfmRAY', 'PtfmRAZ', 'CC_DesiredL', & - 'CC_ActuatedL', 'CC_ActuatedDL', 'StC_Input', 'Flp_Angle', 'RootMyb_Last', & - 'ACC_INFILE_SIZE', 'AWC_complexangle', 'ZMQ_ID', 'ZMQ_YawOffset', 'ZMQ_TorqueOffset', & - 'ZMQ_PitOffset', 'ZMQ_R_Speed', 'ZMQ_R_Torque', 'ZMQ_R_Pitch'] + 'NacVane', 'HorWindV', 'HorWindV_F', 'rootMOOP', 'rootMOOPF', & + 'BlPitch', 'BlPitchCMeas', 'Azimuth', 'OL_Azimuth', 'AzUnwrapped', & + 'AzError', 'GenTqAz', 'AzBuffer', 'NumBl', 'FA_Acc', & + 'NacIMU_FA_Acc', 'FA_AccHPF', 'FA_AccHPFI', 'FA_PitCom', 'VS_RefSpd', & + 'VS_RefSpd_TSR', 'VS_RefSpd_TRA', 'VS_RefSpd_RL', 'PC_RefSpd', 'PC_RefSpd_SS', & + 'PC_RefSpd_PRC', 'RotSpeedF', 'GenSpeedF', 'GenTq', 'GenTqMeas', & + 'GenArTq', 'GenBrTq', 'IPC_PitComF', 'PC_KP', 'PC_KI', & + 'PC_KD', 'PC_TF', 'PC_MaxPit', 'PC_MinPit', 'PC_PitComT', & + 'PC_PitComT_Last', 'PC_PitComTF', 'PC_PitComT_IPC', 'PC_PwrErr', 'PC_SpdErr', & + 'IPC_AxisTilt_1P', 'IPC_AxisYaw_1P', 'IPC_AxisTilt_2P', 'IPC_AxisYaw_2P', 'axisTilt_1P', & + 'axisYaw_1P', 'axisYawF_1P', 'axisTilt_2P', 'axisYaw_2P', 'axisYawF_2P', & + 'IPC_KI', 'IPC_KP', 'IPC_IntSat', 'PC_State', 'PitCom', & + 'PitComAct', 'SS_DelOmegaF', 'TestType', 'Kp_Float', 'VS_MaxTq', & + 'VS_LastGenTrq', 'VS_LastGenPwr', 'VS_MechGenPwr', 'VS_SpdErrAr', 'VS_SpdErrBr', & + 'VS_SpdErr', 'VS_State', 'VS_Rgn3Pitch', 'WE_Vw', 'WE_Vw_F', & + 'WE_VwI', 'WE_VwIdot', 'WE_Op', 'WE_Op_Last', 'VS_LastGenTrqF', & + 'PRC_WSE_F', 'PRC_R_Speed', 'PRC_R_Torque', 'PRC_R_Pitch', 'PRC_R_Total', & + 'PRC_Min_Pitch', 'PS_Min_Pitch', 'OL_Index', 'Fl_PitCom', 'NACIMU_FA_AccF', & + 'FA_AccF', 'FA_Hist', 'TRA_LastRefSpd', 'VS_RefSpeed', 'PtfmTDX', & + 'PtfmTDY', 'PtfmTDZ', 'PtfmRDX', 'PtfmRDY', 'PtfmRDZ', & + 'PtfmTVX', 'PtfmTVY', 'PtfmTVZ', 'PtfmRVX', 'PtfmRVY', & + 'PtfmRVZ', 'PtfmTAX', 'PtfmTAY', 'PtfmTAZ', 'PtfmRAX', & + 'PtfmRAY', 'PtfmRAZ', 'CC_DesiredL', 'CC_ActuatedL', 'CC_ActuatedDL', & + 'StC_Input', 'Flp_Angle', 'RootMyb_Last', 'ACC_INFILE_SIZE', 'AWC_complexangle', & + 'ZMQ_ID', 'ZMQ_YawOffset', 'ZMQ_TorqueOffset', 'ZMQ_PitOffset', 'ZMQ_R_Speed', & + 'ZMQ_R_Torque', 'ZMQ_R_Pitch'] ! Initialize debug file IF ((LocalVar%iStatus == 0) .OR. (LocalVar%iStatus == -9)) THEN ! .TRUE. if we're on the first call to the DLL IF (CntrPar%LoggingLevel > 0) THEN @@ -890,8 +900,8 @@ SUBROUTINE Debug(LocalVar, CntrPar, DebugVar, ErrVar, avrSWAP, RootName, size_av CALL GetNewUnit(UnDb2, ErrVar) OPEN(unit=UnDb2, FILE=TRIM(RootName)//'.RO.dbg2') WRITE(UnDb2, *) 'Generated on '//CurDate()//' at '//CurTime()//' using ROSCO-'//TRIM(rosco_version) - WRITE(UnDb2, '(135(a20,TR5:))') 'Time', LocalVarOutStrings - WRITE(UnDb2, '(135(a20,TR5:))') + WRITE(UnDb2, '(138(a20,TR5:))') 'Time', LocalVarOutStrings + WRITE(UnDb2, '(138(a20,TR5:))') END IF IF (CntrPar%LoggingLevel > 2) THEN @@ -954,7 +964,7 @@ SUBROUTINE Debug(LocalVar, CntrPar, DebugVar, ErrVar, avrSWAP, RootName, size_av END DO ! Write debug files - FmtDat = "(F20.5,TR5,134(ES20.5E2,TR5:))" ! The format of the debugging data + FmtDat = "(F20.5,TR5,137(ES20.5E2,TR5:))" ! The format of the debugging data IF ( MOD(LocalVar%n_DT, CntrPar%n_DT_Out) == 0) THEN IF(CntrPar%LoggingLevel > 0) THEN WRITE (UnDb, TRIM(FmtDat)) LocalVar%Time, DebugOutData diff --git a/rosco/controller/src/ROSCO_Types.f90 b/rosco/controller/src/ROSCO_Types.f90 index 16d4ada2..becd11cc 100644 --- a/rosco/controller/src/ROSCO_Types.f90 +++ b/rosco/controller/src/ROSCO_Types.f90 @@ -275,6 +275,7 @@ MODULE ROSCO_Types REAL(DbKi) :: NacHeading ! Nacelle heading of the turbine w.r.t. north [deg] REAL(DbKi) :: NacVane ! Nacelle vane angle [deg] REAL(DbKi) :: HorWindV ! Hub height wind speed m/s + REAL(DbKi) :: HorWindV_F ! Filtered hub height wind speed m/s REAL(DbKi) :: rootMOOP(3) ! Blade root bending moment [Nm] REAL(DbKi) :: rootMOOPF(3) ! Filtered Blade root bending moment [Nm] REAL(DbKi) :: BlPitch(3) ! Blade pitch [rad] @@ -349,6 +350,8 @@ MODULE ROSCO_Types REAL(DbKi) :: WE_Vw_F ! Filtered estimated wind speed [m/s] REAL(DbKi) :: WE_VwI ! Integrated wind speed quantity for estimation [m/s] REAL(DbKi) :: WE_VwIdot ! Differentiated integrated wind speed quantity for estimation [m/s] + INTEGER(IntKi) :: WE_Op ! WSE Operational state (0- not operating, 1-operating) + INTEGER(IntKi) :: WE_Op_Last ! WSE Operational state (0- not operating, 1-operating) REAL(DbKi) :: VS_LastGenTrqF ! Differentiated integrated wind speed quantity for estimation [m/s] REAL(DbKi) :: PRC_WSE_F ! Filtered wind speed estimate for power reference control REAL(DbKi) :: PRC_R_Speed ! Instantaneous PRC_R_Speed diff --git a/rosco/controller/src/ReadSetParameters.f90 b/rosco/controller/src/ReadSetParameters.f90 index cff32f3f..f0fb1dc9 100644 --- a/rosco/controller/src/ReadSetParameters.f90 +++ b/rosco/controller/src/ReadSetParameters.f90 @@ -217,6 +217,8 @@ SUBROUTINE SetParameters(avrSWAP, accINFILE, size_avcMSG, CntrPar, LocalVar, obj ! Wind speed estimator initialization LocalVar%WE_Vw = LocalVar%HorWindV LocalVar%WE_VwI = LocalVar%WE_Vw - CntrPar%WE_Gamma*LocalVar%RotSpeed + LocalVar%WE_Op = 1 + LocalVar%WE_Op_Last = 1 ! Setpoint Smoother initialization to zero LocalVar%SS_DelOmegaF = 0 From 302a6ba5ea7149f97ff24d7735ba447e2f1b2ebd Mon Sep 17 00:00:00 2001 From: dzalkind Date: Fri, 27 Sep 2024 16:04:47 -0600 Subject: [PATCH 183/224] Fix OL_BP_FiltFreq input writing --- rosco/toolbox/utilities.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/rosco/toolbox/utilities.py b/rosco/toolbox/utilities.py index 4f35c433..30224f49 100644 --- a/rosco/toolbox/utilities.py +++ b/rosco/toolbox/utilities.py @@ -254,7 +254,7 @@ def write_DISCON(turbine, controller, param_file='DISCON.IN', txt_filename='Cp_C file.write('!------- Open Loop Control -----------------------------------------------------\n') file.write('"{}" ! OL_Filename - Input file with open loop timeseries (absolute path or relative to this file)\n'.format(rosco_vt['OL_Filename'])) file.write('{:<12d} ! OL_BP_Mode - {}]\n'.format(int(rosco_vt['OL_BP_Mode']),input_descriptions['OL_BP_Mode'])) - file.write('{:<12f} ! OL_BP_FiltFreq - {}\n'.format(int(rosco_vt['OL_BP_FiltFreq']),input_descriptions['OL_BP_FiltFreq'])) + file.write('{:<12f} ! OL_BP_FiltFreq - {}\n'.format(float(rosco_vt['OL_BP_FiltFreq']),input_descriptions['OL_BP_FiltFreq'])) file.write('{0:<12d} ! Ind_Breakpoint - The column in OL_Filename that contains the breakpoint (time if OL_Mode = 1)\n'.format(int(rosco_vt['Ind_Breakpoint']))) file.write('{} ! Ind_BldPitch - The columns in OL_Filename that contains the blade pitch (1,2,3) inputs in rad [array]\n'.format(' '.join([f'{int(ipb):3d}' for ipb in rosco_vt['Ind_BldPitch']]))) file.write('{0:<12d} ! Ind_GenTq - The column in OL_Filename that contains the generator torque in Nm\n'.format(int(rosco_vt['Ind_GenTq']))) From 0c0e4231e551a176742cd51e46c5534c9762b18b Mon Sep 17 00:00:00 2001 From: dzalkind Date: Fri, 27 Sep 2024 16:05:13 -0600 Subject: [PATCH 184/224] Check breakpoints of open loop control against maxima --- rosco/toolbox/controller.py | 33 ++++++++++++++++++++------------- 1 file changed, 20 insertions(+), 13 deletions(-) diff --git a/rosco/toolbox/controller.py b/rosco/toolbox/controller.py index 1b560268..a81e8018 100644 --- a/rosco/toolbox/controller.py +++ b/rosco/toolbox/controller.py @@ -800,21 +800,28 @@ def interp_series(self,control,breakpoints,values,method='sigma'): # Check if control in allowed controls, cable_control_* is in cable_control if not any([ac in control for ac in self.allowed_controls]): raise Exception(f'Open loop control of {control} is not allowed') + + # Check that breakpoints are valid + if self.breakpoint == 'wind_speed': + if max(breakpoints) > self.u_max: + raise Exception(f'The maximum desired wind speed breakpoint ({max(breakpoints)}) is greater than u_max ({self.u_max})') + elif self.breakpoint == 'time': + if max(breakpoints) > self.t_max: + raise Exception(f'The maximum desired wind speed breakpoint ({max(breakpoints)}) is greater than u_max ({self.t_max})') + + # Finally interpolate + if method == 'sigma': + self.ol_series[control] = multi_sigma(self.ol_series[self.breakpoint],breakpoints,values) + + elif method == 'linear': + self.ol_series[control] = np.interp(self.ol_series[self.breakpoint],breakpoints,values,left=values[0],right=values[-1]) - else: - # Finally interpolate - if method == 'sigma': - self.ol_series[control] = multi_sigma(self.ol_series[self.breakpoint],breakpoints,values) - - elif method == 'linear': - self.ol_series[control] = np.interp(self.ol_series[self.breakpoint],breakpoints,values,left=values[0],right=values[-1]) - - elif method == 'cubic': - interp_fcn = interpolate.Akima1DInterpolator(breakpoints,values,method='akima',extrapolate=True) #,kind='cubic',fill_value=values[-1],bounds_error=False) - self.ol_series[control] = interp_fcn(self.ol_series[self.breakpoint]) + elif method == 'cubic': + interp_fcn = interpolate.Akima1DInterpolator(breakpoints,values,method='akima',extrapolate=True) #,kind='cubic',fill_value=values[-1],bounds_error=False) + self.ol_series[control] = interp_fcn(self.ol_series[self.breakpoint]) - else: - raise Exception(f'Open loop interpolation method {method} not supported') + else: + raise Exception(f'Open loop interpolation method {method} not supported') if control == 'nacelle_yaw': self.compute_yaw_rate() From f249520e8d72f22320d1974869c181160c8eb38a Mon Sep 17 00:00:00 2001 From: dzalkind Date: Fri, 27 Sep 2024 16:05:27 -0600 Subject: [PATCH 185/224] Account for rating command in setpoint smoother --- rosco/controller/src/ControllerBlocks.f90 | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/rosco/controller/src/ControllerBlocks.f90 b/rosco/controller/src/ControllerBlocks.f90 index 8a95a1cb..fdf80a9c 100644 --- a/rosco/controller/src/ControllerBlocks.f90 +++ b/rosco/controller/src/ControllerBlocks.f90 @@ -449,11 +449,13 @@ SUBROUTINE SetpointSmoother(LocalVar, CntrPar, objInst) TYPE(ObjectInstances), INTENT(INOUT) :: objInst ! Allocate Variables REAL(DbKi) :: DelOmega ! Reference generator speed shift, rad/s. + REAL(DbKi) :: R_Total ! Total power rating command ! ------ Setpoint Smoothing ------ IF ( CntrPar%SS_Mode == 1) THEN ! Find setpoint shift amount - DelOmega = ((LocalVar%PC_PitComT - LocalVar%PC_MinPit)/0.524) * CntrPar%SS_VSGain - ((CntrPar%VS_RtPwr - LocalVar%VS_LastGenPwr))/CntrPar%VS_RtPwr * CntrPar%SS_PCGain ! Normalize to 30 degrees for now + R_Total = LocalVar%PRC_R_Speed * LocalVar%PRC_R_Torque * LocalVar%PRC_R_Pitch + DelOmega = ((LocalVar%PC_PitComT - LocalVar%PC_MinPit)/0.524) * CntrPar%SS_VSGain - ((CntrPar%VS_RtPwr * R_Total - LocalVar%VS_LastGenPwr))/CntrPar%VS_RtPwr * CntrPar%SS_PCGain ! Normalize to 30 degrees for now DelOmega = DelOmega * CntrPar%PC_RefSpd ! Filter LocalVar%SS_DelOmegaF = LPFilter(DelOmega, LocalVar%DT, CntrPar%F_SSCornerFreq, LocalVar%FP, LocalVar%iStatus, LocalVar%restart, objInst%instLPF) From 90ccdd88594efbf36d5e201949b3f7ce645e882c Mon Sep 17 00:00:00 2001 From: dzalkind Date: Fri, 27 Sep 2024 16:05:41 -0600 Subject: [PATCH 186/224] Set up PRC demos and documentation --- Examples/29_power_control.py | 149 +++++++++++++++++++++++++---------- 1 file changed, 106 insertions(+), 43 deletions(-) diff --git a/Examples/29_power_control.py b/Examples/29_power_control.py index 230a4514..ef5ea89b 100644 --- a/Examples/29_power_control.py +++ b/Examples/29_power_control.py @@ -11,8 +11,8 @@ The power rating (``R``) is the controlled power relative to the rated power (or available power below rated). For example R = 0.9, will produce 90% of the rated power (or available power below rated). -* Speed (``R_Speed``) will change the rated speed, or the speed relative to the optimal tip speed ratio (below rated). -* Torque (``R_Torque``): will change the rated torque. In constant power operation (`VS_ConstPower` of 1), the torque is non-constant, but the rated power used to calcualte the torque is adapted accordingly. +* Speed (``R_Speed``) will change the rated speed, or the speed setpoint relative to the optimal tip speed ratio (below rated). +* Torque (``R_Torque``): will change the rated torque. In constant power operation (`VS_ConstPower` of 1), the torque is non-constant, but the rated power used to calcualte the torque demand is adapted accordingly. * Pitch (``R_Pitch``): will change the minimum pitch angle of the turbine. When using peak shaving, the min pitch is the maximum of the minimum pitch for peak shaving (``PS_Min_Pitch``) and the minimum pitch for power control (``PRC_Min_Pitch``). The ROSCO toolbox can generate a lookup table from ``R_Pitch`` to ``PRC_Min_Pitch`` using the Cp surface. The three methods are compared in the following figure: @@ -25,13 +25,42 @@ #. Open-loop control inputs with time or wind speed breakpoints. Two applications will be shown in the example below. #. The ZeroMQ interface. A simple example is provided in ``17b_zeromq_multi_openfast.py``. -This example shows users how to set up +This example shows users how to set up open loop control inputs for -#. A constant input with R_Speed of 0.85. -#. A soft start up routine that slowly ramps the rating from 0 to 1 over 60 seconds. +#. A start up routine that ramps the turbine rating using R_Torque in steps over 400 seconds. #. A soft cut-out routine for high wind speeds. +#. Active wake control for above rated operation, using a sinusoidal input for R_speed. +Start Up Demo +`````````````` + +.. image:: ../images/29_StartUp.png + +The turbine is started in a parked configuration with the blades pitched to 90 degrees. +R_Torque is increased from 0 to 0.2, then from 0.2 to 1.0, simulating a startup routine. +The torque, because it is saturated at the max torque, which is scaled by ``R_Torque`` follows the trajectory of ``PRC_R_Torque``. +``PRC_R_Torque`` is the variable name inside ROSCO and the ``.dbg2`` file. +The blade pitch controller is active throughout the simulation, regulating the generator to the rated speed as usual. + + +Soft Cut-out Demo +````````````````` +.. image:: ../images/29_Soft_Cutout.png + +The turbine starts in above-rated operation and a ramp wind input goes well beyond the normal cut-out wind speed of 25 m/s. +In this demonstration, we use both R_Speed and R_Torque to ramp the turbine rating from 1.0 at 20 m/s to 0.5 at 30 m/s and 0.0 at 40 m/s. +The signals ``PRC_R_Speed`` and ``PRC_R_Torque`` ramp towards 0 following the R versus wind speed table. +Both GenTq and GenSpeed drop to 0 following the reference signals and the power follows. + + +Active Wake Control Demo +````````````````````````` + +.. image:: ../images/29_AWC.png + +In active wake control, the goal is to change the rotor thrust through low frequency changes to the blade pitch. +Since the blade pitch must be used to control the rotor speed in above rated operation, we can insteady vary the generator speed reference (via R_Speed) to create similar blade pitch variations. ''' @@ -58,10 +87,10 @@ def main(): + FULL_TEST = False + # Input yaml and output directory parameter_filename = os.path.join(this_dir,'Tune_Cases/IEA15MW.yaml') - run_dir = os.path.join(example_out_dir,'29_PRC_Test/14_AWC_Torque') - os.makedirs(run_dir,exist_ok=True) # Set DISCON input dynamically through yaml/dict @@ -73,39 +102,90 @@ def main(): controller_params['DISCON']['PRC_R_Torque'] = 1.0 controller_params['DISCON']['PRC_R_Speed'] = 1.0 controller_params['DISCON']['PRC_R_Pitch'] = 1.0 - controller_params['DISCON']['OL_BP_FitFreq'] = 2 * np.pi / 30 - + controller_params['DISCON']['OL_BP_FiltFreq'] = 2 * np.pi / 30 + + # simulation set up + r = run_FAST_ROSCO() + r.tuning_yaml = parameter_filename + r.case_inputs = {} + + sim_config = 1 + + # 1. Soft start up + if sim_config == 1: + if FULL_TEST: + t_max = 500 + else: # Shorter for ROSCO CI + t_max = 100 - # Soft start up - if False: - olc = ROSCO_controller.OpenLoopControl(t_max=100) + run_dir = os.path.join(example_out_dir,'29_PRC_Demo/1_Soft_Start') + olc = ROSCO_controller.OpenLoopControl(t_max=t_max) olc.interp_series( - 'R_speed', - [50,70], - [1,1.1] , + 'R_torque', + [0,100,200,300,400], + [0,0.0,0.2,0.2,1] , 'sigma' ) + + # Wind case + r.wind_case_fcn = cl.power_curve + r.wind_case_opts = { + 'U': [14], # from 10 to 15 m/s + 'TMax': t_max, + } + r.case_inputs[('ElastoDyn','BlPitch1')] = {'vals': [90.], 'group': 0} + r.case_inputs[('ElastoDyn','BlPitch2')] = {'vals': [90.], 'group': 0} + r.case_inputs[('ElastoDyn','BlPitch3')] = {'vals': [90.], 'group': 0} + r.case_inputs[('ElastoDyn','RotSpeed')] = {'vals': [0.], 'group': 0} + + [("ElastoDyn","BlPitch1")] - # Soft cut out - if False: + # 2. Soft cut out + if sim_config == 2: + run_dir = os.path.join(example_out_dir,'29_PRC_Demo/2_Use_Torque') olc = ROSCO_controller.OpenLoopControl( breakpoint='wind_speed', u_min = 20, - u_max = 30 + u_max = 40 ) olc.interp_series( 'R_speed', - [20,30], - [1,0.5] , - 'cubic' + [20,30,40], + [1,0.707,0.0] , ) + olc.interp_series( + 'R_torque', + [20,30,40], + [1,0.707,0.0] , + ) + r.wind_case_fcn = cl.ramp + r.wind_case_opts = { + 'U_start': 20, # from 10 to 15 m/s + 'U_end': 50, + 't_start': 500, + 't_end': 2500, + } + + r.case_inputs[('ElastoDyn','BlPitch1')] = {'vals': [19.], 'group': 0} + r.case_inputs[('ElastoDyn','BlPitch2')] = {'vals': [19.], 'group': 0} + r.case_inputs[('ElastoDyn','BlPitch3')] = {'vals': [19.], 'group': 0} + r.case_inputs[('ElastoDyn','RotSpeed')] = {'vals': [7.], 'group': 0} + + controller_params['DISCON']['OL_BP_FiltFreq'] = 1/100 + controller_params['DISCON']['VS_MinOMSpd'] = 0 # required to force low reference speed # AWC above rated via R_Speed/Torque - if True: - controller_params['OL_Mode'] = 1 + if sim_config == 3: + run_dir = os.path.join(example_out_dir,'29_PRC_Demo/3_AWC_Above_Rated') + t_max = 600 + r.wind_case_fcn = cl.power_curve + r.wind_case_opts = { + 'U': [14], # from 10 to 15 m/s + 'TMax': t_max, + } olc = ROSCO_controller.OpenLoopControl(t_max=600) olc.sine_timeseries( - 'R_torque', # could use R_speed or R_torque + 'R_speed', # could use R_speed or R_torque 0.05, # amplitude, fraction of rated power 100, # period, sec 1, # offset, (-) @@ -114,34 +194,17 @@ def main(): fig,ax = olc.plot_series() fig.savefig(os.path.join(example_out_dir,'29_OL_Inputs.png')) - # Write open loop input, get OL indices - ol_filename = os.path.join(example_out_dir,'29_OL_Input.dat') + os.makedirs(run_dir,exist_ok=True) + ol_filename = os.path.join(run_dir,'29_OL_Input.dat') ol_dict = olc.write_input(ol_filename) controller_params['open_loop'] = ol_dict controller_params['OL_Mode'] = 1 - - # simulation set up - r = run_FAST_ROSCO() - r.tuning_yaml = parameter_filename - - # Wind case - # A few different cases highlight TRA - r.wind_case_fcn = cl.power_curve - r.wind_case_opts = { - 'U': [14], # from 10 to 15 m/s - 'TMax': 600, - } - - r.controller_params = controller_params r.save_dir = run_dir r.rosco_dll = '/Users/dzalkind/Tools/ROSCO-PRC/rosco/controller/build/libdiscon.dylib' - # r.rosco_dir = rosco_dir - # r.case_inputs = {} - # r.n_cores = 2 r.run_FAST() From 26fe47ca9ba5ac64c568612f3df63174df5373ff Mon Sep 17 00:00:00 2001 From: dzalkind Date: Fri, 27 Sep 2024 16:06:01 -0600 Subject: [PATCH 187/224] Elaborate old PRC documentation --- Examples/27_soft_cut_out.py | 14 ++++++++------ 1 file changed, 8 insertions(+), 6 deletions(-) diff --git a/Examples/27_soft_cut_out.py b/Examples/27_soft_cut_out.py index d6164234..4f9b34bc 100644 --- a/Examples/27_soft_cut_out.py +++ b/Examples/27_soft_cut_out.py @@ -1,9 +1,11 @@ """ -27_power_ref_control --------------------- -Run openfast with ROSCO and cable control -Demonstrate a simulation with a generator reference speed that changes with estimated wind speed -Set reference rotor speed as a function of wind speed (estimate in ROSCO) +27_soft_cut_out +--------------- +Set up a control input to do a soft cut-out of a wind turbine at high wind speeds. +This example uses the first power reference control implementation (PRC_Mode of 1), where the user specifies the speed setpoint versus wind speed. +We can use this to track specific rotor speeds based on the wind speed, or de-rate/power boost using by changing the speed. +With PRC_Mode of 2, we can do this but also change the power rating with pitch and torque. + """ import os @@ -58,7 +60,7 @@ def main(): r = run_FAST_ROSCO() r.tuning_yaml = parameter_filename - r.wind_case_fcn = cl.ramp # single step wind input + r.wind_case_fcn = cl.ramp # ramp wind input if FULL_TEST: # Full test From 82413fcee1b699e9df0afaf7f82875482b2f0e69 Mon Sep 17 00:00:00 2001 From: dzalkind Date: Fri, 27 Sep 2024 16:06:12 -0600 Subject: [PATCH 188/224] Update some example documentation --- Examples/05_openfast_sim.py | 2 +- Examples/06_peak_shaving.py | 7 +++++-- 2 files changed, 6 insertions(+), 3 deletions(-) diff --git a/Examples/05_openfast_sim.py b/Examples/05_openfast_sim.py index c552f6d7..222dc375 100644 --- a/Examples/05_openfast_sim.py +++ b/Examples/05_openfast_sim.py @@ -10,7 +10,7 @@ Note -* you will need to have a compiled controller in ROSCO/build/ +* you will need to have a compiled controller in ROSCO/rosco/controller/build """ # Python Modules diff --git a/Examples/06_peak_shaving.py b/Examples/06_peak_shaving.py index 2edfb3e5..a4f4f375 100644 --- a/Examples/06_peak_shaving.py +++ b/Examples/06_peak_shaving.py @@ -1,6 +1,6 @@ """ -06_peak_shavings ----------------- +06_peak_shaving +--------------- Load saved turbine, tune controller, plot minimum pitch schedule In this example: @@ -8,6 +8,9 @@ * Load a turbine from openfast * Tune a controller * Plot minimum pitch schedule + +.. image:: ../images/06_MinPitch.png + """ # Python modules From d1021ffe333105a775ee7c9c40cdb9471dfe77c5 Mon Sep 17 00:00:00 2001 From: dzalkind Date: Fri, 27 Sep 2024 16:06:43 -0600 Subject: [PATCH 189/224] Update example list in docs --- docs/source/examples.rst | 5 +++-- 1 file changed, 3 insertions(+), 2 deletions(-) diff --git a/docs/source/examples.rst b/docs/source/examples.rst index ce1b73f1..fdf39779 100644 --- a/docs/source/examples.rst +++ b/docs/source/examples.rst @@ -122,12 +122,13 @@ A complete list of examples is given below: .. automodule:: 17b_zeromq_multi_openfast .. automodule:: 18_pitch_offsets .. automodule:: 19_update_discon_version -.. automodule:: 20_active_wake_control +.. .. automodule:: 20_active_wake_control .. automodule:: 21_optional_inputs .. automodule:: 22_cable_control .. automodule:: 23_structural_control .. automodule:: 24_floating_feedback .. automodule:: 25_rotor_position_control .. automodule:: 26_marine_hydro -.. automodule:: 27_power_ref_control +.. automodule:: 27_soft_cut_out .. automodule:: 28_tower_resonance +.. automodule:: 29_power_control From b450185532f7a024671aaeb699520703633ac417 Mon Sep 17 00:00:00 2001 From: dzalkind Date: Fri, 27 Sep 2024 16:13:28 -0600 Subject: [PATCH 190/224] Fix old open loop nomenclature --- Examples/14_open_loop_control.py | 10 +++++----- 1 file changed, 5 insertions(+), 5 deletions(-) diff --git a/Examples/14_open_loop_control.py b/Examples/14_open_loop_control.py index 2b895940..91c98378 100644 --- a/Examples/14_open_loop_control.py +++ b/Examples/14_open_loop_control.py @@ -46,7 +46,7 @@ def main(): # Set up open loop input olc = ROSCO_controller.OpenLoopControl(t_max=20) - olc.interp_timeseries( + olc.interp_series( 'blade_pitch', [0,20], [0,0.0873] , @@ -59,7 +59,7 @@ def main(): olc.sine_timeseries('nacelle_yaw', 0.0524, 60) # Plot open loop timeseries - fig,ax = olc.plot_timeseries() + fig,ax = olc.plot_series() if False: plt.show() else: @@ -144,9 +144,9 @@ def main(): valid_ind = tt > 2 # first few timesteps can differ, depending on OpenFAST solve config # Compute errors - nacelle_yaw_diff = fo['NacYaw'][valid_ind] - np.degrees(np.interp(tt[valid_ind],olc.ol_timeseries['time'],olc.ol_timeseries['nacelle_yaw'])) - bld_pitch_diff = fo['BldPitch1'][valid_ind] - np.degrees(np.interp(tt[valid_ind],olc.ol_timeseries['time'],olc.ol_timeseries['blade_pitch'])) - gen_tq_diff = fo['GenTq'][valid_ind] - np.interp(tt[valid_ind],olc.ol_timeseries['time'],olc.ol_timeseries['generator_torque'])/1e3 + nacelle_yaw_diff = fo['NacYaw'][valid_ind] - np.degrees(np.interp(tt[valid_ind],olc.ol_series['time'],olc.ol_series['nacelle_yaw'])) + bld_pitch_diff = fo['BldPitch1'][valid_ind] - np.degrees(np.interp(tt[valid_ind],olc.ol_series['time'],olc.ol_series['blade_pitch'])) + gen_tq_diff = fo['GenTq'][valid_ind] - np.interp(tt[valid_ind],olc.ol_series['time'],olc.ol_series['generator_torque'])/1e3 # Check diff timeseries np.testing.assert_allclose(nacelle_yaw_diff, 0, atol = 1e-1) # yaw has dynamics and integration error, tolerance higher From 78829138014a67e84d362f7bb0bc21d80a3be48a Mon Sep 17 00:00:00 2001 From: dzalkind Date: Mon, 30 Sep 2024 10:32:30 -0600 Subject: [PATCH 191/224] Fix error message in ol control --- rosco/toolbox/controller.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/rosco/toolbox/controller.py b/rosco/toolbox/controller.py index a81e8018..3f9f9c03 100644 --- a/rosco/toolbox/controller.py +++ b/rosco/toolbox/controller.py @@ -807,7 +807,7 @@ def interp_series(self,control,breakpoints,values,method='sigma'): raise Exception(f'The maximum desired wind speed breakpoint ({max(breakpoints)}) is greater than u_max ({self.u_max})') elif self.breakpoint == 'time': if max(breakpoints) > self.t_max: - raise Exception(f'The maximum desired wind speed breakpoint ({max(breakpoints)}) is greater than u_max ({self.t_max})') + raise Exception(f'The maximum desired time breakpoint ({max(breakpoints)}) is greater than t_max ({self.t_max})') # Finally interpolate if method == 'sigma': From ee2b46ac361008799fb9996ea099097d375e6a79 Mon Sep 17 00:00:00 2001 From: dzalkind Date: Mon, 30 Sep 2024 10:33:07 -0600 Subject: [PATCH 192/224] Configure PRC example for CI --- Examples/29_power_control.py | 35 +++++++++++++++++++++++++---------- 1 file changed, 25 insertions(+), 10 deletions(-) diff --git a/Examples/29_power_control.py b/Examples/29_power_control.py index ef5ea89b..b37c632e 100644 --- a/Examples/29_power_control.py +++ b/Examples/29_power_control.py @@ -67,9 +67,6 @@ import os from rosco.toolbox.ofTools.case_gen.run_FAST import run_FAST_ROSCO from rosco.toolbox.ofTools.case_gen import CaseLibrary as cl -#from rosco.toolbox.ofTools.fast_io import output_processing -from rosco.toolbox.ofTools.fast_io.FAST_reader import InputReader_OpenFAST -from rosco.toolbox.inputs.validation import load_rosco_yaml from rosco.toolbox import controller as ROSCO_controller @@ -87,7 +84,7 @@ def main(): - FULL_TEST = False + FULL_TEST = False # FULL_TEST for local testing, otherwise shorter for CI # Input yaml and output directory parameter_filename = os.path.join(this_dir,'Tune_Cases/IEA15MW.yaml') @@ -109,6 +106,15 @@ def main(): r.tuning_yaml = parameter_filename r.case_inputs = {} + # Disable floating DOFs for clarity + r.case_inputs[('ElastoDyn','PtfmSgDOF')] = {'vals': ['False'], 'group': 0} + r.case_inputs[('ElastoDyn','PtfmSwDOF')] = {'vals': ['False'], 'group': 0} + r.case_inputs[('ElastoDyn','PtfmHvDOF')] = {'vals': ['False'], 'group': 0} + r.case_inputs[('ElastoDyn','PtfmRDOF')] = {'vals': ['False'], 'group': 0} + r.case_inputs[('ElastoDyn','PtfmPDOF')] = {'vals': ['False'], 'group': 0} + r.case_inputs[('ElastoDyn','PtfmYDOF')] = {'vals': ['False'], 'group': 0} + + sim_config = 1 # 1. Soft start up @@ -120,12 +126,21 @@ def main(): run_dir = os.path.join(example_out_dir,'29_PRC_Demo/1_Soft_Start') olc = ROSCO_controller.OpenLoopControl(t_max=t_max) - olc.interp_series( - 'R_torque', - [0,100,200,300,400], - [0,0.0,0.2,0.2,1] , - 'sigma' - ) + + if FULL_TEST: + olc.interp_series( + 'R_torque', + [0,100,200,300,400], + [0,0.0,0.2,0.2,1] , + 'sigma' + ) + else: + olc.interp_series( + 'R_torque', + [0,100], + [0,1.0] , + 'sigma' + ) # Wind case r.wind_case_fcn = cl.power_curve From 8b304cffc804757cae5de32922f9c60585dd9c5f Mon Sep 17 00:00:00 2001 From: dzalkind Date: Mon, 30 Sep 2024 10:34:01 -0600 Subject: [PATCH 193/224] Add docs images --- docs/images/06_MinPitch.png | Bin 0 -> 29865 bytes docs/images/29_AWC.png | Bin 0 -> 91521 bytes docs/images/29_PRC_Methods.png | Bin 0 -> 76001 bytes docs/images/29_Soft_Cutout.png | Bin 0 -> 106575 bytes docs/images/29_StartUp.png | Bin 0 -> 101288 bytes 5 files changed, 0 insertions(+), 0 deletions(-) create mode 100644 docs/images/06_MinPitch.png create mode 100644 docs/images/29_AWC.png create mode 100644 docs/images/29_PRC_Methods.png create mode 100644 docs/images/29_Soft_Cutout.png create mode 100644 docs/images/29_StartUp.png diff --git a/docs/images/06_MinPitch.png b/docs/images/06_MinPitch.png new file mode 100644 index 0000000000000000000000000000000000000000..22bfce8ad0cebf04d8a3d6a6fbc63bd1280bc400 GIT binary patch literal 29865 zcmeEuWmHvd)a?Njqy;1-6#+rI8w?PXQc>yd?oNx45)ckZDgq)12+}PIA}vzV-EioJ zyEgAP?vFd}@B8aIhQ9iqvk!Ye&wAFHbFR5g=mS*+VggzM6beOrPf_j>3WXhrLSc5lMU)IGKqnKT#Ywl>xMmHZ^X1j$|fB>tu=%<#*;v2hVw4t}xtaG+j? zgoKn|K7SKFmP|AQ#SX7enqNZ6!^^|r*y-?UNYX>pC3w|IkRb5v^1E0M;ME`P?EnAb z{|5`!)Vhf6EEwF_(4C=xPeAb9yjV*w5_ZKjkUyxrTfskvb?tmT zon!5wsF;{0vbQW~r@5iB;o=D$WS=Ac&mi$Z6({fqefuV~>|WKI88WSvnwskAg3Pfvmu9UblI z?ft0Q)5+J@*VXMd3n7h(;=OwlKSC+w?%sV=>+4mXS0+Qet7>pw} zHg+D50*l(_?r!tYP!bLv$(xv%=V@tay{w@j)0PJo&Qv{d7owNncfJczY+B&W`kxSf zOK-RMH)pytZER6s`o`UGnp1FVfPO+?M*x28+xt|8w~Hni5uafdIEFQ;Ax{VYH3fz_%e^uPQ;( zgQq=7bZ%>*=PBA<@6n@2mc5@TzkdDNmMWc;BIzMu)5rDsN$y=`Ee##^_07kK0A383t36ZOMPEd+TRHm zEF|;u^W*ZtAJo$E2?>^^c0=am6chyu2~Q)y|afq^LXBGY@Dzph0kl$V#gHm3=gy@uEo zJvlkaGHH&SP4O7zzk2m*6O9S;wQCXW=7Ki;`6^|d!A$;^_v3Du!IQ~v+Ygs_qs&iF zj?sRqr+zYlR(*Mi{7nhMHhl^4+&b@WzamH+A2;mzW~E;2e|(_q#myt+IDV6YhQ{*4 zhYx?g$a<_Mb3FX;(rT#mi;Z5fd3#$%l#Df_-_}D4a<=DlSWX&xu#AowDNMgHp#^ zJz1XXlWbS6)C*a5)pKcoV;@Nwa5kG-Sg_hz8S)tE+>g`Hzqh;pb!cU_ zSHnP<_5NEv85x-@*r3^dg8(;a#>))QaqzWZ>v)A{Lm6e;mHzCqn4@8(TilH&0-e&k!<4(QNl9Mo zKdE^Suv>pLb_|%*uM_yT6h6{!Z|_j~_oO*;6nu*r5c?eqW-X zq%`}GkrBb))RrbYb`B3ODMvl~U5(G~yRm@N5eV{s;WYf;OV)hWYAjBUHr0w9#$<{e zCvK~MHI_$qt(?)I#=GR}pso4Ve7E^rN6PFAQW?Je%{hNUp@8z1l9V%L|aWrEslW(r97^oiYN@h^u-I6omZk5EsR zir`SG-P!NsgKfe0@87eDi0lLzgq;=*t*`~09L>HDW~`i^%D5XLAd=MnL<2TYxz=~T zZ7NFE-hFw%sP~2s zk4jL$Hgt9_THo3df-|dH=Kt%>)hx&`=n;pF>6R@08gDjXVc|Pid>kAtKYsiu_a|YH za8<$LyDHu*Cw1sjddk9LaYVRXwN@*5p5PLnzrTN$(^QlB9%jOPbGCh<6swI?_UMhh zUM!nR8=XUSwEf68s~+XA#y@#{@*QgTn=ajW{Hw(G^msSB>W^8tVEU;js^gt->m~LF z^^^}p?f#kCiX?@GhgUCqHAT=_Kw?&Y@ZgPA_lH-P#hpJ6R(TXGt#2Bc!djuFgZP_1 zW@aX)r(fCZQIoCcGi$POS{~rXN!T6rS&ND4OqCu&%@)+12sDY|7|#5T>p6dDk>=O; zIA3>=#srd@PdFTEg-H5)9?3%vbt6PfGQ%`eM1g^Wa9p#bkk$VgMlA|Ee7{TufU;*9tBwLT}kKJb)mKiDa7&PITcq68sq>e)zMotoJWox+DkBF7CE?2_GLHWjj`zayNoDQ*!lHD}$u_kJi>OCjULGK)9=(5AuZf z(L8>G|B#deao40_;3p3cytgytkfU94gOG}=eA4B0WTg3c{j!Te-aLrIjEJb*3I!g%}dC|C3BM9JdOM?g4epoxgqpSCN;dK zjE!kjBg|0NAy=t2cH^(|6>8NI^YDu4EgSc$6g)=HK)CNXs4%8`dyT=Q76XMw`7;9p z12zQDPDWF0=?2*vhb*W996D|OjdpfMJ^iBH{rL$eMh zkS;S_<~q<)qt9^g%BLbFX~Z0_6x8g{o+qR--QSqmTI!Gb`}gq`6Vbziy}hms1=1|# z#M_X3_79c{ydbO#Dh&V>!I??F6HHQla3gjV(+jYE zNq=79aOZP5v{GOdI!=5Cn56Go!Yd(h@FDj(%E`$oPp2$0f=*Nb@I?K7rb&1ML<(f$ zlp*`7l@G^IN7uKvYgQ%fMCh<&D%MyF9%bIIG?J~ZsevtDD23cjBI&XEQMbYwE!9-% zwxp<}WU@T)HUBbQ?fz_1SVyt<_M+<&k1p=~Se1@JRS%Uz%xlB6(k_3lr2I{AFrHqOyV=3kLO8v6Okp8k zze#9lXgHH>s)*gc2Ze^W`VW+9RA*Yz%{@J_|4M93%7y@jW!;NqyZm|LZrWzRc|1II zfQRwC2C9(d^_Dd9b??2vCC<-bBx@NeWr&#hdYNv(hZ!r0n9*K4-ssDX@u|4$wCpb5 zhS7I<8k(Df;n|7|8?fOdPHWe}Ush`mSHnt4Nl4705H9pZz^%xh9>qfDjubHaZR*u7 z-VKXW4oPWYsEk+G`tKEX_7H$${N`;5t_3Cwe=@bo9j_wiptiOa@?ap^z&{b{I0YkP zN6qeN7(B5~sjU%wI1)~8xpm?JCd(YmUt6tQ;(3~<+3*sd;!jEdU`CHl9ksn7z} zf7z*cbQN=-exVUGCxWfLCLj<4pfVZ`ipXpmj_mX|YiwE^_ltkqm@4 zUlCBwkJd;^`|OxPsQk^>OM+Y2faLn9#@kJ!yy`84HnlhWD6g3~4LAo}CDy&h0BCLD z_7{4x4R(f^CuPFKCcJrb5h>j_p5|HV`>xBo ztPYF!yF*qGh9V-UudlxlB$Fr`P>U4w_1#_3hK7c$TQ6`Iyt5z@swgo!MShp z-Je0@@>z5wJJ|_Z{b51y=G5An18iKrYh(RU|Hpf=M23JtTz<~ELRJto{dH0Oi?(nq z;AM(SmrOrv6xbtJ1!7olNF`aU`(U#oTW(f-B%L6gMqW%2eWPy~Q5G=O?P zJ^ezvRYuEig7VzCc2vx~uu<5joJh z{AW3=E)lfCuM-6=^j%r|8H5~0leJ5%&E`iHJU(P>9ec~;_4Re6R7S}hg!JqC zv@bdXXT^E+hrarFh=h$N>|DCBIL4yq6JmMc0|m~ z;-UOOYkf?!aTTYIJU>-WP!3J5Ik%QR8)=Mb6(yf(C8nPTK0empn{e>|=X)vet|;YX zjeW@l!tUb=@mK%7;oUY~2WGD=f?g&zBs(|)au#2qmX?%sQCUW?ZsOT{hWUaU`HU9y zn@(y8s~Rurccqc8=BlJTqK=}x(Wj1RG0}9+%sh!kW46YF_H%8wJbJl0KB@K!MLCdU zohdl|b~CB5QZhCau+i(AJLA11PZqR!rG}b!Vr~ADEc)A4`Fsl3zr($rw_)@1R)y+$=uxY@c3}oq(f+2z zfm6YpG$X(9IXLdWx3uM0Z0N)8O+E|F-FJL1c;uE#-7(xycH?MR=e6w zjrhnC)WPhbo$qYpaJn~}=p4ErSf4+C4sW`Y=C_l$v`(0WN6o7bczCL8%s<0@ zN4z{*~JnovCI3!K%0WbiP@3KMx7HKr3Wf zkC|w!*zAz(vD<~+B%`H$4dn`I&=gb=Rgb(e|HFviahym-{a0$I^!V}P%I0i9Z16zq z@G}5)0CbQUnX>82dyhQ!{ytLRM4*tat}6)(cP0wXeHINdSgB@?@gqqSSLj#MSYP<# zhuX5f)UbRjfdGMt}elgn(|RdMnCm?1HG5{MAwUiKGr3kFK<=zyuQ zrKX-bWQlvM(yvu-k^odfkP5w&=bP+Q@88>dAgFmwyrQNNw!Q@LeJ(@m$D6TlQoTqoQO_#QYAnS}^M|v9Sn24~>YJ0U}g4zs@ZG8g*J{>^b`B zVMaLsJJ0Q24ZS5ex{3Bj9}G&1)0p2bV0&T|ARtnx@r|$~ zIS<}r2QF<(@d^va;Zv|ZD7Dq9zZ?VmZ7yumr z0Etpw0>}aTq8$edg6JQn7|NP&xhWcQMf&&Oz38s9xA^_~81AvbitDP5^Icbgn91YMcISY6gDe=PpW|J+8kwco*U+`IBw@a zeS9N7YOAhjMe(-wP!E|962?q&87HHdnC07 zHBS7($cQAZd~U{IF!j1!-~4je1_`5lD%>=30hx?un6<_OI#P!u!)fos0eYau$gH=% zsI06k;0<}ext@UQ7J$YSRBsS~U{$;7k{Y1bndUS3BUH$CfN#WoE-9MVmz0M!W3AWg zvUov=X^NK)#B~+-57un5$+h+YADcf#_doTT-D6WnwW*2>35)*J&aoRR1uBRtf2Zv7 z8ba>lQr<;abW>B)_!M3)u5i%j%q(>PoGrWiRJs9?Fr4`Qs{ik>uk`1~Ig_-{vw-H) z%lIZhGSOSVF+KzP_~?TiKE$2E?&=7yPc6Xr=!ArMg5+F{0@X5=XlD74u&`@zTI+Al zot|pYUgJZSwhjH(+Tt(oP-5u;3gvc<05fr1!V!JCc$)Bb7_<(aRv=a&T37jZ-UDVR zlBJsRThC)e{u%apnSui|3?kpw$`G1X*c#-EA3(7XD&aBaCyE03Hv?`QV8Sc-HyRcJ1QZfm z5jt3{_AW0F-5cIqy#q)w3!a_D*-n!v>85wWHi)u942MZTW4h%WV@mBayN6#rv zdc}=uReTs9ALksUvxtM_f~dOx${Y}qdaF5-p=YGkJQHpWxZ!ix##sdHIMf}-gMRZU z_bE5BQjnYqmShwl`&teZUWG_wR7n!agpjJ<`lCcd!xsobT1Dw06j?+<-yI8(g(5zY zXpvemzc?MYwKkU4DSMg>ToPeNaLY}wa2)Dc;kl7%{s*D391pA9?LaU-KkB{o#kHAT zv+#<6-!>)4av5-l0jFLYag^?Nfix_&S$fy0U!ir7ic+cJCR5fQ@2;_%@Wn7s1*;v~f=r&6Q-Ddnzv~PKS z1@HE=aj~og_@80zzvsA+re9>T%5?Vv-GJ*n7YZjSZYHOX67%PYY}tDRQcm8bS_z*G z)k+fc;fXVp=|I5rT#M54t^Or`Y!(r7)%WNo1M%{5)>$8MqkO)c zC8%xS*P>rG*1VI;Io{HO@B)nv8tGd_X~^}8jHTXV9E?d{qbZzP&h2?_n4@W3KUp<= z`xukKjxy(WE23&)Jje_EIOj;i#x>F^S-0}TDE+pjOp`}}QpJb;JRTKi)cJZYXaCn< zfccqO-sd5!;0K)thbMJZ^#?nC|{sv4zu@T$7L< zPmcCOBi;S?K*H4B?0Bs>%irV(a0V3bmNeOb$V9TcKW-$ErkHhY5z~t&g+!t8u1P-5 z)H!za!@DOz5U9n@#YI$4i7n5vg!GrT5sKABQ>*P4*zZ583QSk-Jxazuouv2vOTc~8 zH{pt3=EV>5H2Ggsao>kdNAC=D(MCr{D>ts&bIXWFOca-G^vq_UzU9#V9@_0=8Bi;e z`;`g61xHOy%}+cuL@|EAO)B!4!553M&~w#Nwo?81%t$XcTGx6fsIeN; zIL4Co51(*nYHGD4hwfq5Vi61V1B5}en8oyf>SRUNb1HG+X6(i*uR0xWf|<>da)B1^ zvu$&Z&aj~HGCjZ*VUh@I$Gv0E+4*Lub!y=~n?Z}%e?Pn3kB+&c%l%o_rLHc}kuQs9dF3-TP;+;)SW)pUH6$**q+r zLb-m?h>7;lXzbL(7+?sxZ*)u9vydl~5KkL+*yyZNP8F)AIyJafifQd*M@jVZ zG|;7do?6Ses?TC`)>73pRCATWsnhOEo%gJkwyXYIOCW6@S#RER>>smz_KZb?1yG6> zhuT>_4&W2-nECEj{*7Qabkmx=``_#L-i?E}AxMy_Ldep*nG>d9i(Pi3UiU|aoflfvwxUeCO@S`u@WAPaC%8?7zF zU9q`TR>|dLa`qHj^K;w^UI#X_~W7Pqb|Qs>yiZ zERCm@*4R1pf`9k#$2%$`YuClYDj7qe%N+y7cwWk%6<*IU#R@Q&bq@PJw(UG%H04^D zt)+J_^&=+z~HIMr#z=vLjQ9b5CJ!C7K!T;siEjlDPh!cgy4JHgqV z_FL_)i!r_{P5l*%k4P3zAxY)weP1kc&K}6%+vOkF40aKpd^#`2NFb-Fqw!ymI5YSk z&e1fQ+c97LsTz88;`=Xy=PV06T{R&(I+i}#U|~r)&nsJgOlc{0QOcE4IQPs|p^FpT zh-vsff>8AFnxL;m*)de*Pz$}01Q=eo2Lq){Dm*dmr&?87_co`+g`i9=_nt%B(6xNJ04uZR)- z<<$#}s_K7l`3AdH_-l5FM$fGru|#DliSW{`b$v?vs-ezp)tHVvgyL@5=~FE2@E5}wC+6?nhp zq&0QZs%Tw3-{Iv;@u8uS&OYEWEpcCZhxnPBrd-;Dh$4R3q|HH+50@6r{bO&{?HALy ziJMi0!u{tiBx7!|$*uA??w~_2J{|d2IUR$X^B-SWGyi${?>sekkixEiA&Q=itNLv1 zIA`PJnNpn5yin6I6BKo`Ril1r3@$0!_l`bZK%fVggI1-2Mi41!1)e($YMRm{ZeoCyp4`3yjYGQdMYZO24I^J~1} zMb5(vTu^bj3~H018=p{Lf0NOB{wiVWGdSDXD-XYJoqiu2yf)Aowm!1tY_tFUDLT$4 zd3dFI(ZltHOT|BF$2rMygZh7!EO%_7yYEJp_#VV*gtn>4?Efgq2Z-sqJP-}u7>jut z&>qKGdU>}QwkxqB+J(dY_aze3M+M%)k6F@s z&1OiN>i>17>>g&aJ~y~9oLCj)(Y@=zXoanM@17BK6TbmW9XaUxqJy;Ei5N_vqY3?w z7~oxc?n%?rrhveDjseH48ih|3XZl>`vtyWhv^@MM|Dp@-$OjDip;NQrfi&M5hs7Re z4-unQT<-TYv6)b|anKx$%ZBiYiB-yEgoNIL+Mwq&25mTJ5Sah``9lM;8pv;T%cUTG zBkq9qx9{Y^wUzl%+;bxMOMaqsr6||W5R%2^XrrOo?`n6htP^?e-)hx(-*AU^lokD( z0t-`3s9-7Dr0e!~2bdBW6I176Z!XfzWY@^22iSVbTE-ybE7ll9?84pL)I`phe~VjQ z&bhJ&p98wksltb9Q${Z|RzKhGyi4|O@Y=PQDWj9(!gbC$XHDXHDYDm3i%NMau6i+} zK(wGyQ|k=N-;q~PFmQc>xeXu`3t^=6vi`{+80(6l4h{|`mzI*m<-H5VusC^q}RtA+YJ_s4kWf`AZSm+-!D37XzqQ~ zL3%l~qV~xXQ(zfVRqa^b0HYFfn8)27ucP}UDXJeIH=xW(t@AKwvK=AKqj(ojv|#i_ zU2^YJB5notqZu-(}~g`7=oxr?s7kb%`A74V6Yopa(;Il#@j;V$hczQ#U z^dv!~Osat6p?`t&kVMCPW8v@&e9peY%$!)i$`^iMCK;9rrY?XviVG5|l#B~SfUPV^y`UZEhGKEi z;kE&n zzK?zpldxBtD|+W#aBmGi#9*G!Hcs?iuW#&G{LMm$JP( zETk9jTHY_>ysz^7)itB-=8l=?X75|&*dO-8>DECKs$zbrrGn6ly3w1rU#AqwV<-Np z!pbB#uc`O6!+qHSD$9p5arDymtGbQO-|#X2V_O?HvzT@ym$LLfR2y5m=tAR9bKwvzj^_OKiiGJ_?T5ZT z)_4RNN9(fk|Lk}JxS+6ouxEEcg!1xVU1`4p%Owv?E1%+PtTmM7Chp%AV(<3hcmya; z(_Wv7UD*98f#76d1}1A?TJ(f_dv=RrjK|U0hD)LyGvsdXdn_K5CzrT|&YazZ26Qb` zN7efr=UtiiajFvsiW#?+sJ~U_B`=Lz@A;#C(4R}f6Y~4FKb7OdB99bm=V!vv*_Sah z62|1}2n^%!TU0Mql*w)Vow#gO=t{)pM;DH>p>T69^ug!%uM!ykmNw6orK z#BfGI4o9p3w_d)%V@zb5iocoq{H-U3_}R|d?QNgDd}U{L1W&a%{aGf_Pdy|xICZ-i zC{y-!_NQd-_`-YrT+$KhJOnXZ}X=yCVkOPp-mL56Kut3P;ukz2l0QHib29LfGPB6f9ngRH!@^x zgoNXOy3x9&<_?cx`pwJp0{Hi>84X%!&aNQ?l#|^*Eeu^3MIg~KYfqviG6|5M<6>Rl z!Z>zqDW$c9@uj=NvjT5l*b+WE z2rteEhH|lu^?1b;!s{&TLo#Pi{lc3q>{-OyZvh=qUVRdEn|7A9=7%6=lLFI8+A$NN zlfoc<`@XggdRiNS9>$5hPggB|sGS-T4eRHyGf6*4LNWOXXBG#%ay-@vPe#OZ^|{D&H{m3FW&Hya;?FF&B-8NofYN&4eK<8BLE@ zCv{%OT;jiNzIEbgvlJtB4+-9);aZCIt%Pqu*DNSF$fsNX%53LoOZ@=s9C?jy{LsH6 z%K*aNhw7cw`P74V@p(prr&{12Jc1rHmriLo)Ig-K`}z{c?UjEeP~M5b`%wB>2%=6- zhqSrN=Qph?>&FL`4^TY^!YtK>fl$(kNbvG#@dy>3U!#1kbQ|4y^+PnA3P$wG$QNjA z((oCgz*}iD{VSSjF?%5^EH$#e3rO^>q1Y(``xe?rA3C%>(%Oay)Hr|4_UF(%47eu3zK zBRZ4u$VH>-{x4Lu`n2T<-!5tHeJ&oPPPcqgZXs~#3+%i7-LWw$U99RpKD2scT1bd) z8%^V3!1C;iS5;W^qlK5Qt>p)02j|;5Sr-7t?2hP|IlxKZwi#b>u+y82F9MjKA}QK9 zIH=Kq$3|y@bbR3HUfzD)MCUC1P(gnuK|stkO^NT*UGMKC@)=>5 zje6(W=z$IR!i5XtU?DUHr!3Xe>&(m=E^Jp{$*A`iEp%yN`%3M9Q_yQ)H6qG8ruX;3 zT5h@cxJ^7mAu;Qz2HT{u6>7N3gZJuH>Zo%}V%9v_l z8gG9)x}Br<83I>pY1k^^kY;&rutK+1*!AcfHldCV`q%lQ8vMPw#r}d$xVg~Rubsbu z!;l6rFbgrQP+_3}tXvEbQ`db{R`^8F3TBdm={SxUjtFJ!7Ks8FN4sW;J;&)@$+kpu z)nFqY9neq#b)179D)uqpdj7w+3E7sj#JBc?p$Rk*Im{+Ge z8JfMObBS59#laPNC2cofp-@t7rPKkxjS;opoYGSKeT9RAV}X%Qz%)euNodHgfc8Ppm)Gk?!bgnCYaTt6S=Gmrbr4PY*Pe>2H2OT# z0SEW>xauU3{`b3!-2hvHxDc^P|O(vQ>k!0BuVAf;QtNAyC=ea%G1$~XZrIB(Wzz++x6At|jm=^91%v>yKrSfwU zCXSL~I-!|(WmNKXdZ={DU_eC6`u z`W3kZU@h?sNRp=X4?ZdGWVgep04NJt&X)qqX3hMc^-V7QxW` z9gyf3E)}^Sc9%^&ZBA6#xCRO9)xU7^?Uim&X_!R|;*D3;I+~`qR5Ubp9SCEbr&2p( zu4~ewz%B?HVz1ScDf~2IY}e}h=&dmT{_NUMArgFoBqZfVtMBHQ67wF zH~ssNS9EN#=X8ASdnVnfN_znj>BhOQ`7q81_Ct z{X%dPnkfmQ4yjLOVDzO#sOklTM_W`<_euzjhfgOoSH5QJO{eF1iZQ56RsDzdMdk3Od;)M|HrNV$$#-!k;wmH3uN zZtbQu$SI8PAAr^8zp6{(aA8+D=%Of5!=wmT4W1*k2M~w(5p!*~yb(^Ye@p&0t9 zt~%{(NY_#p-ip2ce%}%EZENWP%aGaO={j^h&f(&k5AHBCJ6k#3%h`HY9Yl=RNe*J| zH-F+B%G9yNqN2{ewejrctE`OJ1b5~-(}!2!#*IU5*Uml4*A*Z2oFa|{U)`WxI6s$W zVIa5))?o<5+{BHU*-PE_(G6)f@kWEfH0qwis)u_@Dz3P7YlrZEeth9`toWW*USeB^ zUGBMVj5yEq{kEULtb#mr?%DOL#lUP0LnA@Z>G^8idjp(Umw{%JN^d=IN3%1>WdC5v z`s4D)z*dI-4)};_7yI8>v)<0*;RNmD*dcapERgt}3~_tvlh}fC=~iznCTJBR9V%$o z6$PC7LxJPaE$0JU40LBjhMk%jJUulf?zcb5p^grjb_Km=zE0=IepO?0%%QJGW(wF3x5s+E&V930y=b?3^HKlx;fYkSddMLw~ zBe^qp;n*R|SQCkw8g-wEB>mI1nW5#&7O@4v*}ZY0)9eV2^lIDZ41o038jeNG!L*1w zv9>nI=kco!N0K^-hvNOR9c)v~H3WxGUxmlPjI&r2J52b>wE2FzI`evV9pf>fTT51U z6MgTZZri^~IcGk=`O#9$v${7(RS&`fBAXtucLiU@vF|vXSlg1Z;2rza-Z8_bc6)QK zw^d{M#uh%*U>sxe6!^i{IxxH2fk~VG#cQQZ6U_~8=m}5Gr_}himVJX9q}#B8^4wY0 z0$g_od`Bd~*G5dh1o`dL4YKIrsUxufov0sTK8GZh31yPLA2aKpqsI&IJ7zFR6R9m1 zAALvejZ6t=Tut^^4m!K{6cxczdLgNO*1OHT7%_~`eyrRCGc$5Z8nBHAS>e)&oc)7R1FU38kNl-w$+ha(>@@#(NY@j(q181# zV~yQlE?eeNlVed(x?dtV9_9v3nAtImhs!8&K(x|CmH(TI#4`KojlmDTg!MiNoyH%O zp)L$oXyTFhXDb3dbt(-P6CrduXo%pjde+ld?5Kd)&y|@R1xvnff_y#eB4)U+skwzq zgLml*wqD)K?=xTWl{YRxygQ!9e1ESGm~as)N1=lVa&4_Xqw=DjtV2+pOZG%?u+i>X z$Bg#KM5IT(!tU!ZQ#PeFtTx;Ko2Uv#ClzoRus`~E0Wi3b_1_S%F>%x7Qj)dMm=N(E z6~?8BF#T+8Y(|fXCH4K^VwB`rrJA z%bkcAB(~l~f}7$@WF_RSt_KT})t`^}z<{Ozuc3$i!Q+FB5qNFRe)T{0*8XPM0KNU6 z@V0`v9AGW@CPW$jgB@)p!61X zhbEX#2P>_ZvW3H;Nhg$AiiEu4ub(yj&tJR{2XGn`6&n-t9n2+&RQczN!$_qtr$&BT z7e9;*g8lsxmnNoY2n+qwS)ha7O8O;B@U*^YmmqG~r?vZ^|pd^IDm+LlN0Lc~)B%|F!&s@=hoH zUfwIgqZz_i`YtIwl^jQ*ri4lbC=xo6a6nYZI051=K-AJ-17A(fh7k5WO9@XLX-s&u zJvhL4WB4P4>}YQ)>Jqp2zK;zEfgK=I>bAmcAHg%`m<9h)=eKj_4(G?;XNj&4*v)X| zvr`PJ8#Qni9+=EI|KN7)G`&DjT*^ZxYGQ?21`~TrOG`L7alt1`9Eey7Tdt>d0Y@TY z%KkqG3#h@TKm~I56!@qzK`qu8?(6TTHZT|?>Stwk{sOj2^Z7Ov8k}8G_MaH{IDswF zLEWn&1hp%~!A~X8bfnLQ46xLc>R!tY$ILX=OKtqRhB#c{&`{9PwbuF_=5rij!3^jF zXh=|TX}+;P2EV1{aQV8~ZW6xD!Fq>F9oe(y2Ka8 zfRt0E62S(u`GZ2u5i@=ZmxTU;Sdzmj9hXI0!Y!D;xeOZ(BC8-+L#AL`V3x|XBbI`! z0=Fuvx!Yq=JLVCCP=V&luX;9<3(2#q4 z&;U$h@@S{Mee3%3Rx)pF$H?bFeNTz#Z+bA{6;1 zWcX9@+@o@j?>F2Pnn6drGDd8x{Ol%EZfm8}b@%UicoWk+7)(%U#(V#O?TtA4TY&WR zu=1Ydf;X2qsofoh&tMV}nGGPkK>=35P!4wlHm=Tlet&+vS7gvwO?GmUN-Rqf^!MC_ z8zg#lff!t<=**`^_fX;C;Xh~^;n@9vc!LcKS>gvQ3QmaE+1c5YnV})3VUW`m>PG8> zz<9W`IT=<<%pN@kV9vhn)t&0M_Sn11&wS+{xUTXw>i$|!<3H@1}w{0V;RPJlR@Mg4;bC+!OKc|Xsul_{#m zucX|Rl9CbwIxZhZ^|Ntmqh=T!PwrLHbevW0m7$O2@_Xl6ch(Phhp=dRGViXYj`h=M zZeBjxkrMlpuE;vSLwSkE!Oe_Wf&I=@G7-P?0} zR_wONO%=K&6s|OQwfkJ$N^$~sMJ*uFzlifu-S}IUgf$QJ@x?oIN%;plM{C};MXc`A z!1f;TjOO+iLO;S3d5rfJGhkx!Bj5+5tpLre?pi+|#PbNtSbjK{6mDGjL6+!)`)qN+~k+`#e6B623mO2hYGan ze4->B?x?`euW7LY`{-s8xE6e+(HaI~&~ z@OZ)-O(Z{WKTfZ1{a z&oXNQkqQQ;RLyEnesEf28$#bHPxI?@sHibu6YeTmfkn)_p$_BV%G!)A=v)%R;s%i3 zABuhm>}A!X^SNQbSr1g$r0=l#H5=1JoP=|JeTwRE|QBt^i+nmGygtL|P5 z`Sr?wg!X58fv6!-wWER=u249(VIGo9?DrrHpjSY7;iQ=91fxP466UPB(6_Jt$u%1=nIcu!%`WIi z8J@PB!}YC*oEE|>)41{Ou<1ZY^t`_x?lQ-Na^_)CJ@v}a{|qsr^S~4QvhrtKZxi$? zy~K3ml&o)j^G!Yuzo+utAT0>78gP09Mou+|{sP#{qJ+TX;Xp_Rw|Yb`dI>xu-#_Qu6a+A72d^_RDR5r^ts4Z20gy|S$w-uN0QZL3PZ>n##m4Qp>lS> zY*~Vs6EmXbY=ekp4ozLEr)x8BO=tto(eQBN!~r2AuX#EAp4q-seuZkNoJYIPci-8*k^`-h#=`71 zsKZwdmh2Tv(R|8fH~&@TM^*s zzX4@>F6Lw-c3wo7Vo7o6XP7L`>=17mt0-gZRSMG7?WRnYJ}1Z&Xrfc!Ncb;22p8w? zG$%6;Kx>Osub_kk8o9ctZOpVH5k?LUU`53X(78B= zH}`zK4o)(Ic+#(tsdyIwnOE+;-}m;ONqBlrcX3+T$Oapv9eeoJ(K?RxTW?TSobwBq zd-E(E2OIm7MnP(?SxCso*ktp$=z>1v+8aNgUmhwk?;r}W;^_E#+^6Qmqp^g|&}0=t zO;(X-OBx8)hYn0B;JS|Q_vPgBmrK&hzRoxjL2q$C&tfE5yxGC`TXDFp8Zi8n! zL5u#fWECH5Pi?5kH%{rYBhGp)$V_uSD&L?k6+TE`{Q(T8+Pa7^PUQCDrSw$0<;u5U zi({<+bw}_OOa5TQ8oM~ZA^zCX4mn4Jraq`-_)>giQBfmLQ)el|v~{~#ZTG2WNrJwyus>#8O~ZQCs-qVdGEE-u zj?DpBt`*IjZT$1~Lf_hOMJzBIWbFTcYC+8I4`8rH!_GS?is|?EzbmiwpgNOX$I==} z2n}9QGKryE%bxL2H1Oh)DqV|doCluqEWPK?A26vO$}g2Uj72t16hbX!hxu`KZsTID$<~FF)?FgGK}NK{qpK&t0JS2ktqP5Ik3RM$ zm@qJD#c%vXgTpx*EUSN>=&kiRz3f}H%!uHfyKpEO4A)n1?u9CjB2}^DpB!8$N{K)H zg-6)=?w*o3o(t29x;hu0{uSbtQCwaokRqb1K^55>@fcfg7ac<&HDKO9(xosj8upo- z%wrv_Yg|KqDFgpf(KKv4;ejN6uPeo|uLX*622r%dps zU)(x+2!e({N+y;gj430sa5$YP2|&tJui48$H0q(Of(_^^>FvX&QFUu5cI^sZyJH^#x8IbGAU=W&=$X<&LD%pLpxw3cWzP{g;fCUd%T za8jC%@7Ws9eR;GL#v!ycLqp1AdkmmGSM`4CdgYj! zT#;TWUOgD`jbJG8UrVETG158&%-+%p&IqrKv8x7^y@c6zC56kp%p6p;Yot{HEp zTb9OSjNkbQ(G<6W#U~&jP^HGfY`+@EbUOQMP>vaFCW6zgiN~02KSyIp&;5oGrrhG- z5X~DyIEHdBn@Y%m6HH}YYa4XEq((}&2FcLSU2WUlkhRSlGxon~JM&;H|Mu@+s1!xo zP?l(stfed=lD;Vwr9xR#_UvocQfU!i5?P~?WGC5|2nm-;NVa6(*X+yl{&X*M&pglE z&&+S;_eWEc%XyvW`Pq--{eB%(E`6)z233U!S;Y^Rf|%&YGzG-L3gU++OEO&VcD9hru4(oI7Xf@Y z4Om1R%w!0_JqMPCDE3GfC#E`*t~-m%v0!cfo^blZu9&j|GICy*11k$2OAn6DKOF6N zK^;}^vgj4l#R#!ki^Gywjm%NZTAFZ>gC7)&K}Mp-IPh9^SFv-s&*-4w%(VgXAr!$XDQz8K^N)hc5U5oSl4ygJNEXd&!LH+{qpNoOJd9%Yy^qq$1 zg*uUpFSW#uKsslbH)Yy_j|0o<>+9J)VQ5 zVuw!1yabf8--Mq$8(x?0RQ2WU)fsD1a+Y%)*l5*M8QOSM(Pkyu1~$Y5$;5k|`V-5C z%Pf~U$`Li}rPhs2ek^{~W*e(-=qQ=B!8{Tf)7MP{{qqoXtq)>aA;cTNPK3YLl5C55 zyu(@)V^RbM>l{r*P8G7A8Ci)y$=u4oe4zmJz$u&s5%r2Xh+sL`nrfxil z5!Gpm_FtQ3 z4EItty=U;q8-<(l&#GjP{9=DvM>i#6J2jaaXu<1+_on+T`o@}4fpam8tur)g8}#bEMjKZ2*i@=VOw8SQ zW38w-E)IO4hPI+1@k817e`|lNa@aaCUMqV)#`jeKanzeL5s4-$3?eHHrLzCWX4t5` z`2}w=#vf7gbBRBdd&|FB!E%&AdtuE?jsQmsC9;4dDh9%(N*^fsz8V>kv0>H&@ok_X zxhK0PQaQ5#3=T+c_t#Pp@jV45l9`maxOlCv5O1)NPkXhqG^NLfTY_Wh%+Q_WLnR@L zKXpG#C0>rZE1~oHo|3RXU#O=_q|E&m3%&yf7W2aY8Q`s@irttrhDcaT4q5aN2XmI} zykpWYG}D(!I$-T}&Gs@T2Pe)`rd?}2W_Luj(cY0`v6hC`HPW$NL$B=VDNb&41S|eU zUJ5iR-{P;FF1^-rF=wM^Yi8gpC->z6x$nNtq8YN`(kn~NjxNhZS!JJkb6#=h^v8{- zi|#P8metlyJdbxnKATm0a~=y25wPJI{uo1Y!u`9`?TGS@)l(B!RMWSuHZ$XUpBGys z8Rcr0WyCPkU74ow*i}Oe=J9;?kEV{fsCZ#}| zm%O;Wtf<%@I!0)gTIhzuqDT37Ere9GXjZU^o3qK@n2Z8bisUeA4$u2|(KGJ{0IjIe z)urHS)LbTftAC83kGsUEKH&`UE&&530ta3zASoC@wjc?h`v)DuHJW|%3 zr}=vBXDm;O^IhBQSu5iy!K>Zhta*8}RU_AU!VFD}gair$lot+mWl-w?(? z0MxYEj00FSyd(jR02o{uA6KG8nyB^tC~k|(7fsw4E=#$2?B`9(D8&dt(teKTFe7mE zEXq0fhj&N0_t7@%WE+<`%H*&V?;OMQmk-k`1WsGoJIJM+0uZS z5Y$RU2`W|Q!stNvIYURX>%l5*=Z*NPqm;EKVWbxYz^pvc8n?1W2S7^DH zd{dlx$2>T<*_`Y1lH2Ph0hb3jKkmTue6T^n(6z9AHAQyYF?{etx@gB?$t;Gvg`bi9 zs(rqL{O52IAX?ta#gwtt_;B-i$-ggu+EOt2mvwo2ys(w4z|7quIx(K-)>B*XK93W{ zVvNteQpI+q%3I@`RFSPl#-N}YrbBX7<-}IUP@Fv1jE=oj zZV6zuv|8YPTF?H=@5s{XUMYHp*1#cq^qO5*m#)N_#818k+ix`<<4F9)MQq;#Cu!fHof6Z4;scdcybr= zwVHGz4kq;kao@8 z7y1Kn5k~TIb`>l*_6E~$4JP8 ztRdSvt2c1=vr|gOO1ukevPKW#BCT!jE)Mk3aR`xap)*~LA8FtQqb{Vz>u_vuYmDB+ZHPx6xg-h` zWznBIv6fsbraq(}K7G77C})dIUVG#T)h>&8ocgQ<$W2_oI4Dz`p86uI#db$oE&b&N z6V=qjx@$NpaFYEA7yp_~bE)(fWF!JiCramUhNw=7<5bLIt-MwL0^IgCG8MXZuTFkl z_3IILx%4TdT3J$wKK5#2r_)n+k%HqFH<~Rt=k^+(thcy^KnAbHY3yXusD!Y!h%c&PU)polJMs7x%ImZHKm3@(&p%7zO=t#m{ET<``PtNHW?&!v$!|PT)zqoi z8WhvOkCrC)VbLXnQewDxv|-}-9-VET5#_&>GPa=~uMz3Bw2tQGr8TA9;=j%Q&M19K z*XVMX$93_r3l|$1Im_si<>bE2j8yJe&KI@b`N_GurO<1Gz3>k~DCmY9_ zI6PfkKe(_`#;tvcUG+`-E{T>cn;*95?+LF7zQW_)sP!7MLtoM`;UzSPH+UF&c}rlj zvoLjNtj^>*%=nrP2AeYkUc(OO+}r{4P$qE|Xj#u2yOnBFrzuG~3e|;#(L=6L^(^`Q zj~be7cA=CDhqUa2CphIz?+X0;ZtMlh->0Qg+nNgL59a9D2hVgKfIgf)D)i3{6Mc%! zwXlM_h)OQG&kLv~tK4;%?@?M?CZD=q?!l_KKX*bV)!@tt^%?7wiRr(*V1C%2H?U120^plSzTTFSSJf9s-^etp4KaQbL>x0(4=xO)WuF#;PpluK`iN zIISAI8#XQdTs~U#nm*;85|un?A0%kWhmP6^DmMS(7%r_H2xVfi6@Ic9OQk_evQ*qB z4YW*+xZ5|aP`qY!{BU?zNz-yDbNcVL?zVF)>EJ7S+(;UD-8o9t{S9Z{*Ntp6`psgs@ET@UM)wBC-xihr>6G&gb#mC3_Wk%_zthEhj$upQ+MCCsro2=$nK#`_ z$=O>`$-y);c2+Wl*3~O|UShr0U=DNUZ&zl$mSr3+cJwjmo$2JH%oc}NTUEAsF`FI= z>vEvdd$;uW?-aRofZ?4xBVs?ll~*U;IO;vWyk2xxELsvW9CHRwsk2@*qaWHn+iz|D zMk|^!@A&jfHT$Z}MPvIr0m0@o8-nsX7V;P8Ro|7a;~d5|90zDx)kMY7bz30E)jUEY z8aqDeK+X7J%Ovyez0~St51M;YE7~UQ#2a>%U)GN4gkS{rsE9%dx2^q?S?xz7M<_OG z{_?jL@+@bZplYApM6vZ!xE5W#hwU9*sLY!0dI(sUY?RDv#l2@9a_L>BlWpi-C8YB) zu*5>DbFJsWx&?thE#1Al)!k~o^7Firkw|szyxuthjk$Nj>jKTD2gInUODF5SnYgtl zASIrkDEhl&ErcY6)gzhNom`JPxN!kckrmbwRy!k=VZR& zi*<$5_b5|qOh*3UCuu|_(i@}d7e`0W?a|nBh3U}IpV1lQ7aN~{S?{u9{J5mF`_<>w z-c(vuo&&2rxNAi#!7`K-UU_wW@-hEMwiS%&n*TD2^* zM#|Ot2_bKEoJLe+Y|ZU?Bl*N(DwW5Uz9b;?JzKoM<8Zx}tCDH0QgxS`B*Yd+%h=v= z9A-3Tki_Ghp%G0Uo4lJVx8#^7ulHqu+SmCZzm(JK&W?z}wx#_m?p&MWXL@#`vnu;M z9M$LdZVBuwXGOa21?4Ggqd8S%w*EzUCFAj8s%~Q9iG+h5S+-S$zwD!Q+61LaXXlsq z-d))~5W@tQl~f3=o=&}!=(hoSHlpfnGqgW;J)14z7?w;6wzPQXNxEh;)qA?sQ&3{eVZsP$G&{}++|y| zYG60!#Ka_}w68axq}cgPOizs*x%pM|M$SZa;e`kE9Yb+)0(fxk$T?-%|BFSf-s}$A zH6+WdAgd5e&+b!C|33ZX(#tE-Mk9Kj&NW5NJfYH(A}3|&+L*1FX0#^UU%RUWJ^NZm zqd2{cPz8hYZUT>eh=|yDF{4Ndl3t+)OcZh*hM?L0xhvDp$EOq7<0!x%&6~6Q5lV_A zdMHR-jcmIb2kZHw>b4gZmvufe;oT~3PVibY2&rog>{U-X1$hTM4mrn~%mNdApjSUNNl zYa_(|lV?{j#y6JSQr_`>Bj+=d^4xp-Hc4hg?$6!LvNhvl#++UBAr4_TW|P*NnvNC~ z=Z@@?<}Y-UVG3i753AY!O3%K*0OA4HeA%&yajT_n3TO@y@ztBCXQ@x z{AM1(i@HVTOW=48Jpw3M33E%-(`my=qvnDC);~?=b3j8<4PCZKb`1_o#yCFZ*nwn&$?s%J zw^HT$$6pgC9oQb*FmH4}y>kDQ`;G5WdQr@9=|wD8_Z%(1w98m?*W{b|VOf@%>`l^$ z0KzBRw(g=ZFK;7{%8H_Y*;Y?4U)%g|NbVn0uG^(cTcMVJ39cgR5IJ2#6l$MiEd_i6h+IwEVLr|jW<{7uObn>SuB z4@g(UF@aLCGv?4el`|#!Kd-tn@O7wZHHrLSseaRA$@hKam&e-0hUc7LDCb33Y+BS= zh&i_FKE)}rI%uh~oXz%2PW*L`xZgeNxDSWJHk?h~4(M-%tu`X@X8Be*^_2@9I@&Ib zRQ`}e2CJTf=FdzWt#-d>UjnSnYA;X7^z!%9K+F{AdOU@rEqky4k=7smbQHTdwed0r zOf2S)`Dh8*2Z-jpUQ=B=yUAnfvs6Y##@x;+m^YEf=na_1iTSkT+7=6`EJn6|373? zyQWRPz5a5nX_=T`;?+k2FwU|bQ|(V~=o~05c)Uii$#y)g$t~4Xj?&Wa-O&?q&~`11 zx7}dMuGjmo!YJgo`hK`049X#C<%#!}>NfANTP3mz2uzZKO}N3pEA>}YGOKp~p)k8b zjqK%sCM1RpN+Z><@RV1xG-^cLgThGW%Zjz1Aq+edai|oja=2EWBW_<6CgFE)bq}i= z;k)glsSM;NULB`j_xWa^dgF(58pvZFFsV}e`R{e^!I4oE*cw8gDT-Uc%MioO)%)-X z)n)n8MW&dmHz@)q;n^GrG%BNcd#j8kATJ3nKfy-(TT7Wi?WI!}v<3_wpUa+obSGRn zRV?4*s0F|J_hPuOk{-d{s=6`d-qiw-66i*&bB=~9pRi3_c3;$|#(d}3J;42_QYWW2 z5PDZFvLV#0-n)tCxhf^~gh^GS(j?+{(Ov!OI)4a501Wa zwvw+ceD`ER}t<&dXw#2k$3CQhQ5W0!hg=CMC)>lW3_LVtX>V*{F zRBt^2A+R9%)i*x68;Jm_!G$APh-%2bV6@c;)rbgGBAtL+0v#w>XH-Mb^K=*bON6pwG$L zfN!gKJ<-(7p)>ifB~_9t0N=v{^tl%o7bgf; z3JGcF1m+IsJj8th!1+|n=uA%eqkZ7)-y(NDGNJ-l6bR=Y3Ha5x?)~&T9m%G6 zWgBIvUBAJ<2)LE@_!z*LqryxyV!Gi=w(xzHpNVCIqgi#*yhg!G0pj`$( z+ME-+OF3w?_k~~Djo+roxyoZ5NW7f6n}_Fp#-qbx^&daF(BV4|?XX!#_+o15hNt5z z|7N6gBll}11j9RF*pk#!1A+UJf(qDQ=pDH;+*dqZ%4PtHz%`(oEtLEHmmm82ihCk| zb${Pq&qBgGi>J%j+$_>=B~d;dY|3|$0HBtDFPf1Uh5EIoKcJHqKw9W|eZX(Xt)HEn z`oIME@FX3e=he!34H3afBiYdoj4v0Wez%v3*6=oH}FE?qVBxSRzE3Mm6aK z1U0kZ?#>QnwvntJwi7S#rl9Wp)c>_p4)1uC{J#XmN#!55B8+JO5al2d^WO?RVVwNuWvywgSSRJmTz>{Ua`Q_ zTwoJ}^H~Y+8=(N2<>NZJ%`Ue5bIr}5KxOk_-$78k5NT-QLdQ|Q1EK~4Ffo(tVZ;;E zOuG%)#$}BVtzJZYQISUJS+t;`k3NC%qErciZv(vj(naeT`+(L^e)c9e3ybhj&#q7z z)JJKyZ_p0hd*MNEud$BDqCJK+*vP?kG1(C_Gq7Ydc3krH@wp019Q5FS181_&u2+>< zdSJ0qLDtY2aw=loyh+cMlG2|ya&kl&_r(sV23D77JR<=blZ_^Fm$h+fe2nqbc>>oj zSei3)htv-fikA8u@&llypteh&n1O$Mz699A=*cSua31IDXkXy`f$@mP>I z54ka9v^L5Qw+QVoIwpsdAZi+TXEtPdmM-I+v4mC3bQh$juaMt( zrR2|B*3{I5C;kMMWF^da;B`&pDd+Qf;riyb9Sw+eW)2;C?w;dvM-ae?GUwsRVfd2R-plHcCEm-r(hO?e^k{gXB zhE818Zgq9Q`PhdWSjqx;Hts$}80jEDHsqjHV03~>;Y7~$V4=%*s|^jn#618&E5iJE zk7>D`T05kqLI^ZHSmy@6ns4yar%Lkj6nI&)emP(_j@LZ)yFu6Jlk>5i(bR*O3q6K~NJtHKS@@{3czJa&?$IDlufz{QuS)FP;p_dUY`aMETl4~aMyDE3#E z+fa0&VPyF_?cuhab5O;fh3^4cuj82dhzEDbGP8*ti4zbrV^yOSKu8qRx?cYYC5fyW zv>nd^rbtUi7l+ymn5mW3OGFA66p$1rEL&`<%;9Nh*@ubf1UfL#(3i9 zyLR0nk~LBxf{jfH^G4rw_|qj(ty9UK@J8!qKB3 z*2yIo%FGBjX}-S0f!`OtS7Qr#S1gt2R zsh+5&IL<^unJJju(~ZCIHjHEV8@J|3;qGk{RRF~Swj_z-#1AWB2Oy35z%L78wL->d z{F|CeHWxSa^f)9Kq9+jWPi?HqLkI@BcqTd^aw&L6Pf#l0bGEG!;O4~%n&}z3r!w4@MKXX6kN0z zz>gvj!hD257qH*I&A3r{3n<4bXr0!{XF&)&@hVKn4?LxE0GEogHq>}nG`M;D5&|BbkpF(L@bPk@QZ+u z?z#@dUAshS`~E<}xkrhc{bg)`<}*+H0cTs{(aTCoN&vkMg?o(+1H~8VH;XXz>VH&I zF{r{>+Y;dAu;DQ2$3ZZ)n*CECNYzZ4#SoBf!%S;>ha~hm}txEJVAeTPF zky?^rf&YDF)n1&mh?%nr)4hm`yMa%fcJ9{M z1BJ%MF#{6?+LS8J3E9!rNrW zz?b?bZ$jg(F$+c(-F9$eu^6UYDP#jEGm$Hc_IqBa*lybX0SFtS2q zUBroz5ozR8(=#4^&gf?FVRZHLUxv1gte}W?IDYZ-^J69pjzuO4QMrBT(AU?efGxJG zMM_wvCx%#wpuL3&!J)3l@nEjw2r2Hx`iM^>T47}*Ecc|Y23BM;ptSrzMNS1_8U?1@ zN_trRn~!1(pL7C?G?`J5*0#~6Sz$y8$F}aoi4zi=C^TH)5R)CL`%F7M;0Eubj(8;< z`g;X@RH3LIVZ)*-C^t)tJ zMB-;y_Tn^BdEw|%$*jgfqXM^a2Acz{g;$1~v(X?FRp`Hh1T~BCY{aaH*6Rjp{5dvT zNsEN#4po%%cm*H14C?OuM1tQ&whfmGA-G&p&jDN6F=*rA`VrCjJ<9~rE>tBf8#me} zid;B^0(J&D-MZ-1h$$SywFsmeDB&3V$(!qsPr8meEl2Q{wWH4}HhWb!_db$9NV9p? zdQDBZ)Z=KA#)QuqX6on!)j-iFn=NCJI*0um>SlGC1{8#%KdPdCVQC^8*`xuG(-6?*chR>!Ufedw897EVA%dKm_tKf6jWLp8uaS k-#-tL|E&gR)iR~k*+f+BvQG`lhEh%(JENGSpm*#40O8dsy8r+H literal 0 HcmV?d00001 diff --git a/docs/images/29_AWC.png b/docs/images/29_AWC.png new file mode 100644 index 0000000000000000000000000000000000000000..fab57eff45bbffd6aa4e52466271c622782bee85 GIT binary patch literal 91521 zcmdSB2UJwswk^swAff~VASgivB?u^zl^`lP=Zq+^$T=qgQ4!G+M3E>ti%{ew1|)+} zAQ?m?2PI1UW0vld_Brp~cmMydwP)MAp~b4T=9+8HG5YAek9AL3QHqR|j+BUqh)hQM znko^|?jRzfJ+DZJ;gh6YLFDj5$oaaqvzncmvzxJ_DUpJ)v%R&Qv$f?-CRbBOCrdlq zi(GbMnIOOdJC5(fpX8u^E0s0G3%_S1JS0bX}w1505?YWHCGChB+v(n40c)ZMQK9|d& zti)z#Dl5EVlP^!D!C$8q_xzInV) zky+ET#EOcFBVB9njwpS+alS-U;_6j=rUpl>-}cXS^v&AZTF*E>qMD&YB!3V+;&q$T zm-)n9z4_8*x=X{$_Up&Ty`@fRJQpu!*%%dBKZm0Wjo%U%pD(iR;h_zaBsw1Y7n^GJ+b-CK6T?WWK51wfr1TV+Pp|aZ<*DWDY|Z=O%$n)8R;zdLq1;vJ z5fMj4HW%Jbb>+N(^EtAoQ4lSt?U5kzAL@H$90(u14CN}5#`2oC#9&&(PY9`EFMg%B z>v?Uu{+4l@Dez5#MwVu&NOzhN<8>)1Ic!(9PLj-%Gm{mIEgc`ij=QvqtXjOgdx-9$ z*@INY*v!~VZc|-)b~$R5J{v3ege!r()}PNCc+KKG$79_JU1xQ5&QU8oJAY+tY%FcT z?+>EkaP&l~wWx^Vz2=0-XnC&1d;hp6D=Vwt8h-481aV-ZE>lx;Grm=9CmW3uo%K_S zoIxwSu(R~W>b%=t85z%S&&}b1Ex`mdTJx9VDUTja-hbpw%nzZZDZJdys^3mp;693} z4kfXimHwUWRk1Jz5#7g+ACr=i;f2OylIE*6a(hKJqLOR}%3v~GB456IdGyGUBsR6w z^w+Od%Ux$b?WNIAxObTU4~P z8LLBnMmwA1VpMRh#a6K)&ZDxQ@LEPWhLxU^@Z{U*-TD)sUo@Wz*vHTYqsv6|XXLXS zDH%qWQoT9Gz5b(-+aRy8rKRi9$*YC#-*1X6cdD(!y2)8=xuirPvh--Ka@8qiU+4iNJ#9p&rzdao0ypiGYjQbuJm?fqUnMw zn3$V)uX$TqW?aSI>MwDC6OOQQak;*G_fGIbIHQq`*o)?G6ZovCTQ&ZF*w*<@rbK1V z_LaNYg)rAe8Tn53n&EWmzkmP!u#vmEA2<70iorqJFn`Til;2}Un2nm?3~kZ_*Gb<1LF-@bLhYiL=HHAMCnn1@?c4-H9`z)lQ<^@w$z zD;<|zw=uDW4Kmf87k}#1DZ0sXF(=5SaCKQ)d76fXac2}`(i<9NyF&(SyV1H~^xIT< z|NcGR(CPbo8ZEE>6ge7*C}GD1T5z1_&nv@1R@T*xw(5h&nU`x&j)9xP8~QbJ7JnSE zpV*kMwoC8WL&VFp>m*T)-RwZQ7Kdhb+jSZP=8(6Eo15Na?AkdsjJL)Ta<`g8s6*az;i5eva`$XsDWnMY^h*nuw>U z#veJ?L#eUJr==cBV{7=HW_2q(rjh3en!ZvA@)5%wBNm=Xm@ytW7ts?XA_J?xF1! zfxUb7u(Go^P_1V^jSw7KA2w^APzfW51nXQ>swY@&ACK}JFS2Xe5JWk~Wzl}4b z5jkv&(D(_6kX9Qjv#>CX!WgeyxstXi6fWSoWMMN@WdH|e7Wr&%{^U7!5WkCuC}HwO z5JZV6G#XYB5d$>YR@Y|T2g=>Lt@0{Ug`B>X%w-)Ha!fY#{(jvDuHiY67?L?F<~*S+ z^Qn4!nHxn*V`F1{9OGs8SA*V*3Ik59B2#_Ed1n-&lOdMXV{lVx@xGt>?5cC-2Fk5A z*S??4@frOPcK`l;EFPob=~-5_F?Y#l;mtl-Y3a6ZBfnWvkCBlPLdv>#8>A#LLj7uTPXRA(^d12wwhh+|J@t zvdmOxhFYLE1CjXKQwqK9IY#I35Hcfz=iPP^hr!Dp4rt?maKkKg{17eev*^55T7fds-4F1<%0FTG5jmxt$d{hr#kHs$M*lKjuPHF+q<1)+K7ATujLPh3LBW!fvgpb9OCFh+-F4X#G8CPFZU6pNA@8+UC}YAGq-hMC zRbn4n0l0)q-C;e1E>ZCzZTCq1=ULYQ=MIH+*!J15N%22ju3x{787RY9^S|(1oy$p! z^OW^jU&?UV`SHUsGAgQ^LGK*34D8oPJVs>shy{}dA8)Yku+ZP0^6y8^_nx6!J=ADl z?RdPOVL(7Y^komnSRyvep@tq~RIyGiLcOm|Lxo*uv`4Mtd{%T6 z;zb8+Hom+MrJ|$rY*-d3WRZL7UcQHS*I$-~YPg)NY=03gWQDf}aJ<3*5A&+lWupu| zGng$QvY=p4XxVY5yE4$Gx3C>zeja47>XtfO->mS)OaULD!OHciEWSCl4iaNnn2wH) zM`>w28pb=7A+|m}r}Of{tq&hfcs$BaxRdy-_$+-EYcn5`3g6ld|4_)UqYk|e;e#EZ z#295Y{Ym{&$CTHvUq@iEUwX|7dX|O*DKPMah3$vMV;|n)rNdYI`9Y9R>+)$bD}ev{ zT%Xi;np6oUr)p7L4iw!G^_*dxD40*G+YS)js7mb|jhteG&mTBWt&y^l?7MYGTrEb8-o%y$<028B0L8mtK+gko0 z#DqM?p{G_&t*zZq8e}vz z$-_FzP>L7Th1Cz?vMm9(8;vjxMtI`F&7i4^=86idWL$bh*}bC>N-^J>o~P*$qMCdB z_pjyXl0@Ez0J*}S&7=Q^e@5sr^;h|9$QUh+gfMz0A47u>A9XkogaAK)SysS+MT;;K zyvDVA6ry=ERPLj@BXWPJ#{|_41>da?2cb@qhwPhGRB6?n3rnQ!Tl0(K1(N76|9vHU zYdLaDB>IYM)b#aZJeQ|ZXpFp7qVyf_&6Q1aiL89Sr3iXFYlH zO1HjKnD6HIx(~S&=&<3FwgC$-?5b3{a}98IL!vhQB`U3#7atVa4rBuCnC^FK#V3V} zW&&`u>qIp=k%c&X1CU*3{Pxn>9GwD5^H`Us%xve*$wLNCg(Q3&C2j;Yl4yQ?LECnf zGS{fuP{eB`+hH8`(FBBouH6)uhridNGZMv(@k?my9m_rp#RI?#_iQHgsrYC*zr@9bn z9JejG^2Z;4>#CE}rAy&H8Szk#)#ZdR(`ZH z+n2Vs=3YDwaEcex$r?t-CmSxdT|&*JpAMs5o*&xbRU}NWJv$5x{mQm%@(jJGx3+7! zfsyae6u>1ZKNrWRVHssC`*T+;NW_Z$45l&EuEzXYu^(o!?K3mhGN0DIk1kK9#bZWl zgW-vK&g9n>-l`+_*;?*~I$b`N+)!6H6N^3EJqj0Yj^>jKrRKyW{2-hpt-&Vf6$Gj1 z^TxMrtG8SY09y&~Y%VJO97dakt9sLM0G?3;gq@mz-KIRxBc41-f~rgB$r%OVoG-u5 z(P9&{0I@&n{mph5N@Pq-Haz;$E~e}}g%|vm6K#puWWZ?pfZm}-?%4dfxD1;t&TtIP zqkqR2YLdM2Iblx23T-G=%0?evS_=2uyh?w`wG-gtGWxrzsi}*oyNt{|1c+opX}G(_ zqKvqb+S9KD60>n~=8Uuu7O=7%j_cB6xO^R>pFXe!-H_w(up$RM#$$nF_$0F0ua*|* zHqmzF0QEV*pdp18?We-%FKJ>UA|q2ie*Abxh!ACJ*fRJi8SEhJucKJwx9ts8RwXb& zF2ZZK!bMU;7(As>zJnRz1KLQYrM>nDrvYIu7Akb3V$&UmYyPNQ9rQx=$TFZ-3~)YW zTPuCj&I=rQ6{_QLUb#FxJe^ru+}$e>O{QNra$Q=^{56?5AH=maHB({X%FkD>#%X42 zCqCuWn|i8e+YY64ChU)xr3AnnZ7fmxFM;>4fMG(;@xYDmgDk-Go^S_>v3)E_Zi60a z(E@h4m*z^YLVb+Tx(f^p(to9*u`*V4ed2WRojaHxU+eFOhISxci9&Qu+{43z%s>o1 zn&G3Rduwr4-I(>INm(VOZYVA?p|~>wmd0=&J>(ce&q)?kQ(1LoxA&OG=RiqeAR{9~ z2fs3FiOGOi&i7dcor!3wm6HXsu!09 z*}lwmHWT1U=E(hDcuh4;M=~6q_Q?U)KAW_q`b@6tTM)J*VFe@9WmfPr;-Lo3e*%Gm zlNY*y{Ibd|l@u6oeu9{@7q(?GT1Gy&t{lB?Wm7cK;z@#&=aQxXqlCx-q z5K3euOZkAIO?jF*9ld~U3{YoowLVb!W_!(7YQg^d1SP%mr&}$s8*hDh&<@2D3#vZx zKgJsQth&zmKq?_q6+lzROI$3D!u3WF_h*1Nu@qGfqml|Sf-09>XCA#BNneS1bK_C7 zS=M6y*m0J%iI+KmFoixKI>}!W^;yYfm3ePtSu+Vh16B$<9%rVslw0*mpe>8+2C70$R&lv zG%-NVf`k$I=7#+N`?{=Y=8MIHo>{0=gM7n!;X?l4lMeS@STlJwHR1|!mrGmn>YJL> zVFlo9AR06@HDxdJ!Aj3gRf?Z0^7;PdJ&<%cUT+v)3*pnVd6LvMr)E`$9f;Rw7XPVc zIk@i7$RBLBH8U&0EW^UWV%yih%UD$v3vkNCz;iN%kHG{Ad#H`=VnvNHn9QopA95}b zhkPUXZ$pBZiqtY}PgQs^MX&BxUHx`MaO46aGl2jsLFk+1>{(Q0-GA^P+h~NL?dRR= z2cmLSA*E3r)1J?|>u@JMJG&DCwsgGDv45EzZpKUUoVRK#4IU;B<*Hwf>(ep<5*K*H zR7imJk`%w_fu7eXGQ_o!99rxg9CB=IY`Hf4FBD+!CBTwS*}advbFB=pOnDfwnW<@M z7#%~aHGj9D$HRIPY`uvv?udo>?2*%WQB}H5(JGnF-L0>5a~k@t|MgMneFzeG4pl-3 zU?x<4eEIT4m*P|6)qOyZ6e`9q47d&9-`zWcv+3h^nI9a;@rP*AIVl)t|L^f|S2r2M zWo@~q=Q3OwMq*c#anxNod%e93O2$WD+K^e=wH7>T};FWvf zOeEX?2sfjMafj@9Dk^hOM%rG^^P7a-5U-h|JJ#-mVy6Ec&3PA+>01!U$|h4^L_B_c z687F~(gm|)1HgGh^hy%-S(nD9%0GVzf0@XyW5`;(K+bSE{lSBS-J>V3-kEr!B-#!; zGYvRe6ie5aI+XbAhii!Q7||BIoY6}%0vX3}oW}R(Sk&2pvjPH8P%PB!pU+!NK6F~L z^QW(r4Bwyt;th*!5Qze$T0=)V0sK_t^^zC^9GO1N!=nmtBbML#^RTBcluzq(WU=R1Fcpcw0$k7-bb?k6gcb$h#PI^*&%wkbj&-7L0XUM@BFEx9)kz2# znHpK0Nm3NWGNw}n+l0|37~{((>Vc3$)30?bBH7=cNCC=;t9K5zAK@XM_*(x2)u5l0s%!^@$G(1ra*|6p_|vaMnA9b1!ArLc8F(77_|x|{ zA14bdoGI|xa0P~EA~P%ZQ_%h+oq0xL@9XO191ZW3!EbVOak7lQYl)CudHuFGiG``q zh{b(6=}5x0x^=FzSOSIBTjr95BE^9HTQY?8fR2ak0RVwn1}gD(R9*oc)?m#aulpOK zs9G^ycKmvm!E@pyfFU=a5ghe~2h0lao^7yVrXVkWn&~OPxlC))3)+jPq@+MXRfDOa zqM_-wH%CJt5@f*<*Xr4pUf)N-&d*T+)M!!-et=k}rF+O#p1 zCQH#)xhjB{puouk@(0not>a^39uVNzP~9na$veZTLgVAVKRf7W zxj@A{4Y=tRy#)Hzf{Jay11_T~eb7w0Uz;{M10KrE&X$LWNymqYkbHO|11iK!K(B-8 zgy-Dm-@j`Fa2+3TrXuSTNs!!hAprt>N`-?aK}yr~@F*2_o=5;ez$3{JT||6$h6}xf z3{Yxx{MOIbSLgHI1n#qHe|eptV7bi?e#rb?(eV-2zJAREa*Hmo*8nRUm*9k%Hho2O zaASy%C1Vt=$e$)u2fXKt#RZ`n*;*S7#|%|fq6j9oHK~LSJ$&Ryr3zt_)Lez}LYxFv zJsIu901jOkImE&k|HG%z4V?P4+M&%DYM-f2g7|0$7B_SXY@3&q0x}cy^O(O3NMj6yN! z1+?=0d-qi2Eeo9!U&nIO3<_ zV+8L6euWy|*H0AL38Pq001XrV5VXwyPk#dIq6HZH`)FMjXd+NQfgW%LHy-c)Wq+(o zmk#NH18N0k&CY`!UUol&2GzFUElf#GLj#JCp(lt+81E{;a_DbMfPJh$ z8^&~`hJAQQpEWZxbA&+v@&GL@Enf6?V4#QtA%PBG2pHt5c>*vo&0+KdetmPf+sJ74 zJ1AP&fTSz{%h8E=I_KnFJa!P}r$9Vm?+gxi1iTVuXJJ$m1m+a#+3K#*Y=d%5uhlsu z?U>|iF9Drl0X6AAu#YgQzt~66VUpY0+B$@}(FCT4LV0QcTo?++CMLxj82nai!lO<3fBOxAbDg?(r_+aQx$}1{rDk?tAIy7j4)5V$89}c6v zD0${decxEk)xS}Gzxh9_`yxf!=imxi)FfNm*!EYi&I3BU0@7UDZ;Gz@`9&#sggG74 zVUkHGC?LwAEWF41X^*vQpDoYx=q8$w&ZVgU^S{%Tzqrfp2v2=AdQp+ai42fG@sf*E zuXg~r&zCc4*zk)KN>#wse0Ar?-1#zaSF0>#I1=8Pl|h@R_{X?(zV0iQ)KGP`X0Cn)lxC%dP7A|VXv3<>lD~n* z*m7xJ9fTK<#yi0ZkfWV1v77jyMa2=c8U2Z2-PuF15^j$XLdZoXJm0$KH6|Q91sOm! z#@Sk;8y$A(ze!(BS>!Z-QtEfBs8?SUsWm zz=9NP%*n|~(4QZ@xv}61CIa}T|JxB|m=fUjPA0Vr@k=u;-3Cz%?%AuH0FQm4F1w1s zXGX%N*SdD?nzSSTDIT6rjd*FzEDc2Ufc*h@rwRk|%Rzr(@IONx`||5o6D@|vBteEM zF3&AYOiZ5a4@yi-gz2>AG0L`Z|BG@m#=z*;NB8F)BDoUX>Hq1UKPJUXZoVfCV-!OQ z5=>Yd(8-GH(PNEKS$0EJq~zq9U`65eTA9&Z-2%ZC1T1HWzWn;_XjQhQ6lqm^_G}qF12(|(b27#kNGDbrrM`V2bP)#Hu7>uKE=7SjP zTXhd}en}`0nIQ@r^dUwS&^hud+07hA%P`^18amw6%#0oAf!?Bb@2+WRYO+H(0<5qO zI3J8jCy)}{Qpd^7tp#vx8Z^zv%s|#+u5{>SVk}5;HBSE~pyy^#?;4pucJK}c?G`J5 zG>J$IM#%#O`o#?iEP*uavJtB;g%Uz`$@d`E68viynIv)NH_%i1M2eF0j+OxjX!R9=S!a2=Tj|Ub8KesMZvPy|w2A@1MfeT~Mc4sf>B6n} zUzqa07$|xnpL%BT{Ykz`&tclXto;(m2-s-?^ix$;<#m}- zM+`JD?orH$_eB_n*RfVVXW&*JKf5p;M7$uA8G25_RZEqj9=gE)1Og__--Ku@EHhNLk3(-^cQiHt^m zC6-(nV+@bo;N@bQw;>eWh^g5W!U!W)k0@rpcF2D(B>lhDv^w|i9s!MNX(B0n3d{s* znwn3UC#!e1@(>3g$wm-EhJ~Q2Lpv5E1l?lWSVS~YQBlcYk{qwSX<3_>;EGwZqqg)_2{I73k-U=~I= zk|LdtQgmynLsmvcrSU1JhPrw(vLJnaWlYCoa+kqpsr^ItA#~*MAE0g+^E@Xo@k*jU zlYQ4G&%#NUCp)Bon73|PC!CML@l)_5uxxpV)dncGOiM%j7cl)s#;Cyir{nT$pB8wD zFx|PaX034svp<2JmIC2N1JHG6w$4Q;yFGNPeJev+2&cZB)^(`14@`7H+%cEjYy)XJ z+EB>>l=*LiXABIBeB?* zz@*Ax%bX`)0nFaK+mQRj4gS9>_1{~4JJILm8k$PAU1&SDole=Qt;l@-EFM!Kr#u~ z+dq&MjY4emRT}0;G(2CHGiM+gJ$r`yGeDZKva!|A@`YdiaTg@b3>Z#c*XYxzsH}>L z{^id%^Q9dhmg(kn5od09YT(8o)rlLlc6L8^ps%rAXK;qjXr=_{W{ z>^n;gu*mU>c0J6fn!UY!PMtSM+I&9i&c(BkpfxQlCM-4k?Lp1|GJCj<TcTYaYEDXO{2WcS7Mz6v>e|>pcE9V}nPPbQzt1W>G0NHg&=D#0c z5iv9QDTRSE^#ag)h$G9b18EBh{y=?$d*Nkw4V~mqi^57rD9+hEICU6)oCNi2Rh>GQL+YZGaU>8 z*qEp{E3i+)MOL0Mvz`t|{X?xSQbv%MN%#(m111C?R*=8sV1ReSX4ktD}qv{Bj?;Mks? zp6JUSuj4>J#`J;0>VUkyprkCjJD_8TS~HdzYLOf!Fyvj(w*sS8G4lQ%EES4y8u(q}~Zv3qL zGv(1~SVN*naiqKCnvGBw*|GEDkRsHjrSF28UI-LFViVCqg2Him&}%*eY|3O_nrLYL zPcr!^6{C4&uuGtRmy4L6KZdD{;bmo&2784X#L_+|Fh&q4H?R^TZS?>Rm%6Sl-7nKf zMM9UjduEhV)k5t7m%-KA1KgKWS_vhGpbu{F>Ssz2eKk~7zj(%g&Ib_?ZK$}-Lc*1W z1&x{XtGr8*eG7QObbydZiH4d~XFSlzv7UvnL)gT`jF2oM$6c8W|EnWU;-to}r_2eV z7Gk3^_|4?Ix*zl%drlQ&{I)N{U zc>1)9XpF#8DQe`L4no2+$lwD-N??44ZSNxN4yyu@BxqqH?GMrri;Rwr4wNXD-(!Dq zzKLDp&j2feIlaYZ15!yEU^-#?P0%U`xE;2>1#rA{VEtqsw=f2qfnvT1nnLlb_T?r^ zMSZp%2ng7m{ZH2_Qxsv@rBrRnQq=j|;E%J0WTXeB-4>z|`nQ8Mx}a zjopjRmM{p6Bv`oeK%!OziC-1Ix(o{6BuI*B%o#v@B5A~>o+T<~;XjMe{%Po3M1oYd z0c|7pCEGqdrctq@<1uh7m7+5WCKGnS{II_RVb8TvTr}B zGW+>s4EbY$X2a(iTxtd*yG=ZI)tUq#^~fG;P4MQx5-{>eAaK+R*>t;&(-dRTNNU5& zPy+=L1tBu9b8;#m>a=QS+Y9+kk!81d$hYst*+s8^P>+RY_q$2ATS+^sf88me00=c)?NnlL;r8-NkRUb{aLdyTY@<7yHSH( z1{q$TavSBs21G=-?E>`dz#pZI3zW$J2##QjS4vnYak8_|^~|nd`d;+PC&7>%aw4_I zkSz`jy-?FZC0+>aCJ4aWZm0);yx3kfb91&qfE8nuyK6UQ6YEcrUa0ZOobk7Z?-wbi zg&!UKnS!CW`{62tbKID^G_bKRy!h`rb~?X~0)9Nd$C_-VluiP8C*a7lY~jZ66J{VK(9}*@~}dKRgz3RCjbX8O^2Q+q?}|OrmK> zapNOqApA;foDKw4S7$GpAZG%wd|9yYY+F-OQ>OrgszXqia*?+KyJl&hv=LMnyLRuU zI)2=%*2h;2<6Z#}0n-q{Mz~Q>eNbROb^0{nUXT4l70EX+VjaW4;j`lLuii-wEp~?a zLT+u*_Pbvo6yiVvxp;;WWKV6lZx@^mf^OBmTlxwoAgBO%Q=Jv9MF!)Kk51wky8o1% zF+4^mR6DZv#a;Oey)@;Z;NreS-UZQ0>&RKf&LW#WLT}ZsGxE=d>y`5U=QXC9%}N_+ zluB>!kaZyUfE-upwH@FymZ1Dnf=vHoq7+TI_|-)VCjClJ957)is5Qp6mG46`&;O(X z&1E^uYzcS14onNG_%M)^k#Gamk{a0w!M3Dv0@@&JP71L9tuymNfp0(e>CEpCqH#;9Yu!|Q3$5UNrGp?shi~qR9GmmVfyoclSUgE-7lCDOBC2Idi?mR z_Hzk+!=G6B7E?A@6QHC6b^$CUXS-MYwx*2;hA^jbMJ*;E$#a*7Q3Dioy@2%V$Z1qn z(d$GU81RdsHT+6VQfxPr3l2ZlU@%w{k@n+2Csk!Io&MaTco* z_=YLzdvOd1%>!opL>`0R&I;l&;wD_c1e%_ZAP$a0o)^uzkKZEe0MvS&V3`1(<@hi! z8WGX*7&QqHPT+a@s%u}Bo-U2d+|-9z*tog#x&l{bderPHm!Cq#n*%1nDR7KIHqk(q zRPcV6l#~#QlA*JR`+(I7;9K4sa$7KwLzN4faMqiL1e9uV%$6X}E(_NH_{s*C2J5+V z*>CRu!oP8S$vn$Y=ekV->q4e-0G%%3P^>GHv)~CbmEVFc{FA^##617Uj!0OQf9sG` zyhI6{h3=Ur87F_)3wci!i@PsPsBA%pAvpUS`brZLYGzB}86$GLK!b2~x)?nsZ{Uau zfysoaEt@?-MU?`^mMJhSc_kesTz%mL7?|KOPXI>EUEYi2JyBTK;nes?s6>E8q6xeJ zO4I=RJZiU4baI*ebp7PXlT-br1>aiZ=ZjjibqYF5oy>!Sf>?!wbPz%V5&p8vFY)Y9 zK=sfoC|zB^wbMo8Jo8xvR>Pu&3fUNVPVuM&5Eyj73e86k2R)}b5#xz=6mXq=+h}p4 zG>^!Lt&P=gsQp|}x`i}}oUzQ4j5})~3{W97$6nGx4hkT>T%cJ?8Ve4$o@Z%&4<@jQ7^jwY;Q#Uv_Jcbs1Lra{ir)DkOxSf6l(zM`$o~y;We)cm zI4Y4+qtw;O1cG28I=0EaAyS6UT(qdHaDitGLb7HwuO)WZu3gMBU|2%x6tek+i>{}) zAIQlAsjkPGpFmE;0Xfms)I?|G1Q2f;`HWCQBKTwV(8a)-0$Cf`@RF06QL|_R^dy2E zgacaKfYJcFw+yfu(mA+@-z-K6=BZ{Deu^}DP+jAyTKe99BX!I;DBym3z7bP$Mky|P zXQO&Y4JdSk2VrplrkX^Jw8)tw$yRdmPpY`Dh#krzH2@vNWOS&@4l0BJ$41WR3%BlY z9OKq2k_RYPh*m1(0cB7(@u)I@k%PB2=fkKdv^hkJ`jqvpKcj zmV`rp;UPdAgi5HWc^I@ozS#=jEzhk{#+^23CxGrb6tR&AN_YN-f87Ba5*RV+Sp}&x zwUMj53AY99TOEMxk!MHO$O@u@wHZ+PthV7J3!qxmrHP@wxyGtV#w@jQU%+NGddoj^YW$8tYB995OeaJK?0lPHhYSb|vsJ%YKa4OwAxwpCr1?0jj z-LsJyx)lQ>_7-qc>|9*AMM_YX>HFP=UOCK@(7xCSUE!xe-}3kO zm*ggB3&XUwr-Klc1Ja~HIQXg)K=?^XOB28tqd6jKbvzIR5fDgxe9>NF;!JS-w*M_1 zvm^n*3GIfVpt4%&>F7L1&j&={(jp%a4#LzC^Kl@?*cRaz)C$h zjL_powgWiWpv<`)@_@*n+12(y#|9P_nmYKps!_mG2sXyaEk$X`m4_ zn()YAL5~@bHYdOyvO05a+MM+CHZa)mxz2pX^wohG2M+9Biv~9|yxc*nkNWW8mjFr| zF*sT5Heenr#0f)iPKSH|_E-bdz5_im=8A+fUVdjTMdIY>Xj0G<@$8wljn~baFM+|f z@@_`VKB|aNlN=%}Q0os+j?m7h0sa(Zm+{;2^?}BKvXMK-3qcG+4tj)`HFR_`>KMGT zKl~GWkA*%t4hv5;4Kjs9YIpK~(<8@+|56a}>i%!OzQiVr2SOGomKZRzI0~LX{kELN z{V!=Rnz14asY!7k+B-mC=mE4vunW5Qmw~kdPvBoP(rEL~|0S>gtsvk$^l8J%Y?A_j z)v`^xqXFIZ=(QK9XF?c^lW^Ari_)o6641_vO@{3GT>gxfctkQ6K8fEaUw+ie) z20$jB_0Fj`QHA=ESq8m!f~#unCip4(I9s8Y8?-Mepj&fo%H8HQfl&#A4hh)6O=eDE z@o5>}4$=yF4DQ5#nf{DAKKw|*lLqNe5o~HpfN(K${iVJ6w?dF^gSziwDHJo0e;k0K zX{Oh2b#4F&RXFojh8$?!LLmrtXsUUf#|K<1)GiS(USy%d7Y5M*K!6(t7vrsBkRn01muuJpxet2xV5@>sW#kDL(t3s*C@>KSx#uF<9(a=Fsr_rLI~nMl<@hvy5O3vp6iC$DAbGlphF)rQeD2u zws?~TJ|UV46~EizxJhCx`3FG)5qyHa^^oyolL^5tC71;NZph{@zt3TvTPGFDQK5|x zivRj4$}bUAPc<~XybFVLBmwgHU)&Gln^|p?{~C2(0ue$nG9*EQrqvWd4+y>_bLw3u z6?HV2c#p+|)1E}*X*st?BIb1_%URvJAX)4WxolYWgXhr76&FF5&6FfjyZM$`Cek&8 zw2?z;i6FEokiccK*(uLRKBKaB^ko~PabiR`#6Fb?hNNM@Lq~N})mi!x^Xfe__?U>- z0A1wv=q_XRyBWRw=pzM2I7O4H>p99h(MPGK4hH>9Y2roocMKaEu|`tB<2S#@dUh!I@ct$08jCV|KnVNWl4qo31gvW6RKu5dCZtA#}cmie#~r;0F=BMM>gk{{B7{ zD%+9S40_e~9-vnD+J??Kf|!k7P&0pY`g&dKdCyJ1-;;S_PwfyJ7Z;%J$|Zys%UaPp zTu@&~9YCPt`L(HUROOfoDbc3#zbFYVHw(;fmu{>*BfNtG>M;S;>k1v;LqEw?@2#!< zA*<0lLwa!74n1*kHSqE5MUtz8#BF%Z1#ngN2&n_xp8jtd{-?GM;WFu_)Z`3Ro-?zZ z5)=nZKw_N_%NX@j_A}?wuUNgCyc8)q+9dI-KmNDjl%U=dha_Qgr8nciMh2xw3aDhA zxLII7G~C@w00`xDcB(_YssIvZZ;3+^%4&5UU+$gdC5ZUwohZPhiD*WEK(sVKE@xoo#&QvSfWCo32w?C1EJL!7_uy2#~|ZiNrKL*t1)d>!mNQu zSC^1l0c6vyW>^ND2et+vdak7V6Fi21#zESIb_C(dZ(}T8OW*FR4_s!w-oYg-hvnUT zPbJIE+A;1%rkq3n?19gbB z_O$rr&Q-7WB;~NiCQqC%nC5FwyaK0IQwgq=iKWT3!Wg+(xc@U>juQEsCdM@6yM@38 z2mo6wXQ{q7B@*lVLjK#DU%?XEefDNIf)?Ds&spd;Z`eHw(+Xxa9q?^{f4=>Q(&a?d zbq-cGcqM^9a^OJ$qzL-jbDAt$?`orvg}+ZAW*VoN6Aix36bK=h;mXlwOP_eZfB4(ulFD zFp2oJ_YR?tGY^TY`CmDiO4RLYMvDR`iawn$Qf5AH1->~0xuV;Z>+hfIUAech6<8;B z=2z%~o}#JQVp_?peYF#hm_VL7$iY4vW=I34@n1hl`En2wZLE$xb$hpl%U-smAoy6k zLyGBIrA`AoOKCVIT^RB8XR*_V4-@uYYPk4a&kf+&+Ga~9+7fPUsPkeJ;44H^=obZ@ zj`b7Y`;HMJWV9$;IH$;qBz#Dc5ON3~%mxLVU(#kecaktT1^NKWWlfiQ3lsa<(?LIf zO^gBqeE5MS2@TMW2@O#1nc**AsQF=ZGuKWBwbvEt5YUYH6Rmmi64OR%c*BwVOX`?E zAmB%8^|Hje2c3^6yiLXb%zT6-ki$|}y8|u;r8Lnl9VBL}ovAu6@;f$?7Y|Lqd*OZ@ zsY-yY1jX>Jy@{5WeDA0vwQo(=;AZv^vWvwJC>6ooodYfYsHgG+&1Y-=aGK!M>1(SL z4ArrwXVG|5p~Kb{SX1QIghuWaI-^(cZVDgZ8X33`DySLkHol%>V5<4zwnD!hirTyy z@cIBCRI~sTW-jkFE6{iakpE#djxxIrznHD*G8#Rj%Xc*+=si4^5f3 z#`)AXN|b{W3KoAjH4MY#bP#di6_t}`#;CN?6FM{BeH{L94jIwKMSw4gZZ?B1W6va* zAw_DEaKDEszs8&MZF>7*e&1|wxmzC8&wxO(L_oegA5MKIHG`e9tB}|@Qu=8eoQ9}{ z1VnxiV$n+%wBY4gePw~rgREE(#sCE*I8T(J58=z`C?2};pErN&$fGlK+I)QkcklN) z41(TE;2?8=5kgu5co9@%yBXxc5ewcf^bRuQzQ)&@K-c~qa{A0m^A&1n79U6!b7;1| z!;fQC2+eVAh4|=?Kr|&GP!3>N1^6fMYGnF!eg$Gq4V3gkfb}9jzdl)qUO{zbE#wWK=5gK;W(;@Yb1tbCAJhy?j?4=Kri@rxQr81#MxMGT1B zN?=p6ZH2Z6i_UZvWWhjm4f64TJOl3ioeT}~JoI8IfQ$6dc?F%x20Pmw@!QGB2>^mA zdJ&9#>eL?z@Z4zmAWeIzvWe^W7bpww} z>9)bLzQNhZfcg9g4NiH#A3BnY`w6@Bi6$o{|JU1#Na}DnMF*L7c=!hDpg^n#boBJx zh(8jiVOfxs-cL(XYJvnU!A0mPgFtQjYPS)*VgPaAcxYQhHWgq?kYWczN5r}XQ1`;~ z6^lzShf`QNF3VS~2U;`e=p&Lp4);dAGU-7`2f7QV?UqsFFcOLlc-Up2!q#wgEkadH z%t8%h98Y*#2F!RNrf&yKT=0?r1>_|MHv`6_1o%4~X~Dh1G3aDc9tOizg+v$l($u zISP8!wKX$HUl{yxXUOve<$~Ujf@IPINl)KY_MBH4ulh5wjxQS6ZAi}_J9_MfdO|ys zn*X8*gEbF(|A~)Y8wX8sJsQdw4a;B!7Ah1zj^5z?c)}urt>)(;Yf|NF_6hQ5*Jwjh z8=;;^u0137T!VOP<)To{jYsXQFc==Xv31cFub)jO1(%!)lO-y$@6hmUWfNgY#z>r2pZS#FabTc=xM?waOlCCsMD3D&<$NuhU!g;5J=wN`4hm%Y0GP%g!RUZF# zXzCGV?hQ5Z)3N(8U+e{)3*TjS#@tN#c63@?F<;dw)P*(gT2Js;14pj1N6J=m-37Yj z68nNLr&>H{tcq-ypZd<~UYP(^b>)>&Dq?WzAw9Yd|?PZ|Hd*PdG zTCT>WvN^`$m2;uvlA%Kj1ItkT7;el9NkD*>B7MmQlvu9#6-+G#!} z{}wp`_aq#ll{s^2d_yp=WKQm6@ZPUP#5IzO zA}gmrbjYrC)bdkvx*y}y!lqf2q7R_=tk}m3utMM8*~i9mM%|n*+MpUUaINW` zd&maL!cuAz9v-eGDfvN$;shA7fzT@F)XVo=#sH%whn;aP2cYL;wUQ2RQJ6qtD7cXG%987xl$yPNt5|>e*lzTNUWtg>B0ix z_S>pGmsKm(UgCL#lZ_P*az*l&ub5CxjvE~)T(+-rHK(@pQ_Od~-=MUv8+e73Z!aq| zt2lr8)kyx3Y}ayj8}e?i0gTgxy>ABjc$6&rqasF!O3^k8<&8D_aqh_G)17C9bj^!x zKQQ`SW-5QxzbrcV*tor=Nn*B@OOxmWu8ut5bpsoRo^cJUh}=$A(<%8EfvV z(rxJ_uS0JFa>aHnS<~hO%-)PRd_>mY;s#Zu>ugiuM3i&riun#T3Hi6Do$Cd~vcviD zt7m)X*Wx?$$j7w2xP&{u9we{ZvYzWbr8?rW=0m*f^iDOEGvo(uwnQ}T+tIA#FJJwV z5Af5Px(Rw&W~Fq)K453hQ`fbUQERbYIHkSS%iEFQnorlpFG>I9t-;B5c!g$nQi^W5nAT2jOfKWfSUTplLDCiB zODWIqxZKx@N|wf9s9$O}OB_8kv$=Dl_>!Ma;iZ@zT+a!1TyIR&MRoPe8jm3nyhCkZ8)gKl<{v`93+BYR&#_L2W({T|{I4C0y zsGOoSy}}E#>C>k>R5eGd{*VmBz6d@sZCBF!Atb{fX3@)4{jN;=$uq@6p$~W9?Q?Fv ztu5Rc%8+#+9pEk&wBe^?UXrGaJ!R!AUT+OjmE6=VBa9bYtK-Tk} zKDAkH$>&dbdiMa_-3HYb2j@@ZC9_IC z^=$=F(a1HwYo-<7yH%=NESC2{CGlzd$*Fc8*#SMtOdszO4yMl4DChAl((1}HJfD-_ zeT?>s(^H>2NLuGv$yq6WiH9`OP&sw)iw@ikr!wXY7whypZuh%iJ^W7h>Eu%*evEx# ziNv((V&RH*yc<26^MRj`fnDrqGvaby;#t@vW=G%Rh52U+bNS)5!le9r(@mYF!%mlz zhd6zGH5E>DiRaw-=azJ>+(2*lMrYhC&Oyvg-i&);;CQss?}bwT?ZGJ;GbzR6$%Ey4=GdirKOmMepW= zS1*G)!Jwfo=%+$XPEIgDi2V3?8eTm^CeWV%FO*8`8ow&hl5KI|;vY#ehZ>j!rZO^_K=b>+p&Bl&K zPAe-u7JeVU#+@=WYrjoI-_B+j8QH?Po^+}1|Do(Xz_IN6|8a7Y$f&Gj7G-a;g;G{V zHW^7|Wv`G*$(FtM-m-Uzlsz*u;}Rj+3IF$b(epg_^E}`0|M%@U?&G*|UFUUP=lMC` zpZ9o;Tt|iMzMpa%)3I1Jj<>#;zD+1GtDMkwycWt=Ve!nGx=-g*r<4O-W%DipbLTF> zzL~H3P5Ga9i+Hgq1~Oc|WfCHi*Tmvj=c*cixaBH!KEvY6RxHCQ_jR%=9itv~O;^s_ zo_o0eRMbkLJt`w#75_=sKvPn}VNnfVaL>oCHA+W~I=8Y{`Tay6YPNP2fU&<};hFP! zrMrL8!&N6P7Ukqy2n7ZC7x7Oji$gUrzZh;Z3)E${4=lgYS#p~El=F)3!k`4B-2R)y!oaMuc4J*9N`ME3Mm<`U_EmyWMq zZ;TBsWWswC#d2YfW=Ts{u-HPGcOK}8)!X<$U^TmsatT}@$-=aX{iNq(AmComtvF=)aRN8Djj(@<$X1ZzA}{;nmBxTkQbg6`JOOjfLUBEVMf}~cKiC! z*2Ztu0>#e$;FCYgA3P}}L>+GFdmc2346+DoT@q=vfN#|3!8!JwaQP$CKw#i=eAFlNqg_Q?wJ0+s+NQP_9W*~=$bvJm(!$oC-l3?LlT zuk5zNm>;1)Kt8vW;zOefoKHZSq{DsyL%=r&rad1|<4Bi3#sw9N0+{gM1hK?Ir;+c7 z9u5cx!W=&P!>s69^SL9q6TrT1rKFg4nJ^yS=3T6HNRwe0anz1GclcBEQKgE+9HpbI zMVw4|_P%__bO_BD1)cw3vg}<;Vb))j9-6e=3;p|;euQ>rI<#?%KYda=t8wZp$95HW z+A0JHtn|mkJo{4a<@A_`2wlTFWs~iiec$|tN zO!{t|&;b8v3gK(Q7rQ@bQ`g%wJYL`|bJ%!(jnF*2@$SA&wxYK*bsCj9?KkD6ADJWl zvEk}+kJ(-tdpJo{rYrl@T(w`wH>(}>&bz(p!>jT_an!)9C-KDdEv?hm2CJdr6f??M zw|s=J3k`5IrF^90B-K?S^a;N^@6P#1Vo_8gZnn~%_dN9?$(%cz^LVrz5!#hDL zRgIXk+P5R9da~z!ta;ml3~zU7Rw(9vH+;T0AQWnInWSisjkNc*z7f)PS_dT0Uq5AY+k4NZC4MgAsxchbwXB2jK)i?DgT)*#a!dd3G z)<-=L=qmcc(c86c|J|39LfBY{O7%fb8EUxuD}1<|)nMay7P{&4x{eNWlSk8hj`q@JJH zXwB;m+pTi$Uy!SfY^YP!elho^Vj<&{Y0^$GF65(wX^-+>tL2FJRP-jbCXUwoDBgwS zGjg@7cf0mYx!t26wmE@$n`kO)vsm*s}xz&2{Qxy%uSo++C$=38P8*zj5_oP z372v3E1k5H&lNM^KOtCkHvqOHmDR5c<_6NHERaRlYq$LJ)U1eH?)sehe7B8>n<=e1 znb9W@4xdDl?zp%O*KOT7YC4S~kp&TfT zf#VKBkTpL)C$>%!rD?v|Ajy3?#Bw&;d-|O8q)?b~QSaQBB+s@j%Es{`) z@f$MjH*M+pr=LeY5afJBGf**7BHo&#&Wnn`Fx3fW%qh-Sm7uosY}9{3r_`8EUZc3t z%T2HF9BL24F$w~+F@;X4?vTd$`0LQY%G*Yne=DS7AB!ls^a2*;oapMAg!nWckI*!| z?S_Ph9u=^g#obM(C8BZ++M@Y*N8fg{H`onAWW0~l%p*t?$ z&n8Cym5OvzRTMDhq177q$6 z_A~F5k8Dn%B=X>Td8nptqVQ{Wz6-1R_Fld#MyH@jWLDrOR|^4rv6fm}r}~QS-W&h& zZ-xy5)Ez?|t6MA_`LSUOGn+ z0m;^C>RGCGki&;cQC zDU`#j{?upQwz%(7ldrp}eO>U`?K9FWj84A^w$D zz3fvu{^Rn27xg-Akaa@^+AtZDVN&}BDT3A;A}`%=a~{NefrD*kQ>z6vXx0I<${Ueb z>!kL40Vv9Pl}^F}#OgYg;Q1ujNjX_%Uq?jxU}~#mF@kEjbh1>0K_*A~Uib>tgk&U7 zp2kX7ud_(7*+`)!j1U%{h?H(NCUot!jJ5b6g&%<#b-_K0{^gRdb>4RU@6twXrm{b0 z%|E=E*|O|85gx6a&`+=NJZMvhzUit@8+Zk9EcB|9Z`d?MJ&~<6Ye}?ZAB%xCy~Yv3Zx6|)p4^c-F#B{U8DGuE9YFumMvwUxCUev zyWbgHzUZ`M>*i4?QjVy+FwrO&4NHS7{qS2M+Z;*tp&re+xCYi3Uwu+LfPuE+!a+4n zK(SF8Fn@)N7a2Z1D18Vc0GRm-e!H><;|2glJ*u_>&z%eeG3Iike+am_&@0gcz>;le zkdBH<3P=hp0g!Cl&M{GQNY;b_B_-}-RPycjP!Ru+*Q+e9q$}}F&d+iokT>Qz2JQACIx{i zbWl*7=a%pBC*KXYxNl?k@_~_LO}-NA-OpJO-<^Cs#r2Y5k(66HM+(rkId@tLZJ+#< zjNxJ968NjqcW|U2F2^~~40n%V(MGuEy97P~8!1;fkkoKGrw+c(8{`RJ}qemzY0w7NIQ z3YnnpjmIW(zsGZZOM*6?p?3&%`}pT)yeBCKMTB&okBPjOgeaes5I=qW;&a8CY|~JV z#TbUTFDV9n_+|GhOS|I;=PjO8*elk%<}orWuhQxiU|KXLue>wwE(b2XPPY{UK%Yn%`m!Zq%EW~v4r@a0B&*+B<#i3J9q(`E(ZU%^j>xGw}}|f*RPEZ4hl9wcvCY~<}3y$EDOfN(yV;&!wrmjDkV%8$Be`Jqp<=PLrHQ9*)I-q za3~ZQzYn*w%-woP;mXQZx~Qz5Vv_!Ef@fiipxZfNYi3+8~ba(q| zGdR9|QFW@79^+*z6n`Wbk~M=D*8t&YH7Jnn{OPXq4r9$Pa}@Qm^CqokZd+9}%nA)z zunra7l-Fy|p^|WXtO$dOfxThj0IV_Ln*_htqCT8E1^ubg2;PM+BDrY*T+*@6Z=4u1NsE34Ax`e)Xo{8Z>$dgQ=bYV27vw@SI&uSk^H8_3+G78{8`G5`V6O9+ z|E-yFR66da;={}at9yLeRsm{=H1#e*KXy7 z&8-yr@kNTfn^x3m&`9|`AH3pdBDzv9>gsTFjx56Bu6bfKm{0fNLvT3=Ql2cw+cY>7ZL9Iw9QuW zd3mJSYM?-w-%wy|{$+K0?{Jm~%kj34U?u9X8p@di_dK_6c zsp;pO*W4Ny+z-9mZ9*3Qtw~c8SzMK;AEsTo>>%>+?g2|X2EysIZ!z788~SUJ_&ceWT?9H{MAruJn%Q_ZvUV+q$*c50fv zay@#m+SS`aWf;N>G*`w=Ir$%+2BZ+JN4fHuEpl0d$Y=CdRZyfuz zj)iG$cu!D(?bd7h%P*o&kidjBxp(TfkY#DR&cmp|2b!)KcOf0I^JfXy{jR5O@D~uxQxQEbnB9ZmzZwV`Ax=g(L^S!JqyCHU_WM$q0E(1zigo5d@&G5n1>Y-) zW_78tuYT#lJR91Xi-!8Xu%7~{Q_tGt%wI*RgKX+MA-64$nRyRBL7O;h-ASzoT$@WSKC7da1kXG%EC@x<3SI zonZEMBS(%m9+aulii^?2gJWn$(kFwnz=9P`wR($(LL6wc)qyEU;`*i%C327v2V>1kx`{PE%S(?+K30x>KrG|Y? z>Z$2pI1~|QIqnLkm#;vK`7K{_1KuCR9FUZO)JdA+RqU16K z_+La`0nx38MhXKc`ymuJP@>R(uNEX@QYmtu+5RBeH{YHvpsy*3_ioe+nxfRcLekoV zDB%P)V!1wc=~46P?igftqFGlhgL0N1XcH3>j@C@YwNKWsU9pV8+F$hy?>FM3)Qcjx zy`b(f(3squds;r{4O^E=GK2-cHWs*^pA17z1ma**5CA&CL5vWOkAeYlv8KNwGA z{o~Z-L&csUY#fTgU&AIhFL^reNyQ9iK8KBNGkZN4BeG9UU2W8akCMdDCWuYwaDVIx zR?w!ffatALXWsb{U1jBA2r;-=$0jhIKWtO_t1`!P^Cg(1osqAG5h+t`vD7XjDKckN zsV*IYA@2#S06Z?r`*=Ic`&8%8W-lnCZrxe`XxQ@NB)8kDNhU^GmpKjexN8lx)!=EC zhMn$`Byt3f%AE96RgJh=tt0{-Y>K;LL`h8Vay_tgqGI!4I|nENTpzLSS6g4m~;70o$(d=1o00oW0?X_vKNaHB~Sgb(D z#PfybpKAf60qO2Q+Tf#itF^}cKZ6$Il~EVc&s_o?xq8%MT*0@|q&xW)B}SA(Y1Nt! zW)Xm{yJY#b;TlH^SyfQXb6TBXhpiA33x|oLYyY4qwj*AsbaWO>Mu4;jde1tc;Ymq| zpfm(EV%%=7&H5+GcKQ=MFey8zoP7mt6+3Jx=t8VI(Y#jMvpZLQ>J(m&daEK@!*^<+ z`U`O}JWYtKZq3v)dJt0;LaPh?K}f>a^z4L#b!*Lj2?D0N_8tgoz#x4EK(8{p zIXSE0Vo5|t4v4I}t5`|^g9SyY$-(ONN2L@FFh%1v?HT|x9yd4jwBCd^gkLc%CJSq4 zS$IY-Un{g>cmw9$dch3Vh6vlY4&;rk;fTmF5RDb&++szX3lU@(z`@+81%VldnYfknw>s(m?u#ByDXOb3E*q@^Pf2<{Xg z&;o(Sne_7=kQ#-+Rze%(KCgUn26<*6wgU6-u0vZAQDBz&i0?+`Pue=KrE5fAuYMGPfFb(?Sm&rzY~HlT+02y;~nCnOxP(Md~6p z#Ik+Bw%h=f-X+9TWz!4M9tJ})#Pt^uCqVkFAgKh}@>vkJSUEVlq_a*aL6I54aKncO zO(NLw11G1Qy^{dNmPN>|2&zkO3}iWyK{a9lLHhvpP|3v*kb9s4lmiWa0zDqexGyU^ zR^B1<2r&U8X}W^YC<0iY*#?cC)?<5{OIg5$##rhGT6p|z6x=J2yqL(vQq&qu-8hmq-ib7S z3K8uy`nT4vd5J%~j5}fxdA(FyO6LKaRKLK$2nK}ch|KEYwjuJ)AkkXZi|4& zI)g?NdnwuKI?cdz1|eyM!;VziB`l8!bAs&%Kj<9Q11A!p2ZIC7)C<*V_K_FrPeUBh zR38H{Py*nN5h6{5DCL7P5)xULpqNnu(smGySZ?h~jXcsIy=wj<>MPX+`hehL%qXLE zQ~+>)gAsjg#DfzFy^k9AE0D=5P~*PufU~bG+$8f2sop9%R?E?l$Si>7glm4U^WjQ7 zUMcYT>py>j^P#=0D$otU&l)t8X5AVo+-KO2cBURRE^H@Yu4CZGDmSt1wOwM?7^h)$p2$i=pXPx^%j zUizAJo}-c5PSI~wQ#wmBvh+rSA&@(kmbtY38d-V`FSVtnE;lw;cU&)34r4fjW=hlE zpv%v?lIS7@-ImdtgFMs?sf(e#3&dejtjHraC9B8dhF9abl!>@_7q$X}Qa?X)8qLOO zt9g!`8s{bA#Am=gPP#xUsz1nhOqXd0yyk+3>^F$xZYQuxq%Y5`Y2$2KWe1~)7$4D=vo&AqR}2_yQbV2bqm z)BU~?r6)yAZ{*lx-GfG3d|Ycq`9l8Nxr59lI7S!h(0vWZT;?w2K^ z)!ab=1@p{q6b!;gNXg&${X?(-f075UNb_)kUf|ElGL^kHqtF%c?#)bF!Ls_4Ig zeixd~6Q^cg4w3j$$1w}gn2uN~RBeiiN(~wuFlDUQMPvfKWF+al89u2Rg)jhs?{PJn zSr_=?8m??(ATaCfs?l^BPF(L0hPeol!**PHc+->w^0P^V5a)R-^6kU#U!2|hH@8~X zG)FVPC9{Y3VP|}=m(0XtAvx3RILN9Qo|oFVbgkKzS`+gm3&#rf_9lzpD>u?jyo;n~ zZU}tL?0BQw#-wN(E3mu&T0prb#j5Y?zPqUVu;;p>U6btC>ZjcRL-Lz2tc8D$H?UJM zLPGDT5eqz=nz;qq>esKQ7iQCuB;E~ap0>OxIV{rf+CL2tnP<+tu1S5SY(}y${OTam zKlUME$}8j_dGAa6rcQGHOFsr~uTXyZGVXqOd0*FX8DH^D&#<@#fa{FKz?(^uv`b!NZwfrfOqR%>Y#zM zb0h1_trL>2TkdTo&dP~mNh0%ARR>IkH?Lu*$b)tK31V_`)bUqo9)n+;B_qS}dgtln z%H-Jepwt$`Jb-!**sMarlcggHdU{kqrntz*H!wJTi(LhdXZM{t+_XE3>hVeVsA}V& zWhW6}Ni=`>0Q`|?v24N={GFYh9*`r}^ih!mzx1&>?Tjs^?nEV_EyA`^)SaOE=Rd#i zjAJw$)bqa(yu9 z(Y%h1z6I?8(4x3+YAVtlBkmy#!j!_$I=%-W-fENZwH+9mg}F+ka))x11X@QQ#yB$Ri8-P+Z5j9?+ub&oh1 zRAs>eEDC3*@Uy7+JyDnpG)+!Ux^`8wk>P_? z)o%TWB@WfBUx9|jpuP(`OVB&&d#^{+{_)TqKfd;@R8gez^{lw7jfb9Kn$iIdX!2j2 zRuVnIl${^(7wSdqc#5WV=hBcqE;9;NBua49mO0}d(EswZ4vq13bvetKS-~(0i^sKC?g|i?T z%neT(N(hExlu);-^4AjBY_Wt*Y;=J4xaPD~ZYJjy<$9XE( zU$;j1^i;>KmeN80XJG%k{uYaf3#?E<{hnN>f^C-wY<=Wmswk_VkPhTBjIStEDfmMn zaR39v?E-tv7`VA#gV^aQukdgZzzMa1uqh@5mmvm-e}kOcOVHLoQ4Cxa@M?>{G3$ki zh17YsWMys1l7Oo9;XY3zFM>>18qg#_OgRz^ z9nX-EG(!Z4M}go?f+(0$gBnisj~_OOSRCkmF6uc#=PF1Ka>4*wiA0ED0uxTep%yjw*m!Bof>LU%>yafsr&9_(@bQYzCJ0M$N`Kv=8s|H;MZ|+?a&un8jtpb9l+b$Td@1dY~a-&>+7@NBx+}^ za0tNj>7}J5Q4~ZO6Hx2z8oUK&2c2*S<16=m{dxns#w+#P`jE=1-7|K3q^w7bL+K&^ zh0Jh++4ioK}e8c>&Dl@W;2WUBiGb+yW?eFkHwPD# zw-3G^ZE@!Y+dXhw_`6nqV~6+Bv#n5SIDTAMW5X8^+4)6bHlDmeg)mUgoXNS%f}7Fi zhcEUVQ^7N1QuygX(6i!PX_-5`KQUh6aZfL$SzSRNaWNK8Du+kD7cULdv%zGgnnJ6S zKCQI_QmZ(nGT>xG#-oNll!&)UC#^RxwvqnR0=aeZJAT66u@X#3yq}>&UcjPbMDkY6 zp|0matB#hdWVFrzeSn4!IxlKwR3ny)ASJ?Pw~#!~q|KyZViaS%NQ}N8EGgvoZ$eW_fXdeT2$!QlTe>ouU?#k!(ho z@??ZsO3=domz=P-Q|*@#`T&)G{bV5#Z_hb$Z@31PY9`V$oz>W1Nv(`i{(M9>d;}}U z&l4<*#J|)Fq@(Y3VJ91fl#B}@cFY$qs@5WBKbKg}?cwU@6Q=Q*USSX~4gDvMtY^x( z9o0lBPj(+&Kv6Zh>%ItfRA3D_`eyOSl|_a0!j)3jQ@hOn{zSI)(FK!3E?AcXu0=8( zTdXu>W$1Ki>G(ugbpHAv-%S$S8NWgX$>1Mt=!Lr`m+N6Rli5a5a(d!^RR8nwrqozynw`y70QOCv&LSR2^9Egk1m>;c0Cg=lqrisO74>1` zv($H|$2nucqy=1*y>Gn@uwP`L@8dv&o9&Ingak!sBF6ArXjG$+una0xf`__QHb%Z< zS8m6D1SPbXtB+`)gLZ|L)gQvNik8a*v)TW1lDEz|+DX!VD&OqRuhK`HWg{hIksP>p z%1<7x;jtg~ju`6P_nL8G`l~W6bUDm-VPS#iQTxY_Q$XvP0!b$$&~L=(h~f3AsuDzO zS6&j)b_G$3XqB0r0qLq#XvbpI9UknRrr`2|th%qk<1rbheg|ZDLJkYWVCsfZ2YlXu z3s-~4^o zcIeW88X+}ksb67d?{pml)?bNE0h9)U!Qgz<2QsGMNRIgy#N^-}*^@oTfV+7GG{sHdbU$|5bXRCd>I}I5lZ-YRi;4_%*qRw0x@cW z`b+lq?Rl`Vp9lJ}DI~Db3YVd=vbMdQ1vi6ng`AZ1hPgQl#-Cj9J31GIx(~gH1ai;cIy`?)u^Ozl-x%N&CBBK?5a`Pd-eKQ%G1XP zku_n-JCOt@IyvCR{dM8XO!?!m+^^b;SC0y{f6W>FZ<2T;_7m$%knr|^&MKU)cCjHQ z$TE0TZtnp<{Dw>9+cV?H#XP3&ne%@u8@m(i;={u3EJnkb zpg?SdUR*p8gy^w|si_q`J;kAbVyy9oobfb>Rl9bGzOU3elX(;jgI~Z8u))*las>(2#*Oo=orYN1{oO;u9pVi zY)q|sH-5+#yHahTjzKCFtScd146Y7qN4GT(1Dd#6EKRd!I^_XE(+8<86ao@dydcxj3W_kRT}8NQ(m=JaB&fY zu_G>^=^P7%K?Lq5XwAxjwM921e)w;JqSpx{WwXf!F$^d?!NA!UZWE}47uhThFe7Or zymXZ;pYG3zx&tWPknm5xY3G;)ebOro49%`dpn!}eAt7O1^X;;oy?r(KC+&dD z`HxMpJ5%mpY68{wyK2gBpc60u-D6>CsU6JdszCVnJf9iy)2B}Z&hx%RBu*<1Pw5rr z?h&8h!)0Q@WoNunK*OqI#K-V9*ziuh%aSh=Ze7aUY}LhKGWvb1FD{-OLAX)SKz{e`H|X=Ac!ZS5KiL8uBf7ZZ**_l7X4pl%H#B9;p0vh`QLNvseO?| z_USX*Q`~#Ra?8TJ_sf1(29!#>bcOVW&nSNT6IXSWC7IM!^@x$ZI3E4ifzz!ay%eNJ zvBp{wc0gI{hBP`pb&HP+Lex_BwvrTD?|ac_{Baj~cc`Xvppf?sX&K&bY96;y?)z%g zNBiq`GVI9dRnim-PcW&QQt8uTkM~U)Wc$~`%WcS3xFzJ@mQF@+KF}(g{wVi3+H^~$ zwK9afWs>jva9wQ-=@$yR@nC=+-6^vrI@)!ScNc%M?HaMi^{@vTKSbg^D~!fCc+$Iq}hEq80^dL?{#s5xrh4q~4J7#JFM)FFRobnG+qI zdSx2=5EuHdp0*?Lejy+-uXi(wtK96PnM3w*cg|VGBCOhJW&9K941a)?^xw|+(-sC++8SbtHI#|si0s6MFmkaj;Sp3QY@dxwcWNa*Zjc^*87VR*qZ-YVEZ5J1pY81HIgu>E(4oZrF z&@X?J`96g5K6{z5y#jWAA4?iW;In-p7Z#s8BS8h12@~2dlU-+%b$nIOseNwI2mB_8 zp|h*22H#x4-_#JI43x1$4!ElC{c4{pZxR~KmI@=6&8LqV+sJ)(DwgP|k=Z35NOZnH zj@yMECI6+Agw$IchwGPyRr@O$$rkLC2sL|}&r%|gtdm8cSFi1*IVaq!fbgC>`3-bV zsw=@R@g+E?z5rg8rGT#Q7-HYXBH>eYyUZ~r81H`zs!zr zsI!W-$pouMRB!#{Q3fhojg5#3bzTY`H}zSg4tgf?|kuDMQGee?7N)fSDjC1;-$ej7T;s*13~Z-Tmb4fFy0^9pO) zT=OBSBkd^=uPTLfK#q32wbe)RInJO$`V3Etw2Y$q@bh9VJ(a6JY}`1I;zN6Hp(mE; zHu~mt=~ip*fK5sY*j8i&Ra%aOf*OwIw|BJQ!478Io$JB3$EEc7x9R>e`~0z&UV$G~ zvUv*!V>wOQTwD-+(S;ttMF$+oM~H#lAcq4GQDc)^{w+=Lvl62Jx-o@BYcSzUhxrSH z<5Ow9S~FYF2mEzHDyl|R)TdZjTIRyZy>n(8j6*sfb1YjwUtCV59FTKIKc04;ZS1&{ zpmvKSy5QNpFi|gp0n^(iL#`i4)e7ed8lcc2YXcEd88DzK4^a?v6sMMY{_a{-W=j5- zB*JSx3&c_<0wTuc(cgJdwHn(9_B}|1AXW-7Fftldj#Y!ME@-!&e)mp&Oz$@c*vvyB zd=DCo{A9%g^}JA7JQ{2B*YOs?Z+f>JJK&;sbaF;=q~6ZswkHu=4A^bxnV4Q7?TtEG zQ3$@U1`U+GX537n9&+;`p89;S=3X&Rhbd!VePKA2>>|1w_!?g&caHb*mL=>L7GK|G z!8QnOZ3qoHuUpRz2_|{qV&1!e^X8{7>&|jXd;FL(dKtXhV;ZC{8(ZeznnD~qhHITU zVMUgi^`;J_BF-GyC8*F*`vz$l>g^o;GtB6dbCm{D|Jh8@LavN_CR&)n|AoQo74Dy4~TE~NRSL|Kjz1e{s(76j2{NEW) z#XV|ZwylM3ELgC>bl@xn1(<_K4+Bxd*B)AqU_gKYi|ntHCwbjA%m{%{JQEM;6?pr} zYiUtH*9htCz;hHOh;*>^z(@>U3Rm@=_o;K>=Ppq+q;3%3{b2+B^=A&?UX_=-{(ixx z5%$k2C8iS8{S)9BO@KjqiPN$UG~3P#SW>{eqRSq%;{IF3qO~Au3XX9|FB)V!OTdLp zz^IoFclMzGh&0^CEp&V?JmHYm{Ef(v}&2M8M=EGo&tx^$2_!Xj{AH@;|wqRpT2Y9j_lTJRV4nTYi}+KCwl|B>-( zmxNbmpB8-iumQB)!3w~;tgKA+#SHX2&BdG6Ltf9TYJ?*Vkp0lsJ1CLAlKsuxefQP!($|t_6dG@{H}j zmpBTS&w-c8fNfgug1{p}CJ7q(lr)iXx}L8ZYi+x>mD>peqJJ;*vS2iDv$|bIzUS@SBGVV}qb>%+ER+y5>Mviql-4W+yCO(8wYYZ8wD`l2a047gWb}hY+B!K$ zourN@gD&B)nZkk&0k6ff8t%Gchq4!ft|$hM+;JxyudedB_|JDwe;f z@IN8XK4?JyvuAA#AT`S`H4)JAJ?>d!;Ns)Y0*T@)JpB*AHxrB|X~#j(-C=ojuzJx9 z_Qq-`OU_GpibBKT9w@aV9c-wvd!g5W0aM3?ft+*D+nxhYP(ygTC}7v%6%*_)JwKEA zS0oT4&+OW*Il}WEU>ou;JAm3_TX1wD6}N!_6ExF};bsH6@i~|<+aQi|njwI0V=Z}R zx(1emj~WwzVg3pP(F4ZE^^lN$JWYhzz~%qFqUqm6^fF@rEoRT(2h+r;;k}-rp(s#; zwE=N`9*}_rr!8bl1s$wK*ZRU=7mMDi5aayHJ5K9mVPA(lXms7P2P&y`Xh)o*rtU=2 zW3X?tp9se0y8kf*4@E_J8V9KjfoR$$c7=}4D~8vU$9}%UuKN@bktyuoq#ybK69uku zdveBGB-k$m@?Qi!c}#HrsB6pyk0QW$#aB-vMxUonpH2sXR^+Av%rDAy0_iMFbkp;< zTc3<8aOh3Yw0Tf_=D4vdDqoFF{}#?|7i@Og0R)J6MIavvR~H&0y=4#k?N$*9KXr>Z zJlg`(#>sc_gAEKPmuFMF2^p>1Sz{$|4S)6@w-1$6ttG2KD-yI1B_YePfJeeW;Gs4OCA++nHAO*n1cW1rD!$@5A4LcsQ*_qgdvlQ;g%1}3lL zU`Ue@bk%A!9MH}zVu+H*TM+n{r%vKF#sLeF`}|GeqiS_p3i>hBQp=J@-Qpa$Usxwj zaK&|I1g*lb6FM7e-`-7vQ2_$*gqi1x=oZ-H@PIWWz~^jersb@-NF8z6O&pMltB2;O zL`=*Y7xIStO8~NhY`{9go{Bbg0^<-waM8MI`X!u=!Qn5>+livGQc@?NO^AX#(iCjM zVDv)-U6JvG6QI@f-n3u^)_jA)Pue>cRy(7}D*4 zCS6LK(hr#afUlS=^gyJIjObyFXF{Kk|7_hr07l~swEj6+pprw9#OC#IU1At}zk%7Z zCzwTp@vB$ogEW9}!UkN{bn^F5nRmBwKTAXr;WsuP7e=t7{|Lfj}4TIt~vFa2pcfKWdxPlIoHRG=3u9 zkvziQrY{4`kDKyY%<9DR^Yd>&Vjrfp*l%I}_!QitCRU(_fVd0YWA!U#ymDnoHCt6T ze(ZMmApOAcx(im%rTY!o!(GS=60oOXptLYv%?r&23`l&>T)5CKO(dpP`C6`knPaOh zR$5Ds_)jT_V&*6O0pqASaLZ+~wFJd|w!1aq8S+s`GeuC7hP@s1kFPs9IYlJ8gZI&> zXA?p6@3u*&R2N#Qu;Y|5_)ad}c)0~REINBnT4G|a;O?0IUt7z%_YB_IgQ-Qr&W;OW z|GNf*dz;@owkRuLe^^e`#X$Y)58m%TK|V1Cx~s8n>~@Lq)J<eVQaa(CNUkc1V}d7YEL>8oZPcl~iSx^_7OuL)Uo1d>YZUSFytIS4fH{3gpP`+PmhjS7R;@NTBqs?sx1D@V^DDG#X;`W9nhxWu#^am zoFvH9jkqXo$;sV=9v%q^$q(?;tGTF=!)V$~)KN-y*77Io+I}_as8ldzQYV(Vaiavx z!_b!+7K3r+80O8&N8m_a2Q+C2W`nNDs*g|n?s7QnV#l@j$CE1HL3c-HTp?-30E^rE zkYdIQJNf}i8lxvu@d7y8E%6EFTo4z>aVK!XTYjm^8u%xV>{fpusl^5b5aeQ?)!AmG z4#Y!rT{1D)0C?@A{Acf_Q9OMP!!HXrQI}W;evN+WjK8rMc$MNy{fXXWEV$T$cZhZ5 z2+j{4-}Xc~fLob5;&zY3i(i>s^9cDzbpnsB*BhUJ(dDgDye7OM+Ox<8`P%Ikyxwrb z_WM=WtyG@f7Xo-zL9>#V|HSw}JSoh!72@Bci(OZH+QnN9jF%WACC_Hcp z2_L}rOC|1J)hq=4W29t(h9=Zd6e3P+SxQNT{!vttELuc%h8-sP5naMK+ecCcms(;VwJ8ZQ}TofdS ziwq>h4|a^<;WtpkjIl z>2Igs8*EUusX)&I^Q=SnA+|59VeF9QxXl@BA ziLU(x+qWHZMST7JFVWK@11vuSEo!(tYzh14Fcedbs~2;vG42L(0EslTOC;??6JA^qCRSOgd3b8yha@(VIYXQV-ncywcv2172MenRkuw z2LuIOmXJu=*w{FGw+Y&FID}LHLxT!BBXJ4*w=!yiO?m%`NExdW@TO)FT0{z05vgpCL!^q)cQk83c=OZ^5MXTrhpQc&{}wU`?pY=OCB0m?1c=Tl z1xd3?Y0s22`RIZhCdlS;T@)}Tm~RjBou$@_dm-C9M$n2vu7de?2m|N&tcCv|wcrz+b3Z484+OmqSd;jhKs7%J{?)OY{bvLfK=M`z~8*C87-bwfd(4Qdo zE6@JmHjLp!uiR1b>AA-)YC$Abk1ivwi$)Y~wR}_X>3Ny*7RM~&_)2F!Q;v_f$1Qj< z>>u>-xG&TV6O#D&yZ|y1Rb|L(l^>yR${D4MJP%vpQlgYVJ!Ce5gXxC8sjpmEXf;pL zt;~Lhc}nC749e(ZaDxjBPiF25Td2h3iyjY*5^rOt2qug~H-zM;5*ii%Ng9#QJK;wb zQKHpN;{9h+u7<w(i%00s9m#0W~b4F4X$c4Gav=r*?3ZM#^HK-%4DdHd@>U=Ov2 zq|pw%V|!s(`Jf|O5&+W({U=Ylmac`m>E53kKB7jfaR;W%fc(5dPoL7f=I#9#zyPLG zv(07JsG9EmS+H@1J9*!LS_Tx1vj~{eMNN$a>Ku~^Km-_;#K%OL{$r;b#jo)5Gybt% z5+yjn)zi&B6BeryFF!Y6{~!48d@Z;lSCHM}aqSoVMXeIxiM@toHBz_%AgvI_%o!Wj zOCIcU23T9u3H5t@BFEtqZ2|X|yVQ{b#h`Ad=|fkp@OS(+b1UTB89_O8`I(R?yL))Z zJ7PhjNzReLUknuP6k_>4A&}C`kUzjzg?^+3|3ohALC5p)LLM|+J+yS)QY}#|^zYMT z;~@W=EQyNPM*O>bd;PV}k3gfo8VGptt>@r>z_+fgF8I^^ru#e*!q#9rJl~1ALLNLo z_@B^sWY2)F?gNuJZl~{BP#eBSP?8Wp1zmp79d184L@oB9pWW-Z3fR-GRZv(6x&CB8 z3Rp06KpLPRYH^m9cJ*&BtAVj@HT-v%`XxFI|LEF(oWWkym!p;fcs}*senfd&Fe@M^ zz+e;VYHQwUb@Rl3N3wTQ+w18)AsM=q{H%u&z|xqn{Qd21VK|P2Rx9`gAVjd<8cNiP zh6@{&jtIJKFhRJVvwmO@<+pu9)L|h+_q#t+x%5BL{>Mn!Afbw}Wdz(0z4+i@<2 zZ;q+iS!sy=dekz^!1lCWe-QCs;JuYp~Dc>2SQJ{;N>wmeN^NibccU@ zm$a+d&w8+t7l8$I-g|VKd4|(rp@$wQpE%ic4!$8F#BX1}0*W>HO)QPP2!J1lg@kzZ znmITMs>=V9x^VoItVA25Te9(`G!Sw)R74f{0MT!Shgjgjs)fbH!mson*SAYZ{PAe) zaqfWrj@@hjkK>Oxi)ZNe)tPDx7ToUF|4-8jN2;8oh4!MCs>vP+P2gG+?i%;MV%_gV zrF^b_CUqfaUNn{;&(84(Pp66nkx2T#_Wz*?#QrZ>@N>Zs!#rFtkIB0U`EIoHR$Gz8@AACwp-l>oH`FknX9&vbLuN7 zhwM3w!Bfpz=kZytb!_f!4%K|e;nNS8j%OkU%G!RiZT=h2)7$Qzy~=orNaJAfcf;N8gAI%G`kM4|1phO<2Ey1& zXpq0{We)K5wWU##muDU17mfRSkRfd?we0RaJ4vfhX=5w0?Rz)3>&t|*>iWNA(DS)h10+!LzK)1!0Sl)1 z$tzc`l!Es(6yZo3`aflz0r+W!9`obR&QAJZSGQ(Sp`SXt0|<7;K;lLwFfe&R9enZJ zTXu)G`P zqILA$o&r=P1G;A^m_f{0os`&^HrJ1OZ@20pv0*XkvUk9hK0&3c$j3Hnm%3Ah{tg35 z$U#^47l-Zcp-L1mr2O&T+izb+$DG%{0D`Q>!k_kahTG_AP)b^hJ^pbQ7ShiM^Fam* zubeaytRAk9v|e{cb~*fI(OU%vg1S|UY~kiBb6GJABR+@GT3SYgZUf%(Ku#q>y{yd) zE6h0C?7ppJbk0%NFxWaf27f))$o z+lY=9ni`effSgR5aF+DKtZ}kRv9VE1*a)QnI*n8{0C+7Pb$3}v*eV4XC7GE64H5Gq z8JRQD(f2q|kz^v(sa{QAUkdSp#!0HRQRYz|_S#JzzB^NvS(RCFBWJ^nb)0DhTP@Le zbk2Hxkrpt$DgD(!H;i98`*PUUxrqPU8<&mCEcYW3I>QucOwlK-HL!piAa~UNO!k%cXwQLO4mD2^}nCJ z_j})8p3l!7!!hrbFI1Nn)8^yB$36W+3T(-dw)6!BdH^!!3ucA=o(ccso`D7bvIQ{QJyntGnWPg@64)o8USo;-} z2L*gNh!_VYEg0vh*^JpusCU9s~U7e;!>^TMuS8Hyp&s z-4barK^F~@wHl&KslmkVPBfhQG$bnRU&Ip|8?V?El82W1+lqGZQ;wep!hSdqq1IuQ)Y5;@hP}P zfIBo5$N|)#6CB?f#io7Xk7N>RxgeSB5v@nxOvgAb>s=42Og_5664@gu^aZbr`{1H} z&Zbh-0}|0c=Ycd#4OfFi7qp;PIXEuAxNmbG8r-a5EzsFC1=X=X#3fL&J&BN&@c@%r z9|%Z1L=#WoV1>L81WN85pz)n!MNyNKZ!nYzVOu>T10!A2Q7az7peB_Q?|ZQXVNqlY zpEBY@8=JCi@c*-ASVtMwq67Q;$>sOtY<8IMTwTxOG? z0=OXGL0XfD8%MH8vebYmPVMP~Ag8d?VXc%+S(jno1N`83@R=O#?&U>V^~fY0 zjElWJnahG9xhQ@hErD zV~cK{%jVGfy-VX%ATZ1fS`SN|+Yicqr-y`^KOF_JQn*t$_T;`H#n@5lEovU3IQ@4l z;AIp94D%TUPZ=^M6MXgc&r+Vbtr~xdsi9C~ZImuqe)ugjT>4SZABkO3A4J{4@B>1b ztj6zuuV%kvs#2lo0b!slAr}i7=HGhj0CWtQ@}FEW$@d8^*>e#1fX)Zz>o$Ss(*c82qjrl-0Ae6O{viJyJR4ge2+aJjiT9b7 zH|k&VNpE5}=NfS)T8Q#@)(D?tac*jADnb<+UEYU_swa~_lGDtop@m8T9?JsYGKmzo zEQ#Z~OSjH;MyPVL1PE$ze23YFzmZ@+X;@SnB%=@Dbbm?(IMSOS$4Kw__H&EPyv>kH zb#!e)?Qgj|sSmQNzfvkm!18PcgL)rGSc%XDw!9QxAn~>ZyW$&{cavbE&7C)SP+>t1 zMZf*;OPMYe;HOp%zvXkdTY}i`tQvHFNpZ1}wkRLY3nkh%g`Ao9nM-@F;6>V;OZ-wV zdus93`h$mmmaYo?!?5C?Ldu8KbLr^L7mu`pmogNOHKBl=)?qEB zmOcf!6(y11N3xmZ6_v`fXU>>GbEFT7{g2F3K_Ll^zvoUuyQCF5*3Go9|J=D>mVf03 z6%=UiCm_$e1!Ij^XYn!Cpb55yuu{ZLC;6nw*nrd43WGPcf0{g75+I<1W=#tW+mS+# z6AI|9-g6Y3`aeM{yFf2w<~R9{r9y5(7yC3ZGb4(c!FxrF)qky)?XL3{iIA#2Aw5>5ZTwxe_9d$l&jI>*zgT@i=nWe5o0;sMh`Hv4vL1_Oi?}K*){V}8h4bhrd zvExU0KYt6kxJ&S~q%~=^%#Bu_so*c6EQeM|7$MC6LF zyg`K|x3CL?XZI2%A{relpbs$WxTEZjOZEU-&Om}err|i=biRl46cJ2AA=}`FjjS9D zmLe@#M570KrbFP4Ux%77$n^^0;0%x*pR>W*?>7EPYHTph|&kj%9uW- zWI@cTt4T z3f8z@eM?8~6dw0%O*-mR`Wx|8q*$KB5e?0`ulI7{F`-R6?x<u39Ue%pOh+EjyH$ z3u_*5RX?T}>HD6wp)_Q^i8Bxo=r&?}yUdJG(KooEfjLgn^AX1djxUi0HwEfHRDM(H zJ1sliub@{ww^$9S_kpBNSC0DCXiTSR1*7-ayYuJ*;)3gKTwzo+G+2SBDC|44!fo>g zmUs7LN_K-^M=_Y=`Uqf=;(peqs~GD`tUCHIQ&m9U20vMboq+|JH=gU^de7>D!o&|s z**M5Ow&@v{ZJ-Wq$VCBSs@zL*j%+Z*P3`zgO2u~O3ZL~#GrU%$KZQ(w=Z`trhwOy> zcOGI@kDjRv@M*iSqOU5}x3)2MJ!)lLy~T_s%~++rJwaOW=C7}35{%cX>(q4Z#vXhk zVavT-HN90fO-#O9?&D@*_+9$(A`wa`h1YmoF6}LmEjGUP+a8r|8q!!_Dq$@6u@87z z>~|U;b*b@tKPOyJt$X`4_l9oO3NDtFnqm>b*(}^(hvjLKcM)Iq@VN)ha}P8yv9$Ab zOGMq`s`B!oTpX-+99Yg6GE|Ei@av*V#G`C}_kwo%a`;{$*Is`^{{4dUq1Z#~Z({_8 z&aX-Pj3`G_aYeCZ+=fCDPvF@Dc04(waWs}p7-p<*gqrZ<(J*Y0I(M#(3wS@dGrDs9 zs2qvMM^m`!#%AMivBVRp3I(;z4kNh8m*6#+u#f9z5M9Kubt5FwN>nVMqQT0!kV!-~ zw;+3sGqs>2$j|S-p5C1o;xMQAq5^DAtDw7qsBR$jq!hIK3MCG54!sw;Z;Sn5&>DjIWdxXY=-R)7#n=~f(FGZ#B)wkn6w>e;rC*l0@ zVZ>NAG3k`{%-(~`gGEebP+Wxhp}4GI8Ukgb2KR>RmF)hPt}6sd|dEmzv-GqA=>>cg?L-$ z%YiyCCi1gpJ2#o;2}fKcSflr~ibC~i+u-u4lP*vnV^k;Bl=C_84c*Q#_ATKodU>(t zI*g!vldAVkL+wArS#AkSqr`50_fsJshF#b*7b9sYbXE>1uv8ri9OxatKBbNx>N=CkcOtFDZ~b3tpWI3!0);R zBl|a*m{Pm*V5;2k``e(`J5VTGTc_Kr9$#EkoX7+19Ws{VmI{TdFz&PAAJI!~=LR3T zNt0^2-h0en_fju?!(bpV^vu1Tf=BTysDlb(hpdIG!m9$U>r1CJC}fU1UO!3;5RWpM z&L6owM>Y0g=xpBj2EO0!;;Fc2B>QDU{(%h;?HQl*wKh85emdMsn|7_5PqZWM?MIb$ zyf>FF-P3cS!FI(&MFw1rWrob2i<-|n-S=$*9#+Un-9=(!@rmGpD!;Bm#u3|h@%)l& zwUYLv!)50MC&|r+Tx=ek8b<5ZjP(3m4OFgU3n|{eTE4>9T1KQR6S%#_`njF%(>-U^ zK~XnTZM2@D6~Fr1N95crQhM3`5S;qzDmF%LXI#EKiJq#?r|`{KxyJ`L=IyBFi3XEA z%ytNRJF27Z415nSk&&C;XSEN*X~`ZjMh8XI+3F6c9P?NdJv1ZK`=xDzzT@D4Yw_v4 zwqD&GA6yCqzU?1rvTJr$I9>tlQb^n_KGZd79z%S*Cn_jXtj*uXo(a!tC2JY-Dl_ zBl@PE&|@AAk$P!KAh03(WJqOUH4C2f?8N=UBy0B2_rWZCd!}Y#=ioPBQTwL-kfq^v z7Ox#&&}R%`ViVz7pUdnJ!zu9NvX}L44f*J7EGJxs5frDpMnmtDi)u}!JRj{7mXQz7 zhnA=CKsE>fjQdC_JmGnm-f%(Y=B{O*avdNMrRV)e%<8D1LcamfvX7wfuxk#R1>M&y zK;phZ7LRBaza{SAp>MvZ}hq=4|u6rCdb2Ujge*zHs#hu!Iv%k|;z54T4e6#haQn zXTJzK6zyY(c0FU+Coee3$~(P((4McYY4?+papyQ%_lkvJSkyeSVu4EUWh z%vZ&a^LgE#dr0^f9Fcw;@?G!vbR-bk9;veKtw%H;5lgi2ATsxJ?t$cb`SZtntNYch z0v@M#&Fa1dau|=d#T$jSU%y^3T(`ExN=Q6czZIYy6H)ir$`g}v^NY|fQ%F32SHHc0 zCv76icG943H19~!ZPV8;Vy^SGsEE-Z{LLPP&)QHVks+VOpsm0yMwj!lIq@PE=ZvmX zeBCFUT`GCZ!E#ZmyV4gQ$MiU@)LP6y0xicI>enRfJlF#J@N)msVHx@c?MZGpe#f=p z?%O_@Sd*+jx?Ut7=g;4XN)xK66-jK!j@&DDg7^8XAchHwRzKa&YWz^+T=!wseZ-pU zi*M#6XlbEq6&F0<%;u3FxN?n-)4#=oz2AYy_2e+JdEDx`*xcooco=eM^(3lT=Ra6h z-DWdczV8!4rR)f&kAA1iN(;I9PJF5!Nzb=tgSG6(<2mrLv-y&qrs#Eld19vl+wf_k z0p#@@_~>S@+HldN_P1#-hna4QwvcrvWC~?$VSp|ZQTKtVNZnZZ^!rFiNrB?|avqBr z^vcjs0RibZ9N$iFq`3?z=TQ6A(jX8DfY7E8$|*JgVpD=VnfHL;vG$O}=_^LhqKuLT z>0`OVN~_-e9<@jrwEk3>Ot9hXsz_u=f5eqLv|N&N=i>mww!d!f#Y^LLIg3SE%ilwo z`>3unbyXD*^lh}aTM6*wI58u z)=c$bSXsR^V!9*8ubLI@Kfo_6u-&7Bft_dEoWfdqj-XeoIyA>_O#GH(=0{i&5q0j? zK9dV8nM$1r=hZnmC{x}x_@4F1o2iU8YRD$uSZ_RXD4jUR@2j1qKSq}pnHyflR8^QH zN!hofzrad!s|d>=+FMeVYTV6@KU}!!xJ>BK@&%4@*&Uz2iwUsq!59FBdf9joA--$Tr>MBE#Wj*>)o;kmQsX+Tf?Q#?pjSr zq1UgmA;GSbp^|d47BTjnA79GTHGm%vt zjA6loE5e52>PK%a%J!!2Jhi6Qoo}5weQ>bx>$}9TgH*VaYM&-753Vrps;W+sJpg`# z6gkez{%bc#Zs{Xr#{i(gqFIXzt<;Hy7y91u6@J#Pl^vKr#4?<>_}(|%&Th!LthTWk zt^9gm)psHy_M-{q&$s@(B_~5dxA2W*7s5@rsb@yC4=_I9;f$;1|AHLaG;IYUd$f`5 zyvGe8h0G{!r$JFAo2&5fW#V_Iy+-QTY;C132``JGs2Aa!^zg{lR15o{;Cwu~?u{Ir zX08frt;`3z>IN4erIyRwxzSg;#b3?;7$xcnecgvVTS4a)IW)9NDyHmvw-Cj6eQ&8=wBhb-(S^9^0J{2No- znk6}=9@$|Wn`psjWkp1Nzw{IgSZzG3=Xsy)YY-WHp-Q$n*eBf`8t+x=q7CeQPToEE zsa!}1o3F;blaA{voMAJGRCRKttCyqF`KJ%lB^_uZi}Rj-^oe~P1r4T--q(@)It+zLcO2E^{~3~(W;@QZMFmx zR4tyqRI-`aGF+W0Ve|%3p8+iei!y3oTU(pec4L};xo`(2SJsh>7IJ9@dRVBZoPI=& zozAQMMxo^-V-M5Ki7ppSk^K#K95P2o8$+A3D`CZNt%H`Q5`@fd&R$9g*$h66&^+!C z49c5am9@IF?r|6LPFS69)HXDGI|T)fw}=%u-@KSGeZ*V+@B`Xx{dIymAE zcPElLQ*~zzUoYbdIdq7iiiZ_ZxGZeIW6I{S<1|udU%sL_TtO^gCVln@^GAY!!8Kp! z+z^x2h3m-ioZz#fq$69F$7w`bUv50#@Sb6C<7hUvq|k!EGoMCteOpthlk1)CBg>dn zoKfekklglKnzNFd&H0MrPg+g`2E?x%&$wkIDDTInE~ILm&esYw+K z5?)f9E{bd^NYiCcTORl->pa|$P@O1meKo>B=cu*dKGW`|s9BDFO!P?)w3S1OXRn%^ zWcBfWihcF$4m^r?(NwW|uj^=a1|PYtO>T|c$r;$&F*&edG9x)FF}pTNAl`g3b&gr7 zFCfwkFL(Kc;L8=&BV>lO>29$X6hZugg6a_JL#aJC)R7#v2Xq63OrwMx>zkTl0Ud@+ z^oLg1EOaN~_^RlOnt5bo?YX`me3NKH%4Dyir$d^!l8zkOkeCkw9b7QR1%7loS#b;D9fPH$klw6~y1Y z#bDMPUdKLWtUZu6H7!qd=A=|afj#CaZiI&N$-HA&J@zxoK_7TZ!N*e)P9v7#V^&dW z-OV$Q;`j*f7^!Fo{rGBBU1>obeBiM;$r|(aqr9eFXTE4b6LV)M7w)u)hytqbCR51X zCiUo^HuHhx?AovVq1{z?+Gpj_iXZp%Uvfc_?lHqQ`*O;)iqcSSt=bl_ZcZL8m)1N! z$bU=8j$ZFRWID{D^+p!xK{?DNL@(QnZ*Y-o$epQUXA z6=;LRTF_My1uvg*)XFP}wvqANEgX9zzgX-RTprY{vP)(nOad`u5?5Mquwgz=BIqR9tx9qDa3Ld8RpU7O& z0-E{RNpVXy5{;DvQM}3il4gB%i~Rwi4IN$r6|Ac>0m7E)rc$S%R$($c9I-g2P`Q%B zXl!SFb9Jn@?xylx>!2{z`Xdx~#*GG60S@}^pRh+}eeN?2ujq1fRMe*)O%>)k3&h(0 z+^7!<eG zYwN6k%~UiP9)p7mA?Vg4aWBR&)d)8 z{Cpf!J-mp;8k9}vk-lNmzUuvSF1zIMJk`C={ zvrsm3HAdG99My2{8jSs17P{iF*!VWLGqgMFOWVIRzKX7%lC@HMCcL9qldJw&m|OXB9b|DVMicmfOFWNY18|oY ze>!{Dq-m=(bU}BZMVjaC9Tt|)kfcwQ$h0c~a}FwRaUe-YQ-v2if*nU+Zu;(s$|U*+ z@p}&m-t8!Zfw+zHv#FsRYWq<|sIg(Z!>q1M3tQ-JVkvOW=3%Z&hk7DWWh{S3z4;&+ zdEAPliZxYdnWYjl#Pr=`6>~IJ#j_aCoF;X&ncp{78WGG>S;Din^|%u#B=CNfi)vy< zlwUskTx}Gyek*${Ur+ty`N*q#54qA0gMShzzRCpM3`XlNO0tL>2UYy;L}}gI zHRPzT49UR=oF#Pt-Q{1_{}ZxhBtLT8cL+Qa_R40r$-9+c3p?MSD$IFa6pI8GGtH+R zgEpVQurfnJ>e-$##nUgHyV_{8G-vxW%t}LUmCIpzVm5vc!Xlg5SId0avX*@5}}X`p%RFjKzB_2C155TsBdx3^|_C5=YTXRTPVPl zdY0zaIMXL@i_#X?ywF>1KpPNrvhscPaL-NNK1|rHt#ml4sPWp{(T7`r?d(u$34fks zE_F2#bctDJ$CAStzKXgB+blAdK4Iilrg?vcjEw)=8H9(niDUH{Zcb6Dy!D~e{sOEq zv?9Z6M4Lr98g1uS_H80IMZ(IMszW#vZu?!^LW^94eXF_8i4H6?6DU_ZiyTG=Ep!g$ zyl#pI+`0>Mcef_7yavDMv`+a;pACjUSHXHp)9}P5ZM7#yrF2J=0()cB$WctluVrjD zq`ReChl~S5{C`||));y9~Mp-z;K6qY&GFZK& z$k}rifChVgQT8lx%0xn{)*m<<5^dlGEs3$BcE)9lRr~E?&C^rBn&1SAy!i;J1{;?Y zqXJRA59Tre^M3}q8YydURqf_)BG?jS+!knc3i|l!dfyk(Kg0$$eso;JrC%YGQI`s- zo-gcQ_ObQwPG-flv)GY)WbK=}v8Vm!@=_ZGx3z9}dEn+$o~GA{4b_n%r_QsnS(QG~ zK}SYU$v)~?bR5S^whbhYO;xn-%6%hOTK3(?gtGY{e`{h#@U{&cjZ1=&Ey^_Mv6lX7 z$Cghe(}xJ{n+AmI1?I2QWnhq#5F+?TI_`vSq z{$*T?R~m*C5e}!qQW*yW8)J-;l*W?jm{rE4Bb>Q4pl!IFWvtip;|c=D0QsKb$0?Ai z%_1-;XcJx$%JB7_^4%y*RWBa#sZ_gzdWvJB&J_moI$B!VYNiXC$vusrcLZU4GK}IL zX54fucPx7AslYMWbV4CF;V6lo?wT5Sh+$RE5>v(N_|(61ck!{oJR!hLJ_hy98GQdi zCcLasD_I;dwxd7#*>`mby)E)X|6Py%%m_2_#>xr?+a@K|$Xq+d?8wO2)b-U` zsGT)1f{8=Roj<=el}k~KdQ*JMn0qJY)|C^+Foms&Xy&}n224NeF#5Lj8gmwl?S>6h z3vRl3l=nYO>sjB4Q*AOGEzGr!NH37>1M$A9Q}JgY`*eAES5ncLJMm+T?bgoVu%L!3hva=~dKjFN5cjRd6@bE0`(dL^B zn0=sCh#0e?LGPX6@AnUMD~}=&83g+N6(a+SC`D_nTm{>cCO1Y2ljhnO(Van2&T-cv z=8Xbg>oEL?+3GR>J*zIMC9AsLmpe*>pCCV#v00WIi?H`z#&7%~0(B_YckhsKE2F_2 zIx`0tC4h0Mi16_63sK;utbJuv$YyPP;pd9faOqX>JEMJe=s-)7|52?~`G~&6#ObZK z)yXcV%X5Ds`eC)**fIZ*jq+vixu40p76t?NNJ0jeP@zLXGL#CY*~HtQ9%s9ttp!z? zt?$A)H9oouyZT4>k3$OlhaX@?Xi%naP3B#sR>qBLZO}ceTa+snrgF)+M|(m#;74)r zvydliFjK>t{MB)Bs4|(4aGL87=R`b3(Ip}oVPW;OPyX^gqOWz1OFS5#VuCx3@%&Ku z5O&VhVJsYxu$EQ^;gxZ?l4eZY`9MuR=mV7jOEaxp!2E9R4T?aHz-He`iTZKeT}D(CUZ*xm!TGxhcT0+@`vTR8pYNmO$fPT79iZr8R8y&?a^ zD%!Q9&jl!W5>EHs&P-Ik^5Kn_ju4iE!FMd=2!WKuRJ2a)cw@DPk}seMY6*;EsCU}M zKAULI$+;_I-#b%T7d+h*U)oGJJr^x^z_TzRt_?5Vzc_j3=?*vU20FHUdnTUdiySO+ z|A9S${jruMv4&~CiREySNWsc?Ep!4rs{|Jeg-CHt4a#lcm-K(^ym6tu;O$3y?0g;5 zgImL#_Ea8SsF3w8DXjGeEDI(a7-bLa?fcR;D`kaYg&$T=zfL_QWVdAtL|oa&026@I2;Sd1I1x$!CNMQ1;?^mdzViXvchKUB`~m| zO8m2#wNxPQ4&M;)M-O?{UkbtL#@tJ#@%U57;;2$3e6efMsGPdX)v$=Iok!{nJgqgD ze#IZH5E;KB42&PfpFp~l>}>+oK>m6N(;=93lvU6h`T~0HOBD7x5`93RYI0ZumWI&o zI2JmF1Ni&XpmAZCnAkGt_!K(3LRIB_lIM#iSsEXt&TQUAwLMuKb6n71GfzF_cw_3; zbTr0k&jjU=sX_xjcB^}yaiA^MH+Uh*=od%jdGJ0<239WkvvlXFAsj|$k zH&vZ&@<)pAOICA~6c2)2x&#~zPT{>1IPq;Qyl}w?uEWeGhdDSEtY5QqUnMBZmV3NB zhO);F{E9_bK6mweO)1!q`GSd`E1eX_r_IRY?3pRjr!$S#RKDWnVA(U%4$?EGAXH5k z9&c!2o(?g|-&n4VohISi_9-dU#(Y)hZ5nn>%yJ$%7irCcHU)*hKi8zD8jV&-303st zKv5GoW_Iw(vNY@Ij-KGfXueuibcy}eUJF^z8Wf6KHGP!_BH<#goQ^WgA3_eNvuL9m z4(J*<62z#C%SkCl6;S-+|Q8jwG{|$Ic?1$6(rO=HPqlPyA-JL z`+6<4a+VHjTD;74_abh?OnGLzi5bMCSPO3kPMlatn!2?Lu!2GD|9Vq)u)?3da<$0* z{%)hMIP#S8w@q3%`>axb9b>5~Rl!}Utl0U58;SCH6GqLxOh%otjv$0mGtTgx?9Hrz zPWo`0J658+^VNvM2NXis1<|tX$l+Ow2ki9B#*DX~{YJ;HE%WQ8uQy1Z)={i1iz@3jf>8K&JujJj#0-G zls#-2mYOOBX$(w@1L1Q}L?$*ApNJA(p4GAvdizLqh4ixI>)E@;g}ucnhd*@xDW#kzu9(l^1FzU|A@7c^?mW`SQm)2#U zXW3^t{vrdZfqdzKd@IymcV)vO+^$xz)AAEKnKRIi%&nTkTNyOW!?DXkQ09QC34zu% zg{o>Dfe{RjgRGw!-*s=_8p+{9~blYxd*(z{JY|3?}A!Qi7`@Rrm zc!xk~)E#P@8^Y?S(1(P zDC=y8o%4B=W{eM5jMZ?U?{QNK&x=v1ps(g)kqUf~lcVytDZ|!Zpa`CAbHGY{Y)+(_ z!v9lszYb-YPny5VhSVLWRE=h#9f(oa_+@o;Fbn|6ub{PDb%W&W9QNH+!kWVaY_>(T zAmgZ$*A;t7^Olqu0lpH!*rJ+V&laM& zxYKD{=qhlYpM?m{1H>@-r#l(z?Qe8OJF``$`(c(A3X~<0bM=W0Z62&gp_|jvRFyLI zTqJd9{cD(yR*F;bta0@lN~6+{l5z8)Ex{_|P}7)u&O~&y(a7I3>+Eyu+?QT;Gbbdl1?HHFdNgrRO<@?;u z+sK4AkJCk?ATe%j4f4gjr8*J z_l`vquRK)xWtRDCTsM!$VXI(3XO-BnDll^$s}mEXAQj;~kNNILJ5Z|e!R4?w*|Exw)8yyL3e8Wbs+ar{xuoc$ zwT9l2F?+rvch{Jra&9H_?$NaVRCL!f)vrH`u;!;pu54H<4}XCN@y%9qXGyEbpUdx> zgZ0yIUgQ1;v+r0bZ*Moqp|Hw3$&S?P=4^!L9U4t$W-nb?8p_aXLFtn zDZBIW7iHaT|Jzk_{oMZU+q)C8SlkB;GVhGiEpgG20v}nZ|P? zUgx+Af*ErLkaI`pFvl|{m9`KpvO*Hdwcs?a0M`X>tXQW3FDK^*)Wrh&Zo?ofKovh z!WctxWzY?h#+Ny)j?y?)t%JYFR3GWP+D$A@FI zpzv{o@u>(^wJDoGHzp6sO(+mHWbqu2(30CtzR6l|qeFg$TMHr|UgP*xdH&FM@l7s{cRrBa&7FEaSJ=tf@ZW47Sz1q_4jD03@M zSl;!Js+wu8@;EH4nTR>|K^KqsS;2eISlBvM;v=zm=${<$LHb-*x z_!eIHmaXWo3+(&*rhl7kjKg25h*V7`#*-+K;yx7lrbn+C&2^Mq6Aa@{+4B5FMW=Jj zrCW-c;dBvJy5;J-=JGLvJm;$<4ptc(A`e;swxfEj&iU2wdJr34mxiWE^2MqAX7q0Pd}G42j%)s z4;b+E?XR&LM7OM0R=08_Fg-I*qbHkQZ9?@~Bn5d=7W!LBU31`Bxh|xL`V4(*jmP@8 zlD8u?b}7o)V5K`kDPsFAlm3zJ{CESU)0q7`IG;DlpX(A6AytTGMZ1OSVjRLTp5RQZ zcZHdflx@uYNcWf5fR~H4UkotKRk}{ygLb?IjBy8P6^NLj%ABHurcfPItcE= zTNDAovbFN(_#cN3js@_qb8mmtd=YkzdUuJS_eRvI@j9bAxx$?r&|5kMdLn3?=xe2y ziz>d_v)IBsbadQxTs^;$qD$;h1RWSSC6h)^uA6hqT6#~wrTj2&@$_adH6mjQACl(4 zWn)_|O8fPu@51IGNGF6 zZ&B;eq)X};4i3PYxZ=dFz3qi2hWUI9eRkM z;%<99m?mIqt0;3jN~6(w2*Ua7ya}aeuGbQIHS{ApuU7c>XSk3bSdUrEaoGFvySqE( z%|2TuT3T&_vXVIjD|l2Z-(KG*1w=Rq#XLWv+ddv>SxD{w)9uss26 z!USms<)7W$JydMuTJ(3%F+_>T(Rg?T>b}mGBR?A^SA23A)TG(6E4q+Th*GpXFqFe^ zhD*tCjB}9Gh$h3*5~u}tNyqgbQ6r~lx0k@7gM(ZSQ|?dOktyyKjcxHw(bAK2qD~OgRDH zesW6vA(WWYu5-KT z0!dGOantsfH*}`Pdtdk(dR$hw?i zh&H=m$R)GHJ5O1wx&(!OrS9wD_l>T9*vPn65uYZJ4)Se8b&3#(%l2j|V353E`peVs zd=r2?0enMt_uHdb#QJFyU~+v9KVL4kGSa`Qk$x0`I@iQ}jv$f0wu{?fT0ZI%zTQZG z;Z@Pq-A5(6BA0Fn(|{m}yBp46fuuZQwJ@BlpzqvDclsy(x-axvbp|8}k{Xug9lA<@HT3X^S z$$L*xz=f(z&iVsrlbRgLKr?_2k&1Y|)OQU!mqFGaCO7b&GE~{jF=aoQ4CR*!cwXyJH@jOiB6ZOb6K9 zb;Ts#Jun-aF)BcJ%IrHTd&E4zq8zfqpukVq{Kc&}U@Z`)WN>W}KMr-^+>7Buu$s0w z@bz9Sb0R7gLeq1bjE``N5nds`XCa5-nNLN#_mCJSJ2N@xT6oQ4c1v!qp9~8}V9Mn{u~c zaYk*5qzk^0FUc_V*c3uLeR9ZyYR<8f&@k!^0}OB9xGV4hJOUWn?p{{=W!XAbe3Hd= zn86tUYDP1GrYZu(m*EHYr*68Nlh(*rd6g*`A0r1r%|od=~wk zPXe1)?Il0^t5)>V>Nxe=>HKP8=J%D|w}DgXf{~R*6=hBRcVnOOoqc($RFxKrOtp8h zW&vOPnv#WAG{ieuF+jHXTRn+ti=2`V)!dh~(8HLhJmxsJHg()ISkUq#As0%>{c++% zFni1mNGTBe-T&x#8nf(h<0(1EcZb|kE~CLU;1nX%GO!?cZfe>P-vL(v)3?#Z65s{L z0~TFLQ%E5OeD4x)uK$qlp=Q%hv8hMK47vEh2xH6cOv1vs^DG;kc)BueE!o6bu3UG;8sEA87xWUbsgcrk!v zgMwF&dv(gN{g=6ndl!tjh)t{yrO10(KgE(2hSxWvH+=kX^?HI~RY3Cnnwd*xTP8J( zFw$}}JerDqaNE%LuIml=5x**;?HLZNoN5sm*tKv->AT@mG9@=lS#-Vy*_WsfRZ4xq z?jc_xxn1Ha?FiK!KDQpuN2ktvY$raSffJn9)^3FGT9d3SU?EOAQpk~7CxCghTiOO?`1{qq@h&2IB@YfLskGfGmsFX(Ccu2 zF;{-^GPdfJw}sK{Zt-r#6(ig6PkF6FDy1Fk6TWv)j{=w4IlZ zTr3x2s+vdjHhy(3&vM0y^&2$b&Y^Z8Nnc$Up1AjfKL2WSYwIkS2xATCFHM9&g$li9!s@Oy- zss~Jw;OGPR4`go7d3WM005>bX-FN+QsK#9S>k`qeXIJlh-}u-KFx*+-#CTEiW;Ob* z`XJ}8M3hhq+{YRP|FB{PJnIduQWSJ^6~KNbmr5i4lP2(2U_ISYxj0g1ocz)OQ~U7azI)iA0HnAbCqEy9Pusd zZ_4Z+E<`227U+u~K4s&OI)!@Iw}0hDfK=>b)cDMEr_%=mAy!iJ>anZ0_cAy~JSY^2 z&CM)AOb}ric#vrWga&cefC(*tb-cZBp$eWWGIGdfzrCb?g$WpsvoPy84N%S-{|1Zn z@os>>Z$SJ+;AedrUYE;;3z&{$q$=c2!hkgpX42?(O0xLgLn0i`V^$S%PB!ab=$g(= zL)_3ZTpFw!eM)idbGY?byG(jhDvh6&_!J3cBe{6du!Qetf&dDmc-s%fVv7AQ9y z`ZXewaerJ>{{uY&Oo5N@GKS%32IBxw=-i~I{{)!5uXYz6#_-Dv+xW!cfTkt0%G$98(UVVdO9GRn)?u#LCuN(274p=nrx2*wx3jtz+W(4n1&`s&Q> zJ`s@bA{KZEX;Zk|{Df>VVv^~)208ZYJ)z2DCsJIsd{^E+g_x_&EzB0iwbZfFe@(ld z6b3W{0e_Lr#|{m`?@8E1!!U7>h9CcE=86&T#c9>8>wR@~_rMtgd^mzPFMJR%xV+SX zTL-os&z#<4+el0>{@xtt>6O@~VXWp5WE!&{Z%2-IC%tmf{5}UP&V?I1)`0+g88J?T zS;F5RE$^8Z{(X}AeGOzM%jo8kFAOB{m*JlyA|AguWR6T=f3W#tuE+(eMF*^-zES~m&{3vsChg5d}!gvllt{Cp9_ z`h<$F>sra0s5Xe8A4~oNflg~w)&`c&*O{iEO#o~mw@DZzEVbLxfM;w;7S)}(sr>p@ zoSsxjwuhI_v_b>Z0?(s={?AtQBXozrjYh+tbWgdTc;O}<8R{LMJGyvvFH}vgs7LsrA}-1OJ?gMs<*<>pgTPW{Um2p9$|O>K*z2LOgCN*`12{6vMzYvhjYdoT0D~9bGBxWf#`~qpMh#QDo@xN%IVn}!B0dwSMXi($&>3a(Ck5N z_uZH_fX`2sLyO~EsK}#g*CR}xkcd?Qs~du6T@wDWDhzz0yyXmjK*++r>C+Oy9|Tz4 zEQ|S<$joFJ5a?lMd!cu4MWnyr`&9u;tNU^#RsT52Ob!`N;gZS^`=bWK;u0y$qJ-#>RJ{imwf(8Zgb?o%-%U*yiHfRN5boCu?eT zPhxLpF+mT7SL!t>*Q>vXJ*EJ1wtc{PY}AmbwgVP@1q@|jXxXDu?J6DJM;M)!g3c7^ zcjiCI#Rpzl1qR>6N!8^8ZlPomo1E|bq|>WU@5da7P z%-mM6-Z1@74(`E58(1(N$e2ixx!k(ugRicT5dYIu3eafmn15%y>7@xz<$zfVOiP=A zs}x)@u^%-nY`ppFtq%FHuE?8N310|_Js3Yk z6YlSlLdU;0^e7PnlofWPBai+Z&5q=33eU$Jcc>iqe@%d74$h}9Q0LzOnPV|u3b~n% zRLCatBzE4Lr9(Tt$3~KWUgYnu>v*uezCC1ufY2iyHpGz$b8!7&33)bbHDvS`h4*Lf z8UticU{@hAnI>k2TS#1Ya^#4Irs^{~nv^Txb%Q&U^Ga7YlS&lNW%L8yb*29>cSZZ~ z-en+mEww@0CS7uNc1A|xzy%|`?iO?-)?-rfDw0-=l|uu1_9KyQ`;ve_Sq5Uo@h_~(pyd*7vHu5e9~Z32_ZS#jlj0BWzn=b)Y*)y~n514~OAQ$`xV0gU z?EmFa@y9FPMB68^CP2Iwlr29-f0;q)q6#!S4${C{zC z@PPC@0RrC#Q0=n<@f0>gHKc2{0MIJ{D;y=N!87(&_b*{QwN5DH`Hc~|n1n-rE_oiR z#TsCmfC$JDh#msTK`c;$$`5Ohp+SMgy*8S^5GE0kM{U*M>IRYfYjX8>&T76l#pix6 zA(LV7AlUvIJxx;MH?iElm8%l zF0OuqA82I0bN8I1GUZ?B))|CYN!R{21e(OaPnh4OpGwYm`<)PQw+EE-AX{TA?+?lt z8$J@l&w z&o!!I>`r8iUiiJ@M;}SMV0?ZxzHsgjLo^M31&l#AUYUS5L<1Eye!strm@<%@FfJS2 z7lUcFG`v5=!Udp4VScMH#>lDq{^u)q^ps<$Aqhk0U-wuQ5!sV>H4616b(AJ&jCg;a zmXm@OTg*42n$4UdbeSyF|G)-c1_9^geBfk{_V3UBIfX2te}`c&WZbPEP`+;vJ>vGy zSK0s{&MhgRKkq?BID8D8jEh)8ajdOm+ZF!dxaI>+i24wWqa9_}40TD~pZSZqEOEb3 zwV7eRV~n_)f`P|kpD#d~IzVG<-j@Gg;3WOjEgOc-X6vB{RkS?L$n{%Ewl%iWPJ%)I z&5UgNRHK$Z#Q7$L+zGBtun7@B5_F5F0JCx%jubGS?ttqN+bRO}hPt-G!Y-`k^WfOB z{Fz~^TR}DJ0wqP4?;B;YaDZ2>&vcYA;rDxBc|`#qkj{8ydm1EbNq&0p8D_G)xR^4-U0(@ z9)!l=+-RZW@)6FBP;QgR zWRX9N#-xk-=l^Uy8@j(lSDa?K0H3T%L$2Z$YC1sd z>9!^Q*WGDqazD1J#b}tE${MG?Xt`PqTAgIB;$re(F zH)Ca`o0Kro1h+Kg>=2WbOhj76d$VCMQa)gdI2rprrk==d6Qcb~uLc=+lROnxTw)@- zdevz}C5M4H9D^d{O@Bu8W;mdE%^|s1hl>Rf{6jEpW&`IcSly;~F49roA}1$b;5wuJ z;sxPf)M;pm#lAYwuodmn|uhSOKm{SmIF61Fh2Dn=loPv^#IKa0Ye?8rx+D- zJ|Gri&>;s`v&E9qjEv84Km7vY79h(ZPRVesx&rx_>Bynx?*RUx`?DQ%Y;yFZKCTKM zu89CvULO3of>iA2{>wv*1x)4scM~xeD1s1@kkkSB`zNsT2Ot zm{`~uKr9-}H)#VCr2(kdz|aX?bBJ9KA4o7dT8Fz`foPrN@0bxs5AMcmN|4cDfU6DG z=kV}nK=_0m)rxv{iwNF@PR*w)7*Ot`PVP~d3M`+XpdKH1sh-wDrZ6^=r+ZvQ96^u-Ie z^`3Yj{VCQ+tc3oSu*@ zzVX~Dc%7W5Z;)D(Dz+X@->WYgll7s#Y?c4CSbf=TcK?RW1I_x1&!?*bwKp8gRc!ri zBkdy#Jq*4ybM}=Q(sTGJ;`#HF>EYCDC-IsEZa-%Q4JEoFk<=RZ6KdSxDQnt~ANr;# z$~WH=2<={_ar|`=0A-tsWE=qhT9aA*;_vTR_y5uMmSI&z-S;RMlt_wzAczVGNK2Q5 zfPl0#A}w7~QYtM7QqrK3($YvtOAFE|-7Q^rZt%VL7ytX=ez+fa9v|VHv(MgZ%{Awk zbBwXIx#`+lk(_*2i;1|Qp~3xWZAAsYco6x5nH_i+p#{e#CayWgL*BO^&&1frl`r`BTKQ$n!2wq*K5I9f~T_=!g<3C(3KnVmz-0p5ga4>6! z83j}|5X?_WNvTSFK@DPS}jVb_K5q>!jn7LGuCgVzeg4>(a5#Hb2U? z=Qe^Jtw(?K6mW%ere#;IPERTY@}V{GtkX5#^qeH$8&V7;TaqZ3!~lT69bChjs!z6= zVS~EaZ3F57Q6@@;2C?T=k`s6Y=3KB<5H)dF{WbuS?hlPYUkY*g0#}PkYwjoxv+ID5 zZ)NiiWvVhG7FY-rX_i}w_CsKIqz!3R3loDeV~z+T(n zXT*Tax2^^Q7%HUY%XcZDLOX5tHH@ zB_7_^I?t%>?Tr)1&y6xI!jNCYXjpmYDZRYMX@}Qqi96WvG<$^MEC})FNMWQ5E)qvz z7NCXQAjJC7HM!Wg9C{X=wNQ}H?;sQvxA=HV@k=G<#JBF4|NhHuqFOvVmd6TIDAVET zB4+}d-OuQ#!i_Q$MM?B9Y4*juS<+;P&b9q^q%c1}&^)G3qWX9%bS2{)KrD1TyMSG) zLiM+DH2)FE@3uU9ldl2_R1eU@%!R;N8S`8rvOL90KBm1SJ&@XO`UQNc!l5S-nZ+FC z)Mxi$?lFACa5Ilrjo46|m!>D`Q_QpEY={B*D%(UNu{;=I&C{AD4^;p2e#yxDIkyxO zzP8eh*4HpO*P7H;gq!TJ2>+{c;|wn|nG460Du~xoZq%fbdACX9-EeiVhqU=8A^XDgo+`hQ9rxLgj;yY2pWN5fXC zsJRk(=#tV3$R$f-$eHt@5(@^e2gEm_rd#)I?gvdBJ?}7;${ZygP&)f)6C67;$A?3~ zF&d{-Nhmhkm=n&H0^gW(30@ETq--?=O)WQP{;BaW|MPy>_c>1A9MQ^?_rs#jPZ+76 zGD&5OUQ>N_nr-8f=c|#vO>#}OZ2ksukU)=!O+;*4y<|5zgqPI5)v5%D(y%Sm6ct#wAq1*0!8-lHl9g`@Z8= zQ}gEeDYnAXc3gBRR?^W+7q{rcEJl)t>4P2lE0NTXy7_pdSS_i2bge7e9=n%?MI2rk zbjS*?l_K7skqwGaR#LIEyyDZ~r9MwUEUWD24RSHqQo%HWx4i`E6zaV+nY#);6nu4X z9PSA^c=9sJ`=tcQ z9hdqLJ=|Vj7gR~u>e6oZcsFwK5<1CiyG=`&LzXEhWexni$32Wub~`mY$3IfuVy6pT z!+vbGdD5YQYld@etNrA{n7Yl+-PRn4hpI3Ab*07)a#q9A<;s}ehSC$q28HL(KEzM7 zXrAw+k0uYFSloYYSfl^KYZ9| z;37+Us^z$;0b%ye_a?S{m;2F=75+*E-KAnnzMNp+6sDxn{#~@eoJX;xdvt%9_gPSv zSchsN_K+xJy^khl5!w_+iQ>%W^SDwacki%GLd-{xBVyh5$M8{?a3j}q-#5ATzr!i` zbw}`RYv`S_dm_sMfV9+FsU zKiEM;97SHkZP!$Id7jPIuY64^ZF#aWK``z%zCVkHGJA{AvpeZ=AeOHDEA0NOl6{>U z)XHiT(@SpNSwhNfRYzDVE6lYsU(E_FJ~SWNk;9H6)=jBZ51{7ui(+ADc*;Z{S0pyj zMt(27UR_h-eR)t4buT%i3HO{3TYcN~*ki3Ro*4J|Wv!3bQZ8)}uwr{w*wQlW5UuyF zUO?82mHVTx>VoVVVJB=)7BiM+2dhWbefoHWmY>tRk=uY}yy8DTF@}4|kuvwiU(YdE z3%?I&?H&=MA1kg@?Y`}HM~;lIi9#5(CGoGXWa3fWPyefZhpqm?kDim}<(8EiX`R)X zZ+dQ=$$?!{m1tZ&T@sejWpbo|P}S^oSn;P@|J;FKZ9 z(fE+L%FTOvN)C@bGjyy!_|JpF0Pi5_Si7*IGR8N2PQ_)aD&6Y#uYbM^*qaN@9+xp@ z+ZNm@30!GvK{jjkr%(>`0953fN4 z(~*46TH&cDrwu-5_s!2Q{jV6mAVz<@gZHH_%Ya6lGjnokr$<3$CADRSDy`6`(wQi{ z-^s&aclN2g{OU2v{PDJglgBYWO4jTxxLIA*VexCvLQ=a>h<~tP@64#?!^#gRzG*y| z;Hp)0HSEZ8V)VcQ{0(T zmDgA?QgWb+4RT@#@(sw?+X{92A&8==Um?_bth6%1olf{o3U4^xAq0;}vp5jJbpZ?u z0SR%?2nUN#GS|7a(kYxV_d|>7Lr^vhj9^ebu;h!EMU3r)PBw5eGBd$e_5z~B`uNF{ z?IJoRrrFQF6qBGFd*L}!Z9~&fOhV#t2u$^&5IaPK+6Z8TW%&xHJCO4Ai_muDqYk`& znc{378ro73)#}pB;R(KV4tw(^}m>)L13!k3VeOMtKh5UuBh9uVeGL zQ~>SUgo^mKpT6FjSn9TP>d=aA-2_3^P*~@G6|RE*Z)XwMqTY#PbCTg@x)f z8&@Xku1f5i%0bW}hKM!gSY?;x7&Y$IN-&>jN=rrW3urIh*NeJY)^}(mc6FMx-22B z+Kv&n>I`A8_O_@5o0q}Cf8H_S_&C__y+7jC`S|A+TJj_IPa$?LTl517N{!z_O$A3| zT2q$^@&huOnKE{s1}tUb5Wb@BE>XJ1S>Tfr|JWuaAb02b`dCa|7LWYMrwapjsNS-Y zZv2(>doKU#@8#1GNHAd8;a^GSsU;ceJrrIFmW#{HWLIqp` zOZhzBzw!{OCk6%v#9a>rsA$Iz`butCARzIW>(-O;mEVMgAk?u5Lo2Z`%L?xHt#^X? zYoSI{E3v#;Q!^&STQcfECJ{ug3xhEzi2p9g4SRaPVnuP{rvRW?%GH%00EINbe~^iZ zIu<9u#F!hDtk_K#cW?1q%u5{kThMl-iKv|hFj5Z*J-&j)w$YvKxz{c+996Q&;-OIy z%vCMums#9l)zRJSMzB9xazJ>~fvs!Q-o{Xz-0}TtOMrTLbTv(EFy~GEt{tsa z($V)WP4={HLrl*OBDE|{uAY{2BB5~5sdOOM7S9yZNQ8Nfc9+nFdhg_6;oVrCsAtW{ z={zZsRF0Z==)^;5#oOq!Ou$LOgoL5$T>g64CAFqFdQK&3G}}^t4us?Vu)1QezINLu zI&%5V%4rz6zC9*V%@y>O^|Q=MqRj3dMx$Y4$sUWKof|>O^>+JPs7zQoF$GpK4<-vPnHdC{Jw zy3c7-|4M)Hpe?7zp}qF>`=0Be&6u`ZsqiBq&XJb&)o&x*d4#HkB2NYG{jC4FY6I~a z-AN}59gBW2M5)80cy@gzh#&HN_d9}Y1h=Dxgrcpq6QoQ7uM=Nf^DQ95iOh3SrGPZY z>q|>mz|LTsFt+4-BgsgT9I_80C41}FkN@1g_tQ(Dt#&!UN%=$tgzBb@HlY>l^`6X(F%wn(`13ArtGTl{HZ57<%HW7lxX!Vfp!Om z&l2$*-dU;@6}cDs%6mVp7>+{w2%r6~9R-nW@;k(ySIc zcYW+L}p+j3jK z6Y$dXNo7x##=iLb%do-Z2s>-2FRk%~F*&*Fk&vb#(T4lO@tp}3SRYq*aO~VB!){_r z79m+rKkl-ak)i>^ZiV5@$G*JhbqYvWf9K}yK6j8d6g|Wo-IgpVZd_kdMpd%Ia%G$} zbT(ErPFuMlRNMLfSVZS$<>j#kf}rpVAFdJA{(VCS0ryW!U}=Ejf+;h0-Sg4Udb8QQ zZ5bE6$>{{u1@h3)SyQYCln!axZ*d&F%|s)P73is*4|IZ0*!rExoK(@+uIhrdXI-bz zM?s&O-reA0R^V)9!AV0HxJc3D=#$KrWo91h!W5~IQt%Pkv11u^khd&4=D4_WD;=g; z*ZsKmz0temt5=Hw8ywefEjPxJJ6FEy8_V(}u5our#0J^?srL&Oa;@@3ev;GiAZ!2W zm@Ap4YTI<<@^cb22;Y0vgt_}l5|&V4lzj>C#H=KU?h`6&KMo4Wi*^%g-3?w7-tq6E z&{<>r6UN9x&TO~Y{E=L6FjO?Ty=^95KPny9VwgNk_W{Rop#@vC%zGTtW3cLmaY8tv z*}+f^Sv25gkFp0-I>@p9=+PqpL-$s>p8r4r$8R)*9e}98BRV-!Qc_10%)GoYi1{37 z7=(dFdq3j3pa*saRa<~Ta+BjAGr}-;HU1(oUY1sNu365kwWUQ;S~}^|r%zArhFF%w z0x$^ftZaQKN^I~|x;yMHE7Y;56$%8O?sv-Cw#qi%7OZV4L3gY*!lB`y31=wh zyRaGdLN2~0=HlgwgGBo*2DT}F!?Btl5BRvS*Q-q0WZu2lXsKz?Bk|#)8d3U*P8O6u zSO1Y_8!cs!w6C`&Dv;afWf0C!E;973R_Fb?nQQ8k>ffsUl!#GpCXzO#uYSW`TKtpm z5Jx^2$+!P<*rtz?egdkC@VI=duL3=7e@~j>51xy0p(~(rlee>AtE@8o=}gSIlgsq> z_%iL>J8zA*r8ypKztQiq-|8Kk9pmPV)FnX>6I?#J5}-Bjd=5Q=XIRp{8#pYSIJStLK^K=i@(s;p7=P}SZkl&ZQKboD@nSQ zp-sU_$!OS6b$e{wI(#aPUm}*r@8qjPqj96n)Q_EG4Z$$c%QF=v);uLLWubpdi#JM2 zva$j}!CXpO+Ra(=;ax9i5m5l9g2)Ynjl_DU&hfjUAq^NE_H8%P2Ong_ZPooT=?@qs zL|UcD;G~?u_BE@@?d#As-7))JU@W&k<2wIYAjMtBbZlg(k3!7VR(@5BqKt+Q)4kiC#skzwz?@ zgP(b1mrADQbe6rYdeiJgMh|G1*K*G|I|M%{{8iccm$^&x5z_P$cA&mI;sB z+%m^xBe`bwi(%-Hx1?msWDI_vR8KZuX-I=*D(jp;<0))|7THAlGT=d8Q78F&AePym z*os@l#If8e-s5KcbUn|N^=?LYp5vJq!7vV1GL=eI0n-5c-9hDn8XhhVAn z_Sh}9b-}qG3vb*EX{wspzf}&1W!r3)`CcOXTS$g2%`$Ju^&+hdAH^PxJliY6SvZS< zMPY?!pWpMz*qpQB7vZ(2ABW{yrz5-J(P|OIVwT&@v?K;>lDNJJ4xUsS_IHb?s#SeZ z4J`*$%=HYP;rY^6bZ(W8@(0S8lhLU@eM$t$R;-T5z)quQyziR(Zh6%jV&CwAN_2jt zj2*$Mxkg_qh3)dW`RVHud2X55eV3qg3-_gTA8;(M65$3~s)G_0_Gkp|Fc;ohp501O z-EoIN^%4UP@zdYN>liun1i$Bx$+q@p8(zmQ(FA^Rv~4{Way_iC?ik`dDLc6bhzNnf zTd4X5Lo_?O=m{k>s#A;G|-?fT8nCS4`5&atl zDkHYrTKq3pW&-E&DL)Y9r;;;g>MpEa=p(;BTd>m9{59v!oZs$#8lMQ9t`euR4se(h z@5|9GWzr%rjGhO+&I;Xn<|QMsUYpb2b->~RPn7LK?xHgJntSs-M;tG_Oh5PSBp&rh<>1@uY(wH`EOP9f~j(N4{5-UsU zN6n^fW3gSQFLf7KM7i4o2~V#pLrqf0dfk$*qhrL@Hgn?GbL>7hBu!T@hLsgt5mbh1 zx+hHU54cst;d0I90bI3&bEw)pDT3|J{T)5*kS1*G&1`=el*>PvCXTn8_FkGX^{(=A z5=RecO^;su=0VG+bV$vbt)o~@a{13r&$pM3sFdd1jc{lyC$K%a1Axsg2G_0}=}*7a zjhjYT0lFm1?MT9?cT%)LLY6PhqlSvkAakGhhFEU0B$HgQkzVd4aRYgkC1hunZP7m5XRADiSb7 z224)sRZ}H7J3GU0eRuyXcvfG{iAYS8)6@Hs+YU1-M;*k(#8VFCZWcFy(v>%OqpG=3 z?fw&*=h+i7$6rqinR@grf6+h^RQISiyvHf#*wu7|Vw^0F$wnc2^Yr<*A2*Y}@84`? z$km;iAaI~$Hg2dAQK7syX|2Gqr9!DYws?oTHhY96k1**~eK&LO*y7;}A}9~_Bq(Bo zKjzVuhi5lQ9jg$^yvH;I$c1KG*5G-XWWJ#0&!2%_oZH{cFu#7gUd44gbnX4T6ePxS zoGx?nOr!Cg6JJbcb6U{yS<$1R@+p^Zj!M|TmJK!`^zaM%sJyl9?=5mtxj@2a*LvK6 zyEgkA()^rNqR!Q#)>4O;B{;g<0NAO_IFds*Q(x0NUMKOd!6Efg(7L^ z#g^@X<=Op(bc83h9h-1GLQ}SHN2{2EajG@m**)O&uGmmipOAORsD2qg~t21Z;_dT&%!M|?Nih!ox5lpkLZhkyEl(*{%>Z1akQg`H10j6~0 zD|$~=2n#-U_xgILy#!LFj`5!gjG;LOP58W_(@MDBkWi$@3R~>L!-0&_N{hbiw zYVD?=I9td=!*Tm4Q}VhS7CjrX1l8K6DAxcNeaGNZZwm=Jq!ai=rj~^Mc5w3`Mc-V_ zs9P3zwi4VPl1Tdv?yFEhP< z!GojvqN*>pObqY)ta$J(uhP&Lu2f(X-WH7-q4jTe3w8RFfek=r)`;p)RhP|u*uk)| z#`X?StX$ntUbp^E+OP3rQfn7RdIH1E?vD>uC$bDr7V7}^O#W2coIiS5x%}979Y?Z= z9q^8@gS(;8PPTeg!z-4{p*NwyQEO4xU1p)i8_}Tw+qDTm1}Fygwn7wDmKh9SUpzap zWd_U!Eky!qcAqX%oBBrsegS#foAfs7?_-0xX7ZS;-_|{PdVef>uB6ry+5ugpV{Rn5 zt6`GCm)0sSl?=D9rZNq^fu`X^+4WN8iwGDS1GcHksROWCNf5CW=fxf<0 zTh(DEhoO8jBU^uP)%C>Df|FsFSW!i3sYKw3Oq4eQHqz0ALlXx87OhQgG9O{}C(yjf z*teciP+4Z2hBY(O5thjl>nS5MAMwNMnLqX_x#+Ibnp75~yOr6A{e`@C)_8#G{*^A; zn&+s5*j^K=y(aY&u{>W)7F28 zwYS@-KlaFkb8fwPmfZcgi&L*I8vzK0J(U)q0i>ra8F2rBeO7V|qlB~@Wm^uf{Iuhk z!P_c2htzGkSw7KjYcH2My2413l6c2SV|fLI8t7-cmEe+d|A0od4L3Pt{79>~q-vWH zh7u6dlD6krW#x@s{ z{{0zs&>Jc=F)(_i`XG+qnGM_$jT!?<`FBU`t`QNjn)TgZg&87F*1ubdn-+XsKWVeJ zV=)t3pLsP&Rk)0#h?T79vfy*F6S~l{eRI5B9n%+U=(4GvH$hTv+d2@YS_73vmQY1k z|49plO)`(jH#GE+=xYu0f!tX1aS*Iw^~Y>$#TQXP4*$8d8QCe0KA_P(zN4wrt*mI`(5*v(@^T~$m6f&^3?)TC6zIPG+76|%UyTaB+^JlfBsGOv%!j4OgAMBZttFF6b&vF@ZQn{!>D_67;wL6E1unbV>(!$_EGf12 zvA4ssaqFkp6&{YPDhat&tR=fLj|{7M-swmSI2!^2_XstxiGWO&XmkiRUZ z^M8$S?C;#Vte>f0^>~&a42UvobcNO5k86xCHcub|e-U9EXcMj~ zW3-gJ$s~6Zq6%PQUK($0di(aTGV^Fhf}I=LhqutO-u1$0++J4OLS;@_-M~lCbO%wqq^#Sk=)bMCPB_xskP~QEvBYl9eP7ah(w?z3XmmSygvqO!Gt_(O0OjV z>qH$xXvgVXw|YAYPw0|C=Hn5u@0yY!kB6`@%|Y^j^U*pEa{bY2{*vi)i}MDx-In019A`q9%>l7 z@Geseg8lCBu64)e#j3*?PZ@~CwdzY$+&}q@+f8w5S6KaE(VwJ}p^16N0C+hzpSr#c zAzREVigc)%TZ6BvkZm}^HeDaQ;zCkcIMJc^!Efy`z695_#3HYgk;>@H| zS=jOAh-H{G*|MUYBqujOMhqJL6HA~Mi5bFKn`Hz~iNFZ65ntDEZ37EBeDz-HgZ338 zR^v^-w`DLC*bvwv=llb7t|sfoB4 zv!f$TM5H^{AEAwEMg82^lBad|THcZq5A{<^cs|r6S!iL+hnSmRDY4=N``2Cy)68F| z6wYfFi@6gB=XuB~#vP_w@wtK7r{OcTe^(54sfUFsdBY%@Jc?lAyh&%c(ZPQ{Ljko> zt!g}TwnM>bVK!bzvirS|UUD%luLvY9C<%)nux9Ael|o_Wuv>3l)UAY2yECi$0Z>V< zLoB$Pao>48J-wg0+r8mTDBgEbYLQb8_HhhIkv8X6_-u5LCeBWiG~8t%{6WyA+Gb>2&)yZ2NA~Pgv_x*9g;$`wDJ5Oh3>vNTP#wyuM50Z|Kp?vs@7^ zZ)CgGn={_ec#E@E+}!KE`&S1F9@fRAtj2caBBHcKoZrX7d<>6<;`_7?J_DE0&y#kq z0_CMyAOV**V}VA{FRq552J-rO3LEHUj(88jB-p*|wdoICjr3k)To2|Hsj}oSE}Gze zwcNmOiyQduc-Uq3YQHM?WnaEfb!dzRF0_dutkB3@LXXai@x&-VBfM#v(xNS$-LxL7 zf6KzRdHPtnte-A(vagfyU0yV-?MB$|FkFJc7CrDX`I4PH9;rXRav8sJPtU=aSgC;h zUztGjZ~LaU4m4rSyFPdBu!dUU%5KLqWZHyjYKVTogjUvIqz-hzWW@ZUN4jso(eW|> zH?6qiQ`XRvPGsUnm&8XH79IW^H~$l+><1E2xd*$R_}Z>bcG70t^74;AV2*$IF~sXx ze~+vo!tx!xHsl4Y=$92VR#M^ogu^pjrTlTR@BCcZRZJWXrf>3FeHBZZAFdl zvkE(W>BCKibenz{j8Cm-d;%i^ZOIt57DmXm1YJ$?NPEHW16Mebs!F!@;)}?Atx;P4 z%)`5=w5K$x<^0!_xd#)J#G^Q(=+k_mfvsF>y0DDV1al0ZY9FV~%ZDb3(q+61)x(|H z>|l-Zl)1@N)30;SW(lF4ZF*o#q3d1HSF)Jk zGl;yEUm*qZH`@U%12-OHppM4{#C4}e8s<12)mwK-#_q@MqMn-@2S^~(F~`M(?^i@I z_I50ImDTL~%zA0PFmEuOS*dqtAX8;=CO_{ze3ivT)y8D%E|Na+CPz|J#qJ}Pt{-*OG@+&(3`Oxz75&E@+Tw*RVJUbjuh$dG z<$=%!RDCi|PNn1fKsMd>2Zh&=Y-Ww<)Yq^pV+3T5 zl=6?6>brXVvx_cFr2)NVbeuv1q2#M}F4&8*S%h}8Sf5MYxu!;l+euf}J<_ksR*M~| z6*-&p)DRC_`?M-t z1CCC1t7(C9k8~xTRlW*=H)AXrsRgf-$bx51{W;og2?DX0gfzb@T^ylCSs1St0=ZZ| zVB*&;ynNO}dpk1d_e%U0oGQ9((J|)4x?Ap5@)PE~RBepC9|_OakHw=fOkE%rAky?6 z`>i?yV1x@e^_jEY@$UE>Fe0rs-y&A-Fhq@b%0uF3(?F!k0*1y3PLr5br^jphBxu0` zJ0x^;bjU2UlHLFgx7pI}E%R3=w;nK4^?Xo3?np>+641nnh=}g%RK>wWbsn&e!8ceE ziY2G@8g#fr=3&GYFr|SE5+fixj&D-4!?^3#RpzR_+nqwE{7Cu5ysZ9{`l;O)5vSD4 zhA6j1Iuh^_$k{Ty&X-^jM>Jkzef=L8VrJDxJ3SshZHF||f7DWF=`uVuAUg?|mE+$L zX8}P^EvEjmZ8eQJE8JT4`}Z!=GI-?-@xok$`TM&c%3{tf!n=(g?BjTV7ZCKyPvBWV zzPrW(F0&5H12%nEG_qB8R!4`IaURe*hxa|5iWMEGfa%HzS-B*Oph%N{e&?E9ut+C- zDHY}AAF8NaSAFJ8t>e0J8CeZ5N)8f)Gl9fl`A%zMVsi8cUFZ)o9}QRvart=n+ZatM zY#cWHS9%G$`T&BwTD+GI1I1^1Tjc?dLE$ry*xqpBFCDdvlcl{v%rp&pmE2QqADOgU zx>Kap^9?X@`PWf6I5>c+V%PgrmDT+S@n4n$mu9A+un*Fi?vx_K>enMs*Z6BqOVYZW zz4nP@u`jj>)9BSbCB2S3HWP~{A6=ihZam7VK6yosgAOJjGnA)$=+V*9$Y?xpec7MA z1kKZn<3J z6c&DBrE|`bXH06wnkZkZY6TKpDM%k9PO`w6p4&zNr&3n^Mr&lr!BZ1FTxN%!@wQ!z z@xAO;E`z_=vEBVwcB#Eq(dL2@)#Pb}>mHp?5qrVThN|V+FK;tbQ#CM|2_R-R0_l`2 z^#UL0HnTy8@R{3oFT15Sl|?{7@jg-Qfwy4`S+uB=7DM3KsCOaVRf5`#40`v2--(;> z1ScKJ5kFx>=>#}h?N#%zv4IMH6>QIqVXC64@(Lj#A+zaRis1uC1yb&2U4u?}mx(E8ecc+d^ad`^ z(a<$wVq`!cC;;aS9eG8?$^Ka&-Do+E+5=aH5NJ4}xB}PKUFdk-Fm<=)@Kh3D+5U^J zoS%h7_TXJvj629r4*IJR_0x@J+QfC_R%|?|%GJ_`w&@-;Nu_|#R(&|SHsAA=5SRl~ zZ_p|JB%U78?(gr<^#K1u3QS6VfVOJ){645Wd?bG6^ai$pH-}jt*Z|jq7}h;z=G~%b zFrK|~{r+>H<{}~D-8(Gs0G-{fK&Go8Q2Yc74E0iLDl#rh13*uzwkU#qK~`Q-UA-A$ zED3oC0{KBO7ESOoS24-Bw4=I2$VLtl3NWH)O-^9ZW0b>$0 zkG(od#KyaHAvG4o>2Rgwv5brX^Z<|cnuJmd3&Rn;7sNWwpOE$f6cJk8-Q9afTb*SG ziTMCgW&#a$`jh$V+@CE*G34joMvEkv@Q2xstMDx}&r?l)$ z9$ze7NRKwf>AlKQ#=KYtbN+=u#up#(Uhz|8shkQ-0-3O==<4_%E>(~U!STK5TPF-; zZ=-@}P~DH)-Ilfg^8?k^&MunYIe#q*x|g7vgNPKs_HN43EWs%mUg@WyruGJ})qFUl zbE*zZ5hb5xhjM1pOC%td1FMRNLFGeqbTf#WiGr1hTl1|SfDOQMGyr9oKuV#iEH3xNdQWVP)vXb%%(>TWLD%>aADT`vZ#+atxpH#9GIP&@Do2q&iH%Vop`dwi! z@t+&*iev2PKKaLR`Nz_+U~PQAogxfe4m8IR8+6X$=7?Lcy-Pul3lkT2_a@)(*}wMo z_F3BHACV)*X+y8-6=F<(}_~qR$xDOl>UXcgO2MM(7x9l--yvjfB8zsGFFAjaBeW*y{-QP zB4bSQbHBR%!A5ZL9N%Ckxs*smT`Oo-ErLs;QcSalq&8 zSYJfiMw~{c*|mh3A_^MRhlI|rHBoPb^PJdg-A>aq;y!-je#E8SbuNCstZh zu7z-l@5b#AvYo)v{k1iU5*XwPMye zldHYT<^%?ZgD?DyV&BOqyofBcyLYTHyN76@kw8XAlJMnLUCSX)EDqQn3K?;o%x z*L^dqwL=w%vt9L5D&weRa-H!WVfJOiv#fFG9U4*XtB8mQ{;f84*Nq0^>6sY?Rn<91 zcR0U|EB6qH8DWl1zGFBFI-S7v_|so~!U0G3!vbFQ{|!tdyi+9mdbLOg3U)t#{`~Vb zE#db4`+>uj&%0Ij;c!{9ya%chOof6(+E^3o)km; zn3##wnS~$A{P)lsSRE-dUX}*oVoI3lP(LJ>T=WebieWc+(8g!b!}6(cXeEKi0&=7kZS*+vZ;Cv98T$rMKi2v(3?cEBCF~ zkITM=3V`=+FYP}l7je=Xd#;e;AriGJZ+~76F!Ja(rzIzQovH2|%qKy&1$FH67l~jB zi%r2!{w-|SlI^e7VOz)l-XZMXTqF*EGs{SS@dL?BJZ+TbthVH=e8}$hFCNaL+q>s# zH%ww-M78a)TnNJ&@+x#(ifLdbHcnXQJ+HZdbCb6o@?IFxD7G4xMZ_mM9INU;2@H99 z8yg!aJ$-%oZifyZnRPl~EE4*jCY!t<)UqZ_f{{=!ys(m1_MNE4R z5J=}jatu{<+fB!j8jz{Mz~m`oo95`(s>?TQjj8wppIH~F0Tlse0Ln}M-~TE8l3`8Xz3T;G4z0;?WoU-%!YfXiFn^$WvpoOtdTZ@-VTRqP z?FAssZMB#IXTi3j4fCOq;&j8>r}K?jLenY;Ns<8aFm1{!U7DfL$DtH#V|L%TQnj6J zRiuWVV&98PDiG<#!ZdcYE#&8tVkoEM+`~E!!D&e=FMS{8x zhy3JAUbi_`)u+3s8pUbd^roguyHxxoSh}GCUQM}ct+cVh8$YLI z-g?HA_@3)+6vm-pBDLD^tw9i_qkv5BA`;+^7UVn>MFxbqI}1cGSoEEY0rYkKR(`JG zLj2e>zjJl898O@!1tldhgoSBiuioSh2j7emnYHBJeV@RXPJ#3F7gC%p3~bTDYX$q$ z6G&#T1v#C&9Ts(7{D|-R$UpHn$>IJ#+U`L02R9sxO&qus8V-)_PzR}@Akc0TKR5N{~_92>h72lWAhfoxWv9#$I|8EyW! zi2Do1^`QU4=eRlzP{QZp;*SXWlHH|ha=Dk5-s|(f+TsE{Ar?p`As=23OFZ(@IhrIU z@j-pvY=Dr@kM=t~XjoalHSp1ACk@R!!Klmn&+DFedf|Nn{ZV8n`pcKw04Q8}7)&8x z%}vfY1efRZOjLI%qJ{`NdXt$OZ5Y zAD!N1*K!&3*fwtao;`=;n^;lsJ>?Pwk-Vv@*nDu3Z+E$%a}$Id)?qc~8MWVl*F`-r zA()w&sp4ce?l1tSxKuSQMGa$F@JsB4pNLpNXOJHnZ z!PXHW(Yu-+c~-sqS%0*k9U=p-c~zpU|37Or&DG}O*Ebw*`b-=Pw%w3tKBFMxQ~jX# z0vS&#sGk6BK-@a>K(-MDhn)K%6c}LtxKjkvUx@4~EE$wM%TeAD%Mu-=+B?`;Su%qe znsK)bXqb@QK0RSzSW~RXJV~tA`$bh;1bUNDg?e&U6K)TYUk+Rt6J;NrMx2^_z6_p zDvo!Cu_*<~QGmzoNcmq1mEtA-3Pn9D)>k zKf~wo4$Y?V#uti7+M#4FX%f6xc`s(5m*CWzZPC1{<(lwQqz1x=;h(?GcO6`zXjQ1PGxw zQwIhkT(NUaMaAHX}>I zt5R
VpUtxR*a2c4Y`$rvq5xef zkgi3_jN01TQplrGz{zyv|D#sK&^A_5^}!4DQ!T4h7T#E2ngmyhDglflx^oKqLx>CO z;MP6zYAO5LwQG2kl%25NLEVlzp3f2OziLDvU=}b&Kz$a`iCDXVpuzxUAQowhi>8Py zo~BjhBkT2MuX#j~7I=G`+2Xtqr9j#;;-gzWakN0sA=|y|okRnT70?9G&^7M7kcGo2vYS> z{0pFTpLVFixAcWrt@5(I_pLdl{C451O~pD_LAV9&m?|t?g_PDcrv`s77Oj6V`ZcH- zNCsk|-YUszTyt{sW*JF6$8hfA(NSH4);LPI@_r{(RxX~n&%N`55mQVGqk&5zuY0CO z$#^eF^`DFb!LM*UEc~>)t`Rw5S6W~EOh+;%$>$(wFmS)-Qfx&;&AS*SLXov%!hbq% zcUj;QP();>UAODRP+N*x&R_8mUh$*ZE3aa9x|XfV4WlSM@a&x)!Z$$vKPz>DycVPV z-?d0eVO)MK8Q_SctJ~1rzVM$nK|U5m%(>+D^qznF!qqzY^Y+l)AIL|3xj*Ky)f$hY zTrSXK^*H_C_dUCsS~+Y|#_Sy?dL<#P9)q_mnZ@yE+FZzYzWn+ZA&-t5q^jt;rM-d8 z2Bz7TXSKjjYPg9g7y_*HJ*re$Uv=cgd(V^aDhAAz%4_5bq^HYOf0q*nEGb2%HNQ2_UBCzQB#@9#_Pkq zb9T6dAjiAwGVM;ny=;fWojZk@=V=~69%M3|UjtftXuWQ*owW`LO5wlc+&J?7BkX}A z4B8I|TZyMK5S5@#)dj=@QGLuFO}TR2Sx+H)lAddZW9*UPf0805YOlEoD0=mQ)rAPl znGfW>fhxidV!id=`b6LA(B-dkCqQB3;HEk2C_%0<;fx?vrAs;GdtJfqV$k9Np!DRS zhQ^It01?d`SKf-nt0~iz|BS`+(RlkUX8Wwp!N*j7RpJo@nm>TA=xL}7-zsCvW1HzBDN^j?fpPf~sjAcKeywNDXV(b4u zP)oW-!1k^N(NXbBK=yPA9i1y3ZFXjcBmKsIQ7t+r6CvMQ?9n6b?h{Vm^YbT@R!(n7 znejGZ`r;HnsE*#h-oS(RKR$r9ar+LDT#DB^xq7w=(oF@d50SB7bAo?B)#R46`|ZDp z3OyWN3f8&-f=vGhAt7Ia+O2hf5Ru-24>oBnjOijMe+$TBl>yMIS#EaroNu?Mdad)j z?v{_I0C{x$WTymjyI&<%IzXR3{RQ!|Z#4!9AAXVr@Wtg2l^*!fF>@3>TiVkVCX{D* z2Yv{S6j7}TkivfL(FpmE>@O7+7&cx+pS@Ul%?X`hEY-8+4OT+`zyfEOxLY`M?by@c-fZDnDBjKrrS0 zyEIh*D<`(+=B6#uT*2DxpiuVCBf50?a!5?f(9r0MTlDl9?G-3oCR{~@6NUf%hmG1X7&h z<1c(tJ`b+&uYdc`@1^{|$nihkccRndgdGv2f|IJo6MYMC_acYLkN%o7-+o%y^n?8X?B3eUU$82O9S}V z163`X%TN+Sjcg4N4bqmV=6q*&xCi_xi209FYj#M_NW9p*As#;?ONRz^4 znU&Lg;0MSDmqDL}+jY;{%<)Og=luLo01A*o;lZmDq$T4`{Ok{uW4i4z9H8dM3cCV& zHf|P(#uae=qo5gtaGJk-L8|464JVC7lb@vbwZDfWq|q5o)Pi(;3n*ecgBy&0P|!}1iK7i?vM3qv%XAy)Y9HJzU(Rn0M9RbLo;y4` zufG9qG`<4s6uQC9h-9^E6V$2L<)fAWvUsp!*Rep84LhJg4{D+D{#m#);_~tzz}TSn z`cnA=ooCMyP)PuI<-iuT!7+e#Mk8!Qt_JQO;gOMK(6ka)QTfOUtqW}5 z<_6pIZqf0i8R(SpIb<I8z3&F$@oc=)yJ*XbKk^e>JUB8Le9t1N*iX}2oBE?*-gVGz<-9v zbrJw@FFpZ5w*g;6nH$o0bRFLXHCkvBA_E_Yj)e~{CCUKNkb4GM`-SI#_(4nF1(6V z_{bxG<|n`@y=M|tuXc0;@a6d%W3Dgg8-~fH<;$ zvlF!X;6|T4(eDl`QV>0KT(y~qksH(C_}_aoPjlaJf*cfbTM;jDgq#a6S#*46gQMl6 z`{yMu(G&_R$a4bLPzwY7ZaT;fLRz_i9wY-~^v({&mNy<+o}Saw2FLf&{Q&Lf7&tKj zCkfzolD(){IRRQI-Qx$%=f+D z@AtgV^SsY*%_1GwtbFqz>WNUpaOCO6K@O!3evw&k$@dC`<|E+5#q~ZY*c{hdjveOI zfZ`T%5{J9|P(Kyf+4+Xw|wQutyc_$}*OOCYam z?CjYO-Fs?GJ7Yj@U9R9F1b~TiJpN#U9-|d0^PL%tUA8?BHDapT&Cq_hsL1-r>Saam zn9U8GUv~H-lKuunbL*s%2~qMj5?Q-k9_|m3r;Pc`?B~}j_a9t+&88$uGW3DX#f_@+ zD-6cY*I=keNax3XYYJDZ+vh_2d_F2L@(@tuF8 zP$=&cFwIHXvno|VNsQ$&U#asP7e*PAQpi4p zbTD2Gf+vG|+_M%|o`KY@RD6a)*grkz`t^3=Q9_bqnLn5@0tCnbhIsgW+<+Gf!8Vpl zSDv50bu~~D*1T=Ess`!3TW|P`#zd7JicfFw10UXNHnO^Z=ku_af$TSu+NNlp@X-V{De8<@PLF5vi0H4|_v>HirX;SU}J@ zpJ3Wj(lR#kjY8THsbSYWWKZv?B=kT+7~gDsw%0Aw;YM9gd0nzaEbiE301{N3+6zlU z>$;c1d`FJ03x%$5){vTIu#1g0_lZ1#ta7MC%AQ!ekY_B|ieTYtW*_?asyYs~_(K1h zf%tn~3!w6+2FyA3we4FR_{5YHj_{R;Xk=fG_vlSqwmb$Lldb0v3!w$nS~98;DIY0AHi?WdeWD1%Omqdu z?}>Cz0*swft+2q_o5INHDd>6AY{Ms>P|T>8n$ck{nnpR&iPmhjU@38nv5-AYqpD_sE)QIkCLvQUeitqQhbP83`mg>w#SZ*LGUsk^P#Tg<}%4hudJ+wJkOGVFMa!Be0|K5 z>jsBm;k6|XMTU6Xtue(zC2l3PueWjF@Hz;?U55f2yrbZHeXY`z77WxCa+9&sVjx(W zpm)Hlz+NROs-#Db8t%=qvlL}Q{LIMAEJEo9D@tssqk!J_!3cpNKq=KH^@vT-GH2uW z#OWumix+W~w8&MeXC*skY8%{bnX;>;C>oDe5tFA|p6v@PL-M7uKzgOEU+(AcqH2}fC;i*h z5(8jr@sie;Sy)M(CO3vpfakxdu_3FtLTOXn;s_Zs^zBn$%@qlnvT?J*Csn4wuO}1=7Y7d;Vu({Grl-9^IQT4NQzJhX*1~rnzb6@Q2zg;ir*|kp z8o@#73!m37aKXsj0|Jc57$+i@f!*HS8%g4v!T~!KVp(KtV^CkKt{>#Ir>WMb&}>6{ z+EzXE{PjM9%$^7Y)vOW=)C{t{gLN(Sy=Ul@Jbhe7MCf{jwQPqlKM;QkasoE6ciFNH z9v-5t1uinouXz+=6$&}Q1rG$Qg~WbXmvjz~YqhVrho3YA9YNdG#ia_%`yB?09OX7% zef_+96}{utH*)G*x4gq7ehYL%gP|_iErQt_=^0fG>KPSxn8b7l*bG}-p}R+^HI24+ zsrq@^%cHMd3oW`uB%Vk~Fd88zzja&DWYc)l^rj>DG?z*D6-5sy0swLHUQP${jtNY#3Ut;V!3SL`4acrf$|nEi(oy(XXTO1-zuM=Ie*s!6pydDn literal 0 HcmV?d00001 diff --git a/docs/images/29_PRC_Methods.png b/docs/images/29_PRC_Methods.png new file mode 100644 index 0000000000000000000000000000000000000000..8f2d49095d64dd16fb52a3de17e4000288544ada GIT binary patch literal 76001 zcmYJb1ymeMv;_(TCuor19)i2OySqzp7~D0uyF+ky2(E*>yASRb90vK^_uu=!XZ5P; zTBmAFcUSc}d+*a7p`;**jEIK_0Re$5EhVM`0RdS90Rbfk5Bu3tkRTHKSwK3gNQywz zOc9)X9t4|dNt?^dL(qKI;UQokF(AJDXY%=jfW(7<`JXxjgbXD9|5sOm{Q18&P!JGd zRuIttYoqg7{@8Xp(yr^6-(WxW#ZNs~2Y_!1@9ZOBs zHrnIuD-Tx{XEj|{Yxr(;kS1R+6KKS}WTB))b#Y|#+Pk6la_YnjE#+V zLu!Om4+AYcJWkRZxwo~|)G+sTFHa7ytAM&{N=kXYkDHpJpskrTF?k(zpVvRtFzA#{4O*XHrh{K!L_Vu$7r~D&_YM5` zNEAY{JL>!KdOPhp#eKxJd*fdh^Gt+~Unz>hEfy#6V)-kldFW`D6qnztad~#>X2;-zIkxnH z3Y54fh-Yj1=8-e_<@-m^OZ}RKdyP}ZbIIn=h(z6w_s} z>EaP9nYRnR$VoN+>KNHTq*?8h)@f2PCgdG`oeKTa)HJX*Jz0(?zGl5RR#TpZiA!k) zP#(Q0Mzmixi294Tz{04BuQ9D5eRx>0p4fziUs`v`Z+aM#oLibGj#Rt^z)W3O=j}F~ zv>s)G?w}c5yIzX~>=^5@_}5?(*VYM`E3?waCsvtw1JYYW1SR|dliFD+>^AeT#+&Ee zgDrQl^cfa_SwBM?+P+JAJM#|UVtX1#+Ud?9E5s7gMfbmQMMLVbn)MP0nWZ&XJHk9B z&DPVSVmv0Fx)wvgM?}>{z$I7MZ&9No;k*@|HYo7t)s`}r_7H+zTHJ?bHP{^mbzY9Z3oKiM+}!Lz7B<@)F}r4zd^w}i4Rd% zP}!|omCGjQfgq3N=J}Yk@tHQ6Y$RK)e&W!DbB;#Kd0CCF%KZae%dvC+>6&PbN^8QS zt6*nAl3#{(F72=Mxgj!JP)aq=X^k?DrLqa?AoiivoUW#oM%a7%^+;AUL(%P_ZyC~| zf7M%`Of)$SF<TNJ6ow)ZVL22 zue+$|b{SB|61nsa>rn_7>UOouaz;$f(X5&{=PRz2pS>|$vb=buq{-kG{gO64OLQ{M zo+tiChQ~$ad?tU*2E>n6a!C{J<8?SY3kHpPpJMzNlm&9Zo ztimmRrPa+kZ=bINAJtRccB67?M9h0zd4f zlzAJ_Xuqu?HrVi*#%;2Z)K`Wn8obm;+RaLo#+~Q;kQWGNKd2dZ(2rH`8sJG*Fp;T% z*H~xDRo$=J!dF;^c<&>;si-T(Y46W7YIm0;sh3Bv5jfB4wkxR-D+|{bYYI&hn>aHi zvek$KMw6({E<3K4sB(Q&-hwiXrX#*lc?nZMCqZj#RO=KY<8xT9)ENtF%*zIla0UIG zBpGLH9kwmnYWWaSoRpVPIpa96Rxjx)wXiWeHK&)F(&&55h}3&+@T&R{7v*43ot`ii z*P<|q7B3NhIIHa}>PB4m4d;o)v&$)N^#blI3ixRLisi50TCcu>O`FIq90-PPIr5Mcyjc5cUkZiw)Wir`yVW1oZWc{1G0rnm zXXvCQ6fVSMExO$^>a-5dQDC%}+qa0ldG4qo=RVZ;dEaYHB*6Xjsx?MzX^U;$l8%%< zEoRE%w3ZrW{t`3lCCJxJI<218+<+K~WyY8lfK=tdb+`|!A!t~?+sPNwRM*zd6HZ>k z^ZN+J6&@Nr08GWOFfLd%dsx6EepF-$Fz@DRj9!HN*VcX)6sE@a;L+5+s}>bxS)B@& zq_!USjJ#adOfXj#TN%$fN8JtK&L)7;MRyoDAcFZ^9f3l^#`S(5yN@sC?>aI1w_QUu zU}XR+XT^n$eYtL&0%8Mv^Vh8DaFBiSnoG+uM^?jZH#pgVKfy|Y0BRB%Qc`bnUxJ&R z5QKA{dHzPgu4B-DOc@JQt4Tm!VKxSg=K#pf3m}D$f@_(C>HT? zGY@no^M9ejze(qct2Ow2Ow5x(`_!|oh^U1c@!%SRk7ATR?8-dXXoK(XWLS5nO*UWl zYy3*Zd(f8^ylpl^E+*h@Hxg^T1q|{&9<&)n5)^UpS`us0&hq_E61 z3v~vjzN+vW=%!P$=$`-LZ`S&dN6(1J=?LW7UBkNk+cA`l7$82H(Y_Ot%LdTSjQzeQ zs#)w)8LYUK%;To<7)Gq&lDjomAWpOK*T6H&1dGr<05^eo>0fFY$+8TYHdauX7SdFm zLd{B|+-(CV%|@d8YFv1qh^zzsgr2>6+%A^YXvO|8_P#~MPeIvPdfxT!V(tJK&kUOS zhXRvtRfx&e0!AMPX2n1G_+)0Qd31GmX#VQ`?VGg0B0~QK)^7WmBw|xK6B}c<+6&HN zy6g+I#j+^%1cc}weB~lrUK1HUPAvg8*+<=$^?WXQ=!4_$QGRUHG!y@7s4K*E#kIuY zi|R-;#og$ZM?Bj~UaOFE{AT|VB1c(*ZJE9cs8xqY%HPG(Hb)XYx8X)c+f_?d{@F1$ zj%XNMEvK21SJmo-X;=Y0mrzA4DgV1bj>0YmtUjBz4mSQoPG@A8(iBz*B|8U?aIM2) zyU7LY;9;$bpfmq-Q;;2My2a8Bi7aas3z2NOTcgQ)3#1zy01OUS1nuKbZDUv+-Cbs> zAC9y%liBL3eLYA$_j0n$?Zm`d?M8RIC|<96>zs^?DW#WnZQkp&=n;@yZDx`sVW{^` zZlM%Mx838)33#R7dW&VtCfi-}0yqMroaX3p+p8%t(ug#T0J@~ZbIo5hDVEm|TL81V z%ycv(|1RA<)c%BJw5Sq(I1Z>wLTv7!1PqC77p|VUoOL*-WM-5$Je*bA^rzB*7mqq) z>pzefWjCvCiTpF#8K0CM8|_P{{bLs-`4u&@f@+pa{;=skKBrhGv`e*^*(ys`^3>1X zG{#=7DZ@!L)~iVRCwLL(wH$Vp4g32^rYP44fu1!aO1=Zeg}xqv3ZTvT2p^mB}}|BO}w zbWXN79KHCL5({Nx)w^A9P}c-lvAYU8=s>m(e%+F(!|qpA55~$~_0zbKYeyJw>3pjG zZ-;I%GKxzV_^h4HKeSZt01?$L{>CQ3p7z16<(BSEi8^Fa(Awq%omOKO>y}RXHl>c>e zvwbVE`Ejh7fV%%|P2u7$YHY89qH+0tG8GfCgnaSM zRpby`-)BiI&IhOsuC`0RqtXX(yII&ZoAM-e0CH<}29CFmx9}XtqBM-jBsKltaAeVP zOA%~jD}CwM&z`57K{J#1uA3R(s!Svjv5Og(R*AE#k>rcV=VcvzY4TGHVk1;0c=ufQ zGp;-@Kx`NGneBd|-MZOyG!?aR(KC}57%B1DHS4h-xfmU>GZN$nP}k{IttrG{H^j)k(LFo za~M$`V41JtSubhiVD&fQg*E1;G$?Z$n->GTs+o3l~R`sIGw>*inNrX<;e-cHHJ zImfBjt40d=Y`B1TD+FhMoa+#yWN>eY;)2Qp72rElmRQK7_ZBzFQ;&7dxhGo3H?z>HmniFzq zl^*$FwMR<&ds~TSjdqZqC&Svr-{#wBtGR%CqAe*gJP|t&;9dHojE_szNDeqxlFqEV8L77XUmLabBKN9h`o{%M(?}M|No+CiEN4NZ@QM&VLCkSUq1R0J!h553@27 zi%osylD0pPn?oR!ux{a3n1L+0HJtaWWsc~Om4>6X{fD6&Hc3~HCuP;5CYY^yVpTbt z$_Z5)o49CMnP}cD=me%uA<$`VTd9h^l$D`x zBfK!ox;l+&w06FXjQw0I=rnd&q9hRTK0N+iKS6BXi{{xte?xtL7k^i4-0Fj)4{0PE z#l_&gdA6ckk_%YvrmNDuQ2m$6r5xGOt2w{Ta{+E>H&|!_$BVD-v-_gd zC#x_o^XWB_*1Xz#I0`dum1(pLfKFJ+&=W&K$?{>pw3Xek;#+cFLio!-0;m*{?eIzr zqYd*gAytz2B*QXbC%-1~d!ul@GP>7$pz#_lwTyqx`yX?9ut@3qUp2yqv#Qac9dyaC{O(z+xPCBW|3RCCebPg%DHO;u^(fRH3} zvj}nYw-EFwx^wJJ4+}@&)6)}xEcwRvB5h+skI{$oj_U)DivuJQ)K9;_$-uyHjRgJT z)$y1O2f6#ryn3rluzvp3Zttspomn=EN>VcTIEm(zTT2|QXMymS z-aRMEU2_+$3+`Ma1oN=R@MXiafY)^| z9Dm|1(ESP}AXFl+$EkcPi&M6=%PDus;-kRkF?OzUljGQ0cFEUvQ^&09C4OnsGmUJm zMY9F&Jzq+8%XJrRWf8rM!%_HarDpBcP^OjK^_KsK?_@TwW}!sPUrIc>gvtHN+U_~v z`#s~^eXajuAPkbrW!ur|1nab#S34zC=Ie#M|84B^ev;zdMGMGFBTdoE$N%M|)TU+A zZNAg<_U>sf?kohyVCE>-e@gQ+rbdp1h!}`dcoD||-gg%8cIH>UD9qiDa!MI)6gcZX zs*hv;YVruG}MxvMTOjqshZ7hWf=dIQBL4JX?+-P;wX?H1q zxj!ql)D4~*$7j+cfd0g5{o)*NH{*<6hZz%6_qtKq9$vNR%^fF`1vX$f}3e; zTKmZJKKUsri(KDkfww!=O)D5l@5jpv!v1>ym-*aAlR-ql>fgb!Hu||}T-Hw0*4aYI zvz{-g3(3@~E(7S2$qBz!N5_1(U$UaMVUgRDvEczkJL~rW7G4_plvs>&w;+banHy`5;e5`bl%yKAn-olqA9}W zlOQAFe!K2RH3+-<@F4w79>@2$H~c@wE{^Xe{0NqS%`)EqVv85s=<#xM{IJ7;5QTti zhJ1NpK`rjj%j1=yo7~w_b(in_++3s2vyQc>Khfyvg97Qu^d>*?A>M?bm>7#sX%5)g9Fw)%6_ zd~$ue5Z8ASN@)eT)z4~MRYIb0$}g_`Yr8r1?6GDpS~P-=ko42&bq{w&wkt}!IA9-+ z!+joBElm6}Q0T+G3dq}8ux2aNY3=g}#Q0|uK*-Za-QcxbQw%Zww&`y_@{8O2 zQ*4Te3g`2yijI9!e%VMAYgSQFX%3(xC-3KtJs!B}V}D_g?EXbDE^m1%HGboj z`jG{fDJ3h2*zo!&{G25Wt;Mm>pq9J5`qyk+M?AO0?BHYx0V##UqT%v5zLwQ_iQ2CB zc8(~_>l90y@*nc!Rw-H5IKX!<;?&E=3N10F&bmrqT7VGuQQ#OVM<4-4T{B1CPgHnl zo~nZ6Y~+pJo@wDQN7MU;oSR!ajKC@U{b^Y6G}ET$AN=;`V`7OiO>Z~DuZi1JefWA0 zJZ|`2@X3;U%>IVfC-AxMH7FwK#qPF=^W^j^qSdTfh!cE2o>ZTO+|}_pt8VFZ@RW+@ zWhps9GslFOwlU-biefILVHxyPqx5f zdT4rH19d8Swekb4KESyg>v>fN`C%2{k2gctOjj@$w3{?^GbcSwz)p_$@9yZ=&Q=y2lx(82%gg$*^sM2@QZNDK znn)nedG6d6&YKscc~=Wti}Oy~QQ6yprpKAU+l$%l(|+8OO#wa70yf)&F_7js+`+f0 zZD^>S!Qqn=KR(`DLR&Tj?3$?Dtl89VO2AE6z(;HTLSPvCWcj^H&t~$2-k+!aPbWD+ zcY5wVVc?mxFDP6>iUQ9?l3Ej^oBkhfJPQ&H-46V%A0>*pmy^|hyiUtcR~t${n!MfN z7jOek#^+qed7V>IyTjgB0I9G)v?!y=uM%LRscm>cPDq85NHZq2`CFCeQRX+0_ONzt z8`tdUJX%mC@LupNj*jy2P=kmw>}7$m+Yw|sq@?-6mw=`Sq!xU;rhZhx zjV~~jW``3Q22+^WTEC=!GCL|9R=@|<$~nCKtB_L=csBj#^yzZ#p|=c~^dGx(OLCVF zPagIZmWjbcmbV_}0N0Ou&yDMS)iJh5BRJW4OV4ZJ`)ZM(7C5WfjCtkVoLcEH1jqZ6 z`Qclah5c4oU>TxE>)c3)4gSZ z*_?}{`}IzC9#Z3sVzbvw#qW{ox|I)eV>cv)&Fw%@AkvEkkHkjM9gG%P6X5}P`1wk> z%kB>8Z|s39?T7oXy)kEDA4m<)By=2d^6zhdoTvU-zq50|U;3Z~f;=`oQybD~1M zI4S^+n_g$t2AhIp2-I4#F~C?tUa$A@!+7s+f7VafR&mjL#_#tZYd>kQ%h_OT*3@01latczi+5YpwwapAVB*uqk`gv z4Znu^B*OQ-YW&(5wEl+UtOxS{=rW(oJXnOF_?j*AEgn1nrpxQz`m66I_opBzn)gZ2 z#3^c*<8*)2PBNNW`h}6Z^pLhtSAoL;F7hpW)%zV+%BDvQ25-Gm&Olx(F6c5xnJyKY zzcX#DX%a956`O3yl)rV)j|=0LXlpwQ3S)U>_J-pgZ)ETjTU%2(w><(q_-s@cuY~&QEvQCDeSHQ`!tp zNRr`KuZif?smU_SB$<1`j81C-`K?#_%S3;nhLR^;BxCrVZ6;V2;QIc2d!gqO=G<@yNj1xG8Nk=B))507jG9z&bJ3cMF=wf^MAu(V^fvoh2?bQPQKApJB0ukxR#`Ux|KHitwKKV2MlBdEOC z6|Lg#zi5A(!CCV=uOIGQD^PpzJkAe$t*!8(f)8vY8VOeCAY`eqPac)D$lw5 z4EsFNG0YG`|L1fugC_qin_xRNFoiL9crv}timU4V{_jkw(Tpg-FJM&5zRH}S` zhd%;%E2}h}D{fM`&kWbrLotXG?nM=lh$|6O_wAb^Qo@l0Rp?$hAAG| z+U}Q%v`T1CbQVK{vXQ+cyrog^tF9w)3&HyZRg?0vZwg$!yuqEN9}O&qa=k)Ym>M3R zF?=UG%y^6TD(J3X>}nRfT;^C+*%5x^@Y5;9rS<*psC|vPqW02HK(kh~{em8}*ae5x zq`C}P%-Jho;W?x-OZr~#5LB+$Tef$YW&fZT;i^7Fc!g$(0*|?GH>)_US3}F$SprG# zT{cavSngd4sHOv}(;noa(oD`tl2vUx*Df2X%BiS0w|45BNLgr_&cj{QdMbWG#U|^* zb~s_T(GR+dYj>Bggxq2WR6QzaKIbd-TbVxZj`7&Rp-N#X_b=(deCN7oJDiM_pX0FgCaYtZ7R%dUf(;;v$l940qYk_8aaXUm`0y!|si7^!}g_+9YnS zhrz|iEYR!FeD8A0U-z+HWzJNSuXB(npD$i5SgP)M2H$$NRqTz1{rwVe19X|^Db`W74jwq=dC>ucTbw7rL#Bh zoRl{8ZU`uAjFlfXOrI|lseAn^z7_Yrmr`=sZ`L^C*iHt2i6U`1$#*i;e4@hEbcJ5V zpPklX(87YoMl*#K=C_x{FwWk7=u43trJ*CELk7BFeQ^!{?VIs~`yg3$;KdKROxfj6 z4-$`G6^~R5ph`|TqmI$H%>X^df{FxA%ba0w^jsn zF;kQC=Q{9eS9c*;`tEFecXklsE#hx54_4{U4t?!d8win>BY~9-VEUWa$5V0x1k7ci zc~YSSWD^GDYMNWB+yL*acFpf&1ocE?{nP;74_lXiqmH3ViIQr9wpr;M#gRHBXc^}YFJ z<{9pCcRXv*fkt+5l8yQ(& zNVsdbt7IMiJX0&3b`J)lrfcxoT`ks4U^){A6Vn*da$_N0wE%jWAd1abo0vN9nlF4k z@tQGL#?M1G*Y2PAK^akGM~uvv$)dio0zW;VZM>p4eOHgdZ;$_RqXD*}U7rw2{`c=U zF8>^M19#tqnyV$ZMd?k+lh|2sxpN0VfA2MXd38fl_l&~iVm05@6T22>kD)_9=H5L){D0nGM<1!kho`GaBhj; zYkfP-ysGE)?iR>!IGLrnBmg!UeP-Z>y%hr+PYShb@xSW?@8{Lqn~CUPK%aj50ak_} zB%JN&hAzltvq}s@@CZa&UQVYCcA#JU!63p$rSRt%9X%BrG3kr&K4Q1_#D&t1Fo_7< z2UC6lW9N0BTLO)iQM9#X+=M-+CU#^Vcw+&+D*LAM#m_GT*3G)Mn>=nwx-j&F6^yLK z^x#%O`Nu2rX1PjZH)FlSta*JEV2KHRtW=4J7xdl7>1VB)rG?yf=#_}6pj2%q)*dl2 zUIGrDS$HY+9q&VFgUZM2qX$61~gg-|1thUK7t}sEnHm#a_#QL9(X}o0-k( zfZf2~T2?DmICf-97(4&cqYomG#H9k)l`#ktcsj3>Fs^q7NYS975fN{ju5X7Mhm&nm zu;*1Z@7tAwBtC?hjn}Ou(IkXrD#X7&sC>_!Q`ZD^1cAp%l@#IQwa)i7p=Crx{oXp} z6oYL{pukD~=kUhN7{(OJ2~1%j2(lhO!0JDqVv-UQX~1g$cX&2DsKJmyua`Z+vjEDE znF4J7#?#;4jYp0LQsbQngNIYnP0vAQ9HZInz7mBeM+*C&iDL^r>fs%6e?k{4HN9~` za?pPN25}5b49ukMASO)7Nbk}I`a_X#e+bpD5h%9}Gg`uH{mvr#aH$z$)US$}t-c>u zc0WG$RRC$o-=5*Dlh7S>gH!A-uRO-BqR(63{wz1cwE;g9%>rJ;KKU+@#8~NtLN>$% zo>s(&G48!+*0CQrv?|eM1V6AdlJ{FbecQ4#aw41r8*1$*RO&1c-Q)-pDkN1hYLX&O z=aNKK)UQ;|o?avjbDa_Xg1UbBiq6rJWt%^fLF`xb6ojg=48Bx%fl)SCCp_l(FD33i zRH!LDYQhdasvxOQLYwQF(A~pKJYDK*c3qVeEt#1Ix@UMt{7=F@afBhG_b6y{x=+{< zP$EJ?#i;t&oQrz-cD0d(9C~m7SBm{M5mNE4&&` zK*6h?@5_j?SJRus{S`qz7)5sB5-VP#ca2@=t<(m~Y*wE+^=f|H8ZFcw*}vwpZNu+B zNc2XcMCphgD!o8#_A2cI-VQ?TTnk>LWa!%_t+elc9vV-|^TRfKbVObH0a@e6u->$b z7VpHuX?+nCcJ@?285xaRvh?d}=2F_*7EZodea+zU2v}zH%mVnk5VynlF`cmF_VZ!` zU+T&VF<%CTyTQ*+TlE-iz*$3DkK*VPSC-Q0X5r~mY$gn=r)0$=mB2IRUz%nop^YGu za8D;_pb>}ZihO%sC`Ersl>@FiZ%5mfqnK zbD8baAik&)F@MRyEah}v}1f~vS^5*z^jf<>?ftZu=Zz(aDD_{ ziD`#syt=TPCZgd^odO!<}QEa{k0EC6; zCi`5FrPnCvZ#lQ>ZlJ9A{|$UIh>^VOiO1!3Dr#}ldiKS?y`qVTBB1Zvn&v(tP-N^G z*d=@Z9)-k7ma_LYuzxcK?!~S8fPzo11%pTHhBT^)=S_A?9b`QvO+WRgVHu%YY ztsAAJM2n{Ru7zB+q2O{C!?|^Q)x61@vR97JwK~R*Of0ZL3nxxB{X2`pDy+@#@SS>g zAdfKcYm-hH;s6_h?^Z9iuh%E6O3MzLlUMs%kWGPqr zznk1&4@C@xTNe!(q|wfV5fQN%Gtl=uNWlX%Aya!}(JYwW1s#V=k`P7~pjQQdjo?gC zlhzCFRkdKc+hxvj#DYS+YQ>;URGMiGSZICu*8T!42 z5`lk+vnGMhrhYNZXcxAZ%fB|KE}44^aO%8GGVEPyocBOR{{2m1pnwM(kSOKcVYgnp zbQVE^2eczG%hb9gZ=_QZr|M@Z1oq+mi=s7Znq4M!IYh$-)CV%Fhm`dw2qHwFkA%7o z@q}o3$fXHs#FG*Vg3ym8hU2Ir$y$pL^J!gmPw=U&6_}k1+R7cZ5|q#a-yCe5=-%j; zNOL`fr_}0Dv1+266UW4qjrZMw;A|X+;Ro_qE;1MQT0633`85oYKVNcK?hx4=na6tA zs$zuP)R4`CgKQGA#*V+#X>(_^>%RvnXFY5(qXe9iU2owi9^2Crsf?#zdOfADyR01x zM8R@mXOCV3+R#!~N{e_>*Um<0;tQ#R*|34*@cs+j@0p;Q#)Q7%c z)rD8xh;%X=CZZQl;Kl!X-M>X`l_v1-AkFaMp)l7}o}miw&a4eHmr2xhpS7(HlmBQ9 zZHszFHWOoDvB5&o-uqavh=TcE6x{7VzYSHMiW8pJJQD}QrJeLOyS1bwnTEcmoko(4 zlp&5dC zwcUb%b-gQ_jv>!E%f(Ct_P&;U&J84;xds;2E8>@;0Y762sqR6uv$S%iWv}gcb#YiLBktdATB=7%ki_mIuM`0lS%=J%# zin`O>FPeHy3G-$Qoxv2xWsWd$E#w8=CHsc*AO15RMw><%Ov53R{c{f!p2}8TGyxEG zB_1(E{A;>>CxJ)|*C>U6!x!H;bOx>uR*kW@N6=OEddMO)sZo;<;f? zDv4BgDIj={tDB`aCHy|zCW!;>L+ic78oeGSA8Iw9*iON)?)WE*a<>XUXdY#dyl%*c zbDz5O&tGKYmkYK-um-rpSOIrzJAL5ERP-RjBIn7L6*d@eCvZ?mR>=b%mCZ`R0&Z>U1KoNH3C>Z~L` z=zcaU`vlzX74)ALKofz`4N$D|P!pC~U*OMw_rM>7P56k=)iOqD{_UY~HffapkjcZ( z^<;KeH>lgy8qN95`w(z96i0k@a@v9Fs5!^bcdsf(2n8eAcN3vb!d3fud+BRtkoqSE zHiD~|K%aV{f&Jy#szomH=A`fE+{O(+)`s!g4$63OI`9c;kyBcm-D?DeC$(6)&%+VZ zEEee8RykYRPn&nhGAf&{4*(t<{n?nHa?BuY{@uKV+`B9AnE6L|>I`~ueTuuCo}@fB zf-3E=xTJK4hv~8rc@tFu;$H%V!zl(TC?XTBrFfzui$o4oxE^wb68vbxW zpCSc}&I`=^0#Tjb8giVh2m_bd!(8VK-u$w|e{k9ay^(MVJSWT8Vy@l?e5m3_eRV#_ zIz2;yE+wqEond@d4zZMgVlm#%hgLKARZyhu?J$|iZt#u`Ewamu9m}Yt*rIL1lZtyO z70Bo_9v;9=0aI^Wz72c6+0o+ub6;qmL<2b$dsqZR?3A>s50d(+h8IefWbPCmIzoNG zyR4=1wH|t~evXv~tx6be*ueWjy&1pBa@1SYW4KF3=i9}u8}eq$d7i|(64mamL_M90 zD-~pY`^ZWTlX0MhCuHciFd<*k>mK~Hv+DDc(>AmCDO}emJAslop2okPiPa+aQTHvN z{I6N=G3RUQo4I~Ej{RZGn2+v`SG?#@6RXL&E%~(-G%}gKu*i7(T|Qh6$f1dlxuhv$ zWSFGn23QE#%4VdOT1p4NTj|<@X6p`QG6v$8%NFs=Ohzr&cz^ZKPigg6*K$Ow(N^ij zuwlj@kKG8b&nY+d17#I;=}_DS@hVz^hBbuNX89A91e4XRR^U~6AM#z~vZ_zJotC}9 zHqS0nAtP=M9@fq^&gm_3gFf;+@MqoLhTkF;WY)}yABSs#dg3(v6Cscf?S1kE0~^!( z5iUBPiDZXzLA&-3u5&K%3*oIywA8*BnVLPwAzjR#<48NDPonM=OgtjI??*Fl+&H8; z=^K1>(NaveqK{^5!IZ<@(dMrR%0R-{;pLcZ4){rwQhAxY89#Y?DWLD;78^XKuHW<@ zaaPQa%aqexZbNQI{(CW?uIqLHa8n|m0I5&Qbw`}$uSHQ4rLS9)1q)fdUd}9sWUHW? z8}xUsy~9EfH6yPR`QNJmIHJ~mtj+P3qxTwr=ua(JP9br)M~c#=FNw~@34`Xw8w1e4 zPsY$Ywh{5Lax;8GHoTxoCcGMX z?$)@g;425WMpE%=>R&avG?c;i^p`vVvtUj+fQfB8W*`7Pj6RtTXc zh5SJwN=xx=P^83DT%-}XNbCov@OQarl|zK_a6Tvz22#xK$8X@VmVSz#vx0JsEcMdC zNC|vsxc(o@OX4pxh`9of8_qe3c(ift#_8ZcQJ(B_ujQ(xUd0CCwgX+G(9~j*3NW+m ze{v5r!{Pge&ksRkpos0)E;rSLoIjmH_8)a3guIVxQwCv`d&Vs^40A0n{hz77BLn3j ztNTuzS>aQE*t8K!b1?oyIb{Ba^qM5{K1sfNm*;~tZ*`^$Z;n1mRQ@|9dwPabcjana zcXB&{3C9BavZD}JXis&DctS?Q72=y-c6di+@O9(70xfOmGZ^%-MY}EAN|nM>S5~$q zjE2D2CqEj~qw@JSQb`Nmt$Z^kZ{J_q-~y3mF|-hcp_ija&>KA2#}x@MtX(~*f=cTO z-rn%)vHLyFoStq0c!WBa@a19tJ}i2+?!9A`^&lxV8Qd>NnU%7*1WQ>Ri&qHWadj`P z!}~2qpr*;QcIvG{zT-0eGf$^e?;tnn#((+Hx>8EIva~yY z__kZc!yqBn&b_*8jTRu@ETG#R+vh^Iu=&~>*{BxP%%P=irfjG!-aMHT@q%&p`k6ul z6-SkW77S@2ib#YGoBG;pL-Wq6o%PGctL9}T7sUN0F%x3M`7&ODdHE^zzIaE&1LKOW zsIaV8n4%7=gFacW<5okj6G}#10-uUvdCn6t>$8R`iFtrs4P8W4eAVRZSsj6u8Z zZpXVH@RqsL$3u@kC^4{zn{mYMp1Y=?$RD=#h}4P){$ViE0kU*5Ko?m+ZFPR^o=%&+ z=|GyInr)f$QnS7uaKCa}1?6p4SO;Hq*=D?B`K-*9*v5L8W3Ax~_hs*DS~Wk#ki>_rR88{6IfYFDu(qRX0f(j0k{n!=v@BT?YjP>ie;n6s^#;k+1}`4jTXQ^q_Id za|kV|PU0ygrR_blmWkF>3-G1SeZb(&BXXAUmcq^3k!{gcou7lwf2YAG=FWghGgu0!+9v0 zfXp{!GA-O=JX2x8oaxZctGh27oKt%r*w%p&ptyy@mD4|A-92#<=Ki0J545~Q*~fyf zkQKmO!9igl#!K`I2yUmV*&`4g8~y3J^Za<#JU$j{uPkLO@dq0Ah4oHD^?pUye~zyh+0UNNX?4V zheh0FZjx~0-swVzI3ysFZF*h9v#w)#FR$UtnQNxA3r(P%kR~WO-4iZzd6a2IbicZ)YtcwJFK@^M*dO-S3muzgXi}Y| zCQ5wupv9mYVV&k{sL~*Yv?7o-6k%gO;n&o26c-O$vc&hLdDB!y3h^qp7Kty@4#LU_tk3btx+zlplmLi7l_#2wOA2e4j<4 zkIrag7uiDSvJmU(hlxOMR~R61HZ-lc&B#OZzl@}r3~o)T91MbEuD@Xc7*TKiCp@>l ztF-$nwa8@9Zmk$!l3OovE!3vheBN z?l~K0VJUVVe%V-5jyD5eS;RB3&WoN&jCQz?E9j=b9VC%3g-06Eox-tDN$xv}_id-K zH=vD#wEKOHjS!It4}Q?(7-AKLX3>DjA%I=F3sHmZ>oclDC1tAqz5UnX83PJ<{V)^8 zvb@JQAX~3z4Y?Z`%EcuJ39uFYnAPayTsYffxBhsd7`Ydjd%qg_@RPh6AY%GmYG2F< zheK9D8)=poHyCdei(|k1sfAX5N~lvEu|v%wmEwAOPaRj?XOqmrm}mi4nZNv^kN`h- z1Eb*w!z}CW9N=zl>`|T#7l`&?zfq5bLtxy5EQ(W~kIVOpi9af7lB9lr`PQyz$w!;X za^o=93LmeV@=Ie$(%En^Sv&VQ16T6wdei&(M)YbSz}MD}?Qf%t>WfV+?cSnh^8JOo zwbgCZ1!FyW(_7x#QNCl7n?>a}s3Bcsd4qVwOa2^G*oHg8udO!ZXvBoP1_ba>Q2ipL za~XV^FGIHgG?>wNvf#(CshnHURD0lCb4vv?j1MV8L1X#t>9=LmsNW^Ke78?%IL{Rx z0VF(CgyHDZ-{vv%`C=^p1>zi_ zZCm06T&`K~kHN#O3tQ>^;8tGRO7tsbc7+tx^g>nvE>Xz`9u>{6w65j8-8atsf>)l| z8&{^;b3nGV%lcfRc?(*B`PPKJ&RBj{K~=>GKasQMs`(i3Mp>*Qp}Lk{8PX5Eyv_BC znlnj*+OqJUzDt!Q!e4N61y*atP&D(wo_QdF(==GB)3J20pYZ#*ep zkiBmKZYk%3|INjW8D1+cUa71}ELXuu(G#jj{>3C3!pYhymq5n^+M$-C`O`W`(&BOX#3f%7Afv+Hyh5O&l;A_&e#oY#D>w$)<55Mm`h$% zP3Em)>+H;H6}sh^n*SSZHbzgksbMRPhNkWq;rkaSF)>?ZNkW~tjst$beJ_@`Qy?-W zzTQsjd;Jd)!?2dH*c=FEx}VS@1E+l{VNnU)@ojD(-huat?7gi*2_&;GDhFYSn%aa95ev+Lp$KFQ=SR6OLms0ns z;QO?FY=d2=As>Hw%QjaJsTT~ai1B+4ByCyH(Ngg6=^!y^Z8sg*^X7vP7XLPL5!rk} z3Pr)L{9+T%ObIib zDH3AjB3W{y!Of#?YXKzXT_Zf zRR+sgqGEsH$$SR->8(#(|2Ca&)2aG=kb!4}|Mx8b3b{>pT#n?#n$2vafX-Kuw?CcY z{=V)JeTb!2q9*wKYXIUHLhGm#T&w!m5$xN?VQoZ-B3CZ@>M|>!wBgS_2``1fI3e4j zV)9`4U@RG(|A)D^?5d-SwsjL+f(LhZ5AFmfxVyW%yF-9LaCdiicM0z9?(U~}_rC3( zpKv~{1`VoKRn0kT%rSa@h9{~~ytM0HaJ;(8nA6klcl)A|MpR7YGrH0;%uLn8Tj->$ z2`sB~!3}Vg1_M%j_6!bkPV16$286(V0V3MGp00LJI`WMfmF??X7@oj^lEE>hC$JuF zbY)Echj0$^e?fb}-WV{aD=TfVmgJ(PIi`G3gXN)&-Mp>?o*+By&lVqPrzfxr-4A_` zo986up-*)Cr>{3z^hoiV2!`Pd7`p!=eBtdKQi+nvMP$Af5Y@jDFpSCBx0YBWJnJ?; zXrcRoyu`fLIfi#=Gsr}HCKpv5I&*q=(LNh=#$(MN{3@5yKJu$|>k%q%7@CA%&?%H= z&BQWJAE-3A(?ah|KN~svfh}L9P4NALTNMe+T29RG-*eMW)XLTo2RzfImfqNzfRUh@Y5;|A3YcK!gB!$si6PkkZm?UviSZVcdmxVUq+a8#Mc7JeeC29C97 z+K*6bcVQf)u~;OaYX-MYl9PRCzW;y+Q&#fsj#{s#AW1_4+%y^v*sG3RAF@GW*97W5JH2d z+BXUxS59_t+igRpre5Yz)9La8Q2h!`MGyA4yx9~T{A>^Vpd-oia9uDdIhsaZS-X5E z?Kj2;R?!Z$+uiF$vrZ-9zbC-MGEdVzKRKuY%GQnt4bn*vFG9LD^;?$BzGi490}bJx zw*h4THqUgbWqL>K><8Vg2b8itq+@}A-_2w+BFjQ5IZR>q9ajU`E*MgwykNb$+1Y>T z6>qkllWt1O1J!o^o^DRXvwSgo12$pzB41QhlY%IE;G`O(f|14m4beJDnMU%z$ZD^e z=9*9@qC&!b|LuW%Cy7BH8;E-1=8%U`!ycRcM=mA9ufjK2%?qD&Lp28Bv&5DCc$-Vo|^ zHgT+&Qz^B;K$8bW4$JZDuF`kDPGeL4VF)P>wf~+5I2E9Tb@yM3p9fbV75`KV*;Hs0 zWx8h;{*-AEr{%ntj~iDql*-IjEagi!QTFr;njN@5ItywMWdK1SFbmR7eOYZoO0tNE zKqeIR^^<9GtWyQq)zG_}ZQO+K6TH)kzFT{*nAMK&3mW};#oSeE%T3i^D03@7#68pA30P2%WHgIHjIl zMM<-VjsKwiO-w41cD4d@1%a_|Jbb&*ng8f`Rh*foQ%np@XeoN2ZE-xsh`6ga=_iW& zl+LlL9WmUrQjF}waca5+Eho|Y)RQt9FC8ubiE2i~E+=?5mWIb0ok*|s^fON-WOS6| zUsa5RiH3h)v;9~8i1!wRQbEu4dReQ3*^htdR5>>oM}L&Q&zol;FF(vizBL}QiQ*Pl zloQ8Wpv@OtT~M7ZnT+*NDVF8Slc?4yt~g8(Lia0l^bvId*~8Cz_3>wwRc>VoZ``*c5Jo9(PH@LgEBh1LUV@MSz9x1H{Ze`JP z?>3_H-wM^uASzm(Vb?TRmHFUdbv2$bfq$hH1K~pd_bki*)pDgJXE#|EG`1#%X?^;;G33ANjfF#KP&*A@|VP?UBx^%<e!zae|+ZV(h?E2SP= zwWU3D#7|yKosWY!ohoBmp86_h=^Xy%tT^3YSN3SsE2jRHk*^yM5mBun-xgePNggyT zY?=&*3NtnLpCX_gA(j&dkx`TigtDS)RVXHMJjze0+q$O}CTJ_*=U0uYGY?n4S?w$; zn!J{tW_bx1jB_^8amskBk`K3!TW}82=JdgTd&%<)uNEBb#PKYe)_Kl!iJ>`NTuN{- zl@$K!fWm3_>DYP)iTwljqy`XS7Wm$;qH6>j;*a{@73(+CDfrECax z4gHnjE#8UdTTkV@Vm;l&hl&aGB&x@jFUqjXEHB`1K^|Ts;l4Ob(?lr6P>g&T|24px9BF6H32J9V)uNst!#npH^KKfW&A9YxdU>@5=-pZ zPa!CGZ0@nUghY5_2U_1x2}Ei<1HYKAU-DN#CaVo~_APkWD(Fkm*CG8#?>UztM14Y{ zRB#NlMqcpt4UY?+%4MW_B*0^$!DFLjMzN?7^DC2gjo7FHRja7RVaX`bt#nnT&PTRE zX+;U+dr&$aTu9gREU9`%N`9DR&)xNH{V~c%ZIAoybebO|HTOAxz15tC=u))R5%>Xx z$H2Gxs%xFIat!P3i+{>>b6yUB+8r9iaeKd`c$ko79sL54l1E6S)*G$EF5a@%$`A1bs2{FMzU?39vAYQHI`MC6L zZDhR|xhIz59n0vn7t5fJS$2@2Xgid;$fW@3PC~6yc@({^&_te3`MT!U_^)Q!7x=@{ zzYuHr>l)s&l}>grsmw|zov*2+NR`T~LtDp&=OOb3(eh>GP$$4lB$n03y?O5Z(Aug- zMfbmZ*hw#;+!9r@=Nz?Iv`a0oFka8;H@E2KF0+)f)*117Sc#$`QcJl|v3zlAzKN=N z_k$RMB8s?hbbsHySBpxGE?*}{U(thkxhnA$5F=l z4_p8Vou3~&XsFmFloTSlnt+sKD14;pm=2IrohkOz^b(brg2Ok+aW!z;O_2qP?YZd? zSlar|dNSR2_6kGE#gs;9*agFhB}epPIri=4?yiFdb=`7gmaMJH%<}9>);FS>MbOlj z7$nNMzc;nldpu|#CnXl6b~Y_D3vOkngG@s!KIKgnFIk)^fGd{2(3xH)T7vbeM0 zw4*Zo6A@njvv5o>R?(?af&e1ibf&m4Ki>`2KM9{&$1u@>;GJuif6Hn={xwZyo=(V? zSOpE;1bt`2HoI_!2(fR3_B>hhw&H3rVSL{(tiwWx2z*QkFH=F9w(gJxpqn^c+o*}*f? zDzojtZFwOTX$5j^N6%PnNfZO5u&;lo1bzGxefzC^bXS$2Gl{A+m=+> zIrsaGRV`JUwgS$LdqMs*QBD4yF2{0>+uKCrn%punQlkrlH*99ErJg}9OF79_4^u@q zcng>RwBqzp>V|jlWbe;=XGhR#VA&o-q6hKHMQJq^xOhN}m-=qcG|ETwYA34yO`~u{ z5oB8RLHUA=IiZ%(Y8r}*i)&wg6~IzLLeE=RsOTk!@KO7F-7-lhw1U^^h*= zx%W^xyn#r2Hfij(mDVAQ{*3!lBM)f-UNc16!;NDttTQ>6sq6N*^D0`ivw!r6X0nOtZ8vqSe*J z+^Gs&Z&8dc*p2!{4|qmDOu!Da2nm2lp(>}UMRj;#Lj0~1!RvrM^S5B*P4dO7Ga0X-YN=;x9>k(ix5_XbfJ%V}glfb3sq^PV(42De9$Jgep-E`mNkCmF z$?l^lzSk@)ydGZ}{r+AQ&%J88&->GQwhtpUI<>`Gi<5Rs7e38q$?Ixzqk%6#2|&$C zmBTMtv{AB{R=AZMund}bkruCAm(NU7TP`2PW5vuULLo*s>#UQa^1S0Q+C!z-5UC5> z?~VSEC;fEQ}cs&wvkWD(^loJM1oqMZjJzpjZ z^^3xf2t4c_nLoZ3haD5-TY%`D-1*73P*6T;a2x>ka|L$WyQ-5E-zbB=QMg+k`$4+TTcDO+ zcyjnkbC#G~xb#LpO`2IL|ER)8akS@cK37{GUfUDz)*TdHlW$tEYq2PCf@M8(1>se9@GeO)+n1ok)$iLUYC5+ z4zn01M6?9M5deRAKNaH=)#MT^MCu&5hF(AM@V9>A8564v3NGT9rkr-l zPx7M_emGT8Ki@HY#ktDpXW8p-VNf-(SY&UHmIreor?p}n5F;oC=!-r=S-h|N%dV_g z`o4f`pL<#A_5p#K?d0FbT4i5b7^kOj4AZ=`tg(Gv)QVzG5&RX*$%eGPD)PJP6t@~$NI{`N(-rqYDRoiv7Uu` z#tDsg%|ld`z1ZLm>nVvPq!G+XnexGJa;HE@Zs3N_ zn4r+J{Too?3kdo)6M^7}X_M-dkfn3t;wWLM66KK%vh?4fs|x5kmKDi+C>$zGaRdaC z2Z9@a$8+venp#^HZ@3c=l@C#flGBU6567$tQK_Vz4%Zd|BOx~+_gm5u;UVUKWLH8X zs2njrKRb;3-jUxT^d}5ce-jz=9*axO4mT`(bP z^wNq~!(^DE-}=VBDo-f&wT;U}fzUU85|Q{ixG5v+1k>^D_$I?r$GM4D!^Mi@za14W z!K5bV%6`rPeAaq#hdr7KuCd)kWs72pHqxOC>!tnxdslCDBNnZ42S-y z)y=O_pA|F4L(Xe%`-u~(iXm%Sq%=SXA9Enw0>`<=EKRtyp%BFm6De&Eyr> zXl3X7vc`RoQjP`nzwHuIdjLi`1z6U%r4}LTQ4D6sIr(=6B4J+xX-|l0)oO$ib-dkl zX~9Km%WC_WkOa=VT=6#C2F;b!*_k9=8O-p71Y{Dx^q~JdV+66yvgE8N$nfNoNQ!bC zW(8m!|8TNSd>P|^?nl@8cB&iXA$=^Q1*rg>_GSn96r#oHq#&8u1j1Xd2{3<&>v&!T zWw`Ap^Mi(i_qIp|ia@HJ1M(jFo>Rc{_N^vGyAF?TJPZEa^AbZAuCe}@4lokt%5gTUT=B3UvcVzCO?c*ke&jZgX;I`A6vlZv{_;L z{@D${h9gOL0Vdnh z!-AGedWPqVtka2w;I%RvKEnYO?PyeM80IzTtt4ZH0 zd5Q`;?0A2+n5dDEmcB=m#$h)84bS_iyXH6}wf64T4>D;v@$_MKee!BP3fVH90T{3Qd4Emh*H;F+ZK2N#LDg3HGutoNbqsPq zFbaw9nT13w0=B#j(y276fL-2%Hc?***?d^3-bTR(e;27STFPOv zn$U4AP9Y27pkj7)Jd>KSq_m~~JUg^XEFZmWDkY7>96jA|#aTsMwJG7?y(luMbe8R% zpkJgx!SA}B^Mc$6)x{obkNiTiXW(TqqyE9QFdGd$;0^cA2uLp=f__<5kosrG$d>6+~tEP!$@4Rv1(G z0#&nyhwvSbrrng)+I5jmNth2zB~?s{ftwttXGcO=$Ij)>{;qxB}giCEB{==^6a?|W3>1d zRr7*svw(|-mff?BV+EyA$l`%tghwk%#p)JMwC|H0e+GlfdnraL;;0;BB#C?n$1 zvOe!Xcxyls7AR01E;QOe%? zvOJG_u*)82L~jStcJ7|$I;2)=23GB5-DcEEINDfgdyNa_t1M_C@upTEu8}K-hH=%M z)*0{NQQDk8>C>@`MLRFDqgV-=jQ52if3YIhGzeZDsaKREbBQ}IP^?)7oNn(jwiuqT za5{98c)3c1;i*jul(P+D-`gCA#xuv^BQ;BDXqC}IU8&sWC(UoQ5Du(%SV+$lOOhQ< ztKlD?5Z~M_PbY*gt^Pb1_t7cDPTms{auao4a*s)GZ)mV8&yU1E4^=N6yDN8mJg#&) zd$2KIU)Q+pd$tWKM5w>#o5`;oq$Zy(P!p^xDk={wLgqnyubsC%Eki1f4Ql?RvGIPq!Xu)kq%?tJnNE@2iR*KPdno~lx zx^LK0$6>Qhdnhp_*9_iu2gDga&_J5Oh24$!U)=TYcb4m3ErroZk1?<#(T#9R4x<9* z+$O)&SIz$Rt{hk1N6`AQ=l?UlZsE(_+bIj2w?kA<7}~c?OL|yqU&r4xRRh1P<5oBY z)S%DmTD-Db>hOzZ{&JRBM1axKbFb1A?qSW`+1_2ODOf3=mkV1hr1aOX(?p*elh!v_ zSEwcj4UbR`S4}zV2nP)=HX!FO+TprfR7$>_7odf!*l)?Hw;5HypV=1OGc>xdJ|mZl zY363uj@KB>;;sMVqFX5g(!D2=D=-nvu99`thWYBZXE_nh_&JY7|CZx?>UcG{gnO6q z%ep@%)}6XUmAJPqraedr5!DadLx1Flg%X4=emEguZdNxIiWVq9 zm^b~XHB%Wvmtv52byUWXN0~s^Hh_J|mR!S|X3IzDQ%5}VK)mt}YibZyNiA?=$G7l; zCzvC8QL7k_wz!-gyhb3lS0lr+-&ck&K|W|2k?VvRZE-x3&u^zyt;*`ju%m<7$3w3d z!^%xchR5eEOYkl2!9$N$O)FpW78D`7A22rP@n2I-za%zi(F`yyX4}kv8@7GE!fu)^ ziM~Ww4^cRf=9fmhf585N&gV0m$|K35@vkI4G?NqVpZ?RaJoC2-{k45$Wt57Vo=u|6 z^s_RP|f=pXa|+n{#8e!rp_%`Xc|#xOqU_ng#cqR^f5HLwfAhbqeLq=NATe=VXqo@It+`L z@^}Kt8v+|D^^j?*w~FBQ;iIS}aFGdYe`8GpvGial3wa?;%!z8l$v<7iS-RPq{@Ywk zz^0+bWAD^AW;i|^#KJW?Mni=I>u~dHoH%)O;&1IAy4437F0*bW=Tk@N$SyM^)edsJ znT0`pk<$~3%f*0ot7QY#g{Z?SAJ7`|x8HHND@Z>qG0eGNp)>^}QXxI$Zl?2)CZXcO zebF@YdvZ`%K#W9nyEEV(^?H>pmzB^%keMbwwp(pY9@I_o-H|*C-hz`J$g}zXl?AoG zbAnX1qM`kz-$}rQPFEn7WrQ;AR$^>AmMrg^da|N$l+$|KnAx4uzhXyq>5{)PUMgdsRYc*)oFVS1ZB~TTvVQ%VZMjyC?x6 zGx$bXDALTm7>CDSNCb`*dy5ct45uUA#|YMV`jAzG*9&XIh!FJX1X?+do|Q|}a@f~u+x<9)ZNW?~|x)4$m^`{$5V$c>)yU#)GG+snpTQ+oES1|1c zWKw>ot+j3u$H4S#BtsqSWT^kh!1@}=zl1pHUuxNOq&fHfEBcjS75x^){h-F>aBP4o zYCSsK?l<|y`3_gPviD=im4BG1BVQF6Z~TSZssh{DvHr36Bk7}4SETe5mX;&2lLL3i zNm_R{ND&guUKp)>crj#HvOs_4e&CY&&|goBPGDlceX6rRET6Ab2u}>LGvOQ#tLr1h zLKi7yLfup;1TW{rwFCG*C!U1mnF{$xV#77tcg?K~Rxa@N7O#=#wAcoQ2Nk9&6Oy zAW;%SX_jH(>4Y)RKg_^>fS^YBYEzY|dO95`A^O#&{i0d(0*m(URM-{?+HByw*czr* z?^zg^dc!!MQ-IjfswKXtiASqx^U0N3cz&xBfLRgf;U1&%d7sxcWT6 z6~+mFQwmQACa_JBhAxW&RLn|MbWA{!SRp zO`|6~W)vuQ*cV!h+$uT4A;7>(wI`@MG4-vD!2uiX zj6Iw%9j|*Qkxisk9WEk%m|@?k;3M$SN#jqZf$&*jFwv&O6@H{gFeazZKA82A#yc0rVBx21fU>1ItNfcWfwer%eSax@@FL^W^x{+gG z)vO#8M)6Sh2Kf1PT`_Yur>CASV{iLb+B zY9uUMB@K1J*uEMjqq!yXw{22c*M}qByv#wo_F4@e*|EM$CJ1+umG7lAi{6MCl%quseXp89}msY4Z=nA4ci?`ACg)ANb%VVVXi< zW+S5aFNXE^n(>RJ&R49Q7q^XYo{t`plPTkU`H0= z^6LIxA1~V1UKo<2Q;U1q8DooU)Re0p9KywF=J;HRyu7E-cnRhxWD1pGucUg36-b6I zS)N#s+SFZCl2)egxzINKLuT-L2@2`ji22yAelm#p?!a+=Vh1h)XX;O2gXwri!AFWY zHPQYh+Q@>01rm-<(qCoUql^Bp6)0xVtSKe~M^T;-=*&fY_l@sb7ts>CYa_GR>G>o8qy^raNxEY+W^M(FoqoY|o*H zPa87)cS+Q*4q1)lE=WWRK3|2PtT6`zD?Rec z;a4^Ydqj`tuB3IlG#UinHmNoXQ>TXJ28{{KRl}GvX8DVKPEIV@$KAm~QTz<}?iHGT zv?Dj2D`0%7x^2a#qN zmWZoy7gzf#Oe#J;rM29?i4QI9-Y?m3+fNVL`X1*!R5}>;_Q%R`#nG+O24!6bCiC8_ zr>U`@h4uZ(>rS+*b6Wbo&sz-dJW0=j80HG!rUrU67A2%5-O6i>*9Vg?Q`uI|U*o7{ z|68AFRq#gx^J)pb1=z2kt`aZkCKbWRrr@)I4|nImMLgQgJvu&n`2Dn{izH%DZ;;rJ z8~*+4y&>3J;hUA?-th^oidrgrd`cY%N`oxBc!6?f4@_O5OW6R%P%PMb$N&(-$)c6~ zA}C_aW~P;b2ElC)Rf`oalLm;G&PlWZHYDVFOC!6@KUZ|j#6Q`o1EWhl86j-VaR|rr zd5MH1=sduM(=b-s{PSrr4cS$xVwqHBV6gvniI<_Xgt;fCZO#FuL+iz`AMn#oBn=q# zq#ik&3Rn<9xpDXeSc2`6Ry{rMyu1_RD+z+-5$d$ytvq(qn>s4;LxqT$I+;e|T#G29 z*$u+m1X`^Dn`qWA)~_a95G)Bf?30pieS#wriN0ACO#j^6C6X=e&8gN|ESne4_0Gbf zk(~VA$Q3VHpTDeRdq1GuRqr*_g9o(%(Mq!Ztx|762b4HZ$FaVXN)-y@ z+@E?SSg2!3#BEyT_q{CoZl;$H%k;>jHPTj{(DgkXEnjc3sE`l=1%()N0hpc94w?3s zHj;4aM8fI5pI^XNfcl2*Rez5qOAe6j)PH@vQmxYUE4JYAdH1|Mo`c0Bi+<|sa6VmR zbUY*o7<`jZVLlE<$wr$(!j1w{F_0_Y^QuBjml)JgCmS(fe zI+Mi$4FUnLY#_0A#5Kcay~zpzgoMaR$kjBAJX5l5L5$U(D%k(sbEq2axjGbbBpSJ*+OW`^(&9CC9V6DjgU zr+HybU(B>J|3am@y1$2-+e-gxgkJ3ap-VM{j;O73&=(eU+551cRZeJW&THC-(SSpJ z(gs{N{UB{utQt{y>Rc|?KY4|SsHj2e_2#JgCkQ~;LxlJ@EyCpBHL^3-BuA|_g0cER z%n^pKL$ua~@p5pc=5z+F=~@ZL!z7(1Q4I-k9=Bq^9wAZWzi1;qyvqzck;lZ&&W_!F zH`EK+-oYV$a=Vo*(sv1I(TfC9=A-2+HG=zg0p8A~F8{aXw;KxEaq-0B*hQYkec(NE*u4m9X zji(kGSn02!~4ao{Uh4*QRSQ>sm(4%j-mvT2miCK(PEqgu3*)=PGsh zSgK~GZLfESAFl@S?IQcIp0`5qWorvmWt0&2c6WU%0n@KedtqTAI*(bSP&_WHB}U80 zrXVrcx(kpOM%VfPGQ$kUV;H2ilwBP!=Ui>~%ND{5HqCozlSBId(m0xq3R3yEehCyE z^$6+?1QWX&ot5f8-O`IJU<8HaiguG5=bx30;@0}!HxfHd5ee};7X=b02aP#>grcgb z-G|W8tU6l#05KNs+R7JH&N3QJNMbSyFNvsi?IN2h`O{ODGqz+eypLHm;c2W^ zSkC9G#dVD4M%2n>T|}5&%MDhrx!(5^Gnu7mAVK<3ukYJ$NmaV^$B*Coi?Yydty+?d z7LZ^U@oExD4`N_QI1R5KHnxT$47QLlLN8s&x_l-H7_&H4uve5|na9gTvZx3)t2T3< zUNozVQWy;&;PJRa-EQ{%$i_;Q%X|8ul(y|`6hkBZV09uM+3}3CsR`;c^R}43HV@j_7 z^!i5#p2VwYcjLOOel@51j)U{9c+a+r58r>ZBgd0B5stF%6cPyrCxbrsGP~;TKB3oc zFzn$lbnaHU=j_IdCME#_^VWNzcDXg`z>^f)l!s!$4#BYiKTfvgBvLE!7rAfw_{ z(F)S!NR3ynq?1Pw%D8_D-rPo*9P8TvHrEFgK}`$)Hr%u`aHv=*l~B9;JJhtP9Yequ z0E%mA!mf4ao3rh36v0%HUoFy$SK-ZE!R@?2@%Y#1fLg{sms~-pQcuYuUyTv#5jrSr zy}Z040{__YaB*p9F^@1!Kdo12aXFE6iS5)7CE_-hnHq1e>v%vD%5abU;+99k$JaRr z9h%Zm&N=Fio@CGi^)%Ot=3T=Rx(SVvzeADqG4mg;&h!zP&)|XDX1b~J*rGB)!zDZq z0bXHKw9~N} zBM^8Q>?h(X9p0TyX~J$ysGy-I0vPe1MVHBuSS&q2Z9P7?|KMgB=oS$1ga6#)?Izl? z4xii{FKuonDG(2fU3PimvU#IFUsSa1m+Vd{mEl<5*w{t$=GBTDz243?NHwRr^Hvm|@f)5waWlreVCUp+kZa{5G05=O{{Z)=NR6Mb=6| zDpN#r>&LFnfytzi0F8VUFKMaioYUnF)FkI(38ki}!zq%Re+{B5Il-iOz1&ms9*zJd z)t?e5+Z`*w=iGIs-fw}Kw?q;q+DLYw%B=Gniv^}GDo+$KWnPC=QiyE?dFuV`C7uxS zB0KEk3Aqn7NX?1n;iOq-C%p;NRVqre-0}qqYn>Nb+q=6zOBW-yDeR(4{KvJsz7dw~ zTD>h(Gj*9h>ZA^^$bJp-?JYqL0)fLSDwn;QcqfcJLlz|5-*PyXRJe>AP*h7SPMxNY`u=b^xXus&1ktHXg$MTd zK^I(1poMlJ1tkGr$XRXvZ3IOpvUQ;{VIHYgg45wLZ3%%Jinq$1R}UGEw(I?zecMH0 ze|qXU;eHb0?hbwbOc|w7gW;fQD#p8!eYVChe~KIpM%QwjYTn+7+mltDTKld;8pi!u zX75h`m0a%y9q^17sYBdWqwn~k!~+IDcrk$P^A?298jk6~4|R_JO5O6~@;h6TJ@?Mz zweCR6-OzFsUiZT)XvFEw)9ta^9aRa(Jdk_{C)~W0C#)|!TWQ<@UM_xg+4X(FxZ66H<4q zUL{+u2q|%>0!F_K<+%@vLy;Q^$kHroP2#fv2Q2yR+v`7ii9R$*Cc<4oCY3@#-QL&N zSMu9$za56~a;Ikj@$sM+3f19Z87^e2|Lb2Qq~(?(h$nsS?>9ZBd86H~v59?QH=XW? zG-SN&>V0kRS-{<95A^Nz(5&0dt1-NQ3Ka|dAX2noQ+vZ=U zh*H~_Pe~@tuG+_rLc}l~6q}Ds9hr2|9R)}Xh*kUOoArFoJ1a_&o5>oX5!k%G32Zzn zzfAKbH&*!`v37^;pg#zIB9a9QsheU#9lJz!1py-$3q5`A`rCIcUb)d0pt4^D5WV;6 z+tq4~^K%5Fv2H`VW>zg0DwMouOl1X_-BT)o@L*@&D(icVCHlb!)a1|8z(fOK@}aaCH~ z$w}77B-a>VWyf3L74rD;AmJhyA>|0iF6!M|v zdkStaIc9{ed2-v`M9rCoL0`J~{fIm_QTS0daiy#Dq)`#O6CjSjIAC6A*@9 zZv~1||NWChF97Zp8#8G^M0e!0A>PFVojPF;1?v01aeryMm&Dxfo&R z1q5|*GwK7iIhWfmoGV6_r87u8)}C*73t5fMQdoYmP$c=}J2&+qmxI}wKPuh0){huL zv^3H~9TLc6zB26|2FWZ`*g`}5xinfIE7jnoTo`!SE6Gw#WD{S#}AC-{x@0(`@F6kMsNhU8UBEbElS_tUX{pu z00ucxPaNaEEhDXwG1NnoyRWR+o$!yrxaf6w<<{$it7fbhluW%RLjC_cQNF%k z;=N0J0M%4w_+Gzh?|s3=ch8g(bPzR6=%lu1T%n71)ZCh=%`Vi;tcCo>9aVkgZDbT# z3NKpYu?VqrE_7>qO@DvM&xC9iQkCfDZ~q89hIK?2&WSK+dkcGFx>B} zCSZ5PW5j5xQ}t#t08}6;dL4q_Sl*hS3I31|-gRg+qcFRa15*zHpGBRZ{(Or7MFMfKe@&xOXW@#S-d=bANcl2$mfPHFITwU= z0&ipOI6qq;&GKSgY;_y$2zM72yA%AOG^rc-xBT1WfV7)_2g}p`Nz?JnwH;YqsEhcT zAWg>$?r1czxA9`n^zntJX%4y)Z}U*y9LRc`1a)Du(4Ffw4?#5RDRz5N(ILdTUM3yQ z_DGAa4u1Awx|T7$APe`%QR%)2bA&!=K zu8v|ZW5huH5V(COV`L;%kq=<8ziV*;&ns&TDoxJT&BKG3mR1Uy9EK7m`+*dPGt56E zV_U`~sr%(HG;#lSm42rKZR1H_TMC^H#Bn#i*@DIUUmjIlk`v##0b-P#H&EHFlNWl`T-;!)GPbUzpQA+`l%O;E70&7TQ{ca76?v zpKtZDlTCpm`#d6P*SMI+Gy5M|sas?#Ii+ekR3Ne2d|sCw-+y}ufP5DxOn^X$EmZ63 z9?{5V$5w%P5zHzA+5WlvgG@X!%9x7N@i=2KDmPs%-Jt&lR#W@;YU*0twC)aDGZrhd z?EUYh>;l&&*>bCZ9SYe<_qNU^xt>_hz;BT>oaCWDKTrQ>fOI7zvgdB_L=+9=`E0s6_cx}$pY zUBYpvF-`3@=uFn#@z=|k>(u+6RG^M_i$LLVe*d@4R3`g_K?)d*z9L;nVE;^&Ouq|m zDa!N9?NB8fuiAXP1NccQs}q1~t_*S+PF?Y3O;`?;3;nZQSjnOe_u*Ln7$&pvcWP%K zpH(E68w}&iVZF-kL^s~#7fi~wF(7oa{Qt24JZr;Q27D7?(P(5}YzLg)&e=i0x8Zk= z%u*SxrSUZNEBl+gGjohyEGz{j?^&7O)j~8G-N>KBz)mLz@e~9{ugDL%fM5yus_c^- z_ym*BRX@xpvjohBP2xo^Zhu1$fKL5b^SK@-pR+hyt}jUw|4XK~-52)w69k@4y-qAh z|4BAyA4>>Ud_Py5Z~Q(a9Kx3D#+$g(o6nEmQJ*B^@zVI$n+ZMVk0L*W3mv17TZ6M`&=cAjmfy`O<7(3?@S;3f-gzlZlMl z18sXDQPF@D`HS`TcoAVMI&N;9Fy#4kp>AQFaK~?})dr%ZvuJdhMS|5Nq@ z;}70nE<_{HXyXP%a${%Yl)?#(Pnk0+c#YZ<=o#|QH3RGvAoV&fI$hiPnLHV9<$shO zsg;Rc(4`}hSe^52QmFz39Mu?ZG=p6n&tjN1WpKR6f+CnUbG*oTroq;q9-4bb@%~}( zZlX~*#WaX!YD1(0PRJ$t`L5zwYTW5J@(!FDEfTB`YVV(t?Z63dweVxAEqXw|6c88p zebOSNomdAebrP9L;omp8+8pXqkw`359w67(ut*l;B#BH*fvNI4A)e%XrWyxEvlcIJ zKRR*|5L4dd@f5_~ajjg?tn?3~N>5qHdW?@YvCw}7ulL9?5<+0CSqwN6h1sh03b7AQ zoo5hi+Y66;Np~R-4^-Bpe5{eFl9K3sw{$BVdT~oLc)35LLKYO}Eo?J#*d7>8Y>%kF zPEeD3I!Yfr_4jkVZnSxQr-q5Rjgn6M0U|ir zg%Ky0-Y^g6_0Y8hGA-dz>QvJ}&CbqFe61eu#NiLp8>M|01BT7KY(t*WUi8uNiHU*J zPV%gU7>=Ttl-~)7?Y|FFLy>}0*~-9`cf%^X1L-^Xv)O0w-i%?=KtQdc^T?=G6G(Ql zxUSfU6LuF48&6?hzox_wkppF-)iGDBMd!-95N#a0u@15S+#xf+o1Thu{QvcXxMp z3&9BlZ`_&7^UnN=>2JMOdso#xXP+(GD)=eKpm{iF-0;ju<1hFN@$zBb@A{|U+&a!d zTM%Z2UUQWvC!7rA@b%V~kxTem7OjnSA%bdK$BtT_==HtmH(wh^3mThX6f+hu$nCG& z>pjsI&}*Lo%jf8hXRL+OYvBcKkSxLuF4K8}a#FH}{13JJsNU!j@8Xb%s(u~}o<-k7 zYmV&UsD-A(myiv!35ARdu(_*1sh!iDEr6Z4{-sLU4cva5ing0}N?lv}mk7^sG3oTE zz`m>Coou_dk}D2}vwE)};WV!-Pe^G(bEuuyX>RRj-KqY^|GHr&&4tKX07~dq~$T>orYoq)NVZ?^>oHU zy2(MNo8CxMbEqy<7x{0E;!|`D+6PC`mXZyvLs#p0Wnh73_vGe=`ZR85mavbwa9%+x zIiSdV*l!GZypI5ql-rQ^-m3-ld3$G`U0jxq)hizu;7&)(B6rEBFz0N;giM>7*eLF> z({NEw36vJGmr&oW(QU~rOogHl7VU&grhisGjheL@IN=Z(eD-+7BW}j3Rxte08rL|m zY~&N&(yHFS zrONaja44a@$`BT3%E27M%;)FcFe{Yl}i^7_m3to;f5*g(gcW{s^qB7zmp5PNEXZ_MZ8KV^~bF6vLueNJe(-H%s{H zzigO4Glm&@-3FV-DS+6Dwr1a_gI^oPekw9HO^(*&LEmQ#$NXW^*2y3lU{)|T z(yQ7l*$=0Stctbct5&R(8A(A#%H#OKcBw+uvc0PN^>Ln=Lz7)-@ezDJ;SSwRtQVgC zC)3HN`)(%Z?vEpT#XpI3mvSw@7Ju{+TX!3EF#ih0Xard|Z(1Bj1ck z?6{)qI5LSo0PCSNqfPL!x?3ZRu1x?GDkqeHJLOy?;ul$Xc}i znp=8AQR6a7d-3|>`<=gzfU?hFi1DR3eCARjt7V$+aYtK1@E)CgdF=-$enM)Qp5A2Z zJH2D^eTDb{vzZp4K~9tvmluML0v}5Iv4}fJ|p%>;|GPZdx z4Pxl5v?gM(>YGt@H%!=|^TpUWsn!Ioa`ulFw~dgSLsjTaKTn4)5;Jxy}C2X6tgt$OdhPPE|gY zt%DP2D7VL1RLP9>Y&vfdAsu)dhcVztiyhwK6kx|=zwdZ7vMUj`KY~ube%fc1ScAW6 zK_R5)mfDcjP&x|=89qaEpPdI48T(vZ`J|A|=$Rx&OpmtQZHUj^3HRvy_`L9@e%pDS zyHhq>k|rM`!X^F=mw@n}BC{5off0i@(&Yy>@nEa6kMIM4RM*^3Fl^8sZl-&cJGvcg z9WlQjnE@3Sp3MV6&tcj7W#Ui&V10YLzWQOAD*t5R`#+bDmB5ma}3i~r$B_jO@{zkBu!E{8B z#?aoJnGiIHNz?oK&Z@xf1tq_-cEt^h5AxcF=kZz*Fwiz@U6$-fUvT&4u@SiVkUheustnL^px>*D?}*w=?KzCpHV5&ThYF@Njr^v;-qquXxlOo{29p5+@b4 z+>pG==80kL&IcKnt)oWHn+wm$cS0-EZ4*NOGw(lh!z-?wzcRq*=0OPH$lB#|JxQ&j zsL&`+9#i0Omtre&8ZuAOFG@x(^{{3KdTNgzc&Egt-Hi|TgMa+Nc-VG|T2I#Y?@;L%N=K=fC{YsY%c-Ctsxzlmtm^qOl>`s;aDhkC zjcg$d`Mg1s8EWio0oIQ$fp+q(Q?I^`NrH0A7i%>wJn3Q9lM(-IPe=3s4n$^8-(pMT zM`|-GFE2j#3o^Qv>(^vKhNLH6A!iPuG#8e?PegHry`G1Ano#6IQzNU*r1ma-i}6N> z;lqnw`_5(ARlvDw1w9tpLy&@){@I~Q4)B(S#IH>SN+Yns^81YLBbUwLH;{S%YsP`x zdL4SH;h*TIFRr^%*0O%Qs8D~LsGP9 zZo9JY`dnB4^?d&DJX9_2ly}YdCSuLCV508Gdh)CQq)17ps;R0`@q%twhJgw(mzuz$GPcq_C3=1`S(Kd0y5O$2;Xm zA5+i&8g3byF4VVdTcxAs!p-k~f}KZgkf=|4y}!tkEFnD!K}I+kz1Mlb{J^d*U?Rco z087i}w){RV002g8pe4;v#bJ;;9(qU2KIu6tp8+6@q?%g1NhSnK7#eBS?XLUjtTd^{ z5VcfiUS6K#ev($14_}tzduni^rZwpEuGdkmxVyU?X@%PZ(OtuO#QFJgz$3(&OqMKV zbUL}J5C-27!GgPMqENQ^5bT1$f5?JZ&KMGN7Gpc$v9geBr7JizFt7y#Vf&YtmqUiC zroY|qqA}?;y(e#LF8xfPQB=do@aV5>-ar%<7FN0M1l}B<%O=s80>rG&$og$At1kP7v^=-X zVhl_w62(0x{f%3@3p`~SuD$5wgF!qzuVg3p4(+_rF2{(bGNySOfoZ#gQp8gOoJUKI zo;bk+(1p%E4BiX%dkV8ardJNo6ONf>2Zlk0j|VS|&;=v!IFq9(a(G^y{b|<_der9( zKUlKj)rnuK(vJe~4l@q-btIE@y#@|;Wc-VU)K}dzGZt?*HNON+@bMA5c@^YTEvsO| zqKU<1!qpZ#3L_4x+MoGDbYO%@^fQ2J^TLUjTmYYX$t>ka=F}7MAF0<^!#J)T>Cuvd zsGS29pw`Qb=X-`a-;>St_I>Ed6SG@xT3-SJg75?xL_lE2&Yw~AisCdUz1j3>aIRHA z9r!MPRBOL<0@gU;;o&OszIU5`!hfeS%WtdhcMDZG!k2y$d8bbG))lx=ah1+Ns{)eB z1rP4sHK3?x{c@Xl2ukhCrI0bhy&Oni^74~3d2nS!e4bbBJ|DK)ypS`Sc*Bw<^$XrE&z;G0kacs)v$crCx$;qB53ld6jsE3MlSO1Uny(X+h}^-` zQ=I0CyMG=Y%bWOylCDMPhN$w*smCIM`DM>m*(rKN>xu9;Ux`2<1qKH_~6B`Kk(m0LF$}+%C4q3y4$rdC?OZ53DJb$C{UcScDS6EDE z={Hd6eBUPW9hq$08MOA>9!K%8!f+)JYX9fdfQ*(5uZP<*8gCVfeCfoS0gr z0`WBDuJo*O;=7X23hv(Ggv9nB)SU$$=-R$Npn`!1jw}|qlX34(?Vw$c#4J-xL1n4}y_VpaDY0kW#QtHk~> z2w+4|I5OV~l$msLO`A*SjM;(!v3oBtN{@=8lxE0BW{z=k_z&qS>9`zYe78tU)a=tC z7W9uM=5Lab2XHRrtmOW-g)u7ADU2ow%G3s zx{e($T0}2_fX7+jxX-W# zFj4rX|53o-p9t}(MPcsI?s&N;N%4Gm|C4mCo&=UeltogjGY)7#j@^3)+TG>E3R8)T z@W1O*jxz?pqjv_gczU|~!x?l{;ayTqt@a)}h*f0}I;C7`xd^`@SGmF!M6n+NT&?%c zER8~Ce{!3pz;zsZ`Yf(_BNPN)-=>tJ#^CUs7dsZSG1A8a9=4T1mIJfQ8&LZkf*skO zzu@7QCxR*iC+sME#1QE@H{7kq*7{Z8fnwv%YX`GfBN zMh1Wk;>WuTVpom6)ZXRDpXGnmI`A|b=xep@(%MCEc?3eUJ*=A&5Km=+$P9JTo$4IIy;I@BD zqz~INl{$FQhxut3C!DskKfQ7?M(*dbOoYdPkQ_T@_O1IFx|YQ?rHzzOM0No1079p! zRC^kV*sl(^$~&Xy76S>V6D<}uM~jSj-nx!S5JIl-ZGVetJ^3EE7;6(|2z>#CyapX! z{iSRderOQ5<>P1juVbV{9(zVLF2|Y;R>$;KeeV0WKhrd!5=e89_{|ag8DGJHB>?JK7;Jb~FjerSA^EfMJS; z3YZptldOJ0!edsCE1z6PM5d8}u)TE$VbK7AEfD#nslRwy**V2Iu6P0Ox9`~JTyB3{ zQhu$frB-p&oud`(>JgmfXR3 z*?VVa24FO%U99!>^~4!=j#${xy}0MJU&sQyPHY?)@;0Fw5X!)fL%h_TGHVEM9;oXa zE&lZnr0{r6lJZOMp6EgoC;79s;^YCZ)z@|kL?hAM`c^pBy7Y6ivqD!WwWxH)b0l{jsUAGT)RoLec0yEprg`cyaO%|mvEJx1s=uSPZ%%AbQ8BzTq}bXq))MSL0nSy z^^8gqbaPu#-cj{bcs=E;Sj;0~-V&)-LR3ua5b$~)Vg54J@L#Kce{}gY+d}67b%{2% z@in53eJe&Fs+?iGo)xJozEvgin?1$nHl2bBG3|VRt76Bmb~C7=%(5+1c3hWtqfqjR zNeIe&y6g0Rx5>?0DYeGp`J{Mycc{%}lbamejCM;^C6%7zs&6 zn%qn3){(y5qlCbyX|^QpvzW_jT*l&3uu*yq9;L9U0`8_3Vqa~0<**r2HMxkP1LZUi|g-i|}9bZ#q z2p@5Za&uJ1zzLp9@pU7*p5%3?ZAN;3npOyxu%Vn^gAL6neln+IGL2|A!DqdUH)oW> zq|7or>Qg!fkdc{w^sWRu8oYHyCsOp7#TJEMN{E48*AaRf%|F(hnf6E~TV3ie8bfL+0lbHeq<0ZO8go&ELfC#^ZGAb z4+EJN&)F%^**taENLs1RtS5mshio};>W+ruO@;Y#E;Fue1n>BTxmPdqybrzF{1Eer z{s&WulbVi)8ZOsZyg643ISJrCTw}pY?pw;zluK;TZidfyf6{Aiy^F!ixK~hD(TC7V zZZ2EO)JirT*an5UrNe>taLMai$Wk|-wmU8#WR}f{^HMoYae0vNz^9>O+!?=37#9PH z5sq-&;dJll<2~~tL=|#xTJuCl^vVa1d$8laFMmo$h1@kanz9)9Q>hf*Dz3CZZBEl+ z;8hFB(3LduX8V(4%+pl~?=mTvfI|H=TpNQUKEaCbSF$&@oDM|gylTF9=yj}E!P!+$ zZ4&wYL;P>n%I*EWWqhjXMDNi&;#C*Yr#iZmdKf`O&&^OB_|r7Rs0J^K2EzEiaHg)s z#}}&Qgtfgc0vWh8UOYyCWt8 zaql}HL;FZr`iosl?2hal6&4FD7FMvz7nmFM)eT4&pcij1Q$`|tKQN& zPK`-ql@ntAcJWsZvv34oN|^m_WAHP!Ky_X-&zH`0wbH6a2&@lu+;haE=fHqruNM*x z8M%s5kxxl}7SLvw45^L0)l>;@&C;=2t04GkD`|g>+<;^qfJUj?x2cQ9#`ejd+le;G z{H7|(`?G_#gja*vP^4TOO^_vdo^DA0&RJw%hxcA1koUV8>Rv3%KdY%r$95(Ss_bs097yemBN4yq3=TV1ou z68=&kP!cs9eM|^e-ZgLmBium+3L#*ltZRw8^r9YiHv~6RW$Rz)VZpR2egj&_Z2}So zyyl&VwxBIyu*qm@0&=ke!HHzOEIgWobBTaqma$znYV&soWQSRp)>nvd#e00XZ^^m# zcD=dq-n>n_M^NQ%Ed}ApW{N@I(n|8xG$Rue4ERM9zg}W-82{Ui&i&N3GxSqeM)n@P zq|q?zQ<@vbs9FCimgc5s8I!y(H%RSn+>*9H_J#de?oZ(#Bngh`^NiTzG&jl3H4H~3 zZ=_#0cabzSummOep0tGNy9y9YET#yzbM(2h-6Jh?G1ncbPvVXg}f1aKM z1$w4HOs3=QvNC=qO-G|OeJIk`ZoI?imZZ*?3Ps9VV}%RCMC)m+@fW9d2CZ)|uCpLY$${mE4`M2(=L3UeGl!k`MhBw}y{`AKQwL%Oy(wMisEP@yY1|*J1NaEF@ z5G^iXD1?NSzyl7yEACQMx8zf1&b{5yU9+Y?X?(#l?#%<=|hNCv$Pq31r_?pKI`h=$Ipn> zFSSTYvv9MjxA9d<;bQ5gPg|s_XvU^OQu!jQP)A$A3paSVzF4bwyj{&Zt8I;A)$fv5 zNXSJg$JvCQ8smO+eEjezbKc-U+rdbj764~rGaErSGc(%)L=;1SYmYww^k{`N%?oIL zhQ4J&&;Kx6)e-2wMjXIz2?;?_v+je9dH!iFMmd>Oq*>6`@o8hQB*`1wo}d)K2NAo7 z(VelCcNAm#>e%QC*$>UBS^Y)(u8;@;dpd?`}s zC3NU8_QaEwBEI(G5)nbBsd*+gTBO1NQPiBJk}v6)Y<#sOzJGSmySVC>c69195NLHO zt2=Y<2EzvHyAiMV^>3fhCR+jThX)VY1ci(zW3HqT6Gq|*|EJweD^0_`DuXW0T(oQc zZROo#iYe_dG+5~69S3iy{*qKU&jopa6QIsU{H9b5%BDmt?f&1lag@$95>vi2 zq!~JyCv({p`t;@&77PaR>Z9t05#&y^Qx-QpiUP6&SD<@6etoD5$Kqp%Rj*8s?u=+f zF@ry6HK>>|j3pQZDhJjONyl>yz$=bdry~hI>qP&?_ZCkE z%suP*SIsxgNVzz&hE~ihNLHuRKaL$|Uk2iWN=r+(E;j*^b9FQ;02D(N*{#$-0O}33 zZp$ZhoM#2Q3H+QBzY73TM9TuaYN)8f5$e$WzE19K?OpDVFZ$aq^(JQq2evoxtu9yB z31fM6wVYd7P{abf+e&=gSfn8_-Wh__TD;69p=hx;&v088DA!Q^p!H1Wl_oM>B0X(K zGIFHN^O3<@WaaN@%mX8Zq&Z|XA45{~L;pCxGB_MC^KRw*s8o(73c(_u#{_x`ki z5+Ox|wM&E=IG^4KAht$mDVK&q{(Z@hcz5D|fb*gv9UZ0H*0z=X_8L%K&Z5g{ORnT` ziII+hgocL(-TE6g8rc?B%~=io5CdKr94aD*g@#?)S_*%KiUlXijVC%h00j+KVWjM| zOXWwz8f!)rP+rd{CLpHX^%b1+Gcgm|(9Q6^Wd&K1z4Dg~`ZNa9xW+Rgpnr+~srNI= z2+X`~Qi~$^#X>=}*gjKbygj)sY#FN_Yy000g5PJqq@l~*`W=iT97H!-x1{8>l*ow= zg~9GPSM?70pWV6!O?4GJob=?35LG)P%O!4E_eNB>70u02?)B&txTU;1a_3q7w;94QGOP03{!R389NB|2-&{V z=`QC9aN2+APXWqr(}#ac-!&Ybgnq`S2R5v820zU_h1!LP-azyw zoel|!L{5c=w(~e~*Nlu!i#a#7G}RqLohXm)+~hYYpXR+Lnke>8z;Fz{B-ue0A~N<1 z6XKbVXyeo^lxv{@=1}xJD>K-y0N+;UJsQF2Vu~pq#2u7G`EtzON6K)HB{b zKGWKQQ$1yf1oH3}e^UfLa#(U)$!;(}PcPsjDBT3(8+R~LYK8{(%$=L_M9kE^#ZCRe z3>x-*)sR$mS}-v2eaj*wwrdxmMj7DFDX#Y=6V!-T7n-rnHRmz|O>t!HAOH z+EpaQ6K$t+j+4{F>69znk76v*@v_*Sm5im3L#0iq*!g+Wd2_yf(^$PL({|E`;H2W^ zJeuHcI!SoM|5h2H6I7fm6e4{0rjyuozh$z1bs)Hs-k?>en&aJg!x*j4hWnIoSI&uQ zFke?>e2vH(h0ehrra5j1Hr zUUGNN+~q(eHa$Bp=C0YkUY;%Zf~MEvSV=eY;VlS}psfvTzsEaenG+flww8o*6>Fp9!+G zFQHM3NYv>wSUbA6eWLYwH4$iOhDO1#OHaSwx?nYgA026dXNO`J_JXaY=YEtly*Q7jJeP%^N_J^VRjO}B z3{Ug>4h12Rs++U2QL>1G+Txg5dmRsm(NnEMa`>cTi3*P}? z){#}|t@dfnNbrDIKLCc^U3$D{T@IOzZ$CWcTROLq;W&Lc>eh>-mlG8=()sH-#ri_& zk5e*>l&X?HN);%A1Ild^CzM|(F%pQrG=K&WAYi`uiu$TLfe=m7*mPLWa&e824~dp} zzchEpT2qg+U#_vR)FKN_(-{I7^)EB2KeXQXW)~V26}!)PNz|XS2T}^?yH3W`yb;h8 zK96Lv7#!f|X2}|i?m1DQ4jz5_SD56mZn?*iCHsoJBQe~?ls^?&y&KCpr`{RUuzS-q z+_%-6Do}bL`x0sFlcDu@*CmJtqxPUYe0f(sTZ*t&$yKGK4(ClO58L{}IMJ>lOt6|^ zvI=cwd3NS+^t0s?^D7xricHalWqK{c#`FsUBC~_TdETUpz1bX@|G;-?N*EUXHf+FY zaySr%)5@Xp^F;Z{9h?r*b{4!;V9n(i8gnJ@I;)A=xmN+3%W>t?D8 zG59JPedfSxaOC)iJEo_v`0hc$a-l%%?M|bY@S%ni9?{?39`dY^u`^h*zAZMxYVIdwwtzG+>aO>+cg^T!S^y*6;f*IIQPgdfo-A)T1*zCL6}tHX5EpzBn4X)>N?2HFzN@~(>#yg zudj&jV4sZhOwkm&gBjC#E!PY@W~!ZSwuNRug*Y>Pxl1p3=$1i$zElJyShLX$Brd z1`His0yqn*q;SOjbkL}S{#N4r zNE0I>Nm--#jC7`BTti(vnNn1E%6!*x+B?B=R_ns?`mw#w%YQK)VCvqWEKcUm-L=+!fB?3ew|Zw9D_DejHa8KE%S292K1Lbx%g0pXU}(|hGXkXE{)c}K{a?jw ze`;fLch=#X3fR;e=`l$?H{p8(23qW#7??~2 zesCA*9^;rOOOeCuX)@p9O(D;pHNtzgpyl)Ti4$3kX_Ev4E+rxwn+GXREuCC#fTD!~ zs_$?7h})A-mykevoERpk@7``$WN)ceK`-RK&5FE1T# z>;(^>NVHA*_SWwwcz<+&XaO+>pXUFgapi50|EA=EnuV|XS6z8Zi0^pt988A zcr06$Scc%+miDgbI?+Q^=qAj0%KE$0C)*c~pGa%WV4(AgVPW?>a^Rkk6BD}gDG=&y~FbFNYUI)bNrRypd)%|Oh4102o@5ovBiq`r{7^^TG0rDYN72puvC?J!M zjF}?z-T@D(vO{w4J*xO*1IkM=5i0e2Ns(Pfe|ZuO4b%0Cb4|(J%oyRGBOiRX+tJ~2 zA9LP6w^zKSkIc@go3cB-Iw0a#*(~)?;4D?ggC=@S>Uj8@uHE8jT>HTjxo0I`8W`Qr z6|`*?9+zV91o%U%2bV*Csh}VCUG_!1Uqhxxr7ntE+_HbJp@IF>7q(RuRXsR^3Z=Bi z|4Og?Bc)}mE+?Uw*5-#V1WfeQ>4Dpv51%NoBj|p-YY;6i04Hm8iwmZ}w3O;ZD zbh6iFVAGW$L1IRuv!(kBo9Wa%?V1Sk)W}$U5^f==uJDE8zvC3iwpiW?5uKbZyB+PL zGd&d!_u56dzwO540stFauta`{rprH(wyb^09`fEn^IiZ-Db?~IExEFVE@Oub!PXsi zjU*pJkNA~^Sdg)jkk)-lmz7bApp%KMgKZPOad^|Bq!3bPy%8P_%LWqO!N->3*JAgoO=`y`>^BdbkvY$2I8w6h z`RM_yP{JecdveH7kSTU0FpT;L0f#~NI?ks^<2nBBE3&=28FOX#0S`{B~(Y$Tp zIc#rh%PI;UYvr_C6TnsVqjq8m{Y;vz^noj?jM#}9-rU^Ur>;9I~_!9Tn|R#Nfx(`<{!c60>zIm9T>tKlrk1-mNo!uF@H*d)hJ5y4dS z%ng@RCulyXG-Go)QTXg3ofiUu_INDkXZEx>epOiE#sAm@4gQt&0PM4RhOH4AVLWd> zrWU|IrJNIo8O7lHtfbA>8vuto0yYdBsF!B0fDB8nJ_11Tkm z$=z(UK+?+;YM;AxG|0|%TT&=u7YGzk2r889FoOO|ESa2u#-7=+t-111T8wZjC}i5? zA(wbWh9vm-I3zb)>qFk_?}(8=Z@q+Zp&GqsHt4CekY~xLpPI#}YW6=55lsSYS8GTX z`WWI@&IHQ(gk=5lEKbv54aZYhw1R$tJ1J`E+zd!{GcFDK3e zpx|c8G|HWO4{Nq|y3p_Z9&b;}A*FRIH5>5;SZUX<_;4mOc(H)Yk2aGg>-nObEh7VF zUUu|-l+Wuq&ElCgzOvR%jwQgC!_WTbRf z!!d-#uv$e90J;bmL=fsW+gApQTYH>bX$@H-G9rGuw7)gVCc@^SC#x>%nHwZl^7`9< zIt^!J$A``gwb{450NK&t%;?%m6ymm}+TmoXhitWg_^>0eT=P~tf>y8M?XFu_7bkG+ z<~}xO)WW2E00*~vWWKH)KpYr^PiuQky#|mazHNC#K05#0zZcD#l-rA$!foj$rD1NJ zkbC~)xT9r|s}gs!n>w(_dpr5=0AmZVsTg3FP0>ChrGjeMQ>*T zkdAdmA`SQ3& z#0Qw2z$-%(I!(nBG&Z~QZ;e+B{1DqXg=rx0*pE)ug{0*!A`7MY<v|nMOXgZrr^G0bRRL`k-78vCpCPzCms^~1 zFRUMyU)1OhHerRQCd~R61I}}_BC8j*`3f+fVPj|+0(tP&`Z>Z4P9JvSX}Nm-%@-4< zB&Iw8G{!6}qbS5h(lQcAy+Y+@_j>qGIus{dxL6p0zyG2R&7Qm*YW7F+qPekXSV;ohAXR-^ zgVZRg5!2~fxfi^6a_pgnX2TN>n`VF7o*yL5u@^@oY2hR?R`vK9B9h3xdzIL^+0mlS zyPKpJ!ceILltY5=dK!=k5N|PD11$bLL9DW(hAA%*(9%L2%Hcf5@_P5%tJld|qx?SG zSs~4BrM7_vw$nqL?j~T}mY61Nvp|PTM91tI4ERG-C!@shn6A5(m+X&4mSr>F5mEe1 zKs~u9hPUzeK&cv7j>}{zos?Yal zx$qreSe{V{h5sx;fq*KembpQQ!%xlYc@5NQJ%q=l>*-r_zkeM9*EG0sd{!g>ItI>5 ztpXk1Y$u>tE?+Lae-idOfWRBP832PUIAfRH^B1Rvb(*x{=Czp+xTFR zgF<)J#-A`QJH6#| z6xSseuhps$^p#7Ytqojj-+b`VCf``@BCKb#qPyLK)j9@l^w=+{Yfk$l<;uIn6w6%y zwkbO})ZkC%GDdMAdNC1rPLu#$er9o=8=zjz|BmNu2H$Mq&a7#N7#jx$RTX^)HP*^6 zS#LvY3ZR_4LQ0>mZPD8?yJpsjPWyA;UpFOP6gsKYM?J?qJ)(pgHX>H=9|}A$yQ>UT zSVKw3HeS?|g|R?ag^N@YYe9}KUJx;(njHRauBOQ5bUOn{ibWi_FJjxjjM8TNf61>| zgH^uf!v4YT4Tv&ONcXGJt@t42>A!%x9`2XtAa?bwNmL)570#Y`3`ph)xN-4bIpwT> z=s@Zppi+SgXcd)|(+18soy6u>8N4td#c~3BLb|6S2UEJX4?9Q%J?R+0p$Wp$BLgl+vlNd%&4V!!y3fA4^_PgiF;p|D+%@*x(0c%941D*@LdPn zov`#b=PCL6%G5SRr#5^5$9CjEW%8O2nx9!l3%zw|w-OdG+YYxBiWOVG1pI zCB`cPL<%b2dLb;>lW#gGIhzlz^9q z+k651U2QK*TQEp`SVt|m{h6oC5n#oRbyTGxTS!Lo)0w3ibg1RWJM?NdHh-!fn}VV{NiQjo3<)Tz|v;7 zcao<~1;H()Ux+_?34g#xV!VS=cDf!vxmCU0ogM66S=4}oWV~{<1q)_eevvcGJxyKn zPa-6{n8O-(Saf zY$3YZ5j3s%7*43wv0bQBO(}eoSl>QfhZL9-_&{@7V_XMQE0vEbr=F<5FDSgf)>X4M zOePLX8G``qkf~t`;OP0OX>2Vx>DVZ2qGEp-bBJLRnvW!wC zf7hfD+0f9?92HN`0p9d85rQpFozdz37!X5@phT?JT2pTlHWEPm>;1WldjcD0pnmbw8n6Z%zb-LdIxY)-bViF#+Y))in?(N88UJq+@fwFXuUta1-!bu zYg-Bm-T8!to&tuEGV8pzxnZ((^ss-0Hmq)jENf2Zr6F0TDC6D4dP?9I4qF(S(~g|Y zGWlG@m}2M!fY~*Cey|tN3AK{-1ksXhiYa%g1@|PO(=jpk=Y?cV0CM3<{Me=@9g9$ z2p9k)XX-^KPi!YpicuWQB6|4r#4sMCrHT1avwLqZE)A+%-*NKY%#rXQQh$-;urk@p zFli3(;s^9!w#BSv3g98gjh>-DE;>0m4w3pjt5Q-MRCj%9|L8`+h%X4C??lg?r7&E4 z9J{l^OBn2O_M?v5t*?8$AhK1bZ9zRzCDfkL)2I#}A(US>-dfgvq7F6TZwyH)kw3as z5%kf13(&bHvN58zmDmtf)Ny!*4ajBtrp4cCFbJ?cyi0+AZqdNny1(mBy=Cm2pvTby zy?NKF%d&phYhrDa^TW-uVJ+aTWlnJ|c(tX z3|6t{bi28CnZKcrM{tri+Ut=Zv8X5qXWwtW$sWaPZYhxhI8d)B91Th;QHPVVv(a4P zB_$=f>|cNZ=T3QbSDALKo(?eF6h$n><+Rv_P9~b#j1tT8$m2YC)s-apin0%UP)#C+ z*g>$_(Qk)tV(|3PZ6i$qztv(c z6cc|)Z}eYFSq$I;>490I6&3X*vqrp({)sLB37Fa^B9CNrzbEf#CGxEQ`NJZku!QpNS*R2f`oVikGKF$h+W(}Ub4<4LA>zBLi;jkBe_uFs+;`FPG&G>}<+@svaqukVO+xFZ&C-3CGJd5mzPL zi9?=9I$_Y*v4e>8i6XsL^6vb6oTX)0M|AYZyD!-|_q}1$9ES5rU#=F4r-oLNPxr1S z53=kub{lmbS{OGe8CbN&z5b5&lMB#t<;PXmJ`&Y$3zV-)bO~>ngXnJ~+zl$ZaXE#O5ltUg_>+EPeCtl>=(=c5>9BfKw?c(I~xtO}tteBMuZjAkq!kG19{94)=BnHTfNv7i?-;_a*G?5oU5r2$O) z2vki@i73a>nd12-+Q08z*KlauquXE)q3?$(gZS`jml9bJr>RQ7*} z`>L+Ex~AJea3{E1a0%{CaCdiicXx;2?hxGFU4py26FekHuy1#s_ZOU-bGb+N*xkLl z_F7eQ&YE=$4QA%_^5}R}K*##qXVFx-v0~~?!zRnya8d6OEG4+}<>f`iwu0&AkdWJs zaj|r9-BC7&Th;M{`hHuRb;4*;oA!;9S2!NK%?I)OE#HSN#4CtZ%W92!Va1j_z-7;_ z^RfkAqh8q*)c|Qoqrn6=j(`WMhsjrbd{32YZ5+>eVp2oO_ep^GebjpGpNZMAq?YuVuq$?)#W5z{G1T1$dod^5j z?0z^ROuPmaYih>3mNF-uJtrN@anV_M*^G(yH-W4LN!m0BG{7`RO~975Q`%s363$??{Iu=+pnC)x zRfMD|l8`6Ue(u06tI_R|t8ToyG=I+P=ETAO_F&8F>w|USjHYNa_wgZQMzGeeD4&VC zmrlA|o8mSWm^_%vq91fH#UUa>L#G7fDi&)HR+nv@G~Y(UA0-=|tV5vJIZq2K24Jan zNOL%^j1DDxvi+kwSKBtCO7hJn)4`C+PyW)ZXsYVE>W(1&+NVU_PBYw$eb&PIqNg+G zaHDy|!z1#}6t~oBQ$nV@& z%*k@^kq+s!<1nE(aUf0O{#4d{kjd#t`Zz2XfbpemST$=vE}#?sy6aBvNHxnA*NGrF zxS~eRZN%#OZ~3&J@ncO{F$ye>q=);GBOSj+%rd(%(+~#{3xyBDmsT}S@uVJUxxA6H zj4y*x$+En;KEklJ?!+Z%pnV)Ba2&$w#P@9@NLw0&bA3WXW3u1oCFc(5L}|C4iW^7( z^66;U8x$MAd7P^CTbykkKB5}P!Pzf2j!HeJq5MK4@)juqqZ}2n51?O*fLn;=v@Pk?!Rz80lg1J}_0{l^tS>~+^I}b)q+1%n&A5r{Y4QV z6UVdZRz`_}(PDEb6jzA`nr0sZzqKn3XfZJryiy_oB($ z`V*;&MOy6Z511xfe-5)9Ms&h^Oe(V2iQ=_)k)JF2gUKV+O@UxH9`~B7xPe;2cbq&< z=)(C=s6deJi@ayr@$)`d0m!4&w-I6~uz{cFN?H_w7cm~i7cT^Q+GYh=!I-5l>qaj2 zL^9Zz-#`4&d816!^MouZKDUrWn<9`X89LhbPUh00PfEvc2EI9>P`+ARv}%GUe=^B6 zCZ+D7gQ=Rd`6UA-WocNQ=ugH^;G6S$?iR2uwpqc{rL6^%Brw5R`tjCbGQnw;{=v_D860_qA#7iS1VEnP)F1^Y8hiN`vG5~B6#z}5Du_id`kBO~6I5Cg0m`~@^R11?C z5}Pdt_0^m%MesHu?&Mv>i`+h8f8s@y|IHzq$4<6qpvV8jdr-SH_V)mJ6_KCO=l?%L#)D#(kF(eWu)#%6|^b_Q+IYmN5|rs7FqE|@$q-h=b>i= zT=_1l@DpxdeTMvQNG7So6RuC34JDD8w8o7`0FVt7@gtu>)n}PduFvG(kQ7SdMn%9% zPL+bVF`_21zr?TSN=Q*5J{SS9;G+a z`%28mhnc|Y#`chBbHSGg*?Z4lcViiRs)vSpv4IAu&9Q$tD4%a|t)~$Z(wD%D(z)%9 z+->iyDEkZazmm+hffl_g>XuFx`zRy^U@F4?8F- z>qLMqyih3ag*EmLJs7#KEy~&s9jUt~y-(pu=(Wb8TMrpXNeo`sX8~X4^Ts^^i(UfO z2b&L6V-k_bvjVjlYK#3&&DT%ARxwYGe}X``ChOnmTKixMJqgBH{(&byLhE8SqF$3V z+T3R?Hs^~7NY|kYZbtJGelNT$INW@gESH`=7{)RXUkNk~Mbw@v^$T-aO5&p!{4xy-$rB7sBxJ z&Oe>B^qBU-xi6|Mu^F;Uv>M`+Z`GiO$Rq%Pl7k7+gUsI;dwR>cL_O|i$W{~Dpw1XZ zZ<3aA2chYNG-l=`if_k%`{wmK-P?%D&)VG>G_7^RoAK7`XlabNHw+t*%*Md#)E_Xj zW8zonD<}w3=Sw9&S!9>DJKpN^TwGQLKu&8YQYfD7+dpfGmRc-s!- zTy3->qfvp^0J`sSkIf%Rl(hG`85xm)2?zX^>2+^1|sda z>fpEEdQCgGd>!X<2VOh;5qD>?1*Vv%E|17Vy=@;lUcfcPe;1p?Eq-dAO>M0y4mFJ_ z)v>Vy2gm}{{b)0P%>&^ z74@b?DMe*!8tTFIL0AoED%?5E_&)8laGa|G2}YbSLQRG?Gf&hg_gY~cC(;YCn1HQx zYr}=k*8QeM2Yer6#?&m4qZ%`|y2^1V<9$oI6WvReq&+Yba>}!U6PsTFTnkOu0 zQtPLUeenaqC=4ZMX2#ETSieJhLducom)Oi6zQSgP413VpmL z9z4%9*NWUrlfVx>YVEB;)x1x;j}#kOT5mRuTJRf~fI`0v0%vGs$$~b|+^@_i*NWaJ zUKjA}An(>!x3Z6R)yYl`b&k4KPHt>$9Ec5Ov!NcZsmMyiI7(wK3%eQ59uJiVuhj+? z%8S&hk-syuZIR{iEWY$+_N;eqsp^ASs++{j&CqH8gCUA;ombR1nZLT>FBdwTaRkvH zZG{;v#!WQRD=V$<_79FMKMtf2kU%5@}h^lbvYk7KaxT;C#Jg< zkv7X)2|7lB5a&3#h(Eos>;wWM#&{d~gMZP+Z!+hd@m;JAmK(L;$;1=jf-&c45W)WRBm>0TqRlVT`6=W(y*qY_XLx9A*LllmVqwB*c(o z`C*kex2ACb1I$MW2#y;AW*O-?5piStWpu);zq=pnO6+7)%@Y56|JlFy!<`=52A^D3 zB{bxX)Y#Y>uvii6P{;?GKD*J>D@=lZB}`dx04IZMHuNyu`QG5})iKmYfk^(7yc& zR#h^FR;>x4amm3vSnSZ;aF{fNfXKU4rD{=^R4dPRXY$>K$ej4ZTD5w(Z^0q9Vo9!t zl1aWrxjJ;FQOK{BpFQfJ;v--1f>DWsv-2JI;w)>{4RYKU6HK(@2P+1jB-5J7r1y$? zY>$dHOPn?wJ0z>tluMP)*hv)++?uMt@206BX#**^?g})fqmC;lvd>36ZkIAArbcB2 z=RH=0goFf#>MH#*;b1JleOJQX7qD}uX}ao?r0bjHTGOD`nK}ZDjm5x9nmmC~LrXT_ z=jZpsX`9o;2|XbI`=#MzYGoB$8XoZGI}>uUp77-*%Uf6l`)8e{G;zGpYB2zqQEJyL;K`!g6UijsEC9hQE#h9Vr=_r=Z?=XaS5O~cNm3*2 zs1xg(TI2KzxMX~w>{s!IMLw?K(3kPPlZeC90b zPml`z-*q|=$7~e3<=UWEi6L;a12}7-#Az_#KvyAx#-C6|m(pEI>_At*W8wh5--e4{ zt^&|?pwNw#6vS6Io=@ojI5be@)(?cJl|!*o!M`UQhLr*gSP4n>pP1mFj|+sNB#x{6 z|M%hfmN&TCf}zQ5xSej716%Gph%78Ds^(b72yJ08MOOT5*}AEXtZAvK6>BmuGhuvu zBLhkPCoi2RbX!&oK(zQD0J1YWz*bhpJbAzEXF!~Nou{W~T|>hFz!0I2_F*-z!|?A5;R45=hhwO#>+1ufqvGW12PJ^yFrs#bL?le-Z;4du4c}QX zGJhY?wf56AfwP8t{{U_G@G#`tw{P6bz@wSN=Zy)BR0%IBFv=P{6GyfW2D7U11h{5(ck|HZD3ups^lxr9mJf0tz$ zz&6g7NAUmpv-1@j9T5$+m6SdKW6**xE^L4?CB%%3DE$2VSSr5zL$KNWzPMV|m;^j- zA&rf9kUJC5|NCCZpo8u0q4#|c(ETy8v587b!cI<3-i*`M64TMiaKU@uU-Sb|eC zch1)Qd}5#9bK(vT4hl1xpQQg=nfxHZ#%r1`z;)#o(B2sVBhb=0>L%(j_}G#+BQ)T$<%|=*w9dCy}~f;X~~M~;pJrnKnafk;%vn$y&1%kYJ?!b zZCp2}G0m|-%^Q1W6Irb;mA~eWp#}w@cflC6YP&$+9W+k`;J`vdPwQqAwtsR`%E>Zl zKB(_z2DCE^Nl8UDNR%!V==b_*08;=TeP!ucMfhZ2(=IDw$?U8;E7plNaPjc8m((jX zN7!q0+LhSu7fr_MjYqAtjw<|neV%?*+KI?Q-FTja2ab)6WvX@m-1(y2a#6A2!1eJl z5QO8NZg)Q)sg*DN!aQi3pPzRCs1{ITHMW4?3#0>sA9wd7OD(U_5DfX)VBOw#*{mCY zO*LLDQ>3D$Wua4B((jR2wfu9vLzD_^Bn_8F#?v`G;ehZtBs{$Go+O|a-tPv7-=}Rp zsP_?j@%Pi??Ew`%y(q9FsZ1n!)-UYqA+bFeVB=%Pd#n46sV+R3X#*s|%1Jtt@uHbl zD4$QR`^9R3P8J6I`OSAx&YHtRlTE+p%W+X)&c?N>!TvIaelou6>UUW@Q?Ay5uI_Hy zWu~sZKW&|J3Y_2xX^x6_@zVx*>$WDTDf)04DQ}}-{J_>`%gU%qEj3JcZ23rEz9eU6 z=~2EU_EDr+KMT;58Ap8x6V+10_U=hffN z<4kJ?joJ$2O;=(7?g>m40%8TxBUiS(TV>|iywToq%W;(85#SY*Z|-5yDDvy-P(Utk z-4EOFczAdqL5|01K{z8Yq<|bh_gRnY)7;JP`G8XC3P5NB;IWM0F9Gs=${j|;2_w*G z_k*7^M|L~5w7wvzAGRIOLtv=?sZwo0ZqDDnW zV`Q}xrBf0+s}o_lsR+D17BPcmP*UANm}Cqt!B7fUpaVx3GueIFvcZ7;(WrEHZ%^?H8LsmIzwh5g4PU@u>XG~(&P5FI zQ;7IYe-}n{3)A$Yh(1))^6v)7>9>!M4GmB!GLS0isi+hNu({wQ{+B{Fp@4g3{!&hqr!UumEBbzFg@=XPN(0W`Em_+N z#^c^MpNp@iosS6F+KdC{;X)N&RBz!RvBb^brULTLJpORIiaeve&qR+|!G^y4j>qXh z4EQS{L?71vwy`t5OnckCAA^7svka5 zFJE@7Zy}lpcd+1;{#@UzFUbC)EtVG>Jl@`+yM3K$GwalNDX9I3g}i&BV*bmfGp-|Ne@yJi!smU2I5Y zd|kw1LdaE5Q_A@^3|C|*gb$Mz_|^jt#bhP4M4il~r+pLXc4PPxoMB{V;*1O)*$rwP z3?Bsup27Hd2MyIvW0OTI6CAEsoqWwm|6IVO-xqtGD^|Gbq@2HkDnl;0DsS^sioOrNhG` z%`f&C@6ORu^6xs;I_31HLF#T@QM!_yOr#c{qm+I**c=f;oWu`Bq2)f39enW9y~nAV zqBG#P!?tO5!{~NXRne^!1vp%~92byJ;%-wLZNf)RpgqZ|nMG6be_3Y6hw#isB~jR| zw3$mVq$H)`y^_VCzk&D*D1DJZ=PzChT^0O?Rd$7#%SWA;t6WEle8r0}v`!8e#XUT~ z3G_B@am_;HN4p8G#BoX@aWi*=3pN^W9?Z#RY0eOMt8EmQ@7U3ypA~C!Fp%O4pL+KQ z99;%bx>&q%h{87B>;G-bNdIbG>zX!q(awEn{j zy^A+ynMNtp?7axP6FP$qfBHA>E+n_n`vQ4O94V>@`RfZ9+19JEhhKx2E5G}#MV<#H zQneipsorUaJCvM)!sK0_wEQqH>h?Lbn?NSgx^9XFpuP_-$3ngfxRev8@~7rZjvERy0Zb_g8pDY zh#o<@BbeT53w?cMXko2sy`oei%SK=2dRcY$00^>ofrgAhptysxwzmF#wWa;T@#x}0 zXTk5#`@amPj0KF(RcI(@%AiC7#=sRBc}thJ@n`k zxP~tOzPJ25Astr>MDT0)E^aUC>^CcKCr$2YlVQWR+$5N-4(R*mw?Hzk-q_TFRcYnC z?a0`0)loUB$Wyq7SrqhkuYs0kA{{>6)eZ_;AP}>kl9FC-X#x5cHvXhtJ9{eePDN6} zCn<+zEdkib=;J=LhmPq75afYrnp1;+qky`D*y|G#T%leZu#){c*6tYB=e9EUEIsie za+e_g6KkPEM!AP>KG{g|#mNG0YPU-hI*9;JQO7FCWrjN4mk~AifuLVRF$>j4M0^q- zEiRXz9fmGCfQwD5N(bN2P|y0ov7G6Tj?y__@67OxLzYKK#R`kB#7P|zso&hy>l;)s4UX-e zD|||cT-;GVDAK*UnbClXjlANLE5?N(Q2#8kdX) zP|Yoq3|+R3AxdDPZ)Z~FOJCom#--|R#)P{XPY7OE|C;~4a}m>1W543u_=vd?M||6U zzNhjnl6_Hm#5HApho%40aM_+%Y?JeoJER&PrkiV@O7{vptV;bfFdl~ynC9IiR(%P`>&TI@TC@Mo2|+JXS!}F6zV*uaH%REHmVW^+QR6>p}bjmk=-@*$A$*qUref^a2M>7UpI8x|# zEgM{!>Ct*6rSL}c_YBPuZGdsg{+vij*k}Y5eYsq6vC%5O7SoA^n33ceD5Mlc$t?Zv zBxaQcrxu@}1kc+*9J-{BhodWCs#3r$!WFEhXV}&a=(LcDM*E^h1Fej_|8UT2-1hG9 z`~IrhC&?laQZ|*42kT3qz7kTCIP&1QGb8&6CrMVA^I!7s#NTkS<&hl%?GV?7B?oqDI?5ifMYFa{Nf3u2pE&d-ht%*YX$`1!YC4e3WvH76eKHyc!=%hBI5N##siIq>Hjxkj< zE=;|wXACfJ?0M$oN&qdCl>dMjUYJ2Br!IfD@uLhXm1L zE?{FImT%s8J}E*Yfzy?>Mm2xPvE+)kP8g&q*^SP*eb0~Qko=-3IVC^x5Z)V3?<+7? zi|kt&__hN+xy=M;>-Rzk$(7fiiwhTrPL+ntGSrM1KB459-} z`;LdEY-OAKu6o|)VTTEA<^XbO4g+lAo6>90hplV7!+-`^X~nf&TRuL%f6|TlZ>B{c z_6lg|5yD?dNlf_z;7V;35S*&72`NYPG)TH9g78Qk#B6Y;H5jEI48wV*0NHCk{BK<^lF(Y+^X zSYJ*C#_{m&zWmGd^QFLxH%d#(g^0z4U+ovI8faF)bly0*s-MtXt~3cd2$}Iuzb^Pm zw594`K?osV8LG}A$CuQA0DP1rYA2h4j6r4$3kbR7Q%kv~>wL1$6*ILsf zh`DvM&2%^+1TaZ@1RW(>&Vaqq=~|;Xy>-&kzuH1pBEU&?&4egi)d%5b2C1)_k8yv= zsb0%Y(vteLfULX<8c`{Rln?%*M5b5LQ*vA*B{=kBwv8@Ik~?N@$<n$7oTFoa7~tlPzJ$O} zr#4;2n^wslKCT5t7DF*D7c?(u734T@G%TQ@9gtz)p!oi|={t6RCv)IA$=`Wm|j{}H@NuUyF*9vX* zS5G0bg^{eWGy`A3*%K?i2(^2PHuT}!N%87XEM@A!l&-yzS#6qw$XM(y=JMy>^3~Q0 zj^dt2uqLJx1&0@imrrQlnnMSh15e+Y?E4GJ$32KOoxT`Fv*ooD#Mb9mhMOVacPmaDZ>Y6k`e z&>i(0by6gMfD%RE&)yd@K<3IT(+?zt>!2zuj>dFD*I^>8`>rBOP%~N|W4ub(OX&90 zatbTJskHv2oWWFAdBO98oAUAi=KUo~Q;iuOwu@sv>5uElzfhwJZROG?9Y~ArB zw-3%Aa*9=1LHXX?ag!a$L9Bg=LbmVz?RW%!ZxE=C(5NgZ|NMuKsz?UpsOZ6cbIA9J!)Pw- ziyLSA>Zm44LS}&K2Mwvyw&!tA&0D{ZX)1gZ6Jc&>SJOyX?8Zl0VP)sFXMwy>@US?YHq@qGqf zA+BmVivqUD)vyG!d^X>>_{b7lV?(bO?65aiOiXA@<(>)~^fpgJ3l5@HB>P~$YJxd( z18g0-;^*4(+D-~b9bV{|JG=S;URqNJ7ZP`j>2#)|@_6-ofEN{XrVyn0x%$hn{kPI4 zVJ4W2Zg60*;=C=h(S@#IrYAT_Tz}Nzyu9L$!R1+VThAYbCfA=Iq;tr`a*={pB9$e! z-btehkp|ew3CVN)#^A2u^1ys|*URC-MS_{;!+)7bwp)Q#fs2!K7hnlgvoWEaEhH;G zGcw);F+Nv{3A%w`8b>q^{9&#|K8XrmvKB>$Q(yan2D)10=d?glh3s@7Wt1mpvIIZV`Rx^zW)lcT*Mh5lL)y7<}Y*@aoG31wj|n5W;X;lEgk^yMCIhEPJLh(DDfhIFtSj(xt9+} zmp#%7I5<|Q`AiS@%pWEyH_e%l7huUyy=QqD7@%bSsL@#zuC6|Ozwj<*{JbpTqkI|| zlFj*;Cq2{&O^S*&4=MK`5LR;#HW>2@(W;8>%+CO>Ge{>rxgjD6oeiZ-{e%wwpux+> z#N?2Cl-YWjZWydiWVa7NE#(AjW~<`mEfEpV1FTdD77k8n{(CmST9l+P^u!CiVcU2A z!2~+(izh|B4`Mm$fQJ*RMX&;(4f6Y899I7#De1oFqfsT1I{46s*6|Q8O@H)E#z>bg zZ-E=U&52_@|K1eG4uYEwkK2WU@J~;f zXcihkq6`HHTaiFAWiiS*z*z7mngBb#T9x6VNrR={UjL_DeuMk99-UqnHl5J$(*UUT z#32Q?Zk@Zd-CR+dVMkfT-~uUmwXHAPSxZ!A5KbD6xBXI-*O~W&yL%TN`{zy<^XDJf z=Uli#!!?f&;rfpEX*+dN2eG0BB71V(BHbIVMLTWOsq*Ks-hNqXBhfl*YCppJ_GgtyIRYju~aO`IaJSS1RQyM_^lDkuH+IxW7+K!@U@0teGnTgJ%!G_CgNBccoM42l zMsqrLl8_J(I&ShnF(##zG*0UPPsPAc^Q(};cjmxZhlaBM@W8lq*w`K`4RCoknvuo9m zV7s@2Vz# zmxW>Q5SsL!`4Vy3o$mA(Caq>6!5eg zMwvffil0UuBjRFIzhkeYA_|;3U4L>`wPtcLuXy4Z8vF{I+}+;uw+X0PwqbWx5d*P! zDTa)-fNl?|H@fMG;p&P^Eh2oRnXNE7g5d*MpM`f&SJ&QFr7NmKF&S15HkTmhNoPE1Y4bb_?K!gi0&%BKthEcxGN8|@QnQ=w1w$_BYsCOpQ&0s{n0`?kjxe{R4{{Rfb>fcsDKDdn-k> zn>ppubD`5|<*-NYbR{owC9@iOYiowNVO5x6-oq(Nvyaw|u|7SX*kQJZGgdDIx7{gt zFn^k>fn;4kfiQYM6(b(n@jQAoay5Y|Js28!AK*kk&>E|#6Z*e60@=Ih53ers8N#FR z8DnWO@wh6xMyS{6-53N8d@L-i;WN9pb1at@MMtF!)j8<&Rv(EWexyj^@i!J(lD}S}%a`F?e zLea#d>KnH#5UxbVF_MqBd#FA_W^5Q24}f9}^Q37P!!^3^Aj+`Dp>WreQg};7?`IN4;t7$a!cRR*t3gwpiv@6 zVt@`2bw~Z_Cr>8T3({ZALq*zCMNuF2>M6!aIgMZf>gT#8@(*#Tau%{@Ki_lPz|1JL zY&QL&L>u)&w${)*tQTo#e@gFdd`C+h^^1#``)FWjjF?2@B^?tKiR~#0QDN(-S`(?d z4^)HJ!<#FJ}!0gj1E*OE6rdZAeYIQ8-aVUts41u10V z_;29r{(SVx3&G|w_mOg@eHNPry0gwO>=(AA;XiWS*>a##?c6#UY1@R^@S zHR>RPJUuTLOrRPz7mj_f?ffs<>QS%7AQZcLg)#?7N-8HiV5|ZVT8hH!cXxOFa)!Xf z^IeOs=n0k?-e6$97OiejVJO15`fXebN~cFj6y*|u`@FK zLoH(_u?>8;vbB%BZQNxw_ihG%<1ERc76J*{NFHxEHQ%-9<{S$Ze;rZAhC8wKD^y!9 z53G2++AI=5AS$b=>F+YerdtN&LMxMr5-&1hg=%1yC5Ff&2N66^8o;FG1Kh3@d?e8J zO%or?hOiZ&O28ui>DND9)KvC|ncgU!i22i_h)G_k8O7^Q?BICmq8iY z5#S`HW$0kg)!!OVln*a9#GmR56~y?sN-hTtx&AP$hP#HTcD6X&xmX_09^TX>3jzdA z=bf;yaB@J*1SFY*1C;oxV{1N0d9Otk2%fn!q$Hyl9T=m$3Y4Lxo$UsKn_|3Jf=R(_ zYHegTGYT%hCRVr)Svcr6q+5)}b$o9Qm*G9Qm>e0i^9FHB5kuCjIX! z{pP`%Wk<*29l)Qj(pJ{7GTJm7lorei!+zuT9!c!1Yh%TDC{g+#cA~wzoy_OCbp$?Bjcf6+&?$45hFH43FW%;;qy=Jyj6Wx?jMYX^ zaP(@8n%0E{)5PI(6_!~zSS14N3iU5>Jw3hg&6+w!+<=sSt*8_V$+Afy@&z_Cyj9%4 z$&}XP`w!18_%Tx?b%}%|_U#~=q7?YCOw35Q_>cvNehg&Wnlq97ME|alwX1k-1i{Ps zVUO_0@IpFmm{sd*y-~!=3LU5|!o!J?R==(b7228?kVZ51!@}A_R3@zbpt{Xba0dQXqU9UB=UAy0YT2A)y&&yOuvWWM$tNLfRMY~h z?#6wdO2wNHy=8l}QB~UQhC~!b8t}h~;1^r(h&@m4NLNMAf*vQ4bv8Uu&KDPkwg+OF zIY)`+Op25W4VGjL)C!e0CvFxlO^y7x;kp1vyB_d?Z?VXTXqidlfJ_c%f9@-bdOL8DK7183L1w`hJbxy52h4)Grzh zw{SRI2BaBQHmmD(-EBE?MNrmXwurkArX`k}CD4eC{Bh4;VL=|8+iG{bOj-{G>Q&&E z@q&5I7fWK$+-9$bph@CtY4-H=?52U9^q7PI!ukxRh_yE+sH-BI1jm9ve_X~?czo}c8wZQ(SWcB4GW`D z3=#8*G3o#?qBN5H(rgW7Oawt#a@UvPHKJU;E76q*=;UT)=V*tBfz>}Ve37>8T0?Q^ zK?x+eH~6m*T^)}_-9=NTRw={6`Hr9%$8~>D>I7~kE193{hMCd^eWeBM!3C-OMuSLr z;epIt5GHeA{S$H)m!ZPDAOgV-Dqkl=U?MC4W~iqCny1Pr zeK!V(%+$X6ww&}HSE!DRwS$tmJ0Sax%7U6CB^&?t_8>R(@`huHWH-qE08@oT5ceZ^ zz3Bb58};Wo93J$>cQ&kC)>SsLHpX5xXSh% zMJ_^;8zL}TC6o6*tF<1^*PR}Ge9%RSGksh0U|$fup(%3gMV6zQIUnXIXFpR8G^vD( zu;+5}n^KJIxRbr`;!B1vs%XH0sRGKylJNynG1$NkRH`DXzE4pIiwnKXnZ{=cDd6Xc zq~B^FQJ6n<_%%{Js3IihVMiuDLL_Tw9b{Juv>86mOb&*u+zZj-| z2;Kg`PR77W&}ADER>l-`w*Qj;{7B`BLCBA=oqM^D$6spph1)an4O3yD@6Pp%imLB3 zEgEE~C`QtTr#h}W2lw={lrG@QAefd4RaqxjoMw*btBBf6Xrz#t<1C~*KCb#=eth~N z`aLn1`6O}ZtHwO9D2urGsil(dZMpJnfwM%kDJz%DDd&gidk!U@9GF=ez zljG@2`hbGIpCjR0mJ8`OI50L;AmR!e6P{-TBs{NuPotx)o5m-%2?@XOB5wqK zO!>|7N}9vUS(n`%{X z2_jvk*^1yYjY}OdHpjKNNGycs$v8yj7w+%r zW@`-^lU)COg_!rSqx^IHE9&g@zEZ?rsR?m;%i5-v5XhgH|auLVmBJj47%usXs6y}QHFDns0zqvJd zgQ}*>EpnimTN8wpsdzq6Va@4MtghLfqEat(#L+|~VjYd;TsahiUj#JIZK>r98XO;c z30W5hXc=*L>}||4IT{2iowm_|gHP-%ykj0#NlDHw#r)hgDr^og4R<@lA7fH?_8A{P zY@;u8HKo#eU#`2_g8zx%)00}Pyul*2a)J+AK##`2{LhWOE!lb{Xy%kFQSTLRUTUq!pKb6thEFx{~{1-`waNZULDUD$DzAJ`Hd6B9!A z2mA5)nL{BKQ6F(;L%YQWXCxMH(s30t|BR=Eg&*H8 zcoZjHpJ1!%&2(cE^dUB6(V}Ymo&t(sBO+k(vkS*VpR63%O(Rio!F6qEO&|WMmc_13 zktne&`W4P;Ou;2DBh?}zb$#hKKt569R%Mij(gso-*My{2(L&%ReTcm+V8pAVQP<9U zf3SH;uZJx!##ZQom*TgnGw77|!Yp6J-r@&LkRS93~jxWK=tV{-ZRl}A*3J-8)j;dOdRfz@ib zpNE@7b-rV9KXDrAY*?P+e5Ge_xAx%H7}%;grW*c>L#_=E_6H=qeslhe$u0u^%+V99 zKl2ion*ocRg&BUDXn@Z`1TTG^>tUeak6?d-NF+|HVaZmC4Adfe##n2kru2w9IRp_?YRapweG$Zz}@E`rTH(P|oyl0rou z=pgvxbEr+?a0EdW(%nXdZ1z-66{92dRNXUTyllB@bP(54&wXeNLC0G=h|-FbzHW@L z?wy^-;(o-FL?0qJK?bbhQI0d$z8Gm=6lP=wB&WL_(ekx7#z!OeBJDt=j8wlHcX;u@ zQjWjSuA`%dzPs0jGnmc|7;D)$Ppz7`{q8g-<#Fvb91$5;!3Q$+!hON26p|9_%zZ3^=0a)yI4URq+vz!4&t2a5CzTZ(5tPF`kIZ8 z)IWsEB7l#Q1dTMsmJn_x@_Q^Ol;Q_GbA14r4QLcpMM{CCMP%k=5VKA6dd%-+`WtrV z@Wzbb!qqe_DdC0^R>-BC5mB39NthXkALdvCU(+D{Wob1svKiR!t$5y*9wvlr!$R-kl0CpLcr)?q7c6(o4Z5CFFJ?Ef<^YNF6{bS5!*q2l-|s)G^uzqdRk) z%1$NZG+=nHCEOIhwp(Q<`#R}*mbBm4xx$~JbqK3x7p#_$6lnV2sWBF4q$XS5ZgvqUcJBp1vTid;eJ<~AE$Es{QSm~9UmPOZ*` z|7+_i!=l>4^#KtH0b%HF7+OM*5=I&%C8bkAVhHJ!9J;$pU>IQN?p9I;=@#h*LE>)D zJ@?<8f3u&N{mfp^nzi0UyP|2k=2kR<@$S5<8l}10f=G{=fEH+}E9lg% zi;PVSan$kWFkv)kX4I{y%bvZzXmxDf)bO`huXpd2?&)mQ`4;|w^~MtSX#7tkrNA`u zxrlJALl0}(k!e^}HkTO@cG0F~qJV&`$KH5+F}OE10*uAQBP~As^3By{!0Qhb`1S>L ztgNDS$c11?RdG`V-xDKu-@>%o#Q~h7i6U+LBzy{emLj+*OtK?)Ey@i|Qc3BxjgnP@ z{LZ||@rg`_B86syt89D(rX)%%|4Ki2&C}C^MH%mx6530Vp!FMR3 z_$>&giD9-+R$OXNyp>p^0EPEp;1P|APp){<7Az8&+UoGgCEOX3#tj|ecyo&$a`(mb z?p;nF?LRW@g8sK0$EW7YPFc2BS*U!YByk?&(GUH4UbAz zi{mcOC#1^EzVz$)eV$GXBC#215e)$f^Z2UK8{^DqH;iN&v|4k&i)%cglx#!Z1#8nX z>zt2NWW6T!Cz~!~yq|qxHEy?6vSJ80oNEhnL)LaBbbV(h0^sd$$-liGtWW8)EmcVm zA|?vj>QRL|u5nry3+w$K2`T3_CXn)T*aNOV4ip$1O z;%$WmSR_p&0N0-jfmqccIj{Pmgv`u}#r9ZQ2?OXYpi@VMg@*3#fUC{*wH^OT#OWk` zJhV-OcKBhI6%BCxR>fQs%>xb+6VzMXeptPSOR*bEw(^YpL2NnF8nLIeSAi^e*ez2t z@~^y2^fKqwZS_i-{w7TasHAB>^H>Z6W_8k@>U%D7JX+94ysT~>cYkexn^2)uF`nh^ zZRb)4c+~84)A3C59Br>&<=<%B7mid`!gx8`KZO5uDBj(@O`(*Y zNkL9QY_mypT4UBmGj{pmx|yB22D*gN=_IMz*;0vnEmJo zM$+6R;WTe#@>sIZNDrERd$mL&FP!P+<{uVX$H|*v^aQI%MPi3in@$R*!4X6+hndm% zr8iBxSQnTXoCi!rWcVgAn7RVca6h9lfMkfU;+{6Bj6u4dJd?AGdq!U*CURni@UPsP zIje51ZO!pL3q44%cDG*6^t-rUsw%H&Y2kQ_gD+5S4#=qb0qx8?{CWopW@0B!mc>(R zP7#K)Ipet2{P87dJH!*7=tJRhc8#eHYP zZubgMT`|JlWv%Lgt(WY95S{6U359wHCOQIqBF(#(^lbJQf6Y-$gTJHEkNLd0p5I~<}bewKZNTVV*azW zA*9Y|s&Dg`&R?^S97Sn@S5H=64~g1211heNq2U$|-Zsh8A*Ox+TEO&ct!FeR*W=Zz zSx1TuXZ?gjvF8Bq1`@!p%f>9%oFYTU1C@GpxKW>IB}D$A@8HTULyNGFTc8V70^! z7X@*qng>+q0t(V&!4C{=2A%}F0ktR1%n&%to9_j{(3n!zg*G!7F@eilt~|wlS3EF& zi)-O~U}rET)p5VVG(HKRZ2<|J39k;1louAyEOrLl6E%Gs+&u@ng!`;qspk|Uq`KKT zF=ne)fS{qi!E}nds$t%?ACu~1oFwY{JG%6 zw~j+&W5S&~C7E)sd}UMVCagMu6pOzOjWEKH3Pg)-%~~iGiZQJ(Vz9HKQT%u@$pbbjo>jBag`Y#L_GBn~o+!@Kaf1zP{>URl0AfCBG6 z;Kou!HHgXYZ_|+R!o>v@^?+~XB6+N!#VT-QdN>=}E`3P5%rTztR02kc6tPk}D~JPZ>E9T=ne>I_@rn zfzuzlTUI*YYmM1}=J0v@`5<*|pN71$SF9tDa04CXZj_Oh%WDTFlLUeP5V3KV&*?C< zwlpje65uv75;=i1`%~Gt%wg=Y7NRHb0G#rkpti?zO%^{b*h5zc154hHKPEF&j{+FK ziun{%N3VrK%m<<BuL()pfi)J&_2kpKn>CRtgUUjPRmr{^v| zzmh)&_r{*=8REc|PQR{>V)S9C1w=+KhS7Y|v+Tv_K8xuTRIGXF3D8IEzLk9GIUYGD zfY6HvL`Q(wUO+B`b56OWhlF~f8g$$#l606X=|2QNC5W$54{51caA+0k2{;tV1vGE= z8@&XtK4PGuump|;@mTf zPr%bUWcl6fNLUp3j5&2)`Cvp=5yE@rhKi;=F6V5#d9DEsq7bC`d|;HfbMee5?Y&S> zM@P=Mb_Y=XGrg^UZ|F9o9i4|ond3;@Ak}vQWNkDKj1PP{q0r>&AJ@L`rdwRKrS_8R zNlBGEww8I(vsqOGc!0hLf<&$WDn8F>rWlceZ4dvppF#*!OZ(oKsn-)}swJ#^YrQP1 zS|ZDFtk3x`t}K3j6Y6D@S)>E#s5P~IijG8%nzv4N$->IWYQSrvo>AO#((S$D`2C+F z6LvuZNk_%1S8*%7(V3bVxz>$Toa!}_dR}w>0|mc`=MuWLxiMNO*fLu_{}VG@X*Op6 z9sAVBsnNND4VV6efw#S z!R3weB*B9TFMAX+-T&^OPfE|7xN?HFKf5=4i~%+JqCbQ=%76nyjwVZOT(aZFm0vr$ z*~3zB5!2tPa)EDI)GRuW%64ndVhoJXN}Nx;u8G|WOj;1s3#*~lWP5HukjU8naQ~;! zZo!+U1(?2-B0vL8Y}mT(65xtOnws@n;f{P~=JP=F`mLn&u#)!3}b!*8k&Gi#SP#n)bX*A?o1>4otXSQg)TzIsmac?NR94mf0)a2xN zSK@FE4Ems3F<^rrfs}*lpH;umVk3fgQwq%CAlBD2><|%we5kEmnVh>-QXZ6^MKoiR zwZ&uHy{d7ED?|CYI@XWQHs5erLf-i~V4hKLtwzOs+CDZkWK>6>{d8v}4SIYlI@!FP zL&XiRMv%<40P6)V1oe;bpYlh=PdM*vj6CU3@mD6n{aZK)$z$bJjq{wj`neP=@L{y`kL#{?c1P*KY~4p8!YmNe;bIm# zYTW#&O7x;&{h1^~I}a5U&T=IgK(U>xu?%-hR|Vx9Z*TeboP8;bfob>@;8l)>=B56c z666t;##Wn6*(0n{$jwyuJsoC)Mzdnj_Qjn683z2cRW}43ZBf!XIz7|mg3w~-xT8ej zLR(t+^gM{MbSVQu;_RcsJJ#r4OYeW9X8o>%|w7!JRZ_GP^|= z`08{*SI~4%y1cZ~-nc=YU!>M-0A>@=m8L);_0XN368gleL1Jd;u^?TFGt43iB9eOq z4b_W4>IsY!(PaKS#8F~EMoz?M21MR-_E(V%IBYI4$`B8%Qb**5d^`f|d?(+$=Yk_g zIBHfN({|N@K%}tju%Io+iqBHiiEN0kdx%!VYN$dqfDBkuT9jYf9O0~^rB_FvnGLq$eI?BKeS#+kc@vnI(BnYGebUu(~~ z&EaAa$kxWTrBFDeZhNp<8&qK;$l8Vl_SkjwU==3IS>2VCDblWdrpJ5v3JEv0R9UwN z2$3f|kd3XRg6)Ax#kT zZW|MzkKwFZvz400s#OK5>li+g2InUJ3sm^g>!tI&N`34dBm@%vyRsAxfS08ocIn$u zQgZZ6d_jamFgpx)zmAK4-%mtiS@zFFx2JfH0Z4}*orydU-X!O=z5VWp3%vk7FMVKJ zO4F9KK+a|IS)$XYGO(j+o$}EZORlgh26CNJ^wV`JMW7$yuQv)QogiBY+wWh}UL#jR zyxA@O1L78jxAeI=){km`YjuCF)&e_W ztxb+M^_vME2wfkF2dZwKTa)iHCh<=B=)_gJtg$+IpH~S0Myd3Yh5oXA0)D%pe*&=- zFT(bXkiuYJ_hFXQzNduw-(P=qFlX8`9qu6i6a7*0AbS6Gt+X~Ny0^`~tfpAGZ8x_! zy5SAup#8eU?9Q^K7ossrQ4C@5 zzaoCal?thj&~^}1Vz%#?VV0H7^RCe&s)1}O?j5A9i2d}@=g%t4UREG6pyDiUR3x@F z@BdbwAER}vM5THBvG&^wXkvxRZ?J#nr}mGo^}|A22g>%%CY|o^PUgB7V@l|I83|oV z%}g#3#;YQlOdT-(fzV1KUjB~3mL_pobYJ0$U8&0a6su%H4-Xx0CxOrp^NXN529mKu z?)tzd_U}jQS7RIbhpEjs%4=5jTG$@$@HLi!`1nbv~bfV(b0z>3F!4{l6>Prho09ySPuWr&aj?h zqw)HcKM51?W^3{;R3{fmv4N_jJf2gkOFez8S&c{~id5>AIbkewGVHC_i}GMd0!bWq zJvwQ9ZZXg&D#wK=I-h!Z4?3LUpmAS>K35KWN^)#ENAG!=1c(XbKj2f)$4K7%qP4?7 z5NCVGZ%MTj0+y|Cd2Gc9W+AeB(@(Mr3!51VN~I?ogM%vE^TySt-R6m59-2F`-kQzy z@n3%exY>~bt+oN|;ULK(%WRP%m||C>!f~K9%o6!HwQ!|dVTtSdXpuk@EIl@+vK0IG zf3XtAbcx^8{&j3C!5cuX>)t%C%beH)klM20E~$jSh>A5;PH!0=WAFk3_cX82KN?hu zB1-8SlvBT)god@Zvw&Ld0w%VWM${*onpaGmxUM;_EXtbR3M!7;;F5WH$DEOjhzLsJ zC2al)$f&83g9X(9H=%GA&M8N&clWi%?9{i&_gH(#)-j1@n_0~q+DH)~w$xL4?nGb@`t;*Y~lZSYczia98&6~G1$ zV3*k`6HTY?I{?_zWrd2v$cZjYxMW z4(gNsIcPMg3(r_`olokFk;P7&HSw2d;W5hOPyJ5b9f4HEdCOvu3r0ubafTEGR~->E z)Q8HP^x)@ky=$vx1oI60>UR)7QJ#)WP!>vC4^j3{=pW@*O}d#rg5z!>$60>DL<@FO%R!<-ZVc;{}!&H^&vLu?IS|J#t%o4M7ah zCtCexM z@G^qk#=a$G6TTRRY%INORtDqfX<#mX`j8#%teX6>QZX5XFV-mRUb3etGgQQ|7Wf1f zg+85nsQW4z^k_puA4;71M-gWiz$g*vOKZ7Y-vP1U1@pd}|5iuT(@h|f3YgbMvsUSA z))?%RDOhAwYpRMx^-qIhTVtxV3VLqj1!_o>f)!9hJt4T>DA|m0`-^lW;kTig0iwE& zV7(89?uKR7B{nj)i*WY9Up(pw-5D%5a@SiTpAy5gO_oAKGSsjvlY9nv{5Zh|{-27l3I05Qd zNrPA}URe4&qVepZq~%%P&7-i;zeRR0_d|IomXigG68f^gz!g}lL`D|{1O{#_gZD%Y zO-r+!m54WY$*@bRUlfvRd4}fBQxEyi7Kl8?RyQ2JF+C{G!|n0slR4J<1c)ai55?`g z{+4@)p-oZFMz-I*_dH685bG1CT&ONGDdEDpGF+(FoTMr6Ro@Nqq7*hX9{EE?$-t%X zcjc=O^6e~2@ent)pyzd-ld@#8y4;bV6k-(<*Dkatef2Hf96SeQ+nYI>d6DD01vG&4 zXfgvdsrb?vj|oI%XFRtKb8@}NrOuk1SrSI3vjyyHDGB(Gu!5=4XMQekI&8ckDzm1E ztS0j?JtD{u_jGoRCM-ZTu)h>=-@HQPx62SiOj2UfJLN3=EqBqj zWAOF5ek*bIi)VqHUo%^$FCM?C=KJ`o*oQrn-{eGojlhbzz`;*145?#jul!s(7uy*Y zEL)t_+J!sfz1|lwsX2*x#i|Py&I*SV&w|J6NQE4i+rDJ6y~!Z<%%|52X2o8tM9s3# z0tG%FW@=XM&5e{86wbZWg&yvtfJ!3=5;L*KD+)C2WeSPS@?dWv*BZi`S#mL#L6B0km zpdj7#G!iMiSCjs5+KyxdZ$|QVG+ozq`s(yK1A#%%=tIXRXJo*%{zUT0DAg*o0+Ofy zq1oZO_4H5vv0&QDmAixgpx1`-Kf&}kItn!5TQ*A{>5~p;B%C@+{)yG;BrzL)leLo@ zDAmw(PjQ!a#K^>FiqS;TdCj(_6#DA@ zO!?n4q5t<2`p|lU(M3%FRsB6DdK&;tV3L3=-uVBJ*THLgPQ;~I`n!>TkrhQC&a)v{ z1$x{W%m3Ze_b>L6%#F|_&`3HC@ M%BspBAf`e81Aq@*8UO$Q literal 0 HcmV?d00001 diff --git a/docs/images/29_Soft_Cutout.png b/docs/images/29_Soft_Cutout.png new file mode 100644 index 0000000000000000000000000000000000000000..e323471c89ff32b763c3ec1fe1f39d9a796cb33d GIT binary patch literal 106575 zcmagG2RxT;`#=7%vS-@r_W!ta z-_P&){>JO?^?dGn#C4tHIFIpuzmGFoQ$vLij|LBgLJ_K7Q_@DEFv3tM%u1Yd@SQyL zFe3Qlvd2{ek6X@nJ-jX4?x1d1c(^z^dpO!zGI`x`bGLJL65*HNzr@RA>*3+zE-4^z z?>|4l@9btHz<80>6CQ%=a?Q{kg(9{=4>M#;8wGQMqqAQkfsubuQw`(OFtrnp;_g z&d*!>AFjPy8Ym!sthR8k)r-URQaCconWk``?av%Dv$J2PR{~Fuy(Ofi@`{V`3=Iwc z%srG7^j<&etG2eBZ=I)zigq^SQW*kvw0LiS z*hyIT{qcnw)$k=lWM*Lj3)RuvTVLi^sKXscFGcb8?OO?#X%sp-I>81ZO!TJQ@uic! z`qS@P{(OcyIv1p+r3oq+;Yrea6Yf;P);Mi()StuH(tYRl1bQl2e~AltSYRMR z<_)N$t#(G`0Q)Yjo7s}#kqq~7dU|?X+})eAF1u^qz8w!+IpN+b{HFe zr%w~w8H4CdO-;cZmcHiWr}7z}%hvE#=~Yr1)DvW8gY}95+XjOda{r-DC+kl|6aRAZ zQ?K+d0@J|#J1uQ(vx_-FZN|=Z;Zs4U^v8#L;$KislOL&*Ic}bNCg3dXv&lrkZxV(4 zBTCSB+nP?=hXk9Lq2;6RujS*?urSPPY-Di^GGmUt%PT8>_8HofnQ4=Esi+I6diX;i%2cW@1)hVX`M;_nHQaZoTr~cl+{GhIVf% zNN&Au&(smd?)}}95}DoE^H;XFxBKdYg4o#Drpw+gsi_eh_vFY4ph)h1Nw@GghULUU zHI-C+vbTLA7xW2rrK77$+02T)D^1BZZDW{LNxXC*lXUu$IVlDD7IWMWFOwqaqaod99i}~ z)3=TpT2l-%_i<2Rj6p~JeJ}fMF>l_yX)#gb8u3=&)b}ci32b3x>A>cxuQD7B1vfXh z(5FdJg?zIFh=+V!TPyW@Z9I}yC1Luz_f+f1D=XKn*{dz>?Rm!UoFX#nZ`XRE1*`hr z$&n4{%fFr`X_IA?xx8$jCm>IPLP>eAhlPfQYDIHz?(H?vJgpP^W`s>dcg4bjnf*ql z^^Uq^HW8e0;smA?)Kv>EsvrMR2AS*psOP)<&zagHJ{S{Qa58qT|Z9 zwzorcxJ3`ErlQ9%yL)?ygHLLRuGIHz|5!A7ZH&1^lW&;5e*HSm z>(ix3uxch|W;9sURtOCT50CHNyQgJh;`nv4@B5A8qa&C34${208rhO)eR79jcg#2; zTH5JPp2WgxH&+d_Yk()gxO7ut=U1;B#-BsZ__1`^gC*9TmEnpWhmUo2-P@z^){dSY zF}vQ*PT`pFs3>*U2v{@T;_~_qj0P}Qv?G}=_u<>#XnoE)Zh6R-!-&B#{o#`<_{|v> z6BBc;RTPf?pFe-h*C*b0eECvZ)f-RyBrGg!dbTxI`Llt%JQ@+5MBg(BM@L5zdir}i z3-j}sD8#p^UBA9Ha8r)@c9qk2$>zgg*~Zt^)vZOh3gQm#jlOPW`#pXfIMMkznd6mh zKMV4}nMlTSC;}=$6hA+|g!g*ZXZNAN(UFl$2UTdtzjCC!iNI-!*qgm`qE})e1wV5) zwU?R2K3+ocnvxQQsAUTdCMKr&&Qd=T4?HC4HL@fg-04bf?C&S7y4#KZEQb&L1`V=8 zQLUD7beGABii*<3of*(EFogVmuNns?BqyH_2@QR9r;CDsQI^ih$!T+QQ;-hVRm8@| z#&PsD76fF*`@dK1JOq!y@Hf}qP0h}KPL8-O%b}4K1u^ZyL%9=)mm1kIAtC4x6EEO} z=W4m48qVL8evrbWZ~66w>a`m;uD)~nUKw;6$ZPZlCr>%P3CN!}W|5Ak={uWV24s22;ml)ZsIx=(#|O7u0j@?aed6%P zRE26XJ1!9s5&IsUuyqs(1B26GYHBLGdb*&zi?=tWwQxpX(JhXdy1mKsZ;bBML1HK;6v1bO(f&wG(d z^o;N8PY-Z_Az;NyEJ^vz%*a3Gid`YWeEj%v1GqEGSAkB6xX-by@7!S)6zuzIK>|;P zM?X$VdJr6pLaF2MHGTe!8+;Pk?g!;N|F9L+XqFz)kcNP3anQu!WaT^*l4qdm*Hd%MPkS@v*Mgfm5LXKkF4N55Rj z$HymBF7K_n4!lKI!PeQCI9$O(6eHD$B7s>LJAw7zk3FvggQ7UU@!U&cPaI-m6)&&1 zGb>;c5qqipw__mcGeUq9f=GhS$jAukOzw*pEg_`mkx7w$mt_z0OjOI?+}aZI_q~4~ zy|0(3+~5^@Mcr?jws_jes3@G$+qD!Bw+-q8>%#Nck;P(hV8sc^SFE|18uxAHYyS1k zU%x_4_*JGp1t2c!jl(bz7Z(@IOWwpJ>v@FCc8lUH?~?EAQ>-dTqQdo7b3P%)_qU z`i$2j&plh;;w3AUxpVJs{qb+w&aSThS5_(}^?~%x^~YlTCN;rTHoYvDFH>WjBe-(+ zF8k5Z5y7zf6EQ+NJG+rj0e;zgr4F}QP^D(|48MQ>zVVy)ud#R(dtSNEm8i|qG(<+K zt)|3TA||WH|IIA&FvNo*rq96F_cEAm@a(K*vnjhe&Z)eiA$3zz6H*F5Kp{q6rl&{Y z9}qwofOxpLID#Wc&O9gc%BhE-!ZaCe{Nv9%Hutyk-=oZTS>>%F495#t{RS^@BuL$9UW40 znSAiTMbbPJ69-2-C-ax??(lc-yzBNL^@abjuL);-Sq^M4uu>m<{Xbt@eLIAS>0&*B z%E04mYPz$wM$F~&DH%JzT;9m*RPyA8ekUQHjlq$#8M)TlXM1Vn?HafAh2MH25z8^5 zxHEE^B|{QHC(`E#X~O#YG$9Bw2?>$P`2EI2>FDZO^gfj_cx@dW&I+XooHQw2-LmGN zUo6@3$!Beg$yDvsEUJ@D~&f-L)j^pgMHYR$sVs@$!7$_?(Bhz1D zCPydffz#O7hzfr1zL=Yvi!O5aiy)nPPGTa8gM$NKMdQqBJV`Opeughd7~MMXWz&uB zdY{jJJVEE!$J0UH&s@Gl4@(zh(~(bxuQcJGPBJ+U$#w0*AxjbtJ_T<>2o`=O2jtf9 z^?{G3jL1efc2^|0=)kbyNV{6K-iv`KipW*;anRdeF1Gy(Io=^ifev5Qwyoqebk_$e z4y7I$MI{f%XcoOMI=aQ899G{{c_P3)LcX5xl2-1msQO>eS=b7PY4|a@#3LhHgHvyz zcbMXgFBdHZ6m=4LaurParCJETA7xwcIDG%Fml*QJ>qY(=@9*uiU>Vzu~_%{`st9|9c0F`8hzyGg1_ID78O9+eK=G*`rZ zBwro<(m1QRV79R^o{X#H5#449FDO{{KiKUTH0jxo{J982mqEX6aAF4s?9AyG8tOQB z)+F8v$rD{UO?b(jlvjM|C*}Oz3c0iV;~qLTqF{;R!AluE;;rz@mO=-8KU#ifST8=qO*y(~SB>Dk>!nb~r?s^+&Ba!&ZY zB1Y>A&GkKgYh7vD?xl$T`&=#BTc-H}r|QUo&LnI9n!;IhiU0IMY%u>Pyu96@Kz=WZ znDoqlrk1P6udiz-u_wS)Mq*Q?Q~0UqXrNI!#ISb%x<@4~y2%<7+14NI z4*~y}6Yq;>I`Jqo3IcXYbaPw(XntEdRV9Gx&p1tVl+yL}qbI zQs!<@=aWu3v}d7dR$!D)i1%O;_e%}ZuCn->(O91gzoUCFTA%srRO1dsUh!DX(JlU= zv>@g18Wu@|prg>(I&f(0|KvX&<4};<%U@1-`HkUJGm6LeQ2(zV0b% zF>M(7uKC|*?+_OkdrBnh#=X!vKB%|)sWzXc_t!UjR6emdCpg&rU?InPD4m21aY5f- z6qXbBjip*yr(Zx!~a@kwH<_- zy2_6)cWwn8HRn%gqsXQeVxH%e)DdWjV%P5xxn8Zw5pldj)`g{EeU2S>20U+HwZpKn z=?+p!0RH3r`q^2Iml>m6(mcvbp74$C*aiG9;xFX{jL||r9OT_Bl*(0{=u2408N|zA z3)9ll@>wZ+x7ma*kWTOiDnF~`!J?6B2g<)TVNV*vb4en#TuHn8ukR`n;yaDo)Mt`} z9fl~e`c`J_-mZdp z6zgZjgVW$BA8F&eUb+!I_w#CDpKbg>2OCS+;bm6Ik?J1=i0}T)cR?u0vqXehhdagR z_oxk00Dj!=VRsSu}KNJw_(-mj_MqVYo2CFTipo$8FJ^@BOo zISij-)im@()CQ4>hQU&H3Dldze&FEYDQIhxNqVox4V(HABJk5WBDyF9B7{I0tkZd( z2if-y|Ke&%lMb%N{>;&{s8q;(;{faZC~NWE-vW{&g!CT`PEjF8+>9`i~xGQ zvWEm}`D6iyzgs&~cu1jW88t^{W|Xe&DVk8gLkO{`fJaO3j>!oZc`V6#fuPapVt!?{ zW{XnULzvaDS(Bog!uT@p92L*^~_HEsrNznDYokpzg;Qh(kPHYSJ7)vDfEq)vuv{oZ4emoHvGB8u(m>KY;T z-UPw<06N6jWe>Bjrm^3h8fQGK0e;;pU5I-!CQ*8k!QS_Ol}@~Q>bK(|t#RdrWccS* ziKkj&!qu+(1xmaMHjFCA`$6*j5Sh?(z*%~Z*)PQjRN*ABLM=q6=-F!dm}D~O^qBAi zj4edZ0qe9t?7_yTLj)OVPGVJ2pX`FF3+3bIM_UcGG%Fup*`y!8=|?JjO8!fBH?Lg_ zuB!`RWfiMvX;Hc!d4-Rzog@RJofJM=1Kj24<;6-hMl1?y(Ks1*f{EHh{M@30NmS6* zvM|HAk-xY_lLeD?pc3vFu>T%!bXAJKbHl3ecw2MfnsG@3WBsed`v|&4)qlrKFw{8emXRq>* z7({pdPqCDd11W*F6W61!u`ax2uv}`^6dCI$KUW-MP38Hc@Z2Da$Cs?0-oE+I5>=XGyWEaNdZ^QS&R0i)!2@@dr^? zuh=kN?QYyS5J4TAtnyxP9hi~GZF~JvNJpOzY{96E0&@7K<)ISS;{#8Vk3OUbZ2;go z2^m=kz+U2Zm8pXMe_XO;1I7y1iVB`80NS~=-6fC*2rJaB@|Kn?fHvWx3X6-Ip33-D zT7M?H9tPZz(xC18Vl_5uu^_G%h!VxlV>r_r&a| zM`{BB(}CvTg3`_2cH>(aZK{CT;;@jSJ^Ej!d29t(7>7Y`PD7nUvQHVA$xjyh{D6eCER}yAegxCuOAkGZy*?b zf33IkFXrDurd~aOrMSi}a=UHN7U4|*&kdnFGJGL8Cgas*(sm3-0-<_4y4}Z9stoAub zXDD!I;Mas)XO*n)-c=|Vm;u^I$<0j|;$);*;C}ujEkZRAo@{F6DStP811qU?&mdnp zb|9k_$_hAg7gC<226^qc2^*bKPIqqKWGQ~4s*s+Rh7H35{)Yw_trjp3z|c3_Xq}(w zSC}Hip{11-t;esJ7(AR1a|wSLK0d-H;?Bxx{I>-Gsr@C33z1%n=ay!%!0F%y$|y=C zgImWgzBm4DN;E0;w57r6Fa*>dFWytO+z266oa5tTge6sfDoqXa!Oc9fcdxA4ErHVj z08kQO>b`f*W*yeT07J|j?@hIf^hysDPM-xee0dTV(RuT=Y@`BvTH<<*g9h;`{Sdn%mp4Z_4amczS=C3xJ>Xx6Xm9BSO4ppXgAV z^{2CGKu7meh%44& zkn+`^>ybBJ{>IcAgKl7B&Hif5pGQS&vYojocH>=ySlmv+l7F*GKV>m#I`OC zS1^A4`t{2p8?rxo>V|sxQ^z7V>i4@oJG2%Si}9bnNs8%bZD{>lA@lzhgAyoeEabj; z3N8Ub3t|94C;kY@h#0TXy|GIO)%s_+{v`aS?EXBX^CX;wqn&}9KGP4dD+3O_5Mm9L z_~Z#bU~``ekTU)?3*@)e&rIsKuHPW@x%_VMMNVxfVJ^W!j#Jd8{uTZd1LTO8z|nHP z1a1w1&=I2UjorW|L}4*bW`D?81TC5{kw-U2604}I6QGVAXUY=Fk;mJs{>{)G4NlV@ zzf=k=vfH;wFTenZhCn3vIRj+cY%H+{?O}qVqT~RMi+(G=9Sa*~F;Z!fF74|U>LeR@ zFwK{7fz3IO`0H^eXiV(HC>Y?T|ZWY+Sn3p8x`l;7x1pS65;xT-k?*$ru)U$Fa) z?ZpVFF>5YY9wkSWUeCt002(v!&kQ!A2S6gm(ed#XVB)igi@tWPLvC^qz*GRoThoQC z5C;yp5LMk2IE*UHoA9Q=K`2b_TfDdUm6lf&UZbP3Ux1VVjZUKNay7Ze!HBtaEQ7fX zyu8s2pw`3APBnxiuRl590rc6aB+KIXU>7+;cYCs;k(9nAij+#^E&;-E0_m5riv}Jh z>WgaL(2QfMTK#WqSb4;#ek}nwO=5bVpBNzqfbEa6(+=Y@{-nw^rz9Bi7M+ zDpOt|lgK%@CVW2+0LL#ma*SpHyF>Sa(jPt~Mo>r~lX5?Pq#J+d9BI-MbQ>`B+?QHq zLo@zf(adPlnR-zx+ymRa=H7nCTg0M~^^v}k3cPp0Csqf(%O;_qps<9n_%4Oy$B!Q@ zfWb*-yY6Fo(;&&IJ9p9G^ffivw|Anpz7MOoZW{@8mb_68c!8iT+5NQu&QzG|`&=G1 z;4NGe2(nRQQtExTwJ(7)-(aZ#yp`D%S;yiY{-7){UanWd;{aqbIqUG z++!_LGwIM8dK?skb^#rA;jQ*gF&DC`SFMBbR~;eMSHc`jI!pI}rDeyRh^P4w`t8R?twrv0ZQzy(*Rms)m}eMiuP{q2uQMf^2Nb`gT2!;Sj-9(;r%D=aKL_g(tpMJ&0KKdfW#oTmzzz;70=ap~&MDcw&3 zaA3>hV&^jF>FRQUpyLS{`6`~c6zF?CF{dZTNb##a34{YY@t%sW?!A2*fHrgLZ(AeCHJm!7=et>c0`n6o^8#IMu) z=iWESPre8eWoF5JLUlYyFYaU#DuB4>(^ofvQUz+R+ZqU;Lh^y1m?mHNgp5wTZ`c`~ z{9JU5EhG^K2!jLx#So9x(G*9f00d=o5PnE-_Y?8v(NXID{(jWXA|3@fxu}FIowyU7 z*V4<1d=|c>S*P+M#r%L_6g_vu?|gIP|VdU9E@1^BWq|n<<4?hAyU#I0NN2g zknr>vlF~U~XWJl`WlmZmb_SjgeBZeXcvnN6CV`y*aex)99+cisKED(evFUMiJVN%Q z#qBzG(&OTm{!14VUQ*0Drs55Wrv#0SU$gI&0|coqhMW10chSb>_4GSN&0rmr+ zn*A8bJMoHSP8tbs`)B_}=}1XMmFsXVJUvB0$MF#8bn5CHxgZ9~>~eYWo2sgICLYL8 zUz{b6eH$kkI=^&HEc_F4u3>s?dwpd*)vUs>4K4xBx%`xs#r`M6w;V_cjt-|z+ZMXg z5G)u(q+mKmpStgvhV}+1Z`kM1&Y%^cK#}rw>mJBnU+k4;Pd1!rjGJUa?piSgUCp$ap7cIzM=x6 zwiOcS=h{W6XYx-zX92Gc9InsO^GHERu#{9(ng<5X2Y({ig&!KJ50XO^IWQut?;kwx z-oF6e=53jFUMuh%%>?G!nPi=A;9-eO6QasxPMAjsA2=a#+P;M5&9T0sH#t@?LNJ3? z$Kbu&MWkrIKuM{{l5~YXE$^erX~iSh%N9rw1ns`Ebu4U4#b$xY$Mf)(H1+EQ%z6W6 zGcX*Zl`m?#D3BIIO1%^^2{`$EtoKc$NJgdfLf=`z2WqR2e`aG5-5Qdv$P1d9A>Ovm zZg2hj79<{);F2XgmoI4Fx&=i88Zj|3aKRW13=BW~&|x+RKl)-m?YQpHCX-D6SEu@c zuS6#)`6^_fl%f4J^Q82jgM&#euIOuQ3f9(afMwB=vq3g% zoLByBR{bTO$}N0Cso=8=&|zbtP~fgzCg>mFjBQ&l3 zlbFtu#K$ksKvIqh@-ygjK$%h&Gi&djr_#r!#lH%tw@e;v+1&h@YKEktbfiND-9|kWk6}^G)PDdebTTri}$TfiY0n z-zE6`8kBs9z2`#Vf(ix<({gp>6_O9bJN|#LpFH5N9CUyw%P6&^yMAl-S~t7kem)c~ zYtr;_opOpYbV%e=x={>gB1wfo9(YNhA{ zE=zsP9&2MT%+dx>MDcX_u0+M#+l$nXF&Av}oUCGh0RMl5dOA%pe4dx_}RLe(M=+W1h#K+|=MNrQ4 zQKbcSA|Ndn3Hgg0v^Xf3YmrPdSrkwnUx|b>;lWVK9QDPp^73*JI7NW=#l*y9S>4S( zImeh@ed;UV22^4x(FqA{0E=xlVlz&I#^fAoety1TczC!^4$?iakKM_eXRyz4>;r(F zG8?tJXsmKm!>yveG-}UXBf&JerN_io_5-NDi;pVOrhgdG*ho?5hTI1K5Cf2*(zy=} zdTrn3$_RrP5Ncn`%5Z?Hn1?7Y%mttvP;ZJHiF=C;oX121T=4nx=l>5-2VVsY{#}Vt zN%Q_HS-`fwJ7$Y#%Ge9D%GvLQA!2M-=_a&a|+5IFLCt@j)h7mHuqst#?61J7;xd(kiCxN+V8_BcoxyEa!P5r6fb z)4mEltojqZ#hgbVFhu0jND_x^E2t!K2nkyuaYX_E0k!Z8gpv}j_^Lh@z zq`K)lzr0_SWE>9wt@v;18%6U4a$hhY1gnRHkbps&>U6(1NYJ_?(fDZNtz4f_^+)+p}7W@fFU}Y{`|4#QNdWeaUe{r0U82*2u;z4dX&m6~_@lM8OVA z7y$z9i zMT#J7Fh8r$k1n186Hw<^b|f-WNqTTb5Ktpv*!31QB_+N@KpVB4iYyj;^X$SqI4|*? z?s&evS^<fPCBEesOUX<#8?fb394NCGPaTHi*Qy$K8yayXFS>oClZ=<^=R{Dy}w z1w+Dm$*&UJ-Z6La8wuYs9F<$UXG|{e%6zA*^Lc&FCuFlROC;idYDeVr`pw7RIw0Ju zFbJ^*2~J-9Zfk5r1Gyla_|TFPo)_9&kZDfQy@LJ2Pt?y<);6-Zfm=vsBND3>Fz`F) zw-^~1ySzsfZ7$S4A{|&7Z-vidyHd3}nL@TkB&d4N3=wF&lcQfZAE%@=PE9d3M-Vmx zUxO_5**Z|X9Kfx4q;C%h6GZbDIqwvlfaM0B=)W>w((f^<3QM!Ih}IU87E3t)J|H|s zo&mg`A&V>`eO8O7C@3eV{RW&dmzK$Mp=H)H@|uKv)qVu+Qo|4t3+Z)PNHa^bf&77_ z6MSAzQi0P_L}c)nKZX-g4F&8Bh(Yf~ zOTY=uzzqrJ@x6nfi*{;|d;uKi@o1Rts5}P^ip=1+Gpi^=C-#8Uh;?wtDC?76T%M>% zF#I%Umni$OkLT8*dsEm>x z@JE$r90R+KX9J8gG9YrKFf~GxCrNx{_EK(708G^`ye88IYOERCP{4!0Y+VptkRg(e z4C*0TJNpO7U_R?mtH~vQeay*OBK#AyBIYCeRRD8`d|x~JQKfTdPY%xA=4Q+1azH@( z|Ay$kPmQ|#@dNFV3B4mP;#f(mF_B*=jbp;O#=|K-cC-MtttuxTIktUMAE{oOrl{SD zTF^;>8`Zjw$N)Q<5Txvhu89bSLDY*kEc0o_Hx8o^en>s93bvp5TKZpG=myg<6L$&9Q1N79v8OizDf*R zz-5vH`G3F8oWEIrXd@nEGtzmMpefym1<*5z+U|{HR<9m#5tlQIm7Jmhv@48k1_p70 zXMk{4*)i#2)53}ryh^4BdAG#Bj_k{r;Z2Ydl*BJ zGS+L$SwU%V7O)V0Q-S`9jQ_r&NNn3A=pn{En1***?>+O3`OI7o8jTAxS{aebiN7ALXz3R*Wc$$Wa=3prW&U(uzl0a#u!o@5sZ=1c3kb~ku$R< zt!4m`+H0RJOQdb1#$^V5b#)bK+~75QjhQX!DZB$ZG@vkBfHyjquO0m<;LviRGX*rE z@66|w_!RS%OTf0Emau0AY0C5BGp7y0m!g}f<9}?$+6j3B$a$p?SF4u3*NPXHl$>?s z@beQvt_Cd&7$|e-Q$f7rD^NXntd5W(nmk}JlCrW05KWvMT9W5y9xYa`8$p|gNtZ76 z+@;7nfW`8o#YHqTwe0&V)c>k?ki#d1DB>Um6Tc5QvRQLi7d|w9QAzspW!{nRu*P7AqI`sN7;hz_$+vLwm|r>xSNOo+if5SANu*S)WhrC_ZmfRXIDDOG@=3+w$e{YrdvlT{|NMd@BbjAuFg3z_hSPzrVS`q{ zM|aV%{x8>EhC1W9NkvmdL0Gy-#v!8g66Y5}o>&IK8t*xze z5u1dWYPEa?b8{v@<)3MCexco=kK)&w>krXB^86!su(O6=q$9_>EcL0jy#2yZf9+G} z$kC0_5eeE69rs>IOZz38VfTTy_Q6WO$;rKPi+W#iuaa*%RvVLbH9_+(BjcU49y0yi zmuLvd&YvfxrNz&PTeE?x^;TfJGrq-HDP5jxRAuVBr4j70V-6=%jV8J zi&VMFRjD}-2Vc9M$&vr9S=MJ=&dZaWEeP;~Ezrb73e9Uffzay*uvFa3z>?zPN;p4& z$<@DaK2yB1e6Y%5{`k47S2h-;7FN)t2<>UYrPLl?UJ=>Zfvj==Zy9Si0s|n2L;|F+ zhSm1uD04_nl-Ceq=c)g;DyrfC&hdhW%N1n)sH*sOf-+jkpwb+Tg4dw0u(!}bt03R@ z5)CwMD&}h&-iQ~e=A~1#CZbdM_j6WK+y8n<>(0O)Mxm*#jgG=0Ab8`#2DS%J{f21d z0Xao6kRs&BwZ+TO~4h(8AZuozV0wH4@6h2Xp`V&~(wXCorofuqOca8WJJ3wk2vMR#VY5aa*%1Bc+PkdBmyL2SFmnFyb> zS__Gi$QRNFfQbTCbGlrR?7Z9ie8uM!G5^~uOY-BGowybM4qf@Irw4xX|K1w#kEHE? zyrC!`!!{OLWS|pi8rpS|u37(dIeU2_A!t`GUc87X-wjH0Xss1&(V!_5St$>yzpp!Y z$J&~Si3x=|uMi9SjsEO3UX$|zMS}9pyndve2}=FM&(^6#kw#4ahn$~Ikvjzsiqr^y zOxp$AnaMi8EyyRCfi3~kZsen{$a?+hiLogN+!+wh01Q<)tm%)Q>{yT)(e94Eu{-~x z`$;4;5is%c5^Q|@MZ^Gn<+*lUWADm<^uM7z$1{~v7&qHjUY{ln+9 zX=T;RH|~HqgoK(p8oG6A~ zJO|S0lP=-P!Vvh!0{Z7_iWoxwu9)hZW$GpX87!eOmvFuQ{;oYpx-CGDgbL=r{b3p~ zzCRm5r?J?K{v@bM%T_#SRA7;nWk8VtM+WdGqFjP}I&?JW!QbZhwQ%kSb>0vimJl7@2>5Td zIw)SbvgWlV#?)pw(`Zb2R;^uLrzlwPgg5D(qx7SeroT6B>5LJbj{7oy=tTWZL{9vm z+kc!Fcu5`#a3b%0+aR7K|Nd|=VgJ(de~TNm=gSRE-t&hj-2ITHQ&0IDPA6t$W4^}sG!@m`uqPS|tzA76w% zmVaLt<>&9=_M)c8GXJC;3gHP%!st8ywLxK9CwGFO6RTJ|zwgJ@A*gJPE7cmoZ+{Hi zX9wGt5z%C$Zd4NuNuq(6o}7jcL`Yi2-*Vq*hiX@!ct#tAKI*hDgzsq^#?RsrK3>q( zOm$$wVJW;6tcEdBEIm4)MI=XQ{6}iMacYPHG}1V3)rvr{17kwsp8875$(xRJDEzNq zLwuU%z5LmDNMV@R+0Q`>nyCHtYuB!Lc)Xbr7lQAAU`u%g=R6r1q-m%3H+Ycf({*F) zj&Q~hL4wgYs`J&ne69q#4xXI6B?_iRG`<(@L2*0tp_mMm@f|vPOjU*G!;cpV2bU6! zbCsQ#b=)+IZ#Z>5Hz&=C5fpn!Ig81NjRR0aKhJC>TfCxia9KL9`zs%W6D0I#+M z^v?|BknMm+I^}F}Xl?GR#7jlAr!NvPAXc=NZAA)TF5mxiaIHt=tAO6t$ z<-i5y#kJ1@ifVz>URk}OCV7=9EKO!PbP<5B&TPbKdSj<%LrJVvWjBO70|J4S+Xa{? zhi|1qcC-jmL@(vlb(p{?$1vCa(Am*PX)vaP%`(hak_BK%aRyUX9CWwqgEd+3LP+&< z%9;S!XIp%HMb|JMLm$s&TJ6E}`p|gH+s7A>h6(Fuz-Ua6EVX4QA>p5GPXA1N{>&itaaZ3e6y1Co-9mzWZn0W*$a-IC=6_I&#T8;dmACH*) zt2yVM@hU)qxDOITc^j0u#U97Xel?y#XmR^M>KI8mZU)iIBKspv}J$a?!-ooTx)?Yf{+JmGJ?-Su|FJ2xt~iyyk{6vB9m98sFJ{7 z0X|Y^B!d?HhSmwPqZI9^dV8{#6>d?Yf(x@QYRst@O~Zf_|FkwC^sG+m+}ph?egZ1x z@}QK+l{^C<`nyuh#^n){+QmY zx{L~Tk;7VFUJbX%t|OtIZW>jD&7nwubtQ!cYR!SkF5I=cEWx5690Zf-;cc6Y-5<%w zLOMfS#IA<}3hMvnmoPL?3BJkWi17T~G)?q$A}azWf_2u^;Q2@mu_Mq3l&5=oV*{@9 zO6oFkE&sgbMyvFNRNa~Oxr{$sKJ0)L#Z39tF|}f|b>1i|micCU}WWyoa9k4jRPL za>v<|qxvhdr4FjyRgMbzJ2-jU%jZp2KP1M&iB2@sdEiW(KR2%U6WJGB_u&ee)%ox% z;(pg75&4rSl5lF}VSN~#1Bzan^n6GRHy@E{cY6>1`w>rOV(|YX*;$d_Kl`G3azoQt zBZk-_fviqcZAm4{foXJ~EydkCHmr@ev+G>-ZJcpJ5ENm=@Rm^~aHP;!flS55ucGO* zUQ8qX4($NJ+B~k!ucf&kag9_bAH6I*p~UJj$x}(s;zmlZjmht; zjnFtf&P*Ch&~Ef4dL_(6_o7!;SEIMz%{jFUg8lp;Mu+D)G9GP}8m3We%kf}e534~9 zCybF7R;luk0hB)^m@|y0z-U+BprHb=kk1s)So*>OapVeztM`OpRu6yc(^%h;#Kc#Qqr!lTzwymO=!90~gS}T20#gIjpf+CplpZP9W7ZB9-JzvBdrDL= z2cKq;9XHZT3w?}5EV1>gHtfK-`D2oE*x0luhtDG!nn2JR1-eq|F@zg}KG82v#EAhD z397;Z1n=IHv?dB-73|rWr7MVk^{GZl_1tbx_%-Z$JHKti#(nc}lrBo?3N-SquP?{f z*7`7i8A!^{2P=E0x$#oC;AW1pt!<&I9~7xjunxbF2M}|pU5~x7Qscm#VCs_`x{a{z zh^uK19pF_npu_;3oX_4nd>q$z?cZ;IgoayZ=vhw_B4_TmjntsA z(eZJsu{UJ&KTS$ zl^qSh0-ae9UdkK~c*Cwm8(H0=$VUuSv7&oCs{l4vo5x;T`uc$! zD+2aQM#*YGNbjTESsPtMhS{Ljl#D*gj~DrL-D-eFwR{AU^&^-7!EDa5YdkxTHC_X#uVrfnMTDml=iR->?GB zlarqwAd#k9o+Ma7)J64T(}E=_e~}Vrv9Rn11x&O_uPe{;g0Ens$tR#6t)gA#AdQad zh)IF_yx{H%PJaFfh36=jSn4LYa|I_S=;Shh4uN^`dbxRdTeGnOVgYaB=VxZnqLnO# zY2mgN2Vn;v5kSU<^vx`Q>VBtw4($prMV|M@WDRsV)dkGX%?W{4t=S<(Ega4&+?GHc z$jW;Iz!2ya2PXW#!4L;Jl@KPT+lCLI>ECs!m@Futf<+}?SpzHa7IRaQbbwqE4vt5) zqKbfu$EKGO^2d&sQdBL5;|uBa+{=b@61l07b5Z}P&OnL==*6-LB}ZD9mY&|-$&Som z=o|p=l$f3#h0Wm8(DyVw{m;XNa_G=%1hJZs@AiDq5gjPvXIpSRpc7+K7A`?^dq45w z_W#!QVt#L~u1cKtgrYym2(PDXN-yr!XTT3 zkt#r?rZ7QIGVk;dB)1@rRbZhQ+Iuy4?VDIa;how4?u`L4goNvC*yjjtzkE?IHGbE#^Z{6Zq<8JAl2X`b8A|A9 z3p_qRv<+}$2U0Y-!qlLKdTsa=oD^^Gb&J>;JY#~5ZSPjqz#6uCR5Ud;gTcVhBWm=hs0JwR2vnWC zyu@He@#S3n{B59{LC)@=Z*Oic3vz!0z$q?XUdnK*z$@v*cX0)*Mlt zvE~Ui;TH2B9ly34otJ$9&zRa|?cVgdZQjFfRU%>)+KzmaC1A0GN?=~gMFq%JW6+jL zL&10ehc%Q~wgGM?8p{$A>x`oo5wvQHlbkZHx*MIba>J2(IA{mT z(xEFYCzk%mWL5A@a$3J1lou<-h!%nAmf-^!cpu-Cw6P0Y(9-IM8u@d<|GhXgxS?Rf}I(p=9vrlBt4=ZxF>di<}%I+#&@RpS@c~ zt|=g7BR$RL{Y|vLcoM?&Oy@SC?j6yXu3c5jq7O8>Lz0Ch)tdS%nlH;EirIa2bpJon z-aDSlHtZk&NJ+>@B(qc+Mn%XjiH5e2J&ID(#jLyFQ=mIo_y@1EOJ)pgVx{~D zu|ez8($@A$1mS!hQuz7<>m8QD0O5L;TLGHFsdXEQ)PnMF?>N6UqFc>`<+#4!TOfFA z!!M`*tsNzGSbO`SvT`<7P2>aox7Q0WHeF*3^W#U4I>B4m@9Zp%fDRa{^ZR#ixDJtB zm#mRyUb7e9_=E-3zs?}(k9ke%?Ng1C;T`6orJU5b92$G(Ix<14pIR)zN$WZxp+i;E z`93~*+P3y==D6*fAHyWO4VctB&hE~MgfkLEzjH55HcCr#Zaoq2y`=lPwvzYFo$Y6$ zx9lagy0i7u*63P^S$6tqNh@UaC^ymmy4z4E>SVD7};HelT%&VJOsd&=2mQ*lwf`gxokRMyh9_5^kZn|0en8q;QK;AX0GL(x z+r4*5NU#$UA%Pk96;0mH%v?L(S6lJqR6?}yK60tN(A79*o?zx3V)bslePqsFdZqRW z6OvfE?Cdo}k>;KKl~g@}A&j0S>L&eA$NgYOl#bk~A8c6a^8k94C(oakVeh~;atnNL z4A2m&UcU)x>$#0Pw`!~YCH2286OrBZ6^){Z-88=;$hDz|&mbFkn zMYy|(vb;0qz$K2)?^tWw8mX|&BN)S>pJ`sPWybUtE< zt1H(q>_6%6N4t27SzzndZbXwMRm2+qx*Qu*B0>7mnlmnJ5gifXgOtb^%TZZb>A8W{ zX9|8|yDrvkAdwM%OdHCKGMwVQ5lWx?ptf6_3Ng~(60v|eZgs^o<9Re2H1GF@!L23V4&jQ}LSzP?(DoQ05nZAaR9RD!uL-ChZu3I70dSEuKe?mXj)*p1m~c{`U= zP4_FY4{N>V8h4lW(mDI+(E$)fULuhP!&(GM!dP#N1?Q_;XjpK7iSj!Ccp#njG9#lH z@|%wS{!72&!C@TE9S|WDHv;_-g+*rOo(ae!LqnDtI3f+DRD36X+~_}WbF6*x{9sO$ zFL{t2hnq$lJeg(XHZ#=Nw}#*Gdm_~+b07+o)vfW4C5iJ86{tYcSs>{OF8xncngLP3 z9f5obh5Ow|2(j}Ub$Hw2F;(nPKl4E27CoApt}kZkXoSD`pUq3V|M2|;_jx>SPP}b6 zWXplQtF}yyd<)s{MI-*BmyL}L>QTx3<42E{0@Q|bY*L06Tggu=4B2=_|J{Y@Isc1D z4!obe;6&fSbK}TR$xLZ~-A`|iLTCWRj}&Z4z`0TkK}%p_;%4GCM6m>+mk@A?ZpnS& zk7+`o-Fg{&A>!MFQ!(Mm6Iy%?#KH$)X9GF3o9uX%n29@Sw3;18Ks3s8?oO@IYqsWR z9oec^hRj^A&6SgD;Yfw{l*)aT`vH$i@n`@9(VA98QBjus&R_`I@Q3&Q;{Mde&$=yE z|7iU@-NQI7EG)Pc+?S+mTo(Doq`lxrp{&WE?RH+#(LP)_U38#dv#^{0xG8)0wG#_v z2?bue9F(?ZOE+sutD;ku)PDO^-0`OSX*0L?Q;5w zkOVT-L-u1L;T_+o4`htrc)-#0f$uuy%CsPlgYeg&k%c3^!50#hluQ~EeJQA-copU+ zSn+leu^y66Dhd#X2Pa4OX<-?j#UzDsk0`WKe^cP`I^KR9wcP0YkfgDWpVVk#Ug;mj z^H~jT*l1@dQM?4U5G^Pij);1|gW zYtgr8W(UECas}}{gohwRqOddA1ZPwfT;(H0i{=;kfUg-|C2l|;Q_yQxUEjbcqtAU4 z4Vk)CZ(6)AaTH#Wl-Q!{wIMz5j^B^tkkXMjh?`lRRx~>-Lwv?aUJtdo7n8yqGbpL^ z!WKXK`g~z|NkbA&&?QJ&=U49Gp+;;h5sSp+Y4Clo?Az(IT_@7wr;E0`vEXE$`?Mo} zwDhp*+^?NTV>G2@@r>SWCQcEflamtp?JrH4z)s~Y9RQXIgt$9GQWui)T$ zHj;5AMNQnrkTg9ig$!o5>Y5TbsIEjQO-Fc};CnZt&W2RmXNox3rl+UVcn~!pBA*pr zXDF6CGb(sX(WdzbKQF992b8wrwP6j0cn=&Qo+E6WPIwh^?77IS9L()MF)^X77a1EH zhz3Ea2Ar@MMhGan)L($q3OmUN<(MOaxYhJ%=Mur4|CzST36;5B1qymRjqrcjZNH_@ zut8;|<>nJ*C`KOAfLHttB`SPt!J1u8_K5uAoK17{oE!6?hQ8Z{z4Bf5e_(Yw-0UhnNokQ zd9ArwlUSxgZ37^x0(&#VsQl(XS9woKs3f!4aQe3bHMGtQ$X5#sgo*=yZ@s1QDLw8Z z8qz!Zt5?Uz$2VtL@PUHg`QyjMI}B8Bu$d{aT`V2I(<-j5t-V+u71Q&tcCqHkJo2@R zSLS{{d-jajjp#Y`uq8}pXYb_(c{rj8urVu$#KcZj&tu+>flH!lv>g>T+&iu$EC6QC zzM%L-Jvk`&CkiPFg(w={O24j34Jy^@dhjplfpb$?HT$MC~RulC;hdJSf)BaqJj5xA3PUTX9TuvA^wzbSIa;A z1t-cIPCca?86CUk= zeHj=UUvsxog#Nq9#r%-GR@f0$)l6I3hLXQ_5~qwasYewhI~GNb-a40BJpS!oNwmW8 zjt3`sxGf4+FAH6@blos-(9<*jq;8?ud@}1ZUc`$HCZWm>!sc^c;HyK?gy|94fo=H{vI7`~;DgA{u`rSnxtNbS{cXG9{K za@0@%UsXPVufYkbpx=~hpybV`H@&c#G}gYX-fHE+q#(q>%DB!Y2IurEr#Yv;Ab0BC zpZe3LG>~ssz``Qt*QTErU^M>Z$+ocVEkLpfJE(X{3Q8b6w$*9IMnRY)Sew{D1WZPS^bH4KRATul#uH7PGgnFEKO6-3yZlcPvI?{jk*k8|VFGN={yxt&vA| zO~u!cF8n(8z5W2OqVgxVy;WIZ(C((&dBv1x(fNc@Ln~(-bGzA4>ow|?#Kd(D{b4)3 zraLk3DQ^f-1jeuVe|lq}hfoHkjihieRi*5MbLGdo-snC$qC*f0#g2@O46d>pA+Q|P z1%unn)JO>NaX~XdnlM~I&4>bimfy}rzl$3eDC_=7TwZ&k>g|S z(}x%aI}FK*9<3W@zC#Shj%w^)7Wg9NrP#Uj?ty7J+_e*GrT{k^PdLNGHwqrj3hg#? z(_`#8vl%7IOn{BYwM?g(c%O-fWszB z50F?!VM`dI==jl?ypDK8k#BhvsYmS2EoOVc@HAOPWaLkz4wdm&akTIPJ>6wfYL&Py zqC2#fvGY$S&n{z4mqTU0M^cX~HLSV&e90@bs0bR>^70ihk%YVcp_ePMJ0bFdAIa!I z)iuZaNeY?LR3Fyt?8?~5NT|l29)JuUepqqa8vhOKi)}*e0mnWsw7rMDV*o7GX@1MO zPVaIDtCi+k47r$`yHn5;80N-nLkx#IU=wvfPcOc+0DYENX*;@muD@21H$#Qb zjd&?viVwuMRWk4f(!JTaxZV$7+0FOjQMtq0dM%{9js$%smn|OsjQSK>8oh)-6 z2-R+&!s^Z|D_b%Rp>U_Q>S32o8GVRWP@4jaBJ- zelsVeR$qVP(-HtN0U3yU=K?G#G&B^h7FPx<2w(6VL7+$Ro;fb$u@cy9=Yr*$*_}O| zLo0KOPqqIj(!xRrhKYM;9c5l_Q%0)C1|xvpV?%ce9e1a00)R|{@2q^QZ++8EVIEGF zk5@0*E*Z)+u!G4W>!7jnO6+GQ_nOy-gtt{>pY`YpaMSq1)QgY#>jh}$4LZY>7;)N7 zB?S*Y(mBpHjZaTSZ`!u)EP3P)J(gftzbBz+PNmO`ZOgawSbinZXz)l)X(iKS=bLcX zqrS>YwnzVx9;+}Z!_cV6;EIzyrNu>xKT9d7qHu5E6zgr6Ih-Rox3swQMg~SkA5{S{ z6(QV>lCa)7{T1%+<`iCkM(+(2zTx~p4>xyOfXhoq3Em`(o**vR`yZXYYYRhh38xXf ztspX9Y1xMA#ZQabg=>36;7BmjVk2v?_4eSz9lL*exlPZj20uEmiC@&{HnTfkZQ}od zy>}P_dsE_8M}}0qT#jC+Qp4>a|B2Exv6cLyZ`Q-HRCQ5emBp3+*oRb4Hf?MLU-9vY zdwL@){vCKBe(5B+`jms|dDQMv?R+Pg%vVx09d@mrN}FSiv^groy`JS1&#F#rSrBo2 zop%z!9-M$aEkT}x{Hqt4qC6*jI=ZDa+p z=t10y5hYHT57j@Qdv3ANwk|DjkO689Z=0swM&X)lPApzs)R<77m7#tS9WM zi?2L(I({~LHT@$Ygy`4_)xMhZyz&1AoGyUq52xT8u${sT4AhpSj7=a2D&_!){(1KN z`IVn46_JETxs*(wQpi!`Xua{aWZQ z=>`#gDp0+E#o408QWRzzX_wJ3@dmD96}XR44b?mV3Wyd9_WH!MZ;2dwf&QFX_^@&KYqhmDIKgdc&Ri#QB~i(rnsUa>98>%=7+C~fpq83=60dk;W*|SMqbtF z#+74(>66p7xiTU7 znK>pV=9CMlb#TOg&}arrB&Ph|pS81eG@hy_KTuyR(A0T!nu>yKb`R&V1AI>pH@-C# z9y|G=^dHZ(y3-Y>?irX~ag(5-_mB!nNwOa8hYsID(B_k zBHqXb-yLFznGR`Qb8|B(o3951(31*`*q1@W59s~sF9R;Yr3!%^6|(XWeu5kKr8+rS zRr)~TCX1$#&uf&J#?{f{Fr(mtqq6*T2Q`@~fMnqLRCX{y8sXq2Foc;K=~-DtK}lxL z;4(%qUent94_(z1F@=iT|id(`06YmD18nO|zUtcLkk3`o(0a8G{0%t?iIRw}m7(CO&0O|h*EXsqE+swz` zMf)fx5SKWh1H_1hhw;_Ee@X8t7r0@$(iP5E+wrDRk@BX4aaeP1-}3y}@9e?PuU-`H z_7kcAZ~e%l>o}x{%G=5B9Yd$gNWK?3Y~2K%B_3_0{ZpTGqJn6=9Y;G%m}ZVUIXdp+ z4~?p#foTr$&AWo~odEnWO!Czh@S<#B4yAO{+Uk=9PK!G`0$zH>!ZJWm`o7eM0aLrdV4T2l&AeoCGPYfgimsi8b~et^Ggw^14Y8TPd++bjKqnu zA^eD;si`l>kP;3$CM2K`uy6Wja+>ABoD*@h>hJF-G*ik35PeU`j(I;=L}Q)|Br*W9 zP3*fsqb5EA=q(?(cY}VN5fs7M&cAmM4<3|K-MBO#7ZOwov7_f)UabcnP@=;-K1v7`89WVrBA&9AR= z;r*rh;hGHeA6wKgaxdwYjfU2G7RGBSJj3h9zZ{=d+nm=eiGZD-*=L(ZtN-p?(8RDxrYl(RX~iCIb(IibHiWU!c{^&{(9Egtp3Z0}QigQ!b$6qd8}-@OxvO$vU} z8W0TX)FI$UXeou~eBC6xS|m<*lO?sS078{M`Lul+v^;imIp5?z7aRuzO0$c6`SkL# z1ZCsCFS@d#TaTm|&QEu3ospEqY~jEQ3_lC-p=NVu4J}np2z`wYwDbKmTJJA3n13rE zQpNr)8u1%g0)%)3Sk8GOLjZqTn;$M1$n%W=gR>*&&eo%Hv>U$^3vSq}YSYo72ewst zY4kI`PMXq6{AMNse@AmXu?t|ZEsiimk?(w~Cuu}=WtxqbqC+i7q z5+CdZ(r`Q{^Ub!Mt4mpT7vJ(bcu3ZP$LhmW$B=%_{&VUV`kDQotp6v2E(H;Ew6~dd zPX02pkL`rFvS3HR{C1A)^IO}$x>FtOQDyMg5?d-BmAo0-k8943$ZL+PSpXbAss5<^ zy{^VC%XcFA_ihDtSqA}ZdMH5TocM>q$NpCdsgF)M9d}LdUZWOHu7mpTb*ODc z%nWUF9Yg7%DfM8Tw4;aw7J6gds9l&UGcQ~I`0I_ z7kQ3UFdbfhXs1xc!>j8?zj+66w6!s@8eb=U*HFKgK1!dL<^rPUodIj<{N1^NdfXpb z0O}gH74N~uFs#qG+-y6@2~Qjj)_&jSRC(Ipmg%I|l%yAypo+rMQmDnAiYK3&SRPCIURj{;J%xWIc{)iU!1n z8wo%LT4F$7vU2zc{k_sGN4mM=9}+MmDfV0Y_&Zze1`pR9fZ$_*Dajb2Z!aXoMFlJQ z=VDogllH-kGoQ^mRc^Bx4U_?7M%w>JdaPH#37rQa6;kelqq*04V%q{-xj5Gl$D$3u z@*(4-cmkP#H_b|d>*GLwa7?#da!d)rp` z4J8)QEuSnYYm-1kClZ_J|-c$r~r zh~c+Ku7i1ZEV65gm6t&o5lh%SN5E`=Cdy zf5`cyZW&wS;U#Tt^AT=8^S0jCH{JW+nS2;S*!tN&^?V?Q-+*tBG9C?<^->Wh4D1&MeLmmH@Lx6y2ymus zQiZgNWUWC5i5*d7Oy-C4qRH#IUp?O~V0P|5ox{oCC3qiQLb;@Z8=^A6kVT?N1apxE z2n6wU|2GSruhRYhBYw)N6eFo9!s1gXm*nxPZ`-!*4H*)K5)zvj4k%Y?85wCPaE1eP z+g7K5P)4{C*ytJ7Jx8Yh{OJU9a}T!^6$OJOD~KZzI-5L*69+UkIV8+mD~TNt{&`Xk z)zL-@deqd&5uc0~kU^T6s{zlUUzpb;2Tf)O@Zp$EvLwD^xXPv9s~(6yYs<+@Js219 z@Z-gkdU}lEM=pqq*ZkkJfBtHys};<~$#ANJQ20_Pz+!~CiT5xHcyS0_!MLNL_<3{H zA24GFnFv}}Xj*f7{@kd3I=L+nm`<`3o!9>|n2P%VxMqoo%c0bQJ1=GLfr~8g)}x}L zieOAQPIsfkj7I2{>i^g!5crd_)=JdU$$a_kv7~VP}s@AF%uV$Gf^DkzSHVFUjcdZ{(xWa#GAjlZ6bIC43z4 zAtfx@17SwG7|}$cG!&A>UtXGa0;|VaWCVY3WjBK1z*w^rur@6{eJQC?L2bQXY}FXy zzhf<3@)6php&=B+&rRN({x6p8OV;f{7pjeayuENa#re!#GzdVX??Ucresb~7owdY7 zjkrHyca5QrGXh*A)t2-iRgfcG2Qjbpe={ zt1WJcEZHw|L#c|#P5XMwJ^#<6FGICN{*G?@XH-Fn_b3f0t%N3FHa@?YzfgR^r)pjoMj=(U@xR-<=+QS%*n1$%6$B z{3{Qp+5Dec+_tSmiz^X6c6jIY+8YDe&f+WJvc+jayMoqE-;%3ZvA}J>Jz-(tcV?5r z{(^ZfkCB<#rh0do;)eR7{-TiI`KKz_e*bR#X^YXA-bF=4ojNhv71k~p1GdXDuTxSW z;7#q-NTCEB_cco?Owmd{5U#!t-s+I*-g%OI>TC)%<%u2tlVne$QXUIA<85oG^n$IY zbDB$P%NZBMi)dO$TiSgT6s!M}POhFsxu?bWUsjq-Jm~snVovA>qVA@n1(8D|epVl%^DP{nHM$f#o_oPjx%{b5@Am9LUdt z$Mr%gM8z*vFt*CuNs7orfu}?XN!)%l=b9K1^slrSeKTFFQ41kSGI<-sqo9^GYu1p_ zq0_zPWo2N^f4s?Ki{5btT|PR0b`XsTR_B}SGha$!*&_nhvZvNpYMZ{oM<>( z_G2Lx{4TXIGh9vmz`4|GFLb=b?mk{@=^ZihofKd7a6w}wRK(sfUe#CAo-S2syoJ*ts^cI4Qxhnm+iuZ!x`2se84 zgg<f4jqxg?@;C3rb3;vZ1uPB+1W$7@h*i7=sA-AdPd145T!8d<-bZ{i=6&S=sZ+g;Lmm)Sx(!pLiE%tz~bTJ;$?YtdN|k` zy10*98>*iaF7zF2gT55j`sB|JD{(UvzBFnPH9CRyuH{8 zuIqFfS=6_NC?eZP(MdjzY~i_oLD1TQ>l5#Eh3#IkN2W%0LC#xqzMr)mp3)F6S^Y5E z2r15@4J%2-G*Y-syd&giE2`(3B!E~e!<+6y{oNbo;LPTX_rpDG2` z$kV}wx#Oe!eu`(wiyhpDh08+kD3V|93bBde3IA~v0Pl7=1yXQBs01f0My@Rw4v%IB z#hoP_x~ogJWy`Xqnhk)wqY|f3h&fb5YFX%7w{!ht3|k=18Ep$?aCO*BO{s%t67^RX zgMIj*Rd!xpu?oNNA(b49_WP6?mPu7U;%F#l^^$g6R=3p;(vq$>J+6aAI-Xb^(y6); zyM}<8r!#1=xF3uDYK+g{r$4_Yd}9nhel^L!ajIk8cW91tzN>$}H3Qs}0sBO^he2X|1y=mQQU^ z{lT>ydg(vhpqj^qDC}I)Kp)r0`tp}|4 z;xZg|5^{9$bkbfHmi1OI!aIjk+ldI1vLP>f8Kk&|xO1|cO=rzY$JjAZZ05C1Y29(X z?Btj06y>;uxaE*;wK0S5fI*bzZ@RJ5_t&n>l$8Vp{Gu0ms}44T8JowntTbE1RKzNAcG3E{c7af`wV z{rS7gR&uSPu^-)aC(;?3Xd+-`X(Ot2mNphN*U%Dy(BJ6&eS2b@R{P;kv(v_PdAG-5 zYWQ~YWmCrdpdDpj_Pu2ecAvNULhuG%_HHP=Lmw^m!(PJ1qZ5r7w0`LE6u$_aJ!Tyh z5cWUB(20M=(6<=lEni2TlXeBPB|)s+SnkGY3Mpn$Ol|2c-#*WiAyNuC(95ByE?74X zFNPb{6=E59!vJUhqlc!+a=5WUQ`(uJW8D!;IO-@Ge}ocAAi|EG-;0B74vuP#pDV^j zR7LMjcuy=}=G`8!;p~1b=EP?Dn+7UsN)tWrUtObnqCw@NaZ?dkU`@MxS-5e<$>M_hPMA)#CUD0ZHmOuH_%|oW3YZ2=mYF;;DhxToy16+dzL+-nu1Eam-CZEZR{g;2!=sb4^u|A8I6 zCXEMjd-mJ`vvZsiYIB`f*< zr(I>fJ{#o&e}25BczJvBsD74Y8*NP3^n7kZAc{1K?9Abr8WBQdG2bGjY_vC!cI=I(O+uQi% zE5m`#EAH*?-uE05U&wtaxi>5J$HqgT-lO$!0yE#tD~1GIx3u^Zue_L#OV_P-6xR(x z^aa>|<9gTSwH*iIyG>a50>*sELQlL-R2i?3b)Yi!(9ad0QuQ{l8pYUbOZL>azr*I6 zJoPwZr*Mdy;2KAdgUhb93(V}tQ?x`LVU?nWAFE9`#Bv+77 zFTmu^b*4WlJEt)=X8N1+fG{xk(TRyfTnXxvhwlqvI{MaNmzv|8O+XMzFpZX^^z>21 z*kC_DwTI^S*JU|aRBm;!H=I91?KtrHX!hjo+~v+OmG84&Se9<&jmnA-u6?_^YhK(n z-H0zQ_`5;VV_$xL>rk1V-s6DWAH$P-9Y1@LHXOTU&c3?Y>#OqV z(`Lr=*M!{Lt?&rA4ZnSqRUbNL+SqP8ZMd>np4ayBTGgz##kLk}mAX&rU%d=Y!MgAr z^d%@G#}h5)Kvjt44SZQ0wc9IiI5z+cCoWIOpfXUK5HTxZZ#?kWw~vC#KDddHPw(En z+iF$8(=)T4fd*Tq#$pt=S<~7UXzRb~;ZarQMc&ri^Ov0Fa>c^Gb)CUhpy_uipG)6z zm+$pvYUZxXkF^sv{h-w^g+05w)&lGQO@&y48MQh$Gx=~UH`#(#@DB~eFyVpikre3 z)04dKa-IcCshty|nO)zy&+z3Jk`M=RiW{MLKEAr<3nQPrDkcZ~0e8CpV}fsj8{`Gx z;Utx8xwrMm@#6y0($T2xtuPr#x~1v)xl+tIyZH6BFnhoa@Ug?;TAgvJULacHs#d=y z7~dwCQ^VHM2ZCf)*3`Lp1h2hk{8z8BF?4u+O^%&r8<7iJLpq{IFM-Sj_X~NIy;Hwf`kvi6^3Y>p;y=u}+&OC8J%o|NT(A=dK z4rE6+nr#sg35G7;K=jfIc`2Ls8?AhP-cdRD`LqOYmC02_fy-+|n{VB@@hWpJL{&23 z+T#cEnNPX)B_C3VzA^i0PgUfGd(S+~EB|Q3{W@eO(i0k+{4?qR76tbE)+;)dRi*O>3}+GY9ijz7)7P zgu7Llh?%_1QOtXH{+Yx(D;>MQ!)EN*4+rcjH-)_`yHG8g^ZeYG+CT)(0jBf6Dhe4S z_^OPsH$GVhd~wFdO9Z?H-;qko+10< zIQ9iMf*q@X>b9vC^Q^Gg*ecK`-+=KN%NG|0CPCfPGh5Ly&+d)B%sm9VGt7*dOB~S! zp9nG&GVn~gr>}X)9__+IsB>ziOjuZ+7UIwVDMvBn?Z$myrWV&8-5A4U^78jd37Ol% zWqj{8Zcp&cY~}wnxpr(ee!|*#`K)8zhUOTbV)+K9$;Sv}c$-e`tc&rZoRDozZe0yS z>F@bZUTkPhH$0Hjq?`~684Q^7;b&6!Y3brLyasExPtb=zH&z2gw*tgpGK+}<5?~i7 zT7=uw(>?_y*{4^RHL$tQ7*=gR^Oy+AuxoFY8+BrP7=t50Xu<2g$6{!O^DYhsB^pP7 zLFI2gd!)(6X{eP9H|W?u`p)dJ*;luMS4HSxVjo*ryhhaw^||oi{_aj?&&X9CJI~~# zRq!pu4=;D*^Dr-|t@r-Y=J(}%S!uOj$QPayVdiFtCG{E?_D_GcDAKLmTN4mto(ma; zZM@s$x!Yl37!a@;v&O8Sb4KGq;6C0LY?YCT!Pu3Xc-LNi+Wqpyi)=LJ0BmgBu)z~l zhZi7m<=XaJx7UL3_Dq5Ar3}wQ>V9S(&D6Hj7klNW>9Mr$Jm*p9o5$jDf^|V}xM6H^Lvw`}vx3;hLK8(dIodIC)-F?l zl5b(ocKMlR&-^M64hN2Ge0~X>sSi-S2+B!d7tmcr=!NB+hEzM^#$73!$1h7*SwaK6 zi<0~$?5HoEk-T5B8)v9VA=}Yw;e#HsLN^v2^$f~SpFBP6Xntx{`4)+rM~?8&x37(C zelK#aT6o#74{%1@$mq7O1i0pk3AH=!Vrz;6SFHzW_}OEu>(=9 zEXTRX{Jq=icyd@o%i#BQk=%m3N7L78y{i(GSLbGzxmng-8}^d!ok;o%BL_}F`y{Ei ztA2~s7wS>sIG2Ci@|baGU`5yPV;8Q2N@mG8dN8&1c2>J{0C>t$udk9Bso31z3$r5? zP*h)Eu^q?C);^Ox9S(zqia%p>J*@nLbXBaIZFdD!AO3Ph{!Vr3CMoXf?OlC5Pv`PC zv3WA9<;w!JSKb84( zAnoW;eE2ndIHuTM$H=l|#o4P_ZOTY5&N3tYXb{!oHMccmR!XAT-|FVH>G>lG_2I+a zdB=Ruy%?hPeM#?R@khR0yD$WY2*Xu;>g1_C^iwt@{j!dDCPZ71pHF6$fU_^$R0tq} zocJyVSdlI*0m)5n(Y_y(oH%ZLJ{|FvuP3kC_s@k2mdT{P@tHIi$N46?Jxo)^7iSNp z<|OjkQQIB$_d9g#^o9KxOyWp99&og(z%;}2g$u31%#TeN4AM`}P9`pA$0xlD68x%U zc_D`O*Ucl-P8BSLU++}C(0xh*iu++ku`YX-uRE@vlH>f8a_W}Ib~cu$RJd5^FRVDl z&C1{z`5xA6l#5?pY(Xi|iz$ft22@y$L%+L>?M)qha~VcXMh?0P24p3rTh4Dp#@v^5 zb^BbV@C|krcao$g%QTdKD6MYX7~pq^ZHF-J(IZEqr0sS%v^yo;RKT-(dfGF~pG!u? z#<=fd*BR@mm(B|GO?*bCM;OBj+e_#bhQIe7O~@%wIiP!d2mk5SXLB=d<>ko`XMZG? za(zr_wnKiz29-<{95l|TsoB;TFI``~Y)Qzarpyb~iSDvaXOBMg%C8hj|26!}ZNj}@ za^ZK638P7Gp0p|p%OBqz4$(v3iWGpf$|dhd%6%6eb{N%}2w^issxi=mengzaWEhTJ z1{8hQu@w?ALsz=lk;|Ixc=NTaEmG2`-`H)sW3mR}Th+h1=6ccXAG5zi`DLxP3#~Q-zM4>Xj=(z`Ed6WcvVAe$aG4 zjwYSNbLgs*p^axAt9GKz-}~w4PP^fA1ZMh>vwro21>5mO_0H!#?+$+JkI!CgAk&MfFyl)3hB1xTgZCc}13e^MU>H}h1!E#8 zI%)bdlS3acXtERxO^h{B+rJH!(g!;;=CXX3+!xj-ICsvkt&KSFC4c6Fxx8*zCAC|$ z<>jUs$LP%IK)=cxsEQn4N7^jF+gEC+5XPSJ$+f86L!&DUc3C>rpA@;grX)oBjH8p4 z?Chssj>EG-7EKWw*=c+IVArI#?o577@y(Ex_{quZm!6J_k^nIdB{BQl&4+Y zpX0XGaPilQuWmZ`>(EX;_zs3r#iOn|-xV3Ne(z-|g{#NjnrD%x8yZk@n7-t~hX^to zFnZ4=MYx}?m$LE3l{1jjn{xJwd{oa*W`vCbgblztpWy7BUr?|fbICxN+yEm7 zh?QzHPR&1ku3r=nEd{qH(DU0EXar+q6htS;Wan5Ll5U?)aEfltPSV&EabmDEyYSfP zq@}U(Y4*}@b8%bQ%{K}bH8*a&>DQq3x5Vm!a>58RSp&HwgMr{gVMHq#lumNwxX&Gb z{`>(tF5lanN`208wKPQTUVh4kADzN#7PD49Cjub3Q^?pLJg5LD&Bnw)V`qSkmXqwQ5F2y{l`| z5dGuv6$h3sPrToul#_;E{ZajdkpvsciaRLHGOW6lp;SPo57Q?TCu7YZ`wOTNcf5BqB-kxvNRyx3F-R7XFpond)_3irItziwi7mi zkAq){!LDqwy*QIg7&;+`1Bl##bFL2rJ7O0NPIf$bE-BhsFAR#8pmOWR*q_+ z7NoaBCr>h?v0ip@ZZ-jVh$6C=SPu!Z4FnI;IF9xD9gT9)&_EewxhKhQj9$We+~sn! z%bupjPJh1!O*Xm`kKtJxTy8oJ5)ix(pEzNP+apQl9j}@g$=VF*ONS28O14^3qiM4p z2xm=@9_~wIN2K`b&Wf?faS!U4?n|P-R1|5v^mU6@3QnGScFZ4=+&>UAK^?TqWa@9cUgrs z(>(!uj)R?w$VwwpG-pk-nzIZ!;qjS55N41q@`Ql&D;=DoR}f9oNMyk;P>Dg9`woNW zE6K^%UPBD1cRbUmh>>#8c|URaYgc#YTl7EHPyD2l*R`P>W54Ma8&4PTo&s9)4Np%> zl7}W#aZn5}kso;f@OE&#{4zLED`oyRa6NH8Xmy)vqf|wU2Y{$O4so5B+swp{Z|m6E zl?@CG9#xoBN0(#hRTPdMl7Sn6T1);gh`}=RgcO=+hJdG?+tByx@kZ4-YcX_w#s`^X zF8#DfJP@+Xs6;iD@sv`cR&wSB@|;%D)7!N8CO&?A8x9xMCW1}w@*14NA|fUT1hQy| z^|Tlp8^fKv@$k2=5P{Os(_de zuPR6uv{^iKe&!+1;OjTHB-O{t&ZcBPI-04@kK{q|#`U_p-*z>nXcKc0ZRh?i3M@t$T!yY>))aNP=N^!rfzk?Fzu0kkvq=7JD`YD z-MW3-TG@EnS~j**YHHsduV!dc(zQ}FQyPu=9(7x(MLH(-o?`SD+ZOU&r|naYi0;FA zM}r!($=*A^Ms8?N8;%=3)~}DQq@2+3-74-^$oFqik5`D5KI;r2Hk~?ks^@k1-r-=G z;rnQi5TFSP#=P%oHe1~vx0$Dj2BW`MpYLQ-F#yMkuse6k5Xc9&(bn3kdV=>UcH#XU zx*_7S`}ON=W=*%Ee?WkZ9qsAT?Y?E}@2FU(@?Kf};r8k|%QuxHF7^I#If0isTYhkw zsf69I7MPenRCCtu{R8k5=&q7$+BqN_j_jF)E#zNnotl6PiFG^xGO2{!aT_;pUM?w_ zMJMI}Ar_m-^zp~=8mNLn;FvTL$-oNYzKf#NGXJ%v5aKE;7gs=0(c+~FYx#32>ZnIa z0wWMMoOMeqiJSB|{KdF2YA9jG#zTGgqE>cz(BUst-v*R#y3p3HzI-sd$b`P<``>G< zdeE)0W8n-55B_1*+a?E^Lh#zf0yii*WSMCqvweVLOF=D9MJ(~;ISJN zP~q(572=^q*=7CxkhH_FDkfh!!61YTnu4s2>b=P@+DT>P+`p5up#{}3I@-q|p+hsV z2MKQ%epm>4QeK7cG(g?@YOKn^mH$}d)8oE-IeyU{Ei`_UKE zY`rZ8k@{En=kxJJxxx?J`z*?BSVDge=d*jG4NAs(kQpFs!Eqx8FHp>L`vnlVoj_PW zj3Wq3DWsL@hfqa9$41BeL2^=Mndl?Q#rziSn&;suJ zxKkoy)0YyjaS7(EdD>dtHX4uGpH}B0kp`Z&x>P4-`{MFQJ?;~}VLIvzNX-4z9-qCV z@J+rh%*rjM!(`9s(A!d--z{{Xx0vKg?_mk0{~1eP5+=OE2AR<>l>2c5D)>u&d*gib zLXorlnJXM_NbWv(TA50+FfY2ve( z*N>i`xY?TIBlIO`*b*zeyQ+IGf3EttfaLHOG>k88`i`sY=iuSd?djli9i=KPEX3^T zK%|=CGA6q?)JV;E=vBwarLM*p8Owv?C*x;K1TRmS?z;HdS}!}52MykMX9_ZiXNvo? zArS-6tcY`s0;NG8zJiom=dq#5u|e3PN#c%*iq~xt*l^)eCm3j`oAgeH9AEu&*YL}r zD@WcN4SF=$9F4pf&-;mUCzGUx?>7D}TejhiWH35ZK%H309(>|=5ZyYFb0s0dZr-wG z48Of+t4@@Ai2|3I2TLQ3b8Qycf_8HlEVOL)Da^Rd^NwA^SAcvLT?wXP{<^m~=ezNM z4{;Ku9`%4+SayD*9?52$^_z8ij@J;!>SsnVZ`lj8Tss*KAdzR0DpEC9Ua-4B-`n08 zzDq&O<+RQEh29a@7tV`^*EJv`ytHGjH^Lc#3_PKgMgra6mN#{YiLA=crnK6Ba;8cs zwRkFy963V9DOeQzW+(3f6d`XhGjA2~nBnhom5cEn?JkY1PjcFZ_DKAKJ=c_5Zt(Lt zqotcz%SNZ@RqXk3+TrELi_g=gf4n12E;0$Y`HF;j!EbeZ#^~ti8`w|1{Gy6x$saV) zIpm!8Kv(`9OXW~=m+ZyZmBoc7@|Xo}jv8(nnGJ5$!&$zwIs)aAEc6%twNSe}9*=8a?}qn<{RgCW!6 zTRir>%vIF0EG!zA&PaNW@a6_46}7!@8erNz-lzM#CFX6iB!=?7sV7NfYzEzmPMpv+ z7d??;h+%3P%>858fnA|i?YV4k`ZkCs`}two6Yej=71oI2{;c&1AIQyX`Q%BYW%a$1#k33y$A8*b$K|kGp~nwVEtNlEcP)BSr95``__?!Qr>{2eijJ zpVTyrNn{MA-`JRz(lPLRr7lmjU*-0v8;D-R>bkpd>7TJqJ=>sF{At;DR^78OD(T~T zC%D7P?jk?`+0&$YmJBLNT#?m~cJlPa3)esEF^8J|PxKm$jlIj~g}U7y{F}j!&Gw zzMKr2Ib9F5M)~)}%954Nb=w+z(KO!Fu3uV}t$XKAiw>$Ho$uHuD0$d$^gaExdaBKV z4~o7XC(<5PN_>5ZhwY66liu6kaX$@TmL?Ys_C`!K-MSMxf}Q-GU;V*`RU%l3V>^LH7X?N;c|g(t2sRVv$pZ-qvc%oBMp ziJv(VGJ1uM&%kqr@Ohz)#qcZAw>djGkJoQK(h~F^fL+w1kI%kSPbak&q{-bJ3~an; zN%YOCk&BJsXn!CQ@K*PDAB|n5@Q%*K!q%#Jo2JXf>sfL-cBt8-pd#@NcM0#+M38p+ z!~~Mg{e#Q-Z;dCGbUL_qg3BSVRcrA8?hFN`Cjn#3+oZwCEJfq{3+b1;FDxtoe~om3 zH=Lf|889b8wH~^sOVSSy)RYOv7+Z^t*1ukBWGd2^756li@tBeb|L|4`SwQivuH)4W z$r>TRR{7uvKsj>ss1wX~iGG(@S9Dy94_Yr~V%enYV1@-@NiW@w2!EJvGQbMuXV+sLQaad+k#y7 zmUdn?_p_`lR?q0fyzw187#nfEHQNf#$pFt(L~_2bfhPg%F=UY@c3|lp4n8+c%+8L& zG;2(1(oU6=kcfbbaolGPiI||+SmI#t{#9RZ@2C6wsWBwI0<$@HRBa#!c`WHtPcJ<9 zkey(9fYO^P_2yQS`itG$KRmMXKQyG#e=qLw@woT!2l@lky$^uD(!UNtx*Wi=Nx2Rd zPxL(9=MEn|ngDbUG1qzsKGTVbiLswKNZIM+r);-~TjjT}Ag3k+DP73IF7`4Gpr^)C+DG#GEBp z_v-6gT+r9zZ7L|Zxzbs(YoUF2c3xwwIJcQsbhOH8H?<1xXF}{=^9+%hK=4d}laaa8 z$LR-M_reweD|Dgp*;#ZZ+CIwL{Zx~mpEzSb-0Jjc3f6b`@StK~WE_EbuJNVTmobz~O)g?9m-s9n4#X~Emx-k#*7j7MpmQMvQl&dK%X?&+y7ml%CzqaAj- zBwvR+%CF%fYREv2-Pb`%uP7W3uVFU-Ru~80m(`f^ZJymp0|qk|&zM{yq_!Bts#Eu- zRv9%vUOF}tYJg>eRh;n`(IO(XCsA~66{ev=Cn!?Sc{_^w)EBkzqQM~K>)o%)jo^(L zjb2WL2d&0StrVp4yA9q@R0YD4OG7yiNo}sVFT2L{iLjHc+-O_x`S?HPEB$k}R5kY& zcWX%WMI0S4+{K~8qnDzg{p*lUl5}s~m>}EYQ^oz$IJj-v?3$z=v!ZEwkoeh|=Z`4^ zN-6~fp%^=<#v`+@vb59--B9=lRfsp~bYBb!2r!22)!9Oeg}FbiPJMAzSl#5*+@E*u z8E1X{l5MpKC4b6`kS|x>UXjqaD0x@4Q9vpWBY6b068<*Js>v#Tk1tke`}a zNY}b%c|FSecQy_da5vDs4ZVF^ z@yHQ6V6wsT=-U!saQG~QfHPo?7n4+Y6;ap({55OYew4T7<^F28rS6!`^+$MN8#Ure zQc6;mz;(aMcWT>c9q^6ROtPM^LIdDddU1~^q6U1Vdu~qGygMe@RtBd>qJ8a$r^1KG zou(fj9t46;*_Oxm>z>P+LU0jKX^%qAgyB&Ajzqs5EDu2d5prf;`EnbNo>W9IyuDmy zBtv4%I7bl8aITQg2ycF1MCii#UhVZ_4m^ufxlFmrHd+Sj%5 z?A*B%bV>UM-PX~-=tZ$aM?$LOnw@T$jK=VS1cD4IrFl|W(Pw>F7ZnI5aAmW%p5 zZr*z;^Jm*2QF==hSCbD~f67N2x@5|4M?67g&%?jos3Z%rqIVZ?jUQSxam>E#LdPQI7S8THKl8i$UfwD0B8xhM zT?ScSaipLDp%+DqZlzMbSWVe_ZK1!yl(;$3H%k6Bg^=7OgYivT%qIu_RhMS7|&=P@DP3P$#;zNQb}j(zEXF;-gJjedDva^+3=k@{I&s3;kI}7K_^xa!9M} z*;8b5q+yRkGw0{C=tsKA(^EJPVRQI#Ye$b_*sC^<+v8&h9h07k^@0bPuSA zE>zW2-?N)7VzAj_xjK4!?A|OV#g?C7XS+q$P05p+zw+OWU(5-N8HKm*?KVP zNPM$J{?M%zBvFU6S0n%0O{a;&%93XbqBMdA4FJ|RzRJ4$?2zpKu}VhSmDlpbWH;ow z{;kq^J4jXUx3;v(_*`@FH(%ZLr^Oeg7>$pp_HVs?$ zSlMwb>g0Nm7tYLDl@^q=k3P|Ssg3pWa%*b64~{TnaB*hzLyfxoOsHtUnW9cz%jgka z#p$`~9SpZQv%LNk(TPR%UF9qi7c}>$(<pd#0`&ctmCR(*r0`8U?# zd;P5;Xg5gN){~-iacE&3qxmuY+93L^o-_M0&Mi+FI!)`Mj3bZ1@07|?&%kN?p``U~ z+NA2bOKfEy>DSse?#KYgImudeVcfpiaV*{;Wq5O$dF$31F`lA^_PYuUf8NzwQPU0W z)e{;y-MGNBx$SgODc`CgiTt4ZsB|vt*a4bf`iGybHaO>5AFacFH0BMs(YO0~mUg64 zZl|i@dxM`{n_qq=B{f8Xeo@)GGN(*fuLloxM;Klw{ClC{=JaIFzHcI%mHi(*D`Ct_ zXqb^R{BIy0Z9+%vd@$d+qrg>(91gQeNU6Xu;{@^J3$q4lw79^fkVM-)O|6TqDz+S( zBeY%}zs`we3@1{)vQv}?|502$_^~#evnTarhfkA>%{yD`7Abp{wZhwWY)}2tpzp06 zVD@WWJH{B0qH?J%zdqT8ln+DX&miy5mQkT(9p#f3wt&v!yH z`6DHt#ua{G+xnBjW1z1H2}1@VkV=7|HjOFg_x|Kw0*)>%MDD66xQ)jC^PnP^#q5TT zY&MQEwYT6Be_LOorntJiz=Wk+`A33lM(Wl1JEK#jdNn(ra`q}F^OHQ>H|OnJ%Wz@q zi*Q%Lx!}Avl}X|-*OTs zm-p;~hrvZxF1(jH@z$}4D;14{DYsO+wtf0~EA3AmJ_eXD_>%Aa`=s0qd~FQ=1=&48 zmzYJY*a53>s6S(XnhC`?LDhJEit5O!KTSyRdh&#`;*xjSGS@$~@H^88;r~$!@AftG z32K*ovCgtISMq)uy=If&!;;CaZP{$uX%eEI1*VP{yBIS6C_T=I-L6%!8+lR~f9N$X z)tBL}&Mx7PaY`?m24iD4pUu$oXME$AX(R3_ZXa8dW9a^@gpz0RwdSR@#fWxB&jYR2 z-bPkdRwV#7aUd6Ih+E4E(^3P6 z!uo%~)41fPR_razGY4*W+?c~dPl0-tY#&o^g@RgPaW)yk{;-p@9{SD*HhHqo>N zL^PZP$|OxJ4EaWYzxhSw$!@&CFZ0Z^wZ;FdgzE{k78K~aZNC>$$}hr2jQ)?zDJ@1{ zf9&*W`qYBSunX_kxPnL+MRe*Iu4VkwDdpN+>kAl{`&eRW6U9!J*szkL2<#KWwJ(EP ztByP$oeU}hEc`<31%$-@(#HSBEcIg^W<2?c^=F=|^P=I>+!JJGdq49(e8jjyxU}Pr z-Xzk~%yc?PEMtNzpQXF2ivq5$p$?3fz^^U?e}8`&C}}CEW~JWCgti$ z<}=y~6*y!_fu?E54wiM2lwh*wobG8scYa736E#vJpOqv8 z0QAW^rkNNTAcIeR`yY~IoKQyZqdNuNDjL3;b1hwiY**LcliEu=_B0(eg;8cGiG&6P zIiM1ITWyIUBR`V7jHt%Jot`femV#0sO*<~QRA_)==Vti-_!UC*toCO#T_(T|H1+GK z+@6*E`DndeTP-kB+!MK}_sTQ!q#4}#t$vT{!^eG|1>@lGOWPf#T!Ka_>*HHBJMmf2wX=)GC+IU*q938%14F^$c+sm&UzPVM}&aB4Az zJq#1Q3+onIqTYnv*m7ASd?>b~*tJZn>)y?-Cx(xUv<3#)mHz(NPrE;>F}n;`>zU4} z652sNBko9)y5GW2^9@Iz&|OniH}sJqFZ_xMa0i z*2C}1`L@p|wFXhD32G**PtF{E;OqHJM)dDZpk}`FY43i^A%;c&aJ`#SmSBSz8p`m~~6^A+#QGi^Mu!T1ko%gG-Y zVc9)V_%I}Al46aiBSlEdI_Gh>3LfdicfZ}se=e-8 zaquHRO>5neqmZQLi5&6!s{H5U)>i4ylY6!BgLPq6p7V2E2J?z@vcLBy$;;f%@-41- zuB$4?Pe0$b)Tc1X>Zq<^d#>=kp!@o}LqglX#8~f}(ya}7ALg!?aPm>jolkUs>b9;| zJUrZn3v8<#I&&mqyBU|)WLr=yzRXxj8Y1f}oJ_)h-nxxWz}LY&EmmHk*7+ge*7|+$l{k-!7~Dr;zs&X-z%kJ6h~}sOjnsCRcPww3FtQCnI9UtQtRW;B4?% zuoRcZX-WwD{rmSrCsv!Fx}B(DFAF`2@olv*9`AaGtcLdPZm2c1-yp76dvg}K!GEQV znDEC)>Aa7~Tr_C()1H%Pb#zi$8zlMJ)30@F!e;tJqXRMyw}8+1L89jghiJ{qtCt{_ z**l!uNdpNS2}7ZDz@Q*V$fzI*e2NN**lP%m3Vj70Xl*Adaw{_FC`AVfJGYj|7jo(G zWdSj@GOpfSu2btyVTmexlOIn4yZ9SaFg!d6Zl=*B>TeDn%ATCN}8DR5T!5m9<9%H)D#6 zF@vvj`kfe2xdZDadtz!MrhohJ^H9l|t*)Yr{I0t=!vs+0g-Pu);JYYwLZN5OX|Y*L z0i8Mpqyxd%brBB_)-BNI?CI08s;YhjW1}oG%QDE)s;)2%Pya9B0@;>(bx}W9&SeLS zUZPPk%j|^QB^E6$g9#B1S{=u*p)Z)V-krVKx z-no0%;8TLCk29A=xLHo~vz8NA0cb;?5_e?w;Z8-k)$NAYgvaFOifDMU9}NHZE@>l~ z&mt7dteM;9Ri-t0T{)kfx$)p0j(x_f3imX%cdU+3UOEB0RS*c_A>`HyT^)On87~k+ z2o}T1D6ZPcxru5)`(bUMq3;m)W73kl|3_nLJSu!2Nz?#b`}RG+jdXf*X2zCc7|81C z>PDd$E9ANohI5yQn|TC z2Ux>?&pnK5F~0#R9ftm2_u@HpC|Te zLh0{X7+RB?7i0nX?4di22RMw_+?xd1?~SluW*B@IbA=7xcaXG;k2|Y=n3W zRB#34F++WVm?efhJmN@!Yv;<)*T9{MK_;|>!%Ad0Zf-|p$Xl$(G!=(_hqXE$$lkI& z|6oz;N$*eIpLX%AR{q}GTY;x51WZHV4e*S_e}WBzX%9cC&erPB>aX>6DG04vl}Xvx zCU7sY@x{)Tw)!%^J8!2S|Jm--g1!<}@~i1)R{S_LGL8dD>Mb>SI)S{2-U?OmOW)PS znIpyL>nYV-^z=gJE%4p@98E42AK=}s_TvwAm!}XI@b$Nq;W9y&Z*tKM@B-ZFO|>Y2 za(anTq5HFEGDSlWc5n8wTc^$&*86Ubz~2bE0;(|Y!Jnc>TlTWhp~dspU6~k%*g*kO z?A@fS-SCiEtY1gk&)aVamhkf~ee=O-*Pbt>a3xZp%{BOZk_Fddv*FZIv#<6Zh1l!n z@DKiLb4WYUTyp=;@<+rP*m5t7fj%$f&m||8)!BMG%>Cd)leg^fY~Nv>!o2Oj+zQTb z3-vm^>d#?dme@8GyT5(n{hfxAli&Uc7td70&qQ!#MaL zuBKA3&Ei7)Z5fIy&)MGIV?IQ;siTv;&@R!=TUH>hh*%J)VWh7EsSLX4o!k7&FX&$8 z6wRlLp=7;p{xRg+{VejD>6u|1FPeuw`VhIDtWtDtY565EkX3P@ilU{{g!i`9L@F{< z<&k$14Ir%%WXiF&2N4m;m+A<*%AeLMZ?k!->8Ra~a}>GLbtaKpz7q8Vll(5ugJ(T% zje?Z9fC-Y=lQm|j&hzkK!ED;eBmVqbHKgUS38hC-s8p}FEIBj8NhsS-%b;@r0$>B$ z!Wt<3nHe&Yd>lkZ)Kn3f&p0r8VZBbmR2iP~RL-M^bt>5TsEQQ!}v z{f5ze=dyP|X8W&ylR>ZLxBzkVLZdXr*M_xv<@bk7H}>?Br4~w3p$n^;dFGEz&Wm?0 zeQ$(39t>iY9Pg&m0Kj-27QdTy+Beq!y@&*jakTEmk5qgx|k`7&6MB|^g z!wAQL&J1^?uk+q~>Stul&o}y{+`mQc=TCMJ8zYrLADh;WUAxr3*aJfkpEQd>H$T`` z7zNDwh>VPB>&q-74)SsM+);j~KX+@q`Ixw9EW_)b%&+`fvR(I1JI=pBvC!9&CrG&O z?c3cj)S!Zll!Vy#%QVjpmq*S|ZwsWW{V%FuY` z4rMnZnW?Y3*1oNJ_E83nv#7G+yX~xs-Ap? zhaMZP4OkvXlMb?7`(-5K| z95JV~wSi_+L#5k6stO{yf?RwKQ)+v=OFya`8SNs$q8A0mpv}*KYK06a0Yk@fL+4um zP9s21WWEyos+bJCVmZ}1b}p`pt2a@?DBSmZ5LB^#&!G5G;&la@GvJen~ z;Oh^ScaD68rGo@;0zOzIauU0haSAdhzQpec#`-i5J|)V5higdLdbExZ%M&@ zJFRJuppHx~UynIkb7L2X+*vF%#(*j588Wob2rHUsHt1 zb-C@gnKkq6_=t@cIAJ$5PR2msehxPIV?Njh28M2jwt}f|idbZCroAcqdT{H73K$;u zm?R-iLqj(flt|vI_D2iPgNanHzgfn9F)F(FLh#ki`;qN-_rmDu{nqZ5l8OQWjy>!? ztiM*p>!LG-!$*Kr#05)jUPlE}kSQegfNB7aNh-~^*ur>9o*Zne%PT*U`3bM)C!1S9 zOQO(=Y#ck1CqUG~2y?|!d3&I`LS!<_B8PUBS=L5Ss*n`(e4z3Ur-2R9ZCoKdTC7{u z20;IU5i{>p-13?{Y4-Y5(~~87Y{BI_jigY1m0F@elU|^%a&t+mMgQeKrX_CNA2q6wVDFc zl#%m)<>#@JCwGd!8fSh}Wn>$7&K&oRng6zmGZi7RMt_vNrCYQ^M53&v$Z-uFHWqkZ42?x`p(1ydu9 z)Gx?MRy+nG3q>E9o~twJfK4v;nrKL9b!=)*8emcimLIFe$JY;;ZX5W4T^WjTo8~(R zgbT)_c-q9W_2ofWu|JxwM^Jl|?R&nQ( zArFB(08&*}1ng0$*d_L%t`Eg92k2QYVy5jqRtYk+4Izx}9euc%(le-g2)R%c`u=SC zq4k;heq5<$?}9H}LnG&B_N;OX1jTp6`2n*d|G0i@OMSgRv>j)@yfnal?NfH{ve3D> z;8QOv;U=lX+$`dIBK9M+ltg=e&a$AP));nYdV2bOcwjNuvL7>+h}0P)nmqhS5B3Zi zsj<|(!kKn1P1H|*2_!8^` zxv=hnb$EV0KL~~ySC_@vHZt(&i*>)@)%_RW(m@od)@|+frieUh;*R4UYl&r=NkUrl}N^@#%K7Cr`HJjfMhS!92tfb53}ac6HartzAV zn-sh^&`gX%5jol)AGNFo>TV)WsOS!aOsXAMD%Cha2)n$;pV{7awdq>w!;nT1EWBR- z>p}B7G<890oNBfRmq5g|AENXioK=K?SjBElU*W>9y{rg1u3vD)`en6r2XSGrh?v_F z9jwipngBU(so?bn=Rv!KPVp<@o0hJY4zfddpY$v3n~$Z_FSBah`O9HE zDd^MKm=!<>PUHB>TcZe_?}Cn|th(A)ac{w=T1;oGkfD_*#e;LD@{O?Nw-ZQvTC;jJ z34J2sQz(bh!N>eHEQQ-LqMqUGt-blvDRR0^-Pv1;`tX$pOr(Zls4CG$+3+?m5sv{H zJ`4(0i7t5j`1^~sc|?v4GS+V7+mPlNdOdJMdvssV?I|X5);ud4>f~3Wol1lsv>cNk zvl0|Y(LL3{+MkT0+ROt=CPwd-`K>-n&|tk1WsSEL(1FUFX-Hg0KTmgA8I}ySW~aQkyGtDL>0@IFUPHiO&7ui z_4f6!S3sc?{`otmlK}{(9zrgI`|aD2a=A-yxbds|x~EP#_su=uJA2+)GuHm@nO0qn zTnOWRD8rx8phYrSup~pAMJ$S-X9&x7iNfq0Bc-s%808J&W6+?z-@MRHWLOT%)`;Z zz2;kG)cH`6KiXw+p_g?@0WV5wg{%eky?j2sCQ3~=Zb@uiH31dNi+exq$^FK3H1Ad# zj!x*h=x~vkbO(d@m!U~&OMxXBM&zU?GIfJd!$e+xK~`C5v~giw{$11T1cmlQ&!z!_S6eUnkrsq3`f*t17d@bHRm@;ZEUKsL5Lo%%sUC`Q;4PJ>~NKZ@%4QtGUN9^u+2E$8JtF zNM54f=%JKerL3$>F=&?`Q)Q4YGBZ6Jbw zY|mDV3m#w3bA%0KfyA zRA7oOt~wC9BDn5m!>OFwJ(xDbWJ;8TgR|I4Fd?k`3_w(+D55IP(nyMXFn!5CBuB_^ zdk`muc*{Nb+~2hZAAEA=Q=;VsfIK8}bkWiGd*bPu$LXWD) z=&_=)*?`E4f?Zg;yssYH_F<3J3wtvaPi%^MDvuQ4@aMm$A{%SRtwFaivG4{Z=mdCk zqWD3e1x*ovWoXW5P#a41KSpWSNh*5u+4>OSlI9ij?2a5cLWU3lMeJ=~5*Y8Q!!^4y>q=`>wYivSnKzDxKZ@W$o6904LS(Wv3#OqiLZmas9?dK5IqP;oJ3nE+W zI-TmNI#sBBPem8tgCi$)@4aEsPd9DY(2GEkdpL<$QjsnTj`H~+B48dAA1mFY4H+y2VlF)4eTJQ` zf?Q@2X*iSOkZD3P4|<2>HDAx}o-T7qm8R=4HZqyr4WI23^H$e-or=Q%GElr=c4DZu zed|@?J%+-Pl2p!kBHqK(d-ct-D;_|jT_F{{3lVNG@9Ite2KsA_gdP!a0ZqvgU&JKw zsOlq>8he_r1|Z9*DI}mfmy3>FpveDb^7hRwLJvQ#AJF^MGX|g38Kf+LHLx4{T80z8 z3L|*Zn}=Yu4TqlW)4-Nuoa*-g08fD9Ru>6+_;49U!#dKV<$vkTqN!d{I)9#t{8eJ)1Io5URUSsQVs44q2An56k)F8m+F@fk+Nz?B>U=Y_<~zrL7YRJls5i6lsXp#49eU$czawAU0D%T@5f z@V}XW6rHJKPz2YnFEU9XzdW$@j<0V#hFuUhJW^Q1X2?R~xW&hMsy{cditebqygvq}7rOk? zJlg#44t8HC+^zCv>`Ogt!ZmL0EWZbl)kL_$lAYGCC)7-HZZ}VQ;E&#Ri&&WgikD?8 zY74CCkWHdzW8128^ABXCtSE|6K zUYXU3Ff5Qfw_N6b=pHcpgyU{C9F*Hu>Z8(!#k&(ZYR_%7Gn?+g&sbw25Snz-W}61f zg@<8sON!~2X~&P7?=WOc<2o4JnkYIb`B2g6IL&pR9yO;UW2@-C8+JULxp~E6b7|aq zHxo7%*QSCQbK2>fAAv>4LbN;GwrztZY!F+aXo~^EKn@c8 z1^}W832)jPG9Ve{29}FZBO=m^{s0M5x2?#t2g|oi?|9m4&Ay%Ol4-Zgy2&xC7`a#} z^Cxqr8hanm{90~G-x0$gjeYyhpUz*KLH_>!e=`lwFI<@U7t3HB8h(WLU6Y5QFZ4~u z3|70JJt#p;&PRTB(fqW!(AO>k`OK#D1Bzgt!#ro};707(;4IrX_WAf@oKBj7-j%WO z@td}7TNl8WJ&tbcl!{6b?Ap0=5M61yretFXu}vyEp})ig{~e_C@Jj-!M3LMS6LX|aNd62FzqYZil6AIz zTp^p@=5F)sno$8H9UYT(*|EGcv^V3=_w7pC%Qq4me03(YHIZ%b zB$#4knB0++e9zP;2YgGi$A5SSz-1IdQWAhRlu4P6;TrNNvmJ1-5OV0~g(h7FHniJl zjiBH~vz2%ZEuy^b-7k@sNlQD%EjoDOoxY_Re_320lQZk^QDhDfA5jP$o52w$^f^zZ z(`XSkr}Y+lb$ANY(0+axy10S@cE{hi7wPG{M0DbnSRi5H*Cy(b2JK^s_u*C}k0wF` zCrcOs&MQ>&ro1Q&es}+A`|AViCt{9;?5*;VNY#*^8oL9h=$ZasJGmBCs=4?YsK@v>+6P#Gq(GS&_^H13}*#MIF%=m)eSl)>S>Wn)&6~6wgx?s3c z@8a39-fq=-q09K#MDZR)%swU9q*~?=Wm8+e1l(4wD~or=580P!$l0Q&Zf7rxKPV%= zi3XhS{}2@wf5`j^BA52M;^j!#*@-k?qj}UX<%udwqZU)VKyY;3szi*^v>qcf&Bb)? z#OD+z-X}X$M@2P7e7-tQp1^EmJ|VVgM*8b>nC;D0C96Wxk)?y>L`G86gMfFpm!Cz6 zX`pOo;o*$HOXOT4u}T3Pl$h+Qn%$)uWl=~e(jpvGtUC7n9mY%<+}z&lj~SM=1-UiR zYbx^oOlIpk>DgD5AwPc@=Srt(orDW|&#@)F>p?9uB@VLc(|SVZXpAzkv6|*FFdd!{ z%&+GcbM>jcx^1PNS8CHr;(a^Kw)At3qSJw5Tl8)r`r_;xA_j??bFe2NttdujKBKA7 zr}pLnnufS2EFag>$=l#lWn{dVe*aqz%SXw{1~n|-8;bifH%v8hE;m$@z&f$>D zhp(Ss!2lBT>Eqmh2<{*oL6<|PYDA>XmezE)n^$->`AA;N|iRcsjE`HxHBGq^)!X~z|1MBx6JULLgrNa zri)N` zOZD1qM9Fbljx?sH^)j2tJ?TTgHeb!=i{lQ@-vQe;){XB@?g~>z`rfYS*Dvml$Nx$X zEmT)sSm6+=O^3WduW)|C<}vL@6$FKEi2S~y-dUfXbVyldeHff@ralab^vrtk@CM88 z{LxDrhZXB_@OT6>xU9c*V_)JZc7eRzguhLE3Psnpw{MMIv{<1h8dT)vUBKSHoi8V$ za>_BZ#bjHLjDJl==A#ZFMCNg+|oH}%f8*W^rsV!ztb=8 z%vz)Ufshs80RH9r-pf5n2Iw`=-&5H|5!KkyxOIS{(IW8NiiK8ncp?7ME}E%G`iRiPBa(kxA88Uc>CO7 z@pY$@c#8?$pv(y`+WSX*C5|}Z)OCxB&%OdU(9bsJ*60dSsoY$}`W=Z;aj~)PT#*j9 zVE4(kZ1eH;rKQ+g@N*-EljwmRM5B8TMQkLZ9qHKEe50bGysHn(^2c_rY>WPo@nl5L zXdyjy=SPFYYXflupcsRKp$b2@H(3U6UbX9#pOv!9h`6Qu6*6+abl%gafmfVWE85h?8WB9mca@&sHl1I(0eXK@178Lj?>U$TD7ru<2dY|!Ds;sOm zBG_8d{J{l}%e-Cm%xRi$)YdURqg34ArMYOqn;!M;ayaE7=UuBuT@TYz&I83|x zr>j^+WInT^>s*F#)6G3;hHs=RSv#D1d40P&p8Tf>4v31*YmJX+#YgnPq4x3uQe9zy5FGCyrun^}=I6lDjl%GrMZq3S})n{OazPY+XHC z$8+1}+CLOX{XfT%8s>lQba8FCflm)3VB-@5>7fNLS~AYQf*1@3U4+fSkDI2izueSg z3?b!-+(NE)XCv%x?$a#Shb(uMR>;hbpAj_nm&b93a21kDbEaaOm~&i*6gGjItroo) z|4KrTNW4u*NQh0vg?|Z^e9#arQ$Z>&a>j-dzr{F1Cyo zBHAfKhmTT9=xCRx(WtiAI&Ke>H~DqiI9(%S*}FR@1FNdkXI>wljrh|0DM}--awbCL z+nA*Kqnl6Ec4u$d&F6u>USPbEy5O{8lVMom(t8rSOWs`kRo`#c!$+5Myf&26Nk|P< zDa?=$X&dW}^y!Ve|B*?@&sUq!gi!|M6{FcV4_4fAW8t-Fg zr+^<2!Xgkb#;|+-g}MYlwv%+U{RZydF;a(M$ltuqWznE*-xp?k;q5pFrfpiKUu)Yx zKwQr&@s{1(S*Of0Q4OjZWS&wpd&XFHBJS7yO%-Ahzm;>|CbhPN=1w*WItQmVwW_wT z>>Vwh6IXUHf9jLtDWr`;Zi6)^gFBZ4oSBrl9d~&vv&cR~7&O;Ao4C}_aDa4WVXlYw zAhvv1y06`0M`?vyOkNp9%jaZDd);qdzg7u2x=c$FlZj}4O_}QPlbsd^R4S13*;cr> zVci68{^@$vx#=K=8#=6ERXAfdSg*uSOt`$OPZneXCZ7sAj(1J4)vVk&Jkq~=b;-O0 zWp1o9%eU9bn?ya-QRlzWGOOq^Drz->E3BwXeX;@Ouu{=Sm7g0EzdRdvj<1i;Sn0&W zJWy&8&ny$CA5ktEF{~NCX|aESS^evkt*sv?+tM;b*4@td(d9B@x?e*_l+OPhvQrb1 z83CWkCW$h*FGK!kXmW+cc5xj#*4|#zC#T%lnPhh!yu&Oc-U6f6?PF6TIHSBit=7^} zb{&_~3yGR!BTl~!d7Dv}JidHqq4UU6{w4I5^h8 zSL;~V0siY9SW*KcBc}HB0}2(Xw~tJNg9N&g)Kh4%GvgOOw0d{lCTEG*azkD&DSei{ zQurgU!k_))D^t}iOgIZDH1{wv$&U*^YdG%gED0*e|6SLBRV>y2RJB7C=+nqn@neIE zbl*k{=%Il8AzuX6ef-M%0@R<5j*i0h%|i9K3jgXyRpsp^o?{aeC3*?0ir2OFFhZk# z470J3CeqNZus(L%pM0c$051Pj>gQiq`L|O4ngzwk$cV1_Ms>4Ye`$8O1|UF(X0z3% z@ArrA)>@~DG63tv`ByLf=PL@dB;pev1aUBFcyb;L_^WClcIzc{gVI3mynHcNZ$HpBFySMkWyz+E)N}mOUV%0cO9YLu{(+#X^-1hkZbGTK39g2L zeSfbMmSI_>K)Y^LTRIR@3m3w`40LpN%lWcOkR8hO+pD}Ku`#l%$=s`pMn)tm_?y$j zNhB%_^&yP2^n$NMImX5!;^Z+RXULpwAD4Bm5CCCjOU2^CloZKpDhKhPq^I{drW%%N zhwnF6k&&ijf?t%FtMBmi16Tb+bbfCKc|#0snh z0vVR58-*;0{;@upDdj{C-6C5MY5zB|UXd-u|U2!w0;T9tA7Wlb` zgZJOO2V|QaZqi-Y86P&=5y?)2XU8Q(Uz)wpx6ili$W&R0LJmO>2N9Z=~a zI&6iZf_}}#3EaLADf=6<#=jrCSTvTZ1LsGFsg3Pd zb2LN%3V2= zG@yH#&uFXz)TO4gsi84LzYuf4*CBMyyVIMvvzmNwWMQ;Hg_c=~mRU@0=~2}?_gkK9 zw4qjf%a`%+l;&iMnn{@&;=)ILdp&k`F$U`8lt5BXtP)LUB3+<+-GIefBIO*f zOWkLn8{QPQ)aMN@lXszmXZS&+?o2>-ouZxJS254Xj+T;(K?u2Q2t=zsF8I z61oo#vkn?}{B}DhM;OTkRzC}%Yaq(NH8eE4cJKBgauqmG#MD{L5hG2+WF#aL)HlCM z_E0HeK(<|HEiW&xLrN$~;dEJ;U=t7!a2QOlARKv8Rd6(mp;6KcjFnE8yNM z0|YZQMQV>dT$%7W{_g-AmSBqa z7l1y~7&Aebu8*7nX8(-Jg2sQKp}I|t3ND<>#Sg}itSkOA+o_9__&H{|{w(>w~Qcpa11MIQt+QByjb5Z9q^o4y-9ITI_D3^IYCU-{8X zN+{ZEJA`mGHg7(8-BS5j_~c=(nL02l7OX78c%F-uS~4V~_t(7C{n{=Q~tN|b*6usY@@cEv)| z(@5WWa~4Mo3L=r4)JG^6_*b8_pqhWeZ9|EC5fZ@PBH=CcD8l`x_-8JojD^FDKQ;+A z1%}BWqW}W}oC@0MD4ZjQNjCj?3=sJy5&{f&U%$X9+()8oc~-C7{V3TrLsw0%^dM&5 z5R`MxXaER*Msroapim^L;WfB8UQbPVRwSUc>iq_2cC}t5W9n z(~?9Mo2{hw_NWNj{Of>ekaVmV*avI5iG3+1tW*Jf6j_2hJ*B1yg(!Au((nP+5vIbR z@?ZupTpxnbo}9x3CCp|qj4h;=C3iUj&nOpOUpzfUd-t^Eu*K1exTp3%@4Yd~%-mj9 zJW$a8{M)0CP&{Eb`RyprBQ>J1lE8r&;PmtI#$v;hM-te&l85;5VXOe2S3$3J^<9F( z$%_ZJ0=_-`BY|T0^{WlgUlBC9=gUBx%TV!KBsad_28ianUDz1h;3zaKZI5X*<2DGAf(E&k=VmxpevUzML=PLM#L)XFg~lzU+J38 zeqBqE(ne;QcC19AGYh6e#pu4@7j}Ev%z7))2f!w%qM|)8Kqng;hOEjmzVib}f1DvA zk}N6zxUocHVExAwuHW@a1fWYb+&q8ocKyy>tNkAhOQQ!%GzFka4AsnH4OjJdaH>Uw zwA{O5sh!<4ANz*ySmoQ^99&XsDCSo66ZEsQZE6B>eTXfH$9toCLEU@TNdM&vs3&4? z<3{jdI7<0+oq2z;f^4i9z`35u;q`e1*JYqW)6C<#AC<$_-WZV>+siO9-*fSGTll?4 zwTBVrwz-BU9Nte8`hgz6eR4K14uei(Kb7Dm1~0^PwtlWKFNH$ zbee80@1LG~6?3^~)YtvWWL$T;rQtHR=O>B~bkSXP#3%X6*5e^j@y|*CBIG5Yuez%^ zm_j2hYvwoe=39&7*>(0hj56>xGUV6)Hk9X4?0nD9cmBmr54m${6egz{qj=U;@O@|3<73cC7$sT}_9iQG(*?k5t!{l0P^7z8M*p=tHo{*qfABa!5TwQWr z{%qdt?$Bvt7@@9rm`e9Oxa2RbHfge#k`sEOw$HvExUyA}@5;AqHs&WEQ+j<1Th1 zuJika&%T0KrOfE4$49U+EKD7?hr+6h00|VM<5n@s6Z>Wk&@N}+FX2m8>Pn-k`p8Kx z(R>J;X!k*X1aZ?9b9&iAM*Y%kA9kLa_hq%Lbf9T?+A@Y>0A7en3G^lEDaxv<8)zkd(m_OoHgX?iKs2o4nkmWv^3ezGz_b~p zgQKcBrmn7@C%KAdn;s-bggD)}u{hVdb2mS~BwIXqJ}yjNBg^}Aon^`R;*S!fqK}Qd z;p?m0x7v*on~H#WtbR2j3%Vm8i$s7P8qRe??Uhm| zNvbT84%(UJ=_#Mr2_UW)J!vOmgSU%_gphE2q_`3fO-oB9qdJ)#g$d1F@lnppzJI$u zVu<()vr#z@ROET-TqNQA9Y}mD%JwqAI(Lk*(8ioCZT^Td5`f`5VQKFi(e`R~W=F2PGXbM+QQPt(!TcQ&_uBq8{YX$26 z66jQznSb=LF)+wMqoJ8)#z0cj5s3j46X|22RN6pCR|MLDC^MgFq@q?9@-d*(!}~$5 z`QPYC+jb>DYDx6p%{#(;e&s&BAaVEj@v~XN5g6{*9?X)6LRM_}kb4H-KFrThn>5*a zB)2f$JBDmh`^-*Ci$Hlwf&sT4Fd>u&k%K~iX4v}jD!?U3QjxLv7%_X@-za`XMxhW3o3R~@cd z*-mb&y3ieY1p{#|3@w~MkCBeqc|faI9QIdXds+Ia{o%~jz83Ze2^7jz?4Q|Zod3dO zOO|F_y#vyJL?d%d>u*C~Rgb7iqzA9U?24~EZN@px@8=(+4z5~g`Z*o{KLXeDE5B%S z{39|Zm(G!%Mw@9_i5ok#Odt0wA8Vqb>3I_w<2Wc9R`Dv!aINo3hcBjG#$4s8gO>tm za}y<>Pa;wLZ_LLZlXJG#DZ0qr0s;?_^_q5l%7Ow<86MPKWRTq+eVFJFJZ$w-6v^2h z={~Fy10f8E()f-(VYj`wpx`Ee9r`_^xsW;SM`$34qpIn8Cz{1+^Veurij`$?M5A!tfXW4xkmUYNiu!9@c3i}uiKm@6 zATNO&sFtTLD#*|I#a-&ha{c zWB`{k(f=VrD8psZc>$9kA@VCmZshXAfROMvOi=#r21p0j!Wbr7)@GZZt4NB0v9b#o zRu>T*LkGIDGCN|kz{S->iOr6@Qv~jl9Q1{WsKp1Ew?i;XiK&)T=0>wP=Nv&rkkWqm zz8fX zWXJhk_N<)V9s8z69)q~A?k!QXPrJz=M$FhQMi%`MjG)1=AJD{}80G?pcCSM<^pe*0 z_Puba#9|N*RR8-Cg<8StPC-UsV#rMRg@bjNQ3Nc)Qp6`eFK-O$KVsCmHaU0)q4DU& zze9p9*|xX>8})ibI^yuI-7_~5wHHkd)L@sD`FUw_Sa>)3XRbX~#m$KkqFJ+oJonC2 zG|SHGu?n0>T2iA@0BfwAoy4}q{NQE}m zPbi$IhAJc#O%=j3{6Z~v3QBpOJjTV=R?@2QAZJzNuI;#YJ`7ugwB8Rnc~rcmQs;Wu zJqO2J1SJsH_+iUUH@~qO>K6Fi_$8E>3ps@iE)Tu1T0JxmeNf3j^g>-><9!@IhzxZD z%?o+lvG;tOd^sUMUva|JeXN>~#7Bc|=MFj&UwY9-kZ$k-$*MR1K~q zep#Uks$fYZ7Q1y~+-ken+edwmZP}hd-tuA2;9=%k=$gFY)NjHNwHv06WVo!A9W??4 ztr1e$UtRRMeVy5+W0_XE=glxbYwZ$Ekf(s9YwvC+GO~!Ra|K+MC})#B_dw4CSrZ1a zg^+yxLq2>D1%LFm9-tm;uN2xqUgpuu1s)JNW_Kpk>B=iA1YH)K)SqjlOnU4Po*(t0ww&>5qFmCv2hOh0rVm-;H}%3e#pRz>La zw420kNt-TT zZrdlkAEmjLGo-&%6n!Rtn zBBI5~^oGR`^(ZJN&a4GDa_ghIaEP?C7I-H=ug|M}zpvW6qTB7D*qFRJjX zfwMTOzcIUejQ3pH_tfQ18Df4|##fn__m1$jy+<>4??+<*!eLWr&dACxL{~0Zed1p& zv{~e!KE`ym^^}nb&4X^768Jcxx0pN>6$PYv&?99n3F1q>@ed0g}yPoMN)DWhjgO zCPV6o?Gt9y2*xzBATAb1m!~Ih_cCXZhUPYP@#Q1TsGTSYy2xmLvS)zis$;J1sjatv z=Zc+1d!~ia$mBY~p==g+NQ+5^0*4rGM?ByvMivwHxn=<2VG2aFsW}>4zo8`S+ z_f@C%e7M(K)?qHMiHOI=<|`pT_9j-y%!l={%52!cv|s(I9<(=b8J;!)qO1>|DgNN^ zzfoq6leHjS5g(5wwwJf-$zQd%^KMTx$p-q(dxs=&hFa!442=)0kdx(q!DGDoT=wO6 z6V+1Hm;vI2@N^1Tqeej*55s3SftVrL#o*6I$3zR5i{Q%KL^79=^~@8$k_`RIQbZ8e z+`eHO#<|ea_lg}&Kxz_vKi8$oZ6*O9$bed!dh{7CBg|8Xcr`Qd3_K@MLc{uS{j=LD zq@JV8vZW@hw3!qHaU0J6usxHnpfhVIY^y%h8yu0ir|m|7YAf@&O5szS6-pAAiy7`m z&D2*7vjR*a@#`cV$1f6pJ!b4i2t?xc`ji|kcawr5D(#r8^l1x9on3Iq-!1d~`9yg_ z1^cuR#%CzPumvX%zeyhd!#YYHfu6(i&;R^w7Qed8q znF8^S-tNZ;O28T=4J<##D<3-aBuf+tGt*`|*>Cmt%rY{`S4h6dk1>{bf%p@lM-Cr$ zJtbv=R!kfo7%0?5t}c0)L{>~Y?E4j#O(ME{U9voWZx_AysPN{Zxp=9qMh=HS(fg$l zb|QhpGuI}ngax6p^_Tqk2@PJl<{o2~KIBhtfixTQnBWF`4X3nC1!nz11HOxghZ=&C zl-v$#@Cg6EG~GXJ$>CJr2yFTF^*(`xsDfD<-=wcIA`20rA5KsoQ&??EcWp$$QZ1I+ zAV0|4pyJluS6v*f6|ut%02M^DnzMK41+yydqZS2yJw1@Vgy?BW!+e9=LB6 zSTlVilFL`LchL4@*hSHcRo{$9^d$!LgtlmA2u8AwJijVgXi-m8?-B)|~K;6Z?`e9FDMK)!_(48>ej!ID(AiBr&Qup>`cS7>L5q z&)>h(Ob~$?5HXyEg%3#;oJeQ_gZk2^x2vlL7HFg{X=1Dwfd6h7v3p@jFHCAAVcNkT zJM=HUJ((3M6}zeGSpZiLeL- z1n#^RmQxC&kKxB~4x#A~#vd7yh;%ggM2W!4N<&QFjtH3`PB(;4m5nY-#QL*-GMwBhuZ;vorrT^Y;^gYL>#ThG!{7yA~=l_Sj_YUW} z?f=JBmj*?{-YKLIGO`;gl~IzG$X52q$|x#I$f(F@8A*|ZL`KM_NV50d*;&8Gsq4Bw z_kDjq$MO69@%{7HaXYSVhu+@r*Xw+p=kxh^KE{eo0iv&Sjv8_~cz0t4O)vy73ih)3 z$rjSG?X@cR%+P@S6$Kul&N@ysGEnngGzVz`UL>>i;c^N>LJ2u~d+|ptYzi( z?HB#kvVQ07tBK`#L-Bf|S9sOa?VJ??<4{sPOq>?H1-yuX8laodvWAsO5{(+;Q6+uU*p-&T40Xzx?pV zsNhq7zl+fohs8Y8=X?j1#D4v-yf!0rMRK~P`*YBS?-oimekYh8(07J7rgKt4@rIm$7Ot|A;pxD5J8~PZiD~6K9=HD zt?nx1fUUj+PkUrHrQiJmQJM%+kl{2oyi=ZWw>AtkqmgAo`NcTpeA4+hvr}Q^-J65h zj34BOMA`jW7)MXOJuA>yn;;$0e^Yoc%w%zINKUE3V!=DPSSI%)`W_`+OKImiU6xly zpv}vtd#SX%HeSNJ&x8#hrTs2#Ke)Py0Ba&ys`mC0px3y7E29yo-t{ga2-AK*9r)h9 zVMS5=hfUgUEoPALNpr%6PnanUX_kZn`57iYAR1G&j*L`7X79<_lUs%y;~eD5cvl6;sD3pqImWPbdNg^7o7?c{Gr5~YUj&;2Jbx!pIJwkx zf{(r15jiB=35f}h`C)K@$Wx27nvd=KmS#F=;l|TnFE8`gcfojd7pj)j>o_bbn zKs=?_bI683lZF9%0gPJ+cQJ7$g?yG2Ls1sTSI1SPYvYQRT-nQqxA4m@7Vr*VIT>1O zart_paq-NAwqn!=`tuu`?HkO`xO~IH`303NL2gkfoNnD%Ra!$*SL7W`VEYbG6dp4| z?|o5B;`!1CN%L0fy7lXc{3-L2z-eR>zyte}Nf{|1--)fA?&vX=8LeoSbNSFu(PAO} zxqemb?8v8blarGr91kGcDaQ_S#Fyo20V6xGWH8*nzdG#$u2DF?GIQ(|5II5LLTtV| zkDZlMzL%LUFIiLRnmVd5$^>9$PJnNKldK&YC zl56QQ2&>XNiM<72J#b>AC@BDmBMCr6b_gLV?i);zG@miTx27`T&}+OV_o0%?>ayT# zkFE71xU?6>c1z?(KCArx;9mBNb*^DIFV3&Tk*M`7`5q0c#68l0g6-7a=VU=&i_;N_ ztR=@k&R{W9%S~0@AubGxjeS$y4{*G0E9Wi=3J)!>wv`yKa=37`vc%rOgqyoo;~8Ze z_;603r2QI7)QH<`ZT(0>WgHsYVtjji=m|^)5p4I%@Ftni;XTQC;>De7`tv$CGZo(dbGQl7l;N?!u*N#USpFnI3h4CI(idYR@!@6P? zzd|?OQ`Riso?Ki+{i$E1Cn@#jZzr2p4Hk#Y?AxKcXj`r5Ui6PcEP6>xg8@4xT=r?8jt1Z&;R;#@%MR(|71NW(-!TT}>!nntbV5r_pOXfR*u? zvUclVy+7Wt0(;Nsq*jFkXU+m|5E)qzy)xJI22CQ}@eW>{a?oYAFO&vev^3qX74ol@ zPA3oNTwc6pY0JIxQxnX#is(zvY&0@3cnfY44zo2mMFHEA>MDF6A@$}SyNpDoI^7c8 zmMylv2hf^svgTAvz9VUAsa$w|f9Ax3rUd7)&hDi*dhHP^z13$;8SX0e1zU#a5$8t{ z{oAJ3P-%kQmtZc|q@=auGU!y2=`av(- z0$l0k`IMbxssS&g&dy@nJ=TWC#>sf9F|LwBr&@`Q&j)IOlb;B+I6zNdf|>bSEJrfO zWt9_B)EVvSy$Y@ybS!0WR>z4`ABwUoI`(EAot~FiN?iIV@ zZ8@(;SuI~|ZC@NMexD&DhW4yPGEN!(=XGFI;sXhe-o!Dko^I1ct^FQT0%9US%#ZL* z%#n^CKD-*{F+`2?^y$;*cZgSL)L(0-COgNyE{x}vEGTPddOcZ^Jv`B-7_*QerLwIg zgKTmKx^}I_e9{OOiQF&}Kna>etB@g>ePFtw_m-_azmc@x9h^~35u z5;ePoJL3h}q=PE5<-OYrv?m?k>tDTh*fRssC&hd%_rDRJ8AxMKq*+`<4njVXy7LK( z6w#n@7t(~*ty@Ppy2IW;ffS?iO;3tnr#vYAE%xM&DK@?ihQZEnm6A5nDWgX$uo3d; z&=Tu=w0N?U-%lan>ht7@_pnNU^9o@Q;~=KH28l2(>8e~>2+KNs z<>Y~dnb}a9#%j@(v0Gvmvi#jEwF?*n!}qrxfCt));Ha%HIs*w0+-)j???W%E8q-R zguv{JI>~bBPTDAC{RWx6|JGb01vwwHUscej;a9kV3zIFv$b-6qps0ka zOg1jS0;I#Fz|6q_;a4soA0jQvj}*vAog&I;;yjgFOH9(EPc^X6pPkX-bCxW-m^@le znc>(Pv>~6*_#+-x{%r~I9#$|~f@kO{EUw{C)7ms_dnxuQE3ZeZ1~0(snji2KOSd&9 z6Xu`qFK@BWkW&kT-vi!h=appOsbHu>kMA3=f=dcldWRG&s7>i?U7rLq-Iq3GI$hJ3 zEkCR|B6DbDDM7E;Z_6;^152*2tlcW$OR~|hKfgQ`OM^zH6@lc$MTFe{{DOiNAPofe zgrn64$6)O~%n{-E2Y!Kzc|{~ABjXV(E32$)Yu2pEsHe*}O2%^0YA7x)rogx!EMof1 z`sWT3eu10)gXK%M@>7*;bpHcw+f9Ga$VnSbBsH~o+-fV z;B}@u_=jv@;0w~`Bxy-f>H_)GYLT>P48f&6nQWvYzcglbq0h+9wwE(k3n0C&2Oz*b9glm{)|1qhq`*f6D0d%*j9v|^PeM@Kk;fI`( zqSx|txzjk>v(8Itj9+yyFg$g+d>g;iKMkTo6Wz_8@v*UING%?0%6Nn$`azn`T0r}szrFAr zj|eaS#o&YLbiqf|>5g6FxcY{(r2Q4W<517gJe})3hew>33Yt+1XE3K6{C@GQ7JlT; z+=D2#ojd#ny0^uko=Vm$paSa|p0#pIziYEWY3@d2lYdEA*sk{kX@W?N41XYk!=N%U zf}1V{v9>}m?l1TlCZjMR#REM4)PPg<0iUNJcG$?;AT>5lJHl?j99=QnZQr@WN{K3F)f^=Fg%oV~PQ30A@( z1cee)R&; zEv-#uq+A$^xerF$hFY=}fUNCqW`y$%8jftga*clIz`X42 zV4G$c(i5!59o|jlT>h!R5ALf7NT+)wDuVc>Ko0o3qz!W|UXc zx_%5GSLa}C_3{V$JB1-ZUykMGMyc0({Ow=+d409*&N)4NMjl-6Y+X5Uq zT%b0@e3?(M^UuBejw9VHeoo|J2ge+wm8nD8v8?tjz9j-`wZShs`U16KgyVX zdX%it&gU@}MY+_tN1y$I|MrjgMAobR+#5sq%04}lcjDptfwFPA{?^M9@3u~@Ux-a? zt4mDnojnjB`nRh$bLVA=u|buT*@ao5M(cw->sQZoRq8iRRM>o(|HWur^{$cqxi{TE zuX@(eX?HW8;PEFz`6x5>Dy@I@Jw7X~ru8MGbn5cLfq;SVKe=nq_J80+xm*6oKlPdJ z2TuM}Gv0;NFx4%O#`+#Ji4N^te<~pkG1@)kyKa2C(@~vwY1Ue%iFbDo#z?1` z?rQP<{lhoPc(<*p*U+sS6}p!dy@KBL4cpP8)`F2Vn~r=#va(`NnGe&PQcUpp^QP0e z(6e|+YZ!M?Uv%o~{;e^QviVVXasHu<%aUylx83LX8vM4W%P6BF;~1ua4HQ=Qn%zEk z_DlY_bSVP~?~{9<94UA=WU{%%T>7&^n4i_b2ft*0X0f=k+|nI8k?pB;d3ksa@_|om zU4Hg?jqVE8ok_DNxRZZ;d3UM78cmYH_%oB{(WYWo^H-xIKTfX&yVcQ^+tj@cb zMx58!@bpj(g?8VCCsHU#jTg4IpE6Uv`0ml=?2#9)gr! z?n-V}*urqIOWR#STR?~=aJW4YeT<$w z7(i0EzrQ@|hj%LS;kck5uhD43)LsU2fBlZ!J!W!&`9HQDRn~eR#5d;nJdY}g79zr<))Y@aQJn>>8=AugE6Ec7JjPu08yQB8qGdOq&0g2 z{A#2^^|sj*u4AxJsHk6vm9pCDyDGM7Mz{1Nh4SH5DW0X@qTVU^?s^n^l*hgQ)~w#- ziGUsI-!(RB$Gmw|$zI z+68k0g7PX9S7lvO)BRPn#5W$Tm1niicRgczRrJLUbq{{2BqpJ@1B|BX8VXB37yGVg zBi>sgiQh`J;IQM!otr@D zO*@$*n??5q-amQoTjg{~+?V#Y0sO z1CRgfy)9$&1a|*g7jSne%41aYoB+f5_a^%d47OvnWth5?zcf3W-smB<(vNxSq{sgY z2!4X&&y-~6Q7MfRpb94v`zg{!fhiV+`9D!k0=)JHF{_GzYUGcWDE-YdB<-vX&rT-X zD%lj=!VmkhBwfl~`AYLmKY^LZAE8jH&%4A>o51R6a9H@yHxojr4oF%p%2A%$PkZ&F z4~k7Wxd^O`&3nF_JI45TIZR4od}+N23^`~#K-;4bbMy56-qj>l2Cwo#>W`F}-;~ff zr>EECwAwM$+}&yu$40XTOo+VN+O)4J)IJS$(ZV#G@>+TiKi{u{7uoVOgG@B=MXuca z>OPDQZlPm=<<(P;18Kr6z8VQybxpc-MU|C_`P*LytNv5_k}jcSTl#q(L9dFb^^t~l zr`WJn;7_~JpWRVWv1A8S=ETzmLpEG;2QThu=$P+%{QB2dg68Gottva0V^g`+565|t zBN%(Zy}z@Y$oKx%f%CukbB+LjI{81pfYxEn2?i-P8lXV80mH2J%x!90z9mY`t#;B7 zslvvd?S)91b1JJbZkB653uJ*+=>8LO45be^1Yu=Trya!VNjx zG3C$4`ku1|K8Mu%pRf4SfwsL*{NG$wUydHd0Pyd)FK;DgXuq{o4RTtgzC{_-H?b3( z&3pNvZ~ryEe_Mb|hZ71lT)^c&1^A60%+!ihym(~P{&nwZuvYhBqgk4*bbqN0>J*Un zmnS^|*0X!%wGDs0do#AKb9m#Q3(RCvcW2iqrT}B8=|?f~twyx{B8C_oZZo>*Qk~#{ z-pJm3y0ju)p6UYWQo$w0BEJMyXruGM8<_JlUPr+_2Hq8<$L=4b-aT)#`zW(=`A7Me z-wPJrY^x_NT-0fym2CqsM3~RY5z;9+QxahtFoCL9RaISW!x;a*;rN$(kr;U;jIi%L zuB@f*9A3`c<)^jb&#M2|%BL*Qvy!giv`Y_HEzF zWVr<6UbH1yKiaed&DO|f%TJH5i2qicFCk^&_a~k2t~!tdVs^>TzYb=X`zYJ!Loqtv zojJM^Smkq&Fu?WMLz*3@9(E4sZ(W9{`?nH8FShOkotqgE$5dmRqG~7{Lw(I$-(-Ys z3#@`m$QD@KL(K~P{xHpvWBmX15zuynfZD~sR@`8MDs%KRHHmVEzYpVed<5Ik*8N}n zIdv}WH~Eh-oqbRGI^$%UaB#3;O4!I05Uk0=pBO!%zPwlc`+jxazMTpNdirAB3*SPO zW7IzlDjxokzV*2j4PWYD)!g#TL9w&yrPnA`qfMzGw1|E?Prv$#n@@T*c!lPHhtxj& zHR0@Sxsg4dednak`!7F}ozk%$qf|uIiJ8#@j7GL_auSPi5*b0F7c&lK==Gg*qW&y) zLE?t|L)kfQhww|5E>x(|bjO6Nk~B9q4R~#A)!$kj=_%N7Be7=Hi*Go(w&z89KC0_v zaqhR17GIyTzNo_bt=+VB^PR?nQt@lTXn8&gGU&vwsoC}WM2ZLPRgcoP9>bUeQq;{1 zTL7BeoN;O&G5pf6n{QTieI1q_|1}f=D|B>ph#tLHbW8NfSAsH?_P?DDDqZls@HzDT zYgu!*yYlu0)A1+2d9C8B)@s0;b*ar}+v=vNy1n7o;P|v?P_VUO^}M#Z?C>Sw;G5#x zIE%JHc&fuAIT4!lqZ{vq{y^RU-91d3QA|W~v_icc#`mI=n`*Tjp z>4}P<@g&!-hW&okN1Hb4pw#-{W{G!J5oLI?qJRH^-{~!eFQ4#P7l%@W+)J^Hu7MOpRkJQqZxOuqe_AOZ*oR3Yz3w{p(Q`J-T(moR7? z!9{Wj3)c!KbIn8pgDrXtuJB6Hc&il~=$A2@Nzoi|kz2QWq&VQ_`ps3zqp6Oq1ARAE zc&jDBCgP=5GqsOb0DEDORM5jihjeyn(r&xfajLkiWUExQY8Qp2>ULwjNnx8_Woh0Q zEAW%Qv>DXR>kR5`t)y+2&L%Q+9&EaA^Sb^T)r)WYC^@MgtjZK&vbiRyuNrMFAmYhz zdex|Cm{M_>(ZNCHT2oP`r|M3-Rio=)(rfu0>-yv^_296xCJh7ai+D$I<_$B~LdWTR z4zK!7C3HmncEpxq2~2adBApsS?ydH4eUl&ib2PQHS%Lej4}~T5Vb2?Ana|4EJgJqn zLQnprb1&(~&a?)2H?;wmYn*-F630rIZ8)(#?p>;eLP6Xk+`{6rS>CzU(=3zzjd?l(Zz3)$GH)WIK?dA z11XuC6XP$>)=qy*oV1cN?iw-w(jwzfU;pu0mffq1WA8?sE{q>Lv*lf|Fof-3vRaLo z3mz-`UedFNc|*uO-q#$wE^_5)(RF^M(|831mznwT7`~O1e-Kd^RCiT2lzfBF&_+z8 z!=r~21A!h>+F!Hvp0j@9YsX($1_@id;#4lb+chCeB(rp^IQTm++OOo2+ZA^2H5=@- zIj=u*u6>c27X9?pp_0E|d~5y973CJfxe#`{$Fu_{wQ`#6-mMXWUYpM)^=vP7D6~yF z`9{W%FS)}}G{~(X!q^>aWmUuJ=nJ1NvD}{1uiB_V9(O$`X^UD8hCFEtqV^@P{gk$x2$# zC+_%^=+)w8**VU>6A>8~PRH24O}tC=u<1MTJFb_FQ+>{VFVJmP;P;R(j`a0+B zcMdgl%v{Oa`i`2({c&Juc~pyi53@~u^8U57sfmYuUafF^tWqoMMlMMN#CLP;7VWl(1dqmy*!_KA~c#=Afx)$v2b0j zeF{~xY<-gS!sDA;T3__sz<##<5!Hcbb27WA8+8DT$i4Y4vqQZKtFNy{I9PiFh&RP% zY^pz*uH6>N9=y~u*6Gp%Zdgyvlf`y?*$lB(yoMy+#h zKRX>iC6FFoh!{`axK(*|rHwI7GhQfBlEY{*wSzKpI=f|h3}5M~88y`1xl=X0XLl)8 zZU7xMc+<|cJpNPStM1f4$uOB?mo$mk7f@AFs@MKSnm#>A^-wd91ABqo7=PJ0ckgqQ zuWzj#ol9_ZYoQ;hpPHPwd+ZD6sFL-LZr z`K+mPQZ&t4Z+#>g2Ul|CG?Z0eG_}U#`qzVG2Gc>jOLZ~a)ge<&t8$Ir9z%OuG46ID zc}-di3$`!izIoRhCy%<%?eg>2EOgjLcsw8DCk6|D{r*5XAT&j_iw1Xn z+gcWjM=fpB!ZfCOzWLSksY^1syZ+oxumKe4vdV{Jni_&Bsr^36&~4(+b$QJ(AAiVj zvF5ob1sd%6x3k`+Yx`z#bhf9be@hsOd9c82bIQE_$II*frW1Wmt!StgE<%O}O}JFMAf6BA*W(aty}#UwA*HHvCxInVWig z$EDAw$OC?uG!{w${<1d@1i5c7 z_V0MM7+FAvoC~EoDAVz-)19BW5ei7hh{*wGO^NuaNIk+oWPEbIS89!F%visgJNZhV zYN{6X$T+VVbF}N%Sy{0%h@(5NkOn6}ugiRlAcW51>nU4DL+$XX^I}c)b~_K(y0di; zC{#>}O2iFTUKHF}opF+h-Zh2cIi`4B%WaYc{ifdXmls$>`ybwpGW_W{($MnrIFpY< zzRpDBn)8NM!y2$Dg8{W0!LdMkv@Fc$@^nycbla8Q7Ct z{`UOVGVdZqfa7rgj1050?H(Ah@Q2#}7*;6HD4ibfY0LMCbmy-7!aDBo>&tuu#rwo_ zH;h02XuthuC)(>w=6if456?d?4;KY~x5x3g^ z>Z=<-PFnlyvRYhj0;|i28b7iy&-lWvf?Zqs_rukVHKHpy<5!oGyZoR>Cl`t1wbLNm z>w-!~>UInfX|AW3){24yj`*OnnI|6#D=f|L0hP5KA{RXjCNy4Y+(D&`XjrCJt)p1nWaMSY(v z%2t%sBr(c4Ozf6nS}3LAUYY6G)&0>f{=(RE&fCZOo=*SMhl_Yo-7UaHh@cdQHbERD zuI}zI%Zg-oWWo~qJA!We>J`sXIXZVIc!@)fJp6G$2=a1uYb-5COgR$0mCkiqeQp!`=~z|t>cerJ=g&`G_e{-Iy)q{=_FW%6sSP`k|6=|F z@Sv@yXN}fVt_fIlfu@O^Lxsvkc!SyGZIHYl5MVvDP3Rd|tiV#X@7!6EVp(*5t6AfR z09?mzQ=JpEy5L?SC(&ksyRrPgJE^UJLT;Hx903aM-N;;-DOmW^ZpT<)Mf$U2P8=f| zzO1HebR{kiVbPPqK2RNUogt(nQaHkJA!PbKDA+v~|zuZ){1Bra0PXFTtsLX-vo3C8f>kMvs|% za8Xe5i;E55bJ?CLEy44)xocux_fE{e?h`-m(~Ga}#qu+)t1QyHh$n?f{d;~2l2(N6 zO9wi@`a|ca?0Uc607<&1E)C2V0wTqD6N=o-wXnYPk|7CKJ(=B)3=h`voifYJFyllO z!QiM0;>UAZzF#GoLkX@I2Q)jUSa()`auaT5pudBi+L`Wmq9z7qh}>!ena==$e0w8Q zN!H%#^-S0O{nf0$oNb?PSz6!(cdCbEae!`W1gX`sSr}k1GL2SDP)E`KVouV)Zs|7u zx#pl$aax$4u=~K+fy#5KbK6VppOhshTJyLMThQmKOnR)F9M3oTep4K8;Fs2@zB2F; z5`xu!H~PCt%`18=5`B;r2xvwIqH(8UZNTnJ$Gm+L{{dVMp{t%aY(gB?bPgX+G2G(1 zBLJ8OUA@m*oOGKT{CLOuo#sX?&V^pmQIq~o_57ToQ>MVKdutP)WaMqcCaj4jtFV5*-D~#z-o*_oypNX{ zbTtP--gNt-H9w>5Qka4tg|O?n=9Dd~GRr4SHhL7BJaxWL`-$Z?e5Kw*!Xzj?25d*D z8eIw5hVb#R#@fz%%R}vtkM?ku92cFhPq?cMTQKJ~32vjX+8Z9ORJ{H73GVpm2)*3Y zj_px8j_j{)+GWI_{maodH^IgHmF8#+u4lj3?56gfJ9P#*Ev3phCc$BByDXtA$}%d< zqM>xxyNHMXJy$q}j>M}zwZTFkzOxAnc+w28V-;);$3}J;HY{t$r@3DzF}kvNi40GD zp+IAXkJ(wd?au2uhr2C{()-oFMDIT9GHNHiMlE)HfHKlJldY+rGFejoR-yEdr|7*W z54gsiOJZB?dH3k1fOpTodI=-9)X+Jo+S%Da5SFT)Fz7jTDe>t36j>Sad!&>pRs{w0rgF$_Abo zW9yybJ~P3}etbqYXhuJD;%{AU1w4jYb|(E@zXf(mv~)_niKnbe)?Mq6b~mRo+2HjX z810{l`RXwWGHNT%8fd|{#8wx>yKn|!0R&d(be%Z)j4>QMOU%Jv;4Q#(k0d>wh*Rgu z%*@7NGv(-97*n}mu+7&eey zF1vH4f59}SnSnM_aAU8&l*3b0?W(as`F1iHYEf?|mAFl(B8)IKpJiRl<1^KpF;H1g zA-?nXXv?+7)gRuupUnCT&&z6|4}-+!fl16{BX<7JZB_`eaQQ}!7|XOrcKY!(C9S!h zy9JMt)Yqv{R7Iv)&wU#XocTXVkZ zjkYjvxeN5I?OJcS${=fpHysK2S+UCIOsAavAQMO)!Mhx0^OiYk6JWlPG4)dw`ql5_ zJb+K}=T(rZzd_{)>ZrJ!@zv$O^ClM<{ZnJmo`r}@`FbneIROGJkUK(1M;I*zIPmaZ z1rQ2lffC$4H~}3V+8r4hS`3OEVM6{R^gyDX%VZ*%TsD5bBz&T|;d73C4b#sA77Fmu zLbApE_>WJ~IacKOOMb|DBKbkCJpM1bBQLR$dLN+v4F5AfBv$+a14{kb0m|A%WY9#w zPi-(zXc5Vg8=0AlN#G#tHs4(J#ji-PP4RGbO32t<38BYW)Oxp{F2P5$hlJh^4UHUH z@ioQb5E&(}SaL~4?{fDLc*ihPhKb|`hU3kWJ#eV7!KVU!8J3;r-dcC|1n-La zjB<$<{3K`f$B#?rL`7y!$D%4tm|@W{nMgVe5q#Zv6xdpxW+vz0t}kA z1i*IY_iyd0f?cOy*%h1P#X5f*0Ae~(Q8KE1mAN@yNXDOU+(|>gR+6Klb}Ev#cE#5i zXRar5jV!x;;y&cjZ{j~i<@!7W6hWZMH7Vx8OiC&$WZKZ^GG6}3ZVXhgakzI{kGAH< z(~ume1lq~G`4B7PE%sT>VYF*fbJ_!zDg!1(j9)I*bF*ZndgmEeHEl$GQr!s?+O}Z+ zQ>0eiz#_)AXHO7B32z-nv^_jL$b&7^*G`HUd>^Mt>(G#IomqwLJY@N27>SL3@Of>9 zEpn{4-}U&)v&jclyiQ3f)1nWGRXMLo6TvIAsTdVr)4#HzU7r8KaG(%S)WAhWMLPobk@Ybs4C@~-@xkV(bCL~3sco2>`a#xQ zUd!n^?HP`z$D8iDSh-WnmOs9JSh3TFUOKJ}x`-ptTM-H!bZ^mUAIzFFLzfBfX)RbU ze99p?L>B^Cpp@%xF)SvhEZkj1p%_3)BTcm)8xkAy&C5TJv+HEdZJ*S>n14#gg1fNI z?%++FLT4cFAVHc$gai6qWwJX~46$l#yjpva@slITQvA>t6ZUJ+K{^82KPw-l5Z6O~ zrMHQEr$)>xJ~XhB#w13lF05zf^N{s-7pE1T(wZ+4@>D>O4i*Jl9m8DN(VSJYQ^epv z`LS4Epima#6LgmvwDXyi9kJE(1)1?_kxspEb=g3HUctH>+W3@F?2=)F9>YlO8A&m-}NYIiyD@)5~hO}hIZ=Rjv@C5Q&{Hl8KWQd zXPYl%DO8U2bRQmXY&6MoeB zdc(^RWBU7CdNB9@NCVe{)mcfE;QD*w8K}tQ38FA-NcCm4_;7=0U(jytL4tdvWBa

`FuRoj|Sz4 zMfSp!Y~CeX8yl$HnS2i;5jj%-gw_9RkGjlWJzo6c=7fO!Mcez+XTEgG{Kz`Y6*O{1 z`9!*p|LwqmN6r47S03cE9aB|>3+fKF{UMe`Ca`9LRan9hF|~k?6ksmRH+x-XMtPc0 zUoVB3U3P#IQW7GgWar3`7P~G#~vAvF|;Yk*2wEQ}3b9rK?}6wX7_k2XFWvW#2FQn|LcQ zD8RnAAMP_akt+5yitzAs1!~_%q6I1ef+%3y?AUp5w-jdQm+|*VS9y7Pjh833wk!kD zbtvu#LQw?r0LyJhTq=1k)x z^yD+z1DiG?WH{wPB9{xSRgn#6H{2Ks0e~o&-U19h12e=;2V_r(9>55ZfwPf*0ObXB zL7lA3uj>rS);!_()>Ztu&cObW+s|hGCL=%It#z-+#Adq~=U!^Ke zey;C$Z>#;t7anRUPmjL*A&eV)zVs~B=VXlEsT(<&9Q*Wp6@K?_D|xiL5(o9q_xvNQ zuW~QJOA!Y)kLJkXXM^muUZ8ee`cd!c>*!|-MPoo95ObjQd=QC^>oo6PT|i*HXYPq`YeInuW~4;Aq+=)NQu+rd&_sUwaN_)qgH~ux17vT8*#Ir?}OR zb%q&EyawI9)LDD<_21OBNaucj^n^vI0WTJ!)v5b+lYK$jsXqNYv&J* z=J2upwAmq2nY2~MyltUtF4S3VPyg-TANlsdcLz5z69-Ac?|+m2#Am^F&s*te*T7|? z=2n{ds{(iSKUvC6ic+pk!U(WW{3_22i_19+=J9$G^wRr|D@Of6y<-S$HceZcoJWAp$9+$~8L= z2ojGhNLp5eKs}6NP9R|hYewrEo zr-mQVYGwWm8L}u&B$qj~E{a-Ojp7>!$*|M8>eYEJ4B*wj)s}E3t#e_ZACR_h$S}nu zsq_eKYLw0ONI|-Q_R}V`&mgZw-8wskHxY(1NW1zedGiTJFnZhb(fuHZ*Vi#ou3ZH3 zWanbayxTSHfpW(3zdrR}dP|<||E9O}5!^?v<3RZ~_W0zn2g9;o6Rt!q=qy=>Xj%&B zI%wSuR< zT{iHi4mMt;cCR1)QluF5ddCFw0kCFB#4H4H6~KS2_p&uwc-~G&583LA{3S)ohHC6t}LtjjLRz9_>ATBu9**#C-5secdgwcDoT{tkY%pA1T68V znMAF1P;ov|T*d_sEpxrjBm!D@bN;yMnp)IX_unj{i;nJ4aggkI7}JmY z@;oS!D_q=^A$#$6d^}gUysPvER*C%5QtIpA{cYmls90KPS)#WjP!_kL;?PDNiR^mM z{CfiRzDw*B*ZhKvv+F;DSRs4ul%R#Bc3t_&yG4^+Em5M$#+BUxM>vX;Em6J*Tu8kK zWJLs(5iv5+qbBs4D1l$^LV(Qa&9nPn)=Bm-UBYRZIXa|CF5aoQRBEmLik zK7;Hb!5qof_rBPcqrEQ&_w6p<$IVwjrG0;;h6=!gho@&c9&mVPq-ErR8W=F}HT%LD z-HNBFnbsG!)n=J_1qCRWz35^+{?l&s9_x!O0aZde`$K|*Z+aD`2Sh;<69t$m!Q3k^ zpeOY6I}^+@WEUo?k=Nh{??7y(Fg@bK!LkepD<+(RlCC7N(!R4WR;IJg9mjF{WRp1N zHC-`SDPpD5>vjJZjbj~0a+b-r=dukj?c|3c2j&xZfR=t!IZ0&glL@$E6pv;cd zzSHyX^BqEaJaDe$MMK!_z!0Nt`IRNqEtYFqLEnj-x7lLLVSWg6O$)!b6FZMPZLd8H z&5(zl2oUz3Ss5fjIrhiJdcy%?P#3PMBxMC>8RDeBr1+->J0i#3-$=R1bxmzb{84`sA5UnG7qwZv zljvSwv(vHK@YgHZ!shgNkuL zT`HjYA%<0e%m@J6F$%0+foK=ac<~lDDA@D@J6;De1qBQJ!$>t0@&EXpnzGe%&a$<5 zw`9f??VLSpURKi=^x4c;kFSzdo{b5(e;~L3l+4r14i-XZHy+E4bo+go$dn;oy$K4b zwRJkJ#oXLnM^{%@cQ1K1Uk`wCb5Z{qbi;jeS9!p8S}~*7v>){L+taUo3JxB6=1nJD z`ckVA8fi6H++6%}5sPD9=jnU3V!0_$XYGqv5{Rk| zeqg5XxU+l5q5P)r2OTMeMt??=g?gtd%Erk^;RnNYkODgM9;~7G>B@a;jY3_{{MLxI zlhby_-rVhn|1e=oyxZgkY^48S*E~jVmke0U3wIav>vp!$)Hppmb5Z%Q;FaC#50_C} z2pKWg1t@`R%?WgWW8nsx)@NT8$r}7>-#jZZCdjS z{A4K1dtz?z&i`-;KLh z30^)eczt;CAQP_KGq*@083GP0`nxB4Z_vZ8;S+~S#3pMZkZ0I(`J7Z)i*tBOYN55|z}nl58etevN*)ogas8XwZlNp2(hKo- z^M-@7uC?o+jfxo1FtBvl2?S3M$hk}U@WvKP=@Jy&R+a-hzrQ|P(WL96b>?pp{DpI} z_aF`Gu210XF2vJm)O4d-`RoUu-n=`&ne)m{i{OOJ!GN*1X$KvaF6#@1booDzf57HA zj4sMp8zT)fI%f5T_G=Ey75t&bjF$K}q$k;LZ0f&tLh}0~gSq>X(i7| zN2sQHmfx@Yxv+o# zStqqutDU!KH&d%6$0?1ZZ|z=>YjQyEFoU+y7HtMvU}<;OPCUOt$+>flW1A&EJGC^# zMh8fnN8BbLGZw=L5G`d@+$lZ>FHGvVZ7zZ&Vi(VNAkBGeK9AwArkK342AkjozG~vY z#v{`~EjRtCYi=yX`NWIowDhiW>!y-7Yg8P2nih%%em+xnbX+XsuEcI1{%QZYT>>0a z1+k(Id0UA%aEw1ywlGtWcjxc(7-Qp-7uK{x_CW zsQ0;JGu3%a3Loa(aY>ru8c$>A+tm<|=v!yN^}Qu%qmCMRor$E4t>(EH_)4kKy2#0m zCUt&kH7^!?G?L<;* zk730p|H;NrE=!BdGv}8UT^*fUt)!EB_9hw2yzSY$*N!)WP|l`u`g|5u!Mv5{-Ex$k zc6{F)3#0jn5RuM6d{9m-o^VHCZodk7vQO2X$P*(su+E9*lhmf_FSGe7?c&QpdP|y9 zr1Dvk&h2-N-TV0d4gVTNVD12sFNrbjeH>CTf;Qs8rvxjt$0 zNH+EJ#z?L$@|s%?d)@%K7IeCI@7URnmvK#v+_C0zU_T5I>%?m|8#Yy-xO*L?o5Y03sT`rK_6k?_^F7fJ$zV`xtJVrJb2)GYsFPa2vV>^`p)+DG#8_W}nrxTQt!?Z2z>o&5+ZqgHy^j&-WYk5IkCwa* zGAiY*d8iVzpcMeyx=VTc&Z~Fx6n5!~eT}v_G;DtQmS2kJs8|>X-9EWN{1RY%6JcgC z9cyg$J0+!3ZvH$~u(35RNW_KKMHzS9fA~NJpSjMR@f^7?qHGB~QdAv=62u6E_I={v z>XJn#=kJ43G!RabTP9!krB94CR^4oS-uuvs8rC7BD|vU*-PWJ z$}>D)!(=R9maQ6kwYgQl*g>{BGH)zOS#^HlcV(1ex*IL|?FL3c4<8KumWryY7_!}K zJMttjbQ%-uZI~gqKASoXD$R!+4rP!K^gcFC+Nvp4E~N7>g$M5m!#cWuAGKO?}PJvt!-m`H6-RyF^Bp+?KG6IIc`( zXjw=QT_W?%H}}%awchA8HA1#3hc4LD z^ra?Gm*bwzwTN999#u*%ZoQjZZT8$=N$NERC9Q*a*gcJ%BUf{|yALP?+1@%&lRC(T z8nDbgd&)+W77sk5i~Lvoyz~7^!^B;EcGAT&8Eb@i_ON>8-RWtOOL2=d65wFuP&E~1 zT04pzN&lJKPs%U`$B|vG-QUbaH+PR5ePDCqTdnh<+8ucAcUNP}#fWz+4EQP+VM+lm z2$gIhF`kHEJrWrnE|XdhC*U-lnV`saoBwj2fToPaXjRCY!pKf4wKkK}ql10j9J76SRbI|z!b?gVIJT{*3e(U<$$NzGR(E1U3 ziQAapD{99M|9`%gVSi~E^|2=qs_?@9A9kFit;0j>FyxQFK$0am$`)U9x8||?AgBaF zBE{C4NADf|UzC8s2Pq4lfyGJYO&DlZy)!&spJG}FBj6&?5Qw?*?mm~;Jq}-9dhE1w z0O1hOWl(symfmK~|K-()uFyYuaxD%}ZW6*4tM;TD4NMO?M6Z1JhGO6ZAj#v>3OqcN z*RhUGnPbRu_EwUI2ob&yt1ekBCd&rvwOQ@m3t9z$q%*P)%umY9X>~wmcf8EjSN-FT z|MObdNF$OXY9j}S-?xwq125;bO*tlFa6mG2@H)w*ppd;e=&ic+|8Wi9vq?AXar|-X zj19r5$RYCZPaXG1R7a71T>l=R$($|`MWI{&eP927$sxIIL~=;_q(5RyAyZYRmka%R z4@dkQ9G3eJZuRx3HA^MeC{twquC|vvLYfkIA|YX|bITJmTZgsF|DXKSF?sCkc!d7^ z0K|!%9seN(#Hv^cAYl0AV3YOCzfRwilQ~m)Xt}OUO&Y zowHY9nG-1?5$0?B#P#9Rr(7;BE@X6k1hIhCyoeaZ6VN^~;tv-;GMo?*5m5^}=tX0V zmuv0lIEY+3j2X7>+BI-K(=4sn+QevCgBdVzF^+$2byXE%U=rVt_bNayrQGH}448s8 z>*PlZziUK~iZ~2w0qInM7dlYJZG3!%HN@`(`oLt9Z``n%QUrGczt@hvvbgve2EI|z z(Zo-#yCR|#u9cM_E9gw@uJ^@3*0gNxj#F75t_7{?e>>-Dz4fiR!Xqa3K1Uy8OBdu( zyMUSnD3$#>gpPqwtv(bucL3}PGVsNop$BjZ?2FacG2N&%q?~h>;AHENq_#M7aJe78?UIF6Ct#TuM zFdFP2O`XxU+EgNM>22~@(2}<8`B0(LuhR0_3hId@$Ok1a(D1DM3g-Y6l){#!CpT9Q z{Xd0$2{=~m+V)c_N*N-Ah)NV0O2|~kNGc^2Wgbc-G7}Y1GByzr5~U28hYT4bQ!>v( zhRkH1{&Q*X@7v%0_W%Fy@xI5=v3DM8J?mcgeO>2u4nIE*$iAl078(%)xL=5lBa3+l zPPp-*uo3}BruVysPb~{*>#0W3Iv(@3aN)n%MAg7Pf8rM}8XlT3y@GDtLKD|5zdp)s zu%mnV>|TvYUYCWQttii!A*4vbtkHB&^Ieouxqo=e_YdV=7 zhIEfuNbq1X^>nh`2v>wPH8FLBZa_c3>rVF_P*U^eXTM0QC{(^}LXpm6T)`K*Bq4e7 zdxHMlqH);bR4LzM%Mg^opOq>T;Kq-B=4r@v5bE#OZbn(KKAW%cvz6%cSMC#IVe$#_ zJKz@+l+0UZ@1P^NQ;@0DyXJ-L8((*5*Z@j|gj|jOp(Hkx(Rg@REJUfIx2kqi{n8vG zWm?$oqKlReK|@H=OjX$UO8!~&xqZ@T(t57flQR>$K*Q-1jUYD=9CVPImEoa}U~_)GNlncduJ|x+n?%lh(#w>5b&%aAYR@uIv!(!r)a@*XQ&va$-38 z!iADjB04?FuzB+4{^*v3mQN&B)sy@QOdEh16a^()Rh=>a>st{wg2oR#`-+s;e&+ox zr|rX9B%rw?WYwu@?5A@k89B|3)10zBm2mLTulr^Pp3lCuEugugPWi@c`nc1_ zhKd&b_m(q~iEpz-ln3Ab)qDTLJUK2n*Nz}qH_T#DM*#M}@af9)`Kf-Zl3lj+4xv+s zhE3YSY-6*}Y~?!Odr+0RI#!Cj7<)!WuA1B|;;EooRq=>Ac+sjFTnDD4rVYJ0sg9<- zow{zjHgBSO%M>%%zn6z{W?%nIVbC^J&a(V_^bbt4Ud2D1Qz27A=-YuyuSM@2PR(^3 z`mQQuwYxl=!=>TDmW%thtq(a8-}&Yt|I(BTW&ghK>b-kK#z@0dr7I<~m&N>g+-{N^ z^fH|+-=s-p(AUd$rs}Al$%FJKt-;LO{B+9A90e8W4$s?FoRGR^CD4&*u1nRtL7ZZ8 zgRk0Dul3+xr{~^d|B${z_HM~7DJj{JGxTn^g!ZLNOcjT%X*<=5-y#WRC>T+>p9pY6P3VOG(T%^>~Znf%Iyl5yQI!LeGKWw zr+irV2d=b>YBnxOzIt}kgRZuNB}0%&fT=R&@ba?ry#^7cPWBF#(%0MSO};O;ciqvO zQ*;tj-Or_OJ{{0wk)C5KTAAaM+q3Lw_d6r7bl3d_Tk*)QoBl5rlLVHQk8Rx~u+uwZ z)>8C#uR+rAY{y`2EV+?YepOgzFkj0F<#(@%6=})s-?m>(%wMnP&Ij+n+ClfeuVW?N zOLrx1?X%M!qF}qJ;r{!CR1uAR6E;p5L%&t@4G30Lo8(z5H2=HEjBB|+4oeDF5NqI$ zO@bT7y{4O7Ff)S-7KD6!6wQfJbiTg(Ow+ve~DjNL}(h|chLNg}L9 zGY<=nkGhG9)W0vq46`OqVdH6w^Ba^c*^~yu|M_yQq4&zCPas6PEXR3Ks|Dvh4r4kd zrjsz+BBU>s;$vVaJZWsabnWiEAxN9)%QG$O;EmBwG|MnNh?a5R0&bg-)0_pfi23j< z>tqn#{*1N-LkL2|y^{#OI4Det*pt=~Zg8N160vMx^F0DHO8`Fy^Rf$i4vTSak|qAe z;*h#lcx-Rl@$x?0w|??%Yo!l5IRUU~!`!6-xL5%{)LKmXylYrA^!tz3`{(AX^jRfd z+osE3^m#z+H=*v+Lc!@h50wf1rSO3l2kRS%g33}1w>gJWs5dBoYMACbIlGe|DvB`h zfCNqJc`^Pb#48XtIDuRRHf?5Q5Qye%Y;3L0vu$ufvjAymqRBW+SLpT7u3$;WqbP%J zS12^+x~xi=vcFQ{f~|TLDAt33XW$sIl}W%A)R@I9s}ynXKMrSa)cwHck;X8(zBAS6 zdCb{EF4WN{FB5`(7*;~!GUZg&O6>tu1q5`%`O&90Jtbv(eXI&9a2^o;W}uI)L!ZnD z-={8rs=5>{0;zq*9rbSaFl>->QYKdh32T-C;s4~9wlV%ZEQkowm{)uJk;MMq<))QX zNgwdq6YQ9F)+hM{M{MWG08$JauJ^mT%ipk=>XcV@+39gf-<0}VAF1@Q-LWhsq#V|q zgxwX$&YRv`_1>bAo+PM#a9|!$EVQ@dQI?dYJhyK5tHI}z(sNI%e_i_0N*i$UJyh)H z_)0x=U1oO!yqpO+X;?EO3bVg&z)Ce*Qpic-H-KeZx zmt+;H9Ny}ubZ>*D7@?bI`F*PGtaj+owP4g#kn2pAhn0xhalJ15(`xOCk1Yb`MT)_! zWlD0WI!iakv`>R*Y)q91dAG-t^~vwqPX2NYNK}nDdA(m(X!24tGofQ6iTmuEs`)^+ zl<+Gi_VoAnM?!;=ic*$~B0mj6ESvO#F#8ma{Ch#`7MAs2$kXy%+4gnWu0Iq8j9EOI zRQrK}?pd1b7X7}m+WlwwmI|>9l~Rnh^+%S=2v4xyK>}{Rw&GcF!24| z7b6$vg25=uhYfJnBDH6K5k%=Y*%9S9&$AF1TQL*)EzX!KY~-RBoTIL%B6O9O2ljFs zMboIlqdoiu(~ep~$7-nI{rJ}${K5&(aJ)R<0o?D#w$LyEqOgAR*dm_w{LCYpBi`I& zIXVQN_$Oqwc^Mp$4AiF$IMmcIEz-we+rUs99^Vulx1`D*2Da{W#hcc;Fv?5{{jK)2 z-~5Aj^yM!^2$ZEggtQjsYCDsRj?(ko1_&~GUESUBiaLkXzNh`U^H0?s&t$*~+(~+j zzvB#yx4t`P^U>aWwUwZE9P-9DQOPH+3-z{I#KuL3$)ZRzi({{yzDx-0x!c%x%;t#T z1GuWK6POM)!WI~pvW=iA-v85(OX?5hxIi6#auEI<>1ozGK&tqa7A~SDo~{+zBb)2< zuDG0%X~z19l1scj(SBJFpe*Y zxCGoNw>kd|KcTkWq%?*!zEZ|SQhDVn)0?>+BPVh)O~30^y2`z5Mjs_QkIgLi?QzPT zrvO;5Emi*t!rV5d_t*f^A7nn*;L+1sop>gaDpPPfZN^2+M-|$&!WuU_&oBAc&t0ng zbU9GBs;hFgLCvht2^QGB%!0&r*dV>b?Q2ACcPqLm`p8P_1CtFyUoKC`FdnO;Dzh5? zW#1CBTqc8eAgK2JQ4x9Kt1Ob2RdB~>CM##vHnzSuL*Ll@0?%cZRSUr_qRk{@K&U ziyshQhc|o9JLL{~h91VQk)ev|44*Iu=RC|TN}w;%9U2I2{c%L1DzP7ikInJCy}74m z0${Rzp6H_0=r3$W6CaLosmh|Ql}&C~D_3V8F*hws~=+(4f_3#aEa_y#CSL-Qd5DbMR!|!PJAB(eLLy3B&v3a+R zjP}Ls>W$h}*{2#+7R*GfSCc%W`)_hd?W-kN+McEJTX-odj1CjIA)`oA?L9`A$+RfU z>J?F5jiK#*+TXbJspPt(IgeR~R#|1wH}l8D##edZPU!$xQk9@STzZ0WAEa0qH4(hi zfd+?O&0eWPVo%{bEsuK(N?P$-dycp1e7{l=2?wya-;UT<^y=di-xhhs{5WLe?7<#W zTX;U3I*yIwWM%Ty%&jaa0CYlo_^Voq%coKyE~kiZ*J>ab`<~BEgR2Jd7%jSHV{}CT zlzFNIALOsO79R2niw+`an=T7Sbw-P2vuA3x?R^wSMNeQDlFxRW)d}8jta#qJcRgF!G`aDQKP%XPEI%P91@U)jqCM#` z$;n4R|1Lw_N+}_AyIYR1UwU^YtP&{3=55=ep!NY`nBGi8k^Ki~roZ*V0AcEcj3a#c ziGXJie6&;4;?0nqswx#&E&KTRyutoH3`i$ub;U6hx?9uPZh6p{zOcB{iih*(Zu{bY zCI8ptF751|4I)px-{L)mXYPe6W;_)7M9?&02L2NDG?798-rV4iC`#+0YYR!cvTVot z5ILt;_d&g|xHup*RF$x&MVt#E3P(j+cq8T7cRR zK{E$22R{^UC&C$9k+p*S+c$8y{-~7^Kt!j)JgeAeS2>IxeK9Y7u5k@(E(9KYh)S}l zz#5^b|(%H=E@B5Ns5kLC@^UaY+S>$NfG z_Gk!FRL5%YgO{IU%qK6`J2~gzV4<;%TwKwX|BmS3W6Ay4)z^ld+ zy(E0*38~{eL{;1J&_CFLEgp#47=Ef3r63_Yn;VO9yd>bhdRL>d|zzxax#sh;j`B;ZxrE_ZfzN|;sVp7|G) zg6~XMa7akj%!@Yj67w|e$)W5Q|6=agb#p~@mssls5zjCBj+UJU%muj}#i^0=4SY+v z@vFV7IV(?RgxBx1)szL2vctAiZT;Z#nw4JM#Wl7V^uH?5zrkdUS34&JIs%$qyG{eI zw1+o5zFeztk)|wLeg>~!5&8eHK;JQFz}sJ?(0}I`|1sINd9y7yT>du{arN^<33&yD zOz{mozX%_^%Bskc564wE@QNB3d`nzpB) zclWvf-+=;YB7$!SaU4=r6K-xBhHV^kLJN`*tNsnPjcYFF*vSzHRJDETd-#8iX8zU4 zo3T7n(-mmibH_6ie>7?uttQV1P30e=Bk7yJugcX_um7>b(69a98f$2?5ZhP|5ypJC z7e8bg0x-594Ef=Buo@xq0i40-2h=0bm&L_Hb$(TSoKX#)@iMZqM7NG@i)3JEmdn zRd!(0yA0|-k){Ow2dV-hb``6N@=Fc)%Y-VR{3U;XkZ~vnM3ETpSA)~5aqrT5wW#tf zQplpi)|-)vGsx4&hYRZff8(D<;?O#u26#(o8!?mncO&uhP`9opBikwEB>KO?pO99v ziG<@>6sz2-BBA-egP($qT;Fb78A7;q{8#YPvmG%1aQdTjQ0TK|U{V(iSX=(_6(Q3e zfk`VgpJK^{=HuSUZFuo9d;v%1=mpTMFM>vbL1sQM#iXW7NY5kEiZ)h3hDQgply2$O zd1|<6!M)%fh&POEXZL3 zsshoES#z>3V$%Mfy?c$PQ4(Y094;UW;NjwZUQAjCVk$sC(uM_1; zPHzJ)U%nh>NN7y$k=Q}lwm7qYD!AQl@`G^lK5}~}z-Ol^Iq~0aa|}*`*cOEfJ9!PB zckrBlmw-FL<;yE8Z-Mg0>XRa|IbO55bqVPsAei={U)Kj+^6k5KeTW3*RZ>+g?&t`^ ziM+iw)&#zp&<2A%YxQXG$BQ+K(Qxi5?wJeB=#R=W$&4Z8Up_wqf1WqhJ!;4P$M*Hx zPsWkLxGMBCqClYruiml4H7F>Eh@rXJBt(3-IRC*uJq9+;9YSS1L-36bws4mPq;-Oq4qjm< z50ps$-Oq0cM*sP9hv1N6LCaZK2oO&J{*W)NYhq%!fjbcjVv)8xbbyi03!)z}XS`5Z zrn!1U1||6X%r~10e=5Yu{-ATH?W>5oz#K+RO8;0SOtGi)Ze?Og8iU?;qQGH|@FO9!2V zz=y=d#O#fFvT0BbLhDXU%GRA!Qqm>P8<5%&D@N#*&t=(|rQYhe=EhHS5|i@|uQIaK zH^41ncg2f}l30Da{g!7!kHUt!3ZX`1<4(TEBw7=X{rbrGItF$6}MFK7uLpp(nl! zeZFb^M-CK;%Fhqfq?l^714xrF-9i-PM`-W0XNz}kdbis04ZhSt$#%p{sqgw!eZ*Ce zQW;60PhHDR;Q+g2cT7l%>p|j&B<8osfaZmOT(>%hQTC+o-&I1LCY3P1)LJ~0Eb5G5 z7)&$v0IWQ8HFF$QVl{p#mgeO`!l*(^6Ak%H%Kbo%gA}gl=%lXF6(k!j&h;zjKx}Vk zRLRg_lb*YOk9k}b%vL69#(}f&gikJ0PQ!Y&&-Bjf@~n2f{QlFgo?9_VyaI%RNzow1UAs2z9Z*3XA=aEa-7N1R|?uX|6A+cfSKUL&9vq_@$4#qXp;NT z06n9?as*HM&j_u`!{hGXBish6EUA$wY0?rq@JT0vghcKiJZ z1A&y`K-CJac(U0ve$69m2>EX9+0F6m;%7_=>(IUn%(-Ka`#mZYn{G>pX)nUnTRTp? z5I*(4#BI*QCs2JdT0P}Bv&LizCXxL+H8vaWZ(SdfV@Z8@1w zm~s4Tz9wZ>go_Fx@KgQ~R>jdlQg(PGCVBp*P)e{w}{zLdwY8;P8<|;p_oCC2^f_6mFFNB`z=JjmEG1Uw}BmSahKaxknJqMy!EJjn>Z_X01SP8J8zV9u(Qd(7ziaIkPR;(S+A5P zpbFgh@15S8B)qwRRKXh_t6=p02+UYiqnim{{yuS40n@hp^b1^k^F1)hBJ6q4hatFdKPH-}3U!YLPqB7n+gsi1FDfjgH(LXC-U86hzZ<$? z(f-GK8~NhaW(u&=K&OLaY&gn~gIMvGj zk@8r?^pL>Wo+5Sv98e;nA+_(hYwPA)M3@{*+xo6Mj^D|Q6&=2G(9?GGx^hCiabgK# zwKWK#Bc!|74V)Y-#kaw?a)6hkn15Ud8x7-FHHUoQ{re9+nnNAWoq!TW9I<7=b#; z)m9K+pFqD%9BG%*EjXY(3f?3xE*=b>-z0RJH95|X#Hj~Q?Z*RzFrqZ2TYtI}x8n(w zAmQ`i^<}8f)N1xg3UPRzxmePfUCrr*El!WVS@!>z?Rc*rHI5hYt6+6SoL&(2x_vYF zdLsqRJJoRjM)sg$*h6-SaaTj%b3&OUOglXE4G}8vJ7Mrpjh>ogbirV_$a-m7+je{* zUOfGa{l4Ok8m2QzM%-{Hd5@RNV;f5`_WwfUqD@RsTaS#@MpL6sNbi&nK63plroMB8 zPc{Uq2%yBw1_+8A(nTq@Y&nprL7<-I=cDe6cs*=Cc`^0DW=h+MZ?CMLmREqbY_I9_ zBlF7cu?`oq9c6>EI&fNmw9f)R4Qv1n#)@2n=swIlAY+ryu*2JVFIOzx-K`Tni~DW*8eP5eETQ!i@l*< zamRPxGq$Bkt9jp!T=CYF8M=K6%!5{XI8-d1hmp*uwDz*0_*|bhb3{Hb{x7j2k2CnG z7$(sjUNK^jYT&6#oTFz+(Y{>j7oUoO&Klsko{^gZ-MJYAvPvkj5SmIzyCG8R8X79c zeDd*O1!BGsMKE0pmWZVhzbU1{YPet8_uQ5-WKWz?`@%Q-u)+ROH?z4i&-CQE&M zhlXcxYnM^hMQWy*7tyXww$=ecO0?BtXIQnqAKf2vaI44NT@}^wk@KV9Y?42|+c+vO z_gFUPK0?+XK#=_d?sz1$s*f;3-Ss!OkpY?V`nKlB3flnbJW9vno%wNBoD8v>F zrUe9H5IM}!-~l;>*5a9{W)mQu=U)!z58lZXlmUlMGv~g=%y5&$Wa%FJnF^p#AS@8Y zHxccJn*RLFb=N*XsteM{q!U{5Ods+84IC~UtP+N^9wFNTXA*E=b*_tx535)}^l9`u zIA;qxI@n!YTsBd$opdB|KBl-gSU(Yqtdwj%Ae#X!ehtA;O zAdoxqQs*`z869zx?+`kA87IQKe0>11-@Ti7yi`Zua|Q>>=aUAA2O?VsF7u;@b8mi2Dwt1<8!&_x9gx z%X|(wpY~K5Zu#fxZ9!s!1mGskP8#6tdGKrcj3^gAXRo3V{u@{Z1ZY$SVg zJ*oC?M@e$Wtl-Mb!=<5zOXU~-5@^?W4F|YiIBo2LJK=ZJ_%8}bu$-#c`^w)xA5Z{c z9FXEQxh3U#?L&B`oP$hUHAFNYqS6zZ-EBm5};J5}8W zsGZX+6&00D3Qs9k)&Iz;o4ht4{6BNdmt7oZ*%%CiR;ibkzY82@b>rw2pz-iKd#aRP zzM6g_@2hfO{DM()!1G{j;Wn@22hC~I<7RcAw69#ZX{4n7#GHcfYA7Ok9UG1Cq-%79 z#KF=NI-*;@3s||V9*e+7Tgti;|tZ4=f`{Ya%ttEmNDVs;p&=5Ed-Zw4xTzSU|fBFB}@so zjfZ=cMC~W{g4F2U*Js3gDdCOg`kWnjP5Ne$&h6>zs|ctW271I7MBPEG zO@+j2dR|9vuIEPW6-(&{MIBi>mNx|$e6py8f(j)#WARr;K9{g&+Pv$IPdPwAwtl@| zSeP%qejU8BeVUS|0^CrG>*2iqWYj$DkMwNd`scK?o}f@6nFMuFZryrhmgnHX!|Yz@ zKCZ=D@Py#r^kO!B&XTWx zuhLt^hqA=&9>=B3kqt)~LdZxr+g;WL&uZuGuPWk{YGone%YE>VFZYw^m9`6;NWjoV28;r$;a=3BpkfKM1mBro>rOlN&d_qBTYWyeD#1OpY*n4PN1{xGZjC10>X7>R^Jm~9>=n*6SZQQ-dT*|2Jbde! z{9>)?Y)@M3Oy^_g_EjIx($VBs981FJ$}x1X(cn${1&^n%7?V9gp8T`t&%1zexL%Ac zf}PoJrR{)Y6VbNGDJXCX32g_O=bn`%&UGeqE9q=(T_DC0;H-LuN;)D*l$=Oy#E#70CS;a!)#apOjo$TMi{BjT*m(pXga7x|=`92qEcZ`kKp+`cTy z@G_&*?atP6wjt__;o_GbG_+z#EDUZwy|4iZ1Vne>z=6*Geh(}%e0jTJDMA`AI~adF zx>gq(T+D|LUjca~=$BBzr{PsvqUA5;^z`)3NBcuvRig`_b52BnaOp2gt1wVVyQp2} z9?YA+1*@q9xNO#}4pFVC1ngDW=|Ih9FF+B0_x6Ss-xRI(3HvU2r)ze!t9H6f3m$eY zM^AEcid&b^y8&+!(K@8G9Z;$pW-BQzC3ST>V8cUra5azg^z=L+5Xhq{D9L_vwvQ@1 zJv&OVpI?2?{1?f-8O8RF2NcrOPV-*{>@u56tR>{+W+Ey~DR32@tmFMi|!jaP`|YKb8Vx__m@{mD`329z4bwRX|b(w zT%!OC-xl-l`{BbzFI|hmZ)U(|+!j5OJmACkB_qWnNK_r~m zW_S7DnH1F_IBCE{!f(&P-RpRcw_{8XF8;wr>Gt^%jlGwktwVU_NL^q6< z-0EoYUVlydq?|1`gB$KsPD8%!Q}L(<-9-L*vaYfB>q#NpHQnEQDgBa#sHI;vG>PKs zhV<6HlRpOo_HyhyMq|&vzuWiyY;cQ9ww6cDt^Te=>dABO%#wBSf%OGzUvtbhb7iqm zM{d@QQ;I#a)b7D8lvNiwYzAG%o9j8-?H+ovvaQ{A1WR?y)d}hMvypRWc;?KKi(7N9 zcZmIQmZWsy6Q!hMzj;QE>haolc#fRASLmbtflVEir(HYhhA7u{PV@UlG~73vTgtO< z_kZTeO7-_6HLJ_x$*HoBZVC=#Umx`6)Z#&H))R9}W^?^rr%aB%y2-ekwuVnt7FbJ6-gFE!X+EJ@>;d)l|8_`PiP>J8mX=b}p#?W3z*Ca5H`%%y#< zeM~fizllahYc?g;Ic?h(tU3=)XIl0ex|biU?dHck&RP84LfYN$VcENM)~Cxq$L_8j z|5o2W?t7I)nmDlm{^M@tdxbW0NR5_;F!;VR+H-Awk#?!4dLJn-u6xVyfw;VZoRyQq zL%xq5$iDHL>gD77eT~%`uZ(Bry)tFj0!s~VbV5~?<*xpH#{S-0GfT)Hj85c_J#_23<=#ILMrSB`EkeGgh&g+*h<0hL zp@g{WGsO>ePTHNZiJTlUsxmYN=?4671On~y!9)n@0(Z%|ZzV{?A@;0kH$U>)7JbIgA_zjM%9Z&#!ye!cixoAYm6 zJVmf4_IxT~&&#RR7@xm4)#&(P`#xdsInAz(OP|Kqugv*IGBG(YcJFcM&egl$HTLVq zQ1zqIdkJf=>}M;yU~w8}3a5W>j#SbqNmLtNc)xyLTD?=nkPP>9uML0vG$MU`PxAW~+HV*+m*8KXAkr(u;3@a>{@VNI{~+Mo-X{Yi9<*PU1sw0} zt<=7rH-B*3oW{A$E6&OE8o#I0KbpxDkJk2CJ2}SC(DiwTN?x!NXk^*5IG0~_zUZf1ne5otyy_QvHEAAOoP|Tv%Vn>Z z%W_5>D!!jUN5s++8BQp5nBXrW1rIQcS2|IQQf%9nVr@rkc_fmCJFC+2k(0lp*O3N- zPjic^KT6VIws?QVqpfHMcjhIs2j@Cvo>MV?xHI?r_xpDZCfQnDBXO?29@}T<9Cm+= zCm$Ugq~aIZDDmvj_|ydu^0o_wK2+}YyF_F272`YsSUfIaL{3i1o~jgY%yAYc?8*W2 ze=n{fUf`6|SZa8FeO2*XWZs+hd|>_~s(#JaIr_lu&&dqU3S@^a4q2=`riyA-cy@zj z9cf-#BQ@iyyVm{O=z|V1TAlBn71Y*kl$3lnZlm$F3vW4-ccO9F0?tYur7>ioo2|n@>;w1 z;t9L6TflM5eGMDQEQ1__p(Vj;fd?s>B{97HzV31$VsJ*TKgQOIqiAz3Ptr6lOlx z@bk&RZ4OLN)-%Rhr;52k7r;pQ*=$$gt_m)98RC_W!zGmHyA2Bu6GB{!9 zg<41F2s14WjZO_44UH@89FH~-;|2!)Ypoxgk(Op*YdaPoDt=Hr_yJoRTOZA3vb9p) z;OYUA^SVFkWOM3mCP&r@Z#o`J{_4s0KU~Kfw*C|*o8Gi}n?jz>hOO&Oj;?c{dn2N3 zBD8)Joen);yiv_(zDSY^N#%Z$e&ulrmfivnQ9V0Ynn?sR{ebJ1ULVR$6 z$B9EOt9D_kzp5le%<6ks$`wAOW&1sQwt=5N{*ZT4B#;$&-w4_aU*e|UqUj+^eB3E8f)QH6A6MVHtH7}@-B)mL1+@+ys za#Y8-UG?pgT^mz8Vm}qE8!r!foLhWp z+{2^P&n1iHeBA&0ckaBhN?s?4t8(BbxulR!c^*UHPu{7`F_Ky%TprDjWsM$)vc6J# zFQ=lS5?gzgxOT8nSmXhQ;Ga7~qOy&fVUTm;$`xktxZMy6PN=R#ZAV$bH8LNnCQc1c z&tp$E>h32d@z0+>Ct~E4m6d6B>~Ke8PFTFuhZFAtEv+>ZNRa~l3RL!*xO8TZ~adn zeUjo{bMqBs&7I&f&B*08rZ79s^^`+Yw6R_{`CEB;x%u`NtaSgi^w(Onk@v{0sZ4n7Fvn?#Red%OnX0 z7(HF_J_Fxg2IoM}z8zj9@Zi_7Z8mf6`^V{@@b&z{i}BshYOMtB?&>jie$GUw0J zk+6Skm(d|?a0kLYa5o!WduZD-Qzt1bmL^K0PNk_*oe0?LRVCwj(X2NFX|UhNA|oSd z;rs~+>CMK3e5b@a#*-dm3iYMIsSAhGLP{``s2Gckh!8NT-tFe@-le^|z{uwOr^cp1 zpG_CjJy#Wj%IP_6@E9m=6qXw|Ix9?j5KjI!Bo`LgfYWJZD5-JIKmI8xHDK=qY;l^B- z+>9!4|IVI2Uw~`D{x0gWB7u)tC*T`nXk>_@k3iCMmS;2}rPbu^x0Bm-J4xb(SAn-W;mKVK% z&}r^suujB=4lnx?#DD9K!^Kzz5a!tsNym#6x?i%v#9=^&k85L=Z9MTG@N9GcL2WZ6-E5c&x1E;Azn*N2zUP6|L?*n%Ub5h*k?O-8B6>cE)Sy)-o;o`c%A8T{w{^@OLX}Q7m zVmyYg6dWI4ir{Hx9vT|@wYK)W#PrYe5g$H$2=)ocZ1$c6ta$=aLquq6_*rf_ zAnbuchRU(5x@=-;sgvZcm(t8%XHaAL1O@-9c`d-Eq(S{`?FjM=*&4sr+Wq?(^#3@j z4y96IggJ1Lf}^^%b!%je$%;xL zGqSSw2nf(9NByV|2kLc1$^*wB>-}#AGFb2Uc?>k)TsR;m+w0~=Q;p4ypWma#L=F+v z213`?$;$n_yw-$zylEKH6$(O1_+wyv?!gcis^pp>&i>@;S$n{l*)ZA2nT zEse_ppo_@JXljj)i=*1&zP`YNI_;7z&T_xKn_;uubJ|53FDk*Y#kSGa)pZYc@;$%+ zMXq9FGG`}Hj|lS@At6t2V0tw~huv-d&;g-00R|G0!=GN@mCdiJq9%@7P|-U^bC8^J zWn^d}IKj=$4e<#Q%oOqY(h4Th;V1mt8jJXE!Q%K38 zm6w;F13$$)Qwj(Q8`1OkCb-d{-T zj7+fs5jhw~7bW4oPP`%WQ*aBJfSrHJZxPGhlh_afrTcq(2?y1aCr=8b4NW`XyiSwd zsH>~Xfl3w_|93OI=AMrqf94i=+IiA=Y2ksmrhBs7{z0K^Wno5WQLGP-U<&ef*5W}A_tR? zN%+PE54|5SBO00p(Ed4aAKI=0$T)8O8u#>!p(7T*e?h?B_qEYx&9M;?oK9Hcr4_2IR6a?(HXzuD= zQXU9Qph0+GH4*Czlt%o&XS0%AEHha5tA+^V-a4bF$9c`JYa>|AQ(HNz)o3aM1y3$fm485kZyPK*hbI+5Ll!ZrM2 ztRP-^=sW0elOx6T{=xNoxwya~B#cE+YYL=+KlCOw74e6(Xc#jFZQ?FxSnk7tG!9Z8 zF*^Z2`w~Xm+q~2`IX_b=-I;by!W81;o5Vy~*!n0SMm&~0_UV+a6bbOtaRzv)q|tFmlNJi-G?Z!bv^; z=TEXV6P_AXs1PBS{O3pd%XU>HZq{MLFQX(jdP|CiI1y75lZ4xQ4XEROt&5l4%b6*e z{c!Dk)H>vmmL`J2n?xEN9rfG$t@zwITRIt>s_P654H4+xS1|O*)0~c7r>hg; literal 0 HcmV?d00001 diff --git a/docs/images/29_StartUp.png b/docs/images/29_StartUp.png new file mode 100644 index 0000000000000000000000000000000000000000..f883ae941b5c29c2b737200cf885ff26745e2068 GIT binary patch literal 101288 zcmd43bySsY*FCxo3=}LtMF|y=Mi4|AM5Mc0q`NyUP!P}!iqa`1Ai}0YMWjT!yGy$J zw=R6%e!uVh#`)un^Nfdqz~1-1?<>}tYtFf@7qZeK1o))*7z~C$O!S^S26N~s26On+ zu_N%C_=8Ug;TxyDu&TX+m7%?puB`z^O4r`n+{)hE>l zYAl~1;wPGU{Is}hr}@~Li2ilUgVk7l1-`j2j&Ye%`vzEOw7wT%ER#8o7L~}X^gC)MOTiPQ?Em4s!AqPT5IaSzypWh9dh-2 zTjsf*w+w$a^c2{gxb8DDq8~uPubrlxP8YJURHM(z$wy93o+=yrSUtx$_C}QR-Af#n z_Gac7?{9h!^!+lO(jB99+6&4XOt9{G3xme5WF!cSnNdE_^ za5@^AWLdx5jt*6&3{ADn(#_N#K@>Uz!{cwN_2tVvcb0!=*Vo)USy5SO)}Emi#_v@c z7Z=C&@cS{TNUm0kg##FT-=v~L@OWf>uG5UIsY(*`${$}PjrZ?y7w_$Et+Z)a5pQk~ zl*^i$n#M-o;D7w&No%ao(aP02j{c9YuZfsWG{lD8wg@A=ZJvB1+Px{@%s~u3Y0%4q zn3@E;@n5twG&CA4&M!K**Y?QG+CHZA7CD)%Otl7z(7{i%V&YO#t=aW_X>S=d=x*MW zC8k$atPCVufs5Y>FkyYayxc5f2Ge5NlKlFka@ts3cv8(9dI>DG3+oYQyE3GO?@S9nUh@@OwX0Wm=HNK zZpRiFmbf$5?oWI@O3~ubu64t|VyMMxvMF(@Ju~{?p+oF?KTe8aTTS0kB_<|LZf`8@ z-xtnQDKRN&x{|`HrPrxHozre?V$hf3*X_2?2DLekGwLOaHT3w$kIPl~5wDc(?a1Wy z*!q*Z{bu3aT_47d(41YGhTmp-Zj7EUS?w}gTv}>=dGXfrmqVwjnwu4NHdpLSB*hjN z78<2EdPkf?a@BFB;?mN}utdi0;R z>CT&m849V^Z#uzT9Mf%CB=zJ7K~t=dFPq1veMLou$?`;F;dqo=j$S2UluKM!G)r$|XqHZ5Ff}o-kcT&?GdZX(Vo&;4JhY!` zseZ?1f_?q!)vI(Xc=yW;ts-rQpD$mYEH}))7{t5!t}#_9&3udM;-g28erzm_XXB!I z-P&I17jI6bNe>f{vQ;I^#rr61rDc|yZZCNaVoy>~P+X&?rq}62yEu&2Qhf>WfJ4Z`bj%5M_PKtP^GN`_-${*H~B@ z8*|M&S%t8TpA96g-MZD>NPgywt|%+)uao6BU!FM6bb*hL??-xGU)T%}Eb3dZfLR`V z@lMmegrRieVa3PL1k)*{Cg9B4O_#>%T$k!NTJx-Qb~eVNNx2C+nKLyud0i~EUe=zO*oXE<`dO14Ws#J|SxZ31k)NF52ZGC-xR&TQ0H8J_Q zzLM--vEmlbNSrPL$-ePS@=|sRCQb`34>}3jI=R&#^pv4yNH|AY-~9=~2kz`~ zp8478?B+IpN7>SeS?}RPTZ=Ts6#3F$9t9yGL_6!lL8%H!f$%PBF?@V{Y*0{;VSQBO zFpHp|AXD_5ZRk*7V4!1{(^N~!LGDwS5T*SMF2+fG0ed;fRlD#UwSm;tU>LBLc74|B z+FE*z*z@Pk1rIaC7Zk7wN=Xm5e^gU2`W4X#k4R=QIXS7G^-wraZwDe==VsT8Bcpl_ zjmDKw9mgUq8UCG|Uy4-VqrH@a$a(QccrdccHolOVsC(U)>Qa@{!)Eh`3E9m%WZ%Dk-<753+vl;S z^@d(Wx}In0WxQ3kVcqg*sE%o4oN%gEQEqWbN$W?oTfOk9>Yw#r_?)81@Z8y)TwfS= z-C1cTCM8YX*;*T?CG_(0YE70C>UUoXa9y5=g(-qWB+72qrntAevr4HN%CU&IGVAf<$M&#lO?&cf0@d#C!I1MX^V)1Kn^el5K7Rao;Im1m*`5@+ z`1>YRudW1^UK0sy8LIGaO_VqvK*}y&7tWz#X!s$JjQa!J|5T?@w9?k<%#wW{J*`e@ z@sEH@Nuk=VVyF1GKao2R9Ejw0l0HW*`6@3jPupXq)r{{btXRva7QiWasyW85VJl+d zwM$&@7ub%XNTZmk-FxAVbxf8~eU!OJ&}Ght%Tukj^J{AyR0iQ2usQqLOxr%1sHQ8& z!wvp`z#K8n5K~Y$v@smSPYRiV754X)>I-bfuk`vCM{5HhrIErE-Jj{g1;Cu^*lb_C zWq841s)dDt#J};AuFxAp2hg;|Y(B=5&#?33b0^i`MgAOHClmp>}y?q2+@yqpa8#1Nb0xSs;ra9D^nsjCvzqTEsgq;?k9|FI3Ju_% zfZ)4RVq#*jho60riT14Ugts*VHY6e;d7ESdLrFwN7CAFKGoy9-3P3%KKn71QnSfYR zk(1TRZ10wzhjbKAN>a3^IzYb$i@aWVlN5FE-Me@3uiir+P<3neG)c_QpOOTZ@5t8k z?-hqZMjjtNd+wZ4{CxtYG-av0e$S#@tA6e0a{Hr5f?i)8e4`ey#9=o=yOt-g7(oFFU28AeGWl&Lk+sgG8ytI#3MvS{YEMR#u9!t8^(Fm`s^5z&Cl zoUHZ3hK7byh0_@dp-ftAkhnCr5FUpBVQs3DZyoFI;j!evh#pqF46r)Eg_{C4Ha4(? zUfmO%`0PdU^vszvq`a;sIqHE1#VtfT5VzxRS%}sd9rdQT8dDq>PJ`j?!`J5W z3x0UlkGdREdBtIk_vf3iO?7z0!x+k+zTdy!BfDe$CCg)dUU#M=O9K;KF!@`>g< zj3oXr$1O2}heW!|Pw{_*)MpBi2b*yG9CfmgFCkPkQE+qY7F}%Uy%g^Af{mI)Fht(0 z{*P}`0QiXm{J@{n!X5(~uVw=-Ey{^yxdZQ%Ffh1`P&F@P@qr#^Zcb!)^FS0P*?rNr38!3|^v_dEXsSJl$tk&)bDF3x)L75+{73 zWa$_8RCiuxl=IMW1k>T!-@t+&4pc?;BL=VPR?-gue#TG&xXyn)%5M1c!p6pi30xZz zjGA2KQS>SrD$ZZ5u7lt3&{9PE*`K*I8QzubwYS?<>|*!#m%;NPOb+P}p#-!8`kaRe zgoTAupx`Uq-JD*51VVr9S~*!3+M5{sR|i+yYnhcr_fwuWIsjpUD<}}r={3s=`#1)?@k3&4%`nQRhoFT|3LVm&1Bzt{Ju&Y zJa`a6QxbIn^hWQv*E58JUVB^pJY@Q;?@?4E693y@(kY8!l$PvYRqJDWEty|BqjzA0 zsWb%Ny?;NMap%vE43!SY_GsDJai50we?gR`dE#zSZw6p-EeJbGkh<+B8m@>n<=YIu zQ`}!N;*T^>e0y>3hUsii0h+s!(a}+3tG18t`8Gy^d7=jZ$*31OrYnC`jfE&d%g8v> zb#?!ZM9<-kP(MIfs)nXzbZ~Ic*b0guD5!$y2?6EE1(0zoBZvcWr4?tU0x*BM-Uj@z0g z)Jn9xyjmjyg{gh zQXd^UIyF)qT=Vm13--E1j#WQjT{OQ=KS0BbL#2QwT=+In;ZkP&XUYDUeBB7Ot~eH9 zNkFQiwV}+RQ2xZ)z1g%Rzk^TJccM-27vo+Z-=1 zOk6t=54!&^4$@A?#(@M_Uw7`csU$-o7^eQR+3B(NT#Ih|asm!fZ0YW%8Q#&O(-V#H zi0*)u>}c_N{|+)tJ(iN5y+#Pe8PvYKVOjNY1Nnt+GENRe74Bk;mZU(O^QXG=WQ^V#kM&EESj<0t!AJ znJ4Y(8Y*b(0ylwsSb+~8BZ0La`*{)X@L{5##QPJXi8T{+E+FT1HHKJ&Zuh5QHs9t% zJP*Mx0?`HIQ3`0am3p|La#_Bu_ZvN<*8UyPxEC;S+f+jaVl(=68J3L94e1D3^cWp_ zL8B(~2)08ZtzvJV0~FJs@myoP?`+{TQ+xdWa@WkheBv8mbAZMwVYiF|Vb#Z@1OS|h z>&R;nMaVR1grp=SA4)y8QV|UWZ-;F0dBzGjf=7q`8{C zGtrWw0QdSDrM~x)AKVGL(lt0rU}1EXd6nHZ?}(YsD3XRW^ysdTP%HdN>OHIQ(Np9M zpZsYMo770=)DsI;B)}s^ja-KIQW>6wr+}iaUcH*ZHH!*~d>cKrbY*tS9#w!0jQKI> z1}M)<m2$W9 z-H?fDX_nznM@yE(e>7F^{=Iw2P^}=g0MTz*dX=fL?OY18_aSWiP-^ze-DU`B>{fj| zby2+B^_3BvcK4wMl>;!8yV`WS*%<06beHgW+EQU`)y*uIZksot>H>$V$LqP2Y$t{I zfBQAA+EKrEtf(r#)=%rhT4PyHY4ytLA4tZA)=FJdQm(E>rA%#vP`Y!we{Xlq@91SN zdz$(uR=tHvh#mrB%;3WPTn_+jPz=`Vy*V6wL*{K#QqujG7haD;J^qmB^5uwh#yfXZ zAs(vmFflSpnV6Ua&cJ3D!`2xF*BRD|wBXU-YHoNgEQjS`TdSwZt9XR<`xkuwO^D#s zk5p3^3a6u3y-1XtUB)9>-%Cp4^^7iZRsXye#1jYf;4}=RlC`yU>5U{>v0TgER47SI zyK^lzN`HB+a-1Aa)sqZk6Z-=X3v3hj;oi3qqw{zkWT{nQau+7k@b6W3=jPjw!d1NiWb#?r-ZGUZz>C-KvCjl4Dp zkdT%#9oObhD+VnvG_XXK$Y zi99&boFo(VgO&-32#0|$2P#(w%YAV`7s3{lgMtro*_+QRd8!PEoZfQ&d04VRSj7baP0GKi?0pZ$3M(-2mw->HRIE zn(}LATAYBDU|h#t)SkeaH~Za@rJiRQ2_@zjTZ*J7iS<6xB>Je?eQ|Iu7qu(7>ldm!}=aghhfupVX@nb5t+tTie zJ^Gw4IJg2^cpd32!7lI@h>_$v8C~P6-WjQ^)*9V^X`TGa^`uYOb z12E^h7@)8wpljHT8z>>Ov|rsHQO#h0lCZv~A$>!f*-5x%^sDOTOY^N6N4Jb8KqqTb zcr3p*{1uUsoJ>Q;X?u^BmKL(3JYWT=1Qo4S(BojN#Q>`Tq=&7@f>2>>Y%IjF4e}m+ z))ZlX5~%ho*zt~|SJF5akUX7kOK*lEq!sjmt0(twLss!;!3+WuN!xFw&*!I)quWvotc@*Kq8U5gOc>}0QvyTvm5P?Z(h9` zcdUH>M*TcyvcWuxngUL&v&nohY5&`SyU(8~42g61M@5~vni0jWaV z)N+_^tCPC2j~M(OH*-COEu{iwHo51zZr%G^z7Bu1xe(hh1ACZk^%7Scs5Oa*)JRE5 zN!2bXv@Bk@?=aV=1p<@`$XvZ===bjs1JMzp#1qT>!6PNxi?yFS&AUG7K0$AWtvd-- zmn?7-pc15cY^@et)84=31Jw>>cf~%dGE6lk`UAX9gPPYAl$cE@6(E{Diu2ol23b*C zhGPl}3OI;6J5Yt8LJ(&EBYa22*(UG>P)D@K1)f7!mHiTd{|(q{BnBWRy3l?y&I_uv zsV-a^sBXPyDE4po)g9ue)9slm#>UBoPIDQSy@e?NW?=c)ikPDpc;6k#`Tf1Z|2$MG z3=AKvHP4+DmFw59Bdu+!ucQd=D43Amf2vDWOWj@I6|`(@im)x4-R4S?fMH03usi$w zuMveY0OYB#FchU!5I(<53Vq(Ia!pdsyTmF8ewzdvaJW?>-Ta@RzHXAv; zd*IL!{ccZ)OQ>q5qoWgtyj-<%2dF+!yAJyAuZqRT+)tlTL5&FLQyvj1ImR{>r7vE* zfJ)E@0Q(0hy|lXXteE3y(0qm%^ju+h0CimCY}uaY^&2ykE2mTQ5 zQxb@_FfNBwE~nX#08wFsxE7FyzJ2>4Cx@-l5lB_4YQt>!pSTCFV4!KEm+YuG$-ia$ zw~+01Sx=T*3o%@ef?BXCQNjV@x1pJgxVSu29SF-VR8mX>wrqnUOc63VPeAzl_bCX) zYZclz!Z_Q`aDWmh_3q}^6pz7g&lXo!>e_K=25EL6ys|&|fh*!VrbmSeIyO7X@GCXVxg)WejXMloONs&?1VSZcq{{2+I$FNT=1OAgE zs||+?frp1@K!40dKj+m&pV#TuwGw;4?IZ&Uukzanr*42#kL+S3k;oFgo#I^apY-#H zlr#%03L&8B2`}Fn=-`8*5}`hjLm=FVhuyJ>L$neUgh-7*ZUA5=>|w&W0$tVzeU(7u z1=KBug=*=r!$gB1L@oswdl;<`a2pd(PVvz!PNQ`!n+qRP{&%zjrR{YwgsFeNzqJCm z$GET9#V;U035K{O*Fpo~OSrDhWjjb6@9Vr|W?dJCgbB#F6aiQRfB?}uJ;$()6k<=t z1QU?_7=icqfI~)m?u~YV=4btCrAk$}x!f7Z#KyqMwUd&fSsA%B{r?M^97Uo3Le)pj z5@PT`xD}I!K@7k4+WdAntRi9x3TBYpXRT%L{(~Y#Oes-bae*SeW-1vK{x|t+SFQ+R zkti`Hik_6n2=pizst~I8FKcUsLR3LK0~8#xy|ZJ$`o4!$;*aj&02Lfm^Z%XLJy|Y$ z_wM6w-@fVJHY(w*BKs!)&HQ#61pisWYvJDB-Va}|{|B|L(5G2=%lUY44Z4Ycc|`n( zR?}8s8|cznr)FhkAOGvKggh%TZ5}d zX06dhh;I4l(!hv7Im;TJJxd^e`t4c3gYuAZi}oRa>`yX&Pff_9!AN&m-`bL>*(@hG zcFfw0;dZzby-EfOg!);kJ*59xCcNc<-~-f+Qw!l)Jl)cdYT5U}laY(6u!#v{My*0c z;AO{&gVZ32-wz^BhgeS!a){oKm!O)Je_l~5cFsa--;<-KQXw^Kk{#3D~uzw?BS0D){TFv-(9A>fFSP$zOZo6=TeTxmLqaNkg_~{ zO2VxDdm>x6{0I`&4;>|JfwGAm)l7iEL5)?=)!I*YqCDk*j=J?=i&zj2FxwMDNs{YB?|-_Fe!F3=gyt8tH^3@ zY6^M#cB~^XC@3^!CE|0PA$<(JbzS085jSB7!{3X2TWmyB>`diw&a{59W3*rUUT0Zi7`O@C$7|o-@0M=GX~2;Gvo$OA*=z;pq*XQsKjBuRiweBs9w4kO-WS zP^emkDn|7uE9oCqh9s>sM7H?#-=q@*jk~5krCYq}{lA~LwdtMDo;h)1S-Eyzfc^Lh z*_{E~RP{a)-A8?k*{)a)YcZSJa0wY=?ZC&MPNRAm2po&tT%cl8LGTWII?<68fA!k6 z>=KcDct`-&lYV*{>B>+hBsuz5$TMK2=(Mw9M*b?+DXnVW4vz=3JMEld>~hz9VWJlF zC`?MelIxAVLi_`VbR9L^jP5GU)Yf;{sXP|_4)VYX5;7c9Nu_aw7To9tu z+iJQNj?xk+eZ*vB>2MpItL++`hlzQgppN85;4nyR2p9F)P zp8UIrpOM_{Dd~{X0FZYRSI&UD3W{E*^g+NyAucJmi}*AhWGOQEl9yjfiZw|Eq#7&M zZDT z&Q?-vAG({zZ8o;rAYc_xRFdV&K~OM7#Uh|4g7jnWv(vu)@hfu%MfQBOT2Y3<SFjtg>;x?|90| zc$7-rVE#~Lj*a@QEOO1YCAhV@yf^m1b;3V)bGZB_+j#r6u;p^?&fh+%D$A`cTNk_eon)sBb+#i08dOEER2=PqIjNH*RZ5=F;Bzk{Wa*SFUz`ahC7|4f~&4 zW$?&dNT%L)%420Ez$KF;tDVY|v-Zv_DnBSr{O3dH-@o_K-t!C^+jhN&ZOJouN8R77 z*+*h{1`nTf|4IA;6vMUZca4%t_juK@%iDDXY{eR6ediD3AOG|BXZb|oKEL|oqR^uuAXncg18MH!;01lqoF4 zEr0T$Fhl!eMBIV8_x`p;SHg9Pw=^s)a#$i_;zV#Q;i?Wobs#XAy)uEvJHK#WOEfn{ z7$@Mtne&8hOQV;JM0O17_R{qs|IM=|K zaXqQqL8yeX&MhZ$yMz%9YBrFCux~RVB`2+dB9jJX+cQ!`B#1}%6Gpek+i}phzD=1W zpqn1{?XGI~=OjGfRD+|ueDi^~HrVJYzJG@*pZ3-*g|gkvv?#Y(PTuYLa^Z{D&=vC2 zMe3(tbC%Io7^;MBzF8R*N*}dYu!gC6A8ICe$7bjr3S&s(187akVfm3st1ww1N!oQ| zG}NEI@_vyBp)1;I3JT-rE*ALBh~L z;k6x$bO&;BgDvKHa6<0;KHc2XfK~uG&?3VF=?DOSmQ9)xUc}c!0JHlY92TZd6bkTL z*4Q!fWpjD7rTkrWpRV@QWEpZx36^6-*Hk==ivWQ@wJt69UH&Qq2xG{z1lMmVuru<2 zI%NuqJtzm`A?a|hL_@*V=e{IW=?Ih=sv@Dl<x$g_Mh?3h|E(Pg&AaF#8F{+(A?tTsG5r;CE;C37&V@0gzOh^@4amKpCL9k1ass zp8z?(B|$7WV)N*cBjBrT$SMJSLMz`|5V;9*J%NJ1a^=diOCYKVoZ)o7Eq92&HvzVn zx)O6HXHd?Y=r_mpy@#mVMeZ|e=D(T&WAw$H?WKC;2xHPNR(*PfgaQm~NNWa^^CrCn zV2XN~r$^L}bzmqRnx!~W0HJht0j~IWgUACL7*C=^h4Tt*^TASFp&=O`ln$}2oq78f zfEqawzU&=>jBWas=VC`JIRRyA03#7@* z?KBKCumBQ~at3t76r}ukkD>1`kcPgDW@KR<`07bOi>(M^kB+`ED}#rFo#=q5BPjIV z>P3S*X!h;tap@VbjD}=pT9Ic$3W*s=FcfWGbDnUXV0Sw3AWcsT)Vac5G7!rPaUldO$ao<<6pZs-t}ZOcCgg3gw@U?N@+2Mf9su)JpF?+X~gI>6RLA8B;1i`6%9AjcraM!t>vDcW6N zgpk)i04eoLNfYaD*P(32E+;NQrS0^vHDm5KYb$_4F!%zn6p@VwXnHiW>fk%0LT=YE z$j7sw@m@WF26#63y~zZOP|FXYaiw2VDFs0}3ayKhOvgecoCfqKsp>kXNHR;yqPFtE|GU{dku^S}~M1Vm-(fsuIIb@E&fz!vE327qj zL-ozaNm=>L1~_8OE!LHh#}=E{s0H8bz~U0+R+`s?iC_TjOA}-)%fd~t$T z+1r04w%;m7tf$7;**d;9yV@Ks8N**lG$tx{z+aQPFPnK5&T5w1s8` zS~7se4GD3`Ltzxp?K*r!RdDjT^D8am-3Ik+_EyuTq%I1)PQHh~NP({5vNSdcLUv2A z3||U#m>}cJX1&+$H8Irv1WuC#n8C6C(b$u5un?dlW~4RCuG-ap)-bW-_mq6u=f3=+ zizn(28N5>vG``?7JY6(fSey8b5vp)l0!q<*9xd@Ar=C51s^8t8p~ZdvE*=t6^IwHz ze6{mbFn?GW_7uWOuVzcuv^`ckjkrKP zWe+$3x6q!@_1o2bmxRnuO1^cGFYH!+dW~A-ECGf_5A-n5t}=li*Iux@j`(H>duh;8 zUKZacvn|;b#3XsMXL&=Yb4* z<~zXDeT2mGSKpU*4mG?u+N{SPp zJqSK}gqM9p3Yv=mGw(ZpfF|FBz_|i878P)^lqo@pAQi=5<`3<4DvFxj3G;J0XgypzG2qktMmXPGgwBFegu-yiy`Nba;A1V#2AkS;5R%8 zAhi8{zHU=SV#x(XLYS+U1TM{C^hOCLgb{2~x<6SRpcaS(7ZLE`om~=LlJS2P0^05i z73MQ2Bm?P^>1+-XLr7RyD$K|>7} z0k2IeNYp0K)FeF|CQ02nv+5pM+Y73cL0&g8avJgeaT;-wp97l#NInRfic3f|8%2A3 zK#n|Ea0sMR(L%GBj-EJ-V=xkGl2#!a)wH*Bl!YqO0KwNwc2J!156SG;6ve^)>pk0= zOg2@pWs0H7Mn^xSjk#IEwD0sYE>FJ6X)aR#B-MRf)V6S?in}ayMrQ>bzM2;mT@O%Su5 z`TC|I#<)+({%CmJhpH;k6>#g4_*bO=gJ+~U;gUVrz{&WoOv>jZZ$oYvbx&h*%Qp8< zt(vH+v+B@Ym_R2Np|5VK4a>nX1f^A4kt&_|hg-XJGCiZ4cnNHoRcpyld4&$N(-iKz>-{`2|b_G$BoO%tEEr{0?-6pY87;?X@R>HRMePkdO%F7MD_j$L2Ea&*t-fVC^#ltseP7 zxL{Oa0Zeve>4A~%UBX8ZPGsK&G$BzFCJ0hl80?}KP0h`?2VV~|LIn&d)bZuU&s+7$ zpuLCjxP0DRok@d4c%OfFJs$aJ-kL!$zFzCBRK_ZQp`L0 zmdDmmF(N;X=lbB$B#-Mh@)yOBYY=sQwQIXcfoHU+WEL39^LT)DW0F5evxole=zCOd=OM;(`Azyz)tmNXzUHQTzo{Qmu zkuu88!W2OEq(da!b0+m3nhQJejlLv?2O5J>(*b~|+IDWoie5;=?C$IHm)GhdxjDL5 z-?8Yi0m4rU>;wlnSTHgvzd=23AbK}d>dDyl2alw4iWU8-ctJQ7VlON7oKN$|oQ`F( zrTj!qpODAol}-XkCOS_$>BxKA$v;l|d&=WX;b{IoZFahi0&WJ(_2&|JgW&I;S$73P zabV^3y-7&?ZSXup>iQ^wDyjQu3GsKw^#?|TmbEHG^R{WPJl;X^{48~)$o*TatjNs_ z{X(soI{l5i$Qg!`GB7}c&c!SM1lqr%6oe!J$UlgaYffMVTM^B3Gq^mBg88cCj@h7N zdM^b%g}?6@Uzf5}+L1zZXJDMqH>xK`y>STGP^CchMjj3aklRgQ&ALK|>h*IK31d+gM;qYOP*lLOS-lP6|BVM1i3|5OJc5SoCrvL^L54m|D01RNxi5;LUKuX8)sK2QK!u@>bV%?Zk%$3L zSq5zc84G9Ovf|8cA7WW_L?)-xZ;a^PHksN{>qu3iM>;r&6wq7Tpnzsns!}Cm8%d1;IPu&om>?0Z0b^+#oi)F-hpCn5=qzO<;rqOD6FpT*j0CAxc$L891Mt4kT} zbLMpZmFzN@Q<#mRWv%gV&rY~PkOM7$u7#6{>6Zzh)gqAVwewNOS;*P(v(3v5N#U0( z2Ht6q8aMUU(HuFD|E$?53XD2tK<+>%m-W=;3m1~1z?y=S6_~LDXn_Uy%Y2^3}4DGE#5WniNV+5Su|Vdpmsq`HP^pV0xb?h+%_{ES+6P$+e%F znF=;3sl+2m1~Lw9j8baWTsY(E5L9@45wOl9FC6NQ0aU}oIW>K74~ zz*?Fr3eT-rrC_Lo4#=Ja6B8T?fouk-92`CXDG%HE^VTf9O$F2emw@$$zS7!~uai0x z#w{&lVmVsgcK*B;hw(d_RFeT{7#5{k#!&_k(7|#=_w$`!33Qw$gOzP@byXSsfjCHl znp;e2pYMV3Q4t)S#Nbi-%evON3Hq4|bcIhM+PfnZMipNWLhangj-)NVu4Ir*6iebV zOFcga`#7Wvu^fw0g(j+K&rK6lryv*9Z^xqeUdy~`7~OV&?x?wx*yL43b)2w28+76A zZ1wN8LHc%pCXHmLxjx9bs)0Mu6djMmaA;LQbTV?ZanI%pfuX6sjTwADkOVvV`uh5W zZNvbYVl4O_1@ojdk|xV8zv69{?SHGg>G^%d^rChjNMhdSl0@#$6^xSyT)cH3d2-A4 zcC1=6v@`(80==&Yfg;Ll*9Fp6Jy{mX39#Wr{r$uQXs$$M_FW3k^;l@N8EN4Mc-p;s z$*MROrS*MjmplD0-W)Zs(eT(*-$<8Q`z2{WOteKPyMK<1dGA5kU~Y3Vms`hvC` zu5guydHUD5v#&Lzk4>m0fJILP;Y0*I$VciAFo1K!x-xtSCr%a8E~X1*CL zJh;8u^n8xPTKF%2z^@d_ZNM=0^}K6$EN?)str~!lEcgu{v{owWc&xm!EZbTA7L

*4XARP)^UvDvwURiRXoX0FzL+lFwYaem973 zGZ~c16TObz7XQrSD^nufr@iAAfd!Ynv_xKX%c-J=A@AN^5u-C&Y4KidWzUhYzxWLIgkvI7QU80+p6D+R1=B!8Ri|=Koa!IfB6RfIJpRZUJnb2tEUoj!(MS&*Y;# ze~5c#T7Wj-uw!?aQUsdztBq4*Wu*w55c0n?w?1-XItzR%9F`+onP|H7dP%)x?ql0; z{(hRq$Fz{HGwO! zG$a2|q^_hCPD-q*N-mIsolam4oz=hS6ALpAo^@J{XlPSB?`dDr^7lGHi*Aug4Vw9t zD#KX~{6J=q$GkouQ2pS7&yc)17uY#&FeglmR1j5sPn^<}FJz)hG};M^$XI$YDZV~^ zrliM3yy*6Mu^t*J9yYJNInFtj@D|Dr9gdb0^6f|7w0^iR?Bc>Ichb9ww({{OpqD#6 z@tsZ1UIgX#om?~U+)_`G`2y-305;px!3j@{&N^)0{Vc65Dktx{yT?DIx9}=6)VG+C zoHhLVMR{@C&(IyBe>+?sn{e5(Z^WMeMp9?2-RxRDALr%J%1ie%qHeY4dR>mRi!P3& zthX8In420Ny}sKc{c5cvW7kNJRqXzU*bcia{8S>U;Le1_QtedbuOh8<>!~)$Wu(4G zYAS25`DPy!m>gC-O%7)@kl6t0_>^<9Xf;~8B}!qT>l|4oZ_<#%fO*`n8;Lp#`7yTI z`1Et}siPi5q!aPtqs5BV^%BI)TZcDQM~qfNTAP0>I)k;9QKwWhug}#Z>s<-K_40m~ zW}o5%vSZ+75AAz)2t#?p5$RcH?Q9>-R)7T-Aa~zW1Fhb zDTAXARj3m$4ZPaW{Y~ovknq(hl#h_eM>&a5PlL{fIpPj+&Ssx(8AzerE#LJu>}fxEpM0F&C^i z%a&2IBou;EAee=~xg01`pzcmMsVB1s?CmkfU}=?SiFG+o6yGM}OA7G)HEHi2rcmbR zsSP<^yDkkc)y7!)fGVz7CU6dW0OLJW3kVHVX}+ChgU%V3 z6(eBs@PZF4hRw8f?o4z+^Si4D8-{e{hZ``sRBgfZ)KHbQd3^j#(S@V%Vklb3!Ptlt z3cVs|KUiE|M&?L_G!ww$fv>E5;9W9-?=Q3F*pFA|qs=m0T*6xEii^2gG7?sC^izdX z#Ln%fFy8V29do*878e(5`l_21E?!j8IEs&vy{siE-QKm6rM@(-mfq>rHhD&tStdIp zElLUFn5-qnSYE4uIS5B@Kqv-65Xesm?SZ+_rU@jXq^GB6U@n+Ph|nT;&oUzIve}Mn z+jdb-+v7b zcP?~_2GdUVTuIZ9v3qy(>u3wk)4(A`N6o@aIROLk9&1ap-&7QM2iovonP!_oKn%P( zU*G(qbM>gR+mw&%o7P0nSA{K^9~%THID|nv^Sedjd(ivrmzyVn`L!kTzH};5A$4XB zhmoQNL(3v!qYK+IKa#W_9G%p4)cX#rf(l9r?}v0?P+B=!Z?Y0?gd3~R=CZkRy?d8# zS6SqMvqvwb()?150TomU5pW2A0L$z5CdRO&(>tRb&Rcgko~X$;zkPxERCZTeY7EoL z=RQ313q$ql-k^(y$(}yweJN5(w7F|X%?Z;!8`N5mux!3%ro5=szWJsVCuraRgI=ob z-VJ3Op0Af0xFN*rt6JLP&tDFDH2Wg3KDWQVR)}o+aLTk!@Yj~)k@+$O3FbuMHoFK3+c)vkNynUG~Y31lIlbu*q zGX7`})_1VW1Fv7n$kb2+701#KTs0vMaO{e8026hR*>J3#y4THVy8+2n_5-|i)VLHi zL9Hnj(1Ya)XBQzOARua*t5@&Bt`f@F0fsUiac@8gka1F=^ytbq3W5r2wq*~}7UIp= zflg;s{Um_UE;{lEH8O)^=`|G?tOP-wXb1WP&UP!501(uQ8ti~6PJtXK?D0Y%1>y@6 zb+kuxH2PNM8O zcqb?ScmGa(1g8ROhlE!8eW|$Xvw=UDqsc@BFZ?eyVz%=~LS(_g4dSHHIe7;zKB>z3 z8`BdT`efXpALGY^?Uyw_gCuUt)25F#Ra{mIPJLvm%`RJ)YC!zxKwr-e;`9!|@f-B&uHP%fbkow&m;bogU5=`i}nYo{`a>)ssbz5$v=cm9#F-+a4TD*P3M? zn)(bWScr?($-0ZTWr9)1p8ASZ(y+oC)7oOwld+HbOivGG9{IY963>wF*Y{@wHMBsJGGn^4 z*BRB%aziRC0h;0O;4(D}o}ZW0I#dd8hJ{E_)ugSLXK0^017`tDd?~I1Pln! zRU1cX|Ml;%8>)wYHb4LVV}4dSJqYw7Mj%QS`Zq!ind&Bm8{-VKJ3}HOKCZ8?KV108 z_88))VNQM|gp zf6s6FJjpW&i3gYYJ$q&(9{iK7{co-4dKY})a&ROSb#^Di3+|_haI~T_6be0L_isZ- zd&SiSxzGRF(?XO~TwrfBe>OXO2tFN%){FZ_;QbTIXsngfl#odX8gYw+1dreS$B|0N zh<0|-N6Y}dC+6kQzaMM%KOQBt-#!EfIl?1FV#~_PK-@1XN8=~^6M`AEMLv7>tlIon zA&01-s(1vKgE)-LEFr{7i~tKd$^jTSDQIX(8H7$6+UZjql$2l6vjD4u3@i`AD7NCE zjTr+C=RcPIUx!(J-#6d&$Z?Cp*=Ro!EAPRHU4FuX6VuaasG9}4gf9Nud(8SYcl|E@ zwfBvRA)n5#NZ>Jb-rvzlDNjAuM|^SviVr`q#xvE8~-g!F2$Cr94mc zlty+XZGC#CC_EM0D(h~#ua^7hBAyoh6bJ;~#)VCT{)<2b zqYE5`3lNPmG9h@-q0>yo2DpvGI*<@q}uPjAuoA-Ewa z1Fy8r+>^mnbsAnRb&cqg)^Fh7B}(<>ZVRE>`9!a7G^Egb3H7FVo6{VVO9pnj#i6yf z){tYl!m6^D4Du)VRb)@cH4scGDqwTw^Wr~u-um+n%u%>fVV{%`vEr}P=7s;m+Izrr zy}$3{s?#n_rBIOyArZ0@WfZbUB4tEKWX~2-k)5mx$u4`QsFcV~va>?=-v8@K=X1{I z`x}q{@mku?iW)~+1|tb3ACYJ`{e`ZW%67&z7K$c6+{NF^Ay&UA^#1n`L>UiL#EcEp69(wQ0P3J!R zQpY`C!6azf=i9+f7*egn_6;49x1Xgol-wr?t-%rupg3@I zp734^gN7yzUM;*5+OII~FF%_uQ?~a{WP#kuq#zi0)Zv=>0Z6&)|QQrQgKapb+B;w%=Qn zdt*N2XJ&$-p3L++MU-%RyYeb}H1f^m0fF^M+pcJL{hOKl$MkLWN*#Lp*1J2mgB}T7 zsu)fMu+Jc%)rw7m`=mVXebxv(a{T!5`s<72qhk{Xb|dusuibQ|&C1044<3}f&a+&Z zqH-#DtSRHXf3^GF9`6gLwktH({$r#Dm5r3Ftd&v3K2}{)I)i^0akJqztQ1ETz8tk6 zD%j(IV!$^Ivl`=~U9PRwR$2d%8vRp`$4$Vd_nClt5R$@1p5 z6$C7Oi}7ZCfJ8;f+pt{YM3U+CpTPPc8hb#)N|CR3M2R}fu#eOPv`NdBnJo_N6T3dp z6`ZsJyX^|-(4^`I&%oyZk9$eH8{s9)!rUug0TY5AnAo1f>Il7{P#%n{AOWrcM&3Z{ z*xId;pKPQwTvLGul|JXUDmAIU|Iy-Tbi4KHQ6Ai>p$rHi@j4V=L{~&AG+MSDR1)DZ zjbJ)(;1nvQwIGOB!#;^D!l06wKFBo-Dm}RI_c^hJi8(C--fv1>pZ`<97YC+Tx5w+j z4o-NRVnqLf$QH%E3iwNpIm3kqsl55<(V(-tMVxX`iuVV(1%Wx4KBf<{uQb&2L(P&h z?=FR;YG=dZ@^r5A+~xw4<&JFGamvb4mAPXQ4T}rfxmEI;3ljFsUo{U}=<}?&xBhGI zb8>bj!R>d<;!ZzXmi@-`5m-x2v#sC?kp0Dv89&K+ox$T*$LP3|DnZ8W>yo?X(~_tA z?$kq^Rz26391u#KGin|6<2N{PR~oN&%oJuBEcI&{9tIfqm@r_)+nlbrcP z%qda#OVK)#E@6Gj+CHN{GVE{63awt<6#vg^CmhgcJjRCps`QWtWHvn*y2NY=&(3tB|2XPh$@uOsKq}P3Iwmpq~?C@2y=qEmrUHLy^ z)=PEwZ(Mu@D+L$o%&^L854mJ!9>+3qa{Zc5rRy_}RsWbXAg9#QN_G?b`{;h37gch_=?tZ(UZ>;_ z{X8~SH23G7c!#Vz3BEt*2G;KtScqPQKzSc7RS=~IYL>siu24p)kj{}fQ(z^rCxu61 zsR6zu;W~jH*S|jZ@%oLU6*Sh|h%VGDPn`D*Av8`5!Ov}@l&u}aq!vl{ zE_k*|MdK_AGl=Mj8CpaF$_k!IaJ@&~JwG?#ETC@_icJzW9AuLud)g^F^Ly9NkDQwu zl~87@vr>qdPZ9ef(Xh|?+I_J0a5m`&nzi&WI*uUTAwd3#O9y!dZB@_+3vP5mz({Dy z#Bvq29LQ5tF5V2>zJQa}z;wP56)xhK0%k*$m&pA0*958{UYd|q)0!amCDtfl+BI%5 zzsLDZZkuvkOGI0j;%E=Apg!SXwo4>huW>`^272rB}lBCnE8&E5)tqtC<$wT0Vm^a_zePb2*zO#>iaB`Pjlh&LnA;|Q>W zLkAeX)UqKpHPv|Kznvor{M#F&Ms}W}ZQ6smd#uJqj`!;4ao--L=;zbvYuH9dp0`lx zH9Z~uj{p|?&XT7Dd(wCIwyv&dy!=>jqiu!Xk%S8t_(Ts)>;plUi$>g4jNl3;HHb8F zh$TLuFcQ2LCTGM2p*HE|UxUNL3Q%|?H}=thu}lUEvbZZmsRQ>}BHSr2&tD$|LJXm& zPd6{j2exH`URQf(?Y58~JJ~hW4mK~FYt58e5CDOsuKe*1tChAn0t|S-Pi+t!e8Wyf zVi6Y?3Mti0vG3StPz2qlz4F=r3nF=H_0Bu+^dV;0>FF3CM7H1q=a0=&3cw}OZw-Pu zFKfN=2=D)D0rq9ct(P596pTFxmyIdAG+uhW{l2cR z2hWcCr=CoMo<#ThG^RZF<*_Y7))u!J_;}Z;Trbx7w<|88NJdk`{0AO>=rB+`-qeh6 zp=WZsQrP!1V@{)%`?G*O$d(n5rHy{1x%Lahs4Dmeya0jE5H5y3$xd<-p0qK%O*Ud! z(i9O}kdJ+;tyNvIYJ-`@=z%jJCEK<2>)YA2T9E~UV5>PARG^UIy`D3MAIN(1cT=b* zcO2jH5dNg7RFFB0K%mR^W2H|lR!q=~W5A$|BRoA46k(az1AE;6d*Gp)ooD+P8*Mza zI?v?qCkH%VGitdYcNu4O`N?!%)TaCB$6ID!*fNNGj~Fn5C?J4}2p$9z%wa$w`G(LR z=D@s$pM4Ghc(`^mG~;+SmSaoctXAf2=*~?Pe$uy$~dVkPvFER=ySSOR?*jTdncA%D8g4`SR%0i_3pj@c<}CMW%o4hn;76Odj-a zPcU_rSI>jX9)TVZZ)4_&H@x%w$X=;R#O*D|TGyT1tZ^r>c729!$H3L*zKXp^zjCpV zJxA{XbO$1VqM4EA9mO7=o^N{If(%mkttm$rlX!Uis|F)GT!xB*5YY^NA4{vw6V;0{ z(Cz8ITkr4lRh$GKZ#&E{xN$(-M!;RjMEn!xkj5yhseQ*K)#lGf5ts)cC*1!Mkokbz z$Lk2rs9kqdAfpskXEW9`itWcz>LRWCO`bI=*7m#&5(lZtR3^LLHjBt%pTgX10*Sr7D&I^>LkAp4n4|}@wN}98H|A$;i98Y$4khmuj!1|` z!6AV(000t4{qVYl_O>?PGP9ery_&p|a#jfuyW%K&K75cj(%?Svhh~ZA(r51IR*oS9 z5Q{MJc;LZ_1-FMZAnEW|9TvR1fU-ZGmwT9qvzAXPq#dE)xn6v}dU#Pce<9-5)=JLN z(Skndv>{=7T;3ySb-#%GAnFIw)f zlw}xx9+VwUw^_nio_<2zmKbC~eM4G$5Vpmo4<4S5fJ2GjZ`e2b-#{6)?EARqxZsgG`_A{=Bx0EtKaxxI4vTcT*!zC0JOfWpyPSfF- zcWmU@x9pk1vFYmryBss8pN92l)qBpdz2fZz#;V=HeQph5Ue5eb zQhY%_*L%N@-$}S`DfGXKYIXyuJUK5o5>%R82AZQJ0N_51k)yprLPFw;ehMFq@vTCI z9e<3u-#mE<{UtP-Ul_@=o!jYavU|EtB`UJZWS9~6|CAA)zn3pxR?f4tEV6=WRXd>0 z6oZk8H5Z_GBia^|y5tW>6}xfiqnMJfM*s3)g9uZf(l`N?(;qZ+NjrB)bR4e&ca-AX zZWPNgIuQDMczLNVP4bW*Fs@JHCz?`XvIWwoEcOi)(~X+n36QRAGCg~T*{YILxtU-5xWf8Y$r-RzZHsx^hq>VdJm-16nx3hny%6>~FKRt+I@bdFgvyBe^d! zOe<4n!ExH|k2nv5^(MHOuvYCEz6iG43mEFsYd6O&MA$;13}3Js^mOPPo|1k7muO;d zj@C}L>El=d&X7Hx2jpVRTYE879mZ1P5)W`6&ZEGEZCc{piFs;wX|U zSfY{DmHJ{nwRvf7tYoN9xfYl&V$=RZ?N*xjTIZe%wwy``I`y=h|YsjiHbS)=22BKaib93`n3C(q^=hM#;vLVD9 zw8SqN;}ZK0djBW_T8Fror>JrdJY}wFL*b@{2mR%GLrDK-S2wrAJUrj}2J}Iag=@-x ztN^2)>V4i#gou(vwRJ!C*tTyW>-v%0!COYPi3!N(aBlu}1yJoIXys|3y7<*n z6Cg)iP1ffBcqyL|eXSO`X;tdC3w!5d#SDB$+Y9KX&9AJUvO79*MU?p=u1exxS9Rc; zxd(l%^9NZNpp&GXbTgo&0cdzS0~n4+CE}W0#b9U zTFMYY4Orjzfo|%Dt-`;xFU++r;kgbuKP^o0B<--Td$0s>wuNsShC$~;j3kUJ>obC8GQm%% z#>VqX$4UYPMk}6(#maw{LkY(kVgoEhVMy5`oGo5X*X;Pl#|}u5rCSh3F#|x zWHVLT6ZiCoIC=}+G~yN{Xi{gCa#wwAiu@pFrEre#8xtTzP{n&$Bfw3uaBu`7MB0Ve z!Muhr^%>S~U@|OL7vf%$VOIbKx6}Qqf8d4QQrNgp6+BrKi4x(H5i9M_VgwTuq9r8E zVA4hf?iqwmk4c+Fuk>^>Zfi@zlvldyDUl;{PMorZ!u7GK8=5ju!#gq5uC&<`oOvYw z#N(M*>l2X^VaAYdCs-PO-8&Rkj<#{#o@zI@K2v!V-nqf_u=bHn2?CqruZheFmhutSaFncaZW`!x$46Z9Z9A)v z+YDY*Pf)Mwh<@<`PfiEI9A85Hpt^A51ao=5iRFiA-77zb^Xv>d!V#(e8lo}ES*(b@ z&Duu`JCpQ2AfBJPpJKDi9AsE7{fz#C(P3sGu`MF~wZt3)0mUlo#106%5TblUfDaR$ z>k_mlVkXXd*%6Z21Lf7+^YucQVDLMTSp;QWI9Y4&b}!owBcjNzYo z-tK#;Ji?Nvte|6gplM1aFy!)W7m}OkX&3tT$jlguoKe7;-m)>Rxyhi9(CgBG>+Z&s zH;mnRpG3xfSlj!3{yByZFkRYy$AyMWu3z$UZ39%kt$Og= zYB_ydptjO)o{h+^hSIm$4Ud>er`0V%Bt+ixwzMDKrF(^{iHhx1KVO1Gr?JW<4cA5N z^Te(bqHDIV;N_y>PdvaUPCrpzU+ot*?gYjnqbU*;IZ*Y+!3Uz*5K=+Skqq&h)CR$HV_ z%93SaO*H5D~r@Xvm8?64S;H3_7F{vCRPKH_;v+{Ez~J0=S)cm5CY zwBP9oYS%Xn<|nVszLInPD7AOCJ7Uvb;~0JA6^(R1xc|sP{@~dEs@QrH`|jxh=Y=>p zF24kn?>YVl-hF@^gszYDfB+#au??Xn{`r?Jq#w^F>(~TY%eX7wZzb@X9h6@o+!()U zuTet(#@I}O)T^ie2?hw=Wf3xctn>mV#?Oey_n83J3Umn}M&o+*gkc1O2PRI=%8G!n zutZX|#FBi9j$QguwsNsy_n<6_?#bW~?B=|7KfqL^b!pMM1ryTb=rB8JVxR{7T?c{* z6!;OClG3Wew}|I|f{ABQX95xGTp*DzQefiR%q!vb^J{bca~L31gt8U-c^h7-ejYll z+eg1NxwqbuIK93OYbTQwpw;u~<3I=r-PtGd|5&*_Maw45aNkXRps`kgYA*iCT(8bt z^MpNB@Z-dzyu3`@T#vAIJT)U1oqP7D5zrVgFc3n#8C-EP1`PjW{o|+C4Np{_U#O1` zirdulD~mDD;@bKt_4S=eS&*+zMczQ^wC;z@i+Ea|3vcFXRld~*TD3Pgb*r6sm676s zlj_0yeM$2Ni=KH(1)R;!Z5*AbJqYyE>UVx+Byq_3bW(JU-&TYZg*i3K9p)-|siW3l zvYehNW9+%TtTskea(;j(`p0jLw1Ie)K7oh?i6g(vjD0vc*W3H=mdi^;en?ZQ>r>)P z71Eg>TYg4c`;FX--zJ^;9%oXRmL20*Xoz``Z8=D>kV-jJiI(VBN(Qif>ojJYo8&Hfak>U zF@tLhap9n5UY_s&LZ^#B0N2ksk-k>7uh?lf>>kOAEAS$zic6@+5Q?FW4%@L>*G(Z( z)w3HVQg6&i9f;J|tvBG5Y6{!qX(Hyz-uM^q{Ir+%nE!^hBp$s+=7pKwt2u9GIW~Om zKTdxpv9o=cp|YwlMERE%3)2FNn$Uv$pq5somR7mltnvml{j;4_K6`#1Ht6##FJ%I! zXVaREr|p}gE*=0n+hy}zXR>w{X6?0z`o6ATP}QeC^jhsD zi&jC^<4m;|@UILZRpGLh91>w zihC?2?l>W>Rj(`sBF1+v7}_0yXupjF%Q>BQqo4T@shK3zttVt$5IS-7f;4%Lx%!mQ@!2l+Vu-V zQW*v;g<;%ZMJA%_xb!l#`TGavc8$k727b(U2xr@`*u6kKFnry@$J>x;e%H(_nrG`^XrS4y~pT-9bWOzE6TnozR}u4>d$ajo1LHbOVRHenMi*bk`XJbSLANwV%_m!Op)rTU{c#;9slgB<*jvNuTT1R4_H$O&1c88Pu0rR%D+nX zC@jgpFFw=!0YQe)`7QRg^g&_XmL*ZkzlSjwCG83d^1M|W7NpE*(0Ptlnv=0YC3CYlcEoCbs>(1LE02 zy|vJ9SM~*YwwYLo@z}doRqae1oERtd?G8samVve?u+ocX)Rf-U9*!%mJwxTd7TeMl zZbf8d zz5k^z(~Qw|{_t*Yzmelp$>kTKuL?IypDIqjM*+{?r*8NV{hc=dV5B~iaLtQJzYS5d z+^(WX7l8`IpObeV*WUlkrEGa#ZUs z=3?Z2i26<&KDj-Z{Y7N&rR2UOIcUS`Z_x9_^*IokSoC2&p%->tM6;O{RL_ zU#zYSb(CnJbKf=Pa_t$%Ji*C@HRqOt;i>2TSy$oqX6HbCx|I}};b8nhXaW4FwDvkC zD-LHsCd zP3|MzFLp_l`emxinDrXzHx9lz7UX&0>cMYc^e?g*%w2U=K~s=~H(FuCKp8tBWuq5~ zi*`_7{?{khTZ0RAIU|!VV@JH&!s}8V-MMq(>9f^Dmw9 zsP_1_jwO>J{aj%7E%)!=E+sH+)jXlQiGd*}c^&oBJyM z3ctx6{Yggab#TK^ZG$UpW>W?_Y-V;$X43{1Z2Ua0DQC0)lI%A;vg}f4&VK*QX9|(q zxq`9`#_3O6Du_Y^!@!_Zs>>-~rV|xbDD6A#pR*}h@Pp~V>mz$tvdgtB$YwZ~N@mo) zZ5vC1C-d&iJmH3-Z-!%bd9wgZHO=0wRAY?}+uU{Inx$Z$z<#-rzuq<2+D@0X9=jad zS^F}(E$OU9QtcOTBY!o-&v(Luz<;l+np1(88X>@p!=6%?nrz$&I!O%1#_~nBE z!#y9b3if(xz!+-F7H@v(rKjL7Nf&hs^cVb!^sE%RlP3N-H6tr4i{A6SbHWWB9eVsZ z`=b_%jP3q+=b9ur{CKx+=y>?o{)XWfkt)ZXK5wAHSG2VDP@w$|z31X_#0%8%7bq7| zJbq9d|B^|ktZU@8^MVuP&K#lrv^mPGyu5+Xx}llW8DnE($;;kP#Qv9~f8^KzCZ42} z)H~zxW}%l`3N+AEp$ZDcb8hm|_?8;un`+i#nzgROr*A#W^}fh-jgh+5kN3d-+Xs%t zAbY~Ef8QA%kMh@6vq3!FHnZa=={&0U{f{pry#Lo1x19XHJf=U-nn6J#W*_9r_!SeO zv>A{oepSnVJGXkDa^XL>9CY>>rNrWcDL{+t_Kps3AD>%w#+1hK7B6H&jc)Y)r~%(4 zY_U@~1d=>x1EvuBu&j$~kMr#H2q>k{%IQu8P|wRqL!*9xheCtgao{0*qNq`5{iv*Z zLGL#zqe{W?@vLp&ad5-?>LI*z7yq1`l5!@kF3&#WD4K5WXJILZP07vcs0`7_MvtV1 zRY8Eg@r3qtW#F69s3VTuXBPh`J8kJus&GhRO(3g!0g!qLm~0K&2nxa@WdrT;M-VP- zp`+XQ7VU70;B)y2;Exz8>$VU%Q*&IT0Nd=q!Go(@aOp$1QZJaRRGo=Svz-DlXSGXhuO9jdLo4u$~$p#Zu=&&}&Wi6TwKSH}BlJ6YeN* z_m$Gr)QsUly=N0#Z%_*?=)U0-7N#XrrnWdNBRxGg?r|;J)nBr%x37 zn3-dg>VbBE&PR9Uaz_0-?d| zL%+UlYiQ7XyTE*>zE5~;Thi$RU7IXv6;j9){nwvlhzxk0;=dY z-%GLF?Rvd>JD&(i@HCWMx;)Mp#3GLup)AQnKMeC%pIC%(Fgy{mRZQjfTZiFqvCn0_RY* z&Rp0`uvmsb3*!GHJT&xSeIGlQxlJzcP)<<(-nRMBh_9xkrQR{I`9)OJ(Ti_gUS+Fj z6a@cgwQ9FnDZA;56>V#MxaTW7RUQ#KmNk}=3NQ<*3Ok$=>B|4$t@7QXINz1ebf_Dg z7v@UBMZ)2>`2-Is;72n|LV$h%w`nU_f8;MvUta5e-WujOu193~RcF4Y#Ed6_}Ee_6(``)KF)OmZ>dd?}pSm4f=w!>*6ufuNh zd>*?Juvw-pb4`y#-K!v-dM}z^<`t*Z5&|}#V&{HX)TW1O&L}_cQC6pBznx;CtZN2f zk%8*u7gAWlCb4`1B$f}5h28tCdkJ;yv!VR{sOeR}(+LZvw35~B{H0F^-WD5>HGK%xa-r04ajv@u?oS2SmK5lLN?KD=^O-XOHxX1< zS0`Ts&BVjh3VpIiqXOH1b(cld41(T?uhKgjVE2edi6pYvr3=v zZ;ylezTr3eWU{KgashTy9xb;Q^0{3{Fa3oI)Jbk3d+b8q*&Q=^61J9~FZz?Xer z_@hT}!K{?EO9VG|2=((2&V!3vT<*ph&*9$%Yz{eXk{9cv5@gX8I?rTYl z5@{WuPFh1#DIBzVb$V;=>9Lcvp^`R#c3AGF7@r3Dgf;ja{PU+SF_QD4;&W+D7$jplh4}> z_l#>c10^Wj8dLG-BWhe5Zu7pW`^>dIqh)MYNH}d_^R+B@3mPNlwccER!m$FC*Y#h* zg&W>F*AA?1$zC7K(eZ;){0AGo=h;ZBbALiiX0D9K6$39u=9(hZN)GO!`4LcWpHXhU zl|fl@>3Z*k?w#o3u=}Pl-nCs(r1;~P{p`;tZ0|jzJQMj%{?9==g8SSuCmL_8yP)+| z>Op6zeB+fMYPz0R;zkFk7GLUCp7}JZBij~6R_qBEo!GHPgp2Bw-P=JgKDADeV=svT(9EO9`=`p=+w#AIckHIQfN@cO_u-?d>` zi7R-muI|8P_H19eO!IG4S-B6w@&fb(C@*sd+jPJ9x}o>+R`LnjKc7&cIxf^O^>w#O zUrB)}_sEY=?3&+R$dgy&yL6?W)O`m=&5G*d)Kd-zuL%y~HSPWQAtALTSMueb%Sd_t zwp*wAe4KiYK(J)+-Hd@>r^_sM-{EKV=9gJ|=1Msy1Ks4W&D?*-lyg_z+A8||{X6H} z4k&a5iP4>S3EM8exWsG^5VFu-6%9h=W9C3EDbVHgpC&ziV|ZkveZk}o2YUkglUVr=0olR5CLrWu=a&=rYvvFM*vvmA*^Rh68)l8V6!T8a3`k!|MqO5*O@vu*sZu zauNn(v9Nb+)sF|%M{hv}mI6vV!nIG}1?=K8*S(m(6sf^7@*NC+)y znE~Ja3vkuhM3x{)85unkxHs%R=8g&rIlD@trWBY%6gKeK?XHR2iAXaFJ2z~4-SMB- zFsV{d0HZ)InCBt*bVosXLSz*;sD2+$BSgqF$*Z|+&huLO-j6!mBb_f3Z(NI6x}Yru z#gnLF8dksDg3^g3C@#1-D>2(O83?NFNK=bfhnVFdzEL`2Io;$UV=l(tChHw5&T}C|e z-e!sh5^Lo2K0TtJ9nZ**LWumkA@woDBeX64q;HL1m{nytj{m>%gAk2+gwisZ+||2aI8^yWVn* z!V2cU1HKn_)Tq}}^mptak9Me3K7jX7@IB4Y zeShrIWp&7WMhvDXswM@Zxej8#W2Oz%E)axYOsSJZ?Bz;hN`Xjxg>gfsH`vpZE+Afd z`}!85Y}nnDCqMzZJj0hk4Y*8L5i zF)gJeCHK+O-^8wd9W$gV^ZI4*3qGI~`pHX|7{Fm?qd->P0Gg&CXj#Xul)FIejP`6N z5X&x4@dTkD0OWTrXh8@Em7*UOdn924pOS(aatAn+UPfC4LA3qW)zdqQS{-U?bi>}l zB=jhr)-80JA8vj~(O_Md)nL&L1VK`qCF1LjJE%2wB!6LFFUX!XI}E$+F8H*#fm5+CBnw+Hb zaaU3ZWm_{d*6XH2P1TRvDU-7WWUvN~x9`x?hsD_U?-(fL?-*#itCY&nG;}3D9tvQ;APtOwn%9&T zmbi>4jvsc_83aq*$H%7t)cE^V-SIt}Nwyj3k(XwCD2Z)umy1Etz$b)}uE!a+#H>>m zK50|RT{~DLGVcvHSB%U%>+0ducnij!TqZw`fp6sKK zwsPOU)jL+9V`VFRCy|Io8`mPGLArDIOGoVAr;V@k|FB|jd=W=Wz@Ad-s)2@cZj21d zFN=@tN;rGe=3pPBpyKVnC%exHM;Ii1=oqTVH`ywu*|^77YJJ)L>Vs6Cn@vHysa#FW zqwmhZO}!NI0vRkz!r@8PZ_w27b!FFPG80m|&V~7640K+37AzYx7Ib~&u38Dps#8Y6 z>(&<_e-9ttwy%(bBj~J6UX%HR9FiN6g{d+iTdv676^g2&&nynLnDUO+MD?rRgO$Zc zR>|ku+N(131t5%IsCim&YY<=AwC&*87BA=7{a`UJpWXKEEOtGtLY^4?gMO_f!(@^05Dqm*@r z{HHLtuhb>$1@(d2rweAPKmX+3`N7rmP@=Ei8;b7(dOhMix6MMe@15?g{H7c97oHTk z@iT6T(Z^FJs}QQu9_Rw^i#bUVB6~P? zigYf@&V@$9IVrh3-lcQ_W4;%2z~gwBp7IRi3t1$6<7ZrIaJVOW6h2m8~@7N7Unr%%lK z)%9_oE$n`MV+b?ky-^UKw(3-mAE$3|$rJATFji*an*{&G2J#eUR@Qi*wtILSk~NEZ+>7h=q zs@JuZTz2twTZad>*XV*bwfm@*y^9yfMh>wD0X5@a#d&V8Vh=iJbw0To+kTupE(LBt zX{`&!El4NsEiO8|3frEaqziDrBbl{Q2LPd*`gVOiz0lzn&{1v7N};a zaAB@Z?Mfb@xr ze8X}mE@mD2Qs3yQz6ZmdfSd)q@iqW(x`@s}(RBqc8l=q=P=`D%&Ai_BSj1TvyvNI! zTJ2q3T!3?PwXQuab>FgIE#FB9L4`j=tp7~sAYE#Ps@EV|d_T39tAt5c&yd3lgm;08xbNzv@yBAs`|jCvfeh59=U(+zZSU(E6RK zZggW0{lcCT-#{HIdq_5#YcR9jTr;B{P+wwlEd%v`qnf8L6bG;1`_M4n$zpzANb~XT zqWk%VUaccP$8F^r)um(3*zQ+8grZ6A@#0XWRkMLg!cYUCm&Q(H8Uf7PAw21d_2M|I ztE)?ahQ&%o_6iDH!BeA5#eN3km_S3tN|F8hZ=Zfx+!Wu4HC@3(R#48tLC`8ksQiWC z|A@lx7FAam8X7*M6gArSC-8sSXRFxanm>1iKH`(OLgc$^zMg|MKg-1ER356jQIVufpN?=@<}?DQ1^7u}%ya(VWuBgsP1}*GKk=76T_NvtiPphP&iYBU z*9J>9ZjB3{XkzSI19&@RhShaMC+iHtUnBLv=40{W&=V17r@J%gl<*Z{TEVo|2TYN- zB6hWy9dE}=N=n{d0btL`9(e!v@81d$chI{8y_yBeJ7G1a=jn{9fgwt; z8~Zu;yA@d+r#(*V$ysm0b6$;+=8h_>g2f-4`m{+YO-5}|rgMTpV_3xd(`rGEs+%;9 zJy>h0mPURSqt)ue+wtLCfAY4LeB+~#$iCcm!Evlc?+t+dLexYGv8PY=U330|74Tc;mlMGNmyu2=#+D*N=0h{; zr=|aZvl`*iSmCSLg~Q(!?wx-dc%JjRT4^qKERBhe@&*sd4=k)}!r{L^KOC6vXCK<# z{XO4V1T6qxU}Lut+yf?F8J3tU-&j+xHe)qOfrAVFZqwu;A9XAyPldypLZBAMF|;A(*H{yfrR}tq;b21?2Z9U zh(MA~K?+F7N{)g%PFfuhZ&0KlZvkeAIdw1I6RoQbM@LnuL#F9oYzl!u#uC|X&6sJ6 z_js;5vMZFwWVguN=r)v8VEgyHWbh|cXtH)K01(K-p!?o^OYUI7`kJ|| zWcOtoo=CD9>`V@&5VUucNW5}>DB%zT!vVaRBy5{cH%&KKlnp_T?SnKH;Yb;LpXo+l z$DYY|nv=EL8v*bet!S`8#T4*hIYf$c8#eDs-wz_g1C1`^Sis-O38y~UtcP=RF6}(R z`ePM|ecE_0JXs8^nQ=PUP!HjB(D`rMwd*tDjUv4J$J|#{vijyn!WaH>q{R2P++2vS zFS@)ix5edkV0cmJ&WsJ$#TgWQmDDybCs`V)(#)dm=j@P|Gb1hmL|W_x;-Igx{I;$) z$q4<%Nkw*M^XVO?f^Y9QJ8pXWvWac7(B&IR1dW~`#DpflJm1+Fh{^Y~t2;3o$*ll# zO0l0Xh0N?it7tPWuE$-OMERamMpq9`3kkt%jMEbGmF{S*(; zEqsnx<)DyiMKdL~6e3;5x{Ejv5xo%pnmJ{Tlmxvc_V7LAAbG)G7stM`_CHD65nUv) zkS>*bL(za05j~?M4udDx-q{&Y_XeE;(Nsn)<~G_tgd&Re!DwHZo`>-u2pJM^`+e?a zQ;LRgE^P9_VqW=PS*$JE>l2Wocw6yP9!n5*@ zs50A)Hj8l|Yji&ogZWlmG7^O4s#>-OP{e!w@})ZphCbfjqHvse%&8|GCC7ox-jkN^ zB&eQ4c6kI`L%BjpYLL8LOVR0mR#WGz8>eJ9<$X1LOOs)#c$A4j`FX)D4j!HWa!Igm zPlj2PgYe#+7jA5UbWo&w*#bZ=|GIAgBoL}*!e|1^FcsjDa0&GCC!daoHagAP;FLL4B6C%;`5wkj=U z&s68%v~gIMYMk+|KQmxKGuYYJsD#zfpG9%=4k{|_w%QzsnN>M4ToC5{Ss ze!K~pSsb$xnMm1facn^i0*B}Vi;9q+4tsfDxDoWyT`7xmWh>xTd_ivc%2v2GWVPH{ zk7@tcMTA($-3Hx6W?O%sX2D}pkZ?%W5ozm8C~D&(u}gllIXz_@MqZ4aUMI5?R+3CW z8fQ#`1+3Xg;z53+Amwnevtn2ffdMd8rJi;?pvvKGQj7&*4D%v~;T21P}-rHKWe^tvwU}(|p73VK=2A!l0a<8^RUY=Ii@#~Cds?6%6K`lc% zebhD4dO-KR`JbN^wIOQv!2H>}&&1pUf}~P0@*!H{y78-Anyx{YvjQ*%vAN=|ASqWh z1F7?LHQspBY`;CHreu_cpDXop8_B;dC4+7aVr^&*Uzj}v=~FA-i%`OO@S46S>#awf z?tRzbzR8iRh+cJt4U}pR2MZ+~nmi1R0z=YOK&Mj>N6Dv4!71xz%Hs55j&${** zXiB4$^9&;+V>!l63Kc=hB@@y{%$6-onDU?B)Tx6)N_%m7Lq+sm{jF5qk1C7g$&0Kp z9(r+mwl%!>^WpJFNDaSaXo^n+WDiS=pIkzzB)NyCH)v_(KHQ}}eeGTM55X|Zfh{PX zM*m`FFt>V)Qb;DO!a$>rsa6Hc;^O~48M}NuRF?Rlp|)|)(^DVvA|jDj3jY1u__QZ2 zhz+y|;2+TP`CvB*dl*eXxSA^y-pfs=i#$#oJsxYlzSFZGD8G1t$GQUFOibA02&7ti z0Y9$!4LhYS8!QSzd=>|>?9=n{1p&``6d1Vk3KwD@bhIpkCxKeJ@vf<z;$(v{TMQe?nxUx;O&4C@r+1!n<<3ct>3TI>`7ku-*zEG( zDtTjDy$7G4IW1RUloqg?idBbt)sei>txy+&$ZSnV0j3@UGxI$diJD`5KzY9qLafi| zn|KB)muaD13)TGqkIPd{4goOds`wt&hdWgEf zwgmO5B79s5rKY>2GEA`nkunn9CMf5HDqq2XaZ=a+4do}Bta_=??sZ8&s~*8H?V zllp6f+xv=5Ti-29$V{_m(NB@$(^&s&Vu@_FSd}1+W=q0^f)P+#47P}d+4V4!WejkF zBseJ)m@ZM%An&|JJVAk+@YVlFop$^4StE*FZo)E*K!(e9xSg{eXuPr%|utaiu5c`QHX;~bnj6-(q*|7S22k{x3y|o#mj~=CY-(AleHpIu6yLfHD;$OXb zRl-Achl-k0SF&XRwTY*Q;zKaH2sVRfvfNLd_Y=nh#l!$y=(WMHkg6+i?v<*M z@Z1~ki-c68sca)ib;o}@9i0pUa+nnf)M{F6Y}wm-6=aI1fGqVdR&((2?F#&I%F4vKUBMcepjDQPJsg8EP~VfEQqaQGi~)&9r1e12W++THd+ z8FokPlV|Tf+0oNx4gdBV{B^muT%gswKzzV>=uqJ9 zY0E54R`q1YbH6RSD^~`Ws>GIJyrGly<)<=;Lq2`}tOHM>FiDCMBQiJ!#w6tHmP z@l0o8!~~c2U_(K|@6RlePJR#9t~j4E`s_<)@6Q0TE1s@gqqCCa6a??Xtol?^(jF5X z#sJnKOxNgu{tz?;qaAYp=g6@LzXZq|DhJC>U_pTbc_$F)eEU7U<1@L}gZ+tLHNNE+j784d1l$uW?J+gfjO%rJ1pp z*Lho=Srf5+3m-fi4inm&>6#KTKPnfKu>Wf{R`9-g=!>1_tFX@ZZ?d zv#-6RqqCD#nPp{V)y}evfPH0-ozwM0TBQOP)3qL+z#<8Kt)p(kA+%quuQN7FSv?C5 zVc@m>V2X(h3IVp@+&9__#=Bg-P^5lT{#2B2o1?#wT$b}7%jDrJekl>jMe)Dnu1=X8 zrc=mzc-XmQ-6fW!KEwA)bs1X>XsZlEW|W!@3OSgVnD(*oKXHh5`+d?nCYNQ4VT#%H zIPq1fXMPq_K8)!q@A_pKG%qW~0ghjB+^*4J8SG`DMZIl-5vP6&YQ7DNKRHgztb5Ih ze#UD@%EA@-81Khb2CfaiS?(+MtlPGIfqyQ$#`wAVZKkhsp3fY8k7x79J+&}$Y~0Dj zkQPSDH8GsP%R}APfA{e&8ozC8EbzF@Q*7$Du!2jy{jfJ<&WE#w)T{4}{bm#gGcI}C zPQCpH3r-u~@t4fG%apV7{!}gRFD)-O6wa%lqL2TU>|9xV{#}uH-9xH`QN^at;rak) zm*FyPtsL`9EFzJ^Uh1E_)GKbr9eBZo2BuykXY;M+6ZUwyL7I;`^N}72iSnmmq3`V| zSv!4?OffPj&=C5C_tWh;dB(zzzHG{GA8b34HEXla&1CfmfZL9AYqip2*EXLTSygfD zj5`Cju+PCE`N(Ror`I(Zhvd^06W`e}0M4>)w$`kBeO*n{V?X!p`o7NcgTR=zZ1*!* zE5b#do_{TqO0^t4dxLG^c&H z?!2eIAI7r`I;Ti2%1^$1IN51HzS7#j`;9>GXk%Ub4*TNNtD8-t#j1|~h<<-vRGPI< z;gZxtFNIcQ#|mPLGz$!+Z~euWYQD0n%sJfI>-3q~qD=cv>Di(eV_6(&!l8=2RUiXB zY-5m};grKxw{|bfnp5IEPZFmvl39o>) zcz~6^!bwse4YqV-zz>VaM^W{ghDyi9aJDtJhZ9FuLtc$GMPg&9vJnGyT;2Oqr9ZPGl^Ft4O(oq9Ue~ZWkCjoHFnJViw{Oo@ zPjBNmldhMnTTf5f$$zHrTEONHQ3>0!QkBK*LhD@~uVKq(!@Hp(q?@fDf!7z!WwF*- zxhG}lC!3a4D5Tsx{k>#VnAiKv`2&?1GW#`93n4F4!InJVf|81pJDZI~N_ zqC$w2v1H0nNhlf!37IO&oGE2WnT0f85by*;3?lb7BBq znl-%VU7h0|-)wM=S*`u!%Iud;dtdDcEi>EZCqOXriBHMbXe}rfYr3IbJ{lV`JQz}( zG&{A-Z%oZ-NwZk#YrbAS`?LMN2CZAe-dqe>wU0C=y2zv3vJMmf5n#X#L zh=pP758-tm@=h7OwpiY5Nj~egDdx^c5>IwY20z4AoAO$j%Ur}W3`rC~IXtu`*dYP&@MIOV~Lg+~Y0_b|M>*`{llGx{pL zU1YLbyFP2QS0wpFPsp*)rSCYCyE1yxpSJcN{UP&y*yUDGP2phbuK#5Md&A<3FAqIY>2C737oDN+sSaM0{AK3RP;4~ApU%Lt z%-k)a46NQJ9ncPQ$umSJ@PPGUD&Xj0tHQrJ3;VRyqHlGIck~wP6fWB5!yUBOVk^s` z3rBTz$LF#!CG5K{H~5-pW%>X5Pb|+h0RJt5$4=1~Z@mAD8--mp z6sb~mJrAai-VF?Rv0hLwGbgvICr^R((3HlHDZ%rVfi2;U&qu2hTgS9UBUv+_8RXD~ zx@H(Auw-PnapupB>x<-PF-kstrj--9OmG{6pib4dEt|og`MYt^Hn!!~!@me7;Zl6Z zSUC^lDXXfhzcEd{$-WY82O)6_-J(uAprzkgWqz{aKAiFS*}8L%Ih6JzWjqpoErVvR zo1!CNa}ZXyhM{04?yJV1Glt#Us8Q1oWrHS#Hkox`S8w0@7Hu2SvrwXTNBvc;6PSv` zwt?YHPP@2Qf_kG&mhEavGiQWYHD&Gh57+<@Zo@VAu<_gEj^K4NMJ$KqUL&7A)1EI6 zeZnn3&oMfkArq8GQ!Q~LJumvHCa5Rx`6Yb(`n}xs`>G`~TL8f#TpyEj&tBHk{{yB^ zCD!1+(~CwbZYOR`;u{^Et?P%HhOac~5o3Qdzi{CK4uA`cw{O)O)U#L}TU|CkHxm#L zkZ31!DJ}lg@~bE<_&P49Pdxr#aD6J72&o&Mq^M{pTCkO7l-URCxRdxQ&BReTUFpOY z|E9FmcVCxU)q_97|JP(Wbm8ds?YfE;hp=PUPpi0IRoV51?~65lS=o@z&p0 zUHPv!Yp{$e-+1@e8`p9FCx7RkA4VNB9;chX(K}#Gy<7L4CeC8gO<{bf9j2Z1{5Q7L zcTzu1HF6vMmE2r8O-)U)sJW9@wl1>_K=BhUtLwgtQLk=OC84gM!nF|p77U7gA*Cuf zIC$k*ArQ3CfY^p$@vlbNf3dCjshp|$-Gemb&DSfGpsQB=VB^)mKpsLPVK%Z@@@GB& z0gzp_tBUHj-3HU^|F{W4{ko~q@$<;HQSY7fePYvT;HYR?2!$Rb-r?sR3CmP z9CNlk%P?`MZROhd57MRY=f?8Qrw*%R^~W^iUaas@YJTb*cjQ0VacCo}`i=IXaOS|(of1Eg{V#&pDLY`X4J_#q6?I?NSE@7>-SZkH952$;jApv94 z{K5BZ1t)v^nVV9Ik$3LALwk(2z4ZtfNq8lXCZCpd^ex_#Q zblhO$z&o@0Bu4{IF6$d7T?Rj{IJ;r324CubQiafCxgHs*`($H1-$N6)=d4Q0{y7-E zCa5Q_;*j*eD-~PXchybM+MRvs`|`kZ&v)Z_`Vw7pHS$^J&O4*TN7+U*ZP{J-3I53c zvO(zUliOZe{~BK^ypl}ltnW{rq9;N}AchFOgoA@w6ow>4vi|;lVV!~T(d2a31zG9l zV+SVsYvsH`fAsH7cyw+xY;)#5twEne!ZnTVsUT@9FeUP@>ED6Y-YP^5zAHU-p;m z$F=_ENur6H8||q7tbq;#c$W-mslTC>$GPuw2r2m0m;a8vs$xX^gqtmDX9!S-$0KLI1>9`!6`Yy{y3r#%#Gpbh~soIm+ExwQo*!eVFqK z4N1Y&u#a1h4}2D*r>D*J^=dTlNV!8>_G|j;)|_Ze8mGsBZ^N}rxZ9z618 zylZsQ-&r^H&cQFT@@%{1b69BsU^6w>wa+oyNlj##N;zcuE1%8Cqim?=i2PNEcqqdnC9~ri!eU2 zpVp%ZWkf2UXjFZ<>cNUfao^c}HNKxO8}ST1;BlCP!san|!r@82O|nK6d$M&_g?MkbuRMbT8D8iCZliej$bY%9~WSshvdZzBR{fwl4Mx9vc9v!a= zN=1`(XG4r&`S}aO7gw6{TI&k)zgW@wg*9h{y+eG~Q^`$%Ldh!&eBFJ#lHZgkNxDrT zu+?xtM|?y>QqJ&-VgzNSiM`b#hNqN+84adIX4_a!XBwwR;+gAK&3g*3VUbJ==sH;z z7?8ruV)C$Q(34khSF>`(k{V2jth^<^HmunoxniG)D8{>KndbtlZBetH0wHsq%iV6P zZ`fit)jqs)c5pOs&i2wt-r2rLrOx&2mj{95nNMf3Nj>1jh7DRW~}v!0H;);c_cW-sUr zR!isM#jS>1BB6{Zbc@vbdhM|ZTbfX2l$0fBXum>OF4uXRVKL=vX}_TCu{%|!qq{=w z$F;)?&iq^(aJM_;q~z-nzw|qTpKZ5mY&AMOV3`(a=Nep?-(7t=?PhMk)`H{`tF6Cg zLv}?p;J;~_n*O(>=TqM<3h#dJ`eZD6a`II5gqC}#tdeM_)8UTY+B4>9E@$E|B zvmNN-v3{fSDZp9RKSO{2)pM)XoA4Ex-S@Z|qZ9m{X)uM^M4ZbqAyY@<#Qr^<;>Idw z3da|Ve3wbuP`RaJ%$;A-BR_b$hGDyX;3sD>#;6iXXXy{r-%hbIyAIF>3@A#W0!O=? zma=q}^V8dBa`=X&_-f6#Yi+m-nyyrfkt@*`KDGAMLU*;0)0vS0_PXHuAT*r3nsR)h zC(8yMal9?pl(D1QlI2LpsHxT}@zkhi zWY6fd9jD+$p27J7hg*H?tuwnurUaaiJx}gw@;k%&OITst*%FbVK8z`^bES?<6aeK;YS7i13;>80MBAcrFmd`4#VM;t$ z$*-Eowcoo+5jC*7X^kDhlwap6-dx-f=+u!its=d?Y~PV;4T)n1%9CHLFgV5f%0K93 zn9+a<9#aV?MRl}OZnG>y&y@v;Qy{>Zs+f5gpK@#LRNQVKMEh{J$l(%}*?{Pfgyg(S zQLZnSIkEM8q@QL}iwk)RBIMg8lz|7l7o$IYGv0?~j9T4U6`{H2o1UJgAgG03m9r0Q zov)D%_46?jO;DMzd9zO@MX&P9>g*BrC8#H$BC^B@pG2yR3-t6>Wxsv%(cmle!WcsH_FTxDJLST^H{ARD=5cZ zskur?SNPOdnNLwCzHu#2(?b-VwUryt8PK6P2sqE|S}vTe6@O}Vh3mlN@)~D~s&Ux* z;!79H6i&R~G8#(%(Lt9s*{|dj-Bsy}AtgT))}&$0OBVT74;$&6k=$$Ly)v^=#UpiT zPJ?>hN!|oReI`lq)G*0`H4cf5wWqe5C`caA8l_x^u-KkMVL<{pw?OgY$&64;@ci=f zi>_pUGH+6Li4D@3ZA_Bi_f3lS3$nAP>xRs^TK#-E-1OMe?Pg4t>Uzni>^UW#LO~^z z>Bx}aXyqoMre|iAzM;1&BDM_&dPon9+lLNG%tmPIRq_)OZRBk1?D|QS$^*)ZD?ReA z26boLx*EQ&Og`j=K3a^}OpkQ@WF8zga@KXRIwj3tMA5@yaLJwTwcXCd_BvQ*+#PM& zRXupY@o%G=U&fi&o*naiGW4@UUUK`u$ht2%vk_LM`=$%ZAXa4L(0anYFK)44gT0m3 zC(7HG)nets&fwDpI8UnZ(?xSW;LzEi<8aSb-FsIxU1*FHf01vMDNn+wo5h`!m-5L? zo}UH$JRLhH$G)=8s6;>H&`Daug1rQ3z^@JSO#RU(c|X=L2$pbq{!o$;Qo8w5g8so^ z*)-?*&sc6UvkzOqi`H-!43kvraAJtg{1E)fU^*91A#D64Z}(J*Th13XUn3c|glZ*^ z)ZV7*M~unUp4q8GO$7)@n2M`k<*t^N-|)`iy8b|E-$+>4(aPt%i&y8&Mda<2R{*JE zu}8J_EZ@Y<0#P+(3)~9=pLCMh2AvfnHIjOpl)F>(7A`(zjQpm@Oru|!NW%O2EeC^hAKD*IEGaOne0~g_FQxZ1yu&Ko`LS^$Z$c!k%s%i?yGJL>x9l8ST&PC( z`b>^bT+=c-1I`D7I?Uw{_x6W>k;y}Bmfj^JX_x2#UbP;-@=?2i?Y-Ay8)i@Ps$ibC z8eVBV=^2adY>VT?x92bV2fs9xh^EInbqe90-08%GD%|F1{LLv(xj*FXkf+oVo(Oa(JU7p zp9l^}!6b^!yj#33OEIo#Fy7-PN7{10UfFy*hg=78or8RuR0T_HD5)Vs`d`MEcu4hf z%pAXp_m51K3y&ISMymY^cGeBZnDP9v;>3KuPMVC}tpkcLIg+b4CX@$Pbx{;<{tSMh z{}^-IZlE_Cm-V!#F&`O(TWNB^(|(mtSoGCo`zSSeSlGke-pBo;sXZ4rB$7MQduvx zyVyg8%9NW_6-?aUn5}$pKwe?j)YU`WCPjnJX|i;h-474lkxFH1a7b5F_YRKi4&gXA zkYB*OT*o!BtZXQgOYrK}@2*|(e&;meWB1;iYn;QDl~ryuvH7E5o>0w5S>TJA_DCJa zyB9ah*{s$-XK*eozPhEudrUHLOPf@!;q(+2#eGYiR7O`mpRI*j^yJRiC$@2mA0(CK zFO}3!Z0uIwP$~Qsy{$5lzOff`#tO%MM51lD0K;lw{2Hb|@VamOdhgF`#|C7^?}zxc znldi64}7{Qr2F@oCwHIFB#MjNfCjCf=mG^Qy@okm)?von=Jf@>JxEopimYQJGv8^6+Q-+i8u2 zZ|hwRT3Ft@nzp|vSbAVr!i|_rt9DJs!_5`^2{PTs7rQd&%bf zADhPy`oBz(e=#uh(T+JkEI>7V@~0m?jjz+0q>7s;2prM0Qc9ExiHP+aW%9cIbnO9U zgVB)S$FhhJT*6(u4~?Xj8PY`?Vi8i7MU|~(JHCbeT*di|3wZ-%_WdYa7Ew*pn|d-_ zTJPJ}Go80XA8413l-z3=C@^aAu+pkC9S!BtujGG!mW_jL+mqguT4|AmH{L3Zq-u=4 zxj3(8ZLK5Dq$3WwfGu_xQjS-meTeQC-PJ`>fe0tUo#L184!+vMD(@L~XE#aM5#CcA zTexX_9nWm&I)frt1{#d2u3r+@-{o&l4cKvj|Mb?|ZzY;dR$l$e`YJa|e!ikgO~f*p z>uhnic)8%Xkp&xzNy&wz$(Q=-Z#r5CZ`ZWwT8<`>;}Jomp5sra81|}Y@YhI5xH`>}6ZhDu&`h-6RAW*{ zdwG#4?8o6E{({@%VseHJ6T5f$NLIM!R9pb8l* zCx2T3A~+(#st-L6sP(HmxJo@6s97M#AU)HvN9X>i_7ssD(EH(8CbE{}^Ok)QWqxpp$SMU24vVO71Al;=~Tvz31^`HM&kSf>+7b993f;ByxB33=}kq!^ALK^ zP^>LyipCVXUcqH=7QeNli3 zfXj>zs9m=}Q&`2yx({U?AafX1jJhpqfk^ZR^A%=IoyNi;(OLvgN$b4B^2O?2__k390HbT`UuGRhsB#DK0n|R z$B`O6%CDDiHXZS!-mS?Ktvy+QKpZ#^80X1bOOGCN2LXu?wm~b(1i-@^wwz)BGZ3OE ziio~vTO=eLJ<6L*+#Jj4Joj^JXTJuO(uxTUJi&`B!m= z%E2JTGd@P5Ytu9W`U>H)k{VhqXoEE1hr9-e$_3!CEW&Qu)wQz-<#||Zpp(PdBVmJUN5`!YlgMr+kX z&jG3Gy>mz69(%erB9lT>FnE0(iK}R$@IU@Pa{Fq`#Y=aZKtvo^K%sgQ)s^GzL!PgD zM$UQI(+@_S8QepbkWBgw5p^zB))IhU9WqRr!Zxz|zHZfarO8UwfAW!&di4hqhdC85 zfi)2U`K-vBH*XeRUk&0xFVXcnzWk8VRxnPiP<&xB5qD_wIk@+C2&rEM>^9$uct-Z^ z-XORXD*hZ98Oa5h+FVe9Dbf2_{`~SwPj^0AwU%|7J&AfhX1Jf|Z6}uycp$+U>hvcc z3kUh)7MI6lXVRk0JP8>#hb4og%uOX<4^79c|87Tp+Y($}5tgMr9H+uR{jie;7UyyO z>oyxHND`nPT$^ID7v4&jL$#FNNmz$@uB_-6wRk79vfoE~9T|ee{aZJ1gBZz2JT=nh zNZbKpmz7g&*REI~r-I?N!UTX3piO5$;snZReu^iE$TUcOHRg zi~dC+@Vp=PGHU4RmV<0}rZ#Rl(R%gs zHOlq{M41rv_vlSItm(^113_nYest{5hETtI^9esYa8JmM!;hqUZ0bz?rdydw_@MOFD$_2?w1t@lc`nNj`S5y!RAvSg8-VOf6YAa~aQFuVbb@*KFe@t( z3+h+gQV|gmGmu)`(8)oGx(i_ML8DBY6Af~-VLKtqcXyX$+PA7Ury)R904+|&AbBn2 zyoY9w8)W66DzGtSuGuoVhdiYoFQR6IX76N`t;gPpA8ks-EBCaC2GI z4-V>*5I<_NCkrwnq$NAx?3y@;re$x0k%vr=*IFUnLa1FI0LkXP+ySNqg}ve~olW05 zINbGW1(YWkNS2{GyfxSFL+@DUuZtB{?O^f2t|&pyj<8c2u%3o)a51Ft@rI(uJ7IY7 z(4SOe-SeW$c7>M~kTv90205hJSvMlOM=CW(Ib8rkpY1#BX^P9%W`3-CqW7oEZD%XT z;m>N-D2&ammM4ov>Cp2cHRXiEvF}euoKS|glmJE#JRqy~{1_;>z)5NDC}$Q12fBUe zsP$sQ_Ng+1QkI}#f91oqiF?gN+pB)?`s}!R&Q2vZ{7=$h;RU)3nxX_~OsGMiI1Nv^ z5#@$f`wC$%K7m7DF~7cId`!OACj#<%R+BwU{F-)0m#vY_(vHw8&8r5b`Nq`=?<3Ljw_LZ9Zdza3G_8c=>SS>e3PXL!jo^uiq+5llUvp&LK>pfJY zx_`0%w2e|48e{$|2J(O+t^kzepQ!$ze!Ps!GkVut-(e!8BH!n=l#!FZ5WFo73)l@s zsz0)ic)2R9HXkq{(acjg6i2%BB&vL+_KOdx_$)R7a5%HgS^xGR5iI}*V|EMUESOj^ z$4~J%MVIxT9HmGuu(PcG8r_m&_$M$lBQT^G6?nKoKp`3?Yw;PP`WaW%fQGrb^hZnP z&~24tD#V6MZnT_NZn%&({^RAFuTKB?E>DVl3hzp}rZX9S=X07Xv~^bz&?dP7phoHt zmS_lRu3-L`C=!cG+?>G^>k9ybUci^p-l&B^U%2d#tSit**y^z^y$mrEiOc*Rcn9p| z2=qR3=zdh+*%lhYyMi3=p&F`U!k3@;8aRI}xr7;W8^77D?z?>^Xho2rp;^a*V2t+G zg2|Tl`BH)%z_%tby|D)|knlQ&AqX)B8w8)78igWy2y0XwKR;3Ho=5Q+c3XB^54k?u%AK20Iq6qY=+xA zF^fd%_Naaw3Kz9NT|U!rxs1JqC;=g7!&ofBD;~nm21G0Af9Gyr&&0oCTQYkx==MRC zs+Z4(x+%?fKP?rft|2~XWDtVCjEoFW2@89!u6hpnJP2;W6p6V>(skU51P(enI+8NN z8fOWEUw7Q*oNo_;nsP5V+`epw49f9GYc}28LxV)82xd$Rut$*q50iGmsYH5d~KCm?FK5=NEljQ6bx7mjH|p zMqF;Z>0~sbyf#-l*q;z(tJLqNTBGa*;sZMUrF$)M;j9 zi+m9V%uNMgQ@uytc!RUvENz?T{Ops^42CHzKf!1dEel2faY4R(Bi7NpA_~Ah#m9T8 zdCJZ>^*xhVpC+lg-&!(7NwPWD(MTgKu`eoJBxKWus@EJKEkM^pRVYHvPJKHs(7y>=v9t@*P{ z_sZ{$$%i2W3uDvxaagkhw3EP^lQ-+}9hj4y$dosV zi?hU5AG4qks$4CtWw=IIpnSS9OBBPG+KtWcgQOfwtt5RQB!ZvBD z+nTkF|HkK(KrJ7z!)~Y9Gt$)A4yfBli~Rno5BREC9DH?Cj2Ga*ocQzg-3wpY;r$E5 zME#Z)vf7cPQQ2Z#MsbhG-F8#5IWOgi+PozqHj*2u-&*&sa=RXnf)pQaNT?%r=a?t+B{%JD{5m4HLpLpu zn%bN}@KylpaJEO(^FFvHwM(PqT_sTj;8TbV)wjv^0SkV>Sr!=&4#*-l1qC_ByTQiP zlPW|E%Fz9nwxm^4AuPB-Kj7K6Eew3g8vtaaSMT0bDI;&FTy0n}@mp7BoTKdwTlccx z$RHlpwcengRIzh3{mrp+R4!vmd<*n(&D8qi$c=w((D|JAbZPJAe$BIF6qhsNpaTfk zbb)r3OD)79vcMkMVJC#w(G@knR@>m4(c)S0k%@uo86 z;l?PDH>Q}FLe$INj)~cb0s?R!`ev@kP@%Q^_~Sh#i>;xJW$q4*1Sj9LOwcyC_UZ$& zf|&F129#UMtEz<4+>wv%uzKuzU+K^(wk3x>UIZj(a`F_JnSG3DI~(zUeIH3|Ho0NO z;E6TJ!N4Bf$HIcEZ$LwGfdWW2T%D`+F7ZfsLHlIRQ9Mm&V2Sbc%9!kw<8J;BsenG2 zY~-HMg7Vty$58WFgBL`35?09K#}vcis>iBSfcYaD*+hIO*)xsh(&pr|)z=t;_ingF zhNnDHTe{+mm6Z@`3f+*iJB3II#GJ^hZ#-nvm+WR)ZaMQ}MK%t*lK>;oJThpxtAB9^ zqxBJTyF9nFO!nw@0d3ri-(Bld{p$sQj5hfa_4MslJ0=#Bo~d?6Q%L&|E+&37&w@7k z-~kU25`bFSl0u+HAw%pnw+{_RCQmV+`S7X5*|gIGN{M-;Lef6J3gZ-Mm8cje>#x-B89#S zbL?1i;lfwOF#2vqJs`;-`})h5JLEVSA>11W*U0+&ZousN)ZnrTyP=m<`PHbul$=A6X2ryO`|b}nrSOZhkX@_8vxH7`HV!*` zSKrzI!Dqu0qvFu_T3E>UjCrc8{P}NnQSz~yTrj9mR7m=0B*g`nrg{&=-S2l56E7kG zq5)gfTbkL+sF6+RxK7u&VbujIUD>2?x?|R4f-@yDA>;$Xc^Z1;)1Lh4m)Gw>Bb-%LIV|Do6MZ%Zn@jn$NYANJTV48Qsgs}z!I*! z7b_oLlqeg%aBe1-JLI`@BE;y;L;sdi2GtC5Atff;p-JLV45#tJu96^}Hblj5oPnk; zN)JSyhG;B3`+TPVF;L*4i&w0HX61_;Yd&NBnNr22tMOrft)YRQFi#ws0*9W-?=bRX5mruO3Xv)=!L_*DUzs{R-Z=WtSi=Ys~Y2M7esn2!4$4XXbW?Ubyb{tQde-IZWq`D!%J5TF!ZUNGd<_Rx1su43Z3)^#<5%p3TrRB*8tVIA z>~Sfv-B4%hiI}UxGvntUvC$@<+NNbbp$Kfj;g<^Kh+@tIw6!z2Z&s=BQ)9`T)~W+BT3_Hi&?xIN7Zr>4DYUFh918j#yDp}#=R;^FIuUuj z@3pZmQ%_^d&tIg;n#@(2cOLUWCkJ!_@}1?MpyK=eYP6!1=j_CUP_yHzO90lXZ?IRm z(z2P#cmMM;&_yirOfw^@B{_{RHai0`W11Ox+YLgL^}^ad)Cx=e*{#dsb@X!tg90d1 zUW2!%Xm$jLei?$0?@^1n4@;;Q&b$N{{tP=pvd~lj^v?oKcALsC%^bHXMUjMgE&KGo zJ=75`@}g5rbOKE0!a%|L{j$!<9ZqW{I%@=5YIm=wB#jOKo1mjutSlCD>5ht-9jq7x z&?zPIp!%yP9K5dS%l@FqP4+LoUrz@Lp!#ezqtNF8E>^1>tBZ|ne^gGrO$DBo8baI> zH{M+LtZA^PLio1&^rXu6v1ruu=H*^;;JQLelGv4~mvjgnlX}$>8`0Q#yGx0&Hl23) zESJIqYUC(UA&%BztGd3CPgAm3f-JE+>GSQ9D-^xz&q+KqLS`(-&L1)v9bVxd@PYmT zd44>%FzgoIfR!wULSV41hnbo(Ck-00vKKRr4JaR}0qzL-IAHMi2$1w!yhwqCc$K*v0B3dDarS!m#S$d z(NSx@RMF<5KohoE^EOer=^93Kk-P?_oDcTYm{yS5596GG;yJ# z9em;_yZc$S_m-q&ynS7Z46#eg$F7ktitxW0F@r51IZzF2{0WZrOJ zZgXZ{`kkt!vl0HzXPC?MAHJ#)D`o2Xea+uF9UjwOGa~llh-}xf3qjYY2&V{^@7JEx z`?{;JOLj-?-Ztqs|7_}8zQXUFQAtq=+#Cp!F%s2CQk_Pm;DBb&a-u#~eOLZI!{F69 z`e5gx|8~7bYy_K$Jt*|&VA4Q4j1vC{%2Q*| zU>`%l5l2~BIolnog+wt-TB>muU9WQvpwJC#2etr}qpqJzJNZlV!~MY^`a~4B=ir5Nk3rVpKiW6bM_(+E_UujF;ayb_#jCI~g6jpmKN^^g zPJelI?>w(K`#%0@$?+QQ&xNL+%ii(LD6Y9tFZ3@7FhUF{;{madXo!s+73mCoFMABr~$)L0e?U>TqHBJxU;ZRAjjZJmD!4*Q&)xq z_gVZ!K>C}oK#BuLKw}|B6gaZ=HKz+g)SwF`|D{l*>LkYHiX3;y%Ji?-#K^xv;*Zy< zz{GMhWF2TA8r+K^B5KO_89)cdkHr=cn@*vEiCQ{;y$SWbsvP$(r-X~q(+W_OYtpI) zok2ZPwXw0$H4qe*xbly^jjB!Db8!E&Bbu^kjOy`|?I>mYEGc3oECX+5XlP`^&8cbsG2$!6gUMbdgnNyLr9S zeLq<}LXLEw;o(h?oKjTX{*x`U#rA;m61B*^tNp0=;qM*!H!lU04lNnK;@91wyP&qR z%t=7=%0C_unOF7Rxi$aA1yTM7W9IkG{Db83KUo94@ZCw1xbE*eyaEa6-z7{QW>_-) z7l)_m9tO%3iWQJG@cm6LVOs8hafrvwQ3ny$FvFe>ps(y*7lg72L?N}bp(oAyK$x-Cv{4qU&IWVEVO!D z(Eoyl#4Qg6zKDQQLPpxdhJO1W_o4qFN!^huYd6&~-+XI}fWSRex=|`iE0Tm01yOhN zN(PheW&J#=peXFP5w-Lerz^^CvGPt;Nql^p+yvWpZr@ltz zBH#Tv)XsGYERAa@E+RK(hfH~tl&u-ji^PEg>P|GI##@K(cZN;d0d#m)1|?ZyKFsRg7jQr2bbk#lc>bszg5%n7)n1_Bk_-g-6Mcq*(XW&KJgf}(u zf>F;#@#=tzZeH%@_aOH>b8UHJBHo=6`4;HJ?YI3?j*HP>S(vcaui2f#D-Q_1Fg8@#fS?3cTuD|)Iw@S!UD)gfC0A#K2Ez)@rI*E*8?5-B76!Cg@Hd;3^oy5ov0wT=>bybwvZp>tifj4bk&hi=pU)4I z1nL#8WaE>7ZTr7GUM}KDJKLQ3!Kcl1Yo;yGBViSLUlyZsBjY9-*Y%F+_-xe(PSf(=MmQ3+}sj9AhAM~ zs0<5Z64)5pNEMYLlUuT^F6KbBQMAf3Sz6Q-fRJV_rK-T_1Tio%_cP_ntDO2w3?Q-45@`W|LrQKq?>eXRNd!LW0U{lqRfyEJw51tuI?(tf$&hP)? za@o>-hMuy1CGF3fXqj~EBIjmW75vlo#+4MBE)06>8Qpa<{V|YKtKamDaW&GPT7BC; z!IdAfAl6+@SIXXQ`XuwW`RJ?fs`DO8%;_+H7o zqv9BU3o~`y~z(IBy=u|A;LZKbd^ud4+fNrPvIsFLhUTX&roV z*Q==L#njWwDc9FY*{GvW@d=7CG!S=1LPXrdf|;QhQ;W9o?kL2vaG8%#Ls|InGF|`& zp(pk8kYWOx`F2=w_rbsV7!m5+vJkt!)_(q*^Ixe0meF-@ssHK+EQhvcgg!&6h4~t_ zOfHl2I(fI`>s%$*(@eJXKjHofX3Cl$g$DUOPW9suGml#W)sk zLzmh97a5n2L&n}49Mf9p$NYaaKq@mt=!3HsRQ|QtekU!m16FCDig-S4%r*U|Q=L;p zUH9qNzO?H4FN2Lj)-29YX%;eQlku?;WTPbKDHM1}%PD=9?<^ zbe*F!|GyLOZ$8!AxzJGe!Pp&UX3))YHrs@wGV#qL=%pVPSSStnvI+3@MI9XOcr zX2U}Nw?h7VjZLP}C|w#EaO*d$&ObMC#1bD9_>X3+O*AA6ah(M!lvvqgSPG1QBD*| zFJn6=Mn-fkC{l^Rc>4xt!tpdSx6!wo6Xc-Zfu6J>inBLiPz2`QIoG+N84)X;*j+0X zpq9Wa)_-?b*eiXim7nThIv^CB^VN(4GLjlZK06!wLanXOZqw}v>;7W~qt^{X08stR zAWXFAQk?G6qsfDXtk!~e^G?Kx{BgFCxNE|en{Bn3G)F?K3#~3&idwxxmz+G4`J7=|7jXuB>ll^xJIktgJg1jePZfR zAI*nJEjOyZgnE9#(TIke3k&*PpDQokcNzFgYUX@ZDq`?U;^HVVdh9JO<5C>#AGh(< zn*`MB{=Sw?0{}L?+}8p%boj@ODyyBMu2+9IM^x*jW8F#f(w=J1cu4Y9U; z&Xd`+*Fteqo$WXE#x=`{e~}Im^}vsbd1om-=WOpqIs?O<@gL36eh3J9fogl0-XGH@ z@0IAB;Z82}x5Usmp5?4=Iq%3TsR&OTr@xGpUW?Il0$KF=ME3ei>vJA$pZdN683kks zRR>X0AmgFD!J`f^LT61!IFFBpNQ%Q`Ba|vzRve3NL>$8frb`D{o-BKgax_n zCI5IUrHLebsA@}VM1h%f1sqf+;;g%Yzl5F8pNE}hVXMQ<+ip+-Ng1Rh&;X7K+!MCy z&*+#}y>2zNaj{+uJowpF*1f?kIrb)LljH-;|N06Zd_}p`v2z;}BKd#uPIY{~iwYAR z`ZrE@Wa<}?MWZ@+Ub_9Qwe2%gNPI9q7|h+JhtZS%unZDESW-{jKl!vy`%><{2EZn5 zXy8!V5*+eLv58s_mi)B%`R;8^kW7Jse4WTXmU4gZ6@R9oF!Z9Jtm=zq|NcOy;UP-@ zL5s`EcyquHDmOoD>#>fXcGWqS$1{5cpwE!@W8gVVd+5)4Q^)U#7V;+z+h=BwXhsfZ zSdb@(Hqv$&?8N=H@J!q;5*kWzm6~e|dyOw2i(Z1cqqOzjpMPbBO-1=Em+pKW6X>C4 z?F}b_-UoTh1XDvmIXmhin|FPxEU23>+5WoS=G770^~yi*mEna>@swwji}{oY&0RK+ z1+=274CrBKZuzY$5GKCex+Vi6gndt(uMRZu#Etl?_K+Bg0TKvSlVIG)dNxu5QT0aFoYUP`yA~7sY07g)zNVWf~7eU`X)ECp$zjiDO2c1|lfV z6+i*KftqPW8-)lGqnNVY;j21~L_e58I*!nvakNeaN^5j%j9t=-%`jQ& z0|7e`)p_(8UcjP>AeL|@r=7_&6h#9m{@%SypoVV)NnK%fcrQFaUw?NUCCgUZm=xc} zYm{kz?G<;)y{GzCcqLPD;7h_Qz!{BMLZ>9`Y3i{y{JTQEAzS0Nvn zWj?NFV90eWy4^p*=KIx8R%A^wd)uolvzA;x)?3{RBDrkKh_?@Hp=kb+Z6R1EJ@_Q%i8;neyt>GYVv7~ zUE}Kv>vxu1>QO8N6{UVxF1vD^2yU~oI@PjOhrfLJ@`&F?iEDpXUJeml`)b(S~^ZqQFv2bb@(eKw(8d;h%<6 z-~LaAQ$55T@7Is>19FogSbx0iUv1$zP8c@CoREju9XM zNVNienjMxOuaW`>VBC7?7W<&yNMsgKsDy*u!b_->{dmpWFZ7!8KzXJDP5!aaAEE*)OLv- z65+Dn+^I(&Sg#Be0owBkka#o~4^Oi|?rPxt>9kiFUxd+T7=#d4ssB}Q@dH5;>ps)5 z$?9B!4tN$67hTW-Ptg_fl7u`fC*teMO68qylf#;pTzW!l$T<|auWxk;jDT7a$2>g8 z`>%`^l2CF3SsN5aOu;X~CN+Of{}?EIv2cB=XTvo@L-;;M?dM=i1WG8i@C_||tYZ!T z&|UP!kL?QnZ*}0)&Xz{Vy3Dkkpdl?3gLMg&8 z=3y_YxFO76%MTM9tw$nkNx&j-u`UAKj5y)}Y|f3+yphk+Szv;R2^+B>#4hOA|1lUh zJ_12)`~GK{rff?{8vrFyxtW2qt@J#%Kdq#p30l5iX^$337Kvdsrw3KLo~^N9{QVYgp3Pg9b$55eTg@1I?d(*w=U42J z{30ShZZ2)bQQ3JWu`!P5GND#o)MFoG_=aq6n!=I;vhUi`K6d?_WcwfzQ0ALnd}=$v zfFvrj8g3_e@mxbu^oK>#%&W~Xx>lcar*1BN*)kX(?(kTh*ts$-e+D{u>-7T$~(Jmw6e>~coKs0Y@*Em!~r@K>V9oQ*|1N&%pqjIjs20FD|Ms6$*e3r(Nwffp57_&rmrB(6=mO5S>56&3Pn zbyGcOn0hxUkHKjwu~)iBUx_J^57dBY1^1nRnoIod?8e|R#ln9@3}sP3Vclx47}~$( zBjaoa_eWwqK+qBd^GYZQ)$$V`;9j7Y{)nWWst3P}PO^;|?u0TWSg65LDo(uIdYNPX z^?a-zv*e^%gJlHvQ56LJiEaFm&EUxxTdt8fKy!s=uC zj3^(DQ3l%1yR2@QE*u#OA9ysu;I&ARabw=ZgVi;bYxglNVqMHM)h2jRTgZQLm}Rl= zC7yc|bUJSq#U1e5m=|$`xz_bl)sNZvrc>o+EX$ahHs!|lzU38nF#Fn8WqJL4^=*fI zm&d#sUYze4)Rvu#(bik_qbar9_Cyw_LcmX?npLfX#90MW1W=0}z*e9#Mt0)5+OcKa z-m4V-EmbsD8_u5NDj3-RW?w?*jis_5w!IkbDe_+B6tS0T4M>@5r;GqKX)GB9N0yC4 z1r!A@FE8!i(6@BN=NmL z+|2LGXzEm6n(9W0ZC2UjZO8A&S@b6>bUGWbl*{cJYS6~1x*z(UNY2^8Qw@L-V}$G6 zUmx{}`SlL#=9?%De8{vl!lK=KefGx;)m8bD(8b zl#bcU*a;lZw}z(?uiAhE{&`Wpw>ma?bf3JOTvkuGz6-$ApI$i$LQ$L8!Dr>|=T>P8%gH!^5p~u;a)o1bq4>Gkw0lF3Q8I zx*2Y;XvEGB4GtnI3 zs~#+|W83~jfDSuZ>6sl*X3&_sfUd;IaF#UdNc@_FOuc7lR9s27YoG?SBO@bx%(4|L9>OV!h-u@Y)j$yWyUJGb__?2#r+(SMIc>jQW?zY8$WQYhv>YG$ zH!SgA&TV7Nu(%UuFqH9q@af}dD?fyED;=M{j zH-2%aZNVIf>GKDmqW;8v1RIJsqVf_(&PpVoQ|)_< zF1}BO?@jv=;}^r+=bCoPA8eDPf=Uz zOorHeKZlh!mb0`4c}T2`lvq;i_s~ zaA{9M4}fpAdFSq>6*DW=o8B5U1-!dG=*L49RTWFC^ z0Q{@gtqXi@Tv$=D;$aOjxSs@clH}4r96x{-{jmwwWRobgUCJ!7zIvQhl%E7!l9T4IMNpu?zVZ= z$G?!a=Y|mZVE-rYq*%wu6W)2(_i4~G^OR#OTbB5&@-&KHeE;cFLAWe2%rJ5(Brz<= z+Yqe07wJ9{H0xiytI6Ze^6FWAhds?$w&n2Y4wDZfJ>L#Fo?YERmY0)K{9a|-oIy#F zQ$iWiSnvm!hg5DZviD^DOVsHi^`yR)=f{jy(5v?yjiJtArbm{Y)5doC9{T%WQC+@r zg|uX`fdaDL-P2QoQuA~3tH0kG?QnZ>>)2bf@z`qq4|Rpt&z(4Zb~*PO?PF*6d>b4j z)>~6R?p?r!aRD4$(!NCWC@wDUzF7K=kTz8w)-<{M`1(F6W8G(h-O1a}ulws)Wz+yZ z6?hi3N#O86fECzyU0htmprrTyuDoRiM5uv_}IlLwOqFR*L{ z9UVD?qC&OQ7{wKE!V=4zc5>h(cc)ErwbL!b95 zqF^mGs3z!V^b1jD+c^WD(G9Mj+&FXk-X~Fl0G4T$@%2uqKOSB(wjrk(hCY<5d)iTQ!pki^s%-`=7h2l4NNlLSV^{| zFK1-j%+IfE4SJRt8l?4TYlG{D(#vCO5>YfJwgeWbScYut$te)X*h+87QrdOyL_FJS zMFR&0`TvKluMDVi?Y0F26%*n2P5dgFQKGv}CNjOjV;yn74OZvm6FE&c=uKezs8$9~^)QtskR zBZNW)NwNq8t_t&+ONgQaYJ5F-?<+h3kgwS;!NY@5NCpVUXjFdv z()4kist1&6P*~Do zo&X8N!p^R4zG7HhRW-Kg8FonsToYzHkqj|Anb|i9=FNhjfeJ!4>Io8q)WCf%Iz_< z3t*#66TpCm)SG&HUrA8HFtmHNHJ;GO1b(TSiPcQwRUfC+uV1|8vZgUuARtI@eQ1bB%qZl9%G}gUgG*z$a`o4IE^7vI^*ZJ^HQ8|Ar)ti+u(`J>S)uT@|=0 z07!j>m<_YkZxa%V!9WT~gfG|YuoOamf+#yspmuZz6cH{0Fd%-EN0gM`V4?&d8YUS~X-Y5hPkcl}Wq<1#T+VjvK%SM7HZLjimAxs%kcbr0jLoo6_dSgfkHdMke{f(~yUae0uwY$kq z7+}NO+ij#82gjwAngE-8=F98TkAfN+PM`eZKsa7WowrcopQouNNJ3JqFJse$9IV2( z^h#*yN38wI+ysS_M#Ug=4JOr>_VGUJ#+1BHb{|8?9YP(*OEjnthCd3N;64=oPMFc?9X9vA?rEe6h!qThxRja#g(VjBLB>rL4$vgVX?pZOd+Hv_Z0>M6z6h zklZsv{@*VwzbPU!V#gS>X&b9GnpZR*O^eoOn{)o&Vq4ih zWd60f@xkY5aJD~Yia)-Glo3&0x)Pvx4`{!UImTfIq7@U~dUFc`QX{n?|c;p`V8`6(-hxs4@RN0qdO_9Ys1L)uzEjYH%faZ*0& z=@b*g5x*Zuf2a;%!Iisi@$3__*qf(cYkn)(bjEj!YoAB1QT6-6tJfS}i$9!>;ghhg zs0PO){+yW(9$Hb2bi7DR|D?%8-Y_K^@TcSO2e3jFa=2Q0lNih`EGoV*i4SV&7TxQa z=fAnGq_HD<-J&TB`4Qm=ye|y*rG98B3Zd~z>zV&@=1A|~xgTG3Nd-$InttbEKLww($wZ?!IN`qP!~1z z+e#IQ;*=EPGay-!OnHK(oTvf|Ib-Hx^`nmH2J=P6b{xpwTjPrB{)w|3+d*%xzqGU= zG=5!!hhr~A(naHokK^sN^%YNFFJzzEU2IrRY7rSOOR~=n%7$@^Ke*+R%~q9;gs&Aen(JQJ$(WB-a@GXG+7sGdE4w}Nn$%-i*F_mJVlOuO zCB8)MR>^^$DEqaJzLEhp=|ny9EPUT=NH_`*iKEvCK9_B$p)KW|dNdNY5qSCcPp*)S zK2-avAC*Q(3@Er*6o%14MP3XP&z=mENG;m?{bhb7Xh%@_{8~RNPl$k|$Mr)StJhzV zk7q1jd^@3(3~o^ReBrh}`fAYEf@OO`krsvha;fYjHBTn~m=W~)(tVeAe+7}KA@>o9 zHZqqN@bQZFg$a?*|Iz%`7MZ&-{6>=moLtvh>I0u=-$tcI!yXf zYd;BNjVt1*Mf9lVO-F{fhkt+HBNjeiY=H7VyaeUqC6-;hM5)j(D$R>?rRw!I&tJc2 zFVw)TeP74RA9JNYUzwRd`La3Z_h4h>f>hOZhT-p2sg$qkmc~iw4Q$JCkV?oX#?0%@^3!COhiH*kLO9#2sI2 zYA*mY5n?vH!S>`WSj>LUBngg*qSdo^DMJOVfNB2oN3C1FE zUDqEv8xYOV6}ewLE~&5&1>R90Qid+s0@O2CHM?WEPoa#4LhCc&vOL^8WQO=~AQx9Z zgp(m_LH<4IIn2+RfmSUO{2W=Dj}F`SE!zE`lac%fS;Pga%@6)VKb?bV_~fG;bz##LPO5cU~dEA{ctSD6sr zKo7nf8DEF<%gf6f|0XZe{&iUDOmIp*_yid@*+oXZASq&j+ypS?wF{N5-?&jYPI~8# z5U>TjmVi4R1|xb~wA?^P3u*H3qwcH%+O0Z!{zR{N;q(?VLplbXG{wwRsgz#}mjuwZ zY-P4M+=HKz)n6wwMQ4 z5;hBvcmMVD6}yNGEpaX6p8reLQ=4X?4(Ua#HE-+o+cy3C#DP-Tvcd9uuW21^7lndTw5J#128Mw?c7yc`%Th-S|<@4 zxSwT$)3Zs;6bWEMlrp7|myHgL{$sF zY!yil3LwQA^2LMU)tS_2(Y!TiP(Z^V*oGuJZWvYp@>yOQT4Zm)0i;I7@5$Z_%=f#X z_J(fgSAZRmdAh(a+&Y>I=H+Gk_k+X~SG8_gAfr3MkPYBDF<{|;oIxz5n_|TduuK9m! z|BE{NqHcXNMeQd9qSl$28U2#dW06#!f*{Befz&@esx^WXzPCRz84~=DOM2-bJI1Oc z78!RDR3VBHh5wuILel3E`r(zTjcCdzKx^-%^!;9YCCu;;7XGt;p@)l~FCjD2d42Dn zC+J!J^d;5>U<^-wBJm>AxCl`H|F=Q_M}E-s)xYU7|ne(^ca3@uy{GAb&ctu6E7H!9PKxSlr6Fm@a|mFBj0kzfK>PPhT|A-G}EkPijj zTY#1sPpg`lnWeXCbHscM3`7P$!cOL5|8I3OvWtLwnZxK|NO;2$jcYbcchQQUcUS1BC%)DDE@)V;otxFyAQXb zril?zk+R~W_*^{kQ2j_t&4ykdcQ_jaS^ual zOI*)z!Y?IDMiieg%Mq|t(e}r?C|>-@2`o_{i!WGKqNS4EMS1a}W2tR&sXRpOdi~k1 z^69rFJ_nH&YQIKOAI5?|zpmyectQFyeL!i+)oz=MG3s?%N%aY!R}`uAg~GEJ=umO^ zB^T^k^TY(FYn9MO`Q;k(eaUM5^hr;WCAEKLeHV(iaAW zpTsYF{p~4jcja z(zM5)W2+!Rs_N0X6ryOk@ez0Y@VB!rs>LyEJSW zcE|hn#!7OUl|y>&^bmO3Lsr2QOFL~z7`R^;aHHsBJ5G3`?bqACvRo{uS?};rSx>3# zhUunyK>xP?b{Das@93CkW2Z5U`?q8z_PI-?B#mUDybQGa8*@ju zE*Coktn$`TG;;~fk?`IWWx&-KDb(J)_e^ISXbPlaXupDN_eWef!k}*aT};@z=d06R z$~upaH@CFWXu>%(m)(_KK#MKg6Qe0jz8ds<%gj0Gq*7RcS23R=Fqzt~$OHNr;HN4e zAfWT^-H@-cs3KT}!f;rlL1VFG-LU`K;ES#Dn%_dy^eLOiBe2f7eyo*~!|%QEcGw*r z%@L1ZH5d#tV|goYT*O+Mx!LqFoUeqSvm=8leSTUfJoTy83_0=gB>muMlAIFj_Yj$j zU?-!8r;>wmYVrHhx`uyB2T``ci5Pv6cCe;=y|K)oc7b?!ouj&S0abRwx`(j~UR`cQLROM@MAdB=w4hQ{Ayjx*gf zX{g61TRAu<*%Zwvqtm3LSCm*uB_SH)30Jl&lP}Y_*XQTN^HZ^`&MldD|L+6}^Y7x* zJvpp>rNdU#&Wb}y8>f|DX%oXVLX&43g{Dw9$dxHd)!I)V+;ToXO$u5$7`XgpOTUNO z=47=n&H&%if}v_Ue#7gj9vuVna73c5NLMF)U;a%QT6e&*`wDfS&B^DF{Et^mmN;%4 z=xmoWt`z!IvCoe_l^j|}kgPVArM##?3?{|##5TuTQ|Ch^PI$p_504HD@K+9;4og!t ziXPaUETucnE}5RZqK5uX*<4jtn`s?QtfHvuX?%^tb0bqzn{B6qj^=nzdm_{==HEx# z?f#o5UAaQ`bELUL>%0$ht&MP>NK!l#MQR{2;kYn}Ctp*yp3sX|JuQ*lh{P0yU=Kj=L=Tp|)ltFHLeie{4 zgpH6GNd_?1<8t}y#N>aYZR}JQb9frV8zc?xZFCuxwG}`#2FAt1`lj#Q1IzmCgd}TY zA#i3uw%wQg@&Pg7pY3in6Njb4XMFqxG$t!2JN;Xc$nI3JD@}r)lN*V6YR1Tq@~Ob@ zw9HnFMed9;X8^`5tyhh)%ne@-SRL|ROq%MftYYY}jeFNB_y*_RuWpD0Ul*e7lg-|u zci|)bcbpB$e9EWQHlH!_&n?{x`BU_7FLtTemFU90t9Es|Dfxllp=k~gqvSXr0JEy&i##~>1(2;9j-(o9R z*CBMw^(OHi=swk$`L;42(udf~096f>n8!0Fh6q|ZOW@I!49sRjA`uyTu=+g$(kEB~ zC4$42GjP0$4Q;l=+@Xz=CKdN1ltLW5ST#Y3jnrv_`EJ{?(LnwMm*r+C*sjzgh%=Df zw)Xes5dq8=bZvKlO8#qcu@y+!$XqrwkEbR@U_gh=P6vLTcU_%eF#o|_rrM+A$>dL; zA3hTmF`@deEKPC}p}=SyJn9FemhONevnMNJ<^Hm?P9pF0I+wV+&->gStY50Ss8+)y zdU9pn#ps8bdt?9RlyY*cgY6`Z(1bx4e*KxURAAcb0R6waeD=&B->q+Iy6lelc#Ib5 z6=^nHLdYQ?Cq-1ET+T<#>guH%o6vsS1(3eTdinLGOP7!VbN2+CxuESNoIZfc3@mu) zrglJM5EZeChBoRfxay$QYZoFEr4JuIz(jF!AkHEk2*_f9XoNCS`xs`{Bh(qhp%WCg z%#M5de0+S!SLYv&U+@5A=-|Wen~jBP)J7e6JhnA9ul!06ZI_);wZ3VJ*BDHJlUxlm z(u7=8ZyZ>rKDU107#Hb{N>c5hN0eTJMi!eZh3}c#qMQjiCeHo)ozP%io~+{ZO9nmC zeRcbps~hEWm?)t0eevSOb$$ib(!U|&mQU37;yaL_bS;XiQ+E0j5 zmqDepH`U)HXBX~L3dowsV}dcM$vZwvbBCB zrUk6^*T0m(kSQ91h4&3tMC(U5&EDE5C@Ahio77m4Pe@2;ZOr?h#%W0)P$qhMdXglU zkAduP<=Qpg305wykvz%c6X>RDG2dMq12+eriS#`sIXPV5#o)=v$$dpyf|pAze&`le zd@Gx)q^_wen!_&f|4-vGl(R$@5>+5Vz3mw_uKL@98KAoyR0N64d}eK+`A~z;p;~Oj zuAxf;1yX?)Lj@Ydqk%23KPU^HygtCmmz;4W^gF^o)XS zfxXoqj$2trmlUJ_?OUg&pm$`2T}?`+Mhr9&OIzFZH$G&afp6~V?Tw7E2PO;(bF@T` zN?8!NyJEOQ(ET+#D+E1NgkO#VOA}hK!4QIo+`$;~Q$$1ygv8(A=Y#@9J_Q|}I0GRx zw80CR6~?{F`S*;BCdaPs) zvb$fGqNBFDq-^85zm6ETWR2jf9NG?qeKC5-GZN;+%PE}FxAp2!RO+M5MNQcr|g{q72wqM_GoKn<%IBt9U5vpQGe_LjwACo@yk=yDJ7>SkDBEbsGP2YS_b0@e8c)d4=9S@qAzdtxSfST z7ZnhZL@-Y$BFfHtdVLGnyGg^VU`_2b=(P+c(22-@gyEXNR(oW_(GPwJThPYMLYO9X zXMgArF#!-bY%vBt?`&_A0geOqZ=pfNyt7M7ZGhjbd3#=jlRvYogM zB}pkSN1h@%1lIsa`BLS}u^20PxDzFP2~*$*X{;dmQis#aLbpN9x@qh*dVtiH<&WWP z%C5Vw*^nk1{`d6kXX(u8>9B*UHDT*PK%+?dLT&dq(?slH4_wdLFWfOQzt*r3d_l(J zv{vxrv0MDNaXazsR|4gA#CFBmK0Y$i1!dV*A8;hK6Ae&q)CMiORLw2J2KY4 zUAqP9l}lk)!&-if#LL)MRQA3^e@bR}1;Ntc_M7EpYQExDVHSvjie;BJKoKICthVLv9vC<7?T)Y)!qCqq|} zN`%HUBj8`aDtQb^H_yi%ewt2;H>vb9*CQ48_FjFOl%K?P8NAonenz4^$W{1O8Z`Cc zh8FqzVjj$&s2#KE~amW(5$N^|i{-(Zq(C3H1um|p%h7}FF> z5Q5x(76sjOXJ#?q7ca-{F{W$xg9L||zLegsow$Ru==s|d+sz00U7Ga=d|zVcCZ1fp zcoTwe827ekM3D~i$tC_JmBl$gs;{Jdsh4mSpkm^y%Zk`Y*cugT{1+6ovX72GIT49?)1q-LkR+ z9tbXaYZ6#V1^*qO)66+nG ziKJ%@d!ZIe3`+qv79Da`8w2}P|NhkvuCVx?WQKGD{FN2}fB<{2ZF_DP+&ny4AKuV) z@emv@8hSuMN7F8$4LEnC0w(YJfg5iv9Y8BDEv0V1brj~N;UR0@r~C)k6DC&FFWuVJ zSh}%oOOc;3l5}?snA(himwxwC*T1}tP8JLA0jc(Vc{U;v4vTcg?^U_r{Nd0YZ?`^( z@6dM67e&_MjPbv)=ip-i+u)WUV8Ie|u9~d9J7~bpHL7Trqc84gb8a$r+iX}B^L+`aDZxYf%$+7 zfVsJijeM{&JwA+ld1`LHWpnHGATjhRp-;DRz~po%S|B+BhrH5)e%vO=B)xxV9s0qe z(6%-Wd?(5cE!sd#N?j{@?$7TTgzT3No2VBA=7^@NZbM-0@pJijGw_C$R0tr;JxLGt z_V-0n`e0A#j}2OIy%$ZHiBMFpU~KqU`CR6S(P8G-y;o{RFO|I{j&!N2?y#Vaha`o^ zK180v-vl$Q^}$+UG)FGZ7qB=K=K;q(KRS}Gy1HRtHfyJ%Ubn zInA}d!a38O^gy*p_m*FBZ=IVP5Wk(^tQvZY=J6hy5qC&PT-7{qZG1#zs8z5c&)H;E z)u0(lj!~MuDmk=kGuIa%IN~PYpGv{nJ$X2aubsZvIzH4AodgGHc>wIK5zB{x?-`x} znI^@y{Cd{t6U6F7DX)&q_cuP1@SpiQo0MeyBSCz5S0-!#enyB2O?uc#sDCF5H>=Xk#enS z4$3x{Kh}`pSy)*il8LqHy6HSg;OXH|Nj+j_#>T?J0;YEZ)UfMghzJ-|#6Sc^@-I*r z!2FD{65yQt`l({p($wSuohzu-J==A@86ibDQt$u>07lz$Kus0NBv;c*$l={6kTx2A zmXUEzd_II(*`vz98mvy?m%PrQSy{rT8@dos zy+_U2yb3W&|6xR(aaD-4*tVUpV`u|Hv%6xFdt@k~_waNQ2@A;_*~JfHVYoH;ER%zq zt#)tXQ(y)ci;1W@JM$qmGT6!@!fvR(?>AP9(a6j3svbA zM1$_PL&r_I!jghcF;53%9*}&B@tYPZ-35s`d^<9>1w;=!Fav%Uu#qeiaHT;ktl%vn zH9U-tK!o9s!6GjEtd`5?Eml$K2a?9-93gEi)nCpEWIfJRCx1K@+H(108ylL9`EK%v z+6CtnboKt!vaed<{;d4uG`e$@Fab`B=c8V_^a@@%&a61Kqb)1X+N*bVQ5Vl0(A_gV zn7TK&bn5i2-`v8o@&D>%of!5IUue)af>A=yVpf<^D)u{Yms_CO)eaI$M4<|GHsU;2 z42!05*R<}hE%?`+1;Z2ixpCaI!(len>9kqX22<2K0O2@4)OdOCU*S6*i7c)c*mZ4z zR?{5(?omo9IG}Jkzpf%y3@-H!|o2in?s}R3kLBwAxU@fDLUhOho|>CTW0Zidqaf2w1EP(j+G*(>fE2 zh=|zMWRH%PzI+CBVcnv)pBCslW_!5T=*BzHLo}3xEeiiK@k47GU;+w;p5~un%WIBF z=j?$+dE9Z4J>DsqC==skr=i?^4+p~pF)50cjL~$hYF6=*J^Jq&y*~5%BK=R12$&HRl(}5Z1Efj70u1AfiRRNP4Dfvk6m}rxhN2)MF$z# z8O&(?=DuA`8a391`VldAfc_>Bwts+v9%-U7Rc~Da{7DEXlWZd7I4XFc$Fn6TBCA!B|tuXX{(O(D9IAcdyr;1? zvbwjcOP*iT_uYCmQudDFgt4#of#l`iBbLAK(<#VpM$cr^Ffw+JlKH-Q0guFob*D9X zM0ez;k(OeXx7YJ^y-Py|xb%MO9tRH;ul}u=l<@VQ(Ecu18i&`G=kz`K{(s2LuCBFB zwPNR%(A7_@5QtrV3Iqxoa z#m=+Gcp?>RTb(;5w1#f%W8qT8mYMcImT!g9b8!8i{xAZ3PEB$VBpsv zIToKJ;j(8osG#(n&e$LVx9v$AZ%ksx{mZ#2NQ?KlWeF&aQS9F?gQP+In@dc5S;vkg+}xQGmBnVVq>m525~2=~P)k0ke%8@G{0&2|$z7uJe$byeaQ9GdFiM z#Q1CzM%D6P=6^wxQ?&}@^q~!V@PpPZ8qJe5Fw+`6aevFCt1Oz*XBuTdLqPDE@RRZ9 ze9ZJ?_T#whJ?ED?AwVPHAN6X9?WQi~kC_!N zA@dRGA_owA&T+nLI7WJVsgSL8-?SOJ*yfM83ET}jOp0Qjqm={g5Li;rb=-NMy%~P1 zH2$ZW?;%=EH#ceTNAa+Pe+d0@xX)4n1K{!eJUcVf0P06N{W`ilC>MDe@LjU1WR=KvRa>_lSu6`}Ds8U)?YU5MPq8_OF-;fq{XbQJK)9 zHc*o}D?;&?Pb&8lCxI+#aa)Af0h$n|W=qvelZIJ#Z?WDM(%v+_{d%Dtjg9aYLsJbx z74Z1TEyaXz9XWWz!@J7Hd(4f-&HXwR)KB{qj&dgwz@pnTJt}p&m zH&h!GRW)*d1{N(_G$R=EhWY^os&k2>i-?KofEPPj}?JchnPWHhZqO| zI)#`6gRTfM@p3nLVFI*#WaJBgg9nUQO2U|tK%U1< z`to=xxk_0|*tG@DOhBoQrWcpx;);suGCK+F)&F&FYHBO8RC==r@BOuIUQBXG0c0wg zb1td>u^<&Zw~625!#Q*-^#a^v_I*#8LU};H`(nfCQf&;%Z|H(d>pq3TezwNR>|t8G z^8+f+^0WJn*NNB-o+@VR&j5_FMSLA>s`iwtkO43t)cSAO z*Av(bpl%}L;J^pZo&8vlRASYrgW`SS8PrH%#iI!}X}_%rNYBpxACbY@Pl3T@>r;@i zOGGih2PyUc?e|2EwSrm^0(-pk&PyKKHQ$5;QrR?#LMMTOJPT?oJRpB44DM-%g)T9& z(ki8CFZy}JN_4&5@F4CrFbjBC$p<|trv)+;?-I-u<&5EX-37xe69=d*d7c5;Br(`- zpIfpr&dp*N6rk|RSXxD^@0(ZcUQ{!#I+37+t~=qC@)TvDW!h1+|VV`Hs?aPJC#L_B0)43`&*Mqd*wJ|m;f{vmPZUoiUGCM zcUbRqu_C)-h)@Q`HGzQpEohgQnRRVIBImaHCt?}2MUz;^JFxNLlt#=g~#`&>)kJwi|Tk9}d0_5nS(wQyt zz=SA(wXjZjG`o`gwq;5fkc`<+8=uOF_N)Kwx>}<9JM5R7WE{2uYL()kT(4yy-`W1xrI%h>q&dEMCimMkjfKlcreTdHezm_=(MHxqt$ ze~?T+ng*iHt!KY~eHwJ70fJ9pN4VzsOOvoN*yPr=C2R&dS4`!Tr4;pKS6y9&p zTW9)Po&dzhg)FOd0tq&9CJ#@c ztUg;sedBdfVC}3pb^MnZgCkB`ZrJteK--9X-ZQjNgn&H%h?%GK=e0UOZ#;~P0~K8k-3+cjG<{uU_S-vtGxJVh_>KDR^8 z)gFfNXGPdd`21sDSi|?{iuS3>>#Q!T6HbL*s~!0PZ0Ty2WIPjcXHc%w!OE{C9Eipk z6#+CIX$gzB+0BL7v>iJ)-7qyG>gKg8d)N74-IzbR8x%P#86wxq-1ev_{UdrvS6+xo zk%dKWq}3)6O$TkZy4l6gtVj4%RLEZ^4K(g~tFfuG{t5TY!HU(p+4J#AM=tbEj(|d< zMBl-Dl4p}sd#Y}gb;mwxF|uZuMOEFKVNL_|gZ}Yme;Xh) zlypV!IXl+Wpt+lotP2JIuFu|QF}x)rQ~s_S4O8R0*6VZqw41fxW|C9mPjw0EHY9a~ zrdv;UBNsml&d>sJ79pB~jloY}pS+gTcMCBu+Zmvo0;)N4y94qYpw>$-LO3X@3B?W|Zg{u*PTK$6+d^*!u-gAe0LKIQw^7wvPZY3t|P zn796pM1(wDHp}d956*g)J~ZNzIKR3fr2A4@D&+HR52@^_GG$+aw%3+J2e3enS0&OM zO~D5Oya`fU=NDFzjlFFR@FdTea^K7BFbEd#Lu$W{iI3daWzW&9&|hApl7 zZqJ&`%eC{^?K@9?|IYcz>>F3}b%fjI@v(Gf9s&e2sp9^`D>Frw9my5yV1=2fH73@* z>NS^JjtuWf(7HcYdjo$6s9<4mJZYSN4ELX`VQ8x6er2iQAtmmCViy#lN(UMpnL>H~ zGOMqGyf`d_o64h6C4|?vYmcV99IKLt5?gN*ueE;+R}~uozFr{f@>SK3AOEHxsO2#w z2B*l;PE#0v)c%Q95arU=20y3#m^hsw!7)Dth%12#&hF79oq?zck$*tESqO}XixFg? z#(svy-wah5xHP8GtKPRTgB))@E>zKYHPU~EfM*{ zCyoSqD@kAPdzanFwra9+ola<;!Qci$U%y+IaFjYCRcG3un_dNv*dX(zyO zJfxxM-m!Dd0vkxpdTII-uoOt&%`6T`tdVvRudiB+KPTdji0m0`kc0!gdiO*N1(Ra2 zz+UANFyZM(BkNn=(yWjU^GfMu04|v4DPc>YlQm8hls48cN54%gF+3HiR9BdGX789!$Uvh48j%Lj=%GN`h)>Z{4K4@ z*GPQk)F1dB?rKR9DsmF0eJxfU_|M#-O_6a`Qe=tp>v%q$eCb_!x7OrBiaccuNbNAvGrV(C`YdzORzI3 zk{eqG^)5fc^9Um0M;JRJU^D|r0Tp@5O3&Tnlam2(TgkqYk-;0UPH0x9=H(dD|AvWu z*tLezZmva-$ExF0rW9OrB#v#%{={}X(=dHI8)_ffmXNJG$ljK9nILLs(o`yZPqUiH z$wDbKSY=<(VP$~rdT#4Mo940Lpzx#&54EriuB)$LTffN-kUfABsQ0Xd%e%Jj)BKtc z$(bclLLP6!WewwZa31UC^9UK5-ex*4PJjTKhJO`Ug~+>0UzHA#T|95;7tABSJTc?~ zIQmU9D~r(t-m&2ntHBm!i>2TV;ik|7_#ejcKQ-31kaG;;u$0Nkif`mzzTI|Hq8aI` z*iz^{TOzdbB119KYBiIkDOXvpY5t#*CMS!;xzW9cvzr;Iz{#_ytkfUf>TzA!)rE~0 zEm#>gW()C+kN?-~wXbkQh=H)IUZEf_c0ycjpa`UC8bKQwrEz=(H>CIdOPy+JzNp@x zEU-1yU|)=R=&a0L@!8Q>`&_^3Wy+#p|Ht@uqM|v`V+3wkI!s0}^o+Hkzi3&PR zXIn%j`{f>|nN{PHH7n0Eh6mf#!aZ%V3mGDdxMMlO{u@`IA5W zc*lno%iN+z!WQ4fN2~LeFqu;HkRJGAYJ$beO5tbkG9Bklf6_0K#_|$v-nH%~2dnb3 ze=>R=PW97zj!fNQ4gnnZ#?93*_vz)#ZXb4WI&BaW2Ivi>fu z9DRJ?rBOJvvZbmoQ|P71q-evNKR>V|o9Q5NevG2Ix=+~815@Mdp+mDlz1t>ig80wC z;zaMnFO7e(^gizv807c|$6y2>a8K}ge{kz`#Dd2IDANuFtJ4VvN~#*rwc1qW zfVZ%<%WTg4IEHk#r>{(zSuOcAx|}V3|M_eC)qXvE?wRVPM_b|)%Z9cLk~4> z+DVLC2ERGv<~Tq2=ZF$QJ}O*(N4i{-Do>4sBObxoD1Dr|J$~|P%i2Cy#m`OzW0eSBRf-3gnTV+dgMxiCg7OJ4>adp z;px_LqP=Qcr<)aCEfeE3AHXsLVO>7%56%m`WIq@5v-2bG51hY*I5V3_UbHg~d+;=c z{S)d&zy`@n(7i!q(fkHV)t+?OuYziXSGSOj0)+7AmCyV624jZJg0&WEAHn&Jcl*o~ z$#y`81nm!rq|rvujv*RFja|)^Ya=?qZZ=Yb!()%EiVk}zgG!9sEjI108J3nJ|a_xbwC zFWY$pRq+g_J6S&fR`|KTVlcGhDSDjaXF+0Z0OZg*cr)-TNM{2`;=EF+IJ4_NCW%)D za%E6Puj-nb5lF$cPE};zN-*JSIG>ydXnh)A%~wqUWd5C<+}theA)JJe_c8uK*DBd` zp7;y(@A%y%#1Ta}q~$5>oB0Aipt{1j_q(B!_f3(d#-03$pMD^_mEJ39r;__WbBqOy%d8lTyuYQmVTHtf4@X*F8&NUky%Ub`hq7!>Za*g>LT+gNMo(iIXyW zDi&(IsH&PZ+s&NuNV_gMxP&_AM-4DFpuC`AH;5(lQt@+UcOF$-E;NK z4Hb?g-qql*%z8sIC};dRSA!1>n}I~}*lyhd1<8a#IxrOF$bMsfl_lZsFh}7@*xmDe zDWAXR)v5Pz{)j4?w?-W6cRfa`iLzq!g)kZ7vxEISVM(I58nUU2_%g;a*Y_pC=Q~hjQKxx192L*6%AYk^7NsWnJ*dF*1t2`(wdTazc!=^ zIK)7L4pRT#(3C+{{nakxLa6m0s|uNcoiwo?>{7!aKNxz7bdI2#sXvhRC&3kh@cNK| z;snC&esUD-3ibGTSXA?Vae6xvw_03cqP< z+=0*oJ^9??$^ByU0UF&LuJ1r1w|^&0w|_4isywdG%JrWxDuk~&v7|j8l&{c;`BOS7 z5=^RpD;8$yW(7p;%{=BNb>OFOGm!u6%9 zjRl9CS;MS&Ds=Q{yli{q>}9?K6itEzLCc+;c-Md`<589!FHN#m-+ONSOW2U42g|4- z|` zLR_7`lUz4{8)>@Ugyl#(%(e6Mi>UXHk z5lDBiaH#f(uJjGD?rnBFm37B+OL52RtQd>}Zc%#QM!K36U+tVGXO3j$X&gN}<&IyO z_VkL8MlINm`YYixJWx2Vdd3sh?iiBSy@nG0h;E9l<09s8XXvBfSr1&>@o7qfJ zRjn9Kso0l2iWtHc@6aXip@L5~@njKb+<_{_-;cm~WY@ZyCmI zq+CpJPDFOwE9cgzmBVtKwVX@X(RT{)JTohvd}pswlnj;Crvy<-CEHGVZ2~Xd0p(8D z&jEyjRFiz!!E&1sWdBQmGx?(L{pzlWDNw>gn1@AkLFV&9jJxN2B6Ye?R|w4)oQ}J7 zam_hWPzd5oh->;u{h|0Q_$$W)SH?!Dv}>%f@kfU>6O0`Ni?1R|w>dc;*gu)QkHKB~Fz36f?anPx}(0X_OjcyA`0}wXL zHVvCVblItFXh*0qm2B zGBeUR-tl8EtNaDIwaYfjNvM={2*Y}=@-4>c(zYeZn-hP1HL+Ve{!XvB0> zhl`mM+lYP)OvCPtv-%Zc*l8Bho=$gl9g&^ge;#IqP-$)7NAFYM96WkQz+!&D!+s!C z6ftV?d~iKkn@*1v9jtHGEmz|p4R<>qzdYioOd!x7U0d{1yO5Tzuk5iJ(eduw#_myN z6?2{)x#~X8#7)Oa;bX8!HIGUvk_kzl44M4lO?BbRdP)o%2TW&D`Z!MY!CL;p#2p6L zftteJB^ig4-U!e8ZVauxH*=XPlh*t8WX9(*wCTM$Qbky$Hk0+W4?4edX7WEteQoJC zxb&x<;}}GgIXvbTFMa_Fr~9i$^#Q=LxOgf`Zu7Ik?BmjDDZ`^@<(s(6ZQv`@96?Wv z0C)sGC7NrE#Kn0_P2o=^nN9>$O$@QL#P*%8cj42~aEo}JR01zCWyuV27g4X`_Xb&7 zz#mIGze~{V+qNBIrTeL1ek-td>yMra=v8O5diwyiF`@9hhelePU&(SH+(YUEk&ZZsH9Rz&F1ZK;Yw-$h`o9t@#e;PaQcr4rh|6eUhNTCo) zN;cUuWfjUOAv4*RRmlz&MKncHMv-0io<)kv3fUDhvXfCMey@}6@9+M6f8+7}<9+X*aDE-_q zmUXY6$FsYu*3F@+;#coTTvb=A#HF|GG5R(|bjw4YBdNJN9a>WvV=qi^0P3C-{d)jg zX)a>=fS&Hm*GQT?!*MHxx(~Ku4BKRBztOLD7^OA6nbKY!C|ppZ=wz<4?(v^;Z2ltC zg7wM|jvHL>IK8Lh-4hXJPiv|-vl59zk%ijnfm6oTmwt8cXt&-VZ<4t4$Qwb+p%m&8 z#lei6$dM<)m}DZ@Kdzy74hmfU%Fb5v5eghxyV}6y14f(7F|-YgRQbeJzVcTutG_+% zj(th*v%MKJvobEDD7?oV_1WQCIA*g)wCtYYS=IIJ<&vIUA%@hK`@O<#L>;<5rh5@j z%IQp0Y&TeyuSd$?k`Gz1+FQP3AwBbx&ab~Dd>dI<>S``ynvSIb>nsM`;yUakP*v}# ze!2}AA0&0})2=yk+swbZ)H0tV@YL74#H;&bdW_d(ms9Z%=ZmL=m_P6kL$ePOfTx9) zZrLw%vh+JGCenm4!?x~oQmpT>z)(G6%q5(?3;0H`(k>kl;S@~y{lK5}=i&PAhaxw~ zyknf98w?Y|x|%*Rw{VWC&N9MIU)SM8pv%4NS-Q?`0d}5Tf|e2E9Q?TtqbM9ipWGYg zSZiRKz2CTh=O(Bf?-(TNr(w56r8k?8gZ|>N`ns1 zliQ}7){INvzF)`ry+&6U*X zdopCYOpEy^7uAuuedzMA#&8^Yms??`=vCgiy%mr)B{k_0%YDx@thWn{M^9tmyZvnq z3eh=y9CrsFo8p)}zWD4+FgDDePOnd5z&ZKY!NR2rTbCBicW{`d(^k3BzyIE3Cr<55 zpD37i20f5Mp2~;_zfLWP7l{iv(fqY^epJx9yDPH(hCea(eXT`~Yu5Sl37sHhZs6N2 zHkGpTVjt1>(XczZERHAE}viJmlcrS`3En z5)qjWb~*zEoT=|mE5ZyEikEj7vA{$~ire$PSK7Xtk8n2*U-db7KgQ-dqnh>0Q&tBJ#t>&#KUO ziLbxk$z4N#Lp6SDz_Uu9Mq4qt#)MS@RgO8QKZIRVVxM5Ib(gK5ejB4qQ6STR5>I%( z0B^pqomy#?Xds~%zs{JSH%;{V?*54+n18R^B3H-u-k`OL5!2f zr<^hFL<24o3|#`3O2P`O0_PZNLZEGx4GlZ3grXqaBIW|);^R9i{1npkGX}8+@154x zy;jujd-!bDY~L38i9PaH63>m&tsWDMY!xlEl+RzCbLIEByKlnAX{fm)XQv&CE(?pd zDXW${GNlxxJ@b%?e2}!i%Ya4c>$^uN5Ui5AeV^uH;K3xpZQ7|iw*!m0INH5>pU=rT zE>QT2r*dO=MrB?Em z+d#?dV)WVQpXpTrJ#aksWa%*!5pz2q=p0x+d|ULuhefgI6x3(HlSV`Sl>>Y zr@4j#1kQhHalRr_*4-&#n-4r5JYk|iNke0W*)>L54#vJ?Z#FRt&b0t^qZgGHe3I@;BHQu9o2W(aKi_p_T zjm-zZrX!xi96yt|)h(_g&p&K$-}P?ew&=mro6H~WCDi0d5r*?vCir;@$*Bbs4pr#^ z)S6GeWC1|dW648;&|s=^x{OslTY%^LM33V)S9kN1zoi#lU0je0g}iosk$Ul<^TJq) zQNM=P;br_JN4ikp{%6jJu#q8QBGUsRXd%xgD8y(bB_(nD zPZplxfUe+aW)IAD(&{`4*AmpkzEGvXPSSq(@hCGN*W3d0^&w>)No;J-gN0 zO86G2&A&Q?C8)%g9K5Ap+xX(WDJ+dS5nep`!jPh&qy!xcbocrS}lL$dLa+%wrIU*ru9*>(l?1@C7@6)@Uk!m$E6r~$A*#fW9^&E zOtml^*4mG0^`bGEfKBo<+BZD6s<&tYjBTPprFgM_Ps3>V{!MztHFE7-wrYn1XN2_NG~ zzxoJBh_+DX?2|vj-_RhA-|CP4 ztp|2A!DGKy0OK;W>&!dWeO-m2P(i_MOFvpiXASu8O(%6=s`y1~h<5jF^}s+Dlk?iy z%F1?=4+ER@w8Nw8vU5rAcshnAeY0>^%zx4C&_}~t$A-dHa=5itMSX9$9qZT&^o#EY z3vGQku(1-9wGo-i36(x3txTj}5;^h;Qg#REG18INm3K7ou!0zi6nd19?ng3u-!F|j z?V3FH7IP$b*s}|Zms3K=6TSTLkf876sm;H6KaQJK=6q1MvC-raGMOAMRPHrP2GCWz zHwz)e?IcL$)%zJGgZe@_;uFfwTNQ=R!o8n4>w@-X5;PJY*fo10-5WVQp;~tHjtPr# zlYNF-sfh_Nh;@jLofd|*N-SvBblcC`1E7iX7m6|rfMps<`9i08(NRKKMJH8`b*5f+ z5bv_bTuWZO$*$~|rI>g-DcRi87Qsn7eEWYSz(!}##D_T40 zY2=da4IMM@s};*iO3FhhFG8W8(OLb;dr}@lt8V}xCdNcb7!2*pYcuVK>slFkezR*s z)|YPeTeH_``w-^rw&|jhk2f97v@I*q$-$zd zF;{IJP*GxXmU+yPk5U{HjFqJspHF(Llj)ZiNUcb z0lG3~q8PSq6Sa6njr~&zAn`n*#Tw3Aw}Iw@mc9d6fKR>)0>p$OnCS$CVae!HNHI_4 zr=!u~Ibk{(c}C8eGm+)*2X>UC=D5U@6DXuvA{y?Ov4!R0c+xy7HJ zOst*gs>HRD3*$}X?^VZIoS!fLLv6A&$ie^c)WTBU`D|7q;-}P+)RnT-&1eI;esT(6 z;HB~H#QYY#B8bVn>eCqfyN8+m-{Ygf#d~Ys22}($J>H4!B?6qJjnBQA&X2fUNob&B znKkTw%joDNC<7pY<+-y5T?0Adt*n^^7>Dh4*NpZ(QAdp`kOM{$JOrSlfyPcVvw+Vv zn&I;DN^(7ZWgW+JhyaM07L0M0$NhhOA^1Y{T6mV&KU{9}lTUU^`ogf;@Zi}KZqjSE zmFe~5hh1MMUTk|-NYb*U?i3%T#@AdH#WyBh@$dNKNrpEZ?Siv0Jp0}M&x3VYgJ-Ce zi~>y^GFrRoR@`9%l1q36C;;%;smqQ*E9TUv>X*v@Bm1#TGH7yIOMJ z){-D#ag$1HvgI`inIdbdyTtzl=*<(3BPbd@ftwg%Gzjk?Y1yatszn#*ujbSCgPPUq z=&$MjxceA`YT1W$Njis+iU@%%8s4k_$WfCI+KzIRN|_(2B6U3xHMg>+qnQ!D$NK$q z%Hq*fx~%1mpDr)3f0y%~r+W4YW)VjBO^u6)juFAXARN1P?9j?EEn^a~#JKf_dfM>^ zJSDkmRv5f1VLw==X)hVT;1JRfVaENjPQ^y@yY1JU%jH)0lFmqW&eKUu6)+OfU5k(J zz`dxI-xVjAlDqR=Lqo=gbqK1C!Vo64#SO7ufFOjR~LgsVNbo8Dg;^?A#GYSO%s-oVB0O89!%-i$IC4naaUW%)%Y*+r7!VZU54ifqvnnx}2428N> zvkbWxY95)U9Sr&7x!=i)nq}dmDx041>^3dxdDm(OiT+WyeFHaSrr-uSOXV+T+%oSp z@y9WXm&z+T|3hhPp2^n*{>g&EE&rRhurf5S!-~~|D`?SE?E2KCgpfns26dyez&T@U z5GKb`rb-DLEBHQ60f_kxo*lOVt=CKf89lY^CJ^ryC{Gfc5~drks4`qQk!Mw(&Z7HA zX#ulPs)k5u7p{!b>ENoxWd%hKpH#nBs@StJR;e?jMw9Hi^k~_`>aE(Hkb`S~pqwvT!}@+sywdc)g7 ztJO5F(E7i#A_;Vz&hhEQIGsl<2~?ZTK{1){{HY%D`bsE{jt>k`GOCz2#K=dV4+4jTj^+^(-#J$byJDUdT^2iShCTvwE zxh|dewvR5JtV#3tkepzOb;>+?Zf3E}kqHHR@3foWz7^Ax9AZCgGMf)+V4xZj`4?XD z%fhZyRYEcH54Zz@7!2=ipr+mp@WV4^!H#g3;YJP^aHY*LJgBoKxb~Q$J)W?gEXD#= zk_I6AOTII%2B%K#l!>l?ED4Q6$K$rluqNB5neMIC)d{M*jZWC+MNF`*6)qg!H!PGd zI(*)vu%p6BNRo3u``qX%7HW!P-v!;St@kME?d!Yj9I1ACby*MV*63~Z`VY?;w6Oli zBIEHqu0tKJ$x9Dc02mDsh8u*7D9#L+o?=q|72q8{N7s}!F;P>%BH(jlI4cksn8=T2 zXw6H~HSgUJt!g2ea@{oPg|^c@9e>S`w2xVZPbY^G7faBAAyMQ}t7Nna=ei~{_%A=H zeOLAEHksSna^uO`jgT}TU@d4n8bG1M#Kg3TmTxDdE&nenX0Cl=+>1A;YI-JyRNZkk zqyb$oxhvml@7PA^oa$h`QAmJ#vi3i`nKXT7{;=y-BH?iR?Y;A3di_#>DzQ;u;F+iq zLs<|R8A%8c2~`E0_p-qeg~^Cgh3_8^xUyu}M7e$}oBya`Xvl&mj2C(G%a<=RPghf6 zPI`E(F+DQ)*Lnr-WX??&vQG4TuoDM~MY|x6h1F}0cXT*ya;V;Khx?ehK*`K<^bi0I zw8nm=;nC5zfGG`k9x8QIh(KgWCWEQ;|6~%f_$gCds=_nS@23p#|YkOm0 zuX~Gdppy5tB>R4w_hcSdxJC5OX9lkN^9EOLR5Fr^8a1;%cRzb$<8o#Q3;?0+MW(ZE z-8#9sc8e%k_nWXs$nu_dg1qKAazX`y?gS?Az;y!^0qrX%jtKHfw&ZvwZ~JwwVYMOS z@cWuiy)Ca7#8x|$T~9#YLHEzcl{1j?H9}m!#=U#@n$4e59(T8zedO~ksnxd8Zd@T= zn_-<#_>4lMXkXGII|ZVJwmtk6++}|c!e6}nl#?)fx$JMn z>vz^Md@|qzS*);FYU>57kOO7^&`gcRY5h#ze)sS5Y9g}*UI%_Cr3>*N={h6BwUsLu zRFU!ir0SKz55{lmxD9_D>FrGMA!aPtN1K^4CpmJ}eOEr-*;bfn=%uwXpAFis{ZnOF z!<(9Ojl9RuME;1crxU@%Kq=Ec9#`*5A-nM#MlVJI=~elPSpeBVVqt5d#U)Ds+<_e+ zgFhgpqEhC|C?Kmd0);)v^VNx!*Qcqy>bo{t`M5ppQF@7PRuV)+u$)_ z7ML`RZ1(yJA^-AQ789UXNrZ@fp|9TxDXsi?Kw&GkZn`%nVlxfo7HAajxj*<&UK(MSw<%c@~U&lQy}XH)LJ;TgvVD z(L9|OPest7Tt!gl-=3KqWnIQ=AUKg@F4&vCT>&;Sv_H&&{96g7|}ka?JH zs6y#c3oSKUCjo(jPfYK~h&r6UV9BC1`{^Q!;vK`-A_!c61>48{pc5Sc*O5*0NM4=I@D4nZSw3LfBalQMF2fshu-ojM}W zpj)?wpeVM%Br@?z@N5^UsL0;ik1_3f(~wP};2D z-M>^&fQaKe4Xk|l4KhhEWI`MF&`nlzc<3C76oG=M3Q>t7)a&<=43h*5b5Ft7d?PX<)&!`Umx6E=E-0I zk;`S;lsu##N;-4F^+|wY72!<<+<1GDOHyYd490MGN+bYY9s)Iq{1BrzT_y|AYFXn` z07I^k-+?IT)M#BdeqM?A=QKz1GZ98}JS9Wbe^+<1ZZwjGD72{wSlQgqWfIw8b@gLi zfRT0P@yPE*&pJ6dnJR-GwD7ZM_aS&9oD4e?XZGWNQEq{L=Li4=5Fw8MCoMs;&N(S? zI2yri*DSIDcNecCaf5tyn`;@*{uf?*ImE+oRh$%A1rPtP^RC>sRtWMm@xjy1%imD# z&(zXkDETwc6{gAU0(t8v{cwqax+v+K%6Wt!TiwwIi1C)^wvvf$K7RaU*6Azs@tgD1 z{=2KwG8s_)oY&rz#{Th-KK$?j#a=P1|plO>jyuN2? zq{GC(@UrnSTNKOPxu&@T3xg&>c%Z0y_!OZkJQZcxVRlfKK^-gEz}@<3qp5##}?k8$oI< zwBmaLRmT6#&AtgIDaLB;A+B)3l6XaN3GdW)1WG0DlU$OL+cJ-~zt6VPz_X|Vlmp7) z)*~$`*SAY*j-T8veQr0z{ZOvvz%z=7MqtVGxL%lwV41tXO$=1PO03JDFc6G{9UFWO zPgr>V`kDj=_5jgbgQS&kWqoRx7mVCA&5`)|ZDto`v~(WIKPd!5pXsG5K17}R7q<7hS@X%itaTtdRrA}8jN(xUB&~!}82)%!w*gPOOe}rOD+q7eG`V;n*6D`h~*uY`u#B1W8 zsf*3z$3TRcU`HYXP{g5&p#-R~D&3?+uwyX2WTFrM6sK+gq}r~o{Bb-C|VmYWyw zJ<=VzdOi5Tp^?9bD4C0ZJBj88I<}979juFDz4kW@+2!g~lbkFaQgnTBNbpxzq;MHDR zU;heTwH>`dhKm1AdzK$b!;fJfs1owlz>dHM4)P@UeD{7i{P*Y+KM6EE?gPm-EPLQ_ za^8QTuFH`2e;ywnZ!u6F|2O4)#mh~=`CkC`u4e!DN(P5)^9)DY zGA74_$MDFu1-;z%Z-nAsJpYqYo^fXWJ$K(MhcyT*Y1CH;N%%8h@i>xY;+tyT3RS?~ z?7SOy+}3~075-t&-|W0CDUx!1%#P+1YPm0b^BL!K=^B5vRld;s5B( zW_G3Uqji0h8vHZ?o8JXVGW<89A$0D_yVJdSpbkD60BI(ND7eE+56kzcyr48^>S;LV zp~VK4%F~Iv__3q0``K=&TFf)Du%xnQI7-9As*p@HNC?`>MxoLJc>IxipRT#h0a><` ztXS{v{{gK9V5AlaoZCddobZYSk}?!B@2TD@IMB9@S_Ki(eOH1@NI*uQEe6(=8Ds;z zHF^upB~qla@ZYDhy9CPw=iH z&eZyb2Cbh+D0kbuv>N#Gh5P6OF&*sIgwr%P*dn=c+|%Dxb;t1R>mlDa>dorBFZy1I zJDuuo?Mnbe@Rc)r7P05$z)Nzk${unyu32bUm}P`0c38YgvUHBikS2T=O&-E|0PU*X z8BRL^Zy~`ZdQGTo-!%W$jez{_K>`T+q*{H@TQ7VIW;RKOTi4?B$ON%C&+k<565z`Y7fQa))IfC@_=1c8eBIy`FKnmACDK$;an_G75$N+bN@1h7W zzh+lPxni)XDsb+{>mv@AZ2)4s!N89-JYQ^XxRF5a< zslj?_Cr(>fFsj^%g5<&No{kE3zMF(Atrg0lZ-Ao>1Mip{d!l}6X=zJ^r@c`@l5s(i;pKv`XL>l5m0aNmf^-SH01N=bz^{3YzqN>fGZOzK zwEyEHXBl)!oahPeZY0D`FY_L8Q{m(`;NNN!xGM_aYfw=kzO1KJ`Nw5Su|*n79-Ao6 z`DnJ_Ga_JZz~vjJHY-20`y_GhDMz1%J&M;1H%z)8J=#f4;Xgyya}i(zOOZRFp_i*q zKUTZTWt%ts1m|TKTyOBZM;I`a(n{X5Yu9SLB?9KCnz}j~_?~LU?!QrMS=rj!+QG2_ zaSrE>a5R9E?>><{eDTXAcz)gd9rm}X@PC-X;P6i7P`$-o2dqr`B3yN)F7%vxD?mF` z_U+YnKzBZ(BN1qUIv%`1LxEp<+)9p=^UPKvY>jn2GEh}7X~)#SErrFxs-K{~9>9DJ z9!S#upI_*)QouUW>-sV{h^<@^8S7YmPp0`A*nT3UG@koI(3`L)tfinJcrGaMNr4+? z)qt{uj`VUg6~r=f&&Y{m-@c{^dnAUmt1x0Z6Bl7x2U!a&i*HL8v|N*q(U_q!=85P6ezr zoq6^MACdr$itthRzw*)E8r~%=E|)FQ6kD`$tl-rpLJA5BB@)5s}cP-$M#=GmT2HAlCH~Lf(cChbDv;qF94`hsa`Q@FDO~8`Di>UCju5&!$ZP z*X50r=h?TN!x$Gql0f8PSx^B)dW4VAUt8wM@&!ShN>6Ys@B>DS%^{oIn))_I2sM+_ z%RI{D?}+g}>5heE*q3!rmU@0KgxNeEkzUw-*?cVZY%SKrWuVzE@dSE#>K*%|@Cm89 zFMb$^iSbwD-_A5g?CVpOa?F-0~!^w10RVJj=R#V@A7+lczJb>FSJ!GR)+|c zQyxHCj64}vM9=n+>PnPtHa*AL3T{6})9#0b z1-v+QW|)I!`N&RrlR=d1*1iwF}khM~F2qOubl7{-(z(EPNZ;Octz{0Y67U2uwt+i+4W9w+GSt!BZH3Qj`*;44*LdGhs3afn$>=5PF@eoe#G_4!u-WC zi+%Ls6#E(!M8z6Lt`ngpkVa(Z#l=M;o;=O#Khfde0+R%e*Nc)bWKd2 zX>&g@;OEL{<5N2)#d=OAy7SW~eQt(h;M(c!lV+urmy_e(8dCOf4`6L0U%&p0e!GVB zd;JCu($1mCBZ)Z}>4O)_Yy! znq3M~QptgV>($;rKQO4=HT2!i-CaM+;0P)Z&f}&T`dwXJGE!2FH8qFz_T}Z})spkb zHa3TRE6m<&sNFccJ1!w1!9j?IG!@eAC9|4zTWMl)QsL>X90UH;zj_y{c9w>Qts9b2>%Tn162@=UqTO_ijy823#=1^eeNR2}GCeoDj2;FKDiF6=l7spx>>1tPd zyEZnRPAwOgoTlDY2kKALaF9sC-Hna6Wn^WW=T1KRpukE)`m%}mlBWtoL$`#7g)y;F zkiM{)GOxoMU6fN%q$Jg-ImFRiTOg6j6^TFbWQ^8rxfbx^&gZ=zWt$8FDM??muF{ci zA4hOM=2jBdl)O77GgBKC-OtHWNeRbz_H5ap60g%S?iSp(<^Tml;(F4TC|%wJ^7{3m_^OKskzR}Xlcv@YpO8eVIqtx_hWH=P aksS(@o_wKeg&q-qR8!GZPFFm2`F{b3i8gis literal 0 HcmV?d00001 From aa1694dd660e189604f5cf8623c9d0cb26244e55 Mon Sep 17 00:00:00 2001 From: dzalkind Date: Mon, 30 Sep 2024 11:22:22 -0600 Subject: [PATCH 194/224] Add a note about building docs --- docs/source/how_to_contribute_code.rst | 14 ++++++++++++++ 1 file changed, 14 insertions(+) diff --git a/docs/source/how_to_contribute_code.rst b/docs/source/how_to_contribute_code.rst index 970f5d39..d11666ee 100644 --- a/docs/source/how_to_contribute_code.rst +++ b/docs/source/how_to_contribute_code.rst @@ -22,6 +22,20 @@ Look at the .rst files in the :code:`docs` section of the repo or click on :code The best place to add documentation for your new feature is in an example of the new feature. We are planning to incorporate docstrings from the examples into these docs. +To build the documentation locally, first + +.. code-block:: bash + + conda install -y cmake compilers sphinx sphinxcontrib-bibtex + conda install -y sphinx_rtd_theme>=1.3 + +Then + +.. code-block:: bash + + sphinx-build . ./_build/ + + Testing ------- ROSCO tests its various features through the Examples. From 8778c79bcd027760e6fb6a1db55180ed0b3fa72f Mon Sep 17 00:00:00 2001 From: AbhineetGupta Date: Mon, 30 Sep 2024 11:41:51 -0600 Subject: [PATCH 195/224] Fix global variables in Example 17a and 17b --- Examples/17a_zeromq_simple.py | 36 +++++++++++++-------------- Examples/17b_zeromq_multi_openfast.py | 21 ++++++++-------- 2 files changed, 29 insertions(+), 28 deletions(-) diff --git a/Examples/17a_zeromq_simple.py b/Examples/17a_zeromq_simple.py index e881964c..8c2cbd6e 100644 --- a/Examples/17a_zeromq_simple.py +++ b/Examples/17a_zeromq_simple.py @@ -5,7 +5,7 @@ A demonstrator for ZeroMQ communication. Instead of using ROSCO with with control interface, one could call ROSCO from OpenFAST, and communicate with ZeroMQ through that. -""" +this_dir""" import os @@ -22,15 +22,18 @@ import numpy as np import multiprocessing as mp +# Directories +THIS_DIR = os.path.dirname(os.path.abspath(__file__)) +EXAMPLE_OUT_DIR = os.path.join(THIS_DIR,'examples_out') +os.makedirs(EXAMPLE_OUT_DIR,exist_ok=True) -def main(): - #directories - this_dir = os.path.dirname(os.path.abspath(__file__)) - rosco_dir = os.path.dirname(this_dir) - example_out_dir = os.path.join(this_dir,'examples_out') - os.makedirs(example_out_dir,exist_ok=True) +# Controller parameters +TIME_CHECK = 30 +DESIRED_YAW_OFFSET = 20 +DESIRED_PITCH_OFFSET = np.deg2rad(2) * np.sin(0.1 * TIME_CHECK) + np.deg2rad(2) - logfile = os.path.join(example_out_dir,os.path.splitext(os.path.basename(__file__))[0]+'.log') +def main(): + logfile = os.path.join(EXAMPLE_OUT_DIR,os.path.splitext(os.path.basename(__file__))[0]+'.log') p1 = mp.Process(target=run_zmq,args=(logfile,)) p1.start() p2 = mp.Process(target=sim_rosco) @@ -51,14 +54,11 @@ def run_zmq(logfile=None): server.runserver() def wfc_controller(id,current_time,measurements): - time_check = 30 - desired_yaw_offset = 20 - desired_pitch_offset = np.deg2rad(2) * np.sin(0.1 * time_check) + np.deg2rad(2) if current_time <= 10.0: yaw_setpoint = 0.0 else: - yaw_setpoint = desired_yaw_offset + yaw_setpoint = DESIRED_YAW_OFFSET # Pitch offset if current_time >= 10.0: @@ -77,8 +77,8 @@ def wfc_controller(id,current_time,measurements): def sim_rosco(): # Load yaml file - this_dir = os.path.dirname(os.path.abspath(__file__)) - tune_dir = os.path.join(this_dir, 'Tune_Cases') + THIS_DIR = os.path.dirname(os.path.abspath(__file__)) + tune_dir = os.path.join(THIS_DIR, 'Tune_Cases') parameter_filename = os.path.join(tune_dir, 'NREL5MW.yaml') inps = load_rosco_yaml(parameter_filename) path_params = inps['path_params'] @@ -92,7 +92,7 @@ def sim_rosco(): # # Load turbine model from saved pickle turbine = ROSCO_turbine.Turbine - turbine = turbine.load(os.path.join(example_out_dir, '01_NREL5MW_saved.p')) + turbine = turbine.load(os.path.join(EXAMPLE_OUT_DIR, '01_NREL5MW_saved.p')) # Load turbine data from OpenFAST and rotor performance text file cp_filename = os.path.join( @@ -109,7 +109,7 @@ def sim_rosco(): controller.tune_controller(turbine) # Write parameter input file - sim_dir = os.path.join(example_out_dir,'17_ZeroMQ') + sim_dir = os.path.join(EXAMPLE_OUT_DIR,'17_ZeroMQ') os.makedirs(sim_dir,exist_ok=True) param_filename = os.path.join(sim_dir, 'DISCON_zmq.IN') write_DISCON( @@ -148,7 +148,7 @@ def sim_rosco(): if False: plt.show() else: - plt.savefig(os.path.join(example_out_dir, '17_NREL5MW_ZMQ.png')) + plt.savefig(os.path.join(EXAMPLE_OUT_DIR, '17_NREL5MW_ZMQ.png')) # Check that info is passed to ROSCO op = output_processing.output_processing() @@ -160,7 +160,7 @@ def sim_rosco(): if False: plt.show() else: - plt.savefig(os.path.join(example_out_dir, '17_NREL5MW_ZMQ_Setpoints.png')) + plt.savefig(os.path.join(EXAMPLE_OUT_DIR, '17_NREL5MW_ZMQ_Setpoints.png')) # Spot check input at time = 30 sec. ind_30 = local_vars[0]['Time'] == TIME_CHECK diff --git a/Examples/17b_zeromq_multi_openfast.py b/Examples/17b_zeromq_multi_openfast.py index d3749696..fa2e9675 100644 --- a/Examples/17b_zeromq_multi_openfast.py +++ b/Examples/17b_zeromq_multi_openfast.py @@ -12,19 +12,20 @@ from rosco.toolbox.ofTools.case_gen import CaseLibrary as cl from rosco.toolbox.ofTools.case_gen.run_FAST import run_FAST_ROSCO from rosco.toolbox.ofTools.fast_io import output_processing + +THIS_DIR = os.path.dirname(os.path.abspath(__file__)) +EXAMPLE_OUT_DIR = os.path.join(THIS_DIR, "examples_out") +os.makedirs(EXAMPLE_OUT_DIR, exist_ok=True) TIME_CHECK = 20 DESIRED_YAW_OFFSET = [-10, 10] def main(): - this_dir = os.path.dirname(os.path.abspath(__file__)) - example_out_dir = os.path.join(this_dir, "examples_out") - os.makedirs(example_out_dir, exist_ok=True) # Start wind farm control server and two openfast simulation # as separate processes - logfile = os.path.join(example_out_dir,os.path.splitext(os.path.basename(__file__))[0]+'.log') + logfile = os.path.join(EXAMPLE_OUT_DIR,os.path.splitext(os.path.basename(__file__))[0]+'.log') p0 = mp.Process(target=run_zmq,args=(logfile,)) p1 = mp.Process(target=sim_openfast_1) p2 = mp.Process(target=sim_openfast_2) @@ -41,7 +42,7 @@ def main(): # Check that info is passed to ROSCO for first simulation op1 = output_processing.output_processing() debug_file1 = os.path.join( - example_out_dir, + EXAMPLE_OUT_DIR, "17b_zeromq_OF1", "NREL5MW", "power_curve", @@ -53,7 +54,7 @@ def main(): # Check that info is passed to ROSCO for first simulation op2 = output_processing.output_processing() debug_file2 = os.path.join( - example_out_dir, + EXAMPLE_OUT_DIR, "17b_zeromq_OF2", "NREL5MW", "power_curve", @@ -70,7 +71,7 @@ def main(): if False: plt.show() else: - plt.savefig(os.path.join(example_out_dir, "17b_NREL5MW_ZMQ_Setpoints.png")) + plt.savefig(os.path.join(EXAMPLE_OUT_DIR, "17b_NREL5MW_ZMQ_Setpoints.png")) # Spot check input at time = 30 sec. ind1_30 = local_vars1[0]["Time"] == TIME_CHECK @@ -137,7 +138,7 @@ def sim_openfast_1(): "U": [8], "TMax": 25, } - run_dir = os.path.join(example_out_dir, "17b_zeromq_OF1") + run_dir = os.path.join(EXAMPLE_OUT_DIR, "17b_zeromq_OF1") r.controller_params = {} r.controller_params["LoggingLevel"] = 2 r.controller_params["DISCON"] = {} @@ -156,7 +157,7 @@ def sim_openfast_2(): "U": [8], "TMax": 25, } - run_dir = os.path.join(example_out_dir, "17b_zeromq_OF2") + run_dir = os.path.join(EXAMPLE_OUT_DIR, "17b_zeromq_OF2") r.save_dir = run_dir r.controller_params = {} r.controller_params["DISCON"] = {} @@ -167,4 +168,4 @@ def sim_openfast_2(): if __name__ == "__main__": - main() \ No newline at end of file + main() From f075c807bc75558ceb3471663e8cc0329fd9ba92 Mon Sep 17 00:00:00 2001 From: dzalkind Date: Thu, 3 Oct 2024 08:32:11 -0600 Subject: [PATCH 196/224] Try numpy<2.0 --- pyproject.toml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/pyproject.toml b/pyproject.toml index 8b51ab87..ce8c1f83 100644 --- a/pyproject.toml +++ b/pyproject.toml @@ -43,7 +43,7 @@ classifiers = [ # Optional dependencies = [ "control", - "numpy", + "numpy<2.0", "matplotlib", "scipy", "pandas", From 4486d7ae902d6900a5e5440412d36a80ddb2df8c Mon Sep 17 00:00:00 2001 From: Ben Clayton <55184924+BenClaytonARUP@users.noreply.github.com> Date: Thu, 3 Oct 2024 20:25:25 +0100 Subject: [PATCH 197/224] Fixed bug where TRA_LastRefSpd was set to a generator speed not the LSS speed (#381) --- rosco/controller/src/ControllerBlocks.f90 | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/rosco/controller/src/ControllerBlocks.f90 b/rosco/controller/src/ControllerBlocks.f90 index be9e6400..986322c2 100644 --- a/rosco/controller/src/ControllerBlocks.f90 +++ b/rosco/controller/src/ControllerBlocks.f90 @@ -490,7 +490,7 @@ SUBROUTINE RefSpeedExclusion(LocalVar, CntrPar, objInst, DebugVar) LocalVar%TRA_LastRefSpd = CntrPar%TRA_ExclSpeed - CntrPar%TRA_ExclBand / 2 ENDIF ELSE - LocalVar%TRA_LastRefSpd = LocalVar%VS_RefSpd + LocalVar%TRA_LastRefSpd = VS_RefSpeed_LSS END IF END IF From 4055eeb532dfaa9a22face375be7f5aec427a5c1 Mon Sep 17 00:00:00 2001 From: dzalkind Date: Thu, 3 Oct 2024 13:51:46 -0600 Subject: [PATCH 198/224] Document PRC API changes --- docs/source/api_change.rst | 32 ++++++++++++++++++++++++++++++-- 1 file changed, 30 insertions(+), 2 deletions(-) diff --git a/docs/source/api_change.rst b/docs/source/api_change.rst index 0127cd07..355af0c4 100644 --- a/docs/source/api_change.rst +++ b/docs/source/api_change.rst @@ -9,6 +9,34 @@ The changes are tabulated according to the line number, and flag name. The line number corresponds to the resulting line number after all changes are implemented. Thus, be sure to implement each in order so that subsequent line numbers are correct. +2.9.0 to develop +-------------------------- +**New power reference control mode** + +* De-rate or power boost the turbine using the reference speed, rated torque, or minimum pitch. More details can be found in the Examples page. + +====== ================= ====================================================================================================================================================================================================== +Changed in ROSCO develop +---------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- +Line Input Name Example Value +====== ================= ====================================================================================================================================================================================================== +18 PRC_Mode 0 ! PRC_Mode - Power reference tracking mode{0: power control disabled, 1: lookup table from wind speed to generator speed setpoints, 2: change speed, torque, pitch to control power} +====== ================= ====================================================================================================================================================================================================== + +====== ======================= =============================================================================================================================================================================================================================================================== +New in ROSCO develop +------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- +Line Input Name Example Value +====== ======================= =============================================================================================================================================================================================================================================================== +99 PRC_Comm 0 ! PRC_Comm - Power reference communication mode when PRC_Mode = 2, 0- use constant DISCON inputs, 1- use open loop inputs, 2- use ZMQ inputs +100 PRC_R_Torque 1.00000 ! PRC_R_Torque - Constant power rating through changing the rated torque, used if PRC_Mode = 2, PRC_Comm = 0, default is 1, effective above rated [-] +101 PRC_R_Speed 1.00000 ! PRC_R_Speed - Constant power rating through changing the rated generator speed, used if PRC_Mode = 2, PRC_Comm = 0, default is 1, effective above rated [-] +102 PRC_R_Pitch 1.00000 ! PRC_R_Pitch - Constant power rating through changing the fine pitch angle, used if PRC_Mode = 2, PRC_Comm = 0, default is 1, effective below rated [-] +103 PRC_Table_n 20 ! PRC_Table_n - Number of elements in PRC_R to _Pitch table. Used if PRC_Mode = 1. +104 PRC_R_Table 0.0000 0.0526 0.1053 0.1579 0.2105 0.2632 0.3158 0.3684 0.4211 0.4737 0.5263 0.5789 0.6316 0.6842 0.7368 0.7895 0.8421 0.8947 0.9474 1.0000 ! PRC_R_Table - Table of turbine rating versus fine pitch (PRC_Pitch_Table), length should be PRC_Table_n, default is 1 [-]. Used if PRC_Mode = 1. +105 PRC_Pitch_Table 0.2296 0.2222 0.2144 0.2066 0.1984 0.1902 0.1814 0.1726 0.1633 0.1538 0.1439 0.1334 0.1226 0.1112 0.0989 0.0858 0.0715 0.0552 0.0351 0.0000 ! PRC_Pitch_Table - Table of fine pitch versus PRC_R_Table, length should be PRC_Table_n [rad]. Used if PRC_Mode = 1. +====== ======================= =============================================================================================================================================================================================================================================================== + 2.8.0 to 2.9.0 ------------------------------- **Flag to use exteneded Bladed Interface** @@ -48,7 +76,7 @@ Thus, be sure to implement each in order so that subsequent line numbers are cor * The set point is changed at a slow rate `TRA_RateLimit` to avoid generator power spikes. `VS_RefSpd`/100 is recommended. ====== ======================= =============================================================================================================================================================================================================================================================== -Removed in ROSCO develop +Removed in ROSCO 2.9.0 ------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- Line Input Name Example Value ====== ======================= =============================================================================================================================================================================================================================================================== @@ -59,7 +87,7 @@ Line Input Name Example Value ====== ======================= =============================================================================================================================================================================================================================================================== -New in ROSCO develop +New in ROSCO 2.9.0 ------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- Line Input Name Example Value ====== ======================= =============================================================================================================================================================================================================================================================== From 849dcfd5f72cbfb5d77eb0a1426ad998807fbd71 Mon Sep 17 00:00:00 2001 From: dzalkind Date: Fri, 25 Oct 2024 11:52:42 -0600 Subject: [PATCH 199/224] Regenerate DISCONs --- Examples/Test_Cases/BAR_10/BAR_10_DISCON.IN | 36 +++++++------- .../DISCON-UMaineSemi.IN | 23 +++++---- Examples/Test_Cases/MHK_RM1/MHK_RM1_DISCON.IN | 47 +++++++++++-------- Examples/Test_Cases/NREL-5MW/DISCON.IN | 43 ++++++++++------- .../NREL_2p8_127/NREL-2p8-127_DISCON.IN | 29 +++++++----- 5 files changed, 103 insertions(+), 75 deletions(-) diff --git a/Examples/Test_Cases/BAR_10/BAR_10_DISCON.IN b/Examples/Test_Cases/BAR_10/BAR_10_DISCON.IN index e135132e..c882cb7b 100644 --- a/Examples/Test_Cases/BAR_10/BAR_10_DISCON.IN +++ b/Examples/Test_Cases/BAR_10/BAR_10_DISCON.IN @@ -1,5 +1,5 @@ ! Controller parameter input file for the BAR_10 wind turbine -! - File written using ROSCO version 2.9.4 controller tuning logic on 09/03/24 +! - File written using ROSCO version 2.9.4 controller tuning logic on 10/25/24 !------- SIMULATION CONTROL ------------------------------------------------------------ 1 ! LoggingLevel - {0: write no debug files, 1: write standard output .dbg-file, 2: LoggingLevel 1 + ROSCO LocalVars (.dbg2) 3: LoggingLevel 2 + complete avrSWAP-array (.dbg3)} @@ -54,17 +54,17 @@ !------- BLADE PITCH CONTROL ---------------------------------------------- 30 ! PC_GS_n - Amount of gain-scheduling table entries -0.057899 0.086034 0.108220 0.127602 0.145231 0.161628 0.177110 0.191882 0.205973 0.219605 0.232854 0.245775 0.258317 0.270576 0.282622 0.294421 0.305965 0.317359 0.328547 0.339534 0.350412 0.361066 0.371600 0.382012 0.392231 0.402383 0.412328 0.422200 0.431927 0.441532 ! PC_GS_angles - Gain-schedule table: pitch angles [rad]. --0.017426 -0.014498 -0.012232 -0.010428 -0.008956 -0.007733 -0.006701 -0.005818 -0.005054 -0.004387 -0.003799 -0.003276 -0.002810 -0.002390 -0.002011 -0.001666 -0.001352 -0.001064 -0.000799 -0.000554 -0.000328 -0.000118 0.000077 0.000259 0.000430 0.000589 0.000739 0.000881 0.001014 0.001139 ! PC_GS_KP - Gain-schedule table: pitch controller kp gains [s]. --0.000714 -0.000623 -0.000552 -0.000496 -0.000450 -0.000412 -0.000380 -0.000353 -0.000329 -0.000308 -0.000290 -0.000274 -0.000259 -0.000246 -0.000234 -0.000223 -0.000214 -0.000205 -0.000196 -0.000189 -0.000182 -0.000175 -0.000169 -0.000164 -0.000158 -0.000153 -0.000149 -0.000144 -0.000140 -0.000136 ! PC_GS_KI - Gain-schedule table: pitch controller ki gains [-]. +0.058164 0.086244 0.108382 0.127744 0.145359 0.161744 0.177216 0.191984 0.206067 0.219693 0.232936 0.245853 0.258392 0.270647 0.282689 0.294487 0.306027 0.317418 0.328605 0.339589 0.350465 0.361118 0.371650 0.382060 0.392278 0.402428 0.412372 0.422243 0.431968 0.441572 ! PC_GS_angles - Gain-schedule table: pitch angles [rad]. +-0.017407 -0.014484 -0.012222 -0.010420 -0.008950 -0.007728 -0.006697 -0.005815 -0.005051 -0.004384 -0.003796 -0.003275 -0.002808 -0.002389 -0.002009 -0.001665 -0.001350 -0.001063 -0.000798 -0.000553 -0.000327 -0.000117 0.000078 0.000260 0.000430 0.000590 0.000740 0.000881 0.001014 0.001140 ! PC_GS_KP - Gain-schedule table: pitch controller kp gains [s]. +-0.000713 -0.000622 -0.000552 -0.000496 -0.000450 -0.000412 -0.000380 -0.000352 -0.000329 -0.000308 -0.000290 -0.000273 -0.000259 -0.000246 -0.000234 -0.000223 -0.000214 -0.000205 -0.000196 -0.000189 -0.000182 -0.000175 -0.000169 -0.000164 -0.000158 -0.000153 -0.000149 -0.000144 -0.000140 -0.000136 ! PC_GS_KI - Gain-schedule table: pitch controller ki gains [-]. 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 ! PC_GS_KD - Gain-schedule table: pitch controller kd gains 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 ! PC_GS_TF - Gain-schedule table: pitch controller tf gains (derivative filter) 1.570000000000 ! PC_MaxPit - Maximum physical pitch limit, [rad]. --0.01505000000 ! PC_MinPit - Minimum physical pitch limit, [rad]. +-0.01613000000 ! PC_MinPit - Minimum physical pitch limit, [rad]. 2.000000000000 ! PC_MaxRat - Maximum pitch rate (in absolute value) in pitch controller, [rad/s]. -2.00000000000 ! PC_MinRat - Minimum pitch rate (in absolute value) in pitch controller, [rad/s]. 79.85313000000 ! PC_RefSpd - Desired (reference) HSS speed for pitch controller, [rad/s]. --0.01505000000 ! PC_FinePit - Record 5: Below-rated pitch angle set-point, [rad] +-0.01613000000 ! PC_FinePit - Record 5: Below-rated pitch angle set-point, [rad] 0.017450000000 ! PC_Switch - Angle above lowest minimum pitch angle for switch, [rad] !------- INDIVIDUAL PITCH CONTROL ----------------------------------------- @@ -82,21 +82,21 @@ 62000.00000000 ! VS_MaxRat - Maximum torque rate (in absolute value) in torque controller, [Nm/s]. 70282.09458000 ! VS_MaxTq - Maximum generator torque in Region 3 (HSS side), [Nm]. 0.000000000000 ! VS_MinTq - Minimum generator torque (HSS side), [Nm]. -27.49717000000 ! VS_MinOMSpd - Minimum generator speed [rad/s] -12.03868000000 ! VS_Rgn2K - Generator torque constant in Region 2 (HSS side). Only used in VS_ControlMode = 1,3,4 +28.78748000000 ! VS_MinOMSpd - Minimum generator speed [rad/s] +9.966800000000 ! VS_Rgn2K - Generator torque constant in Region 2 (HSS side). Only used in VS_ControlMode = 1,3,4 5000000.000000 ! VS_RtPwr - Wind turbine rated power [W] 63892.81326000 ! VS_RtTq - Rated torque, [Nm]. -75.83317000000 ! VS_RefSpd - Rated generator speed [rad/s] +79.39164000000 ! VS_RefSpd - Rated generator speed [rad/s] 1 ! VS_n - Number of generator PI torque controller gains --2454.67747000 ! VS_KP - Proportional gain for generator PI torque controller [-]. (Only used in the transitional 2.5 region if VS_ControlMode =/ 2) +-2410.54689000 ! VS_KP - Proportional gain for generator PI torque controller [-]. (Only used in the transitional 2.5 region if VS_ControlMode =/ 2) -332.357190000 ! VS_KI - Integral gain for generator PI torque controller [s]. (Only used in the transitional 2.5 region if VS_ControlMode =/ 2) -9.76 ! VS_TSRopt - Power-maximizing region 2 tip-speed-ratio. Only used in VS_ControlMode = 2. +10.21 ! VS_TSRopt - Power-maximizing region 2 tip-speed-ratio. Only used in VS_ControlMode = 2. !------- FIXED PITCH REGION 3 TORQUE CONTROL ------------------------------------------------ 60 ! VS_FBP_n - Number of gain-scheduling table entries 3.000000 3.181847 3.363694 3.545541 3.727388 3.909234 4.091081 4.272928 4.454775 4.636622 4.818469 5.000316 5.182163 5.364010 5.545857 5.727703 5.909550 6.091397 6.273244 6.455091 6.636938 6.818785 7.000632 7.182479 7.364326 7.546172 7.728019 7.909866 8.091713 8.273560 8.831108 9.388656 9.946204 10.503752 11.061300 11.618848 12.176396 12.733944 13.291492 13.849040 14.406588 14.964136 15.521684 16.079232 16.636780 17.194328 17.751876 18.309424 18.866972 19.424520 19.982068 20.539616 21.097164 21.654712 22.212260 22.769808 23.327356 23.884904 24.442452 25.000000 ! VS_FBP_U - Operating schedule table: Wind speeds [m/s]. -27.497174 29.163932 30.830691 32.497450 34.164208 35.830967 37.497725 39.164484 40.831243 42.498001 44.164760 45.831518 47.498277 49.165035 50.831794 52.498553 54.165311 55.832070 57.498828 59.165587 60.832346 62.499104 64.165863 65.832621 67.499380 69.166138 70.832897 72.499656 74.166414 79.853125 79.853125 79.853125 79.853125 79.853125 79.853125 79.853125 79.853125 79.853125 79.853125 79.853125 79.853125 79.853125 79.853125 79.853125 79.853125 79.853125 79.853125 79.853125 79.853125 79.853125 79.853125 79.853125 79.853125 79.853125 79.853125 79.853125 79.853125 79.853125 79.853125 79.853125 ! VS_FBP_Omega - Operating schedule table: Generator speeds [rad/s]. -9102.377387 10239.314561 11443.140643 12713.855635 14051.459535 15455.952344 16927.334062 18465.604688 20070.764223 21742.812668 23481.750020 25287.576282 27160.291453 29099.895532 31106.388520 33179.770417 35320.041223 37527.200937 39801.249560 42142.187093 44550.013533 47024.728883 49566.333142 52174.826309 54850.208385 57592.479370 60401.639263 63277.688066 66220.625777 65712.002182 65712.002182 65712.002182 65712.002182 65712.002182 65712.002182 65712.002182 65712.002182 65712.002182 65712.002182 65712.002182 65712.002182 65712.002182 65712.002182 65712.002182 65712.002182 65712.002182 65712.002182 65712.002182 65712.002182 65712.002182 65712.002182 65712.002182 65712.002182 65712.002182 65712.002182 65712.002182 65712.002182 65712.002182 65712.002182 65712.002182 ! VS_FBP_Tau - Operating schedule table: Generator torques [N m]. +28.787479 30.532450 32.277421 34.022392 35.767363 37.512335 39.257306 41.002277 42.747248 44.492220 46.237191 47.982162 49.727133 51.472104 53.217076 54.962047 56.707018 58.451989 60.196960 61.941932 63.686903 65.431874 67.176845 68.921817 70.666788 72.411759 74.156730 75.901701 77.646673 79.853125 79.853125 79.853125 79.853125 79.853125 79.853125 79.853125 79.853125 79.853125 79.853125 79.853125 79.853125 79.853125 79.853125 79.853125 79.853125 79.853125 79.853125 79.853125 79.853125 79.853125 79.853125 79.853125 79.853125 79.853125 79.853125 79.853125 79.853125 79.853125 79.853125 79.853125 ! VS_FBP_Omega - Operating schedule table: Generator speeds [rad/s]. +8249.620141 9280.043228 10371.088729 11522.756644 12735.046973 14007.959716 15341.494872 16735.652443 18190.432427 19705.834825 21281.859637 22918.506863 24615.776503 26373.668557 28192.183024 30071.319906 32011.079201 34011.460910 36072.465033 38194.091570 40376.340521 42619.211886 44922.705664 47286.821857 49711.560463 52196.921483 54742.904917 57349.510765 60016.739027 62334.106098 62334.106098 62334.106098 62334.106098 62334.106098 62334.106098 62334.106098 62334.106098 62334.106098 62334.106098 62334.106098 62334.106098 62334.106098 62334.106098 62334.106098 62334.106098 62334.106098 62334.106098 62334.106098 62334.106098 62334.106098 62334.106098 62334.106098 62334.106098 62334.106098 62334.106098 62334.106098 62334.106098 62334.106098 62334.106098 62334.106098 ! VS_FBP_Tau - Operating schedule table: Generator torques [N m]. !------- SETPOINT SMOOTHER --------------------------------------------- 1.00000 ! SS_VSGain - Variable speed torque controller setpoint smoother gain, [-]. @@ -109,7 +109,7 @@ 1.00000 ! PRC_R_Pitch - Constant power rating through changing the fine pitch angle, used if PRC_Mode = 2, PRC_Comm = 0, default is 1, effective below rated [-] 20 ! PRC_Table_n - Number of elements in PRC_R to _Pitch table. Used if PRC_Mode = 1. 0.0000 0.0526 0.1053 0.1579 0.2105 0.2632 0.3158 0.3684 0.4211 0.4737 0.5263 0.5789 0.6316 0.6842 0.7368 0.7895 0.8421 0.8947 0.9474 1.0000 ! PRC_R_Table - Table of turbine rating versus fine pitch (PRC_Pitch_Table), length should be PRC_Table_n, default is 1 [-]. Used if PRC_Mode = 1. -0.1766 0.1707 0.1647 0.1586 0.1522 0.1458 0.1391 0.1323 0.1252 0.1178 0.1102 0.1022 0.0939 0.0850 0.0755 0.0655 0.0538 0.0405 0.0238 -0.0123 ! PRC_Pitch_Table - Table of fine pitch versus PRC_R_Table, length should be PRC_Table_n [rad]. Used if PRC_Mode = 1. +0.1686 0.1632 0.1577 0.1520 0.1462 0.1402 0.1340 0.1278 0.1211 0.1144 0.1073 0.0999 0.0922 0.0839 0.0751 0.0657 0.0549 0.0427 0.0273 -0.0161 ! PRC_Pitch_Table - Table of fine pitch versus PRC_R_Table, length should be PRC_Table_n [rad]. Used if PRC_Mode = 1. 2 ! PRC_n - Number of elements in PRC_WindSpeeds and PRC_GenSpeeds array 0.07854 ! PRC_LPF_Freq - Frequency of the low pass filter on the wind speed estimate used to set PRC_GenSpeeds [rad/s] 3.0000 25.0000 ! PRC_WindSpeeds - Array of wind speeds used in rotor speed vs. wind speed lookup table [m/s] @@ -127,7 +127,7 @@ 36 26 ! PerfTableSize - Size of rotor performance tables, first number refers to number of blade pitch angles, second number referse to number of tip-speed ratios 60 ! WE_FOPoles_N - Number of first-order system poles used in EKF 3.0000 3.1818 3.3637 3.5455 3.7274 3.9092 4.0911 4.2729 4.4548 4.6366 4.8185 5.0003 5.1822 5.3640 5.5459 5.7277 5.9096 6.0914 6.2732 6.4551 6.6369 6.8188 7.0006 7.1825 7.3643 7.5462 7.7280 7.9099 8.0917 8.2736 8.8311 9.3887 9.9462 10.5038 11.0613 11.6188 12.1764 12.7339 13.2915 13.8490 14.4066 14.9641 15.5217 16.0792 16.6368 17.1943 17.7519 18.3094 18.8670 19.4245 19.9821 20.5396 21.0972 21.6547 22.2123 22.7698 23.3274 23.8849 24.4425 25.0000 ! WE_FOPoles_v - Wind speeds corresponding to first-order system poles [m/s] --0.00969265 -0.01028018 -0.01086771 -0.01145523 -0.01204276 -0.01263029 -0.01321781 -0.01380534 -0.01439287 -0.01498039 -0.01556792 -0.01615544 -0.01674297 -0.01733050 -0.01791802 -0.01850555 -0.01909308 -0.01968060 -0.02026813 -0.02085566 -0.02144318 -0.02203071 -0.02261823 -0.02320576 -0.02379329 -0.02438081 -0.02496834 -0.02555587 -0.02614339 -0.02379613 -0.02047291 -0.02537932 -0.03151563 -0.03840840 -0.04587537 -0.05382394 -0.06221064 -0.07100937 -0.08011138 -0.08959645 -0.09946249 -0.10970584 -0.12021535 -0.13105665 -0.14226361 -0.15376640 -0.16552312 -0.17764204 -0.19004300 -0.20272586 -0.21577830 -0.22897091 -0.24242644 -0.25613739 -0.27000365 -0.28425482 -0.29866687 -0.31351260 -0.32866968 -0.34414305 ! WE_FOPoles - First order system poles [1/s] +-0.01018494 -0.01080230 -0.01141967 -0.01203704 -0.01265440 -0.01327177 -0.01388914 -0.01450650 -0.01512387 -0.01574124 -0.01635860 -0.01697597 -0.01759334 -0.01821070 -0.01882807 -0.01944543 -0.02006280 -0.02068017 -0.02129753 -0.02191490 -0.02253227 -0.02314963 -0.02376700 -0.02438437 -0.02500173 -0.02561910 -0.02623647 -0.02685383 -0.02747120 -0.02819823 -0.02048839 -0.02541387 -0.03154966 -0.03844569 -0.04591428 -0.05386368 -0.06225078 -0.07105285 -0.08015458 -0.08963937 -0.09950513 -0.10974820 -0.12025972 -0.13110065 -0.14230721 -0.15381169 -0.16556793 -0.17768636 -0.19008884 -0.20277116 -0.21582305 -0.22901694 -0.24247183 -0.25618399 -0.27004947 -0.28429974 -0.29871267 -0.31355738 -0.32871505 -0.34418717 ! WE_FOPoles - First order system poles [1/s] !------- YAW CONTROL ------------------------------------------------------ 0.00000 ! Y_uSwitch - Wind speed to switch between Y_ErrThresh. If zero, only the second value of Y_ErrThresh is used [m/s] @@ -149,7 +149,7 @@ !------- MINIMUM PITCH SATURATION ------------------------------------------- 60 ! PS_BldPitchMin_N - Number of values in minimum blade pitch lookup table (should equal number of values in PS_WindSpeeds and PS_BldPitchMin) 3.000 3.182 3.364 3.546 3.727 3.909 4.091 4.273 4.455 4.637 4.818 5.000 5.182 5.364 5.546 5.728 5.910 6.091 6.273 6.455 6.637 6.819 7.001 7.182 7.364 7.546 7.728 7.910 8.092 8.274 8.831 9.389 9.946 10.504 11.061 11.619 12.176 12.734 13.291 13.849 14.407 14.964 15.522 16.079 16.637 17.194 17.752 18.309 18.867 19.425 19.982 20.540 21.097 21.655 22.212 22.770 23.327 23.885 24.442 25.000 ! PS_WindSpeeds - Wind speeds corresponding to minimum blade pitch angles [m/s] --0.015 -0.015 -0.015 -0.015 -0.015 -0.015 -0.015 -0.015 -0.015 -0.015 -0.015 -0.015 -0.015 -0.015 -0.015 -0.015 -0.015 -0.015 -0.015 -0.015 -0.015 -0.015 -0.015 -0.015 -0.012 0.000 0.011 0.020 0.029 0.041 0.056 0.069 0.082 0.095 0.108 0.120 0.132 0.143 0.155 0.166 0.178 0.189 0.200 0.211 0.222 0.232 0.243 0.254 0.264 0.274 0.285 0.295 0.305 0.315 0.325 0.335 0.344 0.354 0.364 0.373 ! PS_BldPitchMin - Minimum blade pitch angles [rad] +-0.016 -0.016 -0.016 -0.016 -0.016 -0.016 -0.016 -0.016 -0.016 -0.016 -0.016 -0.016 -0.016 -0.016 -0.016 -0.016 -0.016 -0.016 -0.016 -0.016 -0.016 -0.016 -0.016 -0.016 -0.016 -0.007 0.004 0.014 0.023 0.031 0.046 0.060 0.074 0.087 0.099 0.111 0.124 0.135 0.147 0.159 0.170 0.181 0.192 0.203 0.214 0.225 0.236 0.246 0.257 0.267 0.277 0.288 0.298 0.308 0.318 0.327 0.337 0.347 0.357 0.366 ! PS_BldPitchMin - Minimum blade pitch angles [rad] !------- SHUTDOWN ----------------------------------------------------------- 0.698100000000 ! SD_MaxPit - Maximum blade pitch angle to initiate shutdown, [rad] @@ -162,8 +162,8 @@ !------- FLAP ACTUATION ----------------------------------------------------- 0.000000000000 ! Flp_Angle - Initial or steady state flap angle [rad] -1.46445122e-08 ! Flp_Kp - Blade root bending moment proportional gain for flap control [s] -1.46445122e-09 ! Flp_Ki - Flap displacement integral gain for flap control [-] +1.46447959e-08 ! Flp_Kp - Blade root bending moment proportional gain for flap control [s] +1.46447959e-09 ! Flp_Ki - Flap displacement integral gain for flap control [-] 0.174500000000 ! Flp_MaxPit - Maximum (and minimum) flap pitch angle [rad] !------- Open Loop Control ----------------------------------------------------- diff --git a/Examples/Test_Cases/IEA-15-240-RWT-UMaineSemi/DISCON-UMaineSemi.IN b/Examples/Test_Cases/IEA-15-240-RWT-UMaineSemi/DISCON-UMaineSemi.IN index ed348ab9..dec6f361 100644 --- a/Examples/Test_Cases/IEA-15-240-RWT-UMaineSemi/DISCON-UMaineSemi.IN +++ b/Examples/Test_Cases/IEA-15-240-RWT-UMaineSemi/DISCON-UMaineSemi.IN @@ -1,5 +1,5 @@ ! Controller parameter input file for the IEA-15-240-RWT-UMaineSemi wind turbine -! - File written using ROSCO version 2.9.4 controller tuning logic on 09/03/24 +! - File written using ROSCO version 2.9.4 controller tuning logic on 10/25/24 !------- SIMULATION CONTROL ------------------------------------------------------------ 2 ! LoggingLevel - {0: write no debug files, 1: write standard output .dbg-file, 2: LoggingLevel 1 + ROSCO LocalVars (.dbg2) 3: LoggingLevel 2 + complete avrSWAP-array (.dbg3)} @@ -8,10 +8,11 @@ 0 ! Echo - (0 - no Echo, 1 - Echo input data to .echo) !------- CONTROLLER FLAGS ------------------------------------------------- -2 ! 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 ! 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- no torque control, 1- k*omega^2 with PI transitions, 2- WSE TSR Tracking, 3- Power-based TSR Tracking)} -0 ! VS_ConstPower - Do constant power torque control, where above rated torque varies, 0 for constant torque} +2 ! 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 ! 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- no torque control, 1- k*omega^2 with PI transitions, 2- WSE TSR Tracking, 3- Power-based TSR Tracking, 4- Torque-based TSR Tracking)} +0 ! VS_ConstPower - Do constant power torque control, where above rated torque varies, 0 for constant torque} +0 ! VS_FBP - Fixed blade pitch configuration mode (0- variable pitch (disabled), 1- constant power overspeed, 2- WSE-lookup reference tracking, 3- torque-lookup reference tracking) 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} @@ -49,6 +50,7 @@ 0.213000 1.000000 ! F_FlCornerFreq - Natural frequency and damping in the second order low pass filter of the tower-top fore-aft motion for floating feedback control [rad/s, -]. 0.01042 ! F_FlHighPassFreq - Natural frequency of first-order high-pass filter for nacelle fore-aft motion [rad/s]. 10.4616 1.0000 ! F_FlpCornerFreq - Corner frequency and damping in the second order low pass filter of the blade root bending moment for flap control +0.05000000000 ! F_VSRefSpdCornerFreq - Corner frequency (-3dB point) in the first order low pass filter of the generator speed reference used for TSR tracking torque control [rad/s]. !------- BLADE PITCH CONTROL ---------------------------------------------- 30 ! PC_GS_n - Amount of gain-scheduling table entries @@ -81,7 +83,7 @@ 21765444.21450 ! VS_MaxTq - Maximum generator torque in Region 3 (HSS side), [Nm]. 0.000000000000 ! VS_MinTq - Minimum generator torque (HSS side), [Nm]. 0.523600000000 ! VS_MinOMSpd - Minimum generator speed [rad/s] -32413847.90763 ! VS_Rgn2K - Generator torque constant in Region 2 (HSS side). Only used in VS_ControlMode = 1,3 +30444157.55210 ! VS_Rgn2K - Generator torque constant in Region 2 (HSS side). Only used in VS_ControlMode = 1,3,4 15000000.00000 ! VS_RtPwr - Wind turbine rated power [W] 19786767.46773 ! VS_RtTq - Rated torque, [Nm]. 0.791680000000 ! VS_RefSpd - Rated generator speed [rad/s] @@ -89,7 +91,12 @@ -35730593.18196 ! VS_KP - Proportional gain for generator PI torque controller [-]. (Only used in the transitional 2.5 region if VS_ControlMode =/ 2) -4499370.31680 ! VS_KI - Integral gain for generator PI torque controller [s]. (Only used in the transitional 2.5 region if VS_ControlMode =/ 2) 9.00 ! VS_TSRopt - Power-maximizing region 2 tip-speed-ratio. Only used in VS_ControlMode = 2. -0.314000000000 ! VS_PwrFiltF - Low pass filter on power used to determine generator speed set point. Only used in VS_ControlMode = 3. + +!------- FIXED PITCH REGION 3 TORQUE CONTROL ------------------------------------------------ +60 ! VS_FBP_n - Number of gain-scheduling table entries +3.000000 3.266897 3.533793 3.800690 4.067586 4.334483 4.601379 4.868276 5.135172 5.402069 5.668966 5.935862 6.202759 6.469655 6.736552 7.003448 7.270345 7.537241 7.804138 8.071034 8.337931 8.604828 8.871724 9.138621 9.405517 9.672414 9.939310 10.206207 10.473103 10.740000 11.215333 11.690667 12.166000 12.641333 13.116667 13.592000 14.067333 14.542667 15.018000 15.493333 15.968667 16.444000 16.919333 17.394667 17.870000 18.345333 18.820667 19.296000 19.771333 20.246667 20.722000 21.197333 21.672667 22.148000 22.623333 23.098667 23.574000 24.049333 24.524667 25.000000 ! VS_FBP_U - Operating schedule table: Wind speeds [m/s]. +0.523599 0.523599 0.523599 0.523599 0.523599 0.523599 0.523599 0.523599 0.523599 0.523599 0.523599 0.523599 0.523599 0.523599 0.523599 0.523599 0.540904 0.560760 0.580617 0.600474 0.620330 0.640187 0.660044 0.679901 0.699757 0.719614 0.739471 0.759328 0.779184 0.791681 0.791681 0.791681 0.791681 0.791681 0.791681 0.791681 0.791681 0.791681 0.791681 0.791681 0.791681 0.791681 0.791681 0.791681 0.791681 0.791681 0.791681 0.791681 0.791681 0.791681 0.791681 0.791681 0.791681 0.791681 0.791681 0.791681 0.791681 0.791681 0.791681 0.791681 ! VS_FBP_Omega - Operating schedule table: Generator speeds [rad/s]. +681375.170448 879890.618036 1113642.754997 1385510.322894 1698372.063292 2055106.717753 2458593.027842 2911709.735122 3417335.581157 3978349.307511 4597629.655747 5278055.367429 6022505.184121 6833857.847387 7714992.098789 8668786.679893 9387854.540424 10089767.991426 10816984.456311 11569503.935078 12347326.427729 13150451.934262 13978880.454677 14832611.988976 15711646.537157 16615984.099220 17545624.675167 18500568.264996 19480814.868708 20697039.768044 20697039.768044 20697039.768044 20697039.768044 20697039.768044 20697039.768044 20697039.768044 20697039.768044 20697039.768044 20697039.768044 20697039.768044 20697039.768044 20697039.768044 20697039.768044 20697039.768044 20697039.768044 20697039.768044 20697039.768044 20697039.768044 20697039.768044 20697039.768044 20697039.768044 20697039.768044 20697039.768044 20697039.768044 20697039.768044 20697039.768044 20697039.768044 20697039.768044 20697039.768044 20697039.768044 ! VS_FBP_Tau - Operating schedule table: Generator torques [N m]. !------- SETPOINT SMOOTHER --------------------------------------------- 1.00000 ! SS_VSGain - Variable speed torque controller setpoint smoother gain, [-]. @@ -102,7 +109,7 @@ 1.00000 ! PRC_R_Pitch - Constant power rating through changing the fine pitch angle, used if PRC_Mode = 2, PRC_Comm = 0, default is 1, effective below rated [-] 20 ! PRC_Table_n - Number of elements in PRC_R to _Pitch table. Used if PRC_Mode = 1. 0.0000 0.0526 0.1053 0.1579 0.2105 0.2632 0.3158 0.3684 0.4211 0.4737 0.5263 0.5789 0.6316 0.6842 0.7368 0.7895 0.8421 0.8947 0.9474 1.0000 ! PRC_R_Table - Table of turbine rating versus fine pitch (PRC_Pitch_Table), length should be PRC_Table_n, default is 1 [-]. Used if PRC_Mode = 1. -0.2296 0.2222 0.2144 0.2066 0.1984 0.1902 0.1814 0.1726 0.1633 0.1538 0.1439 0.1334 0.1226 0.1112 0.0989 0.0858 0.0715 0.0552 0.0351 0.0000 ! PRC_Pitch_Table - Table of fine pitch versus PRC_R_Table, length should be PRC_Table_n [rad]. Used if PRC_Mode = 1. +0.2229 0.2158 0.2086 0.2011 0.1935 0.1857 0.1776 0.1692 0.1606 0.1515 0.1422 0.1323 0.1221 0.1113 0.0997 0.0872 0.0736 0.0581 0.0387 0.0000 ! PRC_Pitch_Table - Table of fine pitch versus PRC_R_Table, length should be PRC_Table_n [rad]. Used if PRC_Mode = 1. 2 ! PRC_n - Number of elements in PRC_WindSpeeds and PRC_GenSpeeds array 0.07854 ! PRC_LPF_Freq - Frequency of the low pass filter on the wind speed estimate used to set PRC_GenSpeeds [rad/s] 3.0000 25.0000 ! PRC_WindSpeeds - Array of wind speeds used in rotor speed vs. wind speed lookup table [m/s] diff --git a/Examples/Test_Cases/MHK_RM1/MHK_RM1_DISCON.IN b/Examples/Test_Cases/MHK_RM1/MHK_RM1_DISCON.IN index 89395380..1acfeb3f 100644 --- a/Examples/Test_Cases/MHK_RM1/MHK_RM1_DISCON.IN +++ b/Examples/Test_Cases/MHK_RM1/MHK_RM1_DISCON.IN @@ -1,5 +1,5 @@ ! Controller parameter input file for the MHK_RM1_Floating wind turbine -! - File written using ROSCO version 2.9.4 controller tuning logic on 09/03/24 +! - File written using ROSCO version 2.9.4 controller tuning logic on 10/25/24 !------- SIMULATION CONTROL ------------------------------------------------------------ 2 ! LoggingLevel - {0: write no debug files, 1: write standard output .dbg-file, 2: LoggingLevel 1 + ROSCO LocalVars (.dbg2) 3: LoggingLevel 2 + complete avrSWAP-array (.dbg3)} @@ -8,10 +8,11 @@ 0 ! Echo - (0 - no Echo, 1 - Echo input data to .echo) !------- 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 ! IPC_ControlMode - Turn Individual Pitch Control (IPC) for fatigue load reductions (pitch contribution) {0: off, 1: 1P reductions, 2: 1P+2P reductions} -3 ! VS_ControlMode - Generator torque control mode in above rated conditions (0- no torque control, 1- k*omega^2 with PI transitions, 2- WSE TSR Tracking, 3- Power-based TSR Tracking)} -1 ! VS_ConstPower - Do constant power torque control, where above rated torque varies, 0 for constant torque} +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 ! IPC_ControlMode - Turn Individual Pitch Control (IPC) for fatigue load reductions (pitch contribution) {0: off, 1: 1P reductions, 2: 1P+2P reductions} +3 ! VS_ControlMode - Generator torque control mode in above rated conditions (0- no torque control, 1- k*omega^2 with PI transitions, 2- WSE TSR Tracking, 3- Power-based TSR Tracking, 4- Torque-based TSR Tracking)} +1 ! VS_ConstPower - Do constant power torque control, where above rated torque varies, 0 for constant torque} +0 ! VS_FBP - Fixed blade pitch configuration mode (0- variable pitch (disabled), 1- constant power overspeed, 2- WSE-lookup reference tracking, 3- torque-lookup reference tracking) 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} @@ -49,20 +50,21 @@ 0.661300 1.000000 ! F_FlCornerFreq - Natural frequency and damping in the second order low pass filter of the tower-top fore-aft motion for floating feedback control [rad/s, -]. 1.50000 ! F_FlHighPassFreq - Natural frequency of first-order high-pass filter for nacelle fore-aft motion [rad/s]. 0.0000 1.0000 ! F_FlpCornerFreq - Corner frequency and damping in the second order low pass filter of the blade root bending moment for flap control +0.05000000000 ! F_VSRefSpdCornerFreq - Corner frequency (-3dB point) in the first order low pass filter of the generator speed reference used for TSR tracking torque control [rad/s]. !------- BLADE PITCH CONTROL ---------------------------------------------- 30 ! PC_GS_n - Amount of gain-scheduling table entries -0.030335 0.049075 0.063610 0.076093 0.087460 0.097196 0.106672 0.115225 0.123634 0.131302 0.139019 0.146056 0.153083 0.159873 0.166338 0.172854 0.178999 0.185046 0.191143 0.196863 0.202559 0.208301 0.213742 0.219137 0.224575 0.229836 0.234972 0.240145 0.245291 0.250200 ! PC_GS_angles - Gain-schedule table: pitch angles [rad]. --0.010207 -0.008807 -0.007650 -0.006678 -0.005849 -0.005135 -0.004512 -0.003965 -0.003481 -0.003048 -0.002661 -0.002310 -0.001993 -0.001703 -0.001438 -0.001195 -0.000971 -0.000764 -0.000572 -0.000393 -0.000226 -0.000071 0.000075 0.000212 0.000341 0.000462 0.000576 0.000685 0.000787 0.000884 ! PC_GS_KP - Gain-schedule table: pitch controller kp gains [s]. --0.005283 -0.004781 -0.004366 -0.004017 -0.003720 -0.003464 -0.003241 -0.003045 -0.002871 -0.002716 -0.002577 -0.002451 -0.002337 -0.002234 -0.002139 -0.002051 -0.001971 -0.001897 -0.001828 -0.001764 -0.001704 -0.001648 -0.001596 -0.001547 -0.001501 -0.001457 -0.001416 -0.001377 -0.001341 -0.001306 ! PC_GS_KI - Gain-schedule table: pitch controller ki gains [-]. +0.032829 0.050927 0.065058 0.077264 0.088435 0.098145 0.107478 0.116009 0.124310 0.131958 0.139653 0.146610 0.153619 0.160343 0.166792 0.173293 0.179385 0.185418 0.191500 0.197178 0.202862 0.208591 0.213998 0.219383 0.224808 0.230043 0.235169 0.240331 0.245456 0.250357 ! PC_GS_angles - Gain-schedule table: pitch angles [rad]. +-0.010024 -0.008667 -0.007542 -0.006593 -0.005783 -0.005082 -0.004470 -0.003932 -0.003454 -0.003027 -0.002643 -0.002297 -0.001982 -0.001695 -0.001432 -0.001190 -0.000967 -0.000761 -0.000570 -0.000392 -0.000226 -0.000070 0.000075 0.000212 0.000340 0.000461 0.000576 0.000684 0.000786 0.000883 ! PC_GS_KP - Gain-schedule table: pitch controller kp gains [s]. +-0.005201 -0.004717 -0.004315 -0.003977 -0.003687 -0.003437 -0.003219 -0.003027 -0.002856 -0.002704 -0.002567 -0.002443 -0.002331 -0.002228 -0.002134 -0.002048 -0.001969 -0.001895 -0.001827 -0.001763 -0.001704 -0.001648 -0.001596 -0.001548 -0.001502 -0.001459 -0.001418 -0.001379 -0.001343 -0.001308 ! PC_GS_KI - Gain-schedule table: pitch controller ki gains [-]. 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 ! PC_GS_KD - Gain-schedule table: pitch controller kd gains 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 ! PC_GS_TF - Gain-schedule table: pitch controller tf gains (derivative filter) 1.570000000000 ! PC_MaxPit - Maximum physical pitch limit, [rad]. -0.000690000000 ! PC_MinPit - Minimum physical pitch limit, [rad]. +0.004840000000 ! PC_MinPit - Minimum physical pitch limit, [rad]. 0.174500000000 ! PC_MaxRat - Maximum pitch rate (in absolute value) in pitch controller, [rad/s]. -0.17450000000 ! PC_MinRat - Minimum pitch rate (in absolute value) in pitch controller, [rad/s]. 63.81200000000 ! PC_RefSpd - Desired (reference) HSS speed for pitch controller, [rad/s]. -0.000690000000 ! PC_FinePit - Record 5: Below-rated pitch angle set-point, [rad] +0.004840000000 ! PC_FinePit - Record 5: Below-rated pitch angle set-point, [rad] 0.017450000000 ! PC_Switch - Angle above lowest minimum pitch angle for switch, [rad] !------- INDIVIDUAL PITCH CONTROL ----------------------------------------- @@ -80,16 +82,21 @@ 7800.000000000 ! VS_MaxRat - Maximum torque rate (in absolute value) in torque controller, [Nm/s]. 12450.50344000 ! VS_MaxTq - Maximum generator torque in Region 3 (HSS side), [Nm]. 0.000000000000 ! VS_MinTq - Minimum generator torque (HSS side), [Nm]. -19.00309000000 ! VS_MinOMSpd - Minimum generator speed [rad/s] -1.142870000000 ! VS_Rgn2K - Generator torque constant in Region 2 (HSS side). Only used in VS_ControlMode = 1,3 +18.44979000000 ! VS_MinOMSpd - Minimum generator speed [rad/s] +1.318270000000 ! VS_Rgn2K - Generator torque constant in Region 2 (HSS side). Only used in VS_ControlMode = 1,3,4 500000.0000000 ! VS_RtPwr - Wind turbine rated power [W] 8300.335630000 ! VS_RtTq - Rated torque, [Nm]. 63.81200000000 ! VS_RefSpd - Rated generator speed [rad/s] 1 ! VS_n - Number of generator PI torque controller gains --63.3401400000 ! VS_KP - Proportional gain for generator PI torque controller [-]. (Only used in the transitional 2.5 region if VS_ControlMode =/ 2) +-75.4693200000 ! VS_KP - Proportional gain for generator PI torque controller [-]. (Only used in the transitional 2.5 region if VS_ControlMode =/ 2) -84.4329000000 ! VS_KI - Integral gain for generator PI torque controller [s]. (Only used in the transitional 2.5 region if VS_ControlMode =/ 2) -7.17 ! VS_TSRopt - Power-maximizing region 2 tip-speed-ratio. Only used in VS_ControlMode = 2. -0.314000000000 ! VS_PwrFiltF - Low pass filter on power used to determine generator speed set point. Only used in VS_ControlMode = 3. +6.96 ! VS_TSRopt - Power-maximizing region 2 tip-speed-ratio. Only used in VS_ControlMode = 2. + +!------- FIXED PITCH REGION 3 TORQUE CONTROL ------------------------------------------------ +60 ! VS_FBP_n - Number of gain-scheduling table entries +0.500000 0.551724 0.603448 0.655172 0.706897 0.758621 0.810345 0.862069 0.913793 0.965517 1.017241 1.068966 1.120690 1.172414 1.224138 1.275862 1.327586 1.379310 1.431034 1.482759 1.534483 1.586207 1.637931 1.689655 1.741379 1.793103 1.844828 1.896552 1.948276 2.000000 2.033333 2.066667 2.100000 2.133333 2.166667 2.200000 2.233333 2.266667 2.300000 2.333333 2.366667 2.400000 2.433333 2.466667 2.500000 2.533333 2.566667 2.600000 2.633333 2.666667 2.700000 2.733333 2.766667 2.800000 2.833333 2.866667 2.900000 2.933333 2.966667 3.000000 ! VS_FBP_U - Operating schedule table: Wind speeds [m/s]. +18.449790 20.358389 22.266988 24.175587 26.084186 27.992785 29.901384 31.809983 33.718582 35.627181 37.535779 39.444378 41.352977 43.261576 45.170175 47.078774 48.987373 50.895972 52.804571 54.713170 56.621769 58.530368 60.438967 62.347566 63.812000 63.812000 63.812000 63.812000 63.812000 63.812000 63.812000 63.812000 63.812000 63.812000 63.812000 63.812000 63.812000 63.812000 63.812000 63.812000 63.812000 63.812000 63.812000 63.812000 63.812000 63.812000 63.812000 63.812000 63.812000 63.812000 63.812000 63.812000 63.812000 63.812000 63.812000 63.812000 63.812000 63.812000 63.812000 63.812000 ! VS_FBP_Omega - Operating schedule table: Generator speeds [rad/s]. +447.695309 545.112956 652.112668 768.694442 894.858281 1030.604183 1175.932149 1330.842179 1495.334272 1669.408429 1853.064650 2046.302934 2249.123282 2461.525694 2683.510169 2915.076708 3156.225311 3406.955978 3667.268708 3937.163502 4216.640359 4505.699280 4804.340265 5112.563314 5465.105009 5947.710098 6449.029144 6968.337475 7504.803737 8057.555717 8057.555717 8057.555717 8057.555717 8057.555717 8057.555717 8057.555717 8057.555717 8057.555717 8057.555717 8057.555717 8057.555717 8057.555717 8057.555717 8057.555717 8057.555717 8057.555717 8057.555717 8057.555717 8057.555717 8057.555717 8057.555717 8057.555717 8057.555717 8057.555717 8057.555717 8057.555717 8057.555717 8057.555717 8057.555717 8057.555717 ! VS_FBP_Tau - Operating schedule table: Generator torques [N m]. !------- SETPOINT SMOOTHER --------------------------------------------- 1.00000 ! SS_VSGain - Variable speed torque controller setpoint smoother gain, [-]. @@ -102,7 +109,7 @@ 1.00000 ! PRC_R_Pitch - Constant power rating through changing the fine pitch angle, used if PRC_Mode = 2, PRC_Comm = 0, default is 1, effective below rated [-] 20 ! PRC_Table_n - Number of elements in PRC_R to _Pitch table. Used if PRC_Mode = 1. 0.0000 0.0526 0.1053 0.1579 0.2105 0.2632 0.3158 0.3684 0.4211 0.4737 0.5263 0.5789 0.6316 0.6842 0.7368 0.7895 0.8421 0.8947 0.9474 1.0000 ! PRC_R_Table - Table of turbine rating versus fine pitch (PRC_Pitch_Table), length should be PRC_Table_n, default is 1 [-]. Used if PRC_Mode = 1. -0.1702 0.1654 0.1607 0.1556 0.1505 0.1453 0.1398 0.1341 0.1284 0.1221 0.1157 0.1089 0.1016 0.0939 0.0853 0.0760 0.0656 0.0528 0.0364 0.0013 ! PRC_Pitch_Table - Table of fine pitch versus PRC_R_Table, length should be PRC_Table_n [rad]. Used if PRC_Mode = 1. +0.1763 0.1713 0.1663 0.1611 0.1556 0.1502 0.1445 0.1385 0.1325 0.1259 0.1192 0.1120 0.1044 0.0963 0.0874 0.0775 0.0666 0.0534 0.0364 0.0048 ! PRC_Pitch_Table - Table of fine pitch versus PRC_R_Table, length should be PRC_Table_n [rad]. Used if PRC_Mode = 1. 2 ! PRC_n - Number of elements in PRC_WindSpeeds and PRC_GenSpeeds array 0.07854 ! PRC_LPF_Freq - Frequency of the low pass filter on the wind speed estimate used to set PRC_GenSpeeds [rad/s] 3.0000 25.0000 ! PRC_WindSpeeds - Array of wind speeds used in rotor speed vs. wind speed lookup table [m/s] @@ -117,10 +124,10 @@ 484024.50000 ! WE_Jtot - Total drivetrain inertia, including blades, hub and casted generator inertia to LSS, [kg m^2] 1025.000 ! WE_RhoAir - Air density, [kg m^-3] "MHK_RM1_Cp_Ct_Cq.txt" ! PerfFileName - File containing rotor performance tables (Cp,Ct,Cq) (absolute path or relative to this file) -36 26 ! PerfTableSize - Size of rotor performance tables, first number refers to number of blade pitch angles, second number referse to number of tip-speed ratios +36 49 ! PerfTableSize - Size of rotor performance tables, first number refers to number of blade pitch angles, second number referse to number of tip-speed ratios 60 ! WE_FOPoles_N - Number of first-order system poles used in EKF 0.5000 0.5517 0.6034 0.6552 0.7069 0.7586 0.8103 0.8621 0.9138 0.9655 1.0172 1.0690 1.1207 1.1724 1.2241 1.2759 1.3276 1.3793 1.4310 1.4828 1.5345 1.5862 1.6379 1.6897 1.7414 1.7931 1.8448 1.8966 1.9483 2.0000 2.0333 2.0667 2.1000 2.1333 2.1667 2.2000 2.2333 2.2667 2.3000 2.3333 2.3667 2.4000 2.4333 2.4667 2.5000 2.5333 2.5667 2.6000 2.6333 2.6667 2.7000 2.7333 2.7667 2.8000 2.8333 2.8667 2.9000 2.9333 2.9667 3.0000 ! WE_FOPoles_v - Wind speeds corresponding to first-order system poles [m/s] --0.14373366 -0.15860266 -0.17347166 -0.18834066 -0.20320966 -0.21807866 -0.23294766 -0.24781666 -0.26268566 -0.27755466 -0.29242365 -0.30729265 -0.32216165 -0.33703065 -0.35189965 -0.36676865 -0.38163765 -0.39650665 -0.41137565 -0.42624465 -0.44111365 -0.45598265 -0.47085165 -0.48688530 -0.50710708 -0.52286299 -0.60338450 -0.60991074 -0.61241025 -0.55721025 0.17998191 0.15135742 0.10945592 0.05908027 0.00104043 -0.05507169 -0.11824557 -0.18009670 -0.24756868 -0.31240541 -0.38377494 -0.45106439 -0.52304487 -0.59605008 -0.66806086 -0.74501532 -0.81929468 -0.89533886 -0.97582430 -1.05220290 -1.13115451 -1.21410608 -1.29344979 -1.37444765 -1.45900848 -1.54200828 -1.62439937 -1.70996742 -1.79715535 -1.88045193 ! WE_FOPoles - First order system poles [1/s] +-0.14258391 -0.15733396 -0.17208402 -0.18683408 -0.20158414 -0.21633420 -0.23108426 -0.24583432 -0.26058438 -0.27533444 -0.29008450 -0.30483456 -0.31958461 -0.33433467 -0.34908473 -0.36383479 -0.37858485 -0.39333491 -0.40808497 -0.42283503 -0.43758509 -0.45233515 -0.46708521 -0.48183527 -0.49680351 -0.51157543 -0.52436337 -0.53464226 -0.54201942 -0.54617203 0.18000980 0.14909102 0.10658999 0.05612239 -0.00176199 -0.05869935 -0.12137090 -0.18374634 -0.25063009 -0.31581380 -0.38745594 -0.45408371 -0.52624103 -0.59858385 -0.67066053 -0.74764214 -0.82122882 -0.89719635 -0.97755563 -1.05322868 -1.13199112 -1.21469627 -1.29331724 -1.37401651 -1.45824393 -1.54056126 -1.62265345 -1.70791238 -1.79452292 -1.87761276 ! WE_FOPoles - First order system poles [1/s] !------- YAW CONTROL ------------------------------------------------------ 0.00000 ! Y_uSwitch - Wind speed to switch between Y_ErrThresh. If zero, only the second value of Y_ErrThresh is used [m/s] @@ -142,7 +149,7 @@ !------- MINIMUM PITCH SATURATION ------------------------------------------- 60 ! PS_BldPitchMin_N - Number of values in minimum blade pitch lookup table (should equal number of values in PS_WindSpeeds and PS_BldPitchMin) 0.500 0.552 0.603 0.655 0.707 0.759 0.810 0.862 0.914 0.966 1.017 1.069 1.121 1.172 1.224 1.276 1.328 1.379 1.431 1.483 1.534 1.586 1.638 1.690 1.741 1.793 1.845 1.897 1.948 2.000 2.033 2.067 2.100 2.133 2.167 2.200 2.233 2.267 2.300 2.333 2.367 2.400 2.433 2.467 2.500 2.533 2.567 2.600 2.633 2.667 2.700 2.733 2.767 2.800 2.833 2.867 2.900 2.933 2.967 3.000 ! PS_WindSpeeds - Wind speeds corresponding to minimum blade pitch angles [m/s] -0.001 0.001 0.001 0.001 0.001 0.001 0.001 0.001 0.001 0.001 0.001 0.001 0.001 0.001 0.001 0.001 0.001 0.001 0.001 0.001 0.001 0.001 0.001 0.001 0.001 0.001 0.001 0.001 0.001 0.001 0.001 0.001 0.001 0.001 0.001 0.001 0.001 0.001 0.001 0.001 0.001 0.001 0.001 0.001 0.001 0.001 0.001 0.001 0.001 0.001 0.001 0.001 0.001 0.001 0.001 0.001 0.001 0.001 0.001 0.001 ! PS_BldPitchMin - Minimum blade pitch angles [rad] +0.005 0.005 0.005 0.005 0.005 0.005 0.005 0.005 0.005 0.005 0.005 0.005 0.005 0.005 0.005 0.005 0.005 0.005 0.005 0.005 0.005 0.005 0.005 0.005 0.005 0.005 0.005 0.005 0.005 0.005 0.005 0.005 0.005 0.005 0.005 0.005 0.005 0.005 0.005 0.005 0.005 0.005 0.005 0.005 0.005 0.005 0.005 0.005 0.005 0.005 0.005 0.005 0.005 0.005 0.005 0.005 0.005 0.005 0.005 0.005 ! PS_BldPitchMin - Minimum blade pitch angles [rad] !------- SHUTDOWN ----------------------------------------------------------- 0.436300000000 ! SD_MaxPit - Maximum blade pitch angle to initiate shutdown, [rad] @@ -150,7 +157,7 @@ !------- Floating ----------------------------------------------------------- 1 ! Fl_n - Number of Fl_Kp gains in gain scheduling, optional with default of 1 --0.4009 ! Fl_Kp - Nacelle velocity proportional feedback gain [s] +-0.3935 ! Fl_Kp - Nacelle velocity proportional feedback gain [s] 2.1000 ! Fl_U - Wind speeds for scheduling Fl_Kp, optional if Fl_Kp is single value [m/s] !------- FLAP ACTUATION ----------------------------------------------------- diff --git a/Examples/Test_Cases/NREL-5MW/DISCON.IN b/Examples/Test_Cases/NREL-5MW/DISCON.IN index 185c4126..882317c1 100644 --- a/Examples/Test_Cases/NREL-5MW/DISCON.IN +++ b/Examples/Test_Cases/NREL-5MW/DISCON.IN @@ -1,5 +1,5 @@ ! Controller parameter input file for the NREL-5MW wind turbine -! - File written using ROSCO version 2.9.4 controller tuning logic on 09/03/24 +! - File written using ROSCO version 2.9.4 controller tuning logic on 10/25/24 !------- SIMULATION CONTROL ------------------------------------------------------------ 1 ! LoggingLevel - {0: write no debug files, 1: write standard output .dbg-file, 2: LoggingLevel 1 + ROSCO LocalVars (.dbg2) 3: LoggingLevel 2 + complete avrSWAP-array (.dbg3)} @@ -8,10 +8,11 @@ 0 ! Echo - (0 - no Echo, 1 - Echo input data to .echo) !------- 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 ! 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- no torque control, 1- k*omega^2 with PI transitions, 2- WSE TSR Tracking, 3- Power-based TSR Tracking)} -1 ! VS_ConstPower - Do constant power torque control, where above rated torque varies, 0 for constant torque} +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 ! 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- no torque control, 1- k*omega^2 with PI transitions, 2- WSE TSR Tracking, 3- Power-based TSR Tracking, 4- Torque-based TSR Tracking)} +1 ! VS_ConstPower - Do constant power torque control, where above rated torque varies, 0 for constant torque} +0 ! VS_FBP - Fixed blade pitch configuration mode (0- variable pitch (disabled), 1- constant power overspeed, 2- WSE-lookup reference tracking, 3- torque-lookup reference tracking) 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} @@ -49,20 +50,21 @@ 0.000000 1.000000 ! F_FlCornerFreq - Natural frequency and damping in the second order low pass filter of the tower-top fore-aft motion for floating feedback control [rad/s, -]. 0.01042 ! F_FlHighPassFreq - Natural frequency of first-order high-pass filter for nacelle fore-aft motion [rad/s]. 0.0000 1.0000 ! F_FlpCornerFreq - Corner frequency and damping in the second order low pass filter of the blade root bending moment for flap control +0.05000000000 ! F_VSRefSpdCornerFreq - Corner frequency (-3dB point) in the first order low pass filter of the generator speed reference used for TSR tracking torque control [rad/s]. !------- BLADE PITCH CONTROL ---------------------------------------------- 30 ! PC_GS_n - Amount of gain-scheduling table entries -0.056789 0.084492 0.106018 0.124332 0.140807 0.155903 0.169931 0.183270 0.196062 0.208354 0.220050 0.231503 0.242646 0.253377 0.263967 0.274233 0.284343 0.294292 0.303997 0.313626 0.322957 0.332260 0.341319 0.350368 0.359221 0.368059 0.376700 0.385301 0.393691 0.402050 ! PC_GS_angles - Gain-schedule table: pitch angles [rad]. --0.020751 -0.018231 -0.016188 -0.014498 -0.013078 -0.011868 -0.010823 -0.009913 -0.009113 -0.008404 -0.007772 -0.007204 -0.006692 -0.006227 -0.005803 -0.005415 -0.005059 -0.004731 -0.004427 -0.004146 -0.003884 -0.003640 -0.003411 -0.003198 -0.002997 -0.002809 -0.002631 -0.002463 -0.002305 -0.002155 ! PC_GS_KP - Gain-schedule table: pitch controller kp gains [s]. --0.008417 -0.007536 -0.006822 -0.006232 -0.005735 -0.005312 -0.004947 -0.004629 -0.004350 -0.004102 -0.003881 -0.003682 -0.003503 -0.003341 -0.003192 -0.003057 -0.002932 -0.002818 -0.002712 -0.002613 -0.002522 -0.002436 -0.002357 -0.002282 -0.002212 -0.002146 -0.002084 -0.002025 -0.001970 -0.001917 ! PC_GS_KI - Gain-schedule table: pitch controller ki gains [-]. +0.058758 0.086057 0.107168 0.125337 0.141701 0.156780 0.170724 0.183994 0.196728 0.209010 0.220659 0.232071 0.243206 0.253902 0.264462 0.274722 0.284807 0.294750 0.304432 0.314055 0.323366 0.332651 0.341705 0.350739 0.359587 0.368410 0.377046 0.385634 0.394020 0.402366 ! PC_GS_angles - Gain-schedule table: pitch angles [rad]. +-0.020547 -0.018073 -0.016064 -0.014399 -0.012998 -0.011801 -0.010768 -0.009867 -0.009074 -0.008371 -0.007743 -0.007179 -0.006670 -0.006208 -0.005786 -0.005401 -0.005046 -0.004719 -0.004417 -0.004136 -0.003875 -0.003632 -0.003405 -0.003192 -0.002992 -0.002803 -0.002626 -0.002459 -0.002301 -0.002151 ! PC_GS_KP - Gain-schedule table: pitch controller kp gains [s]. +-0.008340 -0.007476 -0.006775 -0.006194 -0.005704 -0.005287 -0.004926 -0.004611 -0.004334 -0.004089 -0.003870 -0.003673 -0.003495 -0.003334 -0.003187 -0.003052 -0.002928 -0.002814 -0.002708 -0.002611 -0.002519 -0.002434 -0.002355 -0.002281 -0.002211 -0.002145 -0.002083 -0.002025 -0.001970 -0.001917 ! PC_GS_KI - Gain-schedule table: pitch controller ki gains [-]. 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 ! PC_GS_KD - Gain-schedule table: pitch controller kd gains 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 ! PC_GS_TF - Gain-schedule table: pitch controller tf gains (derivative filter) 1.570000000000 ! PC_MaxPit - Maximum physical pitch limit, [rad]. -0.000880000000 ! PC_MinPit - Minimum physical pitch limit, [rad]. +0.008360000000 ! PC_MinPit - Minimum physical pitch limit, [rad]. 0.174500000000 ! PC_MaxRat - Maximum pitch rate (in absolute value) in pitch controller, [rad/s]. -0.17450000000 ! PC_MinRat - Minimum pitch rate (in absolute value) in pitch controller, [rad/s]. 122.9096700000 ! PC_RefSpd - Desired (reference) HSS speed for pitch controller, [rad/s]. -0.000880000000 ! PC_FinePit - Record 5: Below-rated pitch angle set-point, [rad] +0.008360000000 ! PC_FinePit - Record 5: Below-rated pitch angle set-point, [rad] 0.017450000000 ! PC_Switch - Angle above lowest minimum pitch angle for switch, [rad] !------- INDIVIDUAL PITCH CONTROL ----------------------------------------- @@ -80,16 +82,21 @@ 40000.00000000 ! VS_MaxRat - Maximum torque rate (in absolute value) in torque controller, [Nm/s]. 47402.87063000 ! VS_MaxTq - Maximum generator torque in Region 3 (HSS side), [Nm]. 0.000000000000 ! VS_MinTq - Minimum generator torque (HSS side), [Nm]. -35.29006000000 ! VS_MinOMSpd - Minimum generator speed [rad/s] -2.063350000000 ! VS_Rgn2K - Generator torque constant in Region 2 (HSS side). Only used in VS_ControlMode = 1,3 +35.05042000000 ! VS_MinOMSpd - Minimum generator speed [rad/s] +2.230890000000 ! VS_Rgn2K - Generator torque constant in Region 2 (HSS side). Only used in VS_ControlMode = 1,3,4 5000000.000000 ! VS_RtPwr - Wind turbine rated power [W] 43093.51876000 ! VS_RtTq - Rated torque, [Nm]. 122.9096700000 ! VS_RefSpd - Rated generator speed [rad/s] 1 ! VS_n - Number of generator PI torque controller gains --654.312360000 ! VS_KP - Proportional gain for generator PI torque controller [-]. (Only used in the transitional 2.5 region if VS_ControlMode =/ 2) +-711.870760000 ! VS_KP - Proportional gain for generator PI torque controller [-]. (Only used in the transitional 2.5 region if VS_ControlMode =/ 2) -104.507080000 ! VS_KI - Integral gain for generator PI torque controller [s]. (Only used in the transitional 2.5 region if VS_ControlMode =/ 2) -7.64 ! VS_TSRopt - Power-maximizing region 2 tip-speed-ratio. Only used in VS_ControlMode = 2. -0.314000000000 ! VS_PwrFiltF - Low pass filter on power used to determine generator speed set point. Only used in VS_ControlMode = 3. +7.59 ! VS_TSRopt - Power-maximizing region 2 tip-speed-ratio. Only used in VS_ControlMode = 2. + +!------- FIXED PITCH REGION 3 TORQUE CONTROL ------------------------------------------------ +60 ! VS_FBP_n - Number of gain-scheduling table entries +3.000000 3.289655 3.579310 3.868966 4.158621 4.448276 4.737931 5.027586 5.317241 5.606897 5.896552 6.186207 6.475862 6.765517 7.055172 7.344828 7.634483 7.924138 8.213793 8.503448 8.793103 9.082759 9.372414 9.662069 9.951724 10.241379 10.531034 10.820690 11.110345 11.400000 11.853333 12.306667 12.760000 13.213333 13.666667 14.120000 14.573333 15.026667 15.480000 15.933333 16.386667 16.840000 17.293333 17.746667 18.200000 18.653333 19.106667 19.560000 20.013333 20.466667 20.920000 21.373333 21.826667 22.280000 22.733333 23.186667 23.640000 24.093333 24.546667 25.000000 ! VS_FBP_U - Operating schedule table: Wind speeds [m/s]. +35.050420 38.434599 41.818777 45.202956 48.587134 51.971313 55.355491 58.739670 62.123848 65.508027 68.892205 72.276384 75.660562 79.044741 82.428919 85.813098 89.197276 92.581455 95.965633 99.349812 102.733990 106.118169 109.502347 112.886526 116.270704 119.654883 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 ! VS_FBP_Omega - Operating schedule table: Generator speeds [rad/s]. +2736.402310 3290.320419 3895.257301 4551.212956 5258.187384 6016.180585 6825.192559 7685.223307 8596.272828 9558.341122 10571.428189 11635.534029 12750.658642 13916.802029 15133.964189 16402.145121 17721.344827 19091.563307 20512.800559 21985.056584 23508.331383 25082.624955 26707.937300 28384.268418 30111.618309 31889.986974 33751.976875 36506.912803 39352.387597 42284.519933 42284.519933 42284.519933 42284.519933 42284.519933 42284.519933 42284.519933 42284.519933 42284.519933 42284.519933 42284.519933 42284.519933 42284.519933 42284.519933 42284.519933 42284.519933 42284.519933 42284.519933 42284.519933 42284.519933 42284.519933 42284.519933 42284.519933 42284.519933 42284.519933 42284.519933 42284.519933 42284.519933 42284.519933 42284.519933 42284.519933 ! VS_FBP_Tau - Operating schedule table: Generator torques [N m]. !------- SETPOINT SMOOTHER --------------------------------------------- 1.00000 ! SS_VSGain - Variable speed torque controller setpoint smoother gain, [-]. @@ -102,7 +109,7 @@ 1.00000 ! PRC_R_Pitch - Constant power rating through changing the fine pitch angle, used if PRC_Mode = 2, PRC_Comm = 0, default is 1, effective below rated [-] 20 ! PRC_Table_n - Number of elements in PRC_R to _Pitch table. Used if PRC_Mode = 1. 0.0000 0.0526 0.1053 0.1579 0.2105 0.2632 0.3158 0.3684 0.4211 0.4737 0.5263 0.5789 0.6316 0.6842 0.7368 0.7895 0.8421 0.8947 0.9474 1.0000 ! PRC_R_Table - Table of turbine rating versus fine pitch (PRC_Pitch_Table), length should be PRC_Table_n, default is 1 [-]. Used if PRC_Mode = 1. -0.1933 0.1876 0.1819 0.1761 0.1701 0.1640 0.1577 0.1511 0.1446 0.1375 0.1303 0.1227 0.1147 0.1060 0.0969 0.0865 0.0750 0.0615 0.0436 0.0018 ! PRC_Pitch_Table - Table of fine pitch versus PRC_R_Table, length should be PRC_Table_n [rad]. Used if PRC_Mode = 1. +0.1947 0.1890 0.1832 0.1773 0.1712 0.1651 0.1586 0.1522 0.1453 0.1383 0.1310 0.1232 0.1151 0.1064 0.0970 0.0869 0.0750 0.0611 0.0432 0.0084 ! PRC_Pitch_Table - Table of fine pitch versus PRC_R_Table, length should be PRC_Table_n [rad]. Used if PRC_Mode = 1. 2 ! PRC_n - Number of elements in PRC_WindSpeeds and PRC_GenSpeeds array 0.07854 ! PRC_LPF_Freq - Frequency of the low pass filter on the wind speed estimate used to set PRC_GenSpeeds [rad/s] 3.0000 25.0000 ! PRC_WindSpeeds - Array of wind speeds used in rotor speed vs. wind speed lookup table [m/s] @@ -120,7 +127,7 @@ 36 26 ! PerfTableSize - Size of rotor performance tables, first number refers to number of blade pitch angles, second number referse to number of tip-speed ratios 60 ! WE_FOPoles_N - Number of first-order system poles used in EKF 3.0000 3.2897 3.5793 3.8690 4.1586 4.4483 4.7379 5.0276 5.3172 5.6069 5.8966 6.1862 6.4759 6.7655 7.0552 7.3448 7.6345 7.9241 8.2138 8.5034 8.7931 9.0828 9.3724 9.6621 9.9517 10.2414 10.5310 10.8207 11.1103 11.4000 11.8533 12.3067 12.7600 13.2133 13.6667 14.1200 14.5733 15.0267 15.4800 15.9333 16.3867 16.8400 17.2933 17.7467 18.2000 18.6533 19.1067 19.5600 20.0133 20.4667 20.9200 21.3733 21.8267 22.2800 22.7333 23.1867 23.6400 24.0933 24.5467 25.0000 ! WE_FOPoles_v - Wind speeds corresponding to first-order system poles [m/s] --0.01640352 -0.01798730 -0.01957109 -0.02115488 -0.02273867 -0.02432245 -0.02590624 -0.02749003 -0.02907382 -0.03065761 -0.03224139 -0.03382518 -0.03540897 -0.03699276 -0.03857654 -0.04016033 -0.04174412 -0.04332791 -0.04491170 -0.04649548 -0.04807927 -0.04966306 -0.05124685 -0.05283063 -0.05441442 -0.05599821 -0.05763347 -0.05907205 -0.06912889 -0.05993737 0.02104202 0.01345023 0.00276274 -0.00926304 -0.02225327 -0.03584614 -0.04980912 -0.06421207 -0.07916015 -0.09462203 -0.11009734 -0.12599172 -0.14216388 -0.15844606 -0.17538164 -0.19228714 -0.20938601 -0.22668396 -0.24406726 -0.26206186 -0.28002312 -0.29859942 -0.31701731 -0.33587649 -0.35458243 -0.37383930 -0.39323557 -0.41334882 -0.43349424 -0.45411584 ! WE_FOPoles - First order system poles [1/s] +-0.01594082 -0.01747993 -0.01901905 -0.02055816 -0.02209727 -0.02363639 -0.02517550 -0.02671462 -0.02825373 -0.02979284 -0.03133196 -0.03287107 -0.03441018 -0.03594930 -0.03748841 -0.03902752 -0.04056664 -0.04210575 -0.04364487 -0.04518398 -0.04672309 -0.04826221 -0.04980132 -0.05134043 -0.05287955 -0.05441866 -0.05590711 -0.05631479 -0.05673677 -0.05688823 0.02086267 0.01289718 0.00221038 -0.00987843 -0.02289597 -0.03659553 -0.05054240 -0.06492668 -0.07986142 -0.09537851 -0.11082298 -0.12668949 -0.14289917 -0.15915474 -0.17606654 -0.19299547 -0.21006968 -0.22739194 -0.24475539 -0.26277412 -0.28071671 -0.29927703 -0.31771119 -0.33655222 -0.35527384 -0.37451746 -0.39393441 -0.41403699 -0.43420008 -0.45480703 ! WE_FOPoles - First order system poles [1/s] !------- YAW CONTROL ------------------------------------------------------ 0.00000 ! Y_uSwitch - Wind speed to switch between Y_ErrThresh. If zero, only the second value of Y_ErrThresh is used [m/s] @@ -142,7 +149,7 @@ !------- MINIMUM PITCH SATURATION ------------------------------------------- 60 ! PS_BldPitchMin_N - Number of values in minimum blade pitch lookup table (should equal number of values in PS_WindSpeeds and PS_BldPitchMin) 3.000 3.290 3.579 3.869 4.159 4.448 4.738 5.028 5.317 5.607 5.897 6.186 6.476 6.766 7.055 7.345 7.634 7.924 8.214 8.503 8.793 9.083 9.372 9.662 9.952 10.241 10.531 10.821 11.110 11.400 11.853 12.307 12.760 13.213 13.667 14.120 14.573 15.027 15.480 15.933 16.387 16.840 17.293 17.747 18.200 18.653 19.107 19.560 20.013 20.467 20.920 21.373 21.827 22.280 22.733 23.187 23.640 24.093 24.547 25.000 ! PS_WindSpeeds - Wind speeds corresponding to minimum blade pitch angles [m/s] -0.001 0.001 0.001 0.001 0.001 0.001 0.001 0.001 0.001 0.001 0.001 0.001 0.001 0.001 0.001 0.001 0.001 0.001 0.001 0.001 0.001 0.001 0.001 0.001 0.001 0.011 0.023 0.032 0.040 0.047 0.059 0.070 0.081 0.091 0.102 0.112 0.122 0.131 0.141 0.150 0.160 0.169 0.178 0.187 0.196 0.205 0.214 0.223 0.232 0.240 0.249 0.257 0.266 0.274 0.282 0.290 0.299 0.307 0.315 0.323 ! PS_BldPitchMin - Minimum blade pitch angles [rad] +0.008 0.008 0.008 0.008 0.008 0.008 0.008 0.008 0.008 0.008 0.008 0.008 0.008 0.008 0.008 0.008 0.008 0.008 0.008 0.008 0.008 0.008 0.008 0.008 0.008 0.022 0.034 0.042 0.049 0.057 0.068 0.079 0.090 0.100 0.110 0.120 0.130 0.139 0.149 0.158 0.168 0.177 0.186 0.195 0.204 0.213 0.222 0.230 0.239 0.248 0.256 0.265 0.273 0.281 0.290 0.298 0.306 0.314 0.322 0.330 ! PS_BldPitchMin - Minimum blade pitch angles [rad] !------- SHUTDOWN ----------------------------------------------------------- 0.436300000000 ! SD_MaxPit - Maximum blade pitch angle to initiate shutdown, [rad] diff --git a/Examples/Test_Cases/NREL_2p8_127/NREL-2p8-127_DISCON.IN b/Examples/Test_Cases/NREL_2p8_127/NREL-2p8-127_DISCON.IN index a73c2829..e77d7564 100644 --- a/Examples/Test_Cases/NREL_2p8_127/NREL-2p8-127_DISCON.IN +++ b/Examples/Test_Cases/NREL_2p8_127/NREL-2p8-127_DISCON.IN @@ -1,5 +1,5 @@ ! Controller parameter input file for the NREL-2p8-127 wind turbine -! - File written using ROSCO version 2.9.4 controller tuning logic on 09/03/24 +! - File written using ROSCO version 2.9.4 controller tuning logic on 10/25/24 !------- SIMULATION CONTROL ------------------------------------------------------------ 2 ! LoggingLevel - {0: write no debug files, 1: write standard output .dbg-file, 2: LoggingLevel 1 + ROSCO LocalVars (.dbg2) 3: LoggingLevel 2 + complete avrSWAP-array (.dbg3)} @@ -8,10 +8,11 @@ 0 ! Echo - (0 - no Echo, 1 - Echo input data to .echo) !------- 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 -1 ! IPC_ControlMode - Turn Individual Pitch Control (IPC) for fatigue load reductions (pitch contribution) {0: off, 1: 1P reductions, 2: 1P+2P reductions} -3 ! VS_ControlMode - Generator torque control mode in above rated conditions (0- no torque control, 1- k*omega^2 with PI transitions, 2- WSE TSR Tracking, 3- Power-based TSR Tracking)} -0 ! VS_ConstPower - Do constant power torque control, where above rated torque varies, 0 for constant torque} +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 +1 ! IPC_ControlMode - Turn Individual Pitch Control (IPC) for fatigue load reductions (pitch contribution) {0: off, 1: 1P reductions, 2: 1P+2P reductions} +3 ! VS_ControlMode - Generator torque control mode in above rated conditions (0- no torque control, 1- k*omega^2 with PI transitions, 2- WSE TSR Tracking, 3- Power-based TSR Tracking, 4- Torque-based TSR Tracking)} +0 ! VS_ConstPower - Do constant power torque control, where above rated torque varies, 0 for constant torque} +0 ! VS_FBP - Fixed blade pitch configuration mode (0- variable pitch (disabled), 1- constant power overspeed, 2- WSE-lookup reference tracking, 3- torque-lookup reference tracking) 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} @@ -49,6 +50,7 @@ 0.000000 1.000000 ! F_FlCornerFreq - Natural frequency and damping in the second order low pass filter of the tower-top fore-aft motion for floating feedback control [rad/s, -]. 0.01042 ! F_FlHighPassFreq - Natural frequency of first-order high-pass filter for nacelle fore-aft motion [rad/s]. 0.0000 1.0000 ! F_FlpCornerFreq - Corner frequency and damping in the second order low pass filter of the blade root bending moment for flap control +0.05000000000 ! F_VSRefSpdCornerFreq - Corner frequency (-3dB point) in the first order low pass filter of the generator speed reference used for TSR tracking torque control [rad/s]. !------- BLADE PITCH CONTROL ---------------------------------------------- 30 ! PC_GS_n - Amount of gain-scheduling table entries @@ -80,16 +82,21 @@ 22000.00000000 ! VS_MaxRat - Maximum torque rate (in absolute value) in torque controller, [Nm/s]. 26673.40024000 ! VS_MaxTq - Maximum generator torque in Region 3 (HSS side), [Nm]. 0.000000000000 ! VS_MinTq - Minimum generator torque (HSS side), [Nm]. -37.81562000000 ! VS_MinOMSpd - Minimum generator speed [rad/s] -1.654680000000 ! VS_Rgn2K - Generator torque constant in Region 2 (HSS side). Only used in VS_ControlMode = 1,3 +37.83268000000 ! VS_MinOMSpd - Minimum generator speed [rad/s] +1.758900000000 ! VS_Rgn2K - Generator torque constant in Region 2 (HSS side). Only used in VS_ControlMode = 1,3,4 2800000.000000 ! VS_RtPwr - Wind turbine rated power [W] 24248.54567000 ! VS_RtTq - Rated torque, [Nm]. 122.9096700000 ! VS_RefSpd - Rated generator speed [rad/s] 1 ! VS_n - Number of generator PI torque controller gains --599.338770000 ! VS_KP - Proportional gain for generator PI torque controller [-]. (Only used in the transitional 2.5 region if VS_ControlMode =/ 2) +-599.592440000 ! VS_KP - Proportional gain for generator PI torque controller [-]. (Only used in the transitional 2.5 region if VS_ControlMode =/ 2) -85.3230300000 ! VS_KI - Integral gain for generator PI torque controller [s]. (Only used in the transitional 2.5 region if VS_ControlMode =/ 2) 8.25 ! VS_TSRopt - Power-maximizing region 2 tip-speed-ratio. Only used in VS_ControlMode = 2. -0.314000000000 ! VS_PwrFiltF - Low pass filter on power used to determine generator speed set point. Only used in VS_ControlMode = 3. + +!------- FIXED PITCH REGION 3 TORQUE CONTROL ------------------------------------------------ +60 ! VS_FBP_n - Number of gain-scheduling table entries +3.000000 3.289655 3.579310 3.868966 4.158621 4.448276 4.737931 5.027586 5.317241 5.606897 5.896552 6.186207 6.475862 6.765517 7.055172 7.344828 7.634483 7.924138 8.213793 8.503448 8.793103 9.082759 9.372414 9.662069 9.951724 10.241379 10.531034 10.820690 11.110345 11.400000 11.853333 12.306667 12.760000 13.213333 13.666667 14.120000 14.573333 15.026667 15.480000 15.933333 16.386667 16.840000 17.293333 17.746667 18.200000 18.653333 19.106667 19.560000 20.013333 20.466667 20.920000 21.373333 21.826667 22.280000 22.733333 23.186667 23.640000 24.093333 24.546667 25.000000 ! VS_FBP_U - Operating schedule table: Wind speeds [m/s]. +37.832679 41.485489 45.138300 48.791110 52.443921 56.096731 59.749541 63.402352 67.055162 70.707973 74.360783 78.013593 81.666404 85.319214 88.972025 92.624835 96.277645 99.930456 103.583266 107.236076 110.888887 114.541697 118.194508 121.847318 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 122.909670 ! VS_FBP_Omega - Operating schedule table: Generator speeds [rad/s]. +2478.764863 2980.530535 3528.511466 4122.707657 4763.119107 5449.745816 6182.587784 6961.645012 7786.917499 8658.405245 9576.108251 10540.026516 11550.160040 12606.508823 13709.072866 14857.852167 16052.846729 17294.056549 18581.481629 19915.121968 21294.977566 22721.048424 24193.334540 25711.835916 27993.633141 30567.534246 33088.418092 35562.913070 37977.372199 40280.981058 40280.981058 40280.981058 40280.981058 40280.981058 40280.981058 40280.981058 40280.981058 40280.981058 40280.981058 40280.981058 40280.981058 40280.981058 40280.981058 40280.981058 40280.981058 40280.981058 40280.981058 40280.981058 40280.981058 40280.981058 40280.981058 40280.981058 40280.981058 40280.981058 40280.981058 40280.981058 40280.981058 40280.981058 40280.981058 40280.981058 ! VS_FBP_Tau - Operating schedule table: Generator torques [N m]. !------- SETPOINT SMOOTHER --------------------------------------------- 1.00000 ! SS_VSGain - Variable speed torque controller setpoint smoother gain, [-]. @@ -102,7 +109,7 @@ 1.00000 ! PRC_R_Pitch - Constant power rating through changing the fine pitch angle, used if PRC_Mode = 2, PRC_Comm = 0, default is 1, effective below rated [-] 20 ! PRC_Table_n - Number of elements in PRC_R to _Pitch table. Used if PRC_Mode = 1. 0.0000 0.0526 0.1053 0.1579 0.2105 0.2632 0.3158 0.3684 0.4211 0.4737 0.5263 0.5789 0.6316 0.6842 0.7368 0.7895 0.8421 0.8947 0.9474 1.0000 ! PRC_R_Table - Table of turbine rating versus fine pitch (PRC_Pitch_Table), length should be PRC_Table_n, default is 1 [-]. Used if PRC_Mode = 1. -0.2300 0.2236 0.2170 0.2102 0.2032 0.1960 0.1886 0.1808 0.1729 0.1646 0.1561 0.1471 0.1378 0.1280 0.1174 0.1060 0.0936 0.0791 0.0606 0.0000 ! PRC_Pitch_Table - Table of fine pitch versus PRC_R_Table, length should be PRC_Table_n [rad]. Used if PRC_Mode = 1. +0.2299 0.2236 0.2169 0.2101 0.2032 0.1959 0.1886 0.1808 0.1729 0.1645 0.1560 0.1471 0.1378 0.1280 0.1174 0.1060 0.0936 0.0792 0.0607 0.0000 ! PRC_Pitch_Table - Table of fine pitch versus PRC_R_Table, length should be PRC_Table_n [rad]. Used if PRC_Mode = 1. 2 ! PRC_n - Number of elements in PRC_WindSpeeds and PRC_GenSpeeds array 0.07854 ! PRC_LPF_Freq - Frequency of the low pass filter on the wind speed estimate used to set PRC_GenSpeeds [rad/s] 3.0000 25.0000 ! PRC_WindSpeeds - Array of wind speeds used in rotor speed vs. wind speed lookup table [m/s] @@ -120,7 +127,7 @@ 30 30 ! PerfTableSize - Size of rotor performance tables, first number refers to number of blade pitch angles, second number referse to number of tip-speed ratios 60 ! WE_FOPoles_N - Number of first-order system poles used in EKF 3.0000 3.2897 3.5793 3.8690 4.1586 4.4483 4.7379 5.0276 5.3172 5.6069 5.8966 6.1862 6.4759 6.7655 7.0552 7.3448 7.6345 7.9241 8.2138 8.5034 8.7931 9.0828 9.3724 9.6621 9.9517 10.2414 10.5310 10.8207 11.1103 11.4000 11.8533 12.3067 12.7600 13.2133 13.6667 14.1200 14.5733 15.0267 15.4800 15.9333 16.3867 16.8400 17.2933 17.7467 18.2000 18.6533 19.1067 19.5600 20.0133 20.4667 20.9200 21.3733 21.8267 22.2800 22.7333 23.1867 23.6400 24.0933 24.5467 25.0000 ! WE_FOPoles_v - Wind speeds corresponding to first-order system poles [m/s] --0.01260186 -0.01381859 -0.01503532 -0.01625205 -0.01746878 -0.01868551 -0.01990224 -0.02111897 -0.02233570 -0.02355243 -0.02476916 -0.02598590 -0.02720263 -0.02841936 -0.02963609 -0.03085282 -0.03206955 -0.03328628 -0.03450301 -0.03571974 -0.03693647 -0.03815320 -0.03936993 -0.04058667 -0.03922608 -0.03508867 -0.03003198 -0.02417528 -0.01730537 -0.00898539 -0.02245032 -0.02706065 -0.03108854 -0.03712828 -0.04209566 -0.04857003 -0.05395978 -0.06079111 -0.06630809 -0.07261058 -0.07985034 -0.08612180 -0.09374691 -0.10151803 -0.10895439 -0.11680833 -0.12401154 -0.13232357 -0.14130955 -0.14979812 -0.15867841 -0.16925534 -0.17835395 -0.18685622 -0.19682022 -0.20777561 -0.21797608 -0.22670834 -0.23616033 -0.24519119 ! WE_FOPoles - First order system poles [1/s] +-0.01246257 -0.01366585 -0.01486914 -0.01607242 -0.01727570 -0.01847899 -0.01968227 -0.02088555 -0.02208883 -0.02329212 -0.02449540 -0.02569868 -0.02690197 -0.02810525 -0.02930853 -0.03051181 -0.03171510 -0.03291838 -0.03412166 -0.03532494 -0.03652823 -0.03773151 -0.03893479 -0.04013808 -0.03891269 -0.03498777 -0.02998547 -0.02413124 -0.01726940 -0.00898539 -0.02245032 -0.02706065 -0.03108854 -0.03712828 -0.04209566 -0.04857003 -0.05395978 -0.06079111 -0.06630809 -0.07261058 -0.07985034 -0.08612180 -0.09374691 -0.10151803 -0.10895439 -0.11680833 -0.12401154 -0.13232357 -0.14130955 -0.14979812 -0.15867841 -0.16925534 -0.17835395 -0.18685622 -0.19682022 -0.20777561 -0.21797608 -0.22670834 -0.23616033 -0.24519119 ! WE_FOPoles - First order system poles [1/s] !------- YAW CONTROL ------------------------------------------------------ 0.00000 ! Y_uSwitch - Wind speed to switch between Y_ErrThresh. If zero, only the second value of Y_ErrThresh is used [m/s] From f39b6e41b44ba810c027ad1410eb31b73a9e0610 Mon Sep 17 00:00:00 2001 From: dzalkind Date: Fri, 25 Oct 2024 11:52:55 -0600 Subject: [PATCH 200/224] Regenerate Types/IO --- rosco/controller/src/ROSCO_IO.f90 | 336 ++++++++++++++------------- rosco/controller/src/ROSCO_Types.f90 | 24 +- 2 files changed, 185 insertions(+), 175 deletions(-) diff --git a/rosco/controller/src/ROSCO_IO.f90 b/rosco/controller/src/ROSCO_IO.f90 index 33b2bddc..05f9c809 100644 --- a/rosco/controller/src/ROSCO_IO.f90 +++ b/rosco/controller/src/ROSCO_IO.f90 @@ -44,7 +44,6 @@ SUBROUTINE WriteRestartFile(LocalVar, CntrPar, ErrVar, objInst, RootName, size_a WRITE( Un, IOSTAT=ErrStat) LocalVar%n_DT WRITE( Un, IOSTAT=ErrStat) LocalVar%Time_Last WRITE( Un, IOSTAT=ErrStat) LocalVar%VS_GenPwr - WRITE( Un, IOSTAT=ErrStat) LocalVar%VS_GenPwrF WRITE( Un, IOSTAT=ErrStat) LocalVar%GenSpeed WRITE( Un, IOSTAT=ErrStat) LocalVar%RotSpeed WRITE( Un, IOSTAT=ErrStat) LocalVar%NacHeading @@ -90,6 +89,8 @@ SUBROUTINE WriteRestartFile(LocalVar, CntrPar, ErrVar, objInst, RootName, size_a WRITE( Un, IOSTAT=ErrStat) LocalVar%GenTqMeas WRITE( Un, IOSTAT=ErrStat) LocalVar%GenArTq WRITE( Un, IOSTAT=ErrStat) LocalVar%GenBrTq + WRITE( Un, IOSTAT=ErrStat) LocalVar%VS_KOmega2_GenTq + WRITE( Un, IOSTAT=ErrStat) LocalVar%VS_ConstPwr_GenTq WRITE( Un, IOSTAT=ErrStat) LocalVar%IPC_PitComF(1) WRITE( Un, IOSTAT=ErrStat) LocalVar%IPC_PitComF(2) WRITE( Un, IOSTAT=ErrStat) LocalVar%IPC_PitComF(3) @@ -361,7 +362,6 @@ SUBROUTINE ReadRestartFile(avrSWAP, LocalVar, CntrPar, objInst, PerfData, RootNa READ( Un, IOSTAT=ErrStat) LocalVar%n_DT READ( Un, IOSTAT=ErrStat) LocalVar%Time_Last READ( Un, IOSTAT=ErrStat) LocalVar%VS_GenPwr - READ( Un, IOSTAT=ErrStat) LocalVar%VS_GenPwrF READ( Un, IOSTAT=ErrStat) LocalVar%GenSpeed READ( Un, IOSTAT=ErrStat) LocalVar%RotSpeed READ( Un, IOSTAT=ErrStat) LocalVar%NacHeading @@ -407,6 +407,8 @@ SUBROUTINE ReadRestartFile(avrSWAP, LocalVar, CntrPar, objInst, PerfData, RootNa READ( Un, IOSTAT=ErrStat) LocalVar%GenTqMeas READ( Un, IOSTAT=ErrStat) LocalVar%GenArTq READ( Un, IOSTAT=ErrStat) LocalVar%GenBrTq + READ( Un, IOSTAT=ErrStat) LocalVar%VS_KOmega2_GenTq + READ( Un, IOSTAT=ErrStat) LocalVar%VS_ConstPwr_GenTq READ( Un, IOSTAT=ErrStat) LocalVar%IPC_PitComF(1) READ( Un, IOSTAT=ErrStat) LocalVar%IPC_PitComF(2) READ( Un, IOSTAT=ErrStat) LocalVar%IPC_PitComF(3) @@ -722,7 +724,7 @@ SUBROUTINE Debug(LocalVar, CntrPar, DebugVar, ErrVar, avrSWAP, RootName, size_av '[N/A]', '[N/A]', '[N/A]', '[N/A]', '[rad/s]', & '[deg]', '[deg]', '[deg]', '[N/A]', '[rad/s]', & '[rad/s]'] - nLocalVars = 139 + nLocalVars = 140 Allocate(LocalVarOutData(nLocalVars)) Allocate(LocalVarOutStrings(nLocalVars)) LocalVarOutData(1) = LocalVar%iStatus @@ -732,166 +734,168 @@ SUBROUTINE Debug(LocalVar, CntrPar, DebugVar, ErrVar, avrSWAP, RootName, size_av LocalVarOutData(5) = LocalVar%n_DT LocalVarOutData(6) = LocalVar%Time_Last LocalVarOutData(7) = LocalVar%VS_GenPwr - LocalVarOutData(8) = LocalVar%VS_GenPwrF - LocalVarOutData(9) = LocalVar%GenSpeed - LocalVarOutData(10) = LocalVar%RotSpeed - LocalVarOutData(11) = LocalVar%NacHeading - LocalVarOutData(12) = LocalVar%NacVane - LocalVarOutData(13) = LocalVar%NacVaneF - LocalVarOutData(14) = LocalVar%HorWindV - LocalVarOutData(15) = LocalVar%HorWindV_F - LocalVarOutData(16) = LocalVar%rootMOOP(1) - LocalVarOutData(17) = LocalVar%rootMOOPF(1) - LocalVarOutData(18) = LocalVar%BlPitch(1) - LocalVarOutData(19) = LocalVar%BlPitchCMeas - LocalVarOutData(20) = LocalVar%Azimuth - LocalVarOutData(21) = LocalVar%OL_Azimuth - LocalVarOutData(22) = LocalVar%AzUnwrapped - LocalVarOutData(23) = LocalVar%AzError - LocalVarOutData(24) = LocalVar%GenTqAz - LocalVarOutData(25) = LocalVar%AzBuffer(1) - LocalVarOutData(26) = LocalVar%NumBl - LocalVarOutData(27) = LocalVar%FA_Acc - LocalVarOutData(28) = LocalVar%NacIMU_FA_Acc - LocalVarOutData(29) = LocalVar%FA_AccHPF - LocalVarOutData(30) = LocalVar%FA_AccHPFI - LocalVarOutData(31) = LocalVar%FA_PitCom(1) - LocalVarOutData(32) = LocalVar%VS_RefSpd - LocalVarOutData(33) = LocalVar%VS_RefSpd_TSR - LocalVarOutData(34) = LocalVar%VS_RefSpd_TRA - LocalVarOutData(35) = LocalVar%VS_RefSpd_RL - LocalVarOutData(36) = LocalVar%PC_RefSpd - LocalVarOutData(37) = LocalVar%PC_RefSpd_SS - LocalVarOutData(38) = LocalVar%PC_RefSpd_PRC - LocalVarOutData(39) = LocalVar%RotSpeedF - LocalVarOutData(40) = LocalVar%GenSpeedF - LocalVarOutData(41) = LocalVar%GenTq - LocalVarOutData(42) = LocalVar%GenTqMeas - LocalVarOutData(43) = LocalVar%GenArTq - LocalVarOutData(44) = LocalVar%GenBrTq - LocalVarOutData(45) = LocalVar%IPC_PitComF(1) - LocalVarOutData(46) = LocalVar%PC_KP - LocalVarOutData(47) = LocalVar%PC_KI - LocalVarOutData(48) = LocalVar%PC_KD - LocalVarOutData(49) = LocalVar%PC_TF - LocalVarOutData(50) = LocalVar%PC_MaxPit - LocalVarOutData(51) = LocalVar%PC_MinPit - LocalVarOutData(52) = LocalVar%PC_PitComT - LocalVarOutData(53) = LocalVar%PC_PitComT_Last - LocalVarOutData(54) = LocalVar%PC_PitComTF - LocalVarOutData(55) = LocalVar%PC_PitComT_IPC(1) - LocalVarOutData(56) = LocalVar%PC_PwrErr - LocalVarOutData(57) = LocalVar%PC_SpdErr - LocalVarOutData(58) = LocalVar%IPC_AxisTilt_1P - LocalVarOutData(59) = LocalVar%IPC_AxisYaw_1P - LocalVarOutData(60) = LocalVar%IPC_AxisTilt_2P - LocalVarOutData(61) = LocalVar%IPC_AxisYaw_2P - LocalVarOutData(62) = LocalVar%axisTilt_1P - LocalVarOutData(63) = LocalVar%axisYaw_1P - LocalVarOutData(64) = LocalVar%axisYawF_1P - LocalVarOutData(65) = LocalVar%axisTilt_2P - LocalVarOutData(66) = LocalVar%axisYaw_2P - LocalVarOutData(67) = LocalVar%axisYawF_2P - LocalVarOutData(68) = LocalVar%IPC_KI(1) - LocalVarOutData(69) = LocalVar%IPC_KP(1) - LocalVarOutData(70) = LocalVar%IPC_IntSat - LocalVarOutData(71) = LocalVar%PC_State - LocalVarOutData(72) = LocalVar%PitCom(1) - LocalVarOutData(73) = LocalVar%PitComAct(1) - LocalVarOutData(74) = LocalVar%SS_DelOmegaF - LocalVarOutData(75) = LocalVar%TestType - LocalVarOutData(76) = LocalVar%Kp_Float - LocalVarOutData(77) = LocalVar%VS_MaxTq - LocalVarOutData(78) = LocalVar%VS_LastGenTrq - LocalVarOutData(79) = LocalVar%VS_LastGenPwr - LocalVarOutData(80) = LocalVar%VS_MechGenPwr - LocalVarOutData(81) = LocalVar%VS_SpdErrAr - LocalVarOutData(82) = LocalVar%VS_SpdErrBr - LocalVarOutData(83) = LocalVar%VS_SpdErr - LocalVarOutData(84) = LocalVar%VS_State - LocalVarOutData(85) = LocalVar%VS_Rgn3Pitch - LocalVarOutData(86) = LocalVar%WE_Vw - LocalVarOutData(87) = LocalVar%WE_Vw_F - LocalVarOutData(88) = LocalVar%WE_VwI - LocalVarOutData(89) = LocalVar%WE_VwIdot - LocalVarOutData(90) = LocalVar%WE_Op - LocalVarOutData(91) = LocalVar%WE_Op_Last - LocalVarOutData(92) = LocalVar%VS_LastGenTrqF - LocalVarOutData(93) = LocalVar%PRC_WSE_F - LocalVarOutData(94) = LocalVar%PRC_R_Speed - LocalVarOutData(95) = LocalVar%PRC_R_Torque - LocalVarOutData(96) = LocalVar%PRC_R_Pitch - LocalVarOutData(97) = LocalVar%PRC_R_Total - LocalVarOutData(98) = LocalVar%PRC_Min_Pitch - LocalVarOutData(99) = LocalVar%PS_Min_Pitch - LocalVarOutData(100) = LocalVar%OL_Index - LocalVarOutData(101) = LocalVar%Fl_PitCom - LocalVarOutData(102) = LocalVar%NACIMU_FA_AccF - LocalVarOutData(103) = LocalVar%FA_AccF - LocalVarOutData(104) = LocalVar%FA_Hist - LocalVarOutData(105) = LocalVar%TRA_LastRefSpd - LocalVarOutData(106) = LocalVar%VS_RefSpeed - LocalVarOutData(107) = LocalVar%PtfmTDX - LocalVarOutData(108) = LocalVar%PtfmTDY - LocalVarOutData(109) = LocalVar%PtfmTDZ - LocalVarOutData(110) = LocalVar%PtfmRDX - LocalVarOutData(111) = LocalVar%PtfmRDY - LocalVarOutData(112) = LocalVar%PtfmRDZ - LocalVarOutData(113) = LocalVar%PtfmTVX - LocalVarOutData(114) = LocalVar%PtfmTVY - LocalVarOutData(115) = LocalVar%PtfmTVZ - LocalVarOutData(116) = LocalVar%PtfmRVX - LocalVarOutData(117) = LocalVar%PtfmRVY - LocalVarOutData(118) = LocalVar%PtfmRVZ - LocalVarOutData(119) = LocalVar%PtfmTAX - LocalVarOutData(120) = LocalVar%PtfmTAY - LocalVarOutData(121) = LocalVar%PtfmTAZ - LocalVarOutData(122) = LocalVar%PtfmRAX - LocalVarOutData(123) = LocalVar%PtfmRAY - LocalVarOutData(124) = LocalVar%PtfmRAZ - LocalVarOutData(125) = LocalVar%CC_DesiredL(1) - LocalVarOutData(126) = LocalVar%CC_ActuatedL(1) - LocalVarOutData(127) = LocalVar%CC_ActuatedDL(1) - LocalVarOutData(128) = LocalVar%StC_Input(1) - LocalVarOutData(129) = LocalVar%Flp_Angle(1) - LocalVarOutData(130) = LocalVar%RootMyb_Last(1) - LocalVarOutData(131) = LocalVar%ACC_INFILE_SIZE - LocalVarOutData(132) = LocalVar%AWC_complexangle(1) - LocalVarOutData(133) = LocalVar%ZMQ_ID - LocalVarOutData(134) = LocalVar%ZMQ_YawOffset - LocalVarOutData(135) = LocalVar%ZMQ_TorqueOffset - LocalVarOutData(136) = LocalVar%ZMQ_PitOffset(1) - LocalVarOutData(137) = LocalVar%ZMQ_R_Speed - LocalVarOutData(138) = LocalVar%ZMQ_R_Torque - LocalVarOutData(139) = LocalVar%ZMQ_R_Pitch + LocalVarOutData(8) = LocalVar%GenSpeed + LocalVarOutData(9) = LocalVar%RotSpeed + LocalVarOutData(10) = LocalVar%NacHeading + LocalVarOutData(11) = LocalVar%NacVane + LocalVarOutData(12) = LocalVar%NacVaneF + LocalVarOutData(13) = LocalVar%HorWindV + LocalVarOutData(14) = LocalVar%HorWindV_F + LocalVarOutData(15) = LocalVar%rootMOOP(1) + LocalVarOutData(16) = LocalVar%rootMOOPF(1) + LocalVarOutData(17) = LocalVar%BlPitch(1) + LocalVarOutData(18) = LocalVar%BlPitchCMeas + LocalVarOutData(19) = LocalVar%Azimuth + LocalVarOutData(20) = LocalVar%OL_Azimuth + LocalVarOutData(21) = LocalVar%AzUnwrapped + LocalVarOutData(22) = LocalVar%AzError + LocalVarOutData(23) = LocalVar%GenTqAz + LocalVarOutData(24) = LocalVar%AzBuffer(1) + LocalVarOutData(25) = LocalVar%NumBl + LocalVarOutData(26) = LocalVar%FA_Acc + LocalVarOutData(27) = LocalVar%NacIMU_FA_Acc + LocalVarOutData(28) = LocalVar%FA_AccHPF + LocalVarOutData(29) = LocalVar%FA_AccHPFI + LocalVarOutData(30) = LocalVar%FA_PitCom(1) + LocalVarOutData(31) = LocalVar%VS_RefSpd + LocalVarOutData(32) = LocalVar%VS_RefSpd_TSR + LocalVarOutData(33) = LocalVar%VS_RefSpd_TRA + LocalVarOutData(34) = LocalVar%VS_RefSpd_RL + LocalVarOutData(35) = LocalVar%PC_RefSpd + LocalVarOutData(36) = LocalVar%PC_RefSpd_SS + LocalVarOutData(37) = LocalVar%PC_RefSpd_PRC + LocalVarOutData(38) = LocalVar%RotSpeedF + LocalVarOutData(39) = LocalVar%GenSpeedF + LocalVarOutData(40) = LocalVar%GenTq + LocalVarOutData(41) = LocalVar%GenTqMeas + LocalVarOutData(42) = LocalVar%GenArTq + LocalVarOutData(43) = LocalVar%GenBrTq + LocalVarOutData(44) = LocalVar%VS_KOmega2_GenTq + LocalVarOutData(45) = LocalVar%VS_ConstPwr_GenTq + LocalVarOutData(46) = LocalVar%IPC_PitComF(1) + LocalVarOutData(47) = LocalVar%PC_KP + LocalVarOutData(48) = LocalVar%PC_KI + LocalVarOutData(49) = LocalVar%PC_KD + LocalVarOutData(50) = LocalVar%PC_TF + LocalVarOutData(51) = LocalVar%PC_MaxPit + LocalVarOutData(52) = LocalVar%PC_MinPit + LocalVarOutData(53) = LocalVar%PC_PitComT + LocalVarOutData(54) = LocalVar%PC_PitComT_Last + LocalVarOutData(55) = LocalVar%PC_PitComTF + LocalVarOutData(56) = LocalVar%PC_PitComT_IPC(1) + LocalVarOutData(57) = LocalVar%PC_PwrErr + LocalVarOutData(58) = LocalVar%PC_SpdErr + LocalVarOutData(59) = LocalVar%IPC_AxisTilt_1P + LocalVarOutData(60) = LocalVar%IPC_AxisYaw_1P + LocalVarOutData(61) = LocalVar%IPC_AxisTilt_2P + LocalVarOutData(62) = LocalVar%IPC_AxisYaw_2P + LocalVarOutData(63) = LocalVar%axisTilt_1P + LocalVarOutData(64) = LocalVar%axisYaw_1P + LocalVarOutData(65) = LocalVar%axisYawF_1P + LocalVarOutData(66) = LocalVar%axisTilt_2P + LocalVarOutData(67) = LocalVar%axisYaw_2P + LocalVarOutData(68) = LocalVar%axisYawF_2P + LocalVarOutData(69) = LocalVar%IPC_KI(1) + LocalVarOutData(70) = LocalVar%IPC_KP(1) + LocalVarOutData(71) = LocalVar%IPC_IntSat + LocalVarOutData(72) = LocalVar%PC_State + LocalVarOutData(73) = LocalVar%PitCom(1) + LocalVarOutData(74) = LocalVar%PitComAct(1) + LocalVarOutData(75) = LocalVar%SS_DelOmegaF + LocalVarOutData(76) = LocalVar%TestType + LocalVarOutData(77) = LocalVar%Kp_Float + LocalVarOutData(78) = LocalVar%VS_MaxTq + LocalVarOutData(79) = LocalVar%VS_LastGenTrq + LocalVarOutData(80) = LocalVar%VS_LastGenPwr + LocalVarOutData(81) = LocalVar%VS_MechGenPwr + LocalVarOutData(82) = LocalVar%VS_SpdErrAr + LocalVarOutData(83) = LocalVar%VS_SpdErrBr + LocalVarOutData(84) = LocalVar%VS_SpdErr + LocalVarOutData(85) = LocalVar%VS_State + LocalVarOutData(86) = LocalVar%VS_Rgn3Pitch + LocalVarOutData(87) = LocalVar%WE_Vw + LocalVarOutData(88) = LocalVar%WE_Vw_F + LocalVarOutData(89) = LocalVar%WE_VwI + LocalVarOutData(90) = LocalVar%WE_VwIdot + LocalVarOutData(91) = LocalVar%WE_Op + LocalVarOutData(92) = LocalVar%WE_Op_Last + LocalVarOutData(93) = LocalVar%VS_LastGenTrqF + LocalVarOutData(94) = LocalVar%PRC_WSE_F + LocalVarOutData(95) = LocalVar%PRC_R_Speed + LocalVarOutData(96) = LocalVar%PRC_R_Torque + LocalVarOutData(97) = LocalVar%PRC_R_Pitch + LocalVarOutData(98) = LocalVar%PRC_R_Total + LocalVarOutData(99) = LocalVar%PRC_Min_Pitch + LocalVarOutData(100) = LocalVar%PS_Min_Pitch + LocalVarOutData(101) = LocalVar%OL_Index + LocalVarOutData(102) = LocalVar%Fl_PitCom + LocalVarOutData(103) = LocalVar%NACIMU_FA_AccF + LocalVarOutData(104) = LocalVar%FA_AccF + LocalVarOutData(105) = LocalVar%FA_Hist + LocalVarOutData(106) = LocalVar%TRA_LastRefSpd + LocalVarOutData(107) = LocalVar%VS_RefSpeed + LocalVarOutData(108) = LocalVar%PtfmTDX + LocalVarOutData(109) = LocalVar%PtfmTDY + LocalVarOutData(110) = LocalVar%PtfmTDZ + LocalVarOutData(111) = LocalVar%PtfmRDX + LocalVarOutData(112) = LocalVar%PtfmRDY + LocalVarOutData(113) = LocalVar%PtfmRDZ + LocalVarOutData(114) = LocalVar%PtfmTVX + LocalVarOutData(115) = LocalVar%PtfmTVY + LocalVarOutData(116) = LocalVar%PtfmTVZ + LocalVarOutData(117) = LocalVar%PtfmRVX + LocalVarOutData(118) = LocalVar%PtfmRVY + LocalVarOutData(119) = LocalVar%PtfmRVZ + LocalVarOutData(120) = LocalVar%PtfmTAX + LocalVarOutData(121) = LocalVar%PtfmTAY + LocalVarOutData(122) = LocalVar%PtfmTAZ + LocalVarOutData(123) = LocalVar%PtfmRAX + LocalVarOutData(124) = LocalVar%PtfmRAY + LocalVarOutData(125) = LocalVar%PtfmRAZ + LocalVarOutData(126) = LocalVar%CC_DesiredL(1) + LocalVarOutData(127) = LocalVar%CC_ActuatedL(1) + LocalVarOutData(128) = LocalVar%CC_ActuatedDL(1) + LocalVarOutData(129) = LocalVar%StC_Input(1) + LocalVarOutData(130) = LocalVar%Flp_Angle(1) + LocalVarOutData(131) = LocalVar%RootMyb_Last(1) + LocalVarOutData(132) = LocalVar%ACC_INFILE_SIZE + LocalVarOutData(133) = LocalVar%AWC_complexangle(1) + LocalVarOutData(134) = LocalVar%ZMQ_ID + LocalVarOutData(135) = LocalVar%ZMQ_YawOffset + LocalVarOutData(136) = LocalVar%ZMQ_TorqueOffset + LocalVarOutData(137) = LocalVar%ZMQ_PitOffset(1) + LocalVarOutData(138) = LocalVar%ZMQ_R_Speed + LocalVarOutData(139) = LocalVar%ZMQ_R_Torque + LocalVarOutData(140) = LocalVar%ZMQ_R_Pitch LocalVarOutStrings = [CHARACTER(15) :: 'iStatus', 'RestartWSE', 'Time', 'DT', 'n_DT', & - 'Time_Last', 'VS_GenPwr', 'VS_GenPwrF', 'GenSpeed', 'RotSpeed', & - 'NacHeading', 'NacVane', 'NacVaneF', 'HorWindV', 'HorWindV_F', & - 'rootMOOP', 'rootMOOPF', 'BlPitch', 'BlPitchCMeas', 'Azimuth', & - 'OL_Azimuth', 'AzUnwrapped', 'AzError', 'GenTqAz', 'AzBuffer', & - 'NumBl', 'FA_Acc', 'NacIMU_FA_Acc', 'FA_AccHPF', 'FA_AccHPFI', & - 'FA_PitCom', 'VS_RefSpd', 'VS_RefSpd_TSR', 'VS_RefSpd_TRA', 'VS_RefSpd_RL', & - 'PC_RefSpd', 'PC_RefSpd_SS', 'PC_RefSpd_PRC', 'RotSpeedF', 'GenSpeedF', & - 'GenTq', 'GenTqMeas', 'GenArTq', 'GenBrTq', 'IPC_PitComF', & - 'PC_KP', 'PC_KI', 'PC_KD', 'PC_TF', 'PC_MaxPit', & - 'PC_MinPit', 'PC_PitComT', 'PC_PitComT_Last', 'PC_PitComTF', 'PC_PitComT_IPC', & - 'PC_PwrErr', 'PC_SpdErr', 'IPC_AxisTilt_1P', 'IPC_AxisYaw_1P', 'IPC_AxisTilt_2P', & - 'IPC_AxisYaw_2P', 'axisTilt_1P', 'axisYaw_1P', 'axisYawF_1P', 'axisTilt_2P', & - 'axisYaw_2P', 'axisYawF_2P', 'IPC_KI', 'IPC_KP', 'IPC_IntSat', & - 'PC_State', 'PitCom', 'PitComAct', 'SS_DelOmegaF', 'TestType', & - 'Kp_Float', 'VS_MaxTq', 'VS_LastGenTrq', 'VS_LastGenPwr', 'VS_MechGenPwr', & - 'VS_SpdErrAr', 'VS_SpdErrBr', 'VS_SpdErr', 'VS_State', 'VS_Rgn3Pitch', & - 'WE_Vw', 'WE_Vw_F', 'WE_VwI', 'WE_VwIdot', 'WE_Op', & - 'WE_Op_Last', 'VS_LastGenTrqF', 'PRC_WSE_F', 'PRC_R_Speed', 'PRC_R_Torque', & - 'PRC_R_Pitch', 'PRC_R_Total', 'PRC_Min_Pitch', 'PS_Min_Pitch', 'OL_Index', & - 'Fl_PitCom', 'NACIMU_FA_AccF', 'FA_AccF', 'FA_Hist', 'TRA_LastRefSpd', & - 'VS_RefSpeed', 'PtfmTDX', 'PtfmTDY', 'PtfmTDZ', 'PtfmRDX', & - 'PtfmRDY', 'PtfmRDZ', 'PtfmTVX', 'PtfmTVY', 'PtfmTVZ', & - 'PtfmRVX', 'PtfmRVY', 'PtfmRVZ', 'PtfmTAX', 'PtfmTAY', & - 'PtfmTAZ', 'PtfmRAX', 'PtfmRAY', 'PtfmRAZ', 'CC_DesiredL', & - 'CC_ActuatedL', 'CC_ActuatedDL', 'StC_Input', 'Flp_Angle', 'RootMyb_Last', & - 'ACC_INFILE_SIZE', 'AWC_complexangle', 'ZMQ_ID', 'ZMQ_YawOffset', 'ZMQ_TorqueOffset', & - 'ZMQ_PitOffset', 'ZMQ_R_Speed', 'ZMQ_R_Torque', 'ZMQ_R_Pitch'] + 'Time_Last', 'VS_GenPwr', 'GenSpeed', 'RotSpeed', 'NacHeading', & + 'NacVane', 'NacVaneF', 'HorWindV', 'HorWindV_F', 'rootMOOP', & + 'rootMOOPF', 'BlPitch', 'BlPitchCMeas', 'Azimuth', 'OL_Azimuth', & + 'AzUnwrapped', 'AzError', 'GenTqAz', 'AzBuffer', 'NumBl', & + 'FA_Acc', 'NacIMU_FA_Acc', 'FA_AccHPF', 'FA_AccHPFI', 'FA_PitCom', & + 'VS_RefSpd', 'VS_RefSpd_TSR', 'VS_RefSpd_TRA', 'VS_RefSpd_RL', 'PC_RefSpd', & + 'PC_RefSpd_SS', 'PC_RefSpd_PRC', 'RotSpeedF', 'GenSpeedF', 'GenTq', & + 'GenTqMeas', 'GenArTq', 'GenBrTq', 'VS_KOmega2_GenTq', 'VS_ConstPwr_GenTq', & + 'IPC_PitComF', 'PC_KP', 'PC_KI', 'PC_KD', 'PC_TF', & + 'PC_MaxPit', 'PC_MinPit', 'PC_PitComT', 'PC_PitComT_Last', 'PC_PitComTF', & + 'PC_PitComT_IPC', 'PC_PwrErr', 'PC_SpdErr', 'IPC_AxisTilt_1P', 'IPC_AxisYaw_1P', & + 'IPC_AxisTilt_2P', 'IPC_AxisYaw_2P', 'axisTilt_1P', 'axisYaw_1P', 'axisYawF_1P', & + 'axisTilt_2P', 'axisYaw_2P', 'axisYawF_2P', 'IPC_KI', 'IPC_KP', & + 'IPC_IntSat', 'PC_State', 'PitCom', 'PitComAct', 'SS_DelOmegaF', & + 'TestType', 'Kp_Float', 'VS_MaxTq', 'VS_LastGenTrq', 'VS_LastGenPwr', & + 'VS_MechGenPwr', 'VS_SpdErrAr', 'VS_SpdErrBr', 'VS_SpdErr', 'VS_State', & + 'VS_Rgn3Pitch', 'WE_Vw', 'WE_Vw_F', 'WE_VwI', 'WE_VwIdot', & + 'WE_Op', 'WE_Op_Last', 'VS_LastGenTrqF', 'PRC_WSE_F', 'PRC_R_Speed', & + 'PRC_R_Torque', 'PRC_R_Pitch', 'PRC_R_Total', 'PRC_Min_Pitch', 'PS_Min_Pitch', & + 'OL_Index', 'Fl_PitCom', 'NACIMU_FA_AccF', 'FA_AccF', 'FA_Hist', & + 'TRA_LastRefSpd', 'VS_RefSpeed', 'PtfmTDX', 'PtfmTDY', 'PtfmTDZ', & + 'PtfmRDX', 'PtfmRDY', 'PtfmRDZ', 'PtfmTVX', 'PtfmTVY', & + 'PtfmTVZ', 'PtfmRVX', 'PtfmRVY', 'PtfmRVZ', 'PtfmTAX', & + 'PtfmTAY', 'PtfmTAZ', 'PtfmRAX', 'PtfmRAY', 'PtfmRAZ', & + 'CC_DesiredL', 'CC_ActuatedL', 'CC_ActuatedDL', 'StC_Input', 'Flp_Angle', & + 'RootMyb_Last', 'ACC_INFILE_SIZE', 'AWC_complexangle', 'ZMQ_ID', 'ZMQ_YawOffset', & + 'ZMQ_TorqueOffset', 'ZMQ_PitOffset', 'ZMQ_R_Speed', 'ZMQ_R_Torque', 'ZMQ_R_Pitch' & + ] ! Initialize debug file IF ((LocalVar%iStatus == 0) .OR. (LocalVar%iStatus == -9)) THEN ! .TRUE. if we're on the first call to the DLL IF (CntrPar%LoggingLevel > 0) THEN @@ -906,8 +910,8 @@ SUBROUTINE Debug(LocalVar, CntrPar, DebugVar, ErrVar, avrSWAP, RootName, size_av CALL GetNewUnit(UnDb2, ErrVar) OPEN(unit=UnDb2, FILE=TRIM(RootName)//'.RO.dbg2') WRITE(UnDb2, *) 'Generated on '//CurDate()//' at '//CurTime()//' using ROSCO-'//TRIM(rosco_version) - WRITE(UnDb2, '(140(a20,TR5:))') 'Time', LocalVarOutStrings - WRITE(UnDb2, '(140(a20,TR5:))') + WRITE(UnDb2, '(141(a20,TR5:))') 'Time', LocalVarOutStrings + WRITE(UnDb2, '(141(a20,TR5:))') END IF IF (CntrPar%LoggingLevel > 2) THEN @@ -970,7 +974,7 @@ SUBROUTINE Debug(LocalVar, CntrPar, DebugVar, ErrVar, avrSWAP, RootName, size_av END DO ! Write debug files - FmtDat = "(F20.5,TR5,139(ES20.5E2,TR5:))" ! The format of the debugging data + FmtDat = "(F20.5,TR5,140(ES20.5E2,TR5:))" ! The format of the debugging data IF ( MOD(LocalVar%n_DT, CntrPar%n_DT_Out) == 0) THEN IF(CntrPar%LoggingLevel > 0) THEN WRITE (UnDb, TRIM(FmtDat)) LocalVar%Time, DebugOutData @@ -993,4 +997,4 @@ SUBROUTINE Debug(LocalVar, CntrPar, DebugVar, ErrVar, avrSWAP, RootName, size_av ENDIF END SUBROUTINE Debug -END MODULE ROSCO_IO \ No newline at end of file +END MODULE ROSCO_IO diff --git a/rosco/controller/src/ROSCO_Types.f90 b/rosco/controller/src/ROSCO_Types.f90 index a1c53f6b..dbcb522f 100644 --- a/rosco/controller/src/ROSCO_Types.f90 +++ b/rosco/controller/src/ROSCO_Types.f90 @@ -32,6 +32,7 @@ MODULE ROSCO_Types REAL(DbKi) :: F_FlHighPassFreq ! Natural frequency of first-roder high-pass filter for nacelle fore-aft motion [rad/s]. REAL(DbKi) :: F_YawErr ! Corner low pass filter corner frequency for yaw controller [rad/s]. REAL(DbKi), DIMENSION(:), ALLOCATABLE :: F_FlpCornerFreq ! Corner frequency (-3dB point) in the second order low pass filter of the blade root bending moment for flap control [rad/s]. + REAL(DbKi) :: F_VSRefSpdCornerFreq ! Corner frequency (-3dB point) in the first order low pass filter of the generator speed reference used for TSR tracking torque control [rad/s]. INTEGER(IntKi) :: TRA_Mode ! Tower Fore-Aft control mode {0 - no fore-aft control, 1 - Tower fore-aft damping, 2 -Frequency exclusion zone, 3- Options 1 and 2} REAL(DbKi) :: TRA_ExclSpeed ! Rotor speed for exclusion [LSS] [rad/s] REAL(DbKi) :: TRA_ExclBand ! One-half of the total frequency exclusion band. Torque controller reference will be TRA_ExclFreq +/- TRA_ExlBand [rad/s] @@ -62,13 +63,14 @@ MODULE ROSCO_Types REAL(DbKi) :: PC_RefSpd ! Desired (reference) HSS speed for pitch controller, [rad/s]. REAL(DbKi) :: PC_FinePit ! Record 5 - Below-rated pitch angle set-point (deg) [used only with Bladed Interface] REAL(DbKi) :: PC_Switch ! Angle above lowest minimum pitch angle for switch [rad] - INTEGER(IntKi) :: VS_ControlMode ! Generator torque control mode in above rated conditions {0 - no torque control, 1 - komega^2 with PI trans, 2 - WSE TSR Tracking, 3 - Power TSR Tracking} + INTEGER(IntKi) :: VS_ControlMode ! Generator torque control mode in below rated conditions {0 - no torque control, 1 - komega^2 with PI trans, 2 - WSE TSR Tracking, 3 - Power TSR Tracking, 4 - Torque TSR Tracking} INTEGER(IntKi) :: VS_ConstPower ! Constant power torque control + INTEGER(IntKi) :: VS_FBP ! Fixed blade pitch control mode in above rated conditions {0 - variable pitch (defer to PC_ControlMode and VS_ConstPower), 1 - P/omega overspeed control law, 2 - PI reference tracking based on WSE lookup table, 3 - PI reference tracking based on torque lookup table (must have VS_FBP_Tau be a monotonic function)} REAL(DbKi) :: VS_GenEff ! Generator efficiency mechanical power -> electrical power [-] - REAL(DbKi) :: VS_ArSatTq ! Above rated generator torque PI control saturation, [Nm] -- 212900 + REAL(DbKi) :: VS_ArSatTq ! Above rated generator torque PI control saturation, [Nm] REAL(DbKi) :: VS_MaxRat ! Maximum torque rate (in absolute value) in torque controller, [Nm/s]. - REAL(DbKi) :: VS_MaxTq ! Maximum generator torque in Region 3 (HSS side), [Nm]. -- chosen to be 10% above VS_RtTq - REAL(DbKi) :: VS_MinTq ! Minimum generator (HSS side), [Nm]. + REAL(DbKi) :: VS_MaxTq ! Maximum generator torque in Region 3 (HSS side), [Nm]. + REAL(DbKi) :: VS_MinTq ! Minimum generator torque (HSS side), [Nm]. REAL(DbKi) :: VS_MinOMSpd ! Optimal mode minimum speed, [rad/s] REAL(DbKi) :: VS_Rgn2K ! Generator torque constant in Region 2 (HSS side), N-m/(rad/s)^2 REAL(DbKi) :: VS_RtPwr ! Wind turbine rated power [W] @@ -78,7 +80,10 @@ MODULE ROSCO_Types REAL(DbKi), DIMENSION(:), ALLOCATABLE :: VS_KP ! Proportional gain for generator PI torque controller, used in the transitional 2.5 region REAL(DbKi), DIMENSION(:), ALLOCATABLE :: VS_KI ! Integral gain for generator PI torque controller, used in the transitional 2.5 region REAL(DbKi) :: VS_TSRopt ! Power-maximizing region 2 tip-speed ratio [rad] - REAL(DbKi) :: VS_PwrFiltF ! Cut-off frequency of filter on generator power for power-based tsr tracking control + INTEGER(IntKi) :: VS_FBP_n ! Number of operating schedule entries for fixed blade pitch control + REAL(DbKi), DIMENSION(:), ALLOCATABLE :: VS_FBP_U ! Operating schedule for fixed blade pitch control - Wind speed + REAL(DbKi), DIMENSION(:), ALLOCATABLE :: VS_FBP_Omega ! Operating schedule for fixed blade pitch control - Generator speed + REAL(DbKi), DIMENSION(:), ALLOCATABLE :: VS_FBP_Tau ! Operating schedule for fixed blade pitch control - Generator torque INTEGER(IntKi) :: SS_Mode ! Setpoint Smoother mode {0 - no setpoint smoothing, 1 - introduce setpoint smoothing} REAL(DbKi) :: SS_VSGain ! Variable speed torque controller setpoint smoother gain, [-]. REAL(DbKi) :: SS_PCGain ! Collective pitch controller setpoint smoother gain, [-]. @@ -270,7 +275,6 @@ MODULE ROSCO_Types INTEGER(IntKi) :: n_DT ! number of timesteps since start REAL(DbKi) :: Time_Last ! Last time [s] REAL(DbKi) :: VS_GenPwr ! Generator power [W] - REAL(DbKi) :: VS_GenPwrF ! Generator power [W] REAL(DbKi) :: GenSpeed ! Generator speed (HSS) [rad/s] REAL(DbKi) :: RotSpeed ! Rotor speed (LSS) [rad/s] REAL(DbKi) :: NacHeading ! Nacelle heading of the turbine w.r.t. north [deg] @@ -295,18 +299,20 @@ MODULE ROSCO_Types REAL(DbKi) :: FA_AccHPFI ! Tower velocity, high-pass filtered and integrated fore-aft acceleration [m/s] REAL(DbKi) :: FA_PitCom(3) ! Tower fore-aft vibration damping pitch contribution [rad] REAL(DbKi) :: VS_RefSpd ! Torque control generator speed set point [rad/s] - REAL(DbKi) :: VS_RefSpd_TSR ! Torque control generator speed set point based on optimal TSR [rad/s] + REAL(DbKi) :: VS_RefSpd_TSR ! Torque control generator speed set point based on optimal TSR (unfiltered) [rad/s] REAL(DbKi) :: VS_RefSpd_TRA ! Torque control generator speed set point after freq avoidance [rad/s] REAL(DbKi) :: VS_RefSpd_RL ! Torque control generator speed set point after rate limit [rad/s] REAL(DbKi) :: PC_RefSpd ! Generator speed set point of pitch controller [rad/s] REAL(DbKi) :: PC_RefSpd_SS ! Generator speed set point of pitch controller after setpoint smoothing [rad/s] REAL(DbKi) :: PC_RefSpd_PRC ! Generator speed set point of pitch controller after power ref control [rad/s] - REAL(DbKi) :: RotSpeedF ! Filtered LSS (generator) speed [rad/s]. + REAL(DbKi) :: RotSpeedF ! Filtered LSS (rotor) speed [rad/s]. REAL(DbKi) :: GenSpeedF ! Filtered HSS (generator) speed [rad/s]. REAL(DbKi) :: GenTq ! Electrical generator torque, [Nm]. REAL(DbKi) :: GenTqMeas ! Measured generator torque [Nm] REAL(DbKi) :: GenArTq ! Electrical generator torque, for above-rated PI-control [Nm]. REAL(DbKi) :: GenBrTq ! Electrical generator torque, for below-rated PI-control [Nm]. + REAL(DbKi) :: VS_KOmega2_GenTq ! Calculation of torque signal used by K*Omega^2 controller + REAL(DbKi) :: VS_ConstPwr_GenTq ! Calculation of constant-power torque signal REAL(DbKi) :: IPC_PitComF(3) ! Commanded pitch of each blade as calculated by the individual pitch controller, F stands for low-pass filtered [rad]. REAL(DbKi) :: PC_KP ! Proportional gain for pitch controller at rated pitch (zero) [s]. REAL(DbKi) :: PC_KI ! Integral gain for pitch controller at rated pitch (zero) [-]. @@ -478,4 +484,4 @@ MODULE ROSCO_Types REAL(ReKi), DIMENSION(:), ALLOCATABLE :: avrSWAP ! The swap array- used to pass data to and from the DLL controller [see Bladed DLL documentation] END TYPE ExtControlType -END MODULE ROSCO_Types \ No newline at end of file +END MODULE ROSCO_Types From e51ff1f734469851c865222140cca1ccb82a8411 Mon Sep 17 00:00:00 2001 From: dzalkind Date: Mon, 28 Oct 2024 09:55:23 -0600 Subject: [PATCH 201/224] Fix VS_MaxTq logic --- rosco/controller/src/Controllers.f90 | 11 ++++------- 1 file changed, 4 insertions(+), 7 deletions(-) diff --git a/rosco/controller/src/Controllers.f90 b/rosco/controller/src/Controllers.f90 index 78c24156..05089e37 100644 --- a/rosco/controller/src/Controllers.f90 +++ b/rosco/controller/src/Controllers.f90 @@ -206,14 +206,10 @@ SUBROUTINE VariableSpeedControl(avrSWAP, CntrPar, LocalVar, objInst, ErrVar) ! Allocate Variables ! -------- Variable-Speed Torque Controller -------- - ! Define max torque - IF (LocalVar%VS_State == VS_State_Region_3_ConstTrq) THEN - LocalVar%VS_MaxTq = CntrPar%VS_RtTq * LocalVar%PRC_R_Torque - ELSE - LocalVar%VS_MaxTq = CntrPar%VS_MaxTq * LocalVar%PRC_R_Torque - ENDIF + ! Define initial max torque + LocalVar%VS_MaxTq = CntrPar%VS_MaxTq * LocalVar%PRC_R_Torque - ! Pre-compute generatoer torque values for K*Omega^2 and constant power + ! Pre-compute generator torque values for K*Omega^2 and constant power LocalVar%VS_KOmega2_GenTq = CntrPar%VS_Rgn2K*LocalVar%GenSpeedF*LocalVar%GenSpeedF LocalVar%VS_ConstPwr_GenTq = (CntrPar%VS_RtPwr/(CntrPar%VS_GenEff/100.0))/LocalVar%GenSpeedF * LocalVar%PRC_R_Torque @@ -223,6 +219,7 @@ SUBROUTINE VariableSpeedControl(avrSWAP, CntrPar, LocalVar, objInst, ErrVar) (CntrPar%VS_ControlMode == VS_Mode_Torque_TSR)) THEN ! Constant Power, update VS_MaxTq + LocalVar%VS_MaxTq = CntrPar%VS_RtTq * LocalVar%PRC_R_Torque IF (CntrPar%VS_ConstPower == VS_Mode_ConstPwr) THEN LocalVar%VS_MaxTq = min(LocalVar%VS_ConstPwr_GenTq * LocalVar%PRC_R_Torque, CntrPar%VS_MaxTq) END IF From 91bea8cb397f27ef2cae4372e3ce864261b21285 Mon Sep 17 00:00:00 2001 From: dzalkind Date: Mon, 28 Oct 2024 09:55:34 -0600 Subject: [PATCH 202/224] Tidy PC_State logic --- rosco/controller/src/ControllerBlocks.f90 | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/rosco/controller/src/ControllerBlocks.f90 b/rosco/controller/src/ControllerBlocks.f90 index 7642946d..a173d36d 100644 --- a/rosco/controller/src/ControllerBlocks.f90 +++ b/rosco/controller/src/ControllerBlocks.f90 @@ -210,12 +210,11 @@ SUBROUTINE StateMachine(CntrPar, LocalVar) IF (LocalVar%iStatus == 0) THEN ! .TRUE. if we're on the first call to the DLL IF (LocalVar%PitCom(1) >= LocalVar%VS_Rgn3Pitch) THEN ! We are in region 3 + LocalVar%PC_State = PC_State_Enabled IF (CntrPar%VS_ConstPower == VS_Mode_ConstPwr) THEN ! Constant power tracking LocalVar%VS_State = VS_State_Region_3_ConstPwr - LocalVar%PC_State = PC_State_Enabled ELSE ! Constant torque tracking LocalVar%VS_State = VS_State_Region_3_ConstTrq - LocalVar%PC_State = PC_State_Enabled END IF ELSE ! We are in Region 2 LocalVar%VS_State = VS_State_Region_2 From 80a011754b0b94a6db19d69386f7cf25f1b0a2ab Mon Sep 17 00:00:00 2001 From: dzalkind Date: Mon, 11 Nov 2024 21:11:09 -0700 Subject: [PATCH 203/224] Sync vs ref and wse filters --- Examples/17a_zeromq_simple.py | 55 +++++++++++++++--------- Examples/ROSCO_walkthrough.ipynb | 13 ------ rosco/toolbox/inputs/toolbox_schema.yaml | 2 +- 3 files changed, 36 insertions(+), 34 deletions(-) diff --git a/Examples/17a_zeromq_simple.py b/Examples/17a_zeromq_simple.py index 7fea9c85..b180488d 100644 --- a/Examples/17a_zeromq_simple.py +++ b/Examples/17a_zeromq_simple.py @@ -53,27 +53,42 @@ def run_zmq(logfile=None): # Run the server to receive measurements and send setpoints server.runserver() -def wfc_controller(id,current_time,measurements): +class wfc_controller(): + """ + Users needs to define this class to implement wind farm controller. + This class should contain a method named update_setpoints that + should take as argument the turbine id, the current time and current + measurements and return the setpoints for the particular turbine for + the current time. It should ouput the setpoints as a dictionary whose + keys should be as defined in wfc_zmq_server.wfc_interface. + The wfc_controller subclass of the wfc_zmq_server should be overwriten + with this class, otherwise, an exception is raised and the simulation stops. + """ + + def __init__(self): + return None - if current_time <= 10.0: - yaw_setpoint = 0.0 - else: - yaw_setpoint = DESIRED_YAW_OFFSET - - # Pitch offset - if current_time >= 10.0: - col_pitch_command = np.deg2rad(2) * np.sin(0.1 * current_time) + np.deg2rad(2) # Implement dynamic induction control - else: - col_pitch_command = 0.0 - - # Send new setpoints back to ROSCO - setpoints = {} - setpoints['ZMQ_TorqueOffset'] = 0.0 - setpoints['ZMQ_YawOffset'] = yaw_setpoint - setpoints['ZMQ_PitOffset(1)'] = col_pitch_command - setpoints['ZMQ_PitOffset(2)'] = col_pitch_command - setpoints['ZMQ_PitOffset(3)'] = col_pitch_command - return setpoints + def update_setpoints(self, id,current_time,measurements): + if current_time <= 10.0: + yaw_setpoint = 0.0 + else: + yaw_setpoint = DESIRED_YAW_OFFSET + + # Pitch offset + if current_time >= 10.0: + col_pitch_command = np.deg2rad(2) * np.sin(0.1 * current_time) + np.deg2rad(2) # Implement dynamic induction control + else: + col_pitch_command = 0.0 + + # Send new setpoints back to ROSCO + setpoints = {} + setpoints['ZMQ_TorqueOffset'] = 0.0 + setpoints['ZMQ_YawOffset'] = yaw_setpoint + setpoints['ZMQ_PitOffset(1)'] = col_pitch_command + setpoints['ZMQ_PitOffset(2)'] = col_pitch_command + setpoints['ZMQ_PitOffset(3)'] = col_pitch_command + + return setpoints def sim_rosco(): diff --git a/Examples/ROSCO_walkthrough.ipynb b/Examples/ROSCO_walkthrough.ipynb index aeac3a1d..6988320a 100644 --- a/Examples/ROSCO_walkthrough.ipynb +++ b/Examples/ROSCO_walkthrough.ipynb @@ -1,7 +1,6 @@ { "cells": [ { - "attachments": {}, "cell_type": "markdown", "metadata": { "slideshow": { @@ -62,7 +61,6 @@ ] }, { - "attachments": {}, "cell_type": "markdown", "metadata": { "slideshow": { @@ -135,7 +133,6 @@ ] }, { - "attachments": {}, "cell_type": "markdown", "metadata": { "slideshow": { @@ -156,7 +153,6 @@ ] }, { - "attachments": {}, "cell_type": "markdown", "metadata": { "slideshow": { @@ -201,7 +197,6 @@ ] }, { - "attachments": {}, "cell_type": "markdown", "metadata": { "slideshow": { @@ -255,7 +250,6 @@ ] }, { - "attachments": {}, "cell_type": "markdown", "metadata": { "slideshow": { @@ -293,7 +287,6 @@ ] }, { - "attachments": {}, "cell_type": "markdown", "metadata": { "slideshow": { @@ -369,7 +362,6 @@ ] }, { - "attachments": {}, "cell_type": "markdown", "metadata": { "slideshow": { @@ -431,7 +423,6 @@ ] }, { - "attachments": {}, "cell_type": "markdown", "metadata": { "slideshow": { @@ -602,7 +593,6 @@ ] }, { - "attachments": {}, "cell_type": "markdown", "metadata": { "slideshow": { @@ -614,7 +604,6 @@ ] }, { - "attachments": {}, "cell_type": "markdown", "metadata": { "slideshow": { @@ -697,7 +686,6 @@ ] }, { - "attachments": {}, "cell_type": "markdown", "metadata": { "slideshow": { @@ -736,7 +724,6 @@ ] }, { - "attachments": {}, "cell_type": "markdown", "metadata": { "slideshow": { diff --git a/rosco/toolbox/inputs/toolbox_schema.yaml b/rosco/toolbox/inputs/toolbox_schema.yaml index 86e6a892..d1c04275 100644 --- a/rosco/toolbox/inputs/toolbox_schema.yaml +++ b/rosco/toolbox/inputs/toolbox_schema.yaml @@ -519,7 +519,7 @@ properties: description: Corner frequency (-3dB point) in the first order low pass filter for TSR tracking torque control [rad/s] minimum: 0 unit: rad/s - default: 0.05 + default: 0.209440 open_loop: type: object default: {} From 6f29db0810ec6c83eae27a781f4b9fca828741af Mon Sep 17 00:00:00 2001 From: dzalkind Date: Fri, 15 Nov 2024 10:56:06 -0700 Subject: [PATCH 204/224] Regenerate discons --- Examples/Test_Cases/BAR_10/BAR_10_DISCON.IN | 4 ++-- .../Test_Cases/IEA-15-240-RWT-UMaineSemi/DISCON-UMaineSemi.IN | 4 ++-- Examples/Test_Cases/MHK_RM1/MHK_RM1_DISCON.IN | 4 ++-- Examples/Test_Cases/NREL-5MW/DISCON.IN | 4 ++-- Examples/Test_Cases/NREL_2p8_127/NREL-2p8-127_DISCON.IN | 4 ++-- 5 files changed, 10 insertions(+), 10 deletions(-) diff --git a/Examples/Test_Cases/BAR_10/BAR_10_DISCON.IN b/Examples/Test_Cases/BAR_10/BAR_10_DISCON.IN index c882cb7b..590d36f0 100644 --- a/Examples/Test_Cases/BAR_10/BAR_10_DISCON.IN +++ b/Examples/Test_Cases/BAR_10/BAR_10_DISCON.IN @@ -1,5 +1,5 @@ ! Controller parameter input file for the BAR_10 wind turbine -! - File written using ROSCO version 2.9.4 controller tuning logic on 10/25/24 +! - File written using ROSCO version 2.9.4 controller tuning logic on 11/15/24 !------- SIMULATION CONTROL ------------------------------------------------------------ 1 ! LoggingLevel - {0: write no debug files, 1: write standard output .dbg-file, 2: LoggingLevel 1 + ROSCO LocalVars (.dbg2) 3: LoggingLevel 2 + complete avrSWAP-array (.dbg3)} @@ -50,7 +50,7 @@ 0.000000 1.000000 ! F_FlCornerFreq - Natural frequency and damping in the second order low pass filter of the tower-top fore-aft motion for floating feedback control [rad/s, -]. 0.01042 ! F_FlHighPassFreq - Natural frequency of first-order high-pass filter for nacelle fore-aft motion [rad/s]. 7.8480 1.0000 ! F_FlpCornerFreq - Corner frequency and damping in the second order low pass filter of the blade root bending moment for flap control -0.05000000000 ! F_VSRefSpdCornerFreq - Corner frequency (-3dB point) in the first order low pass filter of the generator speed reference used for TSR tracking torque control [rad/s]. +0.20944000000 ! F_VSRefSpdCornerFreq - Corner frequency (-3dB point) in the first order low pass filter of the generator speed reference used for TSR tracking torque control [rad/s]. !------- BLADE PITCH CONTROL ---------------------------------------------- 30 ! PC_GS_n - Amount of gain-scheduling table entries diff --git a/Examples/Test_Cases/IEA-15-240-RWT-UMaineSemi/DISCON-UMaineSemi.IN b/Examples/Test_Cases/IEA-15-240-RWT-UMaineSemi/DISCON-UMaineSemi.IN index dec6f361..40caa21f 100644 --- a/Examples/Test_Cases/IEA-15-240-RWT-UMaineSemi/DISCON-UMaineSemi.IN +++ b/Examples/Test_Cases/IEA-15-240-RWT-UMaineSemi/DISCON-UMaineSemi.IN @@ -1,5 +1,5 @@ ! Controller parameter input file for the IEA-15-240-RWT-UMaineSemi wind turbine -! - File written using ROSCO version 2.9.4 controller tuning logic on 10/25/24 +! - File written using ROSCO version 2.9.4 controller tuning logic on 11/15/24 !------- SIMULATION CONTROL ------------------------------------------------------------ 2 ! LoggingLevel - {0: write no debug files, 1: write standard output .dbg-file, 2: LoggingLevel 1 + ROSCO LocalVars (.dbg2) 3: LoggingLevel 2 + complete avrSWAP-array (.dbg3)} @@ -50,7 +50,7 @@ 0.213000 1.000000 ! F_FlCornerFreq - Natural frequency and damping in the second order low pass filter of the tower-top fore-aft motion for floating feedback control [rad/s, -]. 0.01042 ! F_FlHighPassFreq - Natural frequency of first-order high-pass filter for nacelle fore-aft motion [rad/s]. 10.4616 1.0000 ! F_FlpCornerFreq - Corner frequency and damping in the second order low pass filter of the blade root bending moment for flap control -0.05000000000 ! F_VSRefSpdCornerFreq - Corner frequency (-3dB point) in the first order low pass filter of the generator speed reference used for TSR tracking torque control [rad/s]. +0.20944000000 ! F_VSRefSpdCornerFreq - Corner frequency (-3dB point) in the first order low pass filter of the generator speed reference used for TSR tracking torque control [rad/s]. !------- BLADE PITCH CONTROL ---------------------------------------------- 30 ! PC_GS_n - Amount of gain-scheduling table entries diff --git a/Examples/Test_Cases/MHK_RM1/MHK_RM1_DISCON.IN b/Examples/Test_Cases/MHK_RM1/MHK_RM1_DISCON.IN index 1acfeb3f..1e8b7de5 100644 --- a/Examples/Test_Cases/MHK_RM1/MHK_RM1_DISCON.IN +++ b/Examples/Test_Cases/MHK_RM1/MHK_RM1_DISCON.IN @@ -1,5 +1,5 @@ ! Controller parameter input file for the MHK_RM1_Floating wind turbine -! - File written using ROSCO version 2.9.4 controller tuning logic on 10/25/24 +! - File written using ROSCO version 2.9.4 controller tuning logic on 11/15/24 !------- SIMULATION CONTROL ------------------------------------------------------------ 2 ! LoggingLevel - {0: write no debug files, 1: write standard output .dbg-file, 2: LoggingLevel 1 + ROSCO LocalVars (.dbg2) 3: LoggingLevel 2 + complete avrSWAP-array (.dbg3)} @@ -50,7 +50,7 @@ 0.661300 1.000000 ! F_FlCornerFreq - Natural frequency and damping in the second order low pass filter of the tower-top fore-aft motion for floating feedback control [rad/s, -]. 1.50000 ! F_FlHighPassFreq - Natural frequency of first-order high-pass filter for nacelle fore-aft motion [rad/s]. 0.0000 1.0000 ! F_FlpCornerFreq - Corner frequency and damping in the second order low pass filter of the blade root bending moment for flap control -0.05000000000 ! F_VSRefSpdCornerFreq - Corner frequency (-3dB point) in the first order low pass filter of the generator speed reference used for TSR tracking torque control [rad/s]. +0.20944000000 ! F_VSRefSpdCornerFreq - Corner frequency (-3dB point) in the first order low pass filter of the generator speed reference used for TSR tracking torque control [rad/s]. !------- BLADE PITCH CONTROL ---------------------------------------------- 30 ! PC_GS_n - Amount of gain-scheduling table entries diff --git a/Examples/Test_Cases/NREL-5MW/DISCON.IN b/Examples/Test_Cases/NREL-5MW/DISCON.IN index 882317c1..7561f2c1 100644 --- a/Examples/Test_Cases/NREL-5MW/DISCON.IN +++ b/Examples/Test_Cases/NREL-5MW/DISCON.IN @@ -1,5 +1,5 @@ ! Controller parameter input file for the NREL-5MW wind turbine -! - File written using ROSCO version 2.9.4 controller tuning logic on 10/25/24 +! - File written using ROSCO version 2.9.4 controller tuning logic on 11/15/24 !------- SIMULATION CONTROL ------------------------------------------------------------ 1 ! LoggingLevel - {0: write no debug files, 1: write standard output .dbg-file, 2: LoggingLevel 1 + ROSCO LocalVars (.dbg2) 3: LoggingLevel 2 + complete avrSWAP-array (.dbg3)} @@ -50,7 +50,7 @@ 0.000000 1.000000 ! F_FlCornerFreq - Natural frequency and damping in the second order low pass filter of the tower-top fore-aft motion for floating feedback control [rad/s, -]. 0.01042 ! F_FlHighPassFreq - Natural frequency of first-order high-pass filter for nacelle fore-aft motion [rad/s]. 0.0000 1.0000 ! F_FlpCornerFreq - Corner frequency and damping in the second order low pass filter of the blade root bending moment for flap control -0.05000000000 ! F_VSRefSpdCornerFreq - Corner frequency (-3dB point) in the first order low pass filter of the generator speed reference used for TSR tracking torque control [rad/s]. +0.20944000000 ! F_VSRefSpdCornerFreq - Corner frequency (-3dB point) in the first order low pass filter of the generator speed reference used for TSR tracking torque control [rad/s]. !------- BLADE PITCH CONTROL ---------------------------------------------- 30 ! PC_GS_n - Amount of gain-scheduling table entries diff --git a/Examples/Test_Cases/NREL_2p8_127/NREL-2p8-127_DISCON.IN b/Examples/Test_Cases/NREL_2p8_127/NREL-2p8-127_DISCON.IN index e77d7564..43450ca6 100644 --- a/Examples/Test_Cases/NREL_2p8_127/NREL-2p8-127_DISCON.IN +++ b/Examples/Test_Cases/NREL_2p8_127/NREL-2p8-127_DISCON.IN @@ -1,5 +1,5 @@ ! Controller parameter input file for the NREL-2p8-127 wind turbine -! - File written using ROSCO version 2.9.4 controller tuning logic on 10/25/24 +! - File written using ROSCO version 2.9.4 controller tuning logic on 11/15/24 !------- SIMULATION CONTROL ------------------------------------------------------------ 2 ! LoggingLevel - {0: write no debug files, 1: write standard output .dbg-file, 2: LoggingLevel 1 + ROSCO LocalVars (.dbg2) 3: LoggingLevel 2 + complete avrSWAP-array (.dbg3)} @@ -50,7 +50,7 @@ 0.000000 1.000000 ! F_FlCornerFreq - Natural frequency and damping in the second order low pass filter of the tower-top fore-aft motion for floating feedback control [rad/s, -]. 0.01042 ! F_FlHighPassFreq - Natural frequency of first-order high-pass filter for nacelle fore-aft motion [rad/s]. 0.0000 1.0000 ! F_FlpCornerFreq - Corner frequency and damping in the second order low pass filter of the blade root bending moment for flap control -0.05000000000 ! F_VSRefSpdCornerFreq - Corner frequency (-3dB point) in the first order low pass filter of the generator speed reference used for TSR tracking torque control [rad/s]. +0.20944000000 ! F_VSRefSpdCornerFreq - Corner frequency (-3dB point) in the first order low pass filter of the generator speed reference used for TSR tracking torque control [rad/s]. !------- BLADE PITCH CONTROL ---------------------------------------------- 30 ! PC_GS_n - Amount of gain-scheduling table entries From b60e925ce6e285b8b95ba1bd946283834d1740d7 Mon Sep 17 00:00:00 2001 From: dzalkind Date: Fri, 15 Nov 2024 10:59:10 -0700 Subject: [PATCH 205/224] Tidy up DISCON formatting --- Examples/Test_Cases/BAR_10/BAR_10_DISCON.IN | 2 +- .../Test_Cases/IEA-15-240-RWT-UMaineSemi/DISCON-UMaineSemi.IN | 2 +- Examples/Test_Cases/MHK_RM1/MHK_RM1_DISCON.IN | 2 +- Examples/Test_Cases/NREL-5MW/DISCON.IN | 2 +- Examples/Test_Cases/NREL_2p8_127/NREL-2p8-127_DISCON.IN | 2 +- rosco/toolbox/utilities.py | 2 +- 6 files changed, 6 insertions(+), 6 deletions(-) diff --git a/Examples/Test_Cases/BAR_10/BAR_10_DISCON.IN b/Examples/Test_Cases/BAR_10/BAR_10_DISCON.IN index 590d36f0..db0d124d 100644 --- a/Examples/Test_Cases/BAR_10/BAR_10_DISCON.IN +++ b/Examples/Test_Cases/BAR_10/BAR_10_DISCON.IN @@ -50,7 +50,7 @@ 0.000000 1.000000 ! F_FlCornerFreq - Natural frequency and damping in the second order low pass filter of the tower-top fore-aft motion for floating feedback control [rad/s, -]. 0.01042 ! F_FlHighPassFreq - Natural frequency of first-order high-pass filter for nacelle fore-aft motion [rad/s]. 7.8480 1.0000 ! F_FlpCornerFreq - Corner frequency and damping in the second order low pass filter of the blade root bending moment for flap control -0.20944000000 ! F_VSRefSpdCornerFreq - Corner frequency (-3dB point) in the first order low pass filter of the generator speed reference used for TSR tracking torque control [rad/s]. +0.20944 ! F_VSRefSpdCornerFreq - Corner frequency (-3dB point) in the first order low pass filter of the generator speed reference used for TSR tracking torque control [rad/s]. !------- BLADE PITCH CONTROL ---------------------------------------------- 30 ! PC_GS_n - Amount of gain-scheduling table entries diff --git a/Examples/Test_Cases/IEA-15-240-RWT-UMaineSemi/DISCON-UMaineSemi.IN b/Examples/Test_Cases/IEA-15-240-RWT-UMaineSemi/DISCON-UMaineSemi.IN index 40caa21f..221fa4fa 100644 --- a/Examples/Test_Cases/IEA-15-240-RWT-UMaineSemi/DISCON-UMaineSemi.IN +++ b/Examples/Test_Cases/IEA-15-240-RWT-UMaineSemi/DISCON-UMaineSemi.IN @@ -50,7 +50,7 @@ 0.213000 1.000000 ! F_FlCornerFreq - Natural frequency and damping in the second order low pass filter of the tower-top fore-aft motion for floating feedback control [rad/s, -]. 0.01042 ! F_FlHighPassFreq - Natural frequency of first-order high-pass filter for nacelle fore-aft motion [rad/s]. 10.4616 1.0000 ! F_FlpCornerFreq - Corner frequency and damping in the second order low pass filter of the blade root bending moment for flap control -0.20944000000 ! F_VSRefSpdCornerFreq - Corner frequency (-3dB point) in the first order low pass filter of the generator speed reference used for TSR tracking torque control [rad/s]. +0.20944 ! F_VSRefSpdCornerFreq - Corner frequency (-3dB point) in the first order low pass filter of the generator speed reference used for TSR tracking torque control [rad/s]. !------- BLADE PITCH CONTROL ---------------------------------------------- 30 ! PC_GS_n - Amount of gain-scheduling table entries diff --git a/Examples/Test_Cases/MHK_RM1/MHK_RM1_DISCON.IN b/Examples/Test_Cases/MHK_RM1/MHK_RM1_DISCON.IN index 1e8b7de5..8cb4267a 100644 --- a/Examples/Test_Cases/MHK_RM1/MHK_RM1_DISCON.IN +++ b/Examples/Test_Cases/MHK_RM1/MHK_RM1_DISCON.IN @@ -50,7 +50,7 @@ 0.661300 1.000000 ! F_FlCornerFreq - Natural frequency and damping in the second order low pass filter of the tower-top fore-aft motion for floating feedback control [rad/s, -]. 1.50000 ! F_FlHighPassFreq - Natural frequency of first-order high-pass filter for nacelle fore-aft motion [rad/s]. 0.0000 1.0000 ! F_FlpCornerFreq - Corner frequency and damping in the second order low pass filter of the blade root bending moment for flap control -0.20944000000 ! F_VSRefSpdCornerFreq - Corner frequency (-3dB point) in the first order low pass filter of the generator speed reference used for TSR tracking torque control [rad/s]. +0.20944 ! F_VSRefSpdCornerFreq - Corner frequency (-3dB point) in the first order low pass filter of the generator speed reference used for TSR tracking torque control [rad/s]. !------- BLADE PITCH CONTROL ---------------------------------------------- 30 ! PC_GS_n - Amount of gain-scheduling table entries diff --git a/Examples/Test_Cases/NREL-5MW/DISCON.IN b/Examples/Test_Cases/NREL-5MW/DISCON.IN index 7561f2c1..e9a2472b 100644 --- a/Examples/Test_Cases/NREL-5MW/DISCON.IN +++ b/Examples/Test_Cases/NREL-5MW/DISCON.IN @@ -50,7 +50,7 @@ 0.000000 1.000000 ! F_FlCornerFreq - Natural frequency and damping in the second order low pass filter of the tower-top fore-aft motion for floating feedback control [rad/s, -]. 0.01042 ! F_FlHighPassFreq - Natural frequency of first-order high-pass filter for nacelle fore-aft motion [rad/s]. 0.0000 1.0000 ! F_FlpCornerFreq - Corner frequency and damping in the second order low pass filter of the blade root bending moment for flap control -0.20944000000 ! F_VSRefSpdCornerFreq - Corner frequency (-3dB point) in the first order low pass filter of the generator speed reference used for TSR tracking torque control [rad/s]. +0.20944 ! F_VSRefSpdCornerFreq - Corner frequency (-3dB point) in the first order low pass filter of the generator speed reference used for TSR tracking torque control [rad/s]. !------- BLADE PITCH CONTROL ---------------------------------------------- 30 ! PC_GS_n - Amount of gain-scheduling table entries diff --git a/Examples/Test_Cases/NREL_2p8_127/NREL-2p8-127_DISCON.IN b/Examples/Test_Cases/NREL_2p8_127/NREL-2p8-127_DISCON.IN index 43450ca6..d7090639 100644 --- a/Examples/Test_Cases/NREL_2p8_127/NREL-2p8-127_DISCON.IN +++ b/Examples/Test_Cases/NREL_2p8_127/NREL-2p8-127_DISCON.IN @@ -50,7 +50,7 @@ 0.000000 1.000000 ! F_FlCornerFreq - Natural frequency and damping in the second order low pass filter of the tower-top fore-aft motion for floating feedback control [rad/s, -]. 0.01042 ! F_FlHighPassFreq - Natural frequency of first-order high-pass filter for nacelle fore-aft motion [rad/s]. 0.0000 1.0000 ! F_FlpCornerFreq - Corner frequency and damping in the second order low pass filter of the blade root bending moment for flap control -0.20944000000 ! F_VSRefSpdCornerFreq - Corner frequency (-3dB point) in the first order low pass filter of the generator speed reference used for TSR tracking torque control [rad/s]. +0.20944 ! F_VSRefSpdCornerFreq - Corner frequency (-3dB point) in the first order low pass filter of the generator speed reference used for TSR tracking torque control [rad/s]. !------- BLADE PITCH CONTROL ---------------------------------------------- 30 ! PC_GS_n - Amount of gain-scheduling table entries diff --git a/rosco/toolbox/utilities.py b/rosco/toolbox/utilities.py index 5042cbe3..713ab471 100644 --- a/rosco/toolbox/utilities.py +++ b/rosco/toolbox/utilities.py @@ -140,7 +140,7 @@ def write_DISCON(turbine, controller, param_file='DISCON.IN', txt_filename='Cp_C file.write('{}! F_FlCornerFreq - Natural frequency and damping in the second order low pass filter of the tower-top fore-aft motion for floating feedback control [rad/s, -].\n'.format(''.join('{:<4.6f} '.format(rosco_vt['F_FlCornerFreq'][i]) for i in range(len(rosco_vt['F_FlCornerFreq']))))) file.write('{:<13.5f} ! F_FlHighPassFreq - Natural frequency of first-order high-pass filter for nacelle fore-aft motion [rad/s].\n'.format(rosco_vt['F_FlHighPassFreq'])) file.write('{} ! F_FlpCornerFreq - {}\n'.format(write_array(rosco_vt["F_FlpCornerFreq"]), input_descriptions["F_FlpCornerFreq"])) - file.write('{:<013.5f} ! F_VSRefSpdCornerFreq - {}\n'.format(float(rosco_vt['F_VSRefSpdCornerFreq']),input_descriptions['F_VSRefSpdCornerFreq'])) + file.write('{:<13.5f} ! F_VSRefSpdCornerFreq - {}\n'.format(float(rosco_vt['F_VSRefSpdCornerFreq']),input_descriptions['F_VSRefSpdCornerFreq'])) file.write('\n') file.write('!------- BLADE PITCH CONTROL ----------------------------------------------\n') From 33a3a36293e6a2f6f5596492bef99cb912844d71 Mon Sep 17 00:00:00 2001 From: dzalkind Date: Fri, 15 Nov 2024 11:08:52 -0700 Subject: [PATCH 206/224] Tidy up some code comments --- Examples/29_marine_hydro_fbp.py | 2 -- rosco/toolbox/utilities.py | 3 --- 2 files changed, 5 deletions(-) diff --git a/Examples/29_marine_hydro_fbp.py b/Examples/29_marine_hydro_fbp.py index 67a8475e..62323a6e 100644 --- a/Examples/29_marine_hydro_fbp.py +++ b/Examples/29_marine_hydro_fbp.py @@ -149,14 +149,12 @@ def main(): # TODO: simulate multiple controller configurations in parallel r = run_FAST_ROSCO() r.tuning_yaml = parameter_filename - # r.wind_case_fcn = cl.simp_step # single step wind input r.wind_case_fcn = cl.power_curve r.wind_case_opts = { 'U': [3.0], 'TMax': 60.0, } r.case_inputs = {} - # r.fst_vt = reader.fst_vt r.controller_params = controller_params_1 r.save_dir = run_dir r.rosco_dir = rosco_dir diff --git a/rosco/toolbox/utilities.py b/rosco/toolbox/utilities.py index 713ab471..f5ddd1e9 100644 --- a/rosco/toolbox/utilities.py +++ b/rosco/toolbox/utilities.py @@ -80,9 +80,6 @@ def write_DISCON(turbine, controller, param_file='DISCON.IN', txt_filename='Cp_C rosco_vt['CC_GroupIndex'] = [rosco_vt['CC_GroupIndex']] # make an array if not hasattr(rosco_vt['StC_GroupIndex'],'__len__'): rosco_vt['StC_GroupIndex'] = [rosco_vt['StC_GroupIndex']] - # Get input descriptions - #input_schema = load_yaml(os.path.join(os.path.dirname(__file__),'inputs/toolbox_schema.yaml')) - #discon_props = input_schema['properties']['controller_params']['properties']['DISCON']['properties'] print('Writing new controller parameter file parameter file: %s.' % param_file) # Should be obvious what's going on here... From 8be8713f9c3065c6aa044fc3bb2aa181a7f6a00a Mon Sep 17 00:00:00 2001 From: dzalkind Date: Fri, 15 Nov 2024 11:09:31 -0700 Subject: [PATCH 207/224] Rename example --- Examples/{29_marine_hydro_fbp.py => 30_fixed_pitch_mhk.py} | 0 1 file changed, 0 insertions(+), 0 deletions(-) rename Examples/{29_marine_hydro_fbp.py => 30_fixed_pitch_mhk.py} (100%) diff --git a/Examples/29_marine_hydro_fbp.py b/Examples/30_fixed_pitch_mhk.py similarity index 100% rename from Examples/29_marine_hydro_fbp.py rename to Examples/30_fixed_pitch_mhk.py From ed159ed65e92d80a344e4fed89d25d243bf9324b Mon Sep 17 00:00:00 2001 From: dzalkind Date: Fri, 15 Nov 2024 11:35:53 -0700 Subject: [PATCH 208/224] Add F_VSRefSpdCornerFreq to minimal DISCON inputs, it's required --- Examples/example_inputs/minimal_DISCON.IN | 2 ++ 1 file changed, 2 insertions(+) diff --git a/Examples/example_inputs/minimal_DISCON.IN b/Examples/example_inputs/minimal_DISCON.IN index 305379fd..dcfd09e3 100644 --- a/Examples/example_inputs/minimal_DISCON.IN +++ b/Examples/example_inputs/minimal_DISCON.IN @@ -25,6 +25,8 @@ Extra lines that ROSCO doesn't care about anymore 0.000000 1.000000 ! F_FlCornerFreq - Natural frequency and damping in the second order low pass filter of the tower-top fore-aft motion for floating feedback control [rad/s, -]. 0.01042 ! F_FlHighPassFreq - Natural frequency of first-order high-pass filter for nacelle fore-aft motion [rad/s]. 0.000000 1.000000 ! F_FlpCornerFreq - Corner frequency and damping in the second order low pass filter of the blade root bending moment for flap control [rad/s, -]. +0.05000 ! F_VSRefSpdCornerFreq - Corner frequency (-3dB point) in the first order low pass filter of the generator speed reference used for TSR tracking torque control [rad/s]. + !------- BLADE PITCH CONTROL ---------------------------------------------- 30 ! PC_GS_n - Amount of gain-scheduling table entries From aa3444598e4b3e253c62d53d14934133f14e8f5b Mon Sep 17 00:00:00 2001 From: dzalkind Date: Fri, 15 Nov 2024 11:48:07 -0700 Subject: [PATCH 209/224] Start documentation of fixed pitch example --- Examples/30_fixed_pitch_mhk.py | 35 ++++++++++++++++++++++++++-------- 1 file changed, 27 insertions(+), 8 deletions(-) diff --git a/Examples/30_fixed_pitch_mhk.py b/Examples/30_fixed_pitch_mhk.py index 62323a6e..feeed5ed 100644 --- a/Examples/30_fixed_pitch_mhk.py +++ b/Examples/30_fixed_pitch_mhk.py @@ -1,11 +1,35 @@ ''' ------------ 29_marine_hydro_fbp --------------- -Run openfast with ROSCO and a MHK turbine with fixed blade pitch control ------------------------------------------------ +30_fixed_pitch_mhk +------------------ + +This example demonstrates the fixed-pitch control of a marine hydrodkinetic (MHK) turbine. + +There are several ways to control the power output of a turbine in above-rated conditions. +In this example we demonstrate the following control configurations: + +#. Constant power underspeed (should be the default) +#. Constant power overspeed +#. Linear increasing power +#. Linear increasing power, leveling out +#. Generic numeric function +#. Constant power overspeed, nonlinear lookup table control + +The desired power curves of each configuration are as follows: + +.. image:: ../images/30_fixed_pitch_mhk_sched.png + +In the first case, the reference generator speed is decreased (underspeed) to maintain a constant rated power above rated. +To slow down the generator, a higher torque must be used: + +.. image:: ../images/30_fixed_pitch_mhk_sched.png + ''' +# Copying images, from docs/: +# cp ../Examples/examples_out/30_fixed_pitch_mhk_sched.png images/ + import os from rosco.toolbox.ofTools.case_gen.run_FAST import run_FAST_ROSCO from rosco.toolbox.ofTools.case_gen import CaseLibrary as cl @@ -18,11 +42,6 @@ import matplotlib.pyplot as plt import numpy as np -''' -Run MHK turbine in OpenFAST with ROSCO torque controller - - -''' #directories From f69d11afd5d22b02e0585a3d8c4a1c6d88922e70 Mon Sep 17 00:00:00 2001 From: dzalkind Date: Fri, 15 Nov 2024 11:48:24 -0700 Subject: [PATCH 210/224] Let user specify configuration of controller in fixed pitch example --- Examples/30_fixed_pitch_mhk.py | 53 ++++++++++++++++++++++++++-------- 1 file changed, 41 insertions(+), 12 deletions(-) diff --git a/Examples/30_fixed_pitch_mhk.py b/Examples/30_fixed_pitch_mhk.py index feeed5ed..307ab154 100644 --- a/Examples/30_fixed_pitch_mhk.py +++ b/Examples/30_fixed_pitch_mhk.py @@ -52,10 +52,13 @@ def main(): + FULL_TEST = True # Run a full test locally (True) or a shorter one for CI + sim_config = 1 # Choose which simulation configuration (1-6) + # Input yaml and output directory parameter_filename = os.path.join(this_dir, 'Tune_Cases/RM1_MHK_FBP.yaml') tune_dir = os.path.dirname(parameter_filename) - run_dir = os.path.join(example_out_dir, '29_MHK/0_baseline') + run_dir = os.path.join(example_out_dir, '30_MHK/0_baseline') os.makedirs(run_dir,exist_ok=True) inps = load_rosco_yaml(parameter_filename) @@ -146,14 +149,18 @@ def main(): axs[2].plot(controller_5.v, controller_5.tau_op, label=plot_labels[4]) axs[2].set_ylabel('Gen Torque [N m]') axs[2].set_xlabel('Flow Speed [m/s]') - axs[0].legend(loc='upper left') + axs[0].legend(loc='upper left', bbox_to_anchor=(.2, 2.35)) + + fig.align_ylabels() + plt.subplots_adjust(hspace=0.5) + if False: plt.show() else: - fig_fname = os.path.join(example_out_dir, '29_marine_hydro_fbp_sched.png') + fig_fname = os.path.join(example_out_dir, '30_fixed_pitch_mhk_sched.png') print('Saving figure ' + fig_fname) - plt.savefig(fig_fname) + plt.savefig(fig_fname,bbox_inches='tight',) # Write parameter input file for constant power underspeed controller param_file = os.path.join(run_dir,'DISCON.IN') @@ -165,13 +172,31 @@ def main(): # simulation set up - # TODO: simulate multiple controller configurations in parallel + if FULL_TEST: + TMax = 60 + else: + TMax = 5 + + all_controller_params = [ + controller_params_1, + controller_params_2, + controller_params_3, + controller_params_4, + controller_params_5, + controller_params_6, + ] + + if sim_config in range(1,len(all_controller_params)+1): + controller_params = all_controller_params[sim_config-1] + else: + raise Exception(f'Invalid sim_config of {sim_config}. Note the 1-indexing.') + r = run_FAST_ROSCO() r.tuning_yaml = parameter_filename r.wind_case_fcn = cl.power_curve r.wind_case_opts = { 'U': [3.0], - 'TMax': 60.0, + 'TMax': TMax, } r.case_inputs = {} r.controller_params = controller_params_1 @@ -184,23 +209,27 @@ def main(): fast_out = op.load_fast_out([os.path.join(run_dir,'RM1_MHK_FBP/power_curve/base/RM1_MHK_FBP_0.out')], tmin=0) fig, axs = plt.subplots(4,1) axs[0].plot(fast_out[0]['Time'], fast_out[0]['Wind1VelX'], label='Constant Power Underspeed') - axs[0].set_ylabel('Flow Speed [m/s]') + axs[0].set_ylabel('Flow Speed [m/s]',rotation=0, labelpad=50) axs[1].plot(fast_out[0]['Time'], fast_out[0]['GenSpeed'] * 2*np.pi/60, label='Constant Power Underspeed') - axs[1].set_ylabel('Gen Speed [rad/s]') + axs[1].set_ylabel('Gen Speed [rad/s]',rotation=0, labelpad=50) axs[2].plot(fast_out[0]['Time'], fast_out[0]['GenTq'] * 1e3, label='Constant Power Underspeed') - axs[2].set_ylabel('Gen Torque [N m]') + axs[2].set_ylabel('Gen Torque [N m]',rotation=0, labelpad=50) axs[3].plot(fast_out[0]['Time'], fast_out[0]['GenPwr'] * 1e3, label='Constant Power Underspeed') - axs[3].set_ylabel('Gen Power [W]') + axs[3].set_ylabel('Gen Power [W]',rotation=0, labelpad=50) axs[3].set_xlabel('Time [s]') + plt.subplots_adjust(hspace=0.5) + fig.align_ylabels() + + # TODO: Compare result to desired operating schedule if False: plt.show() else: - fig_fname = os.path.join(example_out_dir, '29_marine_hydro_fbp_sim.png') + fig_fname = os.path.join(example_out_dir, '30_fixed_pitch_mhk_sim.png') print('Saving figure ' + fig_fname) - plt.savefig(fig_fname) + plt.savefig(fig_fname, bbox_inches='tight') if __name__=="__main__": From e75527630a2fcea396368f475b14ff834a8b4a9a Mon Sep 17 00:00:00 2001 From: dzalkind Date: Thu, 5 Dec 2024 11:32:52 -0700 Subject: [PATCH 211/224] Update max torque limit logic --- rosco/controller/src/Controllers.f90 | 20 +++++++++++++------- 1 file changed, 13 insertions(+), 7 deletions(-) diff --git a/rosco/controller/src/Controllers.f90 b/rosco/controller/src/Controllers.f90 index 05089e37..22094527 100644 --- a/rosco/controller/src/Controllers.f90 +++ b/rosco/controller/src/Controllers.f90 @@ -206,23 +206,29 @@ SUBROUTINE VariableSpeedControl(avrSWAP, CntrPar, LocalVar, objInst, ErrVar) ! Allocate Variables ! -------- Variable-Speed Torque Controller -------- - ! Define initial max torque - LocalVar%VS_MaxTq = CntrPar%VS_MaxTq * LocalVar%PRC_R_Torque ! Pre-compute generator torque values for K*Omega^2 and constant power LocalVar%VS_KOmega2_GenTq = CntrPar%VS_Rgn2K*LocalVar%GenSpeedF*LocalVar%GenSpeedF LocalVar%VS_ConstPwr_GenTq = (CntrPar%VS_RtPwr/(CntrPar%VS_GenEff/100.0))/LocalVar%GenSpeedF * LocalVar%PRC_R_Torque + ! Determine maximum torque saturation limit, VS_MaxTq + IF (CntrPar%VS_FBP == VS_FBP_Variable_Pitch) THEN + ! Variable pitch mode + IF (CntrPar%VS_ConstPower == VS_Mode_ConstPwr) THEN + LocalVar%VS_MaxTq = min(LocalVar%VS_ConstPwr_GenTq * LocalVar%PRC_R_Torque, CntrPar%VS_MaxTq) + ELSE + LocalVar%VS_MaxTq = CntrPar%VS_RtTq * LocalVar%PRC_R_Torque + END IF + ELSE + ! Constant pitch, max torque is control parameter + LocalVar%VS_MaxTq = CntrPar%VS_MaxTq + ENDIF + ! Optimal Tip-Speed-Ratio tracking controller (reference generated in subroutine ComputeVariablesSetpoints) IF ((CntrPar%VS_ControlMode == VS_Mode_WSE_TSR) .OR. \ (CntrPar%VS_ControlMode == VS_Mode_Power_TSR) .OR. \ (CntrPar%VS_ControlMode == VS_Mode_Torque_TSR)) THEN - ! Constant Power, update VS_MaxTq - LocalVar%VS_MaxTq = CntrPar%VS_RtTq * LocalVar%PRC_R_Torque - IF (CntrPar%VS_ConstPower == VS_Mode_ConstPwr) THEN - LocalVar%VS_MaxTq = min(LocalVar%VS_ConstPwr_GenTq * LocalVar%PRC_R_Torque, CntrPar%VS_MaxTq) - END IF ! PI controller LocalVar%GenTq = PIController( & From 05c4f37e26cbd66e0dabb552dfa294ea31c93cff Mon Sep 17 00:00:00 2001 From: dzalkind Date: Thu, 5 Dec 2024 11:36:22 -0700 Subject: [PATCH 212/224] Add checks on fixed blade pitch control and other modes --- rosco/controller/src/ReadSetParameters.f90 | 10 ++++++++++ 1 file changed, 10 insertions(+) diff --git a/rosco/controller/src/ReadSetParameters.f90 b/rosco/controller/src/ReadSetParameters.f90 index 1590e79a..62d38114 100644 --- a/rosco/controller/src/ReadSetParameters.f90 +++ b/rosco/controller/src/ReadSetParameters.f90 @@ -986,6 +986,16 @@ SUBROUTINE CheckInputs(LocalVar, CntrPar, avrSWAP, ErrVar, size_avcMSG) ErrVar%ErrMsg = 'VS_FBP and PC_ControlMode cannot both be greater than 0.' ENDIF + IF ((CntrPar%VS_FBP > 0) .AND. (CntrPar%PRC_Mode > 0)) THEN + ErrVar%aviFAIL = -1 + ErrVar%ErrMsg = 'Fixed blade pitch control (VS_FBP) and power reference control (PRC_Mode) cannot both be enabled.' + ENDIF + + IF ((CntrPar%VS_FBP > 0) .AND. (CntrPar%VS_ConstPower > 0)) THEN + ErrVar%aviFAIL = -1 + ErrVar%ErrMsg = 'Fixed blade pitch control (VS_FBP) and constant power torque control (VS_ConstPower) cannot both be enabled.' + ENDIF + ! PC_ControlMode IF ((CntrPar%PC_ControlMode < 0) .OR. (CntrPar%PC_ControlMode > 1)) THEN ErrVar%aviFAIL = -1 From 7390267080dce65b398cdc27ccf6410942977324 Mon Sep 17 00:00:00 2001 From: dzalkind Date: Thu, 5 Dec 2024 11:36:37 -0700 Subject: [PATCH 213/224] Add fixed pitch control example docs --- docs/source/examples.rst | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/docs/source/examples.rst b/docs/source/examples.rst index fdf39779..5c06c6ee 100644 --- a/docs/source/examples.rst +++ b/docs/source/examples.rst @@ -122,7 +122,7 @@ A complete list of examples is given below: .. automodule:: 17b_zeromq_multi_openfast .. automodule:: 18_pitch_offsets .. automodule:: 19_update_discon_version -.. .. automodule:: 20_active_wake_control +.. automodule:: 20_active_wake_control .. automodule:: 21_optional_inputs .. automodule:: 22_cable_control .. automodule:: 23_structural_control @@ -132,3 +132,4 @@ A complete list of examples is given below: .. automodule:: 27_soft_cut_out .. automodule:: 28_tower_resonance .. automodule:: 29_power_control +.. automodule:: 30_fixed_pitch_mhk From c1d32f2f31c7868050d6d81699a19864bb2efd99 Mon Sep 17 00:00:00 2001 From: dzalkind Date: Thu, 5 Dec 2024 11:40:29 -0700 Subject: [PATCH 214/224] Update images in ex 30 docs --- Examples/30_fixed_pitch_mhk.py | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/Examples/30_fixed_pitch_mhk.py b/Examples/30_fixed_pitch_mhk.py index 307ab154..4bbd78e3 100644 --- a/Examples/30_fixed_pitch_mhk.py +++ b/Examples/30_fixed_pitch_mhk.py @@ -21,7 +21,7 @@ In the first case, the reference generator speed is decreased (underspeed) to maintain a constant rated power above rated. To slow down the generator, a higher torque must be used: -.. image:: ../images/30_fixed_pitch_mhk_sched.png +.. image:: ../images/30_fixed_pitch_mhk_sim.png @@ -29,6 +29,7 @@ # Copying images, from docs/: # cp ../Examples/examples_out/30_fixed_pitch_mhk_sched.png images/ +# cp ../Examples/examples_out/30_fixed_pitch_mhk_sim.png images/ import os from rosco.toolbox.ofTools.case_gen.run_FAST import run_FAST_ROSCO From daf36bc0edd85349905489d0f4dda2961204f154 Mon Sep 17 00:00:00 2001 From: dzalkind Date: Wed, 4 Dec 2024 10:02:35 -0700 Subject: [PATCH 215/224] Add mpi_tools to rosco --- rosco/toolbox/ofTools/case_gen/run_FAST.py | 6 +- rosco/toolbox/ofTools/util/mpi_tools.py | 139 +++++++++++++++++++++ 2 files changed, 142 insertions(+), 3 deletions(-) create mode 100644 rosco/toolbox/ofTools/util/mpi_tools.py diff --git a/rosco/toolbox/ofTools/case_gen/run_FAST.py b/rosco/toolbox/ofTools/case_gen/run_FAST.py index 49061f5b..160a4d40 100644 --- a/rosco/toolbox/ofTools/case_gen/run_FAST.py +++ b/rosco/toolbox/ofTools/case_gen/run_FAST.py @@ -22,13 +22,13 @@ try: from weis.aeroelasticse.runFAST_pywrapper import runFAST_pywrapper_batch in_weis = True -except Exception: +except Exception as e: from rosco.toolbox.ofTools.case_gen.runFAST_pywrapper import runFAST_pywrapper_batch in_weis = False #from rosco.toolbox.ofTools.case_gen.CaseGen_IEC import CaseGen_IEC from rosco.toolbox.ofTools.case_gen.CaseGen_General import CaseGen_General from rosco.toolbox.ofTools.case_gen import CaseLibrary as cl -from wisdem.commonse.mpi_tools import MPI +from openmdao.utils.mpi import MPI # Globals this_dir = os.path.dirname(os.path.abspath(__file__)) @@ -160,7 +160,7 @@ def run_FAST(self): # Management of parallelization, leave in for now if MPI: - from wisdem.commonse.mpi_tools import map_comm_heirarchical, subprocessor_loop, subprocessor_stop + from rosco.toolbox.ofTools.util.mpi_tools import map_comm_heirarchical, subprocessor_loop, subprocessor_stop n_OF_runs = len(case_list) available_cores = MPI.COMM_WORLD.Get_size() diff --git a/rosco/toolbox/ofTools/util/mpi_tools.py b/rosco/toolbox/ofTools/util/mpi_tools.py new file mode 100644 index 00000000..e53fcc85 --- /dev/null +++ b/rosco/toolbox/ofTools/util/mpi_tools.py @@ -0,0 +1,139 @@ +import os +import sys + +from openmdao.utils.mpi import MPI + + +def under_mpirun(): + """Return True if we're being executed under mpirun.""" + # this is a bit of a hack, but there appears to be + # no consistent set of environment vars between MPI + # implementations. + for name in os.environ.keys(): + if ( + name == "OMPI_COMM_WORLD_RANK" + or name == "MPIEXEC_HOSTNAME" + or name.startswith("MPIR_") + or name.startswith("MPICH_") + or name.startswith("INTEL_ONEAPI_MPI_") + or name.startswith("I_MPI_") + ): + return True + return False + + +if under_mpirun(): + + def debug(*msg): # pragma: no cover + newmsg = ["%d: " % MPI.COMM_WORLD.rank] + list(msg) + for m in newmsg: + sys.stdout.write("%s " % m) + sys.stdout.write("\n") + sys.stdout.flush() + +else: + MPI = None + + +def map_comm_heirarchical(n_DV, n_OF, openmp=False): + """ + Heirarchical parallelization communicator mapping. Assumes a number of top level processes + equal to the number of design variables (x2 if central finite differencing is used), each + with its associated number of openfast simulations. + When openmp flag is turned on, the code spreads the openfast simulations across nodes to + lavereage the opnemp parallelization of OpenFAST. The cores that will run under openmp, are marked + in the color map as 1000000. The ones handling python and the DV are marked as 0, and + finally the master ones for each openfast run are marked with a 1. + """ + if openmp: + n_procs_per_node = 36 # Number of + num_procs = MPI.COMM_WORLD.Get_size() + n_nodes = num_procs / n_procs_per_node + + comm_map_down = {} + comm_map_up = {} + color_map = [1000000] * num_procs + + n_DV_per_node = n_DV / n_nodes + + # for m in range(n_DV_per_node): + for nn in range(int(n_nodes)): + for n_dv in range(int(n_DV_per_node)): + comm_map_down[nn * n_procs_per_node + n_dv] = [ + int(n_DV_per_node) + n_dv * n_OF + nn * (n_procs_per_node) + j for j in range(n_OF) + ] + + # This core handles python, so in the colormap the entry is 0 + color_map[nn * n_procs_per_node + n_dv] = int(0) + # These cores handles openfast, so in the colormap the entry is 1 + for k in comm_map_down[nn * n_procs_per_node + n_dv]: + color_map[k] = int(1) + + for j in comm_map_down[nn * n_procs_per_node + n_dv]: + comm_map_up[j] = nn * n_procs_per_node + n_dv + else: + N = n_DV + n_DV * n_OF + comm_map_down = {} + comm_map_up = {} + color_map = [0] * n_DV + + for i in range(n_DV): + comm_map_down[i] = [n_DV + j + i * n_OF for j in range(n_OF)] + color_map.extend([i + 1] * n_OF) + + for j in comm_map_down[i]: + comm_map_up[j] = i + + return comm_map_down, comm_map_up, color_map + + +def subprocessor_loop(comm_map_up): + """ + Subprocessors loop, waiting to receive a function and its arguements to evaluate. + Output of the function is returned. Loops until a stop signal is received + + Input data format: + data[0] = function to be evaluated + data[1] = [list of arguments] + If the function to be evaluated does not fit this format, then a wrapper function + should be created and passed, that handles the setup, argument assignment, etc + for the actual function. + + Stop sigal: + data[0] = False + """ + # comm = impl.world_comm() + rank = MPI.COMM_WORLD.Get_rank() + rank_target = comm_map_up[rank] + + keep_running = True + while keep_running: + data = MPI.COMM_WORLD.recv(source=(rank_target), tag=0) + if data[0] == False: + break + else: + func_execution = data[0] + args = data[1] + output = func_execution(args) + MPI.COMM_WORLD.send(output, dest=(rank_target), tag=1) + + +def subprocessor_stop(comm_map_down): + """ + Send stop signal to subprocessors + """ + # comm = MPI.COMM_WORLD + for rank in comm_map_down.keys(): + subranks = comm_map_down[rank] + for subrank_i in subranks: + MPI.COMM_WORLD.send([False], dest=subrank_i, tag=0) + print("All MPI subranks closed.") + + +if __name__ == "__main__": + + ( + _, + _, + _, + ) = map_comm_heirarchical(2, 4) From 3900637f7dde88c581524749bd1a5f490f7b7809 Mon Sep 17 00:00:00 2001 From: dzalkind Date: Fri, 13 Dec 2024 11:41:30 -0700 Subject: [PATCH 216/224] Finish merge: regen discons, registry --- Examples/Test_Cases/BAR_10/BAR_10_DISCON.IN | 21 +- .../DISCON-UMaineSemi.IN | 21 +- Examples/Test_Cases/MHK_RM1/MHK_RM1_DISCON.IN | 21 +- Examples/Test_Cases/NREL-5MW/DISCON.IN | 21 +- .../NREL_2p8_127/NREL-2p8-127_DISCON.IN | 21 +- rosco/controller/src/ROSCO_IO.f90 | 372 ++++++++++-------- 6 files changed, 283 insertions(+), 194 deletions(-) diff --git a/Examples/Test_Cases/BAR_10/BAR_10_DISCON.IN b/Examples/Test_Cases/BAR_10/BAR_10_DISCON.IN index db0d124d..1d4616d5 100644 --- a/Examples/Test_Cases/BAR_10/BAR_10_DISCON.IN +++ b/Examples/Test_Cases/BAR_10/BAR_10_DISCON.IN @@ -1,5 +1,5 @@ ! Controller parameter input file for the BAR_10 wind turbine -! - File written using ROSCO version 2.9.4 controller tuning logic on 11/15/24 +! - File written using ROSCO version 2.9.4 controller tuning logic on 12/13/24 !------- SIMULATION CONTROL ------------------------------------------------------------ 1 ! LoggingLevel - {0: write no debug files, 1: write standard output .dbg-file, 2: LoggingLevel 1 + ROSCO LocalVars (.dbg2) 3: LoggingLevel 2 + complete avrSWAP-array (.dbg3)} @@ -19,7 +19,7 @@ 0 ! PRC_Mode - Power reference tracking mode{0: power control disabled, 1: lookup table from wind speed to generator speed setpoints, 2: change speed, torque, pitch to control power} 2 ! WE_Mode - Wind speed estimator mode {0: One-second low pass filtered hub height wind speed, 1: Immersion and Invariance Estimator, 2: Extended Kalman Filter} 1 ! PS_Mode - Pitch saturation mode {0: no pitch saturation, 1: implement pitch saturation} -0 ! SD_Mode - Shutdown mode {0: no shutdown procedure, 1: pitch to max pitch at shutdown} +0 ! SD_Mode - Shutdown mode {0: no shutdown procedure, 1: shutdown enabled} 0 ! Fl_Mode - Floating specific feedback mode {0: no nacelle velocity feedback, 1: feed back translational velocity, 2: feed back rotational veloicty} 0 ! TD_Mode - Tower damper mode (0- no tower damper, 1- feed back translational nacelle accelleration to pitch angle 0 ! TRA_Mode - Tower resonance avoidance mode (0- no tower resonsnace avoidance, 1- use torque control setpoints to avoid a specific frequency @@ -152,8 +152,21 @@ -0.016 -0.016 -0.016 -0.016 -0.016 -0.016 -0.016 -0.016 -0.016 -0.016 -0.016 -0.016 -0.016 -0.016 -0.016 -0.016 -0.016 -0.016 -0.016 -0.016 -0.016 -0.016 -0.016 -0.016 -0.016 -0.007 0.004 0.014 0.023 0.031 0.046 0.060 0.074 0.087 0.099 0.111 0.124 0.135 0.147 0.159 0.170 0.181 0.192 0.203 0.214 0.225 0.236 0.246 0.257 0.267 0.277 0.288 0.298 0.308 0.318 0.327 0.337 0.347 0.357 0.366 ! PS_BldPitchMin - Minimum blade pitch angles [rad] !------- SHUTDOWN ----------------------------------------------------------- -0.698100000000 ! SD_MaxPit - Maximum blade pitch angle to initiate shutdown, [rad] -0.418880000000 ! SD_CornerFreq - Cutoff Frequency for first order low-pass filter for blade pitch angle, [rad/s] +0 ! SD_TimeActivate - Time to acitvate shutdown modes, [s] +0 ! SD_EnablePitch - Shutdown when collective blade pitch exceeds a threshold, [-] +0 ! SD_EnableYawError - Shutdown when yaw error exceeds a threshold, [-] +0 ! SD_EnableGenSpeed - Shutdown when generator speed exceeds a threshold, [-] +0 ! SD_EnableTime - Shutdown at a predefined time, [-] +0.698100000000 ! SD_MaxPit - Maximum blade pitch angle to initiate shutdown, [rad] +0.418880000000 ! SD_PitchCornerFreq - Cutoff Frequency for first order low-pass filter for blade pitch angle for shutdown, [rad/s] +30.00000000000 ! SD_MaxYawError - Maximum yaw error to initiate shutdown, [deg] +0.418880000000 ! SD_YawErrorCornerFreq - Cutoff Frequency for first order low-pass filter for yaw error for shutdown, [rad/s] +10.00000000000 ! SD_MaxGenSpd - Maximum generator speed to initiate shutdown, [rad/s] +0.418880000000 ! SD_GenSpdCornerFreq - Cutoff Frequency for first order low-pass filter for generator speed for shutdown, [rad/s] +9999.000000000 ! SD_Time - Shutdown time, [s] +1 ! SD_Method - Shutdown method {1: Reduce generator torque and increase blade pitch}, [-] +62000.00000000 ! SD_MaxTorqueRate - Maximum torque rate for shutdown, [Nm/s] +2.000000000000 ! SD_MaxPitchRate - Maximum pitch rate used for shutdown, [rad/s] !------- Floating ----------------------------------------------------------- 1 ! Fl_n - Number of Fl_Kp gains in gain scheduling, optional with default of 1 diff --git a/Examples/Test_Cases/IEA-15-240-RWT-UMaineSemi/DISCON-UMaineSemi.IN b/Examples/Test_Cases/IEA-15-240-RWT-UMaineSemi/DISCON-UMaineSemi.IN index 221fa4fa..83a4ee40 100644 --- a/Examples/Test_Cases/IEA-15-240-RWT-UMaineSemi/DISCON-UMaineSemi.IN +++ b/Examples/Test_Cases/IEA-15-240-RWT-UMaineSemi/DISCON-UMaineSemi.IN @@ -1,5 +1,5 @@ ! Controller parameter input file for the IEA-15-240-RWT-UMaineSemi wind turbine -! - File written using ROSCO version 2.9.4 controller tuning logic on 11/15/24 +! - File written using ROSCO version 2.9.4 controller tuning logic on 12/13/24 !------- SIMULATION CONTROL ------------------------------------------------------------ 2 ! LoggingLevel - {0: write no debug files, 1: write standard output .dbg-file, 2: LoggingLevel 1 + ROSCO LocalVars (.dbg2) 3: LoggingLevel 2 + complete avrSWAP-array (.dbg3)} @@ -19,7 +19,7 @@ 0 ! PRC_Mode - Power reference tracking mode{0: power control disabled, 1: lookup table from wind speed to generator speed setpoints, 2: change speed, torque, pitch to control power} 2 ! WE_Mode - Wind speed estimator mode {0: One-second low pass filtered hub height wind speed, 1: Immersion and Invariance Estimator, 2: Extended Kalman Filter} 1 ! PS_Mode - Pitch saturation mode {0: no pitch saturation, 1: implement pitch saturation} -0 ! SD_Mode - Shutdown mode {0: no shutdown procedure, 1: pitch to max pitch at shutdown} +0 ! SD_Mode - Shutdown mode {0: no shutdown procedure, 1: shutdown enabled} 2 ! Fl_Mode - Floating specific feedback mode {0: no nacelle velocity feedback, 1: feed back translational velocity, 2: feed back rotational veloicty} 0 ! TD_Mode - Tower damper mode (0- no tower damper, 1- feed back translational nacelle accelleration to pitch angle 0 ! TRA_Mode - Tower resonance avoidance mode (0- no tower resonsnace avoidance, 1- use torque control setpoints to avoid a specific frequency @@ -152,8 +152,21 @@ 0.060 0.060 0.060 0.060 0.060 0.060 0.056 0.052 0.047 0.041 0.036 0.029 0.022 0.015 0.008 0.001 0.000 0.000 0.000 0.000 0.000 0.000 0.000 0.000 0.000 0.006 0.021 0.033 0.044 0.053 0.064 0.074 0.084 0.093 0.103 0.112 0.121 0.130 0.138 0.147 0.155 0.163 0.172 0.180 0.188 0.196 0.203 0.211 0.219 0.227 0.234 0.242 0.250 0.257 0.265 0.272 0.279 0.287 0.294 0.301 ! PS_BldPitchMin - Minimum blade pitch angles [rad] !------- SHUTDOWN ----------------------------------------------------------- -0.698100000000 ! SD_MaxPit - Maximum blade pitch angle to initiate shutdown, [rad] -0.418880000000 ! SD_CornerFreq - Cutoff Frequency for first order low-pass filter for blade pitch angle, [rad/s] +0 ! SD_TimeActivate - Time to acitvate shutdown modes, [s] +0 ! SD_EnablePitch - Shutdown when collective blade pitch exceeds a threshold, [-] +0 ! SD_EnableYawError - Shutdown when yaw error exceeds a threshold, [-] +0 ! SD_EnableGenSpeed - Shutdown when generator speed exceeds a threshold, [-] +0 ! SD_EnableTime - Shutdown at a predefined time, [-] +0.698100000000 ! SD_MaxPit - Maximum blade pitch angle to initiate shutdown, [rad] +0.418880000000 ! SD_PitchCornerFreq - Cutoff Frequency for first order low-pass filter for blade pitch angle for shutdown, [rad/s] +30.00000000000 ! SD_MaxYawError - Maximum yaw error to initiate shutdown, [deg] +0.418880000000 ! SD_YawErrorCornerFreq - Cutoff Frequency for first order low-pass filter for yaw error for shutdown, [rad/s] +10.00000000000 ! SD_MaxGenSpd - Maximum generator speed to initiate shutdown, [rad/s] +0.418880000000 ! SD_GenSpdCornerFreq - Cutoff Frequency for first order low-pass filter for generator speed for shutdown, [rad/s] +9999.000000000 ! SD_Time - Shutdown time, [s] +1 ! SD_Method - Shutdown method {1: Reduce generator torque and increase blade pitch}, [-] +4500000.000000 ! SD_MaxTorqueRate - Maximum torque rate for shutdown, [Nm/s] +0.034900000000 ! SD_MaxPitchRate - Maximum pitch rate used for shutdown, [rad/s] !------- Floating ----------------------------------------------------------- 1 ! Fl_n - Number of Fl_Kp gains in gain scheduling, optional with default of 1 diff --git a/Examples/Test_Cases/MHK_RM1/MHK_RM1_DISCON.IN b/Examples/Test_Cases/MHK_RM1/MHK_RM1_DISCON.IN index 8cb4267a..baa62e8d 100644 --- a/Examples/Test_Cases/MHK_RM1/MHK_RM1_DISCON.IN +++ b/Examples/Test_Cases/MHK_RM1/MHK_RM1_DISCON.IN @@ -1,5 +1,5 @@ ! Controller parameter input file for the MHK_RM1_Floating wind turbine -! - File written using ROSCO version 2.9.4 controller tuning logic on 11/15/24 +! - File written using ROSCO version 2.9.4 controller tuning logic on 12/13/24 !------- SIMULATION CONTROL ------------------------------------------------------------ 2 ! LoggingLevel - {0: write no debug files, 1: write standard output .dbg-file, 2: LoggingLevel 1 + ROSCO LocalVars (.dbg2) 3: LoggingLevel 2 + complete avrSWAP-array (.dbg3)} @@ -19,7 +19,7 @@ 0 ! PRC_Mode - Power reference tracking mode{0: power control disabled, 1: lookup table from wind speed to generator speed setpoints, 2: change speed, torque, pitch to control power} 0 ! WE_Mode - Wind speed estimator mode {0: One-second low pass filtered hub height wind speed, 1: Immersion and Invariance Estimator, 2: Extended Kalman Filter} 0 ! PS_Mode - Pitch saturation mode {0: no pitch saturation, 1: implement pitch saturation} -0 ! SD_Mode - Shutdown mode {0: no shutdown procedure, 1: pitch to max pitch at shutdown} +0 ! SD_Mode - Shutdown mode {0: no shutdown procedure, 1: shutdown enabled} 1 ! Fl_Mode - Floating specific feedback mode {0: no nacelle velocity feedback, 1: feed back translational velocity, 2: feed back rotational veloicty} 0 ! TD_Mode - Tower damper mode (0- no tower damper, 1- feed back translational nacelle accelleration to pitch angle 0 ! TRA_Mode - Tower resonance avoidance mode (0- no tower resonsnace avoidance, 1- use torque control setpoints to avoid a specific frequency @@ -152,8 +152,21 @@ 0.005 0.005 0.005 0.005 0.005 0.005 0.005 0.005 0.005 0.005 0.005 0.005 0.005 0.005 0.005 0.005 0.005 0.005 0.005 0.005 0.005 0.005 0.005 0.005 0.005 0.005 0.005 0.005 0.005 0.005 0.005 0.005 0.005 0.005 0.005 0.005 0.005 0.005 0.005 0.005 0.005 0.005 0.005 0.005 0.005 0.005 0.005 0.005 0.005 0.005 0.005 0.005 0.005 0.005 0.005 0.005 0.005 0.005 0.005 0.005 ! PS_BldPitchMin - Minimum blade pitch angles [rad] !------- SHUTDOWN ----------------------------------------------------------- -0.436300000000 ! SD_MaxPit - Maximum blade pitch angle to initiate shutdown, [rad] -0.418880000000 ! SD_CornerFreq - Cutoff Frequency for first order low-pass filter for blade pitch angle, [rad/s] +0 ! SD_TimeActivate - Time to acitvate shutdown modes, [s] +0 ! SD_EnablePitch - Shutdown when collective blade pitch exceeds a threshold, [-] +0 ! SD_EnableYawError - Shutdown when yaw error exceeds a threshold, [-] +0 ! SD_EnableGenSpeed - Shutdown when generator speed exceeds a threshold, [-] +0 ! SD_EnableTime - Shutdown at a predefined time, [-] +0.698100000000 ! SD_MaxPit - Maximum blade pitch angle to initiate shutdown, [rad] +0.418880000000 ! SD_PitchCornerFreq - Cutoff Frequency for first order low-pass filter for blade pitch angle for shutdown, [rad/s] +30.00000000000 ! SD_MaxYawError - Maximum yaw error to initiate shutdown, [deg] +0.418880000000 ! SD_YawErrorCornerFreq - Cutoff Frequency for first order low-pass filter for yaw error for shutdown, [rad/s] +10.00000000000 ! SD_MaxGenSpd - Maximum generator speed to initiate shutdown, [rad/s] +0.418880000000 ! SD_GenSpdCornerFreq - Cutoff Frequency for first order low-pass filter for generator speed for shutdown, [rad/s] +9999.000000000 ! SD_Time - Shutdown time, [s] +1 ! SD_Method - Shutdown method {1: Reduce generator torque and increase blade pitch}, [-] +7800.000000000 ! SD_MaxTorqueRate - Maximum torque rate for shutdown, [Nm/s] +0.174500000000 ! SD_MaxPitchRate - Maximum pitch rate used for shutdown, [rad/s] !------- Floating ----------------------------------------------------------- 1 ! Fl_n - Number of Fl_Kp gains in gain scheduling, optional with default of 1 diff --git a/Examples/Test_Cases/NREL-5MW/DISCON.IN b/Examples/Test_Cases/NREL-5MW/DISCON.IN index e9a2472b..552b4cec 100644 --- a/Examples/Test_Cases/NREL-5MW/DISCON.IN +++ b/Examples/Test_Cases/NREL-5MW/DISCON.IN @@ -1,5 +1,5 @@ ! Controller parameter input file for the NREL-5MW wind turbine -! - File written using ROSCO version 2.9.4 controller tuning logic on 11/15/24 +! - File written using ROSCO version 2.9.4 controller tuning logic on 12/13/24 !------- SIMULATION CONTROL ------------------------------------------------------------ 1 ! LoggingLevel - {0: write no debug files, 1: write standard output .dbg-file, 2: LoggingLevel 1 + ROSCO LocalVars (.dbg2) 3: LoggingLevel 2 + complete avrSWAP-array (.dbg3)} @@ -19,7 +19,7 @@ 0 ! PRC_Mode - Power reference tracking mode{0: power control disabled, 1: lookup table from wind speed to generator speed setpoints, 2: change speed, torque, pitch to control power} 2 ! WE_Mode - Wind speed estimator mode {0: One-second low pass filtered hub height wind speed, 1: Immersion and Invariance Estimator, 2: Extended Kalman Filter} 1 ! PS_Mode - Pitch saturation mode {0: no pitch saturation, 1: implement pitch saturation} -0 ! SD_Mode - Shutdown mode {0: no shutdown procedure, 1: pitch to max pitch at shutdown} +0 ! SD_Mode - Shutdown mode {0: no shutdown procedure, 1: shutdown enabled} 0 ! Fl_Mode - Floating specific feedback mode {0: no nacelle velocity feedback, 1: feed back translational velocity, 2: feed back rotational veloicty} 0 ! TD_Mode - Tower damper mode (0- no tower damper, 1- feed back translational nacelle accelleration to pitch angle 0 ! TRA_Mode - Tower resonance avoidance mode (0- no tower resonsnace avoidance, 1- use torque control setpoints to avoid a specific frequency @@ -152,8 +152,21 @@ 0.008 0.008 0.008 0.008 0.008 0.008 0.008 0.008 0.008 0.008 0.008 0.008 0.008 0.008 0.008 0.008 0.008 0.008 0.008 0.008 0.008 0.008 0.008 0.008 0.008 0.022 0.034 0.042 0.049 0.057 0.068 0.079 0.090 0.100 0.110 0.120 0.130 0.139 0.149 0.158 0.168 0.177 0.186 0.195 0.204 0.213 0.222 0.230 0.239 0.248 0.256 0.265 0.273 0.281 0.290 0.298 0.306 0.314 0.322 0.330 ! PS_BldPitchMin - Minimum blade pitch angles [rad] !------- SHUTDOWN ----------------------------------------------------------- -0.436300000000 ! SD_MaxPit - Maximum blade pitch angle to initiate shutdown, [rad] -0.418880000000 ! SD_CornerFreq - Cutoff Frequency for first order low-pass filter for blade pitch angle, [rad/s] +0 ! SD_TimeActivate - Time to acitvate shutdown modes, [s] +0 ! SD_EnablePitch - Shutdown when collective blade pitch exceeds a threshold, [-] +0 ! SD_EnableYawError - Shutdown when yaw error exceeds a threshold, [-] +0 ! SD_EnableGenSpeed - Shutdown when generator speed exceeds a threshold, [-] +0 ! SD_EnableTime - Shutdown at a predefined time, [-] +0.698100000000 ! SD_MaxPit - Maximum blade pitch angle to initiate shutdown, [rad] +0.418880000000 ! SD_PitchCornerFreq - Cutoff Frequency for first order low-pass filter for blade pitch angle for shutdown, [rad/s] +30.00000000000 ! SD_MaxYawError - Maximum yaw error to initiate shutdown, [deg] +0.418880000000 ! SD_YawErrorCornerFreq - Cutoff Frequency for first order low-pass filter for yaw error for shutdown, [rad/s] +10.00000000000 ! SD_MaxGenSpd - Maximum generator speed to initiate shutdown, [rad/s] +0.418880000000 ! SD_GenSpdCornerFreq - Cutoff Frequency for first order low-pass filter for generator speed for shutdown, [rad/s] +9999.000000000 ! SD_Time - Shutdown time, [s] +1 ! SD_Method - Shutdown method {1: Reduce generator torque and increase blade pitch}, [-] +40000.00000000 ! SD_MaxTorqueRate - Maximum torque rate for shutdown, [Nm/s] +0.174500000000 ! SD_MaxPitchRate - Maximum pitch rate used for shutdown, [rad/s] !------- Floating ----------------------------------------------------------- 1 ! Fl_n - Number of Fl_Kp gains in gain scheduling, optional with default of 1 diff --git a/Examples/Test_Cases/NREL_2p8_127/NREL-2p8-127_DISCON.IN b/Examples/Test_Cases/NREL_2p8_127/NREL-2p8-127_DISCON.IN index d7090639..9b3d766b 100644 --- a/Examples/Test_Cases/NREL_2p8_127/NREL-2p8-127_DISCON.IN +++ b/Examples/Test_Cases/NREL_2p8_127/NREL-2p8-127_DISCON.IN @@ -1,5 +1,5 @@ ! Controller parameter input file for the NREL-2p8-127 wind turbine -! - File written using ROSCO version 2.9.4 controller tuning logic on 11/15/24 +! - File written using ROSCO version 2.9.4 controller tuning logic on 12/13/24 !------- SIMULATION CONTROL ------------------------------------------------------------ 2 ! LoggingLevel - {0: write no debug files, 1: write standard output .dbg-file, 2: LoggingLevel 1 + ROSCO LocalVars (.dbg2) 3: LoggingLevel 2 + complete avrSWAP-array (.dbg3)} @@ -19,7 +19,7 @@ 0 ! PRC_Mode - Power reference tracking mode{0: power control disabled, 1: lookup table from wind speed to generator speed setpoints, 2: change speed, torque, pitch to control power} 2 ! WE_Mode - Wind speed estimator mode {0: One-second low pass filtered hub height wind speed, 1: Immersion and Invariance Estimator, 2: Extended Kalman Filter} 1 ! PS_Mode - Pitch saturation mode {0: no pitch saturation, 1: implement pitch saturation} -0 ! SD_Mode - Shutdown mode {0: no shutdown procedure, 1: pitch to max pitch at shutdown} +0 ! SD_Mode - Shutdown mode {0: no shutdown procedure, 1: shutdown enabled} 0 ! Fl_Mode - Floating specific feedback mode {0: no nacelle velocity feedback, 1: feed back translational velocity, 2: feed back rotational veloicty} 0 ! TD_Mode - Tower damper mode (0- no tower damper, 1- feed back translational nacelle accelleration to pitch angle 0 ! TRA_Mode - Tower resonance avoidance mode (0- no tower resonsnace avoidance, 1- use torque control setpoints to avoid a specific frequency @@ -152,8 +152,21 @@ 0.000 0.000 0.000 0.000 0.000 0.000 0.000 0.000 0.000 0.000 0.000 0.000 0.000 0.000 0.000 0.000 0.000 0.000 0.000 0.000 0.000 0.000 0.000 0.019 0.031 0.041 0.050 0.058 0.066 0.074 0.086 0.096 0.107 0.117 0.127 0.137 0.147 0.156 0.165 0.174 0.183 0.192 0.201 0.210 0.218 0.227 0.236 0.244 0.253 0.262 0.270 0.279 0.287 0.295 0.303 0.312 0.320 0.328 0.337 0.345 ! PS_BldPitchMin - Minimum blade pitch angles [rad] !------- SHUTDOWN ----------------------------------------------------------- -0.436300000000 ! SD_MaxPit - Maximum blade pitch angle to initiate shutdown, [rad] -0.418880000000 ! SD_CornerFreq - Cutoff Frequency for first order low-pass filter for blade pitch angle, [rad/s] +0 ! SD_TimeActivate - Time to acitvate shutdown modes, [s] +0 ! SD_EnablePitch - Shutdown when collective blade pitch exceeds a threshold, [-] +0 ! SD_EnableYawError - Shutdown when yaw error exceeds a threshold, [-] +0 ! SD_EnableGenSpeed - Shutdown when generator speed exceeds a threshold, [-] +0 ! SD_EnableTime - Shutdown at a predefined time, [-] +0.698100000000 ! SD_MaxPit - Maximum blade pitch angle to initiate shutdown, [rad] +0.418880000000 ! SD_PitchCornerFreq - Cutoff Frequency for first order low-pass filter for blade pitch angle for shutdown, [rad/s] +30.00000000000 ! SD_MaxYawError - Maximum yaw error to initiate shutdown, [deg] +0.418880000000 ! SD_YawErrorCornerFreq - Cutoff Frequency for first order low-pass filter for yaw error for shutdown, [rad/s] +10.00000000000 ! SD_MaxGenSpd - Maximum generator speed to initiate shutdown, [rad/s] +0.418880000000 ! SD_GenSpdCornerFreq - Cutoff Frequency for first order low-pass filter for generator speed for shutdown, [rad/s] +9999.000000000 ! SD_Time - Shutdown time, [s] +1 ! SD_Method - Shutdown method {1: Reduce generator torque and increase blade pitch}, [-] +22000.00000000 ! SD_MaxTorqueRate - Maximum torque rate for shutdown, [Nm/s] +0.174500000000 ! SD_MaxPitchRate - Maximum pitch rate used for shutdown, [rad/s] !------- Floating ----------------------------------------------------------- 1 ! Fl_n - Number of Fl_Kp gains in gain scheduling, optional with default of 1 diff --git a/rosco/controller/src/ROSCO_IO.f90 b/rosco/controller/src/ROSCO_IO.f90 index 05f9c809..ae18b27b 100644 --- a/rosco/controller/src/ROSCO_IO.f90 +++ b/rosco/controller/src/ROSCO_IO.f90 @@ -37,6 +37,7 @@ SUBROUTINE WriteRestartFile(LocalVar, CntrPar, ErrVar, objInst, RootName, size_a ELSE WRITE( Un, IOSTAT=ErrStat) LocalVar%iStatus + WRITE( Un, IOSTAT=ErrStat) LocalVar%AlreadyInitialized WRITE( Un, IOSTAT=ErrStat) LocalVar%RestartWSE WRITE( Un, IOSTAT=ErrStat) LocalVar%Time WRITE( Un, IOSTAT=ErrStat) LocalVar%DT @@ -127,6 +128,9 @@ SUBROUTINE WriteRestartFile(LocalVar, CntrPar, ErrVar, objInst, RootName, size_a WRITE( Un, IOSTAT=ErrStat) LocalVar%PitCom(1) WRITE( Un, IOSTAT=ErrStat) LocalVar%PitCom(2) WRITE( Un, IOSTAT=ErrStat) LocalVar%PitCom(3) + WRITE( Un, IOSTAT=ErrStat) LocalVar%PitCom_SD(1) + WRITE( Un, IOSTAT=ErrStat) LocalVar%PitCom_SD(2) + WRITE( Un, IOSTAT=ErrStat) LocalVar%PitCom_SD(3) WRITE( Un, IOSTAT=ErrStat) LocalVar%PitComAct(1) WRITE( Un, IOSTAT=ErrStat) LocalVar%PitComAct(2) WRITE( Un, IOSTAT=ErrStat) LocalVar%PitComAct(3) @@ -157,7 +161,11 @@ SUBROUTINE WriteRestartFile(LocalVar, CntrPar, ErrVar, objInst, RootName, size_a WRITE( Un, IOSTAT=ErrStat) LocalVar%PRC_Min_Pitch WRITE( Un, IOSTAT=ErrStat) LocalVar%PS_Min_Pitch WRITE( Un, IOSTAT=ErrStat) LocalVar%OL_Index - WRITE( Un, IOSTAT=ErrStat) LocalVar%SD + WRITE( Un, IOSTAT=ErrStat) LocalVar%SD_Trigger + WRITE( Un, IOSTAT=ErrStat) LocalVar%SD_BlPitchF + WRITE( Un, IOSTAT=ErrStat) LocalVar%SD_NacVaneF + WRITE( Un, IOSTAT=ErrStat) LocalVar%SD_GenSpeedF + WRITE( Un, IOSTAT=ErrStat) LocalVar%GenTq_SD WRITE( Un, IOSTAT=ErrStat) LocalVar%Fl_PitCom WRITE( Un, IOSTAT=ErrStat) LocalVar%NACIMU_FA_AccF WRITE( Un, IOSTAT=ErrStat) LocalVar%FA_AccF @@ -355,6 +363,7 @@ SUBROUTINE ReadRestartFile(avrSWAP, LocalVar, CntrPar, objInst, PerfData, RootNa ELSE READ( Un, IOSTAT=ErrStat) LocalVar%iStatus + READ( Un, IOSTAT=ErrStat) LocalVar%AlreadyInitialized READ( Un, IOSTAT=ErrStat) LocalVar%RestartWSE READ( Un, IOSTAT=ErrStat) LocalVar%Time READ( Un, IOSTAT=ErrStat) LocalVar%DT @@ -445,6 +454,9 @@ SUBROUTINE ReadRestartFile(avrSWAP, LocalVar, CntrPar, objInst, PerfData, RootNa READ( Un, IOSTAT=ErrStat) LocalVar%PitCom(1) READ( Un, IOSTAT=ErrStat) LocalVar%PitCom(2) READ( Un, IOSTAT=ErrStat) LocalVar%PitCom(3) + READ( Un, IOSTAT=ErrStat) LocalVar%PitCom_SD(1) + READ( Un, IOSTAT=ErrStat) LocalVar%PitCom_SD(2) + READ( Un, IOSTAT=ErrStat) LocalVar%PitCom_SD(3) READ( Un, IOSTAT=ErrStat) LocalVar%PitComAct(1) READ( Un, IOSTAT=ErrStat) LocalVar%PitComAct(2) READ( Un, IOSTAT=ErrStat) LocalVar%PitComAct(3) @@ -475,7 +487,11 @@ SUBROUTINE ReadRestartFile(avrSWAP, LocalVar, CntrPar, objInst, PerfData, RootNa READ( Un, IOSTAT=ErrStat) LocalVar%PRC_Min_Pitch READ( Un, IOSTAT=ErrStat) LocalVar%PS_Min_Pitch READ( Un, IOSTAT=ErrStat) LocalVar%OL_Index - READ( Un, IOSTAT=ErrStat) LocalVar%SD + READ( Un, IOSTAT=ErrStat) LocalVar%SD_Trigger + READ( Un, IOSTAT=ErrStat) LocalVar%SD_BlPitchF + READ( Un, IOSTAT=ErrStat) LocalVar%SD_NacVaneF + READ( Un, IOSTAT=ErrStat) LocalVar%SD_GenSpeedF + READ( Un, IOSTAT=ErrStat) LocalVar%GenTq_SD READ( Un, IOSTAT=ErrStat) LocalVar%Fl_PitCom READ( Un, IOSTAT=ErrStat) LocalVar%NACIMU_FA_AccF READ( Un, IOSTAT=ErrStat) LocalVar%FA_AccF @@ -724,178 +740,186 @@ SUBROUTINE Debug(LocalVar, CntrPar, DebugVar, ErrVar, avrSWAP, RootName, size_av '[N/A]', '[N/A]', '[N/A]', '[N/A]', '[rad/s]', & '[deg]', '[deg]', '[deg]', '[N/A]', '[rad/s]', & '[rad/s]'] - nLocalVars = 140 + nLocalVars = 147 Allocate(LocalVarOutData(nLocalVars)) Allocate(LocalVarOutStrings(nLocalVars)) LocalVarOutData(1) = LocalVar%iStatus - LocalVarOutData(2) = LocalVar%RestartWSE - LocalVarOutData(3) = LocalVar%Time - LocalVarOutData(4) = LocalVar%DT - LocalVarOutData(5) = LocalVar%n_DT - LocalVarOutData(6) = LocalVar%Time_Last - LocalVarOutData(7) = LocalVar%VS_GenPwr - LocalVarOutData(8) = LocalVar%GenSpeed - LocalVarOutData(9) = LocalVar%RotSpeed - LocalVarOutData(10) = LocalVar%NacHeading - LocalVarOutData(11) = LocalVar%NacVane - LocalVarOutData(12) = LocalVar%NacVaneF - LocalVarOutData(13) = LocalVar%HorWindV - LocalVarOutData(14) = LocalVar%HorWindV_F - LocalVarOutData(15) = LocalVar%rootMOOP(1) - LocalVarOutData(16) = LocalVar%rootMOOPF(1) - LocalVarOutData(17) = LocalVar%BlPitch(1) - LocalVarOutData(18) = LocalVar%BlPitchCMeas - LocalVarOutData(19) = LocalVar%Azimuth - LocalVarOutData(20) = LocalVar%OL_Azimuth - LocalVarOutData(21) = LocalVar%AzUnwrapped - LocalVarOutData(22) = LocalVar%AzError - LocalVarOutData(23) = LocalVar%GenTqAz - LocalVarOutData(24) = LocalVar%AzBuffer(1) - LocalVarOutData(25) = LocalVar%NumBl - LocalVarOutData(26) = LocalVar%FA_Acc - LocalVarOutData(27) = LocalVar%NacIMU_FA_Acc - LocalVarOutData(28) = LocalVar%FA_AccHPF - LocalVarOutData(29) = LocalVar%FA_AccHPFI - LocalVarOutData(30) = LocalVar%FA_PitCom(1) - LocalVarOutData(31) = LocalVar%VS_RefSpd - LocalVarOutData(32) = LocalVar%VS_RefSpd_TSR - LocalVarOutData(33) = LocalVar%VS_RefSpd_TRA - LocalVarOutData(34) = LocalVar%VS_RefSpd_RL - LocalVarOutData(35) = LocalVar%PC_RefSpd - LocalVarOutData(36) = LocalVar%PC_RefSpd_SS - LocalVarOutData(37) = LocalVar%PC_RefSpd_PRC - LocalVarOutData(38) = LocalVar%RotSpeedF - LocalVarOutData(39) = LocalVar%GenSpeedF - LocalVarOutData(40) = LocalVar%GenTq - LocalVarOutData(41) = LocalVar%GenTqMeas - LocalVarOutData(42) = LocalVar%GenArTq - LocalVarOutData(43) = LocalVar%GenBrTq - LocalVarOutData(44) = LocalVar%VS_KOmega2_GenTq - LocalVarOutData(45) = LocalVar%VS_ConstPwr_GenTq - LocalVarOutData(46) = LocalVar%IPC_PitComF(1) - LocalVarOutData(47) = LocalVar%PC_KP - LocalVarOutData(48) = LocalVar%PC_KI - LocalVarOutData(49) = LocalVar%PC_KD - LocalVarOutData(50) = LocalVar%PC_TF - LocalVarOutData(51) = LocalVar%PC_MaxPit - LocalVarOutData(52) = LocalVar%PC_MinPit - LocalVarOutData(53) = LocalVar%PC_PitComT - LocalVarOutData(54) = LocalVar%PC_PitComT_Last - LocalVarOutData(55) = LocalVar%PC_PitComTF - LocalVarOutData(56) = LocalVar%PC_PitComT_IPC(1) - LocalVarOutData(57) = LocalVar%PC_PwrErr - LocalVarOutData(58) = LocalVar%PC_SpdErr - LocalVarOutData(59) = LocalVar%IPC_AxisTilt_1P - LocalVarOutData(60) = LocalVar%IPC_AxisYaw_1P - LocalVarOutData(61) = LocalVar%IPC_AxisTilt_2P - LocalVarOutData(62) = LocalVar%IPC_AxisYaw_2P - LocalVarOutData(63) = LocalVar%axisTilt_1P - LocalVarOutData(64) = LocalVar%axisYaw_1P - LocalVarOutData(65) = LocalVar%axisYawF_1P - LocalVarOutData(66) = LocalVar%axisTilt_2P - LocalVarOutData(67) = LocalVar%axisYaw_2P - LocalVarOutData(68) = LocalVar%axisYawF_2P - LocalVarOutData(69) = LocalVar%IPC_KI(1) - LocalVarOutData(70) = LocalVar%IPC_KP(1) - LocalVarOutData(71) = LocalVar%IPC_IntSat - LocalVarOutData(72) = LocalVar%PC_State - LocalVarOutData(73) = LocalVar%PitCom(1) - LocalVarOutData(74) = LocalVar%PitComAct(1) - LocalVarOutData(75) = LocalVar%SS_DelOmegaF - LocalVarOutData(76) = LocalVar%TestType - LocalVarOutData(77) = LocalVar%Kp_Float - LocalVarOutData(78) = LocalVar%VS_MaxTq - LocalVarOutData(79) = LocalVar%VS_LastGenTrq - LocalVarOutData(80) = LocalVar%VS_LastGenPwr - LocalVarOutData(81) = LocalVar%VS_MechGenPwr - LocalVarOutData(82) = LocalVar%VS_SpdErrAr - LocalVarOutData(83) = LocalVar%VS_SpdErrBr - LocalVarOutData(84) = LocalVar%VS_SpdErr - LocalVarOutData(85) = LocalVar%VS_State - LocalVarOutData(86) = LocalVar%VS_Rgn3Pitch - LocalVarOutData(87) = LocalVar%WE_Vw - LocalVarOutData(88) = LocalVar%WE_Vw_F - LocalVarOutData(89) = LocalVar%WE_VwI - LocalVarOutData(90) = LocalVar%WE_VwIdot - LocalVarOutData(91) = LocalVar%WE_Op - LocalVarOutData(92) = LocalVar%WE_Op_Last - LocalVarOutData(93) = LocalVar%VS_LastGenTrqF - LocalVarOutData(94) = LocalVar%PRC_WSE_F - LocalVarOutData(95) = LocalVar%PRC_R_Speed - LocalVarOutData(96) = LocalVar%PRC_R_Torque - LocalVarOutData(97) = LocalVar%PRC_R_Pitch - LocalVarOutData(98) = LocalVar%PRC_R_Total - LocalVarOutData(99) = LocalVar%PRC_Min_Pitch - LocalVarOutData(100) = LocalVar%PS_Min_Pitch - LocalVarOutData(101) = LocalVar%OL_Index - LocalVarOutData(102) = LocalVar%Fl_PitCom - LocalVarOutData(103) = LocalVar%NACIMU_FA_AccF - LocalVarOutData(104) = LocalVar%FA_AccF - LocalVarOutData(105) = LocalVar%FA_Hist - LocalVarOutData(106) = LocalVar%TRA_LastRefSpd - LocalVarOutData(107) = LocalVar%VS_RefSpeed - LocalVarOutData(108) = LocalVar%PtfmTDX - LocalVarOutData(109) = LocalVar%PtfmTDY - LocalVarOutData(110) = LocalVar%PtfmTDZ - LocalVarOutData(111) = LocalVar%PtfmRDX - LocalVarOutData(112) = LocalVar%PtfmRDY - LocalVarOutData(113) = LocalVar%PtfmRDZ - LocalVarOutData(114) = LocalVar%PtfmTVX - LocalVarOutData(115) = LocalVar%PtfmTVY - LocalVarOutData(116) = LocalVar%PtfmTVZ - LocalVarOutData(117) = LocalVar%PtfmRVX - LocalVarOutData(118) = LocalVar%PtfmRVY - LocalVarOutData(119) = LocalVar%PtfmRVZ - LocalVarOutData(120) = LocalVar%PtfmTAX - LocalVarOutData(121) = LocalVar%PtfmTAY - LocalVarOutData(122) = LocalVar%PtfmTAZ - LocalVarOutData(123) = LocalVar%PtfmRAX - LocalVarOutData(124) = LocalVar%PtfmRAY - LocalVarOutData(125) = LocalVar%PtfmRAZ - LocalVarOutData(126) = LocalVar%CC_DesiredL(1) - LocalVarOutData(127) = LocalVar%CC_ActuatedL(1) - LocalVarOutData(128) = LocalVar%CC_ActuatedDL(1) - LocalVarOutData(129) = LocalVar%StC_Input(1) - LocalVarOutData(130) = LocalVar%Flp_Angle(1) - LocalVarOutData(131) = LocalVar%RootMyb_Last(1) - LocalVarOutData(132) = LocalVar%ACC_INFILE_SIZE - LocalVarOutData(133) = LocalVar%AWC_complexangle(1) - LocalVarOutData(134) = LocalVar%ZMQ_ID - LocalVarOutData(135) = LocalVar%ZMQ_YawOffset - LocalVarOutData(136) = LocalVar%ZMQ_TorqueOffset - LocalVarOutData(137) = LocalVar%ZMQ_PitOffset(1) - LocalVarOutData(138) = LocalVar%ZMQ_R_Speed - LocalVarOutData(139) = LocalVar%ZMQ_R_Torque - LocalVarOutData(140) = LocalVar%ZMQ_R_Pitch - LocalVarOutStrings = [CHARACTER(15) :: 'iStatus', 'RestartWSE', 'Time', 'DT', 'n_DT', & - 'Time_Last', 'VS_GenPwr', 'GenSpeed', 'RotSpeed', 'NacHeading', & - 'NacVane', 'NacVaneF', 'HorWindV', 'HorWindV_F', 'rootMOOP', & - 'rootMOOPF', 'BlPitch', 'BlPitchCMeas', 'Azimuth', 'OL_Azimuth', & - 'AzUnwrapped', 'AzError', 'GenTqAz', 'AzBuffer', 'NumBl', & - 'FA_Acc', 'NacIMU_FA_Acc', 'FA_AccHPF', 'FA_AccHPFI', 'FA_PitCom', & - 'VS_RefSpd', 'VS_RefSpd_TSR', 'VS_RefSpd_TRA', 'VS_RefSpd_RL', 'PC_RefSpd', & - 'PC_RefSpd_SS', 'PC_RefSpd_PRC', 'RotSpeedF', 'GenSpeedF', 'GenTq', & - 'GenTqMeas', 'GenArTq', 'GenBrTq', 'VS_KOmega2_GenTq', 'VS_ConstPwr_GenTq', & - 'IPC_PitComF', 'PC_KP', 'PC_KI', 'PC_KD', 'PC_TF', & - 'PC_MaxPit', 'PC_MinPit', 'PC_PitComT', 'PC_PitComT_Last', 'PC_PitComTF', & - 'PC_PitComT_IPC', 'PC_PwrErr', 'PC_SpdErr', 'IPC_AxisTilt_1P', 'IPC_AxisYaw_1P', & - 'IPC_AxisTilt_2P', 'IPC_AxisYaw_2P', 'axisTilt_1P', 'axisYaw_1P', 'axisYawF_1P', & - 'axisTilt_2P', 'axisYaw_2P', 'axisYawF_2P', 'IPC_KI', 'IPC_KP', & - 'IPC_IntSat', 'PC_State', 'PitCom', 'PitComAct', 'SS_DelOmegaF', & - 'TestType', 'Kp_Float', 'VS_MaxTq', 'VS_LastGenTrq', 'VS_LastGenPwr', & - 'VS_MechGenPwr', 'VS_SpdErrAr', 'VS_SpdErrBr', 'VS_SpdErr', 'VS_State', & - 'VS_Rgn3Pitch', 'WE_Vw', 'WE_Vw_F', 'WE_VwI', 'WE_VwIdot', & - 'WE_Op', 'WE_Op_Last', 'VS_LastGenTrqF', 'PRC_WSE_F', 'PRC_R_Speed', & - 'PRC_R_Torque', 'PRC_R_Pitch', 'PRC_R_Total', 'PRC_Min_Pitch', 'PS_Min_Pitch', & - 'OL_Index', 'Fl_PitCom', 'NACIMU_FA_AccF', 'FA_AccF', 'FA_Hist', & - 'TRA_LastRefSpd', 'VS_RefSpeed', 'PtfmTDX', 'PtfmTDY', 'PtfmTDZ', & - 'PtfmRDX', 'PtfmRDY', 'PtfmRDZ', 'PtfmTVX', 'PtfmTVY', & - 'PtfmTVZ', 'PtfmRVX', 'PtfmRVY', 'PtfmRVZ', 'PtfmTAX', & - 'PtfmTAY', 'PtfmTAZ', 'PtfmRAX', 'PtfmRAY', 'PtfmRAZ', & - 'CC_DesiredL', 'CC_ActuatedL', 'CC_ActuatedDL', 'StC_Input', 'Flp_Angle', & - 'RootMyb_Last', 'ACC_INFILE_SIZE', 'AWC_complexangle', 'ZMQ_ID', 'ZMQ_YawOffset', & - 'ZMQ_TorqueOffset', 'ZMQ_PitOffset', 'ZMQ_R_Speed', 'ZMQ_R_Torque', 'ZMQ_R_Pitch' & - ] + LocalVarOutData(2) = LocalVar%AlreadyInitialized + LocalVarOutData(3) = LocalVar%RestartWSE + LocalVarOutData(4) = LocalVar%Time + LocalVarOutData(5) = LocalVar%DT + LocalVarOutData(6) = LocalVar%n_DT + LocalVarOutData(7) = LocalVar%Time_Last + LocalVarOutData(8) = LocalVar%VS_GenPwr + LocalVarOutData(9) = LocalVar%GenSpeed + LocalVarOutData(10) = LocalVar%RotSpeed + LocalVarOutData(11) = LocalVar%NacHeading + LocalVarOutData(12) = LocalVar%NacVane + LocalVarOutData(13) = LocalVar%NacVaneF + LocalVarOutData(14) = LocalVar%HorWindV + LocalVarOutData(15) = LocalVar%HorWindV_F + LocalVarOutData(16) = LocalVar%rootMOOP(1) + LocalVarOutData(17) = LocalVar%rootMOOPF(1) + LocalVarOutData(18) = LocalVar%BlPitch(1) + LocalVarOutData(19) = LocalVar%BlPitchCMeas + LocalVarOutData(20) = LocalVar%Azimuth + LocalVarOutData(21) = LocalVar%OL_Azimuth + LocalVarOutData(22) = LocalVar%AzUnwrapped + LocalVarOutData(23) = LocalVar%AzError + LocalVarOutData(24) = LocalVar%GenTqAz + LocalVarOutData(25) = LocalVar%AzBuffer(1) + LocalVarOutData(26) = LocalVar%NumBl + LocalVarOutData(27) = LocalVar%FA_Acc + LocalVarOutData(28) = LocalVar%NacIMU_FA_Acc + LocalVarOutData(29) = LocalVar%FA_AccHPF + LocalVarOutData(30) = LocalVar%FA_AccHPFI + LocalVarOutData(31) = LocalVar%FA_PitCom(1) + LocalVarOutData(32) = LocalVar%VS_RefSpd + LocalVarOutData(33) = LocalVar%VS_RefSpd_TSR + LocalVarOutData(34) = LocalVar%VS_RefSpd_TRA + LocalVarOutData(35) = LocalVar%VS_RefSpd_RL + LocalVarOutData(36) = LocalVar%PC_RefSpd + LocalVarOutData(37) = LocalVar%PC_RefSpd_SS + LocalVarOutData(38) = LocalVar%PC_RefSpd_PRC + LocalVarOutData(39) = LocalVar%RotSpeedF + LocalVarOutData(40) = LocalVar%GenSpeedF + LocalVarOutData(41) = LocalVar%GenTq + LocalVarOutData(42) = LocalVar%GenTqMeas + LocalVarOutData(43) = LocalVar%GenArTq + LocalVarOutData(44) = LocalVar%GenBrTq + LocalVarOutData(45) = LocalVar%VS_KOmega2_GenTq + LocalVarOutData(46) = LocalVar%VS_ConstPwr_GenTq + LocalVarOutData(47) = LocalVar%IPC_PitComF(1) + LocalVarOutData(48) = LocalVar%PC_KP + LocalVarOutData(49) = LocalVar%PC_KI + LocalVarOutData(50) = LocalVar%PC_KD + LocalVarOutData(51) = LocalVar%PC_TF + LocalVarOutData(52) = LocalVar%PC_MaxPit + LocalVarOutData(53) = LocalVar%PC_MinPit + LocalVarOutData(54) = LocalVar%PC_PitComT + LocalVarOutData(55) = LocalVar%PC_PitComT_Last + LocalVarOutData(56) = LocalVar%PC_PitComTF + LocalVarOutData(57) = LocalVar%PC_PitComT_IPC(1) + LocalVarOutData(58) = LocalVar%PC_PwrErr + LocalVarOutData(59) = LocalVar%PC_SpdErr + LocalVarOutData(60) = LocalVar%IPC_AxisTilt_1P + LocalVarOutData(61) = LocalVar%IPC_AxisYaw_1P + LocalVarOutData(62) = LocalVar%IPC_AxisTilt_2P + LocalVarOutData(63) = LocalVar%IPC_AxisYaw_2P + LocalVarOutData(64) = LocalVar%axisTilt_1P + LocalVarOutData(65) = LocalVar%axisYaw_1P + LocalVarOutData(66) = LocalVar%axisYawF_1P + LocalVarOutData(67) = LocalVar%axisTilt_2P + LocalVarOutData(68) = LocalVar%axisYaw_2P + LocalVarOutData(69) = LocalVar%axisYawF_2P + LocalVarOutData(70) = LocalVar%IPC_KI(1) + LocalVarOutData(71) = LocalVar%IPC_KP(1) + LocalVarOutData(72) = LocalVar%IPC_IntSat + LocalVarOutData(73) = LocalVar%PC_State + LocalVarOutData(74) = LocalVar%PitCom(1) + LocalVarOutData(75) = LocalVar%PitCom_SD(1) + LocalVarOutData(76) = LocalVar%PitComAct(1) + LocalVarOutData(77) = LocalVar%SS_DelOmegaF + LocalVarOutData(78) = LocalVar%TestType + LocalVarOutData(79) = LocalVar%Kp_Float + LocalVarOutData(80) = LocalVar%VS_MaxTq + LocalVarOutData(81) = LocalVar%VS_LastGenTrq + LocalVarOutData(82) = LocalVar%VS_LastGenPwr + LocalVarOutData(83) = LocalVar%VS_MechGenPwr + LocalVarOutData(84) = LocalVar%VS_SpdErrAr + LocalVarOutData(85) = LocalVar%VS_SpdErrBr + LocalVarOutData(86) = LocalVar%VS_SpdErr + LocalVarOutData(87) = LocalVar%VS_State + LocalVarOutData(88) = LocalVar%VS_Rgn3Pitch + LocalVarOutData(89) = LocalVar%WE_Vw + LocalVarOutData(90) = LocalVar%WE_Vw_F + LocalVarOutData(91) = LocalVar%WE_VwI + LocalVarOutData(92) = LocalVar%WE_VwIdot + LocalVarOutData(93) = LocalVar%WE_Op + LocalVarOutData(94) = LocalVar%WE_Op_Last + LocalVarOutData(95) = LocalVar%VS_LastGenTrqF + LocalVarOutData(96) = LocalVar%PRC_WSE_F + LocalVarOutData(97) = LocalVar%PRC_R_Speed + LocalVarOutData(98) = LocalVar%PRC_R_Torque + LocalVarOutData(99) = LocalVar%PRC_R_Pitch + LocalVarOutData(100) = LocalVar%PRC_R_Total + LocalVarOutData(101) = LocalVar%PRC_Min_Pitch + LocalVarOutData(102) = LocalVar%PS_Min_Pitch + LocalVarOutData(103) = LocalVar%OL_Index + LocalVarOutData(104) = LocalVar%SD_Trigger + LocalVarOutData(105) = LocalVar%SD_BlPitchF + LocalVarOutData(106) = LocalVar%SD_NacVaneF + LocalVarOutData(107) = LocalVar%SD_GenSpeedF + LocalVarOutData(108) = LocalVar%GenTq_SD + LocalVarOutData(109) = LocalVar%Fl_PitCom + LocalVarOutData(110) = LocalVar%NACIMU_FA_AccF + LocalVarOutData(111) = LocalVar%FA_AccF + LocalVarOutData(112) = LocalVar%FA_Hist + LocalVarOutData(113) = LocalVar%TRA_LastRefSpd + LocalVarOutData(114) = LocalVar%VS_RefSpeed + LocalVarOutData(115) = LocalVar%PtfmTDX + LocalVarOutData(116) = LocalVar%PtfmTDY + LocalVarOutData(117) = LocalVar%PtfmTDZ + LocalVarOutData(118) = LocalVar%PtfmRDX + LocalVarOutData(119) = LocalVar%PtfmRDY + LocalVarOutData(120) = LocalVar%PtfmRDZ + LocalVarOutData(121) = LocalVar%PtfmTVX + LocalVarOutData(122) = LocalVar%PtfmTVY + LocalVarOutData(123) = LocalVar%PtfmTVZ + LocalVarOutData(124) = LocalVar%PtfmRVX + LocalVarOutData(125) = LocalVar%PtfmRVY + LocalVarOutData(126) = LocalVar%PtfmRVZ + LocalVarOutData(127) = LocalVar%PtfmTAX + LocalVarOutData(128) = LocalVar%PtfmTAY + LocalVarOutData(129) = LocalVar%PtfmTAZ + LocalVarOutData(130) = LocalVar%PtfmRAX + LocalVarOutData(131) = LocalVar%PtfmRAY + LocalVarOutData(132) = LocalVar%PtfmRAZ + LocalVarOutData(133) = LocalVar%CC_DesiredL(1) + LocalVarOutData(134) = LocalVar%CC_ActuatedL(1) + LocalVarOutData(135) = LocalVar%CC_ActuatedDL(1) + LocalVarOutData(136) = LocalVar%StC_Input(1) + LocalVarOutData(137) = LocalVar%Flp_Angle(1) + LocalVarOutData(138) = LocalVar%RootMyb_Last(1) + LocalVarOutData(139) = LocalVar%ACC_INFILE_SIZE + LocalVarOutData(140) = LocalVar%AWC_complexangle(1) + LocalVarOutData(141) = LocalVar%ZMQ_ID + LocalVarOutData(142) = LocalVar%ZMQ_YawOffset + LocalVarOutData(143) = LocalVar%ZMQ_TorqueOffset + LocalVarOutData(144) = LocalVar%ZMQ_PitOffset(1) + LocalVarOutData(145) = LocalVar%ZMQ_R_Speed + LocalVarOutData(146) = LocalVar%ZMQ_R_Torque + LocalVarOutData(147) = LocalVar%ZMQ_R_Pitch + LocalVarOutStrings = [CHARACTER(15) :: 'iStatus', 'AlreadyInitialized', 'RestartWSE', 'Time', 'DT', & + 'n_DT', 'Time_Last', 'VS_GenPwr', 'GenSpeed', 'RotSpeed', & + 'NacHeading', 'NacVane', 'NacVaneF', 'HorWindV', 'HorWindV_F', & + 'rootMOOP', 'rootMOOPF', 'BlPitch', 'BlPitchCMeas', 'Azimuth', & + 'OL_Azimuth', 'AzUnwrapped', 'AzError', 'GenTqAz', 'AzBuffer', & + 'NumBl', 'FA_Acc', 'NacIMU_FA_Acc', 'FA_AccHPF', 'FA_AccHPFI', & + 'FA_PitCom', 'VS_RefSpd', 'VS_RefSpd_TSR', 'VS_RefSpd_TRA', 'VS_RefSpd_RL', & + 'PC_RefSpd', 'PC_RefSpd_SS', 'PC_RefSpd_PRC', 'RotSpeedF', 'GenSpeedF', & + 'GenTq', 'GenTqMeas', 'GenArTq', 'GenBrTq', 'VS_KOmega2_GenTq', & + 'VS_ConstPwr_GenTq', 'IPC_PitComF', 'PC_KP', 'PC_KI', 'PC_KD', & + 'PC_TF', 'PC_MaxPit', 'PC_MinPit', 'PC_PitComT', 'PC_PitComT_Last', & + 'PC_PitComTF', 'PC_PitComT_IPC', 'PC_PwrErr', 'PC_SpdErr', 'IPC_AxisTilt_1P', & + 'IPC_AxisYaw_1P', 'IPC_AxisTilt_2P', 'IPC_AxisYaw_2P', 'axisTilt_1P', 'axisYaw_1P', & + 'axisYawF_1P', 'axisTilt_2P', 'axisYaw_2P', 'axisYawF_2P', 'IPC_KI', & + 'IPC_KP', 'IPC_IntSat', 'PC_State', 'PitCom', 'PitCom_SD', & + 'PitComAct', 'SS_DelOmegaF', 'TestType', 'Kp_Float', 'VS_MaxTq', & + 'VS_LastGenTrq', 'VS_LastGenPwr', 'VS_MechGenPwr', 'VS_SpdErrAr', 'VS_SpdErrBr', & + 'VS_SpdErr', 'VS_State', 'VS_Rgn3Pitch', 'WE_Vw', 'WE_Vw_F', & + 'WE_VwI', 'WE_VwIdot', 'WE_Op', 'WE_Op_Last', 'VS_LastGenTrqF', & + 'PRC_WSE_F', 'PRC_R_Speed', 'PRC_R_Torque', 'PRC_R_Pitch', 'PRC_R_Total', & + 'PRC_Min_Pitch', 'PS_Min_Pitch', 'OL_Index', 'SD_Trigger', 'SD_BlPitchF', & + 'SD_NacVaneF', 'SD_GenSpeedF', 'GenTq_SD', 'Fl_PitCom', 'NACIMU_FA_AccF', & + 'FA_AccF', 'FA_Hist', 'TRA_LastRefSpd', 'VS_RefSpeed', 'PtfmTDX', & + 'PtfmTDY', 'PtfmTDZ', 'PtfmRDX', 'PtfmRDY', 'PtfmRDZ', & + 'PtfmTVX', 'PtfmTVY', 'PtfmTVZ', 'PtfmRVX', 'PtfmRVY', & + 'PtfmRVZ', 'PtfmTAX', 'PtfmTAY', 'PtfmTAZ', 'PtfmRAX', & + 'PtfmRAY', 'PtfmRAZ', 'CC_DesiredL', 'CC_ActuatedL', 'CC_ActuatedDL', & + 'StC_Input', 'Flp_Angle', 'RootMyb_Last', 'ACC_INFILE_SIZE', 'AWC_complexangle', & + 'ZMQ_ID', 'ZMQ_YawOffset', 'ZMQ_TorqueOffset', 'ZMQ_PitOffset', 'ZMQ_R_Speed', & + 'ZMQ_R_Torque', 'ZMQ_R_Pitch'] ! Initialize debug file IF ((LocalVar%iStatus == 0) .OR. (LocalVar%iStatus == -9)) THEN ! .TRUE. if we're on the first call to the DLL IF (CntrPar%LoggingLevel > 0) THEN @@ -910,8 +934,8 @@ SUBROUTINE Debug(LocalVar, CntrPar, DebugVar, ErrVar, avrSWAP, RootName, size_av CALL GetNewUnit(UnDb2, ErrVar) OPEN(unit=UnDb2, FILE=TRIM(RootName)//'.RO.dbg2') WRITE(UnDb2, *) 'Generated on '//CurDate()//' at '//CurTime()//' using ROSCO-'//TRIM(rosco_version) - WRITE(UnDb2, '(141(a20,TR5:))') 'Time', LocalVarOutStrings - WRITE(UnDb2, '(141(a20,TR5:))') + WRITE(UnDb2, '(148(a20,TR5:))') 'Time', LocalVarOutStrings + WRITE(UnDb2, '(148(a20,TR5:))') END IF IF (CntrPar%LoggingLevel > 2) THEN @@ -974,7 +998,7 @@ SUBROUTINE Debug(LocalVar, CntrPar, DebugVar, ErrVar, avrSWAP, RootName, size_av END DO ! Write debug files - FmtDat = "(F20.5,TR5,140(ES20.5E2,TR5:))" ! The format of the debugging data + FmtDat = "(F20.5,TR5,147(ES20.5E2,TR5:))" ! The format of the debugging data IF ( MOD(LocalVar%n_DT, CntrPar%n_DT_Out) == 0) THEN IF(CntrPar%LoggingLevel > 0) THEN WRITE (UnDb, TRIM(FmtDat)) LocalVar%Time, DebugOutData From 2b00bbb9dbaa8fb1a46b8808a42932dad5be8d95 Mon Sep 17 00:00:00 2001 From: dzalkind Date: Fri, 13 Dec 2024 11:43:17 -0700 Subject: [PATCH 217/224] Rename fixed pitch example, add to tests --- Examples/{30_fixed_pitch_mhk.py => 31_fixed_pitch_mhk.py} | 0 rosco/test/test_examples.py | 1 + 2 files changed, 1 insertion(+) rename Examples/{30_fixed_pitch_mhk.py => 31_fixed_pitch_mhk.py} (100%) diff --git a/Examples/30_fixed_pitch_mhk.py b/Examples/31_fixed_pitch_mhk.py similarity index 100% rename from Examples/30_fixed_pitch_mhk.py rename to Examples/31_fixed_pitch_mhk.py diff --git a/rosco/test/test_examples.py b/rosco/test/test_examples.py index e7994007..f21032dc 100644 --- a/rosco/test/test_examples.py +++ b/rosco/test/test_examples.py @@ -34,6 +34,7 @@ '28_tower_resonance', '29_power_control', '30_shutdown', + '31_fixed_pitch_mhk' 'update_rosco_discons', ] From 395c681faf92819c5acf10105e8a0f258ef27a32 Mon Sep 17 00:00:00 2001 From: dzalkind Date: Fri, 13 Dec 2024 15:53:05 -0700 Subject: [PATCH 218/224] Fix typo in example test --- rosco/test/test_examples.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/rosco/test/test_examples.py b/rosco/test/test_examples.py index f21032dc..31eeee75 100644 --- a/rosco/test/test_examples.py +++ b/rosco/test/test_examples.py @@ -34,7 +34,7 @@ '28_tower_resonance', '29_power_control', '30_shutdown', - '31_fixed_pitch_mhk' + '31_fixed_pitch_mhk', 'update_rosco_discons', ] From fa51fab7674fa8615b25ab0af6b0258b518d20cb Mon Sep 17 00:00:00 2001 From: dzalkind Date: Fri, 27 Dec 2024 11:18:29 -0700 Subject: [PATCH 219/224] Use WSE filter as default ref speed filter, Check updated discon --- Examples/19_update_discon_version.py | 21 ++++++++++++++++++++- Examples/example_inputs/DISCON_v2.2.0.IN | 2 +- rosco/toolbox/tune.py | 5 +++++ 3 files changed, 26 insertions(+), 2 deletions(-) diff --git a/Examples/19_update_discon_version.py b/Examples/19_update_discon_version.py index 78feb5d0..7e7dd6e8 100644 --- a/Examples/19_update_discon_version.py +++ b/Examples/19_update_discon_version.py @@ -6,6 +6,9 @@ """ import os +import shutil +from rosco import discon_lib_path +from rosco.toolbox import control_interface as ROSCO_ci from rosco.toolbox.tune import update_discon_version def main(): @@ -16,11 +19,27 @@ def main(): # Tuning yaml can be anything, does not have to correspond to old discon tuning_yaml = os.path.join(this_dir,'Tune_Cases','NREL5MW.yaml') # dummy for now + new_discon = os.path.join(this_dir,'examples_out','18_UPDATED_DISCON.IN') update_discon_version( old_discon_filename, tuning_yaml, - os.path.join(this_dir,'examples_out','18_UPDATED_DISCON.IN') + new_discon ) + + # Try using updated DISCON + + shutil.copyfile( + os.path.join(this_dir,'example_inputs','Cp_Ct_Cq.IEA15MW.txt'), + os.path.join(this_dir,'examples_out','Cp_Ct_Cq.IEA15MW.txt') + ) # Copy Cp table for testing + + controller_int = ROSCO_ci.ControllerInterface( + discon_lib_path, + param_filename=new_discon, + sim_name='sim1') + controller_int.kill_discon() + + assert(controller_int.aviFAIL.value == 0) if __name__ == "__main__": main() \ No newline at end of file diff --git a/Examples/example_inputs/DISCON_v2.2.0.IN b/Examples/example_inputs/DISCON_v2.2.0.IN index 6aac9ab7..5cc3fb04 100644 --- a/Examples/example_inputs/DISCON_v2.2.0.IN +++ b/Examples/example_inputs/DISCON_v2.2.0.IN @@ -77,7 +77,7 @@ 318628138.00000 ! 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.IEA15MW.txt" ! PerfFileName - File containing rotor performance tables (Cp,Ct,Cq) -104 48 ! PerfTableSize - Size of rotor performance tables, first number refers to number of blade pitch angles, second number referse to number of tip-speed ratios +36 26 ! PerfTableSize - Size of rotor performance tables, first number refers to number of blade pitch angles, second number referse to number of tip-speed ratios 44 ! WE_FOPoles_N - Number of first-order system poles used in EKF 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.24 11.74 12.24 12.74 13.24 13.74 14.24 14.74 15.24 15.74 16.24 16.74 17.24 17.74 18.24 18.74 19.24 19.74 20.24 20.74 21.24 21.74 22.24 22.74 23.24 23.74 24.24 24.74 ! WE_FOPoles_v - Wind speeds corresponding to first-order system poles [m/s] -0.02334364 -0.02723425 -0.03112486 -0.03501546 -0.03890607 -0.04279668 -0.04668728 -0.05057789 -0.05446850 -0.05835911 -0.06224971 -0.06614032 -0.07003093 -0.07392153 -0.07781214 -0.08170275 -0.05441825 -0.05758074 -0.06474714 -0.07383682 -0.08430904 -0.09581400 -0.10815415 -0.12121919 -0.13495759 -0.14915715 -0.16379718 -0.17904114 -0.19494603 -0.21082316 -0.22752972 -0.24440216 -0.26178793 -0.27954029 -0.29769427 -0.31606508 -0.33525667 -0.35396333 -0.37406865 -0.39341852 -0.41345400 -0.43495515 -0.45460302 -0.47551894 ! WE_FOPoles - First order system poles diff --git a/rosco/toolbox/tune.py b/rosco/toolbox/tune.py index dae685dd..41be3f35 100644 --- a/rosco/toolbox/tune.py +++ b/rosco/toolbox/tune.py @@ -116,6 +116,11 @@ def update_discon_version(file,tuning_yaml,new_discon_filename): # OL blade pitch changed to array if ('Ind_BldPitch' in original_vt) and (not hasattr(original_vt['Ind_BldPitch'],'__len__')): new_discon['Ind_BldPitch'] = [original_vt['Ind_BldPitch']] * 3 + + # v2.10: now, we are filtering the reference speed directly, rather than the WSE + if ('F_VSRefSpdCornerFreq' not in original_vt) and ('F_WECornerFreq' in original_vt): + print('Using F_WECornerFreq to set new F_VSRefSpdCornerFreq') + new_discon['F_VSRefSpdCornerFreq'] = original_vt['F_WECornerFreq'] # Make the DISCON From 840fa796acc65f2df694a1e7340a551b96f0e5ee Mon Sep 17 00:00:00 2001 From: dzalkind Date: Fri, 27 Dec 2024 11:46:41 -0700 Subject: [PATCH 220/224] Tidy imports --- Examples/21_optional_inputs.py | 2 -- 1 file changed, 2 deletions(-) diff --git a/Examples/21_optional_inputs.py b/Examples/21_optional_inputs.py index 59292fc1..9511607a 100644 --- a/Examples/21_optional_inputs.py +++ b/Examples/21_optional_inputs.py @@ -8,9 +8,7 @@ import os from rosco import discon_lib_path from rosco.toolbox import control_interface as ROSCO_ci -#from rosco.toolbox import sim as ROSCO_sim from rosco.toolbox import turbine as ROSCO_turbine -#import numpy as np def main():#directories this_dir = os.path.dirname(os.path.abspath(__file__)) From 8891a862e2bf14cead4c2236d0c3c95245631724 Mon Sep 17 00:00:00 2001 From: dzalkind Date: Fri, 27 Dec 2024 11:46:50 -0700 Subject: [PATCH 221/224] Increment ROSCO version --- rosco/controller/src/Constants.f90 | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/rosco/controller/src/Constants.f90 b/rosco/controller/src/Constants.f90 index da191846..bcd3edac 100644 --- a/rosco/controller/src/Constants.f90 +++ b/rosco/controller/src/Constants.f90 @@ -14,7 +14,7 @@ MODULE Constants USE, INTRINSIC :: ISO_C_Binding - Character(*), PARAMETER :: rosco_version = 'v2.9.0' ! ROSCO version + Character(*), PARAMETER :: rosco_version = 'v2.10.0' ! ROSCO version INTEGER, PARAMETER :: DbKi = C_DOUBLE !< Default kind for double floating-point numbers INTEGER, PARAMETER :: ReKi = C_FLOAT !< Default kind for single floating-point numbers INTEGER, PARAMETER :: IntKi = C_INT !< Default kind for integer numbers From fa1aa7e95649582ee675de9e67b988900eb3da5e Mon Sep 17 00:00:00 2001 From: dzalkind Date: Fri, 3 Jan 2025 12:15:07 -0700 Subject: [PATCH 222/224] Do not set default wind_case_fcn --- rosco/toolbox/ofTools/case_gen/run_FAST.py | 11 ++++++----- 1 file changed, 6 insertions(+), 5 deletions(-) diff --git a/rosco/toolbox/ofTools/case_gen/run_FAST.py b/rosco/toolbox/ofTools/case_gen/run_FAST.py index 160a4d40..e7039e98 100644 --- a/rosco/toolbox/ofTools/case_gen/run_FAST.py +++ b/rosco/toolbox/ofTools/case_gen/run_FAST.py @@ -48,7 +48,7 @@ def __init__(self): # Set default parameters self.tuning_yaml = 'IEA15MW.yaml' - self.wind_case_fcn = cl.power_curve + self.wind_case_fcn = None self.wind_case_opts = {} self.control_sweep_opts = {} self.control_sweep_fcn = None @@ -127,14 +127,15 @@ def run_FAST(self): # Apply all discon variables as case inputs discon_vt = ROSCO_utilities.DISCON_dict(turbine, controller, txt_filename=cp_filename) - control_base_case = {} + case_inputs = {} for discon_input in discon_vt: - control_base_case[('DISCON_in',discon_input)] = {'vals': [discon_vt[discon_input]], 'group': 0} + case_inputs[('DISCON_in',discon_input)] = {'vals': [discon_vt[discon_input]], 'group': 0} # Set up wind case self.wind_case_opts['run_dir'] = run_dir - case_inputs = self.wind_case_fcn(**self.wind_case_opts) - case_inputs.update(control_base_case) + if self.wind_case_fcn: + wind_case_inputs = self.wind_case_fcn(**self.wind_case_opts) + case_inputs.update(wind_case_inputs) if not self.rosco_dll: self.rosco_dll = discon_lib_path From 8671afa5738e8276a45e471bfbb1c48fe0d259c1 Mon Sep 17 00:00:00 2001 From: dzalkind Date: Fri, 3 Jan 2025 12:15:43 -0700 Subject: [PATCH 223/224] Set up ex31 to simulate each config easily --- Examples/31_fixed_pitch_mhk.py | 21 +++++++++------------ 1 file changed, 9 insertions(+), 12 deletions(-) diff --git a/Examples/31_fixed_pitch_mhk.py b/Examples/31_fixed_pitch_mhk.py index 4bbd78e3..61cb5da4 100644 --- a/Examples/31_fixed_pitch_mhk.py +++ b/Examples/31_fixed_pitch_mhk.py @@ -53,14 +53,12 @@ def main(): - FULL_TEST = True # Run a full test locally (True) or a shorter one for CI + FULL_TEST = False # Run a full test locally (True) or a shorter one for CI sim_config = 1 # Choose which simulation configuration (1-6) # Input yaml and output directory parameter_filename = os.path.join(this_dir, 'Tune_Cases/RM1_MHK_FBP.yaml') tune_dir = os.path.dirname(parameter_filename) - run_dir = os.path.join(example_out_dir, '30_MHK/0_baseline') - os.makedirs(run_dir,exist_ok=True) inps = load_rosco_yaml(parameter_filename) path_params = inps['path_params'] @@ -85,6 +83,7 @@ def main(): controller_params_1 = controller_params.copy() controller_params_1['VS_FBP'] = 3 # Power reference controller_params_1['VS_FBP_speed_mode'] = 0 + controller_params_1['VS_FBP_U'] = [2.0, 4.0] controller_params_1['VS_FBP_P'] = [1.0, 1.0] controller_1 = ROSCO_controller.Controller(controller_params_1) controller_1.tune_controller(turbine) @@ -93,6 +92,7 @@ def main(): controller_params_2 = controller_params.copy() controller_params_2['VS_FBP'] = 2 # Switch to WSE reference controller_params_2['VS_FBP_speed_mode'] = 1 + controller_params_2['VS_FBP_U'] = [2.0, 4.0] controller_params_2['VS_FBP_P'] = [1.0, 1.0] controller_2 = ROSCO_controller.Controller(controller_params_2) controller_2.tune_controller(turbine) @@ -100,6 +100,7 @@ def main(): # Linear increasing power controller_params_3 = controller_params.copy() controller_params_3['VS_FBP_speed_mode'] = 0 + controller_params_2['VS_FBP_U'] = [2.0, 4.0] controller_params_3['VS_FBP_P'] = [1.0, 2.0] controller_3 = ROSCO_controller.Controller(controller_params_3) controller_3.tune_controller(turbine) @@ -121,8 +122,9 @@ def main(): # Constant power overspeed, nonlinear lookup table control controller_params_6 = controller_params.copy() - controller_params_6['VS_FBP'] = 0 # Constant power overspeed + controller_params_6['VS_FBP'] = 1 # Constant power overspeed controller_params_6['VS_FBP_speed_mode'] = 1 + controller_params_6['VS_FBP_U'] = [2.0, 4.0] controller_params_6['VS_FBP_P'] = [1.0, 1.0] controller_params_6['VS_ControlMode'] = 1 controller_6 = ROSCO_controller.Controller(controller_params_6) @@ -164,13 +166,8 @@ def main(): plt.savefig(fig_fname,bbox_inches='tight',) # Write parameter input file for constant power underspeed controller - param_file = os.path.join(run_dir,'DISCON.IN') - write_DISCON(turbine, - controller_1, - param_file=param_file, - txt_filename=cp_filename - ) - + run_dir = os.path.join(example_out_dir, f'31_MHK/{sim_config}_config') + os.makedirs(run_dir,exist_ok=True) # simulation set up if FULL_TEST: @@ -200,7 +197,7 @@ def main(): 'TMax': TMax, } r.case_inputs = {} - r.controller_params = controller_params_1 + r.controller_params = controller_params r.save_dir = run_dir r.rosco_dir = rosco_dir From 334e94c8a66949a8c47b8a5669406741b7b165f7 Mon Sep 17 00:00:00 2001 From: dzalkind Date: Fri, 3 Jan 2025 12:49:32 -0700 Subject: [PATCH 224/224] Simplify save_dir --- rosco/toolbox/ofTools/case_gen/run_FAST.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/rosco/toolbox/ofTools/case_gen/run_FAST.py b/rosco/toolbox/ofTools/case_gen/run_FAST.py index e7039e98..98305d7a 100644 --- a/rosco/toolbox/ofTools/case_gen/run_FAST.py +++ b/rosco/toolbox/ofTools/case_gen/run_FAST.py @@ -89,7 +89,7 @@ def run_FAST(self): if not self.base_name: self.base_name = os.path.split(self.tuning_yaml)[-1].split('.')[0] - run_dir = os.path.join(self.save_dir,self.base_name,self.wind_case_fcn.__name__,sweep_name) + run_dir = self.save_dir # Start with tuning yaml definition of controller